From a03e58b7acd56df24404d42652efc1c75725adda Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 13 Oct 2012 13:19:56 +0000 Subject: [PATCH 001/206] ADC support for the Shenzhou board from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5232 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/adc/adc_main.c | 7 +- nuttx/configs/shenzhou/nsh/Make.defs | 2 +- nuttx/configs/shenzhou/scripts/ld.script | 8 +- nuttx/configs/shenzhou/src/Makefile | 4 + nuttx/configs/shenzhou/src/up_adc.c | 164 +++++++++++++++++++++++ 5 files changed, 179 insertions(+), 6 deletions(-) create mode 100644 nuttx/configs/shenzhou/src/up_adc.c diff --git a/apps/examples/adc/adc_main.c b/apps/examples/adc/adc_main.c index 404fba8c1f..553658fee0 100644 --- a/apps/examples/adc/adc_main.c +++ b/apps/examples/adc/adc_main.c @@ -289,7 +289,7 @@ int adc_main(int argc, char *argv[]) { message("adc_main: open %s failed: %d\n", g_adcstate.devpath, errno); errval = 2; - goto errout_with_dev; + goto errout; } /* Now loop the appropriate number of times, displaying the collected @@ -357,6 +357,11 @@ int adc_main(int argc, char *argv[]) } } + close(fd); + return OK; + + /* Error exits */ + errout_with_dev: close(fd); diff --git a/nuttx/configs/shenzhou/nsh/Make.defs b/nuttx/configs/shenzhou/nsh/Make.defs index 2318e6c9cb..81dedb8bba 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-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/configs/shenzhou/scripts/ld.script b/nuttx/configs/shenzhou/scripts/ld.script index c9140291c0..d167cc49d7 100644 --- a/nuttx/configs/shenzhou/scripts/ld.script +++ b/nuttx/configs/shenzhou/scripts/ld.script @@ -74,6 +74,10 @@ SECTIONS *(.ARM.exidx*) } > flash __exidx_end = ABSOLUTE(.); + + .ARM.extab : { + *(.ARM.extab*) + } > flash _eronly = ABSOLUTE(.); @@ -87,10 +91,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile index 1775f1fcec..0082a526a6 100644 --- a/nuttx/configs/shenzhou/src/Makefile +++ b/nuttx/configs/shenzhou/src/Makefile @@ -80,6 +80,10 @@ ifeq ($(CONFIG_CAN),y) CSRCS += up_can.c endif +ifeq ($(CONFIG_ADC),y) +CSRCS += up_adc.c +endif + ifeq ($(CONFIG_WATCHDOG),y) CSRCS += up_watchdog.c endif diff --git a/nuttx/configs/shenzhou/src/up_adc.c b/nuttx/configs/shenzhou/src/up_adc.c new file mode 100644 index 0000000000..fb20c6940a --- /dev/null +++ b/nuttx/configs/shenzhou/src/up_adc.c @@ -0,0 +1,164 @@ +/************************************************************************************ + * configs/shenzhou/src/up_adc.c + * arch/arm/src/board/up_adc.c + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" + +#include "stm32_pwm.h" +#include "shenzhou-internal.h" + +#ifdef CONFIG_ADC + +/************************************************************************************ + * Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ +/* Up to 3 ADC interfaces are supported */ + +#if STM32_NADC < 3 +# undef CONFIG_STM32_ADC3 +#endif + +#if STM32_NADC < 2 +# undef CONFIG_STM32_ADC2 +#endif + +#if STM32_NADC < 1 +# undef CONFIG_STM32_ADC1 +#endif + +#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3) +#ifndef CONFIG_STM32_ADC1 +# warning "Channel information only available for ADC1" +#endif + +/* The number of ADC channels in the conversion list */ + +#define ADC1_NCHANNELS 1 + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/* Identifying number of each ADC channel: Variable Resistor */ + +#ifdef CONFIG_STM32_ADC1 +static const uint8_t g_chanlist[ADC1_NCHANNELS] = {10}; //{10, 8, 9}; + +/* Configurations of pins used byte each ADC channels */ + +static const uint32_t g_pinlist[ADC1_NCHANNELS] = {GPIO_ADC12_IN10}; //{GPIO_ADC12_IN10, GPIO_ADC12_IN8, GPIO_ADC12_IN9}; +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: adc_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/adc. + * + ************************************************************************************/ + +int adc_devinit(void) +{ +#ifdef CONFIG_STM32_ADC1 + static bool initialized = false; + struct adc_dev_s *adc; + int ret; + int i; + + /* Check if we have already initialized */ + + if (!initialized) + { + /* Configure the pins as analog inputs for the selected channels */ + + for (i = 0; i < ADC1_NCHANNELS; i++) + { + stm32_configgpio(g_pinlist[i]); + } + + /* Call stm32_adcinitialize() to get an instance of the ADC interface */ + + adc = stm32_adcinitialize(1, g_chanlist, ADC1_NCHANNELS); + if (adc == NULL) + { + adbg("ERROR: Failed to get ADC interface\n"); + return -ENODEV; + } + + /* Register the ADC driver at "/dev/adc0" */ + + ret = adc_register("/dev/adc0", adc); + if (ret < 0) + { + adbg("adc_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +#else + return -ENOSYS; +#endif +} + +#endif /* CONFIG_STM32_ADC1 || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */ +#endif /* CONFIG_ADC */ From 8345d911e0e4f6e6dcbc4728325fb7ef0b8dadd8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 13 Oct 2012 15:12:44 +0000 Subject: [PATCH 002/206] Add a THTTPD configuration for the Shenzhou board (Darcy Gong) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5233 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 2 + nuttx/ChangeLog | 4 + nuttx/Documentation/README.html | 2 +- nuttx/TODO | 2 +- nuttx/configs/shenzhou/thttpd/Make.defs | 176 ++++ nuttx/configs/shenzhou/thttpd/defconfig | 1004 +++++++++++++++++++++++ nuttx/configs/shenzhou/thttpd/setenv.sh | 78 ++ 7 files changed, 1266 insertions(+), 2 deletions(-) create mode 100644 nuttx/configs/shenzhou/thttpd/Make.defs create mode 100644 nuttx/configs/shenzhou/thttpd/defconfig create mode 100755 nuttx/configs/shenzhou/thttpd/setenv.sh diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 7375adccfc..b73f072bc6 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -368,3 +368,5 @@ 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) + * apps/nshlib/nsh_telnetd.c: Add support for login to Telnet session via + username and password (Darcy Gong). diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index a8e045616e..971e9ff9bf 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3470,4 +3470,8 @@ * 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. + * configs/shenzhou/src/up_adc.c: Add ADC support for the Shenzhou + board (Darcy Gong). + * configs/shenzhou/thttpd: Add a THTTPD configuration for the + Shenzhou board (Darcy Gong). diff --git a/nuttx/Documentation/README.html b/nuttx/Documentation/README.html index 4d87f55a67..9424262609 100644 --- a/nuttx/Documentation/README.html +++ b/nuttx/Documentation/README.html @@ -260,7 +260,7 @@ | | |- discover/README.txt | | |- ftpc/README.txt | | |- telnetd/README.txt - | `- README + | `- README.txt |- nshlib/ | `- README.txt |- NxWidgets/ diff --git a/nuttx/TODO b/nuttx/TODO index 906601192c..7b4daf2c16 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -421,7 +421,7 @@ o Binary loaders (binfmt/) .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 + This is good and bad. This is good because it means that .rodata.str1.1 can now 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 diff --git a/nuttx/configs/shenzhou/thttpd/Make.defs b/nuttx/configs/shenzhou/thttpd/Make.defs new file mode 100644 index 0000000000..99aed6a514 --- /dev/null +++ b/nuttx/configs/shenzhou/thttpd/Make.defs @@ -0,0 +1,176 @@ +############################################################################ +# configs/shenzhou/thttpd/Make.defs +# +# 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk + +# Setup for the selected toolchain + +ifeq ($(CONFIG_STM32_CODESOURCERYW),y) + # CodeSourcery under Windows + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_CODESOURCERYL),y) + # CodeSourcery under Linux + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -O2 +endif +ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) + # Atollic toolchain under Windows + CROSSDEV = arm-atollic-eabi- + ARCROSSDEV = + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) + # Atollic toolchain under Windows + CROSSDEV = arm-atollic-eabi- + ARCROSSDEV = arm-atollic-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_DEVKITARM),y) + # devkitARM under Windows + CROSSDEV = arm-eabi- + ARCROSSDEV = arm-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_RAISONANCE),y) + # Raisonance RIDE7 under Windows + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -Os +endif + +# Pick the linker script + +ifeq ($(CONFIG_STM32_DFU),y) + LDSCRIPT = ld.script.dfu +else + LDSCRIPT = ld.script +endif + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/winlink.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + 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)/scripts/$(LDSCRIPT)}" + MAXOPTIMIZATION = -O2 +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)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +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} + +ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +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__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-eabi-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx/configs/shenzhou/thttpd/defconfig b/nuttx/configs/shenzhou/thttpd/defconfig new file mode 100644 index 0000000000..5fd158cc64 --- /dev/null +++ b/nuttx/configs/shenzhou/thttpd/defconfig @@ -0,0 +1,1004 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +# CONFIG_RAW_BINARY is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM3S is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set +CONFIG_ARCH_IRQPRIO=y +CONFIG_BOARD_LOOPSPERMSEC=5483 +# CONFIG_ARCH_CALIBRATION is not set +# CONFIG_SERIAL_TERMIOS is not set +# CONFIG_NET_MULTICAST is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +CONFIG_ARCH_CHIP_STM32F107VC=y +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +CONFIG_STM32_STM32F10XX=y +CONFIG_STM32_CONNECTIVITYLINE=y +CONFIG_STM32_CODESOURCERYW=n +# CONFIG_STM32_CODESOURCERYL is not set +# CONFIG_STM32_ATOLLIC_LITE is not set +# CONFIG_STM32_ATOLLIC_PRO is not set +# CONFIG_STM32_DEVKITARM is not set +# CONFIG_STM32_RAISONANCE is not set +# CONFIG_STM32_BUILDROOT is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +CONFIG_STM32_BKP=y +# 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 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_IWDG is not set +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +# CONFIG_STM32_SPI2 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 +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_USART1 is not set +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USB is not set +# CONFIG_STM32_WWDG is not set +CONFIG_STM32_SPI=y + +# +# Alternate Pin Mapping +# +CONFIG_STM32_USART2_REMAP=y +# CONFIG_STM32_SPI1_REMAP is not set +CONFIG_STM32_ETH_REMAP=y +# CONFIG_STM32_JTAG_DISABLE is not set +CONFIG_STM32_JTAG_FULL_ENABLE=y +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +# CONFIG_STM32_JTAG_SW_ENABLE is not set +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set + +# +# SPI Configuration +# +# CONFIG_STM32_SPI_INTERRUPTS is not set +# CONFIG_STM32_SPI_DMA is not set + +# +# Ethernet MAC configuration +# +CONFIG_STM32_PHYADDR=0x00 +# CONFIG_STM32_MII is not set +CONFIG_STM32_AUTONEG=y +CONFIG_STM32_PHYSR=17 +CONFIG_STM32_PHYSR_ALTCONFIG=y +CONFIG_STM32_PHYSR_ALTMODE=0xf000 +CONFIG_STM32_PHYSR_10HD=0x1000 +CONFIG_STM32_PHYSR_100HD=0x4000 +CONFIG_STM32_PHYSR_10FD=0x2000 +CONFIG_STM32_PHYSR_100FD=0x8000 +# CONFIG_STM32_ETH_PTP is not set +CONFIG_STM32_RMII=y +CONFIG_STM32_RMII_MCO=y +# CONFIG_STM32_RMII_EXTCLK is not set + +# +# USB Host Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_STACKDUMP=y + +# +# Board Settings +# +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=65536 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +# CONFIG_ARCH_BOARD_OLIMEX_STM32P107 is not set +CONFIG_ARCH_BOARD_SHENZHOU=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="shenzhou" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 +CONFIG_NSH_MMCSDSPIPORTNO=1 + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2012 +CONFIG_START_MONTH=9 +CONFIG_START_DAY=8 +CONFIG_DEV_CONSOLE=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=n +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_WORKPRIORITY=192 +CONFIG_SCHED_WORKPERIOD=50000 +CONFIG_SCHED_WORKSTACKSIZE=2048 +CONFIG_SIG_SIGWORK=4 +# CONFIG_SCHED_LPWORK is not set +CONFIG_SCHED_WAITPID=y +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="thttp_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set +CONFIG_DISABLE_POLL=n + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=8 +CONFIG_PREALLOC_TIMERS=4 + +# +# Stack and heap information +# +# CONFIG_CUSTOM_STACK is not set +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +CONFIG_ARCH_HAVE_I2CRESET=y +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_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +CONFIG_MMCSD=n +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set +CONFIG_MMCSD_MMCSUPPORT=y +CONFIG_MMCSD_HAVECARDDETECT=y +CONFIG_MMCSD_SPI=n +CONFIG_MMCSD_SPICLOCK=12500000 +# CONFIG_MMCSD_SDIO is not set +# CONFIG_MTD is not set +# CONFIG_NETDEVICES is not set +# CONFIG_NET_SLIP is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_USART2=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# 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 +CONFIG_NSOCKET_DESCRIPTORS=16 +CONFIG_NET_NACTIVESOCKETS=16 +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_BUFSIZE=768 +# CONFIG_NET_TCPURGDATA is not set +CONFIG_NET_TCP=y +CONFIG_NET_TCP_CONNS=40 +CONFIG_NET_MAX_LISTENPORTS=40 +CONFIG_NET_TCP_READAHEAD_BUFSIZE=562 +CONFIG_NET_NTCP_READAHEAD_BUFFERS=8 +CONFIG_NET_TCP_RECVDELAY=0 +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_CONNS=8 +# CONFIG_NET_BROADCAST is not set +CONFIG_NET_ICMP=y +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_ARPTAB_SIZE=16 +# CONFIG_NET_ARP_IPIN is not set + +# +# File Systems +# + +# +# File system configuration +# +CONFIG_FS_FAT=n +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_RAMMAP is not set +# CONFIG_NFS is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_GRAN is not set + +# +# Library Routines +# +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_HAVE_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set +CONFIG_HAVE_CXX=y +# CONFIG_HAVE_CXXINITIALIZE is not set +# CONFIG_CXX_NEWLONG is not set + +# +# Application Configuration +# + +# +# Named Applications +# +CONFIG_NAMEDAPP=y + +# +# Examples +# + +# +# ADC Example +# +# CONFIG_EXAMPLES_ADC is not set + +# +# Buttons Example +# +# CONFIG_EXAMPLES_BUTTONS is not set + +# +# CAN Example +# +# CONFIG_EXAMPLES_CAN is not set + +# +# USB CDC/ACM Class Driver Example +# +# CONFIG_EXAMPLES_CDCACM is not set + +# +# USB composite Class Driver Example +# +# CONFIG_EXAMPLES_COMPOSITE is not set + +# +# DHCP Server Example +# +# CONFIG_EXAMPLES_DHCPD is not set + +# +# FTP Client Example +# +# CONFIG_EXAMPLES_FTPC is not set + +# +# FTP Server Example +# +# CONFIG_EXAMPLES_FTPD is not set + +# +# "Hello, World!" Example +# +# CONFIG_EXAMPLES_HELLO is not set + +# +# "Hello, World!" C++ Example +# +# CONFIG_EXAMPLES_HELLOXX is not set + +# +# USB HID Keyboard Example +# +# CONFIG_EXAMPLES_HIDKBD is not set + +# +# IGMP Example +# +# CONFIG_EXAMPLES_IGMP is not set + +# +# LCD Read/Write Example +# +# CONFIG_EXAMPLES_LCDRW is not set + +# +# Memory Management Example +# +# CONFIG_EXAMPLES_MM is not set + +# +# File System Mount Example +# +# CONFIG_EXAMPLES_MOUNT is not set + +# +# FreeModBus Example +# +# CONFIG_EXAMPLES_MODBUS is not set + +# +# Network Test Example +# +# CONFIG_EXAMPLES_NETTEST is not set + +# +# NuttShell (NSH) Example +# +CONFIG_EXAMPLES_NSH=y + +# +# NULL Example +# +# CONFIG_EXAMPLES_NULL is not set + +# +# NX Graphics Example +# +# CONFIG_EXAMPLES_NX is not set + +# +# NxConsole Example +# +# CONFIG_EXAMPLES_NXCONSOLE is not set + +# +# NXFFS File System Example +# +# CONFIG_EXAMPLES_NXFFS is not set + +# +# NXFLAT Example +# +# CONFIG_EXAMPLES_NXFLAT is not set + +# +# NX Graphics "Hello, World!" Example +# +# CONFIG_EXAMPLES_NXHELLO is not set + +# +# NX Graphics image Example +# +# CONFIG_EXAMPLES_NXIMAGE is not set + +# +# NX Graphics lines Example +# +# CONFIG_EXAMPLES_NXLINES is not set + +# +# NX Graphics Text Example +# +# CONFIG_EXAMPLES_NXTEXT is not set + +# +# OS Test Example +# +# CONFIG_EXAMPLES_OSTEST is not set + +# +# Pascal "Hello, World!"example +# +# CONFIG_EXAMPLES_PASHELLO is not set + +# +# Pipe Example +# +# CONFIG_EXAMPLES_PIPE is not set + +# +# Poll Example +# +# CONFIG_EXAMPLES_POLL is not set + +# +# Pulse Width Modulation (PWM) Example +# + +# +# Quadrature Encoder Example +# +# CONFIG_EXAMPLES_QENCODER is not set + +# +# RGMP Example +# +# CONFIG_EXAMPLES_RGMP is not set + +# +# ROMFS Example +# +# CONFIG_EXAMPLES_ROMFS is not set + +# +# sendmail Example +# +# CONFIG_EXAMPLES_SENDMAIL is not set + +# +# Serial Loopback Example +# +# CONFIG_EXAMPLES_SERLOOP is not set + +# +# Telnet Daemon Example +# +# CONFIG_EXAMPLES_TELNETD is not set + +# +# THTTPD Web Server Example +# +# CONFIG_EXAMPLES_THTTPD is not set + +# +# TIFF Generation Example +# +# CONFIG_EXAMPLES_TIFF is not set + +# +# Touchscreen Example +# +# CONFIG_EXAMPLES_TOUCHSCREEN is not set + +# +# UDP Example +# +# CONFIG_EXAMPLES_UDP is not set + +# +# UDP Discovery Daemon Example +# +# CONFIG_EXAMPLES_DISCOVER is not set + +# +# uIP Web Server Example +# +# CONFIG_EXAMPLES_UIP is not set + +# +# USB Serial Test Example +# +# CONFIG_EXAMPLES_USBSERIAL is not set + +# +# USB Mass Storage Class Example +# +# CONFIG_EXAMPLES_USBMSC is not set + +# +# USB Serial Terminal Example +# +# CONFIG_EXAMPLES_USBTERM is not set + +# +# Watchdog timer Example +# +# CONFIG_EXAMPLES_WATCHDOG is not set + +# +# wget Example +# +# CONFIG_EXAMPLES_WGET is not set + +# +# WLAN Example +# +# CONFIG_EXAMPLES_WLAN is not set + +# +# XML RPC Example +# + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# + +# +# DHCP client +# +# CONFIG_NETUTILS_DHCPC is not set + +# +# DHCP server +# +# CONFIG_NETUTILS_DHCPD is not set + +# +# FTP client +# +# CONFIG_NETUTILS_FTPC is not set + +# +# FTP server +# +# CONFIG_NETUTILS_FTPD is not set + +# +# Name resolution +# +CONFIG_NETUTILS_RESOLV=y +CONFIG_NET_RESOLV_ENTRIES=8 + +# +# SMTP +# +# CONFIG_NETUTILS_SMTP is not set + +# +# TFTP client +# +CONFIG_NETUTILS_TELNETD=y + +# +# TFTP client +# +CONFIG_NETUTILS_TFTPC=y + +# +# THTTPD web server +# +# CONFIG_NETUTILS_THTTPD is not set + +# +# uIP support library +# +CONFIG_NETUTILS_UIPLIB=y + +# +# uIP web client +# +CONFIG_NETUTILS_WEBCLIENT=y + +# +# uIP web server +# +# CONFIG_NETUTILS_WEBSERVER is not set + +# +# UDP Discovery Utility +# +# CONFIG_NETUTILS_DISCOVER is not set + +# +# XML-RPC library +# +# CONFIG_NETUTILS_XMLRPC is not set + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSFMOUNT is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PING is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_CONDEV is not set +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_CLIENTPRIO=100 +CONFIG_NSH_TELNETD_CLIENTSTACKSIZE=2048 +CONFIG_NSH_IOBUFFER_SIZE=512 +CONFIG_NSH_IPADDR=0xc0a80032 +CONFIG_NSH_DRIPADDR=0xc0a80001 +CONFIG_NSH_NETMASK=0xffffff00 +CONFIG_NSH_NOMAC=y + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card +# +# CONFIG_SYSTEM_SDCARD is not set + +# +# Sysinfo +# +# CONFIG_SYSTEM_SYSINFO is not set + + +#################################################### + +CONFIG_AUTH_FILE=n +CONFIG_THTTPD_IDLE_SEND_LIMIT_SEC=300 +CONFIG_THTTPD_IOBUFFERSIZE=1024 +CONFIG_NXFLAT_DUMPBUFFER=n +CONFIG_EXAMPLES_THTTPD=y +CONFIG_EXAMPLES_THTTPD_IPADDR=0xc0a80032 +CONFIG_THTTPD_URLPATTERN=n +CONFIG_EXAMPLES_THTTPD_NOMAC=y +CONFIG_THTTPD_CGI_PRIORITY=50 +CONFIG_THTTPD_CHARSET="iso-8859-1" +CONFIG_NETUTILS_DHCPC=n +CONFIG_THTTPD_PORT=80 +CONFIG_THTTPD=y +CONFIG_STM32_CODESOURCERYL=n +CONFIG_NSH_DHCPC=n +CONFIG_THTTPD_IPADDR=0xc0a80032 +CONFIG_THTTPD_PATH="/mnt/www" +CONFIG_FS_NXFFS=y +CONFIG_STM32_BUILDROOT=y +CONFIG_DEBUG_NET=n +CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 +CONFIG_MMCSD_SDIO=n +CONFIG_EXAMPLES_UIP_DHCPC=n +CONFIG_EXAMPLES_THTTPD_DRIPADDR=0xc0a80001 +CONFIG_THTTPD_SERVER_SOFTWARE="thttpd/2.25b 29dec2003-NuttX" +CONFIG_THTTPD_OCCASIONAL_MSEC=120 +CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00 +CONFIG_FS_ROMFS=y +CONFIG_THTTPD_GENERATE_INDICES=n +CONFIG_NETUTILS_THTTPD=y +CONFIG_THTTPD_SERVER_ADDRESS="http://www.nuttx.org" +CONFIG_THTTPD_CGI_TIMELIMIT=0 +CONFIG_THTTPD_CGI_STACKSIZE=1024 +CONFIG_MTD=y +CONFIG_NET_BROADCAST=y +CONFIG_CPP_HAVE_WARNING=n +CONFIG_THTTPD_TILDE_MAP2=n +CONFIG_THTTPD_TILDE_MAP1=n +CONFIG_MTD_W25=y +CONFIG_THTTPD_LINGER_MSEC=500 +CONFIG_THTTPD_CGI_BYTECOUNT=20000 +CONFIG_NXFLAT=y +CONFIG_THTTPD_LISTEN_BACKLOG=8 +CONFIG_DEBUG_VERBOSE=n +CONFIG_DEBUG=y +CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80032 +CONFIG_EXAMPLES_UIP_DRIPADDR=0xc0a80001 +CONFIG_THTTPD_CGI_PATH="/mnt/www/cgi-bin" +CONFIG_SYMTAB_ORDEREDBYNAME=y +CONFIG_THTTPD_IDLE_READ_LIMIT_SEC=300 +CONFIG_THTTPD_CGI_PATTERN="/mnt/www/cgi-bin/*" diff --git a/nuttx/configs/shenzhou/thttpd/setenv.sh b/nuttx/configs/shenzhou/thttpd/setenv.sh new file mode 100755 index 0000000000..8b4a7969df --- /dev/null +++ b/nuttx/configs/shenzhou/thttpd/setenv.sh @@ -0,0 +1,78 @@ +#!/bin/bash +# configs/shenzhou/thttpd/setenv.sh +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +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" + +# This is the path to the tools/ subdirectory +export TOOLS_DIR="${WD}/configs/shenzhou/tools" + +# Add the path to the toolchain to the PATH variable +export PATH="${TOOLCHAIN_BIN}:${TOOLS_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" From 860e5f0524a79a3fc7c776d925d1e73066b7f78d Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 20 Oct 2012 13:14:04 +0000 Subject: [PATCH 003/206] The termios c_speed field cannot be 'const' git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5234 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 3 +++ nuttx/configs/lincoln60/README.txt | 4 ++-- nuttx/configs/mbed/README.txt | 4 ++-- nuttx/configs/olimex-lpc1766stk/README.txt | 4 ++-- nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh | 5 ----- nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh | 5 ----- nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh | 5 ----- nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh | 5 ----- nuttx/configs/olimex-lpc1766stk/nx/setenv.sh | 5 ----- nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh | 5 ----- nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh | 5 ----- nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh | 5 ----- nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh | 5 ----- nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh | 5 ----- nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh | 5 ----- nuttx/configs/shenzhou/README.txt | 10 ++++++++++ nuttx/include/termios.h | 2 +- nuttx/lib/termios/lib_cfsetspeed.c | 7 +------ 18 files changed, 21 insertions(+), 68 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 971e9ff9bf..ad6521a9e1 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3474,4 +3474,7 @@ board (Darcy Gong). * configs/shenzhou/thttpd: Add a THTTPD configuration for the Shenzhou board (Darcy Gong). + * include/termios.h and lib/termios/libcf*speed.c: The non-standard, + "hidden" c_speed cannot be type const or else static instantiations + of termios will be required to initialize it (Mike Smith). diff --git a/nuttx/configs/lincoln60/README.txt b/nuttx/configs/lincoln60/README.txt index 07ca167cd1..068ca50dc7 100644 --- a/nuttx/configs/lincoln60/README.txt +++ b/nuttx/configs/lincoln60/README.txt @@ -461,8 +461,8 @@ host operations. To make these modifications, do the following: 2. Then edit the top-level .config file to enable USB host. Make the following changes: - CONFIG_LPC17_USBHOST=n - CONFIG_USBHOST=n + CONFIG_LPC17_USBHOST=y + CONFIG_USBHOST=y CONFIG_SCHED_WORKQUEUE=y When this change is made, NSH should be extended to support USB flash diff --git a/nuttx/configs/mbed/README.txt b/nuttx/configs/mbed/README.txt index 4b413560ab..958ae98184 100644 --- a/nuttx/configs/mbed/README.txt +++ b/nuttx/configs/mbed/README.txt @@ -432,8 +432,8 @@ host operations. To make these modifications, do the following: 2. Then edit the top-level .config file to enable USB host. Make the following changes: - CONFIG_LPC17_USBHOST=n - CONFIG_USBHOST=n + CONFIG_LPC17_USBHOST=y + CONFIG_USBHOST=y CONFIG_SCHED_WORKQUEUE=y When this change is made, NSH should be extended to support USB flash diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt index f638ed4ff6..0983ab1f52 100644 --- a/nuttx/configs/olimex-lpc1766stk/README.txt +++ b/nuttx/configs/olimex-lpc1766stk/README.txt @@ -836,8 +836,8 @@ USB host operations. To make these modifications, do the following: 2. Then edit the top-level .config file to enable USB host. Make the following changes: - CONFIG_LPC17_USBHOST=n - CONFIG_USBHOST=n + CONFIG_LPC17_USBHOST=y + CONFIG_USBHOST=y CONFIG_SCHED_WORKQUEUE=y When this change is made, NSH should be extended to support USB flash diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh b/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh index f9194c00d3..bc02a33b5c 100755 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh b/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh index 4c76646f9f..af4a2589ee 100755 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh b/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh index d544f44706..d4627713d1 100755 --- a/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/nettest/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh b/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh index 84150b0687..f9d5c3a16b 100755 --- a/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/nsh/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh b/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh index b94b47ad48..f9516c7765 100755 --- a/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/nx/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh b/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh index a5547b3bfd..2c3bc3e6d4 100755 --- a/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/ostest/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh b/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh index 35dbd55b38..c32bc579a3 100755 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh b/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh index bcf0c4dead..7517148f5f 100755 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh b/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh index ea9fe6c67e..ad34dd6a1d 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh b/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh index fa23269fbe..4e01bb195d 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh b/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh index b7ada2bc25..767614612b 100755 --- a/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/wlan/setenv.sh @@ -47,11 +47,6 @@ 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 diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index 772c59a174..7bf67710da 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -846,3 +846,13 @@ Where is one of the following: -CONFIG_NX_WRITEONLY=y +# CONFIG_NX_WRITEONLY is not set + thttpd + ------ + + 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 due to incompatibilities introduced in later + GCC releases. diff --git a/nuttx/include/termios.h b/nuttx/include/termios.h index e381814e3c..2e1c38fc26 100644 --- a/nuttx/include/termios.h +++ b/nuttx/include/termios.h @@ -230,7 +230,7 @@ struct termios * cf[set|get][o|i]speed() POSIX interfaces. */ - const speed_t c_speed; /* Input/output speed (non-POSIX)*/ + speed_t c_speed; /* Input/output speed (non-POSIX)*/ }; /**************************************************************************** diff --git a/nuttx/lib/termios/lib_cfsetspeed.c b/nuttx/lib/termios/lib_cfsetspeed.c index bf9e660640..714562ff50 100644 --- a/nuttx/lib/termios/lib_cfsetspeed.c +++ b/nuttx/lib/termios/lib_cfsetspeed.c @@ -110,12 +110,7 @@ int cfsetspeed(FAR struct termios *termiosp, speed_t speed) { - FAR speed_t *speedp; - DEBUGASSERT(termiosp); - - speedp = (FAR speed_t *)&termiosp->c_speed; - *speedp = speed; - + termiosp->c_speed = speed; return OK; } From 78ba846c066a97fab1c5f485d4d7fff3bb55d215 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 20 Oct 2012 13:47:30 +0000 Subject: [PATCH 004/206] DNS fixes from Darcy Gong (part 1 of 2) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5235 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 2 + apps/include/netutils/resolv.h | 5 ++ apps/netutils/dhcpc/dhcpc.c | 62 +++++++------- apps/netutils/resolv/Kconfig | 9 ++ apps/netutils/resolv/resolv.c | 128 ++++++++++++++++++++++++---- apps/netutils/webclient/webclient.c | 56 +----------- apps/nshlib/nsh_netcmds.c | 15 +++- 7 files changed, 172 insertions(+), 105 deletions(-) diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index b73f072bc6..54a6f5cfad 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -370,3 +370,5 @@ when I was trying to add correct handling for loss of connection (Darcy Gong) * apps/nshlib/nsh_telnetd.c: Add support for login to Telnet session via username and password (Darcy Gong). + * apps/netutils/resolv/resolv.c (and files using the DNS resolver): Various + DNS address resolution improvements from Darcy Gong. diff --git a/apps/include/netutils/resolv.h b/apps/include/netutils/resolv.h index bf71e3b6e8..21b9b576ca 100644 --- a/apps/include/netutils/resolv.h +++ b/apps/include/netutils/resolv.h @@ -74,6 +74,11 @@ EXTERN void resolv_getserver(FAR struct in_addr *dnsserver); EXTERN int resolv_query(FAR const char *name, FAR struct sockaddr_in *addr); #endif +EXTERN int dns_gethostip(const char *hostname, in_addr_t *ipaddr); +#define dns_setserver resolv_conf +#define dns_getserver resolv_getserver +#define dns_whois resolv_query + #undef EXTERN #if defined(__cplusplus) } diff --git a/apps/netutils/dhcpc/dhcpc.c b/apps/netutils/dhcpc/dhcpc.c index 9801242fe9..f5e15c8dc5 100644 --- a/apps/netutils/dhcpc/dhcpc.c +++ b/apps/netutils/dhcpc/dhcpc.c @@ -352,9 +352,9 @@ void *dhcpc_open(const void *macaddr, int maclen) struct sockaddr_in addr; struct timeval tv; - dbg("MAC: %02x:%02x:%02x:%02x:%02x:%02x\n", - ((uint8_t*)macaddr)[0], ((uint8_t*)macaddr)[1], ((uint8_t*)macaddr)[2], - ((uint8_t*)macaddr)[3], ((uint8_t*)macaddr)[4], ((uint8_t*)macaddr)[5]); + ndbg("MAC: %02x:%02x:%02x:%02x:%02x:%02x\n", + ((uint8_t*)macaddr)[0], ((uint8_t*)macaddr)[1], ((uint8_t*)macaddr)[2], + ((uint8_t*)macaddr)[3], ((uint8_t*)macaddr)[4], ((uint8_t*)macaddr)[5]); /* Allocate an internal DHCP structure */ @@ -456,7 +456,7 @@ int dhcpc_request(void *handle, struct dhcpc_state *presult) { /* Send the DISCOVER command */ - dbg("Broadcast DISCOVER\n"); + ndbg("Broadcast DISCOVER\n"); if (dhcpc_sendmsg(pdhcpc, presult, DHCPDISCOVER) < 0) { return ERROR; @@ -474,7 +474,7 @@ int dhcpc_request(void *handle, struct dhcpc_state *presult) * by a new OFFER. */ - dbg("Received OFFER from %08x\n", ntohl(presult->serverid.s_addr)); + ndbg("Received OFFER from %08x\n", ntohl(presult->serverid.s_addr)); pdhcpc->ipaddr.s_addr = presult->ipaddr.s_addr; pdhcpc->serverid.s_addr = presult->serverid.s_addr; @@ -509,7 +509,7 @@ int dhcpc_request(void *handle, struct dhcpc_state *presult) { /* Send the REQUEST message to obtain the lease that was offered to us. */ - dbg("Send REQUEST\n"); + ndbg("Send REQUEST\n"); if (dhcpc_sendmsg(pdhcpc, presult, DHCPREQUEST) < 0) { return ERROR; @@ -531,7 +531,7 @@ int dhcpc_request(void *handle, struct dhcpc_state *presult) if (msgtype == DHCPACK) { - dbg("Received ACK\n"); + ndbg("Received ACK\n"); state = STATE_HAVE_LEASE; } @@ -541,7 +541,7 @@ int dhcpc_request(void *handle, struct dhcpc_state *presult) else if (msgtype == DHCPNAK) { - dbg("Received NAK\n"); + ndbg("Received NAK\n"); break; } @@ -552,7 +552,7 @@ int dhcpc_request(void *handle, struct dhcpc_state *presult) else if (msgtype == DHCPOFFER) { - dbg("Received another OFFER, send DECLINE\n"); + ndbg("Received another OFFER, send DECLINE\n"); (void)dhcpc_sendmsg(pdhcpc, presult, DHCPDECLINE); } @@ -560,7 +560,7 @@ int dhcpc_request(void *handle, struct dhcpc_state *presult) else { - dbg("Ignoring msgtype=%d\n", msgtype); + ndbg("Ignoring msgtype=%d\n", msgtype); } } @@ -582,26 +582,26 @@ int dhcpc_request(void *handle, struct dhcpc_state *presult) } while (state != STATE_HAVE_LEASE); - dbg("Got IP address %d.%d.%d.%d\n", - (presult->ipaddr.s_addr >> 24 ) & 0xff, - (presult->ipaddr.s_addr >> 16 ) & 0xff, - (presult->ipaddr.s_addr >> 8 ) & 0xff, - (presult->ipaddr.s_addr ) & 0xff); - dbg("Got netmask %d.%d.%d.%d\n", - (presult->netmask.s_addr >> 24 ) & 0xff, - (presult->netmask.s_addr >> 16 ) & 0xff, - (presult->netmask.s_addr >> 8 ) & 0xff, - (presult->netmask.s_addr ) & 0xff); - dbg("Got DNS server %d.%d.%d.%d\n", - (presult->dnsaddr.s_addr >> 24 ) & 0xff, - (presult->dnsaddr.s_addr >> 16 ) & 0xff, - (presult->dnsaddr.s_addr >> 8 ) & 0xff, - (presult->dnsaddr.s_addr ) & 0xff); - dbg("Got default router %d.%d.%d.%d\n", - (presult->default_router.s_addr >> 24 ) & 0xff, - (presult->default_router.s_addr >> 16 ) & 0xff, - (presult->default_router.s_addr >> 8 ) & 0xff, - (presult->default_router.s_addr ) & 0xff); - dbg("Lease expires in %d seconds\n", presult->lease_time); + ndbg("Got IP address %d.%d.%d.%d\n", + (presult->ipaddr.s_addr ) & 0xff, + (presult->ipaddr.s_addr >> 8 ) & 0xff, + (presult->ipaddr.s_addr >> 16 ) & 0xff, + (presult->ipaddr.s_addr >> 24 ) & 0xff); + ndbg("Got netmask %d.%d.%d.%d\n", + (presult->netmask.s_addr ) & 0xff, + (presult->netmask.s_addr >> 8 ) & 0xff, + (presult->netmask.s_addr >> 16 ) & 0xff, + (presult->netmask.s_addr >> 24 ) & 0xff); + ndbg("Got DNS server %d.%d.%d.%d\n", + (presult->dnsaddr.s_addr ) & 0xff, + (presult->dnsaddr.s_addr >> 8 ) & 0xff, + (presult->dnsaddr.s_addr >> 16 ) & 0xff, + (presult->dnsaddr.s_addr >> 24 ) & 0xff); + ndbg("Got default router %d.%d.%d.%d\n", + (presult->default_router.s_addr ) & 0xff, + (presult->default_router.s_addr >> 8 ) & 0xff, + (presult->default_router.s_addr >> 16 ) & 0xff, + (presult->default_router.s_addr >> 24 ) & 0xff); + ndbg("Lease expires in %d seconds\n", presult->lease_time); return OK; } diff --git a/apps/netutils/resolv/Kconfig b/apps/netutils/resolv/Kconfig index f92d732f5f..afbe0eaa53 100644 --- a/apps/netutils/resolv/Kconfig +++ b/apps/netutils/resolv/Kconfig @@ -15,3 +15,12 @@ config NET_RESOLV_ENTRIES depends on NETUTILS_RESOLV ---help--- Number of resolver entries. Default: 8 + +NET_RESOLV_MAXRESPONSE + int "Max response size" + default 96 + depends on NETUTILS_RESOLV + ---help--- + This setting determines the maximum size of DHCP response message that + can be received. The default is 96 but may need to be larger on enterprise + networks (perhaps 176). diff --git a/apps/netutils/resolv/resolv.c b/apps/netutils/resolv/resolv.c index 98d1b28e84..eb60c098e2 100644 --- a/apps/netutils/resolv/resolv.c +++ b/apps/netutils/resolv/resolv.c @@ -59,11 +59,13 @@ #include #include #include +#include #include #include #include +#include /**************************************************************************** * Definitions @@ -96,7 +98,12 @@ #define DNS_FLAG2_ERR_NAME 0x03 #define SEND_BUFFER_SIZE 64 -#define RECV_BUFFER_SIZE 64 + +#ifdef CONFIG_NET_RESOLV_MAXRESPONSE +# define RECV_BUFFER_SIZE CONFIG_NET_RESOLV_MAXRESPONSE +#else +# define RECV_BUFFER_SIZE 96 +#endif #ifdef CONFIG_NET_IPv6 #define ADDRLEN sizeof(struct sockaddr_in6) @@ -233,6 +240,13 @@ static int send_query(const char *name, struct sockaddr_in *addr) while(*nameptr != 0); memcpy(query, endquery, 5); + +#ifdef CONFIG_NET_IPv6 + DEBUGASSERT(((struct sockaddr *)addr)->sa_family == AF_INET6); +#else + DEBUGASSERT(((struct sockaddr *)addr)->sa_family == AF_INET); +#endif + return sendto(g_sockfd, buffer, query + 5 - buffer, 0, (struct sockaddr*)addr, ADDRLEN); } @@ -262,10 +276,10 @@ int recv_response(struct sockaddr_in *addr) hdr = (struct dns_hdr *)buffer; - dbg( "ID %d\n", htons(hdr->id)); - dbg( "Query %d\n", hdr->flags1 & DNS_FLAG1_RESPONSE); - dbg( "Error %d\n", hdr->flags2 & DNS_FLAG2_ERR_MASK); - dbg( "Num questions %d, answers %d, authrr %d, extrarr %d\n", + ndbg("ID %d\n", htons(hdr->id)); + ndbg("Query %d\n", hdr->flags1 & DNS_FLAG1_RESPONSE); + ndbg("Error %d\n", hdr->flags2 & DNS_FLAG2_ERR_MASK); + ndbg("Num questions %d, answers %d, authrr %d, extrarr %d\n", htons(hdr->numquestions), htons(hdr->numanswers), htons(hdr->numauthrr), htons(hdr->numextrarr)); @@ -286,7 +300,28 @@ int recv_response(struct sockaddr_in *addr) /* Skip the name in the question. XXX: This should really be * checked agains the name in the question, to be sure that they * match. - */ + */ + +#ifdef CONFIG_DEBUG_NET + { + int d = 64; + nameptr = parse_name((unsigned char *)buffer + 12) + 4; + + for (;;) + { + ndbg("%02X %02X %02X %02X %02X %02X %02X %02X \n", + nameptr[0],nameptr[1],nameptr[2],nameptr[3], + nameptr[4],nameptr[5],nameptr[6],nameptr[7]); + + nameptr += 8; + d -= 8; + if (d < 0) + { + break; + } + } + } +#endif nameptr = parse_name((unsigned char *)buffer + 12) + 4; @@ -301,7 +336,7 @@ int recv_response(struct sockaddr_in *addr) /* Compressed name. */ nameptr +=2; - dbg("Compressed anwser\n"); + ndbg("Compressed anwser\n"); } else { @@ -310,21 +345,23 @@ int recv_response(struct sockaddr_in *addr) } ans = (struct dns_answer *)nameptr; - dbg("Answer: type %x, class %x, ttl %x, length %x\n", - htons(ans->type), htons(ans->class), (htons(ans->ttl[0]) << 16) | htons(ans->ttl[1]), - htons(ans->len)); + ndbg("Answer: type %x, class %x, ttl %x, length %x \n", /* 0x%08X\n", */ + htons(ans->type), htons(ans->class), + (htons(ans->ttl[0]) << 16) | htons(ans->ttl[1]), + htons(ans->len) /* , ans->ipaddr.s_addr */); /* Check for IP address type and Internet class. Others are discarded. */ if (ans->type == HTONS(1) && ans->class == HTONS(1) && ans->len == HTONS(4)) { - dbg("IP address %d.%d.%d.%d\n", - (ans->ipaddr.s_addr >> 24 ) & 0xff, - (ans->ipaddr.s_addr >> 16 ) & 0xff, - (ans->ipaddr.s_addr >> 8 ) & 0xff, - (ans->ipaddr.s_addr ) & 0xff); + ans->ipaddr.s_addr = *(uint32_t*)(nameptr+10); + ndbg("IP address %d.%d.%d.%d\n", + (ans->ipaddr.s_addr ) & 0xff, + (ans->ipaddr.s_addr >> 8 ) & 0xff, + (ans->ipaddr.s_addr >> 16 ) & 0xff, + (ans->ipaddr.s_addr >> 24 ) & 0xff); - /* XXX: we should really check that this IP address is the one + /* XXX: we should really check that this IP address is the one * we want. */ @@ -336,6 +373,7 @@ int recv_response(struct sockaddr_in *addr) nameptr = nameptr + 10 + htons(ans->len); } } + return ERROR; } @@ -343,6 +381,62 @@ int recv_response(struct sockaddr_in *addr) * Public Functions ****************************************************************************/ +/**************************************************************************** + * Name: dns_gethostip + ****************************************************************************/ + +int dns_gethostip(const char *hostname, in_addr_t *ipaddr) +{ +#ifdef CONFIG_HAVE_GETHOSTBYNAME + + struct hostent *he; + + nvdbg("Getting address of %s\n", hostname); + he = gethostbyname(hostname); + if (!he) + { + ndbg("gethostbyname failed: %d\n", h_errno); + return ERROR; + } + + nvdbg("Using IP address %04x%04x\n", + (uint16_t)he->h_addr[1], (uint16_t)he->h_addr[0]); + + memcpy(ipaddr, he->h_addr, sizeof(in_addr_t)); + return OK; + +#else + +# ifdef CONFIG_NET_IPv6 + struct sockaddr_in6 addr; +# else + struct sockaddr_in addr; +# endif + + /* First check if the host is an IP address. */ + + if (!uiplib_ipaddrconv(hostname, (uint8_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 */ + + return ERROR; + } + + /* Save the host address -- Needs fixed for IPv6 */ + + *ipaddr = addr.sin_addr.s_addr; + } + return OK; + +#endif +} + /* Get the binding for name. */ #ifdef CONFIG_NET_IPv6 @@ -358,7 +452,7 @@ int resolv_query(FAR const char *name, FAR struct sockaddr_in *addr) for (retries = 0; retries < 3; retries++) { - if (send_query(name, addr) < 0) + if (send_query(name, &g_dnsserver) < 0) { return ERROR; } diff --git a/apps/netutils/webclient/webclient.c b/apps/netutils/webclient/webclient.c index 5a84c4fd12..8ce7b93a07 100644 --- a/apps/netutils/webclient/webclient.c +++ b/apps/netutils/webclient/webclient.c @@ -167,60 +167,6 @@ static char *wget_strcpy(char *dest, const char *src) return dest + len; } -/**************************************************************************** - * Name: wget_resolvehost - ****************************************************************************/ - -static inline int wget_resolvehost(const char *hostname, in_addr_t *ipaddr) -{ -#ifdef CONFIG_HAVE_GETHOSTBYNAME - - struct hostent *he; - - nvdbg("Getting address of %s\n", hostname); - he = gethostbyname(hostname); - if (!he) - { - ndbg("gethostbyname failed: %d\n", h_errno); - return ERROR; - } - - nvdbg("Using IP address %04x%04x\n", (uint16_t)he->h_addr[1], (uint16_t)he->h_addr[0]); - memcpy(ipaddr, he->h_addr, sizeof(in_addr_t)); - return OK; - -#else - -# ifdef CONFIG_NET_IPv6 - struct sockaddr_in6 addr; -# else - struct sockaddr_in addr; -# endif - - /* First check if the host is an IP address. */ - - if (!uiplib_ipaddrconv(hostname, (uint8_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 */ - - return ERROR; - } - - /* Save the host address -- Needs fixed for IPv6 */ - - *ipaddr = addr.sin_addr.s_addr; - } - return OK; - -#endif -} - /**************************************************************************** * Name: wget_parsestatus ****************************************************************************/ @@ -465,7 +411,7 @@ int wget(FAR const char *url, FAR char *buffer, int buflen, server.sin_family = AF_INET; server.sin_port = htons(ws.port); - ret = wget_resolvehost(ws.hostname, &server.sin_addr.s_addr); + ret = dns_gethostip(ws.hostname, &server.sin_addr.s_addr); if (ret < 0) { /* Could not resolve host (or malformed IP address) */ diff --git a/apps/nshlib/nsh_netcmds.c b/apps/nshlib/nsh_netcmds.c index cfea5a08a0..e04dab1234 100644 --- a/apps/nshlib/nsh_netcmds.c +++ b/apps/nshlib/nsh_netcmds.c @@ -51,6 +51,7 @@ #include /* Needed for open */ #include /* Needed for basename */ #include +#include #include #include @@ -80,6 +81,12 @@ # endif #endif +#ifdef CONFIG_HAVE_GETHOSTBYNAME +# include +#else +# include +#endif + #include "nsh.h" #include "nsh_console.h" @@ -599,7 +606,7 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) if (optind == argc-1) { staddr = argv[optind]; - if (!uiplib_ipaddrconv(staddr, (FAR unsigned char*)&ipaddr)) + if (dns_gethostip(staddr, &ipaddr) < 0) { goto errout; } @@ -621,7 +628,11 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) /* Loop for the specified count */ - nsh_output(vtbl, "PING %s %d bytes of data\n", staddr, DEFAULT_PING_DATALEN); + nsh_output(vtbl, "PING %d.%d.%d.%d %d bytes of data\n", + (ipaddr ) & 0xff, (ipaddr >> 8 ) & 0xff, + (ipaddr >> 16 ) & 0xff, (ipaddr >> 24 ) & 0xff, + DEFAULT_PING_DATALEN); + start = g_system_timer; for (i = 1; i <= count; i++) { From dbdf7cb3ae33224d45b5185d15d756508c11a246 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 20 Oct 2012 14:15:59 +0000 Subject: [PATCH 005/206] Ping/DNS fixes (part 2 of 2) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5236 42af7a65-404d-4744-a932-0658087f49c3 --- apps/include/netutils/resolv.h | 1 + apps/netutils/resolv/Kconfig | 2 +- apps/nshlib/Kconfig | 9 +++++++++ apps/nshlib/nsh.h | 9 +++++++++ apps/nshlib/nsh_netcmds.c | 23 +++++++++++++++++++---- nuttx/net/uip/uip_icmpping.c | 2 ++ 6 files changed, 41 insertions(+), 5 deletions(-) diff --git a/apps/include/netutils/resolv.h b/apps/include/netutils/resolv.h index 21b9b576ca..b0d93fd822 100644 --- a/apps/include/netutils/resolv.h +++ b/apps/include/netutils/resolv.h @@ -75,6 +75,7 @@ EXTERN int resolv_query(FAR const char *name, FAR struct sockaddr_in *addr); #endif EXTERN int dns_gethostip(const char *hostname, in_addr_t *ipaddr); + #define dns_setserver resolv_conf #define dns_getserver resolv_getserver #define dns_whois resolv_query diff --git a/apps/netutils/resolv/Kconfig b/apps/netutils/resolv/Kconfig index afbe0eaa53..a8e79d6c1f 100644 --- a/apps/netutils/resolv/Kconfig +++ b/apps/netutils/resolv/Kconfig @@ -16,7 +16,7 @@ config NET_RESOLV_ENTRIES ---help--- Number of resolver entries. Default: 8 -NET_RESOLV_MAXRESPONSE +config NET_RESOLV_MAXRESPONSE int "Max response size" default 96 depends on NETUTILS_RESOLV diff --git a/apps/nshlib/Kconfig b/apps/nshlib/Kconfig index d12a329738..9bca6658cb 100644 --- a/apps/nshlib/Kconfig +++ b/apps/nshlib/Kconfig @@ -520,3 +520,12 @@ config NSH_NOMAC ---help--- Set if your ethernet hardware has no built-in MAC address. If set, a bogus MAC will be assigned. + +config NSH_MAX_ROUNDTRIP + int "Max Ping Round-Trip (DSEC)" + default 20 + depends on NSH_LIBRARY && NET && !NSH_DISABLE_PING + ---help--- + This is the maximum round trip for a response to a ICMP ECHO request. + It is in units of deciseconds. The default is 20 (2 seconds). + diff --git a/apps/nshlib/nsh.h b/apps/nshlib/nsh.h index cfab262710..f85df29dd6 100644 --- a/apps/nshlib/nsh.h +++ b/apps/nshlib/nsh.h @@ -215,6 +215,15 @@ #endif /* CONFIG_NSH_TELNET_LOGIN */ +/* CONFIG_NSH_MAX_ROUNDTRIP - This is the maximum round trip for a response to + * a ICMP ECHO request. It is in units of deciseconds. The default is 20 + * (2 seconds). + */ + +#ifndef CONFIG_NSH_MAX_ROUNDTRIP +# define CONFIG_NSH_MAX_ROUNDTRIP 20 +#endif + /* Verify support for ROMFS /etc directory support options */ #ifdef CONFIG_NSH_ROMFSETC diff --git a/apps/nshlib/nsh_netcmds.c b/apps/nshlib/nsh_netcmds.c index e04dab1234..f3457a809d 100644 --- a/apps/nshlib/nsh_netcmds.c +++ b/apps/nshlib/nsh_netcmds.c @@ -94,8 +94,16 @@ * Definitions ****************************************************************************/ +/* Size of the ECHO data */ + #define DEFAULT_PING_DATALEN 56 +/* Get the larger value */ + +#ifndef MAX +# define MAX(a,b) (a > b ? a : b) +#endif + /**************************************************************************** * Private Types ****************************************************************************/ @@ -543,6 +551,7 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) uint32_t start; uint32_t next; uint32_t dsec = 10; + uint32_t maxwait; uint16_t id; bool badarg = false; int count = 10; @@ -626,6 +635,12 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) id = ping_newid(); + /* The maximum wait for a response will be the larger of the inter-ping time and + * the configured maximum round-trip time. + */ + + maxwait = MAX(dsec, CONFIG_NSH_MAX_ROUNDTRIP); + /* Loop for the specified count */ nsh_output(vtbl, "PING %d.%d.%d.%d %d bytes of data\n", @@ -639,7 +654,7 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) /* Send the ECHO request and wait for the response */ next = g_system_timer; - seqno = uip_ping(ipaddr, id, i, DEFAULT_PING_DATALEN, dsec); + seqno = uip_ping(ipaddr, id, i, DEFAULT_PING_DATALEN, maxwait); /* Was any response returned? We can tell if a non-negative sequence * number was returned. @@ -647,7 +662,7 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) if (seqno >= 0 && seqno <= i) { - /* Get the elpased time from the time that the request was + /* Get the elapsed time from the time that the request was * sent until the response was received. If we got a response * to an earlier request, then fudge the elpased time. */ @@ -655,7 +670,7 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) elapsed = TICK2MSEC(g_system_timer - next); if (seqno < i) { - elapsed += 100*dsec*(i - seqno); + elapsed += 100 * dsec * (i - seqno); } /* Report the receipt of the reply */ @@ -673,7 +688,7 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) elapsed = TICK2DSEC(g_system_timer - next); if (elapsed < dsec) { - usleep(100000*dsec); + usleep(100000 * (dsec - elapsed)); } } diff --git a/nuttx/net/uip/uip_icmpping.c b/nuttx/net/uip/uip_icmpping.c index e3ebf72520..36f6e892ad 100644 --- a/nuttx/net/uip/uip_icmpping.c +++ b/nuttx/net/uip/uip_icmpping.c @@ -123,6 +123,7 @@ static inline int ping_timeout(struct icmp_ping_s *pstate) { return TRUE; } + return FALSE; } @@ -365,6 +366,7 @@ int uip_ping(uip_ipaddr_t addr, uint16_t id, uint16_t seqno, uip_icmpcallbackfree(state.png_cb); } + uip_unlock(save); /* Return the negated error number in the event of a failure, or the From 736ac8982a3388fd6e5f96f0587e05b8c09bfd61 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 20 Oct 2012 15:17:19 +0000 Subject: [PATCH 006/206] Add MAX11802 touchscreeen driver from Petteri Aimonen git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5237 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 3 + nuttx/ChangeLog | 3 + nuttx/drivers/input/Make.defs | 4 + nuttx/drivers/input/max11802.c | 1313 ++++++++++++++++++++++++++ nuttx/drivers/input/max11802.h | 167 ++++ nuttx/include/nuttx/compiler.h | 9 +- nuttx/include/nuttx/input/max11802.h | 175 ++++ 7 files changed, 1672 insertions(+), 2 deletions(-) create mode 100644 nuttx/drivers/input/max11802.c create mode 100644 nuttx/drivers/input/max11802.h create mode 100644 nuttx/include/nuttx/input/max11802.h diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 54a6f5cfad..b9ba6ac91b 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -372,3 +372,6 @@ username and password (Darcy Gong). * apps/netutils/resolv/resolv.c (and files using the DNS resolver): Various DNS address resolution improvements from Darcy Gong. + * apps/nshlib/nsh_netcmds.c: The ping command now passes a maximum round + trip time to uip_icmpping(). This allows pinging of hosts on complex + networks where the ICMP ECHO round trip time may exceed the ping interval. diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index ad6521a9e1..bfae8e3670 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3477,4 +3477,7 @@ * include/termios.h and lib/termios/libcf*speed.c: The non-standard, "hidden" c_speed cannot be type const or else static instantiations of termios will be required to initialize it (Mike Smith). + * drivers/input/max11802.c/h, and include/nuttx/input max11802.h: Adds + support for the Maxim MAX11802 touchscreen controller (contributed by + Petteri Aimonen). diff --git a/nuttx/drivers/input/Make.defs b/nuttx/drivers/input/Make.defs index 6dbae268e5..8b009760c4 100644 --- a/nuttx/drivers/input/Make.defs +++ b/nuttx/drivers/input/Make.defs @@ -47,6 +47,10 @@ ifeq ($(CONFIG_INPUT_ADS7843E),y) CSRCS += ads7843e.c endif +ifeq ($(CONFIG_INPUT_MAX11802),y) + CSRCS += max11802.c +endif + ifeq ($(CONFIG_INPUT_STMPE811),y) CSRCS += stmpe811_base.c ifneq ($(CONFIG_INPUT_STMPE811_TSC_DISABLE),y) diff --git a/nuttx/drivers/input/max11802.c b/nuttx/drivers/input/max11802.c new file mode 100644 index 0000000000..ea3883cd0c --- /dev/null +++ b/nuttx/drivers/input/max11802.c @@ -0,0 +1,1313 @@ +/**************************************************************************** + * drivers/input/max11802.c + * + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Petteri Aimonen + * + * References: + * "Low-Power, Ultra-Small Resistive Touch-Screen Controllers + * with I2C/SPI Interface" Maxim IC, Rev 3, 10/2010 + * + * 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 +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include "max11802.h" + +/**************************************************************************** + * 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 + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ +/* Low-level SPI helpers */ + +#ifdef CONFIG_SPI_OWNBUS +static inline void max11802_configspi(FAR struct spi_dev_s *spi); +# define max11802_lock(spi) +# define max11802_unlock(spi) +#else +# define max11802_configspi(spi); +static void max11802_lock(FAR struct spi_dev_s *spi); +static void max11802_unlock(FAR struct spi_dev_s *spi); +#endif + +static uint16_t max11802_sendcmd(FAR struct max11802_dev_s *priv, uint8_t cmd, int *tags); + +/* Interrupts and data sampling */ + +static void max11802_notify(FAR struct max11802_dev_s *priv); +static int max11802_sample(FAR struct max11802_dev_s *priv, + FAR struct max11802_sample_s *sample); +static int max11802_waitsample(FAR struct max11802_dev_s *priv, + FAR struct max11802_sample_s *sample); +static void max11802_worker(FAR void *arg); +static int max11802_interrupt(int irq, FAR void *context); + +/* Character driver methods */ + +static int max11802_open(FAR struct file *filep); +static int max11802_close(FAR struct file *filep); +static ssize_t max11802_read(FAR struct file *filep, FAR char *buffer, size_t len); +static int max11802_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL +static int max11802_poll(FAR struct file *filep, struct pollfd *fds, bool setup); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This the the vtable that supports the character driver interface */ + +static const struct file_operations max11802_fops = +{ + max11802_open, /* open */ + max11802_close, /* close */ + max11802_read, /* read */ + 0, /* write */ + 0, /* seek */ + max11802_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , max11802_poll /* poll */ +#endif +}; + +/* If only a single MAX11802 device is supported, then the driver state + * structure may as well be pre-allocated. + */ + +#ifndef CONFIG_MAX11802_MULTIPLE +static struct max11802_dev_s g_max11802; + +/* Otherwise, we will need to maintain allocated driver instances in a list */ + +#else +static struct max11802_dev_s *g_max11802list; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: max11802_lock + * + * Description: + * 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 + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#ifndef CONFIG_SPI_OWNBUS +static void max11802_lock(FAR struct spi_dev_s *spi) +{ + /* Lock the SPI bus because there are multiple devices competing for the + * SPI bus + */ + + (void)SPI_LOCK(spi, true); + + /* We have the lock. Now make sure that the SPI bus is configured for the + * MAX11802 (it might have gotten configured for a different device while + * unlocked) + */ + + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); + SPI_SETMODE(spi, CONFIG_MAX11802_SPIMODE); + SPI_SETBITS(spi, 8); + SPI_SETFREQUENCY(spi, CONFIG_MAX11802_FREQUENCY); + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); +} +#endif + +/**************************************************************************** + * Function: max11802_unlock + * + * Description: + * 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 + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#ifndef CONFIG_SPI_OWNBUS +static void max11802_unlock(FAR struct spi_dev_s *spi) +{ + /* Relinquish the SPI bus. */ + + (void)SPI_LOCK(spi, false); +} +#endif + +/**************************************************************************** + * Function: max11802_configspi + * + * Description: + * Configure the SPI for use with the MAX11802. This function should be + * called once during touchscreen initialization to configure the SPI + * bus. Note that if CONFIG_SPI_OWNBUS is not defined, then this function + * does nothing. + * + * Parameters: + * spi - Reference to the SPI driver structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#ifdef CONFIG_SPI_OWNBUS +static inline void max11802_configspi(FAR struct spi_dev_s *spi) +{ + /* Configure SPI for the MAX11802. But only if we own the SPI bus. Otherwise, don't + * bother because it might change. + */ + + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); + SPI_SETMODE(spi, CONFIG_MAX11802_SPIMODE); + SPI_SETBITS(spi, 8); + SPI_SETFREQUENCY(spi, CONFIG_MAX11802_FREQUENCY); + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); +} +#endif + +/**************************************************************************** + * Name: max11802_sendcmd + ****************************************************************************/ + +static uint16_t max11802_sendcmd(FAR struct max11802_dev_s *priv, uint8_t cmd, int *tags) +{ + uint8_t buffer[2]; + uint16_t result; + + /* Select the MAX11802 */ + + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + + /* Send the command */ + + (void)SPI_SEND(priv->spi, cmd); + + /* Read the data */ + + SPI_RECVBLOCK(priv->spi, buffer, 2); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + result = ((uint16_t)buffer[0] << 8) | (uint16_t)buffer[1]; + *tags = result & 0xF; + result >>= 4; // Get rid of tags + + ivdbg("cmd:%02x response:%04x\n", cmd, result); + return result; +} + +/**************************************************************************** + * Name: max11802_notify + ****************************************************************************/ + +static void max11802_notify(FAR struct max11802_dev_s *priv) +{ +#ifndef CONFIG_DISABLE_POLL + int i; +#endif + + /* If there are threads waiting for read data, then signal one of them + * that the read data is available. + */ + + if (priv->nwaiters > 0) + { + /* After posting this semaphore, we need to exit because the sample + * is no longer available. + */ + + sem_post(&priv->waitsem); + } + + /* If there are threads waiting on poll() for MAX11802 data to become available, + * then wake them up now. NOTE: we wake up all waiting threads because we + * do not know that they are going to do. If they all try to read the data, + * then some make end up blocking after all. + */ + +#ifndef CONFIG_DISABLE_POLL + for (i = 0; i < CONFIG_MAX11802_NPOLLWAITERS; i++) + { + struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + ivdbg("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } +#endif +} + +/**************************************************************************** + * Name: max11802_sample + ****************************************************************************/ + +static int max11802_sample(FAR struct max11802_dev_s *priv, + FAR struct max11802_sample_s *sample) +{ + irqstate_t flags; + int ret = -EAGAIN; + + /* Interrupts must be disabled when this is called to (1) prevent posting + * of semaphores from interrupt handlers, and (2) to prevent sampled data + * from changing until it has been reported. + */ + + flags = irqsave(); + + /* Is there new MAX11802 sample data available? */ + + if (priv->penchange) + { + /* Yes.. the state has changed in some way. Return a copy of the + * sampled data. + */ + + memcpy(sample, &priv->sample, sizeof(struct max11802_sample_s )); + + /* Now manage state transitions */ + + if (sample->contact == CONTACT_UP) + { + /* Next.. no contact. Increment the ID so that next contact ID + * will be unique. X/Y positions are no longer valid. + */ + + priv->sample.contact = CONTACT_NONE; + priv->sample.valid = false; + priv->id++; + } + else if (sample->contact == CONTACT_DOWN) + { + /* First report -- next report will be a movement */ + + priv->sample.contact = CONTACT_MOVE; + } + + priv->penchange = false; + ret = OK; + } + + irqrestore(flags); + return ret; +} + +/**************************************************************************** + * Name: max11802_waitsample + ****************************************************************************/ + +static int max11802_waitsample(FAR struct max11802_dev_s *priv, + FAR struct max11802_sample_s *sample) +{ + irqstate_t flags; + int ret; + + /* Interrupts must be disabled when this is called to (1) prevent posting + * of semaphores from interrupt handlers, and (2) to prevent sampled data + * from changing until it has been reported. + * + * In addition, we will also disable pre-emption to prevent other threads + * from getting control while we muck with the semaphores. + */ + + sched_lock(); + flags = irqsave(); + + /* Now release the semaphore that manages mutually exclusive access to + * the device structure. This may cause other tasks to become ready to + * run, but they cannot run yet because pre-emption is disabled. + */ + + sem_post(&priv->devsem); + + /* Try to get the a sample... if we cannot, then wait on the semaphore + * that is posted when new sample data is available. + */ + + while (max11802_sample(priv, sample) < 0) + { + /* Wait for a change in the MAX11802 state */ + + ivdbg("Waiting..\n"); + priv->nwaiters++; + ret = sem_wait(&priv->waitsem); + priv->nwaiters--; + + if (ret < 0) + { + /* If we are awakened by a signal, then we need to return + * the failure now. + */ + + idbg("sem_wait: %d\n", errno); + DEBUGASSERT(errno == EINTR); + ret = -EINTR; + goto errout; + } + } + + ivdbg("Sampled\n"); + + /* Re-acquire the the semaphore that manages mutually exclusive access to + * the device structure. We may have to wait here. But we have our sample. + * Interrupts and pre-emption will be re-enabled while we wait. + */ + + ret = sem_wait(&priv->devsem); + +errout: + /* Then re-enable interrupts. We might get interrupt here and there + * could be a new sample. But no new threads will run because we still + * have pre-emption disabled. + */ + + irqrestore(flags); + + /* Restore pre-emption. We might get suspended here but that is okay + * because we already have our sample. Note: this means that if there + * were two threads reading from the MAX11802 for some reason, the data + * might be read out of order. + */ + + sched_unlock(); + return ret; +} + +/**************************************************************************** + * Name: max11802_schedule + ****************************************************************************/ + +static int max11802_schedule(FAR struct max11802_dev_s *priv) +{ + FAR struct max11802_config_s *config; + int ret; + + /* Get a pointer the callbacks for convenience (and so the code is not so + * ugly). + */ + + config = priv->config; + DEBUGASSERT(config != NULL); + + /* Disable further interrupts. MAX11802 interrupts will be re-enabled + * after the worker thread executes. + */ + + config->enable(config, false); + + /* Disable the watchdog timer. It will be re-enabled in the worker thread + * while the pen remains down. + */ + + wd_cancel(priv->wdog); + + /* Transfer processing to the worker thread. Since MAX11802 interrupts are + * disabled while the work is pending, no special action should be required + * to protected the work queue. + */ + + DEBUGASSERT(priv->work.worker == NULL); + ret = work_queue(HPWORK, &priv->work, max11802_worker, priv, 0); + if (ret != 0) + { + illdbg("Failed to queue work: %d\n", ret); + } + + return OK; +} + +/**************************************************************************** + * Name: max11802_wdog + ****************************************************************************/ + +static void max11802_wdog(int argc, uint32_t arg1, ...) +{ + FAR struct max11802_dev_s *priv = (FAR struct max11802_dev_s *)((uintptr_t)arg1); + (void)max11802_schedule(priv); +} + +/**************************************************************************** + * Name: max11802_worker + ****************************************************************************/ + +static void max11802_worker(FAR void *arg) +{ + FAR struct max11802_dev_s *priv = (FAR struct max11802_dev_s *)arg; + FAR struct max11802_config_s *config; + uint16_t x; + uint16_t y; + uint16_t xdiff; + uint16_t ydiff; + bool pendown; + int ret; + int tags, tags2; + + ASSERT(priv != NULL); + + /* Get a pointer the callbacks for convenience (and so the code is not so + * ugly). + */ + + config = priv->config; + DEBUGASSERT(config != NULL); + + /* 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); + + /* Lock the SPI bus so that we have exclusive access */ + + max11802_lock(priv->spi); + + /* Start coordinate measurement */ + (void)max11802_sendcmd(priv, MAX11802_CMD_MEASUREXY, &tags); + + /* 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); + + /* Handle the change from pen down to pen up */ + + if (pendown) + ivdbg("\nPD\n"); + else + ivdbg("\nPU\n"); + + if (!pendown) + { + /* 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) + */ + + ivdbg("\nPC%d\n", priv->sample.contact); + + if (priv->sample.contact == CONTACT_NONE || + priv->sample.contact == CONTACT_UP) + + { + goto ignored; + } + + /* The pen is up. NOTE: We know from a previous test, that this is a + * loss of contact condition. This will be changed to CONTACT_NONE + * after the loss of contact is sampled. + */ + + priv->sample.contact = CONTACT_UP; + } + + /* It is a pen down event. If the last loss-of-contact event has not been + * processed yet, then we have to ignore the pen down event (or else it will + * look like a drag event) + */ + + else if (priv->sample.contact == CONTACT_UP) + { + /* 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. + */ + + ivdbg("Previous pen up event still in buffer\n"); + max11802_notify(priv); + wd_start(priv->wdog, MAX11802_WDOG_DELAY, max11802_wdog, 1, (uint32_t)priv); + goto ignored; + } + else + { + /* Wait for data ready */ + do { + /* Handle pen down events. First, sample positional values. */ + +#ifdef CONFIG_MAX11802_SWAPXY + x = max11802_sendcmd(priv, MAX11802_CMD_YPOSITION, &tags); + y = max11802_sendcmd(priv, MAX11802_CMD_XPOSITION, &tags2); +#else + x = max11802_sendcmd(priv, MAX11802_CMD_XPOSITION, &tags); + y = max11802_sendcmd(priv, MAX11802_CMD_YPOSITION, &tags2); +#endif + } while (tags == 0xF || tags2 == 0xF); + + /* Continue to sample the position while the pen is down */ + wd_start(priv->wdog, MAX11802_WDOG_DELAY, max11802_wdog, 1, (uint32_t)priv); + + /* Check if data is valid */ + if ((tags & 0x03) != 0) + { + ivdbg("Touch ended before measurement\n"); + goto ignored; + } + + /* 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); + + /* Check the thresholds. Bail if there is no significant difference */ + + if (xdiff < CONFIG_MAX11802_THRESHX && ydiff < CONFIG_MAX11802_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 */ + + priv->sample.valid = true; + + /* If this is the first (acknowledged) pen down report, then report + * this as the first contact. If contact == CONTACT_DOWN, it will be + * set to set to CONTACT_MOVE after the contact is first sampled. + */ + + if (priv->sample.contact != CONTACT_MOVE) + { + /* First contact */ + + priv->sample.contact = CONTACT_DOWN; + } + } + + /* Indicate the availability of new sample data for this ID */ + + priv->sample.id = priv->id; + priv->penchange = true; + + /* Notify any waiters that new MAX11802 data is available */ + + max11802_notify(priv); + +ignored: + config->enable(config, true); + + /* Release our lock on the state structure and unlock the SPI bus */ + + sem_post(&priv->devsem); + max11802_unlock(priv->spi); +} + +/**************************************************************************** + * Name: max11802_interrupt + ****************************************************************************/ + +static int max11802_interrupt(int irq, FAR void *context) +{ + FAR struct max11802_dev_s *priv; + FAR struct max11802_config_s *config; + int ret; + + /* Which MAX11802 device caused the interrupt? */ + +#ifndef CONFIG_MAX11802_MULTIPLE + priv = &g_max11802; +#else + for (priv = g_max11802list; + priv && priv->configs->irq != irq; + priv = priv->flink); + + ASSERT(priv != NULL); +#endif + + /* Get a pointer the callbacks for convenience (and so the code is not so + * ugly). + */ + + config = priv->config; + DEBUGASSERT(config != NULL); + + /* Schedule sampling to occur on the worker thread */ + + ret = max11802_schedule(priv); + + /* Clear any pending interrupts and return success */ + + config->clear(config); + return ret; +} + +/**************************************************************************** + * Name: max11802_open + ****************************************************************************/ + +static int max11802_open(FAR struct file *filep) +{ +#ifdef CONFIG_MAX11802_REFCNT + FAR struct inode *inode; + FAR struct max11802_dev_s *priv; + uint8_t tmp; + int ret; + + ivdbg("Opening\n"); + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max11802_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Increment the reference count */ + + tmp = priv->crefs + 1; + if (tmp == 0) + { + /* More than 255 opens; uint8_t overflows to zero */ + + ret = -EMFILE; + goto errout_with_sem; + } + + /* When the reference increments to 1, this is the first open event + * on the driver.. and an opportunity to do any one-time initialization. + */ + + /* Save the new open count on success */ + + priv->crefs = tmp; + +errout_with_sem: + sem_post(&priv->devsem); + return ret; +#else + ivdbg("Opening\n"); + return OK; +#endif +} + +/**************************************************************************** + * Name: max11802_close + ****************************************************************************/ + +static int max11802_close(FAR struct file *filep) +{ +#ifdef CONFIG_MAX11802_REFCNT + FAR struct inode *inode; + FAR struct max11802_dev_s *priv; + int ret; + + ivdbg("Closing\n"); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max11802_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Decrement the reference count unless it would decrement a negative + * value. When the count decrements to zero, there are no further + * open references to the driver. + */ + + if (priv->crefs >= 1) + { + priv->crefs--; + } + + sem_post(&priv->devsem); +#endif + ivdbg("Closing\n"); + return OK; +} + +/**************************************************************************** + * Name: max11802_read + ****************************************************************************/ + +static ssize_t max11802_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + FAR struct inode *inode; + FAR struct max11802_dev_s *priv; + FAR struct touch_sample_s *report; + struct max11802_sample_s sample; + int ret; + + ivdbg("buffer:%p len:%d\n", buffer, len); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max11802_dev_s *)inode->i_private; + + /* Verify that the caller has provided a buffer large enough to receive + * the touch data. + */ + + if (len < SIZEOF_TOUCH_SAMPLE_S(1)) + { + /* We could provide logic to break up a touch report into segments and + * handle smaller reads... but why? + */ + + idbg("Unsupported read size: %d\n", len); + return -ENOSYS; + } + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + idbg("sem_wait: %d\n", errno); + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Try to read sample data. */ + + ret = max11802_sample(priv, &sample); + if (ret < 0) + { + /* Sample data is not available now. We would ave to wait to get + * receive sample data. If the user has specified the O_NONBLOCK + * option, then just return an error. + */ + + ivdbg("Sample data is not available\n"); + if (filep->f_oflags & O_NONBLOCK) + { + ret = -EAGAIN; + goto errout; + } + + /* Wait for sample data */ + + ret = max11802_waitsample(priv, &sample); + if (ret < 0) + { + /* We might have been awakened by a signal */ + + idbg("max11802_waitsample: %d\n", ret); + goto errout; + } + } + + /* In any event, we now have sampled MAX11802 data that we can report + * to the caller. + */ + + report = (FAR struct touch_sample_s *)buffer; + memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1)); + report->npoints = 1; + report->point[0].id = sample.id; + report->point[0].x = sample.x; + report->point[0].y = sample.y; + + /* Report the appropriate flags */ + + if (sample.contact == CONTACT_UP) + { + /* Pen is now up. Is the positional data valid? This is important to + * know because the release will be sent to the window based on its + * last positional data. + */ + + if (sample.valid) + { + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + else + { + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID; + } + } + else if (sample.contact == CONTACT_DOWN) + { + /* First contact */ + + report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + else /* if (sample->contact == CONTACT_MOVE) */ + { + /* Movement of the same contact */ + + report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + + ivdbg(" id: %d\n", report->point[0].id); + ivdbg(" flags: %02x\n", report->point[0].flags); + ivdbg(" x: %d\n", report->point[0].x); + ivdbg(" y: %d\n", report->point[0].y); + + ret = SIZEOF_TOUCH_SAMPLE_S(1); + +errout: + sem_post(&priv->devsem); + ivdbg("Returning: %d\n", ret); + return ret; +} + +/**************************************************************************** + * Name:max11802_ioctl + ****************************************************************************/ + +static int max11802_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode; + FAR struct max11802_dev_s *priv; + int ret; + + ivdbg("cmd: %d arg: %ld\n", cmd, arg); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max11802_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Process the IOCTL by command */ + + switch (cmd) + { + case TSIOC_SETFREQUENCY: /* arg: Pointer to uint32_t frequency value */ + { + FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); + DEBUGASSERT(priv->config != NULL && ptr != NULL); + priv->config->frequency = SPI_SETFREQUENCY(priv->spi, *ptr); + } + break; + + case TSIOC_GETFREQUENCY: /* arg: Pointer to uint32_t frequency value */ + { + FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); + DEBUGASSERT(priv->config != NULL && ptr != NULL); + *ptr = priv->config->frequency; + } + break; + + default: + ret = -ENOTTY; + break; + } + + sem_post(&priv->devsem); + return ret; +} + +/**************************************************************************** + * Name: max11802_poll + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static int max11802_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode; + FAR struct max11802_dev_s *priv; + pollevent_t eventset; + int ndx; + int ret = OK; + int i; + + ivdbg("setup: %d\n", (int)setup); + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max11802_dev_s *)inode->i_private; + + /* Are we setting up the poll? Or tearing it down? */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + if (setup) + { + /* Ignore waits that do not include POLLIN */ + + if ((fds->events & POLLIN) == 0) + { + ret = -EDEADLK; + goto errout; + } + + /* This is a request to set up the poll. Find an available + * slot for the poll structure reference + */ + + for (i = 0; i < CONFIG_MAX11802_NPOLLWAITERS; i++) + { + /* Find an available slot */ + + if (!priv->fds[i]) + { + /* Bind the poll structure and this slot */ + + priv->fds[i] = fds; + fds->priv = &priv->fds[i]; + break; + } + } + + if (i >= CONFIG_MAX11802_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto errout; + } + + /* Should we immediately notify on any of the requested events? */ + + if (priv->penchange) + { + max11802_notify(priv); + } + } + else if (fds->priv) + { + /* This is a request to tear down the poll. */ + + struct pollfd **slot = (struct pollfd **)fds->priv; + DEBUGASSERT(slot != NULL); + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } + +errout: + sem_post(&priv->devsem); + return ret; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: max11802_register + * + * Description: + * Configure the MAX11802 to use the provided SPI device instance. This + * will register the driver as /dev/inputN where N is the minor device + * number + * + * Input Parameters: + * dev - An SPI driver instance + * config - Persistent board configuration data + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int max11802_register(FAR struct spi_dev_s *spi, + FAR struct max11802_config_s *config, int minor) +{ + FAR struct max11802_dev_s *priv; + char devname[DEV_NAMELEN]; +#ifdef CONFIG_MAX11802_MULTIPLE + irqstate_t flags; +#endif + int ret; + + ivdbg("spi: %p minor: %d\n", spi, minor); + + /* Debug-only sanity checks */ + + DEBUGASSERT(spi != NULL && config != NULL && minor >= 0 && minor < 100); + + /* Create and initialize a MAX11802 device driver instance */ + +#ifndef CONFIG_MAX11802_MULTIPLE + priv = &g_max11802; +#else + priv = (FAR struct max11802_dev_s *)kmalloc(sizeof(struct max11802_dev_s)); + if (!priv) + { + idbg("kmalloc(%d) failed\n", sizeof(struct max11802_dev_s)); + return -ENOMEM; + } +#endif + + /* Initialize the MAX11802 device driver instance */ + + memset(priv, 0, sizeof(struct max11802_dev_s)); + 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 */ + + config->clear(config); + config->enable(config, false); + + /* Attach the interrupt handler */ + + ret = config->attach(config, max11802_interrupt); + if (ret < 0) + { + idbg("Failed to attach interrupt\n"); + goto errout_with_priv; + } + + idbg("Mode: %d Bits: 8 Frequency: %d\n", + CONFIG_MAX11802_SPIMODE, CONFIG_MAX11802_FREQUENCY); + + /* Lock the SPI bus so that we have exclusive access */ + + max11802_lock(spi); + + /* Configure the SPI interface */ + + max11802_configspi(spi); + + /* Configure MAX11802 registers */ + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + (void)SPI_SEND(priv->spi, MAX11802_CMD_MODE_WR); + (void)SPI_SEND(priv->spi, MAX11802_MODE); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + (void)SPI_SEND(priv->spi, MAX11802_CMD_AVG_WR); + (void)SPI_SEND(priv->spi, MAX11802_AVG); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + (void)SPI_SEND(priv->spi, MAX11802_CMD_TIMING_WR); + (void)SPI_SEND(priv->spi, MAX11802_TIMING); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + (void)SPI_SEND(priv->spi, MAX11802_CMD_DELAY_WR); + (void)SPI_SEND(priv->spi, MAX11802_DELAY); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + /* Test that the device access was successful. */ + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + (void)SPI_SEND(priv->spi, MAX11802_CMD_MODE_RD); + ret = SPI_SEND(priv->spi, 0); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + /* Unlock the bus */ + max11802_unlock(spi); + + if (ret != MAX11802_MODE) + { + idbg("max11802 mode readback failed: %02x\n", ret); + goto errout_with_priv; + } + + /* Register the device as an input device */ + + (void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor); + ivdbg("Registering %s\n", devname); + + ret = register_driver(devname, &max11802_fops, 0666, priv); + if (ret < 0) + { + idbg("register_driver() failed: %d\n", ret); + goto errout_with_priv; + } + + /* If multiple MAX11802 devices are supported, then we will need to add + * this new instance to a list of device instances so that it can be + * found by the interrupt handler based on the recieved IRQ number. + */ + +#ifdef CONFIG_MAX11802_MULTIPLE + priv->flink = g_max11802list; + g_max11802list = priv; + irqrestore(flags); +#endif + + /* Schedule work to perform the initial sampling and to set the data + * availability conditions. + */ + + ret = work_queue(HPWORK, &priv->work, max11802_worker, priv, 0); + if (ret != 0) + { + idbg("Failed to queue work: %d\n", ret); + goto errout_with_priv; + } + + /* And return success (?) */ + + return OK; + +errout_with_priv: + sem_destroy(&priv->devsem); +#ifdef CONFIG_MAX11802_MULTIPLE + kfree(priv); +#endif + return ret; +} diff --git a/nuttx/drivers/input/max11802.h b/nuttx/drivers/input/max11802.h new file mode 100644 index 0000000000..b6beec0451 --- /dev/null +++ b/nuttx/drivers/input/max11802.h @@ -0,0 +1,167 @@ +/******************************************************************************************** + * drivers/input/max11802.h + * + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Petteri Aimonen + * + * References: + * "Low-Power, Ultra-Small Resistive Touch-Screen Controllers + * with I2C/SPI Interface" Maxim IC, Rev 3, 10/2010 + * + * 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 __DRIVERS_INPUT_MAX11802_H +#define __DRIVERS_INPUT_MAX11802_H + +/******************************************************************************************** + * Included Files + ********************************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +/******************************************************************************************** + * Pre-Processor Definitions + ********************************************************************************************/ +/* Configuration ****************************************************************************/ + +/* MAX11802 Interfaces *********************************************************************/ + +/* LSB of register addresses specifies read (1) or write (0). */ +#define MAX11802_CMD_XPOSITION ((0x52 << 1) | 1) +#define MAX11802_CMD_YPOSITION ((0x54 << 1) | 1) +#define MAX11802_CMD_MEASUREXY (0x70 << 1) +#define MAX11802_CMD_MODE_WR (0x0B << 1) +#define MAX11802_CMD_MODE_RD ((0x0B << 1) | 1) +#define MAX11802_CMD_AVG_WR (0x03 << 1) +#define MAX11802_CMD_TIMING_WR (0x05 << 1) +#define MAX11802_CMD_DELAY_WR (0x06 << 1) + +/* Register values to set */ +#define MAX11802_MODE 0x0E +#define MAX11802_AVG 0x55 +#define MAX11802_TIMING 0x77 +#define MAX11802_DELAY 0x55 + +/* Driver support **************************************************************************/ +/* This format is used to construct the /dev/input[n] device driver path. It + * defined here so that it will be used consistently in all places. + */ + +#define DEV_FORMAT "/dev/input%d" +#define DEV_NAMELEN 16 + +/* Poll the pen position while the pen is down at this rate (50MS): */ + +#define MAX11802_WDOG_DELAY ((50 + (MSEC_PER_TICK-1))/ MSEC_PER_TICK) + +/******************************************************************************************** + * Public Types + ********************************************************************************************/ + +/* This describes the state of one contact */ + +enum max11802_contact_3 +{ + CONTACT_NONE = 0, /* No contact */ + CONTACT_DOWN, /* First contact */ + CONTACT_MOVE, /* Same contact, possibly different position */ + CONTACT_UP, /* Contact lost */ +}; + +/* This structure describes the results of one MAX11802 sample */ + +struct max11802_sample_s +{ + uint8_t id; /* Sampled touch point ID */ + uint8_t contact; /* Contact state (see enum ads7843e_contact_e) */ + bool valid; /* True: x,y contain valid, sampled data */ + uint16_t x; /* Measured X position */ + uint16_t y; /* Measured Y position */ +}; + +/* This structure describes the state of one MAX11802 driver instance */ + +struct max11802_dev_s +{ +#ifdef CONFIG_ADS7843E_MULTIPLE + FAR struct ads7843e_dev_s *flink; /* Supports a singly linked list of drivers */ +#endif + uint8_t nwaiters; /* Number of threads waiting for MAX11802 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 */ + + FAR struct max11802_config_s *config; /* Board configuration data */ + FAR struct spi_dev_s *spi; /* Saved SPI driver instance */ + struct work_s work; /* Supports the interrupt handling "bottom half" */ + struct max11802_sample_s sample; /* Last sampled touch point data */ + WDOG_ID wdog; /* Poll the position while the pen is down */ + + /* The following is a list if poll structures of threads waiting for + * driver events. The 'struct pollfd' reference for each open is also + * retained in the f_priv field of the 'struct file'. + */ + +#ifndef CONFIG_DISABLE_POLL + struct pollfd *fds[CONFIG_ADS7843E_NPOLLWAITERS]; +#endif +}; + +/******************************************************************************************** + * Public Function Prototypes + ********************************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __DRIVERS_INPUT_ADS7843E_H */ diff --git a/nuttx/include/nuttx/compiler.h b/nuttx/include/nuttx/compiler.h index 1e0af43826..bbb23d01d9 100644 --- a/nuttx/include/nuttx/compiler.h +++ b/nuttx/include/nuttx/compiler.h @@ -87,11 +87,16 @@ # define packed_struct __attribute__ ((packed)) -/* GCC does not support the reentrant or naked attributes */ +/* GCC does not support the reentrant attribute */ # define reentrant_function -# define naked_function +/* The naked attribute informs GCC that the programmer will take care of + * the function prolog and epilog. + */ + +# define naked_function __attribute__ ((naked,no_instrument_function)) + /* The inline_function attribute informs GCC that the function should always * be inlined, regardless of the level of optimization. The noinline_function * indicates that the function should never be inlined. diff --git a/nuttx/include/nuttx/input/max11802.h b/nuttx/include/nuttx/input/max11802.h new file mode 100644 index 0000000000..3d03bdd115 --- /dev/null +++ b/nuttx/include/nuttx/input/max11802.h @@ -0,0 +1,175 @@ +/**************************************************************************** + * include/nuttx/input/max11802.h + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Petteri Aimonen + * + * References: + * "Low-Power, Ultra-Small Resistive Touch-Screen Controllers + * with I2C/SPI Interface" Maxim IC, Rev 3, 10/2010 + * + * 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 __INCLUDE_NUTTX_INPUT_MAX11802_H +#define __INCLUDE_NUTTX_INPUT_MAX11802_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include + +#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_MAX11802) + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ +/* SPI Frequency. Default: 100KHz */ + +#ifndef CONFIG_MAX11802_FREQUENCY +# define CONFIG_MAX11802_FREQUENCY 100000 +#endif + +/* Maximum number of threads than can be waiting for POLL events */ + +#ifndef CONFIG_MAX11802_NPOLLWAITERS +# define CONFIG_MAX11802_NPOLLWAITERS 2 +#endif + +#ifndef CONFIG_MAX11802_SPIMODE +# define CONFIG_MAX11802_SPIMODE SPIDEV_MODE0 +#endif + +/* Thresholds */ + +#ifndef CONFIG_MAX11802_THRESHX +# define CONFIG_MAX11802_THRESHX 12 +#endif + +#ifndef CONFIG_MAX11802_THRESHY +# define CONFIG_MAX11802_THRESHY 12 +#endif + +/* Check for some required settings. This can save the user a lot of time + * in getting the right configuration. + */ + +#ifdef CONFIG_DISABLE_SIGNALS +# error "Signals are required. CONFIG_DISABLE_SIGNALS must not be selected." +#endif + +#ifndef CONFIG_SCHED_WORKQUEUE +# error "Work queue support required. CONFIG_SCHED_WORKQUEUE must be selected." +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* A reference to a structure of this type must be passed to the MAX11802 + * driver. This structure provides information about the configuration + * of the MAX11802 and provides some board-specific hooks. + * + * Memory for this structure is provided by the caller. It is not copied + * by the driver and is presumed to persist while the driver is active. The + * memory must be writable because, under certain circumstances, the driver + * may modify frequency or X plate resistance values. + */ + +struct max11802_config_s +{ + /* Device characterization */ + + uint32_t frequency; /* SPI frequency */ + + /* IRQ/GPIO access callbacks. These operations all hidden behind + * callbacks to isolate the MAX11802 driver from differences in GPIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * attach - Attach the MAX11802 interrupt handler to the GPIO interrupt + * enable - Enable or disable the GPIO interrupt + * clear - Acknowledge/clear any pending GPIO interrupt + * pendown - Return the state of the pen down GPIO input + */ + + int (*attach)(FAR struct max11802_config_s *state, xcpt_t isr); + void (*enable)(FAR struct max11802_config_s *state, bool enable); + void (*clear)(FAR struct max11802_config_s *state); + bool (*pendown)(FAR struct max11802_config_s *state); +}; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Name: max11802_register + * + * Description: + * Configure the MAX11802 to use the provided SPI device instance. This + * will register the driver as /dev/inputN where N is the minor device + * number + * + * Input Parameters: + * spi - An SPI driver instance + * config - Persistent board configuration data + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +EXTERN int max11802_register(FAR struct spi_dev_s *spi, + FAR struct max11802_config_s *config, + int minor); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_INPUT && CONFIG_INPUT_MAX11802 */ +#endif /* __INCLUDE_NUTTX_INPUT_MAX11802_H */ From f44266675e1d65d7e479496d837f17b7da1ababf Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 20 Oct 2012 16:07:49 +0000 Subject: [PATCH 007/206] Several bugfixes contributed by Petteri Aimonen git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5238 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/ChangeLog.txt | 11 +++++++++++ NxWidgets/UnitTests/nxwm/Makefile | 4 ++-- NxWidgets/libnxwidgets/Makefile | 4 ++-- NxWidgets/libnxwidgets/src/ccallback.cxx | 3 ++- NxWidgets/libnxwidgets/src/cnxserver.cxx | 2 +- NxWidgets/nxwm/Makefile | 4 ++-- apps/ChangeLog.txt | 5 +++++ apps/examples/nximage/nximage_main.c | 3 ++- apps/examples/nxtext/nxtext_main.c | 2 -- nuttx/ChangeLog | 7 ++++++- nuttx/arch/arm/Kconfig | 11 +++++++++++ nuttx/arch/arm/src/armv7-m/up_hardfault.c | 4 +--- nuttx/drivers/usbdev/pl2303.c | 2 +- nuttx/drivers/usbdev/usbmsc.h | 2 +- nuttx/graphics/nxtk/nxtk_events.c | 24 +++++++++++++++++++++++ nuttx/include/nuttx/usb/cdcacm.h | 2 +- 16 files changed, 72 insertions(+), 18 deletions(-) diff --git a/NxWidgets/ChangeLog.txt b/NxWidgets/ChangeLog.txt index 06709996f9..f4aedd8285 100644 --- a/NxWidgets/ChangeLog.txt +++ b/NxWidgets/ChangeLog.txt @@ -172,3 +172,14 @@ NxWidgets/NxWM unit tests. 1.4 2012-xx-xx Gregory Nutt + +* libnxwidgets/Makefile, NxWidgets/nxwm/Makefile, and + NxWidgets/UnitTests/nxwm/Makefile: Makefile improvements from + submitted by Petteri Aimonen. Other Makefiles in the UnitTests + directory probably also need these changes. +* libnxwidgets/src/ccallback.cxx: Fix misplaced #endif. Provided + by Petteri Aimonen. +* libnxwidgets/src/cnxserver.cxx: Reduce delay to allow NX server + to start. One second was un-necessarily long. Reduced to 50 MS. + Reduction suggested by Petteri Aimonen. + diff --git a/NxWidgets/UnitTests/nxwm/Makefile b/NxWidgets/UnitTests/nxwm/Makefile index 11c670ece3..f84a78bcc4 100644 --- a/NxWidgets/UnitTests/nxwm/Makefile +++ b/NxWidgets/UnitTests/nxwm/Makefile @@ -105,7 +105,7 @@ STACKSIZE = 2048 VPATH = -all: .built +all: chkcxx chklibnxwidgets chklibnxwm .built .PHONY: clean depend context disclean chkcxx chklibnxwidgets chklibnxwm # Object file creation targets @@ -163,7 +163,7 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklibnxwidgets does the work. $(NXWM_LIB): # Just to keep make happy. chklibnxwm does the work. -.built: chkcxx chklibnxwidgets chklibnxwm $(OBJS) $(NXWIDGETS_LIB) +.built: $(OBJS) $(NXWIDGETS_LIB) @( for obj in $(OBJS) ; do \ $(call ARCHIVE, $(BIN), $${obj}); \ done ; ) diff --git a/NxWidgets/libnxwidgets/Makefile b/NxWidgets/libnxwidgets/Makefile index 0afb55e695..92eb877517 100644 --- a/NxWidgets/libnxwidgets/Makefile +++ b/NxWidgets/libnxwidgets/Makefile @@ -92,7 +92,7 @@ CXXFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(NXWIDGETDIR DEPPATH = --dep-path src VPATH = src -all: $(BIN) +all: check_nuttx $(BIN) .PHONY = check_nuttx depend clean distclean export $(AOBJS): %$(OBJEXT): %.S @@ -122,7 +122,7 @@ check_nuttx: fi; \ ) -$(BIN): check_nuttx $(OBJS) +$(BIN): $(OBJS) @( for obj in $(OBJS) ; do \ $(call ARCHIVE, $@, $${obj}); \ done ; ) diff --git a/NxWidgets/libnxwidgets/src/ccallback.cxx b/NxWidgets/libnxwidgets/src/ccallback.cxx index 374502a386..269a5cdb1f 100644 --- a/NxWidgets/libnxwidgets/src/ccallback.cxx +++ b/NxWidgets/libnxwidgets/src/ccallback.cxx @@ -226,6 +226,8 @@ void CCallback::newKeyboardEvent(NXHANDLE hwnd, uint8_t nCh, } } +#endif // CONFIG_NX_KBD + /** * This callback is the response from nx_block (or nxtk_block). Those * blocking interfaces are used to assure that no further messages are @@ -260,4 +262,3 @@ void CCallback::windowBlocked(NXWINDOW hwnd, FAR void *arg1, FAR void *arg2) } #endif -#endif // CONFIG_NX_KBD diff --git a/NxWidgets/libnxwidgets/src/cnxserver.cxx b/NxWidgets/libnxwidgets/src/cnxserver.cxx index 8816c73bc6..4d5a6e6819 100644 --- a/NxWidgets/libnxwidgets/src/cnxserver.cxx +++ b/NxWidgets/libnxwidgets/src/cnxserver.cxx @@ -225,7 +225,7 @@ bool CNxServer::connect(void) // Wait a bit to let the server get started - sleep(1); + usleep(50*1000); // Connect to the server diff --git a/NxWidgets/nxwm/Makefile b/NxWidgets/nxwm/Makefile index 6b60327af5..f26ae03bb8 100644 --- a/NxWidgets/nxwm/Makefile +++ b/NxWidgets/nxwm/Makefile @@ -97,7 +97,7 @@ CXXFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(NXWIDGETDIR DEPPATH = --dep-path src VPATH = src -all: $(BIN) +all: check_nuttx $(BIN) .PHONY = check_nuttx depend clean distclean export $(AOBJS): %$(OBJEXT): %.S @@ -127,7 +127,7 @@ check_nuttx: fi; \ ) -$(BIN): check_nuttx $(OBJS) +$(BIN): $(OBJS) @( for obj in $(OBJS) ; do \ $(call ARCHIVE, $@, $${obj}); \ done ; ) diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index b9ba6ac91b..02843d547a 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -375,3 +375,8 @@ * apps/nshlib/nsh_netcmds.c: The ping command now passes a maximum round trip time to uip_icmpping(). This allows pinging of hosts on complex networks where the ICMP ECHO round trip time may exceed the ping interval. + * apps/examples/nxtext/nxtext_main.c: Fix bad conditional compilation + when CONFIG_NX_KBD is not defined. Submitted by Petteri Aimonen. + * apps/examples/nximage/nximage_main.c: Add a 5 second delay after the + NX logo is presented so that there is time for the image to be verified. + Suggested by Petteri Aimonen. diff --git a/apps/examples/nximage/nximage_main.c b/apps/examples/nximage/nximage_main.c index 729fcc53f4..c432d8a73b 100644 --- a/apps/examples/nximage/nximage_main.c +++ b/apps/examples/nximage/nximage_main.c @@ -263,9 +263,10 @@ int nximage_main(int argc, char *argv[]) } message("nximage_main: Screen resolution (%d,%d)\n", g_nximage.xres, g_nximage.yres); - /* Now, put up the NuttX logo. */ + /* Now, put up the NuttX logo and wait a bit so that it visible. */ nximage_image(g_nximage.hbkgd); + sleep(5); /* Release background */ diff --git a/apps/examples/nxtext/nxtext_main.c b/apps/examples/nxtext/nxtext_main.c index 9a4b8eea49..2a1b503559 100644 --- a/apps/examples/nxtext/nxtext_main.c +++ b/apps/examples/nxtext/nxtext_main.c @@ -96,7 +96,6 @@ * Private Data ****************************************************************************/ -#ifdef CONFIG_NX_KBD static const uint8_t g_pumsg[] = "Pop-Up!"; static const char *g_bgmsg[BGMSG_LINES] = { @@ -125,7 +124,6 @@ static const char *g_bgmsg[BGMSG_LINES] = "I must be gone and live,\n", /* Line 23 */ " or stay and die.\n" /* Line 24 */ }; -#endif /**************************************************************************** * Public Data diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index bfae8e3670..4e799b4a84 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3480,4 +3480,9 @@ * drivers/input/max11802.c/h, and include/nuttx/input max11802.h: Adds support for the Maxim MAX11802 touchscreen controller (contributed by Petteri Aimonen). - + * graphics/nxtk/nxtk_events.c: Missing implementatin of the blocked + method. This is a critical bugfix for graphics support (contributed + by Petteri Aimonen). + * drivers/usbdev/pl2303.c, drivers/usbdev/usbmsc.h, and + include/nuttx/usb/cdcacm.h: USB_CONFIG_ATTR_SELFPOWER vs. + USB_CONFIG_ATT_SELFPOWER (contributed by Petteri Aimonen). \ No newline at end of file diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig index 2a7ea10b59..02a8719943 100644 --- a/nuttx/arch/arm/Kconfig +++ b/nuttx/arch/arm/Kconfig @@ -4,6 +4,8 @@ # if ARCH_ARM +comment "ARM Options" + choice prompt "ARM chip selection" default ARCH_CHIP_STM32 @@ -239,6 +241,15 @@ config ARCH_CALIBRATION watch to measure the 100 second delay then adjust BOARD_LOOPSPERMSEC until the delay actually is 100 seconds. +config DEBUG_HARDFAULT + bool "Verbose Hard-Fault Debug" + default n + depends on DEBUG && (ARCH_CORTEXM3 || ARCH_CORTEXM4) + ---help--- + Enables verbose debug output when a hard fault is occurs. This verbose + output is sometimes helpful when debugging difficult hard fault problems, + but may be more than you typcially want to see. + if ARCH_CHIP_C5471 source arch/arm/src/c5471/Kconfig endif diff --git a/nuttx/arch/arm/src/armv7-m/up_hardfault.c b/nuttx/arch/arm/src/armv7-m/up_hardfault.c index cb3ce9e8a9..c30015ad22 100644 --- a/nuttx/arch/arm/src/armv7-m/up_hardfault.c +++ b/nuttx/arch/arm/src/armv7-m/up_hardfault.c @@ -57,9 +57,7 @@ /* Debug output from this file may interfere with context switching! */ -#undef DEBUG_HARDFAULTS /* Define to debug hard faults */ - -#ifdef DEBUG_HARDFAULTS +#ifdef CONFIG_DEBUG_HARDFAULT # define hfdbg(format, arg...) lldbg(format, ##arg) #else # define hfdbg(x...) diff --git a/nuttx/drivers/usbdev/pl2303.c b/nuttx/drivers/usbdev/pl2303.c index 69bf879656..95f26c1854 100644 --- a/nuttx/drivers/usbdev/pl2303.c +++ b/nuttx/drivers/usbdev/pl2303.c @@ -132,7 +132,7 @@ /* USB Controller */ #ifndef CONFIG_USBDEV_SELFPOWERED -# define SELFPOWERED USB_CONFIG_ATT_SELFPOWER +# define SELFPOWERED USB_CONFIG_ATTR_SELFPOWER #else # define SELFPOWERED (0) #endif diff --git a/nuttx/drivers/usbdev/usbmsc.h b/nuttx/drivers/usbdev/usbmsc.h index 6a5530d9d9..883a499517 100644 --- a/nuttx/drivers/usbdev/usbmsc.h +++ b/nuttx/drivers/usbdev/usbmsc.h @@ -227,7 +227,7 @@ /* USB Controller */ #ifndef CONFIG_USBDEV_SELFPOWERED -# define SELFPOWERED USB_CONFIG_ATT_SELFPOWER +# define SELFPOWERED USB_CONFIG_ATTR_SELFPOWER #else # define SELFPOWERED (0) #endif diff --git a/nuttx/graphics/nxtk/nxtk_events.c b/nuttx/graphics/nxtk/nxtk_events.c index 33c50b7f90..aaec16b5af 100644 --- a/nuttx/graphics/nxtk/nxtk_events.c +++ b/nuttx/graphics/nxtk/nxtk_events.c @@ -76,6 +76,9 @@ static void nxtk_mousein(NXWINDOW hwnd, FAR const struct nxgl_point_s *pos, static void nxtk_kbdin(NXWINDOW hwnd, uint8_t nch, const uint8_t *ch, FAR void *arg); #endif +#ifdef CONFIG_NX_MULTIUSER +static void nxtk_blocked(NXWINDOW hwnd, FAR void *arg1, FAR void *arg2); +#endif /**************************************************************************** * Private Data @@ -95,6 +98,9 @@ const struct nx_callback_s g_nxtkcb = #ifdef CONFIG_NX_KBD , nxtk_kbdin /* kbdin */ #endif +#ifdef CONFIG_NX_MULTIUSER + , nxtk_blocked +#endif }; /**************************************************************************** @@ -292,6 +298,24 @@ static void nxtk_kbdin(NXWINDOW hwnd, uint8_t nch, const uint8_t *ch, } #endif +/**************************************************************************** + * Name: nxtk_blocked + ****************************************************************************/ + +#ifdef CONFIG_NX_MULTIUSER +static void nxtk_blocked(NXWINDOW hwnd, FAR void *arg1, FAR void *arg2) +{ + FAR struct nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)hwnd; + + /* Only the client window gets keyboard input */ + + if (fwnd->fwcb->blocked) + { + fwnd->fwcb->blocked((NXTKWINDOW)fwnd, fwnd->fwarg, arg2); + } +} +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/nuttx/include/nuttx/usb/cdcacm.h b/nuttx/include/nuttx/usb/cdcacm.h index 307f2a5977..1dca050c4b 100644 --- a/nuttx/include/nuttx/usb/cdcacm.h +++ b/nuttx/include/nuttx/usb/cdcacm.h @@ -205,7 +205,7 @@ /* USB Controller */ #ifndef CONFIG_USBDEV_SELFPOWERED -# define SELFPOWERED USB_CONFIG_ATT_SELFPOWER +# define SELFPOWERED USB_CONFIG_ATTR_SELFPOWER #else # define SELFPOWERED (0) #endif From bac5f185593080ba03993b467c6c80200f217837 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 20 Oct 2012 18:56:55 +0000 Subject: [PATCH 008/206] Optimized ARMv7-M memcpy() function from Mike Smith git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5239 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 4 +- .../arm/src/armv7-m/up_fullcontextrestore.S | 0 nuttx/arch/arm/src/armv7-m/up_memcpy.S | 416 ++++++++++++++++++ .../arch/arm/src/armv7-m/up_saveusercontext.S | 0 nuttx/arch/arm/src/armv7-m/up_switchcontext.S | 0 nuttx/arch/arm/src/kinetis/Make.defs | 20 +- nuttx/arch/arm/src/lm3s/Make.defs | 20 +- nuttx/arch/arm/src/lpc17xx/Make.defs | 20 +- nuttx/arch/arm/src/lpc43xx/Make.defs | 4 + nuttx/arch/arm/src/sam3u/Make.defs | 20 +- nuttx/arch/arm/src/stm32/Make.defs | 22 +- 11 files changed, 484 insertions(+), 42 deletions(-) mode change 100755 => 100644 nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S create mode 100644 nuttx/arch/arm/src/armv7-m/up_memcpy.S mode change 100755 => 100644 nuttx/arch/arm/src/armv7-m/up_saveusercontext.S mode change 100755 => 100644 nuttx/arch/arm/src/armv7-m/up_switchcontext.S diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 4e799b4a84..47174f3ba9 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3485,4 +3485,6 @@ by Petteri Aimonen). * drivers/usbdev/pl2303.c, drivers/usbdev/usbmsc.h, and include/nuttx/usb/cdcacm.h: USB_CONFIG_ATTR_SELFPOWER vs. - USB_CONFIG_ATT_SELFPOWER (contributed by Petteri Aimonen). \ No newline at end of file + USB_CONFIG_ATT_SELFPOWER (contributed by Petteri Aimonen). + * arch/arm/src/armv7-m/up_memcpy.S: An optimized memcpy() function for + the ARMv7-M family contributed by Mike Smith. diff --git a/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S b/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S old mode 100755 new mode 100644 diff --git a/nuttx/arch/arm/src/armv7-m/up_memcpy.S b/nuttx/arch/arm/src/armv7-m/up_memcpy.S new file mode 100644 index 0000000000..a154cab614 --- /dev/null +++ b/nuttx/arch/arm/src/armv7-m/up_memcpy.S @@ -0,0 +1,416 @@ +/************************************************************************************ + * nuttx/arch/arm/src/armv7-m/up_memcpy.S + * + * armv7m-optimised memcpy, contributed by Mike Smith. Apparently in the public + * domain and is re-released here under the modified BSD license: + * + * Obtained via a posting on the Stellaris forum: + * http://e2e.ti.com/support/microcontrollers/\ + * stellaris_arm_cortex-m3_microcontroller/f/473/t/44360.aspx + * + * Posted by rocksoft on Jul 24, 2008 10:19 AM + * + * Hi, + * + * I recently finished a "memcpy" replacement and thought it might be useful for + * others... + * + * I've put some instructions and the code here: + * + * http://www.rock-software.net/downloads/memcpy/ + * + * Hope it works for you as well as it did for me. + * + * Liam. + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Global Symbols + ************************************************************************************/ + + .global memcpy + + .syntax unified + .thumb + .cpu cortex-m3 + .file "up_memcpy.S" + +/************************************************************************************ + * .text + ************************************************************************************/ + + .text + +/************************************************************************************ + * Private Constant Data + ************************************************************************************/ + +/* We have 16 possible alignment combinations of src and dst, this jump table + * directs the copy operation + * + * Bits: Src=00, Dst=00 - Long to Long copy + * Bits: Src=00, Dst=01 - Long to Byte before half word + * Bits: Src=00, Dst=10 - Long to Half word + * Bits: Src=00, Dst=11 - Long to Byte before long word + * Bits: Src=01, Dst=00 - Byte before half word to long + * Bits: Src=01, Dst=01 - Byte before half word to byte before half word - + * Same alignment + * Bits: Src=01, Dst=10 - Byte before half word to half word + * Bits: Src=01, Dst=11 - Byte before half word to byte before long word + * Bits: Src=10, Dst=00 - Half word to long word + * Bits: Src=10, Dst=01 - Half word to byte before half word + * Bits: Src=10, Dst=10 - Half word to half word - Same Alignment + * Bits: Src=10, Dst=11 - Half word to byte before long word + * Bits: Src=11, Dst=00 - Byte before long word to long word + * Bits: Src=11, Dst=01 - Byte before long word to byte before half word + * Bits: Src=11, Dst=11 - Byte before long word to half word + * Bits: Src=11, Dst=11 - Byte before long word to Byte before long word - + * Same alignment + */ + +MEM_DataCopyTable: + .byte (MEM_DataCopy0 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy1 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy2 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy3 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy4 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy5 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy6 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy7 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy8 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy9 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy10 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy11 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy12 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy13 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy14 - MEM_DataCopyJump) >> 1 + .byte (MEM_DataCopy15 - MEM_DataCopyJump) >> 1 + + .align 2 + +MEM_LongCopyTable: + .byte (MEM_LongCopyEnd - MEM_LongCopyJump) >> 1 /* 0 bytes left */ + .byte 0 /* 4 bytes left */ + .byte (1 * 10) >> 1 /* 8 bytes left */ + .byte (2 * 10) >> 1 /* 12 bytes left */ + .byte (3 * 10) >> 1 /* 16 bytes left */ + .byte (4 * 10) >> 1 /* 20 bytes left */ + .byte (5 * 10) >> 1 /* 24 bytes left */ + .byte (6 * 10) >> 1 /* 28 bytes left */ + .byte (7 * 10) >> 1 /* 32 bytes left */ + .byte (8 * 10) >> 1 /* 36 bytes left */ + + .align 2 + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +/************************************************************************************ + * Name: memcpy + * + * Description: + * Optimised "general" copy routine + * + * Input Parameters: + * r0 = destination, r1 = source, r2 = length + * + ************************************************************************************/ + + .thumb_func +memcpy: + push {r14} + + /* This allows the inner workings to "assume" a minimum amount of bytes */ + /* Quickly check for very short copies */ + + cmp r2, #4 + blt MEM_DataCopyBytes + + and r14, r0, #3 /* Get destination alignment bits */ + bfi r14, r1, #2, #2 /* Get source alignment bits */ + ldr r3, =MEM_DataCopyTable /* Jump table base */ + tbb [r3, r14] /* Perform jump on src/dst alignment bits */ +MEM_DataCopyJump: + + .align 4 + +/* Bits: Src=01, Dst=01 - Byte before half word to byte before half word - Same alignment + * 3 bytes to read for long word aligning + */ + +MEM_DataCopy5: + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + sub r2, r2, #0x01 + +/* Bits: Src=10, Dst=10 - Half word to half word - Same Alignment + * 2 bytes to read for long word aligning + */ + +MEM_DataCopy10: + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + sub r2, r2, #0x01 + +/* Bits: Src=11, Dst=11 - Byte before long word to Byte before long word - Same alignment + * 1 bytes to read for long word aligning + */ + +MEM_DataCopy15: + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + sub r2, r2, #0x01 + +/* Bits: Src=00, Dst=00 - Long to Long copy */ + +MEM_DataCopy0: + /* Save regs that may be used by memcpy */ + + push {r4-r12} + + /* Check for short word-aligned copy */ + + cmp r2, #0x28 + blt MEM_DataCopy0_2 + + /* Bulk copy loop */ + +MEM_DataCopy0_1: + ldmia r1!, {r3-r12} + stmia r0!, {r3-r12} + sub r2, r2, #0x28 + cmp r2, #0x28 + bge MEM_DataCopy0_1 + + /* Copy remaining long words */ + +MEM_DataCopy0_2: + /* Copy remaining long words */ + + ldr r14, =MEM_LongCopyTable + lsr r11, r2, #0x02 + tbb [r14, r11] + + /* longword copy branch table anchor */ + +MEM_LongCopyJump: + ldr.w r3, [r1], #0x04 /* 4 bytes remain */ + str.w r3, [r0], #0x04 + b MEM_LongCopyEnd + ldmia.w r1!, {r3-r4} /* 8 bytes remain */ + stmia.w r0!, {r3-r4} + b MEM_LongCopyEnd + ldmia.w r1!, {r3-r5} /* 12 bytes remain */ + stmia.w r0!, {r3-r5} + b MEM_LongCopyEnd + ldmia.w r1!, {r3-r6} /* 16 bytes remain */ + stmia.w r0!, {r3-r6} + b MEM_LongCopyEnd + ldmia.w r1!, {r3-r7} /* 20 bytes remain */ + stmia.w r0!, {r3-r7} + b MEM_LongCopyEnd + ldmia.w r1!, {r3-r8} /* 24 bytes remain */ + stmia.w r0!, {r3-r8} + b MEM_LongCopyEnd + ldmia.w r1!, {r3-r9} /* 28 bytes remain */ + stmia.w r0!, {r3-r9} + b MEM_LongCopyEnd + ldmia.w r1!, {r3-r10} /* 32 bytes remain */ + stmia.w r0!, {r3-r10} + b MEM_LongCopyEnd + ldmia.w r1!, {r3-r11} /* 36 bytes remain */ + stmia.w r0!, {r3-r11} + +MEM_LongCopyEnd: + pop {r4-r12} + and r2, r2, #0x03 /* All the longs have been copied */ + + /* Deal with up to 3 remaining bytes */ + +MEM_DataCopyBytes: + /* Deal with up to 3 remaining bytes */ + + cmp r2, #0x00 + it eq + popeq {pc} + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + subs r2, r2, #0x01 + it eq + popeq {pc} + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + subs r2, r2, #0x01 + it eq + popeq {pc} + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + pop {pc} + + .align 4 + +/* Bits: Src=01, Dst=11 - Byte before half word to byte before long word + * 3 bytes to read for long word aligning the source + */ + +MEM_DataCopy7: + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + sub r2, r2, #0x01 + +/* Bits: Src=10, Dst=00 - Half word to long word + * 2 bytes to read for long word aligning the source + */ + +MEM_DataCopy8: + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + sub r2, r2, #0x01 + +/* Bits: Src=11, Dst=01 - Byte before long word to byte before half word + * 1 byte to read for long word aligning the source + */ + +MEM_DataCopy13: + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + sub r2, r2, #0x01 + +/* Bits: Src=00, Dst=10 - Long to Half word */ + +MEM_DataCopy2: + cmp r2, #0x28 + blt MEM_DataCopy2_1 + + /* Save regs */ + + push {r4-r12} + + /* Bulk copy loop */ + +MEM_DataCopy2_2: + ldmia r1!, {r3-r12} + + strh r3, [r0], #0x02 + + lsr r3, r3, #0x10 + bfi r3, r4, #0x10, #0x10 + lsr r4, r4, #0x10 + bfi r4, r5, #0x10, #0x10 + lsr r5, r5, #0x10 + bfi r5, r6, #0x10, #0x10 + lsr r6, r6, #0x10 + bfi r6, r7, #0x10, #0x10 + lsr r7, r7, #0x10 + bfi r7, r8, #0x10, #0x10 + lsr r8, r8, #0x10 + bfi r8, r9, #0x10, #0x10 + lsr r9, r9, #0x10 + bfi r9, r10, #0x10, #0x10 + lsr r10, r10, #0x10 + bfi r10, r11, #0x10, #0x10 + lsr r11, r11, #0x10 + bfi r11, r12, #0x10, #0x10 + stmia r0!, {r3-r11} + lsr r12, r12, #0x10 + strh r12, [r0], #0x02 + + sub r2, r2, #0x28 + cmp r2, #0x28 + bge MEM_DataCopy2_2 + pop {r4-r12} + +MEM_DataCopy2_1: /* Read longs and write 2 x half words */ + cmp r2, #4 + blt MEM_DataCopyBytes + ldr r3, [r1], #0x04 + strh r3, [r0], #0x02 + lsr r3, r3, #0x10 + strh r3, [r0], #0x02 + sub r2, r2, #0x04 + b MEM_DataCopy2 + +/* Bits: Src=01, Dst=00 - Byte before half word to long + * Bits: Src=01, Dst=10 - Byte before half word to half word + * 3 bytes to read for long word aligning the source + */ + +MEM_DataCopy4: +MEM_DataCopy6: + /* Read B and write B */ + + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + sub r2, r2, #0x01 + +/* Bits: Src=10, Dst=01 - Half word to byte before half word + * Bits: Src=10, Dst=11 - Half word to byte before long word + * 2 bytes to read for long word aligning the source + */ + +MEM_DataCopy9: +MEM_DataCopy11: + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + sub r2, r2, #0x01 + +/* Bits: Src=11, Dst=00 -chm Byte before long word to long word + * Bits: Src=11, Dst=11 - Byte before long word to half word + * 1 byte to read for long word aligning the source + */ + +MEM_DataCopy12: +MEM_DataCopy14: + /* Read B and write B */ + + ldrb r3, [r1], #0x01 + strb r3, [r0], #0x01 + sub r2, r2, #0x01 + +/* Bits: Src=00, Dst=01 - Long to Byte before half word + * Bits: Src=00, Dst=11 - Long to Byte before long word + */ + +MEM_DataCopy1: /* Read longs, write B->H->B */ +MEM_DataCopy3: + cmp r2, #4 + blt MEM_DataCopyBytes + ldr r3, [r1], #0x04 + strb r3, [r0], #0x01 + lsr r3, r3, #0x08 + strh r3, [r0], #0x02 + lsr r3, r3, #0x10 + strb r3, [r0], #0x01 + sub r2, r2, #0x04 + b MEM_DataCopy3 + + .size memcpy, .-memcpy + .end diff --git a/nuttx/arch/arm/src/armv7-m/up_saveusercontext.S b/nuttx/arch/arm/src/armv7-m/up_saveusercontext.S old mode 100755 new mode 100644 diff --git a/nuttx/arch/arm/src/armv7-m/up_switchcontext.S b/nuttx/arch/arm/src/armv7-m/up_switchcontext.S old mode 100755 new mode 100644 diff --git a/nuttx/arch/arm/src/kinetis/Make.defs b/nuttx/arch/arm/src/kinetis/Make.defs index 22d066828b..710db4d01e 100644 --- a/nuttx/arch/arm/src/kinetis/Make.defs +++ b/nuttx/arch/arm/src/kinetis/Make.defs @@ -41,12 +41,16 @@ HEAD_ASRC = kinetis_vectors.S CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ - up_createstack.c up_mdelay.c up_udelay.c up_exit.c up_initialize.c \ - up_memfault.c up_initialstate.c up_interruptcontext.c \ - up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \ - up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \ - up_releasepending.c up_sigdeliver.c up_unblocktask.c up_usestack.c \ - up_doirq.c up_hardfault.c up_svcall.c up_checkstack.c + up_createstack.c up_mdelay.c up_udelay.c up_exit.c up_initialize.c \ + up_memfault.c up_initialstate.c up_interruptcontext.c \ + up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \ + up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \ + up_releasepending.c up_sigdeliver.c up_unblocktask.c up_usestack.c \ + up_doirq.c up_hardfault.c up_svcall.c up_checkstack.c + +ifeq ($(CONFIG_ARCH_MEMCPY),y) +CMN_ASRCS += up_memcpy.S +endif ifeq ($(CONFIG_NET),y) ifneq ($(CONFIG_KINETIS_ENET),y) @@ -58,8 +62,8 @@ endif CHIP_ASRCS = CHIP_CSRCS = kinetis_clockconfig.c kinetis_clrpend.c kinetis_idle.c \ - kinetis_irq.c kinetis_lowputc.c kinetis_pin.c kinetis_pingpio.c \ - kinetis_serial.c kinetis_start.c kinetis_timerisr.c kinetis_wdog.c + kinetis_irq.c kinetis_lowputc.c kinetis_pin.c kinetis_pingpio.c \ + kinetis_serial.c kinetis_start.c kinetis_timerisr.c kinetis_wdog.c # Configuration-dependent Kinetis files diff --git a/nuttx/arch/arm/src/lm3s/Make.defs b/nuttx/arch/arm/src/lm3s/Make.defs index 574526f181..ea4eda5833 100644 --- a/nuttx/arch/arm/src/lm3s/Make.defs +++ b/nuttx/arch/arm/src/lm3s/Make.defs @@ -37,17 +37,21 @@ HEAD_ASRC = lm3s_vectors.S CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ - up_createstack.c up_mdelay.c up_udelay.c up_exit.c \ - up_idle.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_createstack.c up_mdelay.c up_udelay.c up_exit.c \ + up_idle.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 + +ifeq ($(CONFIG_ARCH_MEMCPY),y) +CMN_ASRCS += up_memcpy.S +endif CHIP_ASRCS = CHIP_CSRCS = lm3s_start.c lm3s_syscontrol.c lm3s_irq.c \ - lm3s_gpio.c lm3s_gpioirq.c lm3s_timerisr.c lm3s_lowputc.c \ - lm3s_serial.c lm3s_ssi.c lm3s_dumpgpio.c + lm3s_gpio.c lm3s_gpioirq.c lm3s_timerisr.c lm3s_lowputc.c \ + lm3s_serial.c lm3s_ssi.c lm3s_dumpgpio.c ifdef CONFIG_NET CHIP_CSRCS += lm3s_ethernet.c diff --git a/nuttx/arch/arm/src/lpc17xx/Make.defs b/nuttx/arch/arm/src/lpc17xx/Make.defs index 56aef87fd0..baf2a45098 100644 --- a/nuttx/arch/arm/src/lpc17xx/Make.defs +++ b/nuttx/arch/arm/src/lpc17xx/Make.defs @@ -41,12 +41,16 @@ HEAD_ASRC = lpc17_vectors.S CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \ - up_mdelay.c up_udelay.c up_exit.c up_initialize.c up_memfault.c \ - up_initialstate.c up_interruptcontext.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_checkstack.c + up_mdelay.c up_udelay.c up_exit.c up_initialize.c up_memfault.c \ + up_initialstate.c up_interruptcontext.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_checkstack.c + +ifeq ($(CONFIG_ARCH_MEMCPY),y) +CMN_ASRCS += up_memcpy.S +endif ifeq ($(CONFIG_NET),y) ifneq ($(CONFIG_LPC17_ETHERNET),y) @@ -58,8 +62,8 @@ endif CHIP_ASRCS = CHIP_CSRCS = lpc17_allocateheap.c lpc17_clockconfig.c lpc17_clrpend.c \ - lpc17_gpio.c lpc17_i2c.c lpc17_idle.c lpc17_irq.c lpc17_lowputc.c \ - lpc17_serial.c lpc17_spi.c lpc17_ssp.c lpc17_start.c lpc17_timerisr.c + lpc17_gpio.c lpc17_i2c.c lpc17_idle.c lpc17_irq.c lpc17_lowputc.c \ + lpc17_serial.c lpc17_spi.c lpc17_ssp.c lpc17_start.c lpc17_timerisr.c # Configuration-dependent LPC17xx files diff --git a/nuttx/arch/arm/src/lpc43xx/Make.defs b/nuttx/arch/arm/src/lpc43xx/Make.defs index cc8de3b321..0444a68fdc 100644 --- a/nuttx/arch/arm/src/lpc43xx/Make.defs +++ b/nuttx/arch/arm/src/lpc43xx/Make.defs @@ -49,6 +49,10 @@ CMN_ASRCS += up_exception.S CMN_CSRCS += up_vectors.c endif +ifeq ($(CONFIG_ARCH_MEMCPY),y) +CMN_ASRCS += up_memcpy.S +endif + ifeq ($(CONFIG_DEBUG_STACK),y) CMN_CSRCS += up_checkstack.c endif diff --git a/nuttx/arch/arm/src/sam3u/Make.defs b/nuttx/arch/arm/src/sam3u/Make.defs index b3bdac72b4..b93e5bff73 100644 --- a/nuttx/arch/arm/src/sam3u/Make.defs +++ b/nuttx/arch/arm/src/sam3u/Make.defs @@ -41,15 +41,19 @@ HEAD_ASRC = sam3u_vectors.S CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \ - up_mdelay.c up_udelay.c up_exit.c up_idle.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_mdelay.c up_udelay.c up_exit.c up_idle.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 # Configuration-dependent common files +ifeq ($(CONFIG_ARCH_MEMCPY),y) +CMN_ASRCS += up_memcpy.S +endif + ifeq ($(CONFIG_NUTTX_KERNEL),y) CHIP_CSRCS += up_mpu.c endif @@ -58,8 +62,8 @@ endif CHIP_ASRCS = CHIP_CSRCS = sam3u_allocateheap.c sam3u_clockconfig.c sam3u_gpioirq.c \ - sam3u_irq.c sam3u_lowputc.c sam3u_pio.c sam3u_serial.c \ - sam3u_start.c sam3u_timerisr.c + sam3u_irq.c sam3u_lowputc.c sam3u_pio.c sam3u_serial.c \ + sam3u_start.c sam3u_timerisr.c # Configuration-dependent SAM3U files diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs index ef14b48c14..d516c0b4fc 100644 --- a/nuttx/arch/arm/src/stm32/Make.defs +++ b/nuttx/arch/arm/src/stm32/Make.defs @@ -41,18 +41,22 @@ endif CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \ - up_createstack.c up_mdelay.c up_udelay.c up_exit.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_systemreset.c \ - up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c up_svcall.c + up_createstack.c up_mdelay.c up_udelay.c up_exit.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_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 CMN_CSRCS += up_vectors.c endif +ifeq ($(CONFIG_ARCH_MEMCPY),y) +CMN_ASRCS += up_memcpy.S +endif + ifeq ($(CONFIG_DEBUG_STACK),y) CMN_CSRCS += up_checkstack.c endif @@ -63,9 +67,9 @@ endif CHIP_ASRCS = CHIP_CSRCS = stm32_allocateheap.c stm32_start.c stm32_rcc.c stm32_lse.c \ - stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c stm32_irq.c \ - stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c \ - stm32_spi.c stm32_sdio.c stm32_tim.c stm32_i2c.c stm32_waste.c + stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c stm32_irq.c \ + stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c \ + stm32_spi.c stm32_sdio.c stm32_tim.c stm32_i2c.c stm32_waste.c ifeq ($(CONFIG_USBDEV),y) ifeq ($(CONFIG_STM32_USB),y) From 80c9bda9005d750ad8c5e7825dbd35f593c58895 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 20 Oct 2012 20:59:44 +0000 Subject: [PATCH 009/206] Add Daniel Vik's optimized memcpy as a configuration option git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5240 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/COPYING | 29 +++ nuttx/ChangeLog | 3 + nuttx/lib/Kconfig | 61 ++++++ nuttx/lib/string/Make.defs | 10 +- nuttx/lib/string/lib_vikmemcpy.c | 348 +++++++++++++++++++++++++++++++ 5 files changed, 450 insertions(+), 1 deletion(-) create mode 100644 nuttx/lib/string/lib_vikmemcpy.c diff --git a/nuttx/COPYING b/nuttx/COPYING index 863b81a2fc..1956fb6c72 100644 --- a/nuttx/COPYING +++ b/nuttx/COPYING @@ -163,6 +163,35 @@ dtoa(): "This product includes software developed by the University of California, Berkeley and its contributors." +lib/string/lib_vikmemcpy.c +^^^^^^^^^^^^^^^^^^^^^^^^^^ + + If you enable CONFIG_MEMCPY_VIK, then you will build with the optimized + version of memcpy from Daniel Vik. Licensing information for that version + of memcpy() follows: + + Copyright (C) 1999-2010 Daniel Vik + + This software is provided 'as-is', without any express or implied + warranty. In no event will the authors be held liable for any + damages arising from the use of this software. + Permission is granted to anyone to use this software for any + purpose, including commercial applications, and to alter it and + redistribute it freely, subject to the following restrictions: + + 1. The origin of this software must not be misrepresented; you + must not claim that you wrote the original software. If you + use this software in a product, an acknowledgment in the + use this software in a product, an acknowledgment in the + product documentation would be appreciated but is not + required. + + 2. Altered source versions must be plainly marked as such, and + must not be misrepresented as being the original software. + + 3. This notice may not be removed or altered from any source + distribution. + Documents/rss.gif ^^^^^^^^^^^^^^^^^ diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 47174f3ba9..313d8865f7 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3488,3 +3488,6 @@ USB_CONFIG_ATT_SELFPOWER (contributed by Petteri Aimonen). * arch/arm/src/armv7-m/up_memcpy.S: An optimized memcpy() function for the ARMv7-M family contributed by Mike Smith. + * lib/strings/lib_vikmemcpy.c: As an option, the larger but faster + implemementation of memcpy from Daniel Vik is now available (this is + from http://www.danielvik.com/2010/02/fast-memcpy-in-c.html). \ No newline at end of file diff --git a/nuttx/lib/Kconfig b/nuttx/lib/Kconfig index 69a55d09cf..b3f743db28 100644 --- a/nuttx/lib/Kconfig +++ b/nuttx/lib/Kconfig @@ -155,40 +155,101 @@ if ARCH_OPTIMIZED_FUNCTIONS config ARCH_MEMCPY bool "memcpy" default n + ---help--- + Select this option if the architecture provides an optimized version + of memcpy(). + +config MEMCPY_VIK + bool "Vik memcpy" + default n + depends on !ARCH_MEMCPY + ---help--- + Select this option to use the optimized memcpy() function by Daniel Vik. + See licensing information in the top-level COPYING file. + +if MEMCPY_VIK +config MEMCPY_PRE_INC_PTRS + bool "Pre-increment pointers" + default n + ---help--- + Use pre-increment of pointers. Default is post increment of pointers. + +config MEMCPY_INDEXED_COPY + bool "Array indexing" + default y + ---help--- + Copying data using array indexing. Using this option, disables the + MEMCPY_PRE_INC_PTRS option. + +config MEMCPY_64BIT + bool "64-bit memcpy" + default n + ---help--- + Compiles memcpy for 64 bit architectures + +endif config ARCH_MEMCMP bool "memcmp" default n + ---help--- + Select this option if the architecture provides an optimized version + of memcmp(). config ARCH_MEMMOVE bool "memmove" default n + ---help--- + Select this option if the architecture provides an optimized version + of memmove(). config ARCH_MEMSET bool "memset" default n + ---help--- + Select this option if the architecture provides an optimized version + of memset(). config ARCH_STRCMP bool "strcmp" default n + ---help--- + Select this option if the architecture provides an optimized version + of strcmp(). config ARCH_STRCPY bool "strcpy" default n + ---help--- + Select this option if the architecture provides an optimized version + of strcpy(). config ARCH_STRNCPY bool "strncpy" default n + ---help--- + Select this option if the architecture provides an optimized version + of strncpy(). config ARCH_STRLEN bool "strlen" default n + ---help--- + Select this option if the architecture provides an optimized version + of strlen(). config ARCH_STRNLEN bool "strlen" default n + ---help--- + Select this option if the architecture provides an optimized version + of strnlen(). config ARCH_BZERO bool "bzero" default n + ---help--- + Select this option if the architecture provides an optimized version + of bzero(). + endif diff --git a/nuttx/lib/string/Make.defs b/nuttx/lib/string/Make.defs index 6b21c7f146..16add6e89e 100644 --- a/nuttx/lib/string/Make.defs +++ b/nuttx/lib/string/Make.defs @@ -36,7 +36,7 @@ # Add the string C files to the build CSRCS += lib_checkbase.c lib_isbasedigit.c lib_memset.c lib_memchr.c \ - lib_memccpy.c lib_memcpy.c lib_memcmp.c lib_memmove.c lib_skipspace.c \ + lib_memccpy.c lib_memcmp.c lib_memmove.c lib_skipspace.c \ lib_strcasecmp.c lib_strcat.c lib_strchr.c lib_strcpy.c lib_strcmp.c \ lib_strcspn.c lib_strdup.c lib_strerror.c lib_strlen.c lib_strnlen.c \ lib_strncasecmp.c lib_strncat.c lib_strncmp.c lib_strncpy.c \ @@ -44,6 +44,14 @@ CSRCS += lib_checkbase.c lib_isbasedigit.c lib_memset.c lib_memchr.c \ lib_strspn.c lib_strstr.c lib_strtok.c lib_strtokr.c lib_strtol.c \ lib_strtoll.c lib_strtoul.c lib_strtoull.c lib_strtod.c +ifneq ($(CONFIG_ARCH_MEMCPY),y) +ifeq ($(CONFIG_MEMCPY_VIK),y) +CSRCS += lib_vikmemcpy.c +else +CSRCS += lib_memccpy.c +endif +endif + # Add the string directory to the build DEPPATH += --dep-path string diff --git a/nuttx/lib/string/lib_vikmemcpy.c b/nuttx/lib/string/lib_vikmemcpy.c new file mode 100644 index 0000000000..b50942aaa1 --- /dev/null +++ b/nuttx/lib/string/lib_vikmemcpy.c @@ -0,0 +1,348 @@ +/**************************************************************************** + * File: lib/string/lib_vikmemcpy.c + * + * This is version of the optimized memcpy by Daniel Vik, adapted to the + * NuttX environment. + * + * Copyright (C) 1999-2010 Daniel Vik + * + * Adaptations include: + * - File name change + * - Use of types defined in stdint.h + * - Integration with the NuttX configuration system + * - Other cosmetic changes for consistency with NuttX coding standards + * + * This software is provided 'as-is', without any express or implied + * warranty. In no event will the authors be held liable for any + * damages arising from the use of this software. + * Permission is granted to anyone to use this software for any + * purpose, including commercial applications, and to alter it and + * redistribute it freely, subject to the following restrictions: + * + * 1. The origin of this software must not be misrepresented; you + * must not claim that you wrote the original software. If you + * use this software in a product, an acknowledgment in the + * use this software in a product, an acknowledgment in the + * product documentation would be appreciated but is not + * required. + * + * 2. Altered source versions must be plainly marked as such, and + * must not be misrepresented as being the original software. + * + * 3. This notice may not be removed or altered from any source + * distribution. + * + * Description: Implementation of the standard library function memcpy. + * This implementation of memcpy() is ANSI-C89 compatible. + * + * The following configuration options can be set: + * + * CONFIG_ENDIAN_BIG + * Uses processor with big endian addressing. Default is little endian. + * + * CONFIG_MEMCPY_PRE_INC_PTRS + * Use pre increment of pointers. Default is post increment of pointers. + * + * CONFIG_MEMCPY_INDEXED_COPY + * Copying data using array indexing. Using this option, disables the + * CONFIG_MEMCPY_PRE_INC_PTRS option. + * + * CONFIG_MEMCPY_64BIT - Compiles memcpy for 64 bit architectures + * + ****************************************************************************/ + +/**************************************************************************** + * Configuration definitions. + ****************************************************************************/ + +#define CONFIG_MEMCPY_INDEXED_COPY + +/******************************************************************** + * Included Files + *******************************************************************/ + +#include +#include + +#include +#include +#include + +/******************************************************************** + * Pre-processor Definitions + *******************************************************************/ + +/* Can't support CONFIG_MEMCPY_64BIT if the platform does not have 64-bit + * integer types. + */ + +#ifndef CONFIG_HAVE_LONG_LONG +# undef CONFIG_MEMCPY_64BIT +#endif + +/* Remove definitions when CONFIG_MEMCPY_INDEXED_COPY is defined */ + +#if defined (CONFIG_MEMCPY_INDEXED_COPY) +# if defined (CONFIG_MEMCPY_PRE_INC_PTRS) +# undef CONFIG_MEMCPY_PRE_INC_PTRS +# endif /* CONFIG_MEMCPY_PRE_INC_PTRS */ +#endif /* CONFIG_MEMCPY_INDEXED_COPY */ + +/* Definitions for pre and post increment of pointers */ + +#if defined (CONFIG_MEMCPY_PRE_INC_PTRS) + +# define START_VAL(x) (x)-- +# define INC_VAL(x) *++(x) +# define CAST_TO_U8(p, o) ((uint8_t*)p + o + TYPE_WIDTH) +# define WHILE_DEST_BREAK (TYPE_WIDTH - 1) +# define PRE_LOOP_ADJUST - (TYPE_WIDTH - 1) +# define PRE_SWITCH_ADJUST + 1 + +#else /* CONFIG_MEMCPY_PRE_INC_PTRS */ + +# define START_VAL(x) +# define INC_VAL(x) *(x)++ +# define CAST_TO_U8(p, o) ((uint8_t*)p + o) +# define WHILE_DEST_BREAK 0 +# define PRE_LOOP_ADJUST +# define PRE_SWITCH_ADJUST + +#endif /* CONFIG_MEMCPY_PRE_INC_PTRS */ + +/* Definitions for endian-ness */ + +#ifdef CONFIG_ENDIAN_BIG + +# define SHL << +# define SHR >> + +#else /* CONFIG_ENDIAN_BIG */ + +# define SHL >> +# define SHR << + +#endif /* CONFIG_ENDIAN_BIG */ + +/******************************************************************** + * Macros for copying words of different alignment. + * Uses incremening pointers. + *******************************************************************/ + +#define CP_INCR() \ +{ \ + INC_VAL(dstN) = INC_VAL(srcN); \ +} + +#define CP_INCR_SH(shl, shr) \ +{ \ + dstWord = srcWord SHL shl; \ + srcWord = INC_VAL(srcN); \ + dstWord |= srcWord SHR shr; \ + INC_VAL(dstN) = dstWord; \ +} + +/******************************************************************** + * Macros for copying words of different alignment. + * Uses array indexes. + *******************************************************************/ + +#define CP_INDEX(idx) \ +{ \ + dstN[idx] = srcN[idx]; \ +} + +#define CP_INDEX_SH(x, shl, shr) \ +{ \ + dstWord = srcWord SHL shl; \ + srcWord = srcN[x]; \ + dstWord |= srcWord SHR shr; \ + dstN[x] = dstWord; \ +} + +/******************************************************************** + * Macros for copying words of different alignment. + * Uses incremening pointers or array indexes depending on + * configuration. + *******************************************************************/ + +#if defined (CONFIG_MEMCPY_INDEXED_COPY) + +# define CP(idx) CP_INDEX(idx) +# define CP_SH(idx, shl, shr) CP_INDEX_SH(idx, shl, shr) + +# define INC_INDEX(p, o) ((p) += (o)) + +#else /* CONFIG_MEMCPY_INDEXED_COPY */ + +# define CP(idx) CP_INCR() +# define CP_SH(idx, shl, shr) CP_INCR_SH(shl, shr) + +# define INC_INDEX(p, o) + +#endif /* CONFIG_MEMCPY_INDEXED_COPY */ + +#define COPY_REMAINING(count) \ +{ \ + START_VAL(dst8); \ + START_VAL(src8); \ + \ + switch (count) \ + { \ + case 7: INC_VAL(dst8) = INC_VAL(src8); \ + case 6: INC_VAL(dst8) = INC_VAL(src8); \ + case 5: INC_VAL(dst8) = INC_VAL(src8); \ + case 4: INC_VAL(dst8) = INC_VAL(src8); \ + case 3: INC_VAL(dst8) = INC_VAL(src8); \ + case 2: INC_VAL(dst8) = INC_VAL(src8); \ + case 1: INC_VAL(dst8) = INC_VAL(src8); \ + case 0: \ + default: break; \ + } \ +} + +#define COPY_NO_SHIFT() \ +{ \ + UIntN* dstN = (UIntN*)(dst8 PRE_LOOP_ADJUST); \ + UIntN* srcN = (UIntN*)(src8 PRE_LOOP_ADJUST); \ + size_t length = count / TYPE_WIDTH; \ + \ + while (length & 7) \ + { \ + CP_INCR(); \ + length--; \ + } \ + \ + length /= 8; \ + \ + while (length--) \ + { \ + CP(0); \ + CP(1); \ + CP(2); \ + CP(3); \ + CP(4); \ + CP(5); \ + CP(6); \ + CP(7); \ + \ + INC_INDEX(dstN, 8); \ + INC_INDEX(srcN, 8); \ + } \ + \ + src8 = CAST_TO_U8(srcN, 0); \ + dst8 = CAST_TO_U8(dstN, 0); \ + \ + COPY_REMAINING(count & (TYPE_WIDTH - 1)); \ + \ + return dest; \ +} + +#define COPY_SHIFT(shift) \ +{ \ + UIntN* dstN = (UIntN*)((((UIntN)dst8) PRE_LOOP_ADJUST) & \ + ~(TYPE_WIDTH - 1)); \ + UIntN* srcN = (UIntN*)((((UIntN)src8) PRE_LOOP_ADJUST) & \ + ~(TYPE_WIDTH - 1)); \ + size_t length = count / TYPE_WIDTH; \ + UIntN srcWord = INC_VAL(srcN); \ + UIntN dstWord; \ + \ + while (length & 7) \ + { \ + CP_INCR_SH(8 * shift, 8 * (TYPE_WIDTH - shift)); \ + length--; \ + } \ + \ + length /= 8; \ + \ + while (length--) \ + { \ + CP_SH(0, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ + CP_SH(1, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ + CP_SH(2, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ + CP_SH(3, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ + CP_SH(4, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ + CP_SH(5, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ + CP_SH(6, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ + CP_SH(7, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ + \ + INC_INDEX(dstN, 8); \ + INC_INDEX(srcN, 8); \ + } \ + \ + src8 = CAST_TO_U8(srcN, (shift - TYPE_WIDTH)); \ + dst8 = CAST_TO_U8(dstN, 0); \ + \ + COPY_REMAINING(count & (TYPE_WIDTH - 1)); \ + \ + return dest; \ +} + +/******************************************************************** + * Type Definitions + *******************************************************************/ + +#ifdef CONFIG_MEMCPY_64BIT +typedef uint64_t UIntN; +# define TYPE_WIDTH 8L +#else +typedef uint32_t UIntN; +# define TYPE_WIDTH 4L +#endif + +/******************************************************************** + * Public Functions + *******************************************************************/ +/******************************************************************** + * Name: memcpy + * + * Description: + * Copies count bytes from src to dest. No overlap check is performed. + * + * Input Parameters: + * dest - pointer to destination buffer + * src - pointer to source buffer + * count - number of bytes to copy + * + * Returned Value: + * A pointer to destination buffer + * + *******************************************************************/ + +void *memcpy(void *dest, const void *src, size_t count) +{ + uint8_t *dst8 = (uint8_t*)dest; + uint8_t *src8 = (uint8_t*)src; + + if (count < 8) + { + COPY_REMAINING(count); + return dest; + } + + START_VAL(dst8); + START_VAL(src8); + + while (((UIntN)dst8 & (TYPE_WIDTH - 1)) != WHILE_DEST_BREAK) + { + INC_VAL(dst8) = INC_VAL(src8); + count--; + } + + switch ((((UIntN)src8) PRE_SWITCH_ADJUST) & (TYPE_WIDTH - 1)) + { + case 0: COPY_NO_SHIFT(); break; + case 1: COPY_SHIFT(1); break; + case 2: COPY_SHIFT(2); break; + case 3: COPY_SHIFT(3); break; +#if TYPE_WIDTH > 4 + case 4: COPY_SHIFT(4); break; + case 5: COPY_SHIFT(5); break; + case 6: COPY_SHIFT(6); break; + case 7: COPY_SHIFT(7); break; +#endif + } + + return dest; +} From 4de5307aa30ec5e348a8e9002d96fa0901cb2aea Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 20 Oct 2012 21:42:19 +0000 Subject: [PATCH 010/206] Update documentation for recently added configuration options git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5241 42af7a65-404d-4744-a932-0658087f49c3 --- apps/netutils/resolv/Kconfig | 6 ++-- apps/nshlib/README.txt | 4 +++ nuttx/Documentation/NuttShell.html | 8 +++++ nuttx/Documentation/NuttxPortingGuide.html | 34 ++++++++++++++++++++++ nuttx/configs/README.txt | 21 +++++++++++++ 5 files changed, 70 insertions(+), 3 deletions(-) diff --git a/apps/netutils/resolv/Kconfig b/apps/netutils/resolv/Kconfig index a8e79d6c1f..07a0fd4bca 100644 --- a/apps/netutils/resolv/Kconfig +++ b/apps/netutils/resolv/Kconfig @@ -21,6 +21,6 @@ config NET_RESOLV_MAXRESPONSE default 96 depends on NETUTILS_RESOLV ---help--- - This setting determines the maximum size of DHCP response message that - can be received. The default is 96 but may need to be larger on enterprise - networks (perhaps 176). + This setting determines the maximum size of response message that can be + received by the DNS resolver. The default is 96 but may need to be larger on + enterprise networks (perhaps 176). diff --git a/apps/nshlib/README.txt b/apps/nshlib/README.txt index 0f6aee759b..9f4a88e3e4 100644 --- a/apps/nshlib/README.txt +++ b/apps/nshlib/README.txt @@ -1084,6 +1084,10 @@ NSH-Specific Configuration Settings Set if your ethernet hardware has no built-in MAC address. If set, a bogus MAC will be assigned. + * CONFIG_NSH_MAX_ROUNDTRIP + This is the maximum round trip for a response to a ICMP ECHO request. + It is in units of deciseconds. The default is 20 (2 seconds). + If you use DHCPC, then some special configuration network options are required. These include: diff --git a/nuttx/Documentation/NuttShell.html b/nuttx/Documentation/NuttShell.html index bcf62a5a91..ad204f5dc9 100644 --- a/nuttx/Documentation/NuttShell.html +++ b/nuttx/Documentation/NuttShell.html @@ -2559,6 +2559,13 @@ nsh> If set, a bogus MAC will be assigned. + + CONFIG_NSH_MAX_ROUNDTRIP + + This is the maximum round trip for a response to a ICMP ECHO request. + It is in units of deciseconds. The default is 20 (2 seconds). + +

@@ -3537,6 +3544,7 @@ mount -t vfat /dev/ram1 /tmp

  • CONFIG_NSH_IOBUFFER_SIZE
  • CONFIG_NSH_IPADDR
  • CONFIG_NSH_LINELEN
  • +
  • CONFIG_NSH_MAX_ROUNDTRIP
  • CONFIG_NSH_NESTDEPTH
  • CONFIG_NSH_NETMASK
  • CONFIG_NSH_NOMAC
  • diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index bf2a0cc4f5..a16032db57 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -4445,6 +4445,35 @@ build CONFIG_ARCH_BZERO

    +

  • + If CONFIG_ARCH_MEMCPY is not selected, then you make also select Daniel + Vik's optimized implementation of memcpy(): +

    +
    • + CONFIG_MEMCPY_VIK: + Select this option to use the optimized memcpy() function by Daniel Vik. + See licensing information in the top-level COPYING file. + Default: n. +
    + +

    + And if CONFIG_MEMCPY_VIK, the following tuning options are available: +

    +
    • + CONFIG_MEMCPY_PRE_INC_PTRS: + Use pre-increment of pointers. + Default is post increment of pointers. +
    • +
    • + CONFIG_MEMCPY_INDEXED_COPY + Copying data using array indexing. + Using this option, disables the CONFIG_MEMCPY_PRE_INC_PTRS option. +
    • +
    • + CONFIG_MEMCPY_64BIT: + Compiles memcpy for 64 bit architectures +
    +
  • The architecture may provide custom versions of certain standard header files: @@ -5180,6 +5209,11 @@ build

  • CONFIG_NET_RESOLV_ENTRIES: Number of resolver entries
  • +
  • + CONFIG_NET_RESOLV_MAXRESPONSE: + This setting determines the maximum size of response message that can be received by the DNS resolver. + The default is 96 but may need to be larger on enterprise networks (perhaps 176). +
  • THTTPD

    diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index e6bde645d1..cc65540d7f 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -621,6 +621,23 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_ARCH_STRNCPY, CONFIG_ARCH_STRLEN, CONFIG_ARCH_STRNLEN CONFIG_ARCH_BZERO + If CONFIG_ARCH_MEMCPY is not selected, then you make also select Daniel + Vik's optimized implementation of memcpy(): + + CONFIG_MEMCPY_VIK - Select this option to use the optimized memcpy() + function by Daniel Vik. See licensing information in the top-level + COPYING file. Default: n + + And if CONFIG_MEMCPY_VIK, the following tuning options are available: + + CONFIG_MEMCPY_PRE_INC_PTRS - Use pre-increment of pointers. Default is + post increment of pointers. + + CONFIG_MEMCPY_INDEXED_COPY - Copying data using array indexing. Using + this option, disables the CONFIG_MEMCPY_PRE_INC_PTRS option. + + CONFIG_MEMCPY_64BIT - Compiles memcpy for 64 bit architectures + The architecture may provide custom versions of certain standard header files: @@ -1078,6 +1095,10 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries + CONFIG_NET_RESOLV_MAXRESPONSE - This setting determines the maximum + size of response message that can be received by the DNS resolver. + The default is 96 but may need to be larger on enterprise networks + (perhaps 176). THTTPD From f16ae329fdcd533adc29e035e2184918b3862612 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 21 Oct 2012 00:41:44 +0000 Subject: [PATCH 011/206] Add a versin of memset() optimized for speed git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5242 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 +- nuttx/Documentation/NuttShell.html | 2 +- nuttx/Documentation/NuttxPortingGuide.html | 23 ++++-- nuttx/configs/README.txt | 6 ++ nuttx/lib/Kconfig | 37 ++++++---- nuttx/lib/string/lib_memset.c | 84 ++++++++++++++++++++++ 6 files changed, 134 insertions(+), 23 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 313d8865f7..82a4fd0926 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3490,4 +3490,7 @@ the ARMv7-M family contributed by Mike Smith. * lib/strings/lib_vikmemcpy.c: As an option, the larger but faster implemementation of memcpy from Daniel Vik is now available (this is - from http://www.danielvik.com/2010/02/fast-memcpy-in-c.html). \ No newline at end of file + from http://www.danielvik.com/2010/02/fast-memcpy-in-c.html). + * lib/strings/lib_memset.c: CONFIG_MEMSET_OPTSPEED will select a + version of memset() optimized for speed. By default, memset() is + optimized for size. diff --git a/nuttx/Documentation/NuttShell.html b/nuttx/Documentation/NuttShell.html index ad204f5dc9..78a5651074 100644 --- a/nuttx/Documentation/NuttShell.html +++ b/nuttx/Documentation/NuttShell.html @@ -8,7 +8,7 @@

    NuttShell (NSH)

    -

    Last Updated: August 28, 2012

    +

    Last Updated: October 20, 2012

    diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index a16032db57..e43ca8a2fa 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -12,7 +12,7 @@

    NuttX RTOS Porting Guide

    -

    Last Updated: August 28, 2012

    +

    Last Updated: October 20, 2012

    @@ -4449,12 +4449,12 @@ build If CONFIG_ARCH_MEMCPY is not selected, then you make also select Daniel Vik's optimized implementation of memcpy():

    -
    • - CONFIG_MEMCPY_VIK: - Select this option to use the optimized memcpy() function by Daniel Vik. - See licensing information in the top-level COPYING file. - Default: n. -
    +
    • + CONFIG_MEMCPY_VIK: + Select this option to use the optimized memcpy() function by Daniel Vik. + See licensing information in the top-level COPYING file. + Default: n. +

    And if CONFIG_MEMCPY_VIK, the following tuning options are available: @@ -4474,6 +4474,15 @@ build Compiles memcpy for 64 bit architectures +

  • + If CONFIG_ARCH_MEMSET is not selected, then the following option is also available: +

    +
    • + CONFIG_MEMSET_OPTSPEED: + Select this option to use a version of memset() optimized for speed. + Default: memset() is optimized for size. +
    +
  • The architecture may provide custom versions of certain standard header files: diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index cc65540d7f..0bb531d67a 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -638,6 +638,12 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_MEMCPY_64BIT - Compiles memcpy for 64 bit architectures + If CONFIG_ARCH_MEMSET is not selected, then the following option is + also available: + + CONFIG_MEMSET_OPTSPEED - Select this option to use a version of memcpy() + optimized for speed. Default: memcpy() is optimized for size. + The architecture may provide custom versions of certain standard header files: diff --git a/nuttx/lib/Kconfig b/nuttx/lib/Kconfig index b3f743db28..0f25c89238 100644 --- a/nuttx/lib/Kconfig +++ b/nuttx/lib/Kconfig @@ -153,19 +153,20 @@ config ARCH_OPTIMIZED_FUNCTIONS if ARCH_OPTIMIZED_FUNCTIONS config ARCH_MEMCPY - bool "memcpy" + bool "memcpy()" default n ---help--- Select this option if the architecture provides an optimized version of memcpy(). config MEMCPY_VIK - bool "Vik memcpy" + bool "Vik memcpy()" default n depends on !ARCH_MEMCPY ---help--- - Select this option to use the optimized memcpy() function by Daniel Vik. - See licensing information in the top-level COPYING file. + Select this option to use the optimized memcpy() function by Daniel Vik. + Select this option to option for speed at the expense of increased size. + See licensing information in the top-level COPYING file. if MEMCPY_VIK config MEMCPY_PRE_INC_PTRS @@ -182,50 +183,58 @@ config MEMCPY_INDEXED_COPY MEMCPY_PRE_INC_PTRS option. config MEMCPY_64BIT - bool "64-bit memcpy" + bool "64-bit memcpy()" default n ---help--- - Compiles memcpy for 64 bit architectures + Compiles memcpy() for 64 bit architectures endif config ARCH_MEMCMP - bool "memcmp" + bool "memcmp()" default n ---help--- Select this option if the architecture provides an optimized version of memcmp(). config ARCH_MEMMOVE - bool "memmove" + bool "memmove()" default n ---help--- Select this option if the architecture provides an optimized version of memmove(). config ARCH_MEMSET - bool "memset" + bool "memset()" default n ---help--- Select this option if the architecture provides an optimized version of memset(). +config MEMSET_OPTSPEED + bool "Optimize memset() for speed" + default n + depends on !ARCH_MEMSET + ---help--- + Select this option to use a version of memcpy() optimized for speed. + Default: memcpy() is optimized for size. + config ARCH_STRCMP - bool "strcmp" + bool "strcmp()" default n ---help--- Select this option if the architecture provides an optimized version of strcmp(). config ARCH_STRCPY - bool "strcpy" + bool "strcpy()" default n ---help--- Select this option if the architecture provides an optimized version of strcpy(). config ARCH_STRNCPY - bool "strncpy" + bool "strncpy()" default n ---help--- Select this option if the architecture provides an optimized version @@ -239,14 +248,14 @@ config ARCH_STRLEN of strlen(). config ARCH_STRNLEN - bool "strlen" + bool "strlen()" default n ---help--- Select this option if the architecture provides an optimized version of strnlen(). config ARCH_BZERO - bool "bzero" + bool "bzero()" default n ---help--- Select this option if the architecture provides an optimized version diff --git a/nuttx/lib/string/lib_memset.c b/nuttx/lib/string/lib_memset.c index 916351b974..c910d2ce04 100644 --- a/nuttx/lib/string/lib_memset.c +++ b/nuttx/lib/string/lib_memset.c @@ -42,8 +42,12 @@ ************************************************************/ #include + #include + +#include #include +#include /************************************************************ * Global Functions @@ -52,8 +56,88 @@ #ifndef CONFIG_ARCH_MEMSET void *memset(void *s, int c, size_t n) { +#ifdef CONFIG_MEMSET_OPTSPEED + /* This version is optimized for speed (you could do better + * still by exploiting processor caching or memory burst + * knowledge. 64-bit support might improve performance as + * well. + */ + + uintptr_t addr = (uintptr_t)s; + uint16_t val16 = ((uint16_t)c << 8) | (uint16_t)c; + uint32_t val32 = ((uint32_t)val16 << 16) | (uint32_t)val16; + + /* Make sure that there is something to be cleared */ + + if (n > 0) + { + /* Align to a 16-bit boundary */ + + if ((addr & 1) != 0) + { + *(uint8_t*)addr = (uint8_t)c; + addr += 1; + n -= 1; + } + + /* Check if there are at least 16-bits left to be zeroed */ + + if (n >= 2) + { + /* Align to a 32-bit boundary (we know that the destination + * address is already aligned to at least a 16-bit boundary). + */ + + if ((addr & 3) != 0) + { + *(uint16_t*)addr = val16; + addr += 2; + n -= 2; + } + + /* Loop while there are at least 32-bits left to be zeroed */ + + while (n >= 4) + { + *(uint32_t*)addr = val32; + addr += 4; + n -= 4; + } + } + + /* We may get here under the following conditions: + * + * n = 0, addr may or may not be aligned + * n = 1, addr may or may not be aligned + * n = 2, addr is aligned to a 32-bit boundary + * n = 3, addr is aligned to a 32-bit boundary + */ + + switch (n) + { + default: + case 0: + DEBUGASSERT(n == 0); + break; + + case 2: + *(uint16_t*)addr = val16; + break; + + case 3: + *(uint16_t*)addr = val16; + addr += 2; + case 1: + *(uint8_t*)addr = (uint8_t)c; + break; + } + } +#else + /* This version is optimized for size */ + unsigned char *p = (unsigned char*)s; while (n-- > 0) *p++ = c; +#endif return s; } #endif From d24bf915745de8e2c99e565c94d59a64ba24648c Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 21 Oct 2012 01:31:56 +0000 Subject: [PATCH 012/206] Optimized memset() can be configured to do 64-bit stores git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5243 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/Documentation/NuttxPortingGuide.html | 12 +++- nuttx/configs/README.txt | 7 +- nuttx/lib/Kconfig | 7 ++ nuttx/lib/string/lib_memmove.c | 13 ++-- nuttx/lib/string/lib_memset.c | 80 ++++++++++++++++++---- 6 files changed, 100 insertions(+), 21 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 82a4fd0926..44f38ee10a 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3494,3 +3494,5 @@ * lib/strings/lib_memset.c: CONFIG_MEMSET_OPTSPEED will select a version of memset() optimized for speed. By default, memset() is optimized for size. + * lib/strings/lib_memset.c: CONFIG_MEMSET_64BIT will perform 64-bit + aligned memset() operations. diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index e43ca8a2fa..08c6534cb4 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -4457,7 +4457,7 @@ build

  • - And if CONFIG_MEMCPY_VIK, the following tuning options are available: + And if CONFIG_MEMCPY_VIK is selected, the following tuning options are available:

    • CONFIG_MEMCPY_PRE_INC_PTRS: @@ -4471,7 +4471,7 @@ build
    • CONFIG_MEMCPY_64BIT: - Compiles memcpy for 64 bit architectures + Compiles memcpy() for 64 bit architectures

  • @@ -4483,6 +4483,14 @@ build Default: memset() is optimized for size.
  • +

    + And if CONFIG_MEMSET_OPTSPEED is selected, the following tuning option is available: +

    +
    • + CONFIG_MEMSET_64BIT: + Compiles memset() for 64 bit architectures +
    +
  • The architecture may provide custom versions of certain standard header files: diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 0bb531d67a..9714b0228c 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -628,7 +628,7 @@ defconfig -- This is a configuration file similar to the Linux function by Daniel Vik. See licensing information in the top-level COPYING file. Default: n - And if CONFIG_MEMCPY_VIK, the following tuning options are available: + And if CONFIG_MEMCPY_VIK is selected, the following tuning options are available: CONFIG_MEMCPY_PRE_INC_PTRS - Use pre-increment of pointers. Default is post increment of pointers. @@ -644,6 +644,11 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_MEMSET_OPTSPEED - Select this option to use a version of memcpy() optimized for speed. Default: memcpy() is optimized for size. + And if CONFIG_MEMSET_OPTSPEED is selected, the following tuning option is + available: + + CONFIG_MEMSET_64BIT - Compiles memset() for 64 bit architectures + The architecture may provide custom versions of certain standard header files: diff --git a/nuttx/lib/Kconfig b/nuttx/lib/Kconfig index 0f25c89238..80c584ce92 100644 --- a/nuttx/lib/Kconfig +++ b/nuttx/lib/Kconfig @@ -219,6 +219,13 @@ config MEMSET_OPTSPEED Select this option to use a version of memcpy() optimized for speed. Default: memcpy() is optimized for size. +config MEMSET_64BIT + bool "64-bit memset()" + default n + depends on MEMSET_OPTSPEED + ---help--- + Compiles memset() for 64 bit architectures + config ARCH_STRCMP bool "strcmp()" default n diff --git a/nuttx/lib/string/lib_memmove.c b/nuttx/lib/string/lib_memmove.c index ecaeb54cf2..85cb79e174 100644 --- a/nuttx/lib/string/lib_memmove.c +++ b/nuttx/lib/string/lib_memmove.c @@ -56,17 +56,22 @@ void *memmove(void *dest, const void *src, size_t count) if (dest <= src) { tmp = (char*) dest; - s = (char*) src; + s = (char*) src; while (count--) - *tmp++ = *s++; + { + *tmp++ = *s++; + } } else { tmp = (char*) dest + count; - s = (char*) src + count; + s = (char*) src + count; while (count--) - *--tmp = *--s; + { + *--tmp = *--s; + } } + return dest; } #endif diff --git a/nuttx/lib/string/lib_memset.c b/nuttx/lib/string/lib_memset.c index c910d2ce04..2828f1ff86 100644 --- a/nuttx/lib/string/lib_memset.c +++ b/nuttx/lib/string/lib_memset.c @@ -1,4 +1,5 @@ -/************************************************************ + +/**************************************************************************** * lib/string/lib_memset.c * * Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved. @@ -31,15 +32,12 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * - ************************************************************/ + ****************************************************************************/ -/************************************************************ - * Compilation Switches - ************************************************************/ -/************************************************************ +/**************************************************************************** * Included Files - ************************************************************/ + ****************************************************************************/ #include @@ -49,9 +47,21 @@ #include #include -/************************************************************ +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Can't support CONFIG_MEMSET_64BIT if the platform does not have 64-bit + * integer types. + */ + +#ifndef CONFIG_HAVE_LONG_LONG +# undef CONFIG_MEMSET_64BIT +#endif + +/**************************************************************************** * Global Functions - ************************************************************/ + ****************************************************************************/ #ifndef CONFIG_ARCH_MEMSET void *memset(void *s, int c, size_t n) @@ -59,13 +69,15 @@ void *memset(void *s, int c, size_t n) #ifdef CONFIG_MEMSET_OPTSPEED /* This version is optimized for speed (you could do better * still by exploiting processor caching or memory burst - * knowledge. 64-bit support might improve performance as - * well. + * knowledge.) */ uintptr_t addr = (uintptr_t)s; - uint16_t val16 = ((uint16_t)c << 8) | (uint16_t)c; - uint32_t val32 = ((uint32_t)val16 << 16) | (uint32_t)val16; + uint16_t val16 = ((uint16_t)c << 8) | (uint16_t)c; + uint32_t val32 = ((uint32_t)val16 << 16) | (uint32_t)val16; +#ifdef CONFIG_MEMSET_64BIT + uint64_t val64 = ((uint64_t)val32 << 32) | (uint64_t)val32; +#endif /* Make sure that there is something to be cleared */ @@ -95,6 +107,7 @@ void *memset(void *s, int c, size_t n) n -= 2; } +#ifndef CONFIG_MEMSET_64BIT /* Loop while there are at least 32-bits left to be zeroed */ while (n >= 4) @@ -103,12 +116,51 @@ void *memset(void *s, int c, size_t n) addr += 4; n -= 4; } +#else + /* Align to a 32-bit boundary */ + + if (n >= 4) + { + /* Align to a 64-bit boundary (we know that the destination + * address is already aligned to at least a 32-bit boundary). + */ + + if ((addr & 7) != 0) + { + *(uint32_t*)addr = val32; + addr += 4; + n -= 4; + } + + /* Loop while there are at least 64-bits left to be zeroed */ + + while (n >= 8) + { + *(uint64_t*)addr = val64; + addr += 8; + n -= 8; + } + } +#endif } +#ifdef CONFIG_MEMSET_64BIT + /* We may get here with n in the range 0..7. If n >= 4, then we should + * have 64-bit alignment. + */ + + if (n >= 4) + { + *(uint32_t*)addr = val32; + addr += 4; + n -= 4; + } +#endif + /* We may get here under the following conditions: * * n = 0, addr may or may not be aligned - * n = 1, addr may or may not be aligned + * n = 1, addr is aligned to at least a 16-bit boundary * n = 2, addr is aligned to a 32-bit boundary * n = 3, addr is aligned to a 32-bit boundary */ From d59b634a70f7c02b7db95ef1ccbc5030ec280d7c Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 21 Oct 2012 01:34:37 +0000 Subject: [PATCH 013/206] Optimized memset() can be configured to do 64-bit stores git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5244 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/lib/string/lib_memset.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nuttx/lib/string/lib_memset.c b/nuttx/lib/string/lib_memset.c index 2828f1ff86..902a040c58 100644 --- a/nuttx/lib/string/lib_memset.c +++ b/nuttx/lib/string/lib_memset.c @@ -117,7 +117,7 @@ void *memset(void *s, int c, size_t n) n -= 4; } #else - /* Align to a 32-bit boundary */ + /* Check if there are at least 32-bits left to be zeroed */ if (n >= 4) { From 479687966353b92216e1d3eaf35f83a2b4660f21 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 21 Oct 2012 05:38:24 +0000 Subject: [PATCH 014/206] Minor tweaks to memset git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5245 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Documentation/NuttxPortingGuide.html | 1 + nuttx/configs/README.txt | 11 +++-- nuttx/lib/Kconfig | 10 +++-- nuttx/lib/string/lib_memset.c | 49 ++++++++++------------ 4 files changed, 35 insertions(+), 36 deletions(-) diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index 08c6534cb4..d8ccfc3404 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -4452,6 +4452,7 @@ build

    • CONFIG_MEMCPY_VIK: Select this option to use the optimized memcpy() function by Daniel Vik. + Select this option for improved performance at the expense of increased size. See licensing information in the top-level COPYING file. Default: n.
    diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 9714b0228c..c7f3db0e7b 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -625,8 +625,9 @@ defconfig -- This is a configuration file similar to the Linux Vik's optimized implementation of memcpy(): CONFIG_MEMCPY_VIK - Select this option to use the optimized memcpy() - function by Daniel Vik. See licensing information in the top-level - COPYING file. Default: n + function by Daniel Vik. Select this option for improved performance + at the expense of increased size. See licensing information in the + top-level COPYING file. Default: n And if CONFIG_MEMCPY_VIK is selected, the following tuning options are available: @@ -636,7 +637,8 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_MEMCPY_INDEXED_COPY - Copying data using array indexing. Using this option, disables the CONFIG_MEMCPY_PRE_INC_PTRS option. - CONFIG_MEMCPY_64BIT - Compiles memcpy for 64 bit architectures + CONFIG_MEMCPY_64BIT - Compiles memcpy for architectures that suppport + 64-bit operations efficiently. If CONFIG_ARCH_MEMSET is not selected, then the following option is also available: @@ -647,7 +649,8 @@ defconfig -- This is a configuration file similar to the Linux And if CONFIG_MEMSET_OPTSPEED is selected, the following tuning option is available: - CONFIG_MEMSET_64BIT - Compiles memset() for 64 bit architectures + CONFIG_MEMSET_64BIT - Compiles memset() for architectures that suppport + 64-bit operations efficiently. The architecture may provide custom versions of certain standard header files: diff --git a/nuttx/lib/Kconfig b/nuttx/lib/Kconfig index 80c584ce92..ddd5e2dde5 100644 --- a/nuttx/lib/Kconfig +++ b/nuttx/lib/Kconfig @@ -165,8 +165,8 @@ config MEMCPY_VIK depends on !ARCH_MEMCPY ---help--- Select this option to use the optimized memcpy() function by Daniel Vik. - Select this option to option for speed at the expense of increased size. - See licensing information in the top-level COPYING file. + Select this option for improved performance at the expense of increased + size. See licensing information in the top-level COPYING file. if MEMCPY_VIK config MEMCPY_PRE_INC_PTRS @@ -186,7 +186,8 @@ config MEMCPY_64BIT bool "64-bit memcpy()" default n ---help--- - Compiles memcpy() for 64 bit architectures + Compiles memcpy() for architectures that suppport 64-bit operations + efficiently. endif @@ -224,7 +225,8 @@ config MEMSET_64BIT default n depends on MEMSET_OPTSPEED ---help--- - Compiles memset() for 64 bit architectures + Compiles memset() for architectures that suppport 64-bit operations + efficiently. config ARCH_STRCMP bool "strcmp()" diff --git a/nuttx/lib/string/lib_memset.c b/nuttx/lib/string/lib_memset.c index 902a040c58..31c386e928 100644 --- a/nuttx/lib/string/lib_memset.c +++ b/nuttx/lib/string/lib_memset.c @@ -92,7 +92,7 @@ void *memset(void *s, int c, size_t n) n -= 1; } - /* Check if there are at least 16-bits left to be zeroed */ + /* Check if there are at least 16-bits left to be written */ if (n >= 2) { @@ -108,7 +108,7 @@ void *memset(void *s, int c, size_t n) } #ifndef CONFIG_MEMSET_64BIT - /* Loop while there are at least 32-bits left to be zeroed */ + /* Loop while there are at least 32-bits left to be written */ while (n >= 4) { @@ -117,7 +117,7 @@ void *memset(void *s, int c, size_t n) n -= 4; } #else - /* Check if there are at least 32-bits left to be zeroed */ + /* Check if there are at least 32-bits left to be written */ if (n >= 4) { @@ -132,7 +132,7 @@ void *memset(void *s, int c, size_t n) n -= 4; } - /* Loop while there are at least 64-bits left to be zeroed */ + /* Loop while there are at least 64-bits left to be written */ while (n >= 8) { @@ -145,16 +145,16 @@ void *memset(void *s, int c, size_t n) } #ifdef CONFIG_MEMSET_64BIT - /* We may get here with n in the range 0..7. If n >= 4, then we should - * have 64-bit alignment. - */ + /* We may get here with n in the range 0..7. If n >= 4, then we should + * have 64-bit alignment. + */ - if (n >= 4) - { - *(uint32_t*)addr = val32; - addr += 4; - n -= 4; - } + if (n >= 4) + { + *(uint32_t*)addr = val32; + addr += 4; + n -= 4; + } #endif /* We may get here under the following conditions: @@ -165,23 +165,16 @@ void *memset(void *s, int c, size_t n) * n = 3, addr is aligned to a 32-bit boundary */ - switch (n) + if (n >= 2) { - default: - case 0: - DEBUGASSERT(n == 0); - break; + *(uint16_t*)addr = val16; + addr += 2; + n -= 2; + } - case 2: - *(uint16_t*)addr = val16; - break; - - case 3: - *(uint16_t*)addr = val16; - addr += 2; - case 1: - *(uint8_t*)addr = (uint8_t)c; - break; + if (n >= 1) + { + *(uint8_t*)addr = (uint8_t)c; } } #else From 6ea7967d8acf16b2cc2849929faf63f902b208ef Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 21 Oct 2012 15:47:34 +0000 Subject: [PATCH 015/206] Kconfig changes to get a clean STM32 ADC example build git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5246 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Kconfig | 28 +++++++-- nuttx/arch/arm/src/stm32/Kconfig | 90 +++++++++++++++++++++++++++++ nuttx/configs/shenzhou/README.txt | 28 +++++++++ nuttx/configs/shenzhou/src/up_adc.c | 13 ++++- nuttx/lib/string/Make.defs | 2 +- 5 files changed, 154 insertions(+), 7 deletions(-) diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 0fe6eb0f7c..325759b41a 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -244,17 +244,24 @@ config DEBUG_ENABLE comment "Subsystem Debug Options" +config DEBUG_MM + bool "Enable Memory Manager Debug Output" + default n + ---help--- + Enable memory management debug output (disabled by default) + config DEBUG_SCHED bool "Enable Scheduler Debug Output" default n ---help--- Enable OS debug output (disabled by default) -config DEBUG_MM - bool "Enable Memory Manager Debug Output" +config DEBUG_PAGING + bool "Enable Demand Paging Debug Output" default n + depends on PAGING ---help--- - Enable memory management debug output (disabled by default) + Enable demand paging debug output (disabled by default) config DEBUG_NET bool "Enable Network Debug Output" @@ -311,6 +318,13 @@ config DEBUG_INPUT Enable low level debug output from the input device drivers such as mice and touchscreens (disabled by default) +config DEBUG_ANALOG + bool "Enable Analog Device Debug Output" + default n + ---help--- + Enable low level debug output from the analog device drivers such as + A/D and D/A converters (disabled by default) + config DEBUG_I2C bool "Enable I2C Debug Output" default n @@ -325,12 +339,18 @@ config DEBUG_SPI ---help--- Enable I2C driver debug output (disabled by default) +config DEBUG_DMA + bool "Enable DMA Debug Output" + default n + ---help--- + Enable DMA-releated debug output (disabled by default) + config DEBUG_WATCHDOG bool "Enable Watchdog Timer Debug Output" default n depends on WATCHDOG ---help--- - Enable watchdog timer debug output (disabled by default) + Enable watchdog timer debug output (disabled by default) endif diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 2f91002360..c9482b6d65 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -909,16 +909,22 @@ choice config STM32_TIM1_ADC1 bool "TIM1 ADC channel 1" + depends on STM32_ADC1 + select HAVE_ADC1_TIMER ---help--- Reserve TIM1 to trigger ADC1 config STM32_TIM1_ADC2 bool "TIM1 ADC channel 2" + depends on STM32_ADC2 + select HAVE_ADC2_TIMER ---help--- Reserve TIM1 to trigger ADC2 config STM32_TIM1_ADC3 bool "TIM1 ADC channel 3" + depends on STM32_ADC3 + select HAVE_ADC3_TIMER ---help--- Reserve TIM1 to trigger ADC3 @@ -945,16 +951,22 @@ choice config STM32_TIM2_ADC1 bool "TIM2 ADC channel 1" + depends on STM32_ADC1 + select HAVE_ADC1_TIMER ---help--- Reserve TIM2 to trigger ADC1 config STM32_TIM2_ADC2 bool "TIM2 ADC channel 2" + depends on STM32_ADC2 + select HAVE_ADC2_TIMER ---help--- Reserve TIM2 to trigger ADC2 config STM32_TIM2_ADC3 bool "TIM2 ADC channel 3" + depends on STM32_ADC3 + select HAVE_ADC3_TIMER ---help--- Reserve TIM2 to trigger ADC3 @@ -981,16 +993,22 @@ choice config STM32_TIM3_ADC1 bool "TIM3 ADC channel 1" + depends on STM32_ADC1 + select HAVE_ADC1_TIMER ---help--- Reserve TIM3 to trigger ADC1 config STM32_TIM3_ADC2 bool "TIM3 ADC channel 2" + depends on STM32_ADC2 + select HAVE_ADC2_TIMER ---help--- Reserve TIM3 to trigger ADC2 config STM32_TIM3_ADC3 bool "TIM3 ADC channel 3" + depends on STM32_ADC3 + select HAVE_ADC3_TIMER ---help--- Reserve TIM3 to trigger ADC3 @@ -1017,16 +1035,22 @@ choice config STM32_TIM4_ADC1 bool "TIM4 ADC channel 1" + depends on STM32_ADC1 + select HAVE_ADC1_TIMER ---help--- Reserve TIM4 to trigger ADC1 config STM32_TIM4_ADC2 bool "TIM4 ADC channel 2" + depends on STM32_ADC2 + select HAVE_ADC2_TIMER ---help--- Reserve TIM4 to trigger ADC2 config STM32_TIM4_ADC3 bool "TIM4 ADC channel 3" + depends on STM32_ADC3 + select HAVE_ADC3_TIMER ---help--- Reserve TIM4 to trigger ADC3 @@ -1053,16 +1077,22 @@ choice config STM32_TIM5_ADC1 bool "TIM5 ADC channel 1" + depends on STM32_ADC1 + select HAVE_ADC1_TIMER ---help--- Reserve TIM5 to trigger ADC1 config STM32_TIM5_ADC2 bool "TIM5 ADC channel 2" + depends on STM32_ADC2 + select HAVE_ADC2_TIMER ---help--- Reserve TIM5 to trigger ADC2 config STM32_TIM5_ADC3 bool "TIM5 ADC channel 3" + depends on STM32_ADC3 + select HAVE_ADC3_TIMER ---help--- Reserve TIM5 to trigger ADC3 @@ -1089,21 +1119,81 @@ choice config STM32_TIM8_ADC1 bool "TIM8 ADC channel 1" + depends on STM32_ADC1 + select HAVE_ADC1_TIMER ---help--- Reserve TIM8 to trigger ADC1 config STM32_TIM8_ADC2 bool "TIM8 ADC channel 2" + depends on STM32_ADC2 + select HAVE_ADC2_TIMER ---help--- Reserve TIM8 to trigger ADC2 config STM32_TIM8_ADC3 bool "TIM8 ADC channel 3" + depends on STM32_ADC3 + select HAVE_ADC3_TIMER ---help--- Reserve TIM8 to trigger ADC3 endchoice +config HAVE_ADC1_TIMER + bool + +config HAVE_ADC2_TIMER + bool + +config HAVE_ADC3_TIMER + bool + +config STM32_ADC1_SAMPLE_FREQUENCY + int "ADC1 Sampling Frequency" + default 100 + depends on HAVE_ADC1_TIMER + ---help--- + ADC1 sampling frequency. Default: 100Hz + +config STM32_ADC1_TIMTRIG + int "ADC1 Timer Trigger" + default 0 + range 0 4 + depends on HAVE_ADC1_TIMER + ---help--- + Values 0:CC1 1:CC2 2:CC3 3:CC4 4:TRGO + +config STM32_ADC2_SAMPLE_FREQUENCY + int "ADC2 Sampling Frequency" + default 100 + depends on HAVE_ADC2_TIMER + ---help--- + ADC2 sampling frequency. Default: 100Hz + +config STM32_ADC2_TIMTRIG + int "ADC2 Timer Trigger" + default 0 + range 0 4 + depends on HAVE_ADC2_TIMER + ---help--- + Values 0:CC1 1:CC2 2:CC3 3:CC4 4:TRGO + +config STM32_ADC3_SAMPLE_FREQUENCY + int "ADC3 Sampling Frequency" + default 100 + depends on HAVE_ADC3_TIMER + ---help--- + ADC3 sampling frequency. Default: 100Hz + +config STM32_ADC3_TIMTRIG + int "ADC3 Timer Trigger" + default 0 + range 0 4 + depends on HAVE_ADC3_TIMER + ---help--- + Values 0:CC1 1:CC2 2:CC3 3:CC4 4:TRGO + config STM32_TIM1_DAC bool "TIM1 DAC" default n diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index 7bf67710da..a60019a279 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -772,6 +772,34 @@ Where is one of the following: before the networking finally gives up and decides that no network is available. + 2. Enabling the ADC example: + + The only internal signal for ADC testing is the potentiometer input: + + ADC1_IN10(PC0) Potentiometer + + External signals are also available on CON5 CN14: + + ADC_IN8 (PB0) CON5 CN14 Pin2 + ADC_IN9 (PB1) CON5 CN14 Pin1 + + The signal selection is hard-coded in configs/shenzhou/src/up_adc.c: The + potentiometer input (only) is selected. + + These selections will enable sampling the potentiometer input at 100Hz using + Timer 1: + + CONFIG_ANALOG=y : Enable analog device support + CONFIG_ADC=y : Enable generic ADC driver support + CONFIG_ADC_DMA=n : ADC DMA is not supported + CONFIG_STM32_ADC1=y : Enable ADC 1 + CONFIG_STM32_TIM1=y : Enable Timer 1 + CONFIG_STM32_TIM1_ADC=y : Use Timer 1 for ADC + CONFIG_STM32_TIM1_ADC1=y : Allocate Timer 1 to ADC 1 + CONFIG_STM32_ADC1_SAMPLE_FREQUENCY=100 : Set sampling frequency to 100Hz + CONFIG_STM32_ADC1_TIMTRIG=0 : Trigger on timer output 0 + CONFIG_EXAMPLES_ADC=y : Enable the apps/examples/adc built-in + nxwm ---- This is a special configuration setup for the NxWM window manager diff --git a/nuttx/configs/shenzhou/src/up_adc.c b/nuttx/configs/shenzhou/src/up_adc.c index fb20c6940a..e62289ca64 100644 --- a/nuttx/configs/shenzhou/src/up_adc.c +++ b/nuttx/configs/shenzhou/src/up_adc.c @@ -85,12 +85,21 @@ * Private Data ************************************************************************************/ -/* Identifying number of each ADC channel: Variable Resistor */ +/* Identifying number of each ADC channel. The only internal signal for ADC testing + * is the potentiometer input: + * + * ADC1_IN10(PC0) Potentiometer + * + * External signals are also available on CON5 CN14: + * + * ADC_IN8 (PB0) CON5 CN14 Pin2 + * ADC_IN9 (PB1) CON5 CN14 Pin1 + */ #ifdef CONFIG_STM32_ADC1 static const uint8_t g_chanlist[ADC1_NCHANNELS] = {10}; //{10, 8, 9}; -/* Configurations of pins used byte each ADC channels */ +/* Configurations of pins used by each ADC channel */ static const uint32_t g_pinlist[ADC1_NCHANNELS] = {GPIO_ADC12_IN10}; //{GPIO_ADC12_IN10, GPIO_ADC12_IN8, GPIO_ADC12_IN9}; #endif diff --git a/nuttx/lib/string/Make.defs b/nuttx/lib/string/Make.defs index 16add6e89e..191b9ffea5 100644 --- a/nuttx/lib/string/Make.defs +++ b/nuttx/lib/string/Make.defs @@ -48,7 +48,7 @@ ifneq ($(CONFIG_ARCH_MEMCPY),y) ifeq ($(CONFIG_MEMCPY_VIK),y) CSRCS += lib_vikmemcpy.c else -CSRCS += lib_memccpy.c +CSRCS += lib_memcpy.c endif endif From 096397d49fbae5398528a1a8c0d84e091625249a Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 21 Oct 2012 16:53:38 +0000 Subject: [PATCH 016/206] STM32 ADC driver fixes git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5247 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 +++++ nuttx/arch/arm/src/stm32/stm32_adc.c | 10 +++++++--- nuttx/arch/arm/src/stm32/stm32_adc.h | 2 +- nuttx/configs/shenzhou/README.txt | 7 +++++++ nuttx/drivers/analog/adc.c | 15 +++++++++++++-- 5 files changed, 33 insertions(+), 6 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 44f38ee10a..f9e1bf5d03 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3496,3 +3496,8 @@ optimized for size. * lib/strings/lib_memset.c: CONFIG_MEMSET_64BIT will perform 64-bit aligned memset() operations. + * arch/arm/src/stm32/stm32_adc.c: Need to put the ADC back into the + initial reset in the open/setup logic. Opening the ADC driver works + the first time, but not the second because the device is left in a + powered down state on the last close. + diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.c b/nuttx/arch/arm/src/stm32/stm32_adc.c index 777f624aa4..b5033b0576 100644 --- a/nuttx/arch/arm/src/stm32/stm32_adc.c +++ b/nuttx/arch/arm/src/stm32/stm32_adc.c @@ -694,10 +694,10 @@ static int adc_timinit(FAR struct stm32_dev_s *priv) case 4: /* TimerX TRGO event */ { -#warning "TRGO support not yet implemented" - + /* TODO: TRGO support not yet implemented */ /* Set the event TRGO */ + ccenable = 0; egr = GTIM_EGR_TG; /* Set the duty cycle by writing to the CCR register for this channel */ @@ -971,7 +971,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) avdbg("intf: ADC%d\n", priv->intf); flags = irqsave(); - /* Enable ADC reset state */ + /* Enable ADC reset state */ adc_rccreset(priv, true); @@ -1164,6 +1164,10 @@ static int adc_setup(FAR struct adc_dev_s *dev) ret = irq_attach(priv->irq, priv->isr); if (ret == OK) { + /* Make sure that the ADC device is in the powered up, reset state */ + + adc_reset(dev); + /* Enable the ADC interrupt */ avdbg("Enable the ADC interrupt: irq=%d\n", priv->irq); diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.h b/nuttx/arch/arm/src/stm32/stm32_adc.h index 34f29020c7..060fcdfb90 100644 --- a/nuttx/arch/arm/src/stm32/stm32_adc.h +++ b/nuttx/arch/arm/src/stm32/stm32_adc.h @@ -287,7 +287,7 @@ #if defined(ADC1_HAVE_TIMER) || defined(ADC2_HAVE_TIMER) || defined(ADC3_HAVE_TIMER) # define ADC_HAVE_TIMER 1 -# if defined(CONFIG_STM32_STM32F10XX) && defined(CONFIG_STM32_FORCEPOWER) +# if defined(CONFIG_STM32_STM32F10XX) && !defined(CONFIG_STM32_FORCEPOWER) # warning "CONFIG_STM32_FORCEPOWER must be defined to enable the timer(s)" # endif #else diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index a60019a279..48f183aee4 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -593,6 +593,12 @@ Shenzhou-specific Configuration Options CONFIG_STM32_ADC1 CONFIG_STM32_ADC2 + 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 + initialized). + + CONFIG_STM32_FORCEPOWER + Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If CONFIG_STM32_TIMn is defined (as above) then the following may also be defined to indicate that @@ -798,6 +804,7 @@ Where is one of the following: CONFIG_STM32_TIM1_ADC1=y : Allocate Timer 1 to ADC 1 CONFIG_STM32_ADC1_SAMPLE_FREQUENCY=100 : Set sampling frequency to 100Hz CONFIG_STM32_ADC1_TIMTRIG=0 : Trigger on timer output 0 + CONFIG_STM32_FORCEPOWER=y : Apply power to TIM1 a boot up time CONFIG_EXAMPLES_ADC=y : Enable the apps/examples/adc built-in nxwm diff --git a/nuttx/drivers/analog/adc.c b/nuttx/drivers/analog/adc.c index 84070f162a..72f19452a4 100644 --- a/nuttx/drivers/analog/adc.c +++ b/nuttx/drivers/analog/adc.c @@ -143,7 +143,7 @@ static int adc_open(FAR struct file *filep) dev->ad_recv.af_head = 0; dev->ad_recv.af_tail = 0; - /* Finally, Enable the CAN RX interrupt */ + /* Finally, Enable the ADC RX interrupt */ dev->ad_ops->ao_rxint(dev, true); @@ -151,9 +151,11 @@ static int adc_open(FAR struct file *filep) dev->ad_ocount = tmp; } + irqrestore(flags); } } + sem_post(&dev->ad_closesem); } return ret; @@ -370,6 +372,10 @@ static int adc_ioctl(FAR struct file *filep, int cmd, unsigned long arg) * Public Functions ****************************************************************************/ +/**************************************************************************** + * Name: adc_receive + ****************************************************************************/ + int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data) { FAR struct adc_fifo_s *fifo = &dev->ad_recv; @@ -390,7 +396,7 @@ int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data) if (nexttail != fifo->af_head) { - /* Add the new, decoded CAN message at the tail of the FIFO */ + /* Add the new, decoded ADC sample at the tail of the FIFO */ fifo->af_buffer[fifo->af_tail].am_channel = ch; fifo->af_buffer[fifo->af_tail].am_data = data; @@ -403,11 +409,16 @@ int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data) { sem_post(&fifo->af_sem); } + err = OK; } return err; } +/**************************************************************************** + * Name: adc_register + ****************************************************************************/ + int adc_register(FAR const char *path, FAR struct adc_dev_s *dev) { /* Initialize the ADC device structure */ From 2327d0eedcef3de9a9aed8b48ea786c531070b5f Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 23 Oct 2012 15:51:45 +0000 Subject: [PATCH 017/206] Fewer shell invocations in apps/Makefile git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5248 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 3 +++ apps/Makefile | 5 +++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 02843d547a..79de56614c 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -380,3 +380,6 @@ * apps/examples/nximage/nximage_main.c: Add a 5 second delay after the NX logo is presented so that there is time for the image to be verified. Suggested by Petteri Aimonen. +i * apps/Makefile: Small change that reduces the number of shell invocations + by one (Mike Smith). + diff --git a/apps/Makefile b/apps/Makefile index e407e2de87..be98dbbfe2 100644 --- a/apps/Makefile +++ b/apps/Makefile @@ -114,8 +114,9 @@ $(foreach BUILTIN, $(CONFIGURED_APPS), $(eval $(call ADD_BUILTIN,$(BUILTIN)))) # provided by the user (possibly as a symbolic link) to add libraries and # applications to the standard build from the repository. -INSTALLED_APPS += ${shell if [ -r external/Makefile ]; then echo "external"; fi} -SUBDIRS += ${shell if [ -r external/Makefile ]; then echo "external"; fi} +EXTERNAL_DIR := $(dir $(wildcard external/Makefile)) +INSTALLED_APPS += $(EXTERNAL_DIR) +SUBDIRS += $(EXTERNAL_DIR) # The final build target From d30053952442a0dfefbea23de238a8077ad3463e Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 23 Oct 2012 19:53:03 +0000 Subject: [PATCH 018/206] Move ld.script files from configuration directories to script/ directory git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5249 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 7 +- nuttx/configs/hymini-stm32v/buttons/Make.defs | 6 +- nuttx/configs/hymini-stm32v/buttons/ld.script | 112 ---------------- .../hymini-stm32v/buttons/ld.script.dfu | 111 ---------------- nuttx/configs/hymini-stm32v/nsh/Make.defs | 6 +- nuttx/configs/hymini-stm32v/nsh/ld.script | 112 ---------------- nuttx/configs/hymini-stm32v/nsh/ld.script.dfu | 111 ---------------- nuttx/configs/hymini-stm32v/nsh2/Make.defs | 6 +- nuttx/configs/hymini-stm32v/nsh2/ld.script | 112 ---------------- .../configs/hymini-stm32v/nsh2/ld.script.dfu | 111 ---------------- nuttx/configs/hymini-stm32v/nx/Make.defs | 6 +- nuttx/configs/hymini-stm32v/nx/ld.script.dfu | 111 ---------------- nuttx/configs/hymini-stm32v/nxlines/Make.defs | 6 +- nuttx/configs/hymini-stm32v/nxlines/ld.script | 112 ---------------- .../hymini-stm32v/nxlines/ld.script.dfu | 111 ---------------- .../{usbserial => scripts}/ld.script | 6 +- .../{nx/ld.script => scripts/ld.script.dfu} | 13 +- .../configs/hymini-stm32v/usbserial/Make.defs | 6 +- .../hymini-stm32v/usbserial/ld.script.dfu | 111 ---------------- .../hymini-stm32v/usbstorage/Make.defs | 6 +- .../hymini-stm32v/usbstorage/ld.script | 112 ---------------- .../hymini-stm32v/usbstorage/ld.script.dfu | 111 ---------------- .../configs/olimex-lpc1766stk/ftpc/Make.defs | 6 +- .../configs/olimex-lpc1766stk/ftpc/ld.script | 109 ---------------- .../olimex-lpc1766stk/hidkbd/Make.defs | 6 +- .../olimex-lpc1766stk/hidkbd/ld.script | 109 ---------------- .../olimex-lpc1766stk/nettest/Make.defs | 6 +- .../olimex-lpc1766stk/nettest/ld.script | 109 ---------------- nuttx/configs/olimex-lpc1766stk/nsh/Make.defs | 6 +- nuttx/configs/olimex-lpc1766stk/nx/Make.defs | 6 +- nuttx/configs/olimex-lpc1766stk/nx/ld.script | 109 ---------------- .../olimex-lpc1766stk/ostest/Make.defs | 6 +- .../olimex-lpc1766stk/ostest/ld.script | 109 ---------------- .../{nsh => scripts}/ld.script | 12 +- .../olimex-lpc1766stk/slip-httpd/Make.defs | 6 +- .../olimex-lpc1766stk/slip-httpd/ld.script | 109 ---------------- .../olimex-lpc1766stk/thttpd/Make.defs | 4 +- .../olimex-lpc1766stk/thttpd/ld.script | 109 ---------------- .../olimex-lpc1766stk/usbserial/Make.defs | 6 +- .../olimex-lpc1766stk/usbserial/ld.script | 109 ---------------- .../olimex-lpc1766stk/usbstorage/Make.defs | 6 +- .../olimex-lpc1766stk/usbstorage/ld.script | 109 ---------------- .../configs/olimex-lpc1766stk/wlan/Make.defs | 6 +- .../configs/olimex-lpc1766stk/wlan/ld.script | 109 ---------------- nuttx/configs/stm3220g-eval/dhcpd/Make.defs | 4 +- nuttx/configs/stm3220g-eval/nettest/Make.defs | 4 +- nuttx/configs/stm3220g-eval/nettest/ld.script | 121 ------------------ nuttx/configs/stm3220g-eval/nsh/Make.defs | 4 +- nuttx/configs/stm3220g-eval/nsh/ld.script | 121 ------------------ nuttx/configs/stm3220g-eval/nsh2/Make.defs | 4 +- nuttx/configs/stm3220g-eval/nsh2/ld.script | 121 ------------------ nuttx/configs/stm3220g-eval/nxwm/Make.defs | 4 +- nuttx/configs/stm3220g-eval/nxwm/ld.script | 121 ------------------ nuttx/configs/stm3220g-eval/ostest/Make.defs | 4 +- nuttx/configs/stm3220g-eval/ostest/ld.script | 120 ----------------- .../{dhcpd => scripts}/ld.script | 2 +- nuttx/configs/stm3220g-eval/telnetd/Make.defs | 4 +- nuttx/configs/stm3220g-eval/telnetd/ld.script | 121 ------------------ 58 files changed, 90 insertions(+), 3236 deletions(-) delete mode 100644 nuttx/configs/hymini-stm32v/buttons/ld.script delete mode 100644 nuttx/configs/hymini-stm32v/buttons/ld.script.dfu delete mode 100755 nuttx/configs/hymini-stm32v/nsh/ld.script delete mode 100755 nuttx/configs/hymini-stm32v/nsh/ld.script.dfu delete mode 100644 nuttx/configs/hymini-stm32v/nsh2/ld.script delete mode 100644 nuttx/configs/hymini-stm32v/nsh2/ld.script.dfu delete mode 100644 nuttx/configs/hymini-stm32v/nx/ld.script.dfu delete mode 100644 nuttx/configs/hymini-stm32v/nxlines/ld.script delete mode 100644 nuttx/configs/hymini-stm32v/nxlines/ld.script.dfu rename nuttx/configs/hymini-stm32v/{usbserial => scripts}/ld.script (96%) mode change 100755 => 100644 rename nuttx/configs/hymini-stm32v/{nx/ld.script => scripts/ld.script.dfu} (89%) delete mode 100755 nuttx/configs/hymini-stm32v/usbserial/ld.script.dfu delete mode 100755 nuttx/configs/hymini-stm32v/usbstorage/ld.script delete mode 100755 nuttx/configs/hymini-stm32v/usbstorage/ld.script.dfu delete mode 100755 nuttx/configs/olimex-lpc1766stk/ftpc/ld.script delete mode 100755 nuttx/configs/olimex-lpc1766stk/hidkbd/ld.script delete mode 100755 nuttx/configs/olimex-lpc1766stk/nettest/ld.script delete mode 100755 nuttx/configs/olimex-lpc1766stk/nx/ld.script delete mode 100755 nuttx/configs/olimex-lpc1766stk/ostest/ld.script rename nuttx/configs/olimex-lpc1766stk/{nsh => scripts}/ld.script (93%) delete mode 100755 nuttx/configs/olimex-lpc1766stk/slip-httpd/ld.script delete mode 100755 nuttx/configs/olimex-lpc1766stk/thttpd/ld.script delete mode 100755 nuttx/configs/olimex-lpc1766stk/usbserial/ld.script delete mode 100755 nuttx/configs/olimex-lpc1766stk/usbstorage/ld.script delete mode 100755 nuttx/configs/olimex-lpc1766stk/wlan/ld.script delete mode 100644 nuttx/configs/stm3220g-eval/nettest/ld.script delete mode 100644 nuttx/configs/stm3220g-eval/nsh/ld.script delete mode 100644 nuttx/configs/stm3220g-eval/nsh2/ld.script delete mode 100644 nuttx/configs/stm3220g-eval/nxwm/ld.script delete mode 100644 nuttx/configs/stm3220g-eval/ostest/ld.script rename nuttx/configs/stm3220g-eval/{dhcpd => scripts}/ld.script (98%) delete mode 100644 nuttx/configs/stm3220g-eval/telnetd/ld.script diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f9e1bf5d03..1aa2d9f151 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3500,4 +3500,9 @@ initial reset in the open/setup logic. Opening the ADC driver works the first time, but not the second because the device is left in a powered down state on the last close. - + * configs/olimex-lpc1766stck/scripts: Replace all of the identical + ld.script files with the common one in this directory. + * configs/stm3220g-eval/scripts: Replace all of the identical + ld.script files with the common one in this directory. + * configs/hymini-stm32v/scripts: Replace all of the identical + ld.script files with the common one in this directory. diff --git a/nuttx/configs/hymini-stm32v/buttons/Make.defs b/nuttx/configs/hymini-stm32v/buttons/Make.defs index efc29cb1dc..565729c1a1 100644 --- a/nuttx/configs/hymini-stm32v/buttons/Make.defs +++ b/nuttx/configs/hymini-stm32v/buttons/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/hymini-stm32v/buttons/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/buttons/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/buttons/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/hymini-stm32v/buttons/ld.script b/nuttx/configs/hymini-stm32v/buttons/ld.script deleted file mode 100644 index ef6968958c..0000000000 --- a/nuttx/configs/hymini-stm32v/buttons/ld.script +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/buttons/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103VCT6 has 256Kb of FLASH beginning at address 0x0800:0000 and - * 48Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103V has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/buttons/ld.script.dfu b/nuttx/configs/hymini-stm32v/buttons/ld.script.dfu deleted file mode 100644 index 5c839a0d87..0000000000 --- a/nuttx/configs/hymini-stm32v/buttons/ld.script.dfu +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/buttons/ld.script.dfu - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and - * 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the - * Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct - * load .text load address is 0x08003000 (leaving 464Kb). - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/nsh/Make.defs b/nuttx/configs/hymini-stm32v/nsh/Make.defs index cade80762c..285bbe40ab 100644 --- a/nuttx/configs/hymini-stm32v/nsh/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/hymini-stm32v/nsh/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/nsh/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/hymini-stm32v/nsh/ld.script b/nuttx/configs/hymini-stm32v/nsh/ld.script deleted file mode 100755 index c09e716cb6..0000000000 --- a/nuttx/configs/hymini-stm32v/nsh/ld.script +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/nsh/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and - * 64Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/nsh/ld.script.dfu b/nuttx/configs/hymini-stm32v/nsh/ld.script.dfu deleted file mode 100755 index 5dfc51ad1e..0000000000 --- a/nuttx/configs/hymini-stm32v/nsh/ld.script.dfu +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/nsh/ld.script.dfu - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and - * 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the - * Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct - * load .text load address is 0x08003000 (leaving 464Kb). - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/nsh2/Make.defs b/nuttx/configs/hymini-stm32v/nsh2/Make.defs index 269b4979ea..9ad8c2774a 100644 --- a/nuttx/configs/hymini-stm32v/nsh2/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh2/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/hymini-stm32v/nsh2/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh2/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/nsh2/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/hymini-stm32v/nsh2/ld.script b/nuttx/configs/hymini-stm32v/nsh2/ld.script deleted file mode 100644 index 1b861e6b65..0000000000 --- a/nuttx/configs/hymini-stm32v/nsh2/ld.script +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/nsh2/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103VCT6 has 256Kb of FLASH beginning at address 0x0800:0000 and - * 48Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/nsh2/ld.script.dfu b/nuttx/configs/hymini-stm32v/nsh2/ld.script.dfu deleted file mode 100644 index a8d0839c1d..0000000000 --- a/nuttx/configs/hymini-stm32v/nsh2/ld.script.dfu +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/nsh2/ld.script.dfu - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and - * 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the - * Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct - * load .text load address is 0x08003000 (leaving 464Kb). - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/nx/Make.defs b/nuttx/configs/hymini-stm32v/nx/Make.defs index fce4ec279b..84700e0828 100644 --- a/nuttx/configs/hymini-stm32v/nx/Make.defs +++ b/nuttx/configs/hymini-stm32v/nx/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/hymini-stm32v/nx/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nx/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/nx/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/hymini-stm32v/nx/ld.script.dfu b/nuttx/configs/hymini-stm32v/nx/ld.script.dfu deleted file mode 100644 index bd995086f5..0000000000 --- a/nuttx/configs/hymini-stm32v/nx/ld.script.dfu +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/nx/ld.script.dfu - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and - * 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the - * Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct - * load .text load address is 0x08003000 (leaving 464Kb). - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/nxlines/Make.defs b/nuttx/configs/hymini-stm32v/nxlines/Make.defs index 8943c4cb72..b9e8841f0a 100644 --- a/nuttx/configs/hymini-stm32v/nxlines/Make.defs +++ b/nuttx/configs/hymini-stm32v/nxlines/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/hymini-stm32v/nxlines/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 @@ -89,13 +89,13 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nxlines/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" 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)/nxlines/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/hymini-stm32v/nxlines/ld.script b/nuttx/configs/hymini-stm32v/nxlines/ld.script deleted file mode 100644 index 4938ad5010..0000000000 --- a/nuttx/configs/hymini-stm32v/nxlines/ld.script +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/nxlines/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103VCT6 has 256Kb of FLASH beginning at address 0x0800:0000 and - * 48Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/nxlines/ld.script.dfu b/nuttx/configs/hymini-stm32v/nxlines/ld.script.dfu deleted file mode 100644 index b64109da8e..0000000000 --- a/nuttx/configs/hymini-stm32v/nxlines/ld.script.dfu +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/nxlines/ld.script.dfu - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and - * 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the - * Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct - * load .text load address is 0x08003000 (leaving 464Kb). - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/usbserial/ld.script b/nuttx/configs/hymini-stm32v/scripts/ld.script old mode 100755 new mode 100644 similarity index 96% rename from nuttx/configs/hymini-stm32v/usbserial/ld.script rename to nuttx/configs/hymini-stm32v/scripts/ld.script index 8a83616146..cef391bf42 --- a/nuttx/configs/hymini-stm32v/usbserial/ld.script +++ b/nuttx/configs/hymini-stm32v/scripts/ld.script @@ -1,10 +1,10 @@ /**************************************************************************** - * configs/hymini-stm32v/usbserial/ld.script + * configs/hymini-stm32v/scripts/ld.script * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * Laurent Latil - + * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: diff --git a/nuttx/configs/hymini-stm32v/nx/ld.script b/nuttx/configs/hymini-stm32v/scripts/ld.script.dfu similarity index 89% rename from nuttx/configs/hymini-stm32v/nx/ld.script rename to nuttx/configs/hymini-stm32v/scripts/ld.script.dfu index c4a12d2b94..1f51a9fc3f 100644 --- a/nuttx/configs/hymini-stm32v/nx/ld.script +++ b/nuttx/configs/hymini-stm32v/scripts/ld.script.dfu @@ -1,7 +1,7 @@ /**************************************************************************** - * configs/hymini-stm32v/nx/ld.script + * configs/hymini-stm32v/scripts/ld.script.dfu * - * 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 @@ -34,15 +34,14 @@ ****************************************************************************/ /* The STM32F103VCT6 has 256Kb of FLASH beginning at address 0x0800:0000 and - * 48Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. + * 48Kb of SRAM beginning at address 0x2000:0000. Here we assume that the + * Hy-Mini STM32v's DFU bootloader is being used. In that case, the correct + * load .text load address is 0x08003000 (leaving 244Kb). */ MEMORY { - flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K + flash (rx) : ORIGIN = 0x08003000, LENGTH = 244K sram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K } diff --git a/nuttx/configs/hymini-stm32v/usbserial/Make.defs b/nuttx/configs/hymini-stm32v/usbserial/Make.defs index 1e8c90b123..559af81de5 100644 --- a/nuttx/configs/hymini-stm32v/usbserial/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbserial/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/hymini-stm32v/usbserial/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/usbserial/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/usbserial/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/hymini-stm32v/usbserial/ld.script.dfu b/nuttx/configs/hymini-stm32v/usbserial/ld.script.dfu deleted file mode 100755 index 5734ed2675..0000000000 --- a/nuttx/configs/hymini-stm32v/usbserial/ld.script.dfu +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/usbserial/ld.script.dfu - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and - * 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the - * Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct - * load .text load address is 0x08003000 (leaving 464Kb). - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/usbstorage/Make.defs b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs index 8acc8db4aa..5fef4f705d 100644 --- a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/hymini-stm32v/usbstorage/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/usbstorage/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/usbstorage/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/hymini-stm32v/usbstorage/ld.script b/nuttx/configs/hymini-stm32v/usbstorage/ld.script deleted file mode 100755 index 7e92fec83b..0000000000 --- a/nuttx/configs/hymini-stm32v/usbstorage/ld.script +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/usbstorage/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and - * 64Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/hymini-stm32v/usbstorage/ld.script.dfu b/nuttx/configs/hymini-stm32v/usbstorage/ld.script.dfu deleted file mode 100755 index 7bb2997c25..0000000000 --- a/nuttx/configs/hymini-stm32v/usbstorage/ld.script.dfu +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/hymini-stm32v/usbstorage/ld.script.dfu - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and - * 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the - * Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct - * load .text load address is 0x08003000 (leaving 464Kb). - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/olimex-lpc1766stk/ftpc/Make.defs b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs index 352c031749..674ad76929 100644 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/ftpc/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 @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ftpc/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/ftpc/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/ld.script b/nuttx/configs/olimex-lpc1766stk/ftpc/ld.script deleted file mode 100755 index 59b80c9bd6..0000000000 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/ftpc/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/olimex-lpc1766stk/hidkbd/Make.defs b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs index 017a79e7dc..3c68d370d0 100644 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/hidkbd/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 @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/hidkbd/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/hidkbd/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/ld.script b/nuttx/configs/olimex-lpc1766stk/hidkbd/ld.script deleted file mode 100755 index c6c97d402f..0000000000 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/hidkbd/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/olimex-lpc1766stk/nettest/Make.defs b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs index 652899c083..57f2b7a558 100644 --- a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/nettest/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 @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nettest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nettest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/ld.script b/nuttx/configs/olimex-lpc1766stk/nettest/ld.script deleted file mode 100755 index cc05746bad..0000000000 --- a/nuttx/configs/olimex-lpc1766stk/nettest/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/nettest/ld.script - * - * Copyright (C) 2010-2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/olimex-lpc1766stk/nsh/Make.defs b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs index b517fae43c..c9ecf51db7 100644 --- a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/nsh/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 @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs index 2d0d63b190..64c9814925 100644 --- a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/nx/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 @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nx/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nx/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/nx/ld.script b/nuttx/configs/olimex-lpc1766stk/nx/ld.script deleted file mode 100755 index a4ad7e35bb..0000000000 --- a/nuttx/configs/olimex-lpc1766stk/nx/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/nx/ld.script - * - * Copyright (C) 2010-2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/olimex-lpc1766stk/ostest/Make.defs b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs index 6883694a3f..2f33642bfc 100644 --- a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/ostest/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 @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/ld.script b/nuttx/configs/olimex-lpc1766stk/ostest/ld.script deleted file mode 100755 index 323f1ec1dc..0000000000 --- a/nuttx/configs/olimex-lpc1766stk/ostest/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/ostest/ld.script - * - * Copyright (C) 2010-2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/olimex-lpc1766stk/nsh/ld.script b/nuttx/configs/olimex-lpc1766stk/scripts/ld.script similarity index 93% rename from nuttx/configs/olimex-lpc1766stk/nsh/ld.script rename to nuttx/configs/olimex-lpc1766stk/scripts/ld.script index 5f6adbecdb..76da776894 100755 --- a/nuttx/configs/olimex-lpc1766stk/nsh/ld.script +++ b/nuttx/configs/olimex-lpc1766stk/scripts/ld.script @@ -1,7 +1,7 @@ /**************************************************************************** - * configs/olimex-lpc1766stk/nsh/ld.script + * configs/olimex-lpc1766stk/scripts/ld.script * - * 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 @@ -66,7 +66,7 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - _eronly = ABSOLUTE(.); /* See below */ + _eronly = ABSOLUTE(.); .data : { _sdata = ABSOLUTE(.); @@ -86,14 +86,16 @@ SECTIONS } >sram __exidx_end = ABSOLUTE(.); - .bss : { /* BSS */ + .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) *(.gnu.linkonce.b.*) *(COMMON) _ebss = ABSOLUTE(.); } > sram - /* Stabs debugging sections. */ + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } .stabstr 0 : { *(.stabstr) } .stab.excl 0 : { *(.stab.excl) } diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs index 984d4e1874..fc49b69814 100644 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/slip-httpd/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 @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/slip-httpd/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/slip-httpd/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/ld.script b/nuttx/configs/olimex-lpc1766stk/slip-httpd/ld.script deleted file mode 100755 index 43d2662c80..0000000000 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/slip-httpd/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/olimex-lpc1766stk/thttpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs index 39e5ed299e..bb4df618b2 100644 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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 + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/ld.script b/nuttx/configs/olimex-lpc1766stk/thttpd/ld.script deleted file mode 100755 index 9225b8da61..0000000000 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/thttpd/ld.script - * - * Copyright (C) 2010-2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/olimex-lpc1766stk/usbserial/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs index 1cedb01d72..b4716971df 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/usbserial/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 @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/usbserial/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/usbserial/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/ld.script b/nuttx/configs/olimex-lpc1766stk/usbserial/ld.script deleted file mode 100755 index 26e03a20e1..0000000000 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/usbserial/ld.script - * - * Copyright (C) 2010-2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/olimex-lpc1766stk/usbstorage/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs index f879340f14..ed338c8b26 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/usbstorage/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 @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/usbstorage/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/usbstorage/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/ld.script b/nuttx/configs/olimex-lpc1766stk/usbstorage/ld.script deleted file mode 100755 index 8c81ff85a1..0000000000 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/usbstorage/ld.script - * - * Copyright (C) 2010-2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/olimex-lpc1766stk/wlan/Make.defs b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs index a316a0e6a6..08f55feab7 100644 --- a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/olimex-lpc1766stk/wlan/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 @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/wlan/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/wlan/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/ld.script b/nuttx/configs/olimex-lpc1766stk/wlan/ld.script deleted file mode 100755 index 82fc20a440..0000000000 --- a/nuttx/configs/olimex-lpc1766stk/wlan/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/wlan/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/stm3220g-eval/dhcpd/Make.defs b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs index e8bb28c762..e5a0e7b06a 100644 --- a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs @@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/dhcpd/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/dhcpd/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/stm3220g-eval/nettest/Make.defs b/nuttx/configs/stm3220g-eval/nettest/Make.defs index 2c6b8a1f4e..2a8976d089 100644 --- a/nuttx/configs/stm3220g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3220g-eval/nettest/Make.defs @@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nettest/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/nettest/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/stm3220g-eval/nettest/ld.script b/nuttx/configs/stm3220g-eval/nettest/ld.script deleted file mode 100644 index 893ae1d662..0000000000 --- a/nuttx/configs/stm3220g-eval/nettest/ld.script +++ /dev/null @@ -1,121 +0,0 @@ -/**************************************************************************** - * configs/stm3220g-eval/nettest/ld.script - * - * 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. - * - ****************************************************************************/ - -/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and - * 128Kb of SRAM. SRAM is split up into two blocks: - * - * 1) 112Kb of SRAM beginning at address 0x2000:0000 - * 2) 16Kb of SRAM beginning at address 0x2001:c000 - * - * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 - * where the code expects to begin execution by jumping to the entry point in - * the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - .init_section : { - _sinit = ABSOLUTE(.); - *(.init_array .init_array.*) - _einit = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/stm3220g-eval/nsh/Make.defs b/nuttx/configs/stm3220g-eval/nsh/Make.defs index 834db56bca..23a57ab800 100644 --- a/nuttx/configs/stm3220g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh/Make.defs @@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/nsh/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/stm3220g-eval/nsh/ld.script b/nuttx/configs/stm3220g-eval/nsh/ld.script deleted file mode 100644 index dfa2b3ccdd..0000000000 --- a/nuttx/configs/stm3220g-eval/nsh/ld.script +++ /dev/null @@ -1,121 +0,0 @@ -/**************************************************************************** - * configs/stm3220g-eval/nsh/ld.script - * - * 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. - * - ****************************************************************************/ - -/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and - * 128Kb of SRAM. SRAM is split up into two blocks: - * - * 1) 112Kb of SRAM beginning at address 0x2000:0000 - * 2) 16Kb of SRAM beginning at address 0x2001:c000 - * - * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 - * where the code expects to begin execution by jumping to the entry point in - * the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - .init_section : { - _sinit = ABSOLUTE(.); - *(.init_array .init_array.*) - _einit = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/stm3220g-eval/nsh2/Make.defs b/nuttx/configs/stm3220g-eval/nsh2/Make.defs index f29c472148..38335c1709 100644 --- a/nuttx/configs/stm3220g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh2/Make.defs @@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh2/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/nsh2/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/stm3220g-eval/nsh2/ld.script b/nuttx/configs/stm3220g-eval/nsh2/ld.script deleted file mode 100644 index e03a33dcb2..0000000000 --- a/nuttx/configs/stm3220g-eval/nsh2/ld.script +++ /dev/null @@ -1,121 +0,0 @@ -/**************************************************************************** - * configs/stm3220g-eval/nsh2/ld.script - * - * 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. - * - ****************************************************************************/ - -/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and - * 128Kb of SRAM. SRAM is split up into two blocks: - * - * 1) 112Kb of SRAM beginning at address 0x2000:0000 - * 2) 16Kb of SRAM beginning at address 0x2001:c000 - * - * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 - * where the code expects to begin execution by jumping to the entry point in - * the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - .init_section : { - _sinit = ABSOLUTE(.); - *(.init_array .init_array.*) - _einit = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/stm3220g-eval/nxwm/Make.defs b/nuttx/configs/stm3220g-eval/nxwm/Make.defs index 4b770ba64e..c4846c0c31 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3220g-eval/nxwm/Make.defs @@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nxwm/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/nxwm/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/stm3220g-eval/nxwm/ld.script b/nuttx/configs/stm3220g-eval/nxwm/ld.script deleted file mode 100644 index 409ecc3af5..0000000000 --- a/nuttx/configs/stm3220g-eval/nxwm/ld.script +++ /dev/null @@ -1,121 +0,0 @@ -/**************************************************************************** - * configs/stm3220g-eval/nxwm/ld.script - * - * 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. - * - ****************************************************************************/ - -/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and - * 128Kb of SRAM. SRAM is split up into two blocks: - * - * 1) 112Kb of SRAM beginning at address 0x2000:0000 - * 2) 16Kb of SRAM beginning at address 0x2001:c000 - * - * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 - * where the code expects to begin execution by jumping to the entry point in - * the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - .init_section : { - _sinit = ABSOLUTE(.); - *(.init_array .init_array.*) - _einit = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/stm3220g-eval/ostest/Make.defs b/nuttx/configs/stm3220g-eval/ostest/Make.defs index a67036f78a..e2de89cf74 100644 --- a/nuttx/configs/stm3220g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3220g-eval/ostest/Make.defs @@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/ostest/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/stm3220g-eval/ostest/ld.script b/nuttx/configs/stm3220g-eval/ostest/ld.script deleted file mode 100644 index 17428ea857..0000000000 --- a/nuttx/configs/stm3220g-eval/ostest/ld.script +++ /dev/null @@ -1,120 +0,0 @@ -/**************************************************************************** - * configs/stm3220g-eval/ostest/ld.script - * - * 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. - * - ****************************************************************************/ - -/* The STM32F207IGH6U has 1024Kb of FLASH two blocks: - * - * 1) 112Kb of SRAM beginning at address 0x2000:0000 - * 2) 16Kb of SRAM beginning at address 0x2001:c000 - * - * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 - * where the code expects to begin execution by jumping to the entry point in - * the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - .init_section : { - _sinit = ABSOLUTE(.); - *(.init_array .init_array.*) - _einit = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/stm3220g-eval/dhcpd/ld.script b/nuttx/configs/stm3220g-eval/scripts/ld.script similarity index 98% rename from nuttx/configs/stm3220g-eval/dhcpd/ld.script rename to nuttx/configs/stm3220g-eval/scripts/ld.script index a264f2442d..1c9f12bba1 100644 --- a/nuttx/configs/stm3220g-eval/dhcpd/ld.script +++ b/nuttx/configs/stm3220g-eval/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/stm3220g-eval/dhcpd/ld.script + * configs/stm3220g-eval/scripts/ld.script * * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/nuttx/configs/stm3220g-eval/telnetd/Make.defs b/nuttx/configs/stm3220g-eval/telnetd/Make.defs index 4a69279062..4004508d50 100644 --- a/nuttx/configs/stm3220g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3220g-eval/telnetd/Make.defs @@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/telnetd/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/telnetd/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/stm3220g-eval/telnetd/ld.script b/nuttx/configs/stm3220g-eval/telnetd/ld.script deleted file mode 100644 index f4ecb084ac..0000000000 --- a/nuttx/configs/stm3220g-eval/telnetd/ld.script +++ /dev/null @@ -1,121 +0,0 @@ -/**************************************************************************** - * configs/stm3220g-eval/telnetd/ld.script - * - * 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. - * - ****************************************************************************/ - -/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and - * 128Kb of SRAM. SRAM is split up into two blocks: - * - * 1) 112Kb of SRAM beginning at address 0x2000:0000 - * 2) 16Kb of SRAM beginning at address 0x2001:c000 - * - * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 - * where the code expects to begin execution by jumping to the entry point in - * the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - .init_section : { - _sinit = ABSOLUTE(.); - *(.init_array .init_array.*) - _einit = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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) } -} From 1bd66e95f8b9817da320c85fc77ca6466bbdaed7 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 24 Oct 2012 16:46:12 +0000 Subject: [PATCH 019/206] Add framework to support loadable ELF modules (not much logic in place yet) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5250 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 + nuttx/Kconfig | 4 + nuttx/binfmt/Kconfig | 34 +++ nuttx/binfmt/Makefile | 55 ++-- nuttx/binfmt/elf.c | 259 ++++++++++++++++++ nuttx/binfmt/libelf/Kconfig | 9 + nuttx/binfmt/libelf/Make.defs | 53 ++++ nuttx/binfmt/libelf/gnu-elf.ld | 187 +++++++++++++ nuttx/binfmt/libelf/libelf_bind.c | 106 +++++++ nuttx/binfmt/libelf/libelf_init.c | 189 +++++++++++++ nuttx/binfmt/libelf/libelf_load.c | 91 ++++++ nuttx/binfmt/libelf/libelf_read.c | 165 +++++++++++ nuttx/binfmt/libelf/libelf_uninit.c | 85 ++++++ nuttx/binfmt/libelf/libelf_unload.c | 97 +++++++ nuttx/binfmt/libelf/libelf_verify.c | 88 ++++++ nuttx/binfmt/libnxflat/Kconfig | 5 + nuttx/binfmt/libnxflat/Make.defs | 24 +- nuttx/binfmt/libnxflat/libnxflat_bind.c | 46 ++-- nuttx/binfmt/libnxflat/libnxflat_uninit.c | 4 - nuttx/binfmt/libnxflat/libnxflat_verify.c | 6 +- .../lpcxpresso-lpc1768/dhcpd/Make.defs | 6 +- .../configs/lpcxpresso-lpc1768/nsh/Make.defs | 6 +- .../configs/lpcxpresso-lpc1768/nsh/ld.script | 110 -------- nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs | 6 +- nuttx/configs/lpcxpresso-lpc1768/nx/ld.script | 110 -------- .../lpcxpresso-lpc1768/ostest/Make.defs | 6 +- .../lpcxpresso-lpc1768/ostest/ld.script | 110 -------- .../{dhcpd => scripts}/ld.script | 7 +- .../lpcxpresso-lpc1768/thttpd/Make.defs | 4 +- .../lpcxpresso-lpc1768/thttpd/ld.script | 110 -------- .../lpcxpresso-lpc1768/usbstorage/Make.defs | 6 +- .../lpcxpresso-lpc1768/usbstorage/ld.script | 110 -------- nuttx/include/elf.h | 53 ++++ nuttx/include/nuttx/elf.h | 259 ++++++++++++++++++ nuttx/include/nuttx/nxflat.h | 38 +-- 35 files changed, 1802 insertions(+), 651 deletions(-) create mode 100644 nuttx/binfmt/elf.c create mode 100644 nuttx/binfmt/libelf/Kconfig create mode 100644 nuttx/binfmt/libelf/Make.defs create mode 100644 nuttx/binfmt/libelf/gnu-elf.ld create mode 100644 nuttx/binfmt/libelf/libelf_bind.c create mode 100644 nuttx/binfmt/libelf/libelf_init.c create mode 100644 nuttx/binfmt/libelf/libelf_load.c create mode 100644 nuttx/binfmt/libelf/libelf_read.c create mode 100644 nuttx/binfmt/libelf/libelf_uninit.c create mode 100644 nuttx/binfmt/libelf/libelf_unload.c create mode 100644 nuttx/binfmt/libelf/libelf_verify.c delete mode 100755 nuttx/configs/lpcxpresso-lpc1768/nsh/ld.script delete mode 100755 nuttx/configs/lpcxpresso-lpc1768/nx/ld.script delete mode 100755 nuttx/configs/lpcxpresso-lpc1768/ostest/ld.script rename nuttx/configs/lpcxpresso-lpc1768/{dhcpd => scripts}/ld.script (95%) delete mode 100755 nuttx/configs/lpcxpresso-lpc1768/thttpd/ld.script delete mode 100755 nuttx/configs/lpcxpresso-lpc1768/usbstorage/ld.script create mode 100644 nuttx/include/elf.h create mode 100644 nuttx/include/nuttx/elf.h diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 1aa2d9f151..59fa735449 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3506,3 +3506,8 @@ ld.script files with the common one in this directory. * configs/hymini-stm32v/scripts: Replace all of the identical ld.script files with the common one in this directory. + * configs/lpcxpresso-lpc1768/scripts: Replace all of the identical + ld.script files with the common one in this directory. + * binfmt/elf.c, binfmt/libelf, include/elf.h, include/nuttx/elf.h: Add + basic framework for loadable ELF module support. The initial check- + in is non-functional and is simply the framework for ELF support. diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 325759b41a..8239dec02d 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -395,6 +395,10 @@ menu "Memory Management" source mm/Kconfig endmenu +menu "Binary Formats" +source binfmt/Kconfig +endmenu + menu "Library Routines" source lib/Kconfig source libxx/Kconfig diff --git a/nuttx/binfmt/Kconfig b/nuttx/binfmt/Kconfig index ae2bf31307..3519536fb6 100644 --- a/nuttx/binfmt/Kconfig +++ b/nuttx/binfmt/Kconfig @@ -2,3 +2,37 @@ # For a description of the syntax of this configuration file, # see misc/tools/kconfig-language.txt. # + +config BINFMT_DISABLE + bool "Disble BINFMT support" + default n + ---help--- + By default, support for loadable binary formats is built. This logic + may be suppressed be defining this setting. + +if !BINFMT_DISABLE + +config NXFLAT + bool "Enable the NXFLAT Binary Format" + default n + ---help--- + Enable support for the NXFLAT binary format. Default: n + +if NXFLAT +include binfmt/libnxflat/Kconfig +endif + +config ELF + bool "Enable the ELF Binary Format" + default n + ---help--- + Enable support for the ELF binary format. Default: n + +if ELF +include binfmt/libelf/Kconfig +endif +endif + +config SYMTAB_ORDEREDBYNAME + bool "Symbol Tables Ordered by Name" + default n diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile index b3a9269b30..1b98e3ede9 100644 --- a/nuttx/binfmt/Makefile +++ b/nuttx/binfmt/Makefile @@ -1,7 +1,7 @@ ############################################################################ # nxflat/Makefile # -# Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -36,55 +36,54 @@ -include $(TOPDIR)/Make.defs ifeq ($(WINTOOL),y) -INCDIROPT = -w +INCDIROPT = -w endif -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/sched} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/sched} -ifeq ($(CONFIG_NXFLAT),y) -include libnxflat/Make.defs -LIBNXFLAT_CSRCS += nxflat.c -endif +# Basic BINFMT source files BINFMT_ASRCS = BINFMT_CSRCS = binfmt_globals.c binfmt_register.c binfmt_unregister.c \ - binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_execmodule.c \ - binfmt_exec.c binfmt_dumpmodule.c + binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_execmodule.c \ + binfmt_exec.c binfmt_dumpmodule.c -SYMTAB_ASRCS = -SYMTAB_CSRCS = symtab_findbyname.c symtab_findbyvalue.c \ - symtab_findorderedbyname.c symtab_findorderedbyvalue.c +# Symbol table source files -SUBDIRS = libnxflat +BINFMT_CSRCS += symtab_findbyname.c symtab_findbyvalue.c \ + symtab_findorderedbyname.c symtab_findorderedbyvalue.c -ASRCS = $(BINFMT_ASRCS) $(SYMTAB_ASRCS) $(LIBNXFLAT_ASRCS) -AOBJS = $(ASRCS:.S=$(OBJEXT)) +# Add configured binary modules -CSRCS = $(BINFMT_CSRCS) $(SYMTAB_CSRCS) $(LIBNXFLAT_CSRCS) -COBJS = $(CSRCS:.c=$(OBJEXT)) +VPATH = +SUBDIRS = -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +include libnxflat/Make.defs +include libelf/Make.defs -BIN = libbinfmt$(LIBEXT) +BINFMT_AOBJS = $(BINFMT_ASRCS:.S=$(OBJEXT)) +BINFMT_COBJS = $(BINFMT_CSRCS:.c=$(OBJEXT)) -VPATH = libnxflat +BINFMT_SRCS = $(BINFMT_ASRCS) $(BINFMT_CSRCS) +BINFMT_OBJS = $(BINFMT_AOBJS) $(BINFMT_COBJS) -all: $(BIN) +BIN = libbinfmt$(LIBEXT) -$(AOBJS): %$(OBJEXT): %.S +all: $(BIN) + +$(BINFMT_AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) -$(COBJS): %$(OBJEXT): %.c +$(BINFMT_COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) -$(BIN): $(OBJS) - @( for obj in $(OBJS) ; do \ +$(BIN): $(BINFMT_OBJS) + @( for obj in $(BINFMT_OBJS) ; do \ $(call ARCHIVE, $@, $${obj}); \ done ; ) -.depend: Makefile $(SRCS) +.depend: Makefile $(BINFMT_SRCS) @$(MKDEP) --dep-path . --dep-path libnxflat \ - $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(CC) -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep @touch $@ depend: .depend diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c new file mode 100644 index 0000000000..74a35174f3 --- /dev/null +++ b/nuttx/binfmt/elf.c @@ -0,0 +1,259 @@ +/**************************************************************************** + * binfmt/elf.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#ifdef CONFIG_ELF + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be + * defined or CONFIG_ELF_DUMPBUFFER does nothing. + */ + +#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT) +# undef CONFIG_ELF_DUMPBUFFER +#endif + +#ifdef CONFIG_ELF_DUMPBUFFER +# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n) +#else +# define elf_dumpbuffer(m,b,n) +#endif + +#ifndef MIN +# define MIN(a,b) (a < b ? a : b) +#endif + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int elf_loadbinary(FAR struct binary_s *binp); +#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT) +static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct binfmt_s g_elfbinfmt = +{ + NULL, /* next */ + elf_loadbinary, /* load */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_dumploadinfo + ****************************************************************************/ + +#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT) +static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo) +{ + unsigned long dsize = loadinfo->datasize + loadinfo->bsssize; + + bdbg("LOAD_INFO:\n"); + bdbg(" ISPACE:\n"); + bdbg(" ispace: %08lx\n", loadinfo->ispace); + bdbg(" entryoffs: %08lx\n", loadinfo->entryoffs); + bdbg(" isize: %08lx\n", loadinfo->isize); + + bdbg(" DSPACE:\n"); + bdbg(" dspace: %08lx\n", loadinfo->dspace); + if (loadinfo->dspace != NULL) + { + bdbg(" crefs: %d\n", loadinfo->dspace->crefs); + bdbg(" region: %08lx\n", loadinfo->dspace->region); + } + bdbg(" datasize: %08lx\n", loadinfo->datasize); + bdbg(" bsssize: %08lx\n", loadinfo->bsssize); + bdbg(" (pad): %08lx\n", loadinfo->dsize - dsize); + bdbg(" stacksize: %08lx\n", loadinfo->stacksize); + bdbg(" dsize: %08lx\n", loadinfo->dsize); + + bdbg(" RELOCS:\n"); + bdbg(" relocstart: %08lx\n", loadinfo->relocstart); + bdbg(" reloccount: %d\n", loadinfo->reloccount); + + bdbg(" HANDLES:\n"); + bdbg(" filfd: %d\n", loadinfo->filfd); +} +#else +# define elf_dumploadinfo(i) +#endif + +/**************************************************************************** + * Name: elf_loadbinary + * + * Description: + * Verify that the file is an ELF binary and, if so, load the ELF + * binary into memory + * + ****************************************************************************/ + +static int elf_loadbinary(struct binary_s *binp) +{ + struct elf_loadinfo_s loadinfo; /* Contains globals for libelf */ + int ret; + + bvdbg("Loading file: %s\n", binp->filename); + + /* Initialize the xflat library to load the program binary. */ + + ret = elf_init(binp->filename, &loadinfo); + elf_dumploadinfo(&loadinfo); + if (ret != 0) + { + bdbg("Failed to initialize for load of NXFLT program: %d\n", ret); + goto errout; + } + + /* Load the program binary */ + + ret = elf_load(&loadinfo); + elf_dumploadinfo(&loadinfo); + if (ret != 0) + { + bdbg("Failed to load NXFLT program binary: %d\n", ret); + goto errout_with_init; + } + + /* Bind the program to the exported symbol table */ + + ret = elf_bind(&loadinfo, binp->exports, binp->nexports); + if (ret != 0) + { + bdbg("Failed to bind symbols program binary: %d\n", ret); + goto errout_with_load; + } + + /* Return the load information */ + + binp->entrypt = (main_t)(loadinfo.ispace + loadinfo.entryoffs); + binp->ispace = (void*)loadinfo.ispace; + binp->dspace = (void*)loadinfo.dspace; + binp->isize = loadinfo.isize; + binp->stacksize = loadinfo.stacksize; + + elf_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt, + MIN(binp->isize - loadinfo.entryoffs,512)); + + elf_uninit(&loadinfo); + return OK; + +errout_with_load: + elf_unload(&loadinfo); +errout_with_init: + elf_uninit(&loadinfo); +errout: + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_initialize + * + * Description: + * ELF support is built unconditionally. However, it order to + * use this binary format, this function must be called during system + * format in order to register the ELF binary format. + * + * Returned Value: + * This is a NuttX internal function so it follows the convention that + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_initialize(void) +{ + int ret; + + /* Register ourselves as a binfmt loader */ + + bvdbg("Registering ELF\n"); + + ret = register_binfmt(&g_elfbinfmt); + if (ret != 0) + { + bdbg("Failed to register binfmt: %d\n", ret); + } + + return ret; +} + +/**************************************************************************** + * Name: elf_uninitialize + * + * Description: + * Unregister the ELF binary loader + * + * Returned Value: + * None + * + ****************************************************************************/ + +void elf_uninitialize(void) +{ + unregister_binfmt(&g_elfbinfmt); +} + +#endif /* CONFIG_ELF */ + diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig new file mode 100644 index 0000000000..c47bc9f9eb --- /dev/null +++ b/nuttx/binfmt/libelf/Kconfig @@ -0,0 +1,9 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config ELF_DUMPBUFFER + bool "Dump ELF buffers" + default n + depends on DEBUG && DEBUG_VERBOSE diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs new file mode 100644 index 0000000000..6299618637 --- /dev/null +++ b/nuttx/binfmt/libelf/Make.defs @@ -0,0 +1,53 @@ +############################################################################ +# binfmt/libelf/Make.defs +# +# 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_ELF),y) + +# ELF application interfaces + +BINFMT_CSRCS += elf.c + +# ELF library + +BINFMT_CSRCS = libelf_init.c libelf_uninit.c libelf_load.c \ + libelf_unload.c libelf_verify.c libelf_read.c \ + libelf_bind.c + +# Hook the libelf subdirectory into the build + +VPATH += libelf +SUBDIRS += libelf + +endif diff --git a/nuttx/binfmt/libelf/gnu-elf.ld b/nuttx/binfmt/libelf/gnu-elf.ld new file mode 100644 index 0000000000..703f369812 --- /dev/null +++ b/nuttx/binfmt/libelf/gnu-elf.ld @@ -0,0 +1,187 @@ +/**************************************************************************** + * examples/elf/gnu-elf-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 : + { + /* 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.*) + *(.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/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c new file mode 100644 index 0000000000..44532ab88d --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_bind.c @@ -0,0 +1,106 @@ +/**************************************************************************** + * binfmt/libelf/libelf_bind.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be + * defined or CONFIG_ELF_DUMPBUFFER does nothing. + */ + +#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT) +# undef CONFIG_ELF_DUMPBUFFER +#endif + +#ifdef CONFIG_ELF_DUMPBUFFER +# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n) +#else +# define elf_dumpbuffer(m,b,n) +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_bind + * + * Description: + * Bind the imported symbol names in the loaded module described by + * 'loadinfo' using the exported symbol values provided by 'symtab'. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_bind(FAR struct elf_loadinfo_s *loadinfo, + FAR const struct symtab_s *exports, int nexports) +{ +#warning "Missing logic" + return -ENOSYS; +} + diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c new file mode 100644 index 0000000000..d72e96b622 --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_init.c @@ -0,0 +1,189 @@ +/**************************************************************************** + * binfmt/libelf/libelf_init.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be + * defined or CONFIG_ELF_DUMPBUFFER does nothing. + */ + +#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT) +# undef CONFIG_ELF_DUMPBUFFER +#endif + +#ifdef CONFIG_ELF_DUMPBUFFER +# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n) +#else +# define elf_dumpbuffer(m,b,n) +#endif + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_init + * + * Description: + * This function is called to configure the library to process an ELF + * program binary. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo) +{ + uint32_t datastart; + uint32_t dataend; + uint32_t bssstart; + uint32_t bssend; + int ret; + + bvdbg("filename: %s loadinfo: %p\n", filename, loadinfo); + + /* Clear the load info structure */ + + memset(loadinfo, 0, sizeof(struct elf_loadinfo_s)); + + /* Open the binary file */ + + loadinfo->filfd = open(filename, O_RDONLY); + if (loadinfo->filfd < 0) + { + bdbg("Failed to open ELF binary %s: %d\n", filename, ret); + return -errno; + } + + /* Read the ELF header from offset 0 */ + + ret = elf_read(loadinfo, (char*)&loadinfo->header, + sizeof(struct elf_hdr_s), 0); + if (ret < 0) + { + bdbg("Failed to read ELF header: %d\n", ret); + return ret; + } + + elf_dumpbuffer("ELF header", (FAR const uint8_t*)&loadinfo->header, + sizeof(struct elf_hdr_s)); + + /* Verify the ELF header */ + + if (elf_verifyheader(&loadinfo->header) != 0) + { + /* This is not an error because we will be called to attempt loading + * EVERY binary. Returning -ENOEXEC simply informs the system that + * the file is not an ELF file. Besides, if there is something worth + * complaining about, nelf_verifyheader() has already + * done so. + */ + + bdbg("Bad ELF header\n"); + return -ENOEXEC; + } + + /* Save all of the input values in the loadinfo structure + * and extract some additional information from the xflat + * header. Note that the information in the xflat header is in + * network order. + */ + + datastart = ntohl(loadinfo->header.h_datastart); + dataend = ntohl(loadinfo->header.h_dataend); + bssstart = dataend; + bssend = ntohl(loadinfo->header.h_bssend); + + /* And put this information into the loadinfo structure as well. + * + * Note that: + * + * isize = the address range from 0 up to datastart. + * datasize = the address range from datastart up to dataend + * bsssize = the address range from dataend up to bssend. + */ + + loadinfo->entryoffs = ntohl(loadinfo->header.h_entry); + loadinfo->isize = datastart; + + loadinfo->datasize = dataend - datastart; + loadinfo->bsssize = bssend - dataend; + loadinfo->stacksize = ntohl(loadinfo->header.h_stacksize); + + /* This is the initial dspace size. We'll re-calculate this later + * after the memory has been allocated. + */ + + loadinfo->dsize = bssend - datastart; + + /* Get the offset to the start of the relocations (we'll relocate + * this later). + */ + + loadinfo->relocstart = ntohl(loadinfo->header.h_relocstart); + loadinfo->reloccount = ntohs(loadinfo->header.h_reloccount); + + return 0; +} + diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c new file mode 100644 index 0000000000..94d200b568 --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -0,0 +1,91 @@ +/**************************************************************************** + * binfmt/libelf/libelf_load.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +#ifndef MAX +#define MAX(x,y) ((x) > (y) ? (x) : (y)) +#endif + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_load + * + * Description: + * Loads the binary into memory, allocating memory, performing relocations + * and inializing the data and bss segments. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_load(FAR struct elf_loadinfo_s *loadinfo) +{ +# warning "Missing logic" + return -ENOSYS; +} + diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c new file mode 100644 index 0000000000..5f00a531e4 --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_read.c @@ -0,0 +1,165 @@ +/**************************************************************************** + * binfmt/libelf/libelf_read.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +#undef ELF_DUMP_READDATA /* Define to dump all file data read */ +#define DUMPER lib_rawprintf /* If ELF_DUMP_READDATA is defined, this + * is the API used to dump data */ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_dumpreaddata + ****************************************************************************/ + +#if defined(ELF_DUMP_READDATA) +static inline void elf_dumpreaddata(char *buffer, int buflen) +{ + uint32_t *buf32 = (uint32_t*)buffer; + int i; + int j; + + for (i = 0; i < buflen; i += 32) + { + DUMPER("%04x:", i); + for (j = 0; j < 32; j += sizeof(uint32_t)) + { + DUMPER(" %08x", *buf32++); + } + DUMPER("\n"); + } +} +#else +# define elf_dumpreaddata(b,n) +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_read + * + * Description: + * Read 'readsize' bytes from the object file at 'offset' + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_read(struct elf_loadinfo_s *loadinfo, char *buffer, int readsize, int offset) +{ + ssize_t nbytes; /* Number of bytes read */ + off_t rpos; /* Position returned by lseek */ + char *bufptr; /* Next buffer location to read into */ + int bytesleft; /* Number of bytes of .data left to read */ + int bytesread; /* Total number of bytes read */ + + bvdbg("Read %d bytes from offset %d\n", readsize, offset); + + /* Seek to the position in the object file where the initialized + * data is saved. + */ + + bytesread = 0; + bufptr = buffer; + bytesleft = readsize; + do + { + rpos = lseek(loadinfo->filfd, offset, SEEK_SET); + if (rpos != offset) + { + bdbg("Failed to seek to position %d: %d\n", offset, errno); + return -errno; + } + + /* Read the file data at offset into the user buffer */ + + nbytes = read(loadinfo->filfd, bufptr, bytesleft); + if (nbytes < 0) + { + if (errno != EINTR) + { + bdbg("Read of .data failed: %d\n", errno); + return -errno; + } + } + else if (nbytes == 0) + { + bdbg("Unexpected end of file\n"); + return -ENODATA; + } + else + { + bytesread += nbytes; + bytesleft -= nbytes; + bufptr += nbytes; + offset += nbytes; + } + } + while (bytesread < readsize); + + elf_dumpreaddata(buffer, readsize); + return OK; +} + diff --git a/nuttx/binfmt/libelf/libelf_uninit.c b/nuttx/binfmt/libelf/libelf_uninit.c new file mode 100644 index 0000000000..cd7ae72827 --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_uninit.c @@ -0,0 +1,85 @@ +/**************************************************************************** + * binfmt/libelf/libelf_uninit.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_uninit + * + * Description: + * Releases any resources committed by elf_init(). This essentially + * undoes the actions of elf_init. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_uninit(struct elf_loadinfo_s *loadinfo) +{ + if (loadinfo->filfd >= 0) + { + close(loadinfo->filfd); + } + + return OK; +} + diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c new file mode 100644 index 0000000000..9e930e295f --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_unload.c @@ -0,0 +1,97 @@ +/**************************************************************************** + * binfmt/libelf/libelf_unload.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_unload + * + * Description: + * This function unloads the object from memory. This essentially + * undoes the actions of elf_load. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_unload(struct elf_loadinfo_s *loadinfo) +{ + /* Reset the contents of the info structure. */ + + /* Release the memory segments */ + + if (loadinfo->ispace) + { + kfree((void*)loadinfo->ispace, loadinfo->isize); + loadinfo->ispace = 0; + } + + if (loadinfo->dspace) + { + kfree((void*)loadinfo->dspace); + loadinfo->dspace = 0; + } + + return OK; +} + diff --git a/nuttx/binfmt/libelf/libelf_verify.c b/nuttx/binfmt/libelf/libelf_verify.c new file mode 100644 index 0000000000..9e265573a5 --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_verify.c @@ -0,0 +1,88 @@ +/**************************************************************************** + * binfmt/libelf/elf_verify.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_verifyheader + * + * Description: + * Given the header from a possible ELF executable, verify that it + * is an ELF executable. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_verifyheader(const struct elf_hdr_s *header) +{ + if (!header) + { + bdbg("NULL ELF header!"); + return -ENOEXEC; + } + +#warning "Missing Logic" + return -ENOSYS; +} + diff --git a/nuttx/binfmt/libnxflat/Kconfig b/nuttx/binfmt/libnxflat/Kconfig index ae2bf31307..fdb270cfb2 100644 --- a/nuttx/binfmt/libnxflat/Kconfig +++ b/nuttx/binfmt/libnxflat/Kconfig @@ -2,3 +2,8 @@ # For a description of the syntax of this configuration file, # see misc/tools/kconfig-language.txt. # + +config NXFLAT_DUMPBUFFER + bool "Dump NXFLAT buffers" + default n + depends on DEBUG && DEBUG_VERBOSE diff --git a/nuttx/binfmt/libnxflat/Make.defs b/nuttx/binfmt/libnxflat/Make.defs index f979741e51..59c3ce3344 100644 --- a/nuttx/binfmt/libnxflat/Make.defs +++ b/nuttx/binfmt/libnxflat/Make.defs @@ -1,5 +1,5 @@ ############################################################################ -# nxflat/lib/Make.defs +# binfmt/libnxflat/Make.defs # # Copyright (C) 2009 Gregory Nutt. All rights reserved. # Author: Gregory Nutt @@ -33,7 +33,21 @@ # ############################################################################ -LIBNXFLAT_ASRCS = -LIBNXFLAT_CSRCS = libnxflat_init.c libnxflat_uninit.c libnxflat_load.c \ - libnxflat_unload.c libnxflat_verify.c libnxflat_read.c \ - libnxflat_bind.c +ifeq ($(CONFIG_NXFLAT),y) + +# NXFLAT application interfaces + +BINFMT_CSRCS += nxflat.c + +# NXFLAT library + +BINFMT_CSRCS = libnxflat_init.c libnxflat_uninit.c libnxflat_load.c \ + libnxflat_unload.c libnxflat_verify.c libnxflat_read.c \ + libnxflat_bind.c + +# Hook the libnxflat subdirectory into the build + +VPATH += libnxflat +SUBDIRS += libnxflat + +endif diff --git a/nuttx/binfmt/libnxflat/libnxflat_bind.c b/nuttx/binfmt/libnxflat/libnxflat_bind.c index ca348178dd..c18a16cd8f 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_bind.c +++ b/nuttx/binfmt/libnxflat/libnxflat_bind.c @@ -263,7 +263,6 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo) result = OK; switch (NXFLAT_RELOC_TYPE(reloc.r_info)) { - /* NXFLAT_RELOC_TYPE_REL32I Meaning: Object file contains a 32-bit offset * into I-Space at the offset. * Fixup: Add mapped I-Space address to the offset. @@ -329,6 +328,7 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo) nxflat_dumpbuffer("GOT", (FAR const uint8_t*)relocs, nrelocs * sizeof(struct nxflat_reloc_s)); } #endif + return ret; } @@ -388,7 +388,7 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo, offset < loadinfo->isize + loadinfo->dsize); imports = (struct nxflat_import_s*) - (offset - loadinfo->isize + loadinfo->dspace->region); + (offset - loadinfo->isize + loadinfo->dspace->region); /* Now, traverse the list of imported symbols and attempt to bind * each symbol to the value exported by from the exported symbol @@ -396,41 +396,41 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo, */ for (i = 0; i < nimports; i++) - { - bvdbg("Import[%d] (%08p) offset: %08x func: %08x\n", - i, &imports[i], imports[i].i_funcname, imports[i].i_funcaddress); + { + bvdbg("Import[%d] (%08p) offset: %08x func: %08x\n", + i, &imports[i], imports[i].i_funcname, imports[i].i_funcaddress); - /* Get a pointer to the imported symbol name. The name itself - * lies in the TEXT segment. But the reference to the name - * lies in DATA segment. Therefore, the name reference should - * have been relocated when the module was loaded. - */ + /* Get a pointer to the imported symbol name. The name itself + * lies in the TEXT segment. But the reference to the name + * lies in DATA segment. Therefore, the name reference should + * have been relocated when the module was loaded. + */ offset = imports[i].i_funcname; DEBUGASSERT(offset < loadinfo->isize); - symname = (char*)(offset + loadinfo->ispace + sizeof(struct nxflat_hdr_s)); + symname = (char*)(offset + loadinfo->ispace + sizeof(struct nxflat_hdr_s)); - /* Find the exported symbol value for this this symbol name. */ + /* Find the exported symbol value for this this symbol name. */ #ifdef CONFIG_SYMTAB_ORDEREDBYNAME symbol = symtab_findorderedbyname(exports, symname, nexports); #else symbol = symtab_findbyname(exports, symname, nexports); #endif - if (!symbol) - { - bdbg("Exported symbol \"%s\" not found\n", symname); + if (!symbol) + { + bdbg("Exported symbol \"%s\" not found\n", symname); return -ENOENT; - } + } - /* And put this into the module's import structure. */ + /* And put this into the module's import structure. */ - imports[i].i_funcaddress = (uint32_t)symbol->sym_value; + imports[i].i_funcaddress = (uint32_t)symbol->sym_value; - bvdbg("Bound import[%d] (%08p) to export '%s' (%08x)\n", - i, &imports[i], symname, imports[i].i_funcaddress); - } + bvdbg("Bound import[%d] (%08p) to export '%s' (%08x)\n", + i, &imports[i], symname, imports[i].i_funcaddress); + } } /* Dump the relocation import table */ @@ -441,6 +441,7 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo, nxflat_dumpbuffer("Imports", (FAR const uint8_t*)imports, nimports * sizeof(struct nxflat_import_s)); } #endif + return OK; } @@ -484,9 +485,10 @@ int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo, */ memset((void*)(loadinfo->dspace->region + loadinfo->datasize), - 0, loadinfo->bsssize); + 0, loadinfo->bsssize); } } + return ret; } diff --git a/nuttx/binfmt/libnxflat/libnxflat_uninit.c b/nuttx/binfmt/libnxflat/libnxflat_uninit.c index 5d06296c79..c507fdc14c 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_uninit.c +++ b/nuttx/binfmt/libnxflat/libnxflat_uninit.c @@ -56,10 +56,6 @@ * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: nxflat_swap32 - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/nuttx/binfmt/libnxflat/libnxflat_verify.c b/nuttx/binfmt/libnxflat/libnxflat_verify.c index f799aca4f6..da25d21c71 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_verify.c +++ b/nuttx/binfmt/libnxflat/libnxflat_verify.c @@ -91,10 +91,10 @@ int nxflat_verifyheader(const struct nxflat_hdr_s *header) if (strncmp(header->h_magic, NXFLAT_MAGIC, 4) != 0) { bdbg("Unrecognized magic=\"%c%c%c%c\"\n", - header->h_magic[0], header->h_magic[1], - header->h_magic[2], header->h_magic[3]); + header->h_magic[0], header->h_magic[1], + header->h_magic[2], header->h_magic[3]); return -ENOEXEC; } + return OK; } - diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs index 55da02a154..eebe11c22a 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/lpcxpresso-lpc1768/dhcpd/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/dhcpd/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/dhcpd/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs index 52831a2794..c8fb0e9aec 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/lpcxpresso-lpc1768/nsh/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/ld.script b/nuttx/configs/lpcxpresso-lpc1768/nsh/ld.script deleted file mode 100755 index f37c4accb0..0000000000 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/ld.script +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * configs/lpcxpresso-lpc1768/nsh/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The LPC1768 has 512Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/lpcxpresso-lpc1768/nx/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs index 59aeb51875..b0334ba46d 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/lpcxpresso-lpc1768/nx/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nx/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nx/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/ld.script b/nuttx/configs/lpcxpresso-lpc1768/nx/ld.script deleted file mode 100755 index f1a49e3aab..0000000000 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/ld.script +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * configs/lpcxpresso-lpc1768/nx/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The LPC1768 has 512Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/lpcxpresso-lpc1768/ostest/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs index 6d228a9363..1e1f2d9795 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/lpcxpresso-lpc1768/ostest/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/ld.script b/nuttx/configs/lpcxpresso-lpc1768/ostest/ld.script deleted file mode 100755 index da29a1482e..0000000000 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/ld.script +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * configs/lpcxpresso-lpc1768/ostest/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The LPC1768 has 512Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/lpcxpresso-lpc1768/dhcpd/ld.script b/nuttx/configs/lpcxpresso-lpc1768/scripts/ld.script similarity index 95% rename from nuttx/configs/lpcxpresso-lpc1768/dhcpd/ld.script rename to nuttx/configs/lpcxpresso-lpc1768/scripts/ld.script index d8f4444753..bdfa155476 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/ld.script +++ b/nuttx/configs/lpcxpresso-lpc1768/scripts/ld.script @@ -1,7 +1,7 @@ /**************************************************************************** - * configs/lpcxpresso-lpc1768/dhcpd/ld.script + * configs/lpcxpresso-lpc1768/scripts/ld.script * - * 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 @@ -94,7 +94,8 @@ SECTIONS _ebss = ABSOLUTE(.); } > sram - /* Stabs debugging sections. */ + /* Stabs debugging sections */ + .stab 0 : { *(.stab) } .stabstr 0 : { *(.stabstr) } .stab.excl 0 : { *(.stab.excl) } diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs index 0f3212522f..93bcfa376e 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs @@ -86,7 +86,7 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 NXFLATLDSCRIPT = -T "${shell cygpath -w $(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld}" else @@ -94,7 +94,7 @@ else 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 + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script NXFLATLDSCRIPT = -T"$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld" endif diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/ld.script b/nuttx/configs/lpcxpresso-lpc1768/thttpd/ld.script deleted file mode 100755 index 37ec255327..0000000000 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/ld.script +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * configs/lpcxpresso-lpc1768/thttpd/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The LPC1768 has 512Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/lpcxpresso-lpc1768/usbstorage/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs index 793dfcdf19..e546666e75 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/lpcxpresso-lpc1768/usbstorage/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 @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/usbstorage/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/usbstorage/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/ld.script b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/ld.script deleted file mode 100755 index 7cccb8421f..0000000000 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/ld.script +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * configs/lpcxpresso-lpc1768/usbstorage/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The LPC1768 has 512Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/include/elf.h b/nuttx/include/elf.h new file mode 100644 index 0000000000..8d6539c36c --- /dev/null +++ b/nuttx/include/elf.h @@ -0,0 +1,53 @@ +/**************************************************************************** + * include/elf.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __INCLUDE_ELF_H +#define __INCLUDE_ELF_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +#endif /* __INCLUDE_ELF_H */ diff --git a/nuttx/include/nuttx/elf.h b/nuttx/include/nuttx/elf.h new file mode 100644 index 0000000000..4be2c23a04 --- /dev/null +++ b/nuttx/include/nuttx/elf.h @@ -0,0 +1,259 @@ +/**************************************************************************** + * include/nuttx/elf.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __INCLUDE_NUTTX_ELF_H +#define __INCLUDE_NUTTX_ELF_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* This struct provides a desciption of the currently loaded instantiation + * of an ELF binary. + */ + +struct elf_loadinfo_s +{ + /* Instruction Space (ISpace): This region contains the ELF file header + * plus everything from the text section. Ideally, will have only one mmap'ed + * text section instance in the system for each module. + */ + + uint32_t ispace; /* Address where hdr/text is loaded */ + uint32_t entryoffs; /* Offset from ispace to entry point */ + uint32_t isize; /* Size of ispace. */ + + /* Data Space (DSpace): This region contains all information that in referenced + * as data (other than the stack which is separately allocated). There will be + * a unique instance of DSpace (and stack) for each instance of a process. + */ + + FAR struct dspace_s *dspace; /* Allocated D-Space (data/bss/etc) */ + uint32_t datasize; /* Size of data segment in dspace */ + uint32_t bsssize; /* Size of bss segment in dspace */ + uint32_t stacksize; /* Size of stack (not allocated) */ + uint32_t dsize; /* Size of dspace (may be large than parts) */ + + /* This is temporary memory where relocation records will be loaded. */ + + uint32_t relocstart; /* Start of array of struct flat_reloc */ + uint16_t reloccount; /* Number of elements in reloc array */ + + /* File descriptors */ + + int filfd; /* Descriptor for the file being loaded */ + + /* This is a copy of the ELF header (still in network order) */ + + FAR struct elf_hdr_s header; +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * These are APIs exported by libelf (and may be used outside of NuttX): + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_verifyheader + * + * Description: + * Given the header from a possible ELF executable, verify that it is + * an ELF executable. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +EXTERN int elf_verifyheader(FAR const struct elf_hdr_s *header); + +/**************************************************************************** + * Name: elf_init + * + * Description: + * This function is called to configure the library to process an ELF + * program binary. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +EXTERN int elf_init(FAR const char *filename, + FAR struct elf_loadinfo_s *loadinfo); + +/**************************************************************************** + * Name: elf_uninit + * + * Description: + * Releases any resources committed by elf_init(). This essentially + * undoes the actions of elf_init. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +EXTERN int elf_uninit(FAR struct elf_loadinfo_s *loadinfo); + +/**************************************************************************** + * Name: elf_load + * + * Description: + * Loads the binary into memory, allocating memory, performing relocations + * and inializing the data and bss segments. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +EXTERN int elf_load(FAR struct elf_loadinfo_s *loadinfo); + +/**************************************************************************** + * Name: elf_read + * + * Description: + * Read 'readsize' bytes from the object file at 'offset' + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +EXTERN int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR char *buffer, + FAR int readsize, int offset); + +/**************************************************************************** + * Name: elf_bind + * + * Description: + * Bind the imported symbol names in the loaded module described by + * 'loadinfo' using the exported symbol values provided by 'symtab'. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +struct symtab_s; +EXTERN int elf_bind(FAR struct elf_loadinfo_s *loadinfo, + FAR const struct symtab_s *exports, int nexports); + +/**************************************************************************** + * Name: elf_unload + * + * Description: + * This function unloads the object from memory. This essentially + * undoes the actions of elf_load. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +EXTERN int elf_unload(struct elf_loadinfo_s *loadinfo); + +/**************************************************************************** + * These are APIs used internally only by NuttX: + ****************************************************************************/ +/**************************************************************************** + * Name: elf_initialize + * + * Description: + * ELF support is built unconditionally. However, it order to + * use this binary format, this function must be called during system + * format in order to register the ELF binary format. + * + * Returned Value: + * This is a NuttX internal function so it follows the convention that + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +EXTERN int elf_initialize(void); + +/**************************************************************************** + * Name: elf_uninitialize + * + * Description: + * Unregister the ELF binary loader + * + * Returned Value: + * None + * + ****************************************************************************/ + +EXTERN void elf_uninitialize(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __INCLUDE_NUTTX_ELF_H */ diff --git a/nuttx/include/nuttx/nxflat.h b/nuttx/include/nuttx/nxflat.h index b6501522ef..59dcea854a 100644 --- a/nuttx/include/nuttx/nxflat.h +++ b/nuttx/include/nuttx/nxflat.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/nuttx/nxflat.h * - * 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 @@ -110,22 +110,22 @@ extern "C" { * These are APIs exported by libnxflat (and may be used outside of NuttX): ****************************************************************************/ -/*********************************************************************** +/**************************************************************************** * Name: nxflat_verifyheader * * Description: - * Given the header from a possible NXFLAT executable, verify that it - * is an NXFLAT executable. + * Given the header from a possible NXFLAT executable, verify that it is + * an NXFLAT executable. * * Returned Value: * 0 (OK) is returned on success and a negated errno is returned on * failure. * - ***********************************************************************/ + ****************************************************************************/ EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header); -/*********************************************************************** +/**************************************************************************** * Name: nxflat_init * * Description: @@ -136,12 +136,12 @@ EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header); * 0 (OK) is returned on success and a negated errno is returned on * failure. * - ***********************************************************************/ + ****************************************************************************/ EXTERN int nxflat_init(const char *filename, struct nxflat_loadinfo_s *loadinfo); -/*********************************************************************** +/**************************************************************************** * Name: nxflat_uninit * * Description: @@ -152,11 +152,11 @@ EXTERN int nxflat_init(const char *filename, * 0 (OK) is returned on success and a negated errno is returned on * failure. * - ***********************************************************************/ + ****************************************************************************/ EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo); -/*********************************************************************** +/**************************************************************************** * Name: nxflat_load * * Description: @@ -170,11 +170,11 @@ EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo); * 0 (OK) is returned on success and a negated errno is returned on * failure. * - ***********************************************************************/ + ****************************************************************************/ EXTERN int nxflat_load(struct nxflat_loadinfo_s *loadinfo); -/*********************************************************************** +/**************************************************************************** * Name: nxflat_read * * Description: @@ -184,12 +184,12 @@ EXTERN int nxflat_load(struct nxflat_loadinfo_s *loadinfo); * 0 (OK) is returned on success and a negated errno is returned on * failure. * - ***********************************************************************/ + ****************************************************************************/ EXTERN int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, int readsize, int offset); -/*********************************************************************** +/**************************************************************************** * Name: nxflat_bind * * Description: @@ -202,13 +202,13 @@ EXTERN int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, * 0 (OK) is returned on success and a negated errno is returned on * failure. * - ***********************************************************************/ + ****************************************************************************/ struct symtab_s; EXTERN int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo, FAR const struct symtab_s *exports, int nexports); -/*********************************************************************** +/**************************************************************************** * Name: nxflat_unload * * Description: @@ -219,14 +219,14 @@ EXTERN int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo, * 0 (OK) is returned on success and a negated errno is returned on * failure. * - ***********************************************************************/ + ****************************************************************************/ EXTERN int nxflat_unload(struct nxflat_loadinfo_s *loadinfo); /**************************************************************************** * These are APIs used internally only by NuttX: ****************************************************************************/ -/*********************************************************************** +/**************************************************************************** * Name: nxflat_initialize * * Description: @@ -239,7 +239,7 @@ EXTERN int nxflat_unload(struct nxflat_loadinfo_s *loadinfo); * 0 (OK) is returned on success and a negated errno is returned on * failure. * - ***********************************************************************/ + ****************************************************************************/ EXTERN int nxflat_initialize(void); From bd76ec3dc037b6bd3aba883118cbac51510b80fa Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 24 Oct 2012 18:22:15 +0000 Subject: [PATCH 020/206] Flesh out include/elf.h git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5251 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/binfmt/libelf/arm.h | 53 +++++++ nuttx/binfmt/libelf/libelf.h | 53 +++++++ nuttx/include/elf.h | 279 ++++++++++++++++++++++++++++++++++- 3 files changed, 384 insertions(+), 1 deletion(-) create mode 100644 nuttx/binfmt/libelf/arm.h create mode 100644 nuttx/binfmt/libelf/libelf.h diff --git a/nuttx/binfmt/libelf/arm.h b/nuttx/binfmt/libelf/arm.h new file mode 100644 index 0000000000..e80457b6e4 --- /dev/null +++ b/nuttx/binfmt/libelf/arm.h @@ -0,0 +1,53 @@ +/**************************************************************************** + * binfmt/libelf/arm.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __BINFMT_LIBELF_ARM_H +#define __BINFMT_LIBELF_ARM_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +#endif /* __BINFMT_LIBELF_ARM_H */ diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h new file mode 100644 index 0000000000..80d971bca2 --- /dev/null +++ b/nuttx/binfmt/libelf/libelf.h @@ -0,0 +1,53 @@ +/**************************************************************************** + * binfmt/libelf/libelf.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __BINFMT_LIBELF_LIBELF_H +#define __BINFMT_LIBELF_LIBELF_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +#endif /* __BINFMT_LIBELF_LIBELF_H */ diff --git a/nuttx/include/elf.h b/nuttx/include/elf.h index 8d6539c36c..31818249fa 100644 --- a/nuttx/include/elf.h +++ b/nuttx/include/elf.h @@ -4,6 +4,9 @@ * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * + * Reference: System V Application Binary Interface, Edition 4.1, March 18, + * 1997, The Santa Cruz Operation, Inc. + * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: @@ -42,12 +45,286 @@ #include +#include + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ /**************************************************************************** - * Public Types + * Pre-processor Definitions ****************************************************************************/ +/* Values for Elf32_Ehdr::e_type */ + +#define ET_NONE 0 /* No file type */ +#define ET_REL 1 /* Relocatable file */ +#define ET_EXEC 2 /* Executable file */ +#define ET_DYN 3 /* Shared object file */ +#define ET_CORE 4 /* Core file */ +#define ET_LOPROC 0xff00 /* Processor-specific */ +#define ET_HIPROC 0xffff /* Processor-specific */ + +/* Values for Elf32_Ehdr::e_machine */ + +#define EM_NONE 0 /* No machine */ +#define EM_M32 1 /* AT&T WE 32100 */ +#define EM_SPARC 2 /* SPARC */ +#define EM_386 3 /* Intel 80386 */ +#define EM_68K 4 /* Motorola 68000 */ +#define EM_88K 5 /* Motorola 88000 */ +#define EM_860 7 /* Intel 80860 */ +#define EM_MIPS 8 /* MIPS RS3000 Big-Endian */ +#define EM_MIPS_RS4_BE 10 /* MIPS RS4000 Big-Endian */ + /* 11-16 Reserved for future use */ + +/* Values for Elf32_Ehdr::e_version */ + +#define EV_NONE 0 /* Invalid version */ +#define EV_CURRENT 1 /* The current version */ + +/* Ehe ELF identifier */ + +#define EI_MAG0 0 /* File identification */ +#define EI_MAG1 1 /* File identification */ +#define EI_MAG2 2 /* File identification */ +#define EI_MAG3 3 /* File identification */ +#define EI_CLASS 4 /* File class */ +#define EI_DATA 5 /* Data encoding */ +#define EI_VERSION 6 /* File version */ +#define EI_PAD 7 /* Start of padding bytes */ +#define EI_NIDENT 16 /* Size of eident[] */ + +#define EI_MAGIC { 0x7f, 'E', 'L', 'F' } + +/* Values for EI_CLASS */ + +#define ELFCLASSNONE 0 /* Invalid class */ +#define ELFCLASS32 1 /* 32-bit objects */ +#define ELFCLASS64 2 /* 64-bit objects */ + +/* Values for EI_DATA */ + +#define ELFDATANONE 0 /* Invalid data encoding */ +#define ELFDATA2LSB 1 /* Least significant byte occupying the lowest address */ +#define ELFDATA2MSB 2 /* Most significant byte occupying the lowest address */ + +/* Figure 4-7: Special Section Indexes */ + +#define SHN_UNDEF 0 +#define SHN_LORESERVE 0xff00 +#define SHN_LOPROC 0xff00 +#define SHN_HIPROC 0xff1f +#define SHN_ABS 0xfff1 +#define SHN_COMMON 0xfff2 +#define SHN_HIRESERVE 0xffff + +/* Figure 4-9: Section Types, sh_type */ + +#define SHT_NULL 0 +#define SHT_PROGBITS 1 +#define SHT_SYMTAB 2 +#define SHT_STRTAB 3 +#define SHT_RELA 4 +#define SHT_HASH 5 +#define SHT_DYNAMIC 6 +#define SHT_NOTE 7 +#define SHT_NOBITS 8 +#define SHT_REL 9 +#define SHT_SHLIB 10 +#define SHT_DYNSYM 11 +#define SHT_LOPROC 0x70000000 +#define SHT_HIPROC 0x7fffffff +#define SHT_LOUSER 0x80000000 +#define SHT_HIUSER 0xffffffff + +/* Figure 4-11: Section Attribute Flags, sh_flags */ + +#define SHF_WRITE 1 +#define SHF_ALLOC 2 +#define SHF_EXECINSTR 4 +#define SHF_MASKPROC 0xf0000000 + +/* Definitions for Elf32_Sym::st_info */ + +#define ELF32_ST_BIND(i) ((i)>>4) +#define ELF32_ST_TYPE(i) ((i)&0xf) +#define ELF32_ST_INFO(b,t) (((b)<<4)+((t)&0xf)) + +/* Figure 4-16: Symbol Binding, ELF32_ST_BIND */ + +#define STB_LOCAL 0 +#define STB_GLOBAL 1 +#define STB_WEAK 2 +#define STB_LOPROC 13 +#define STB_HIPROC 15 + +/* Figure 4-17: Symbol Types, ELF32_ST_TYPE */ + +#define STT_NOTYPE 0 +#define STT_OBJECT 1 +#define STT_FUNC 2 +#define STT_SECTION 3 +#define STT_FILE 4 +#define STT_LOPROC 13 +#define STT_HIPROC 15 + +/* Definitions for Elf32_Rel*::r_info */ + +#define ELF32_R_SYM(i) ((i)>>8) +#define ELF32_R_TYPE(i) ((unsigned char)(i)) +#define ELF32_R_INFO(s,t) (((s)<<8)+(unsigned char)(t)) + +/* Figure 5-2: Segment Types, p_type */ + +#define PT_NULL 0 +#define PT_LOAD 1 +#define PT_DYNAMIC 2 +#define PT_INTERP 3 +#define PT_NOTE 4 +#define PT_SHLIB 5 +#define PT_PHDR 6 +#define PT_LOPROC 0x70000000 +#define PT_HIPROC 0x7fffffff + +/* Figure 5-3: Segment Flag Bits, p_flags */ + +#define PF_X 1 /* Execute */ +#define PF_W 2 /* Write */ +#define PF_R 4 /* Read */ +#define PF_MASKPROC 0xf0000000 /* Unspecified */ + +/* Figure 5-10: Dynamic Array Tags, d_tag */ + +#define DT_NULL 0 /* d_un=ignored */ +#define DT_NEEDED 1 /* d_un=d_val */ +#define DT_PLTRELSZ 2 /* d_un=d_val */ +#define DT_PLTGOT 3 /* d_un=d_ptr */ +#define DT_HASH 4 /* d_un=d_ptr */ +#define DT_STRTAB 5 /* d_un=d_ptr */ +#define DT_SYMTAB 6 /* d_un=d_ptr */ +#define DT_RELA 7 /* d_un=d_ptr */ +#define DT_RELASZ 8 /* d_un=d_val */ +#define DT_RELAENT 9 /* d_un=d_val */ +#define DT_STRSZ 10 /* d_un=d_val */ +#define DT_SYMENT 11 /* d_un=d_val */ +#define DT_INIT 12 /* d_un=d_ptr */ +#define DT_FINI 13 /* d_un=d_ptr */ +#define DT_SONAME 14 /* d_un=d_val */ +#define DT_RPATH 15 /* d_un=d_val */ +#define DT_SYMBOLIC 16 /* d_un=ignored */ +#define DT_REL 17 /* d_un=d_ptr */ +#define DT_RELSZ 18 /* d_un=d_val */ +#define DT_RELENT 19 /* d_un=d_val */ +#define DT_PLTREL 20 /* d_un=d_val */ +#define DT_DEBUG 21 /* d_un=d_ptr */ +#define DT_TEXTREL 22 /* d_un=ignored */ +#define DT_JMPREL 23 /* d_un=d_ptr */ +#define DT_BINDNOW 24 /* d_un=ignored */ +#define DT_LOPROC 0x70000000 /* d_un=unspecified */ +#define DT_HIPROC 0x7fffffff /* d_un= unspecified */ + +/**************************************************************************** + * Public Type Definitions + ****************************************************************************/ + +/* Figure 4.2: 32-Bit Data Types */ + +typedef uint32_t ELF32_Addr /* Unsigned program address */ +typedef uint16_t ELF32_Half /* Unsigned medium integer */ +typedef uint32_t ELF32_Off /* Unsigned file offset */ +typedef int32_t ELF32_Sword /* Signed large integer */ +typedef uint32_t ELF32_Word /* Unsigned large integer */ + +/* Figure 4-3: ELF Header */ + +typedef struct +{ + unsigned char e_ident[EI_NIDENT]; + ELF32_Half e_type; + ELF32_Half e_machine; + ELF32_Word e_version; + ELF32_Addr e_entry; + ELF32_Off e_phoff; + ELF32_Off e_shoff; + ELF32_Word e_flags; + ELF32_Half e_ehsize; + ELF32_Half e_phentsize; + ELF32_Half e_phnum; + ELF32_Half e_shentsize; + ELF32_Half e_shnum; + ELF32_Half e_shstrndx; +} Elf32_Ehdr; + +/* Figure 4-8: Section Header */ + +typedef struct +{ + ELF32_Word sh_name; + ELF32_Word sh_type; + ELF32_Word sh_flags; + ELF32_Addr sh_addr; + ELF32_Off sh_offset; + ELF32_Word sh_size; + ELF32_Word sh_link; + ELF32_Word sh_info; + ELF32_Word sh_addralign; + ELF32_Word sh_entsize; +} Elf32_Shdr; + +/* Figure 4-15: Symbol Table Entry */ + +typedef struct +{ + ELF32_Word st_name; + ELF32_Addr st_value; + ELF32_Word st_size; + unsigned char st_info; + unsigned char st_other; + ELF32_Half st_shndx; +} Elf32_Sym; + +/* Figure 4-19: Relocation Entries */ + +typedef struct +{ + ELF32_Addr r_offset; + ELF32_Word r_info; +} Elf32_Rel; + +typedef struct +{ + ELF32_Addr r_offset; + ELF32_Word r_info; + ELF32_Sword r_addend; +} Elf32_Rela; + +/* Figure 5-1: Program Header */ + +typedef struct +{ + Elf32_Word p_type; + Elf32_Off p_offset; + Elf32_Addr p_vaddr; + Elf32_Addr p_paddr; + Elf32_Word p_filesz; + Elf32_Word p_memsz; + Elf32_Word p_flags; + Elf32_Word p_align; +} Elf32_Phdr; + +/* Figure 5-9: Dynamic Structure */ + +typedef struct +{ + Elf32_Sword d_tag; + union + { + Elf32_Word d_val; + Elf32_Addr d_ptr; + } d_un; +} Elf32_Dyn; + +//extern Elf32_Dyn _DYNAMIC[] ; + #endif /* __INCLUDE_ELF_H */ From 8a2348d18d16427d0787d3614aa90ab20e4b4eda Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 24 Oct 2012 20:19:44 +0000 Subject: [PATCH 021/206] Move binfmt.h, nxflat.h, elf.h, and symtab.h to include/nuttx/binfmt/ git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5252 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/nxflat/nxflat_main.c | 4 ++-- apps/examples/nxflat/tests/mksymtab.sh | 2 +- apps/examples/thttpd/content/mksymtab.sh | 2 +- apps/examples/thttpd/thttpd_main.c | 4 ++-- apps/include/netutils/thttpd.h | 2 +- apps/netutils/thttpd/thttpd.c | 2 +- apps/netutils/thttpd/thttpd_cgi.c | 4 ++-- nuttx/ChangeLog | 3 +++ nuttx/Documentation/NuttXNxFlat.html | 12 ++++++------ nuttx/binfmt/binfmt_dumpmodule.c | 2 +- nuttx/binfmt/binfmt_exec.c | 2 +- nuttx/binfmt/binfmt_execmodule.c | 2 +- nuttx/binfmt/binfmt_globals.c | 2 +- nuttx/binfmt/binfmt_internal.h | 2 +- nuttx/binfmt/binfmt_loadmodule.c | 2 +- nuttx/binfmt/binfmt_register.c | 2 +- nuttx/binfmt/binfmt_unloadmodule.c | 2 +- nuttx/binfmt/binfmt_unregister.c | 2 +- nuttx/binfmt/elf.c | 4 ++-- nuttx/binfmt/libelf/libelf_bind.c | 4 ++-- nuttx/binfmt/libelf/libelf_init.c | 8 +++----- nuttx/binfmt/libelf/libelf_load.c | 2 +- nuttx/binfmt/libelf/libelf_read.c | 2 +- nuttx/binfmt/libelf/libelf_uninit.c | 2 +- nuttx/binfmt/libelf/libelf_unload.c | 2 +- nuttx/binfmt/libelf/libelf_verify.c | 4 ++-- nuttx/binfmt/libnxflat/libnxflat_bind.c | 4 ++-- nuttx/binfmt/libnxflat/libnxflat_init.c | 2 +- nuttx/binfmt/libnxflat/libnxflat_load.c | 2 +- nuttx/binfmt/libnxflat/libnxflat_read.c | 2 +- nuttx/binfmt/libnxflat/libnxflat_uninit.c | 3 ++- nuttx/binfmt/libnxflat/libnxflat_unload.c | 2 +- nuttx/binfmt/libnxflat/libnxflat_verify.c | 3 ++- nuttx/binfmt/nxflat.c | 4 ++-- nuttx/binfmt/symtab_findbyname.c | 2 +- nuttx/binfmt/symtab_findbyvalue.c | 2 +- nuttx/binfmt/symtab_findorderedbyname.c | 2 +- nuttx/binfmt/symtab_findorderedbyvalue.c | 2 +- nuttx/include/nuttx/{ => binfmt}/binfmt.h | 10 +++++----- nuttx/include/nuttx/{ => binfmt}/elf.h | 16 ++++++++-------- nuttx/include/nuttx/{ => binfmt}/nxflat.h | 8 ++++---- nuttx/include/nuttx/{ => binfmt}/symtab.h | 8 ++++---- nuttx/tools/mksymtab.c | 2 +- 43 files changed, 79 insertions(+), 76 deletions(-) rename nuttx/include/nuttx/{ => binfmt}/binfmt.h (97%) rename nuttx/include/nuttx/{ => binfmt}/elf.h (96%) rename nuttx/include/nuttx/{ => binfmt}/nxflat.h (98%) rename nuttx/include/nuttx/{ => binfmt}/symtab.h (97%) diff --git a/apps/examples/nxflat/nxflat_main.c b/apps/examples/nxflat/nxflat_main.c index 4cd2cd5375..2c0030c608 100644 --- a/apps/examples/nxflat/nxflat_main.c +++ b/apps/examples/nxflat/nxflat_main.c @@ -50,8 +50,8 @@ #include #include -#include -#include +#include +#include #include "tests/romfs.h" #include "tests/dirlist.h" diff --git a/apps/examples/nxflat/tests/mksymtab.sh b/apps/examples/nxflat/tests/mksymtab.sh index 611d3a87a0..4b5347f17f 100755 --- a/apps/examples/nxflat/tests/mksymtab.sh +++ b/apps/examples/nxflat/tests/mksymtab.sh @@ -22,7 +22,7 @@ varlist=`find $dir -name "*-thunk.S"| xargs grep -h asciz | cut -f3 | sort | uni echo "#ifndef __EXAMPLES_NXFLAT_TESTS_SYMTAB_H" echo "#define __EXAMPLES_NXFLAT_TESTS_SYMTAB_H" echo "" -echo "#include " +echo "#include " echo "" echo "static const struct symtab_s exports[] = " echo "{" diff --git a/apps/examples/thttpd/content/mksymtab.sh b/apps/examples/thttpd/content/mksymtab.sh index 611d3a87a0..4b5347f17f 100755 --- a/apps/examples/thttpd/content/mksymtab.sh +++ b/apps/examples/thttpd/content/mksymtab.sh @@ -22,7 +22,7 @@ varlist=`find $dir -name "*-thunk.S"| xargs grep -h asciz | cut -f3 | sort | uni echo "#ifndef __EXAMPLES_NXFLAT_TESTS_SYMTAB_H" echo "#define __EXAMPLES_NXFLAT_TESTS_SYMTAB_H" echo "" -echo "#include " +echo "#include " echo "" echo "static const struct symtab_s exports[] = " echo "{" diff --git a/apps/examples/thttpd/thttpd_main.c b/apps/examples/thttpd/thttpd_main.c index b31d0a8642..97f922a768 100644 --- a/apps/examples/thttpd/thttpd_main.c +++ b/apps/examples/thttpd/thttpd_main.c @@ -56,8 +56,8 @@ #include #include -#include -#include +#include +#include #ifdef CONFIG_NET_SLIP # include #endif diff --git a/apps/include/netutils/thttpd.h b/apps/include/netutils/thttpd.h index 92ed7ba974..217914c332 100644 --- a/apps/include/netutils/thttpd.h +++ b/apps/include/netutils/thttpd.h @@ -42,7 +42,7 @@ #include -#include +#include /**************************************************************************** * Public Data diff --git a/apps/netutils/thttpd/thttpd.c b/apps/netutils/thttpd/thttpd.c index 1b074902de..a04a932bf7 100644 --- a/apps/netutils/thttpd/thttpd.c +++ b/apps/netutils/thttpd/thttpd.c @@ -54,7 +54,7 @@ #include #include -#include +#include #include #include "config.h" diff --git a/apps/netutils/thttpd/thttpd_cgi.c b/apps/netutils/thttpd/thttpd_cgi.c index 9c0de509bd..31b1e0d8dd 100644 --- a/apps/netutils/thttpd/thttpd_cgi.c +++ b/apps/netutils/thttpd/thttpd_cgi.c @@ -53,8 +53,8 @@ #include #include -#include -#include +#include +#include #include #include "config.h" diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 59fa735449..c2c9a1413a 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3511,3 +3511,6 @@ * binfmt/elf.c, binfmt/libelf, include/elf.h, include/nuttx/elf.h: Add basic framework for loadable ELF module support. The initial check- in is non-functional and is simply the framework for ELF support. + * include/nuttx/binfmt.h, nxflat.h, elf.h, and symtab.h: Moved to + include/nuttx/binfmt/. + diff --git a/nuttx/Documentation/NuttXNxFlat.html b/nuttx/Documentation/NuttXNxFlat.html index c51e3b6a1d..2e6d2f59a8 100644 --- a/nuttx/Documentation/NuttXNxFlat.html +++ b/nuttx/Documentation/NuttXNxFlat.html @@ -554,19 +554,19 @@ cat ../syscall/syscall.csv ../lib/lib.csv | sort >tmp.csv diff --git a/nuttx/binfmt/binfmt_dumpmodule.c b/nuttx/binfmt/binfmt_dumpmodule.c index 32a3fef3e3..06e97e4572 100644 --- a/nuttx/binfmt/binfmt_dumpmodule.c +++ b/nuttx/binfmt/binfmt_dumpmodule.c @@ -43,7 +43,7 @@ #include #include -#include +#include #include "binfmt_internal.h" diff --git a/nuttx/binfmt/binfmt_exec.c b/nuttx/binfmt/binfmt_exec.c index c070324c31..60e8d8efde 100644 --- a/nuttx/binfmt/binfmt_exec.c +++ b/nuttx/binfmt/binfmt_exec.c @@ -44,7 +44,7 @@ #include #include -#include +#include #include "binfmt_internal.h" diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c index 1b511b0cb8..bc76d4acfc 100644 --- a/nuttx/binfmt/binfmt_execmodule.c +++ b/nuttx/binfmt/binfmt_execmodule.c @@ -47,7 +47,7 @@ #include #include -#include +#include #include "os_internal.h" #include "binfmt_internal.h" diff --git a/nuttx/binfmt/binfmt_globals.c b/nuttx/binfmt/binfmt_globals.c index 069d3a2aa9..d3246bd506 100644 --- a/nuttx/binfmt/binfmt_globals.c +++ b/nuttx/binfmt/binfmt_globals.c @@ -39,7 +39,7 @@ #include -#include +#include #ifndef CONFIG_BINFMT_DISABLE diff --git a/nuttx/binfmt/binfmt_internal.h b/nuttx/binfmt/binfmt_internal.h index da67f5350b..4fab9724d4 100644 --- a/nuttx/binfmt/binfmt_internal.h +++ b/nuttx/binfmt/binfmt_internal.h @@ -42,7 +42,7 @@ #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/binfmt_loadmodule.c b/nuttx/binfmt/binfmt_loadmodule.c index 01ab8cc883..e87075aa90 100644 --- a/nuttx/binfmt/binfmt_loadmodule.c +++ b/nuttx/binfmt/binfmt_loadmodule.c @@ -43,7 +43,7 @@ #include #include -#include +#include #include "binfmt_internal.h" diff --git a/nuttx/binfmt/binfmt_register.c b/nuttx/binfmt/binfmt_register.c index 7f6eef671a..925f29353f 100644 --- a/nuttx/binfmt/binfmt_register.c +++ b/nuttx/binfmt/binfmt_register.c @@ -44,7 +44,7 @@ #include #include -#include +#include #include "binfmt_internal.h" diff --git a/nuttx/binfmt/binfmt_unloadmodule.c b/nuttx/binfmt/binfmt_unloadmodule.c index 04859a2910..0de9dfccd1 100644 --- a/nuttx/binfmt/binfmt_unloadmodule.c +++ b/nuttx/binfmt/binfmt_unloadmodule.c @@ -45,7 +45,7 @@ #include #include -#include +#include #include "binfmt_internal.h" diff --git a/nuttx/binfmt/binfmt_unregister.c b/nuttx/binfmt/binfmt_unregister.c index b97b9b67dd..f895e354d0 100644 --- a/nuttx/binfmt/binfmt_unregister.c +++ b/nuttx/binfmt/binfmt_unregister.c @@ -44,7 +44,7 @@ #include #include -#include +#include #include "binfmt_internal.h" diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c index 74a35174f3..fb3b5acd23 100644 --- a/nuttx/binfmt/elf.c +++ b/nuttx/binfmt/elf.c @@ -47,8 +47,8 @@ #include #include -#include -#include +#include +#include #ifdef CONFIG_ELF diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c index 44532ab88d..87afe79c9f 100644 --- a/nuttx/binfmt/libelf/libelf_bind.c +++ b/nuttx/binfmt/libelf/libelf_bind.c @@ -47,8 +47,8 @@ #include #include -#include -#include +#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c index d72e96b622..71b6b92272 100644 --- a/nuttx/binfmt/libelf/libelf_init.c +++ b/nuttx/binfmt/libelf/libelf_init.c @@ -48,7 +48,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions @@ -118,16 +118,14 @@ int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo) /* Read the ELF header from offset 0 */ - ret = elf_read(loadinfo, (char*)&loadinfo->header, - sizeof(struct elf_hdr_s), 0); + ret = elf_read(loadinfo, (char*)&loadinfo->header, sizeof(Elf32_Ehdr), 0); if (ret < 0) { bdbg("Failed to read ELF header: %d\n", ret); return ret; } - elf_dumpbuffer("ELF header", (FAR const uint8_t*)&loadinfo->header, - sizeof(struct elf_hdr_s)); + elf_dumpbuffer("ELF header", (FAR const uint8_t*)&loadinfo->header, sizeof(Elf32_Ehdr)); /* Verify the ELF header */ diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 94d200b568..26785f6b1c 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -48,7 +48,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c index 5f00a531e4..3770301747 100644 --- a/nuttx/binfmt/libelf/libelf_read.c +++ b/nuttx/binfmt/libelf/libelf_read.c @@ -48,7 +48,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/nuttx/binfmt/libelf/libelf_uninit.c b/nuttx/binfmt/libelf/libelf_uninit.c index cd7ae72827..e5fa2e6c33 100644 --- a/nuttx/binfmt/libelf/libelf_uninit.c +++ b/nuttx/binfmt/libelf/libelf_uninit.c @@ -42,7 +42,7 @@ #include #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c index 9e930e295f..9a198fc780 100644 --- a/nuttx/binfmt/libelf/libelf_unload.c +++ b/nuttx/binfmt/libelf/libelf_unload.c @@ -43,7 +43,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/nuttx/binfmt/libelf/libelf_verify.c b/nuttx/binfmt/libelf/libelf_verify.c index 9e265573a5..9139700b34 100644 --- a/nuttx/binfmt/libelf/libelf_verify.c +++ b/nuttx/binfmt/libelf/libelf_verify.c @@ -43,7 +43,7 @@ #include #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions @@ -74,7 +74,7 @@ * ****************************************************************************/ -int elf_verifyheader(const struct elf_hdr_s *header) +int elf_verifyheader(const Elf32_Ehdr *header) { if (!header) { diff --git a/nuttx/binfmt/libnxflat/libnxflat_bind.c b/nuttx/binfmt/libnxflat/libnxflat_bind.c index c18a16cd8f..2b9f647159 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_bind.c +++ b/nuttx/binfmt/libnxflat/libnxflat_bind.c @@ -47,8 +47,8 @@ #include #include -#include -#include +#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/libnxflat/libnxflat_init.c b/nuttx/binfmt/libnxflat/libnxflat_init.c index 5b6375ff16..20f06c6ab7 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_init.c +++ b/nuttx/binfmt/libnxflat/libnxflat_init.c @@ -48,7 +48,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/nuttx/binfmt/libnxflat/libnxflat_load.c b/nuttx/binfmt/libnxflat/libnxflat_load.c index 0991d0c2d7..02f035072d 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_load.c +++ b/nuttx/binfmt/libnxflat/libnxflat_load.c @@ -48,7 +48,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/nuttx/binfmt/libnxflat/libnxflat_read.c b/nuttx/binfmt/libnxflat/libnxflat_read.c index dbcd542791..da05bc3999 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_read.c +++ b/nuttx/binfmt/libnxflat/libnxflat_read.c @@ -48,7 +48,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/nuttx/binfmt/libnxflat/libnxflat_uninit.c b/nuttx/binfmt/libnxflat/libnxflat_uninit.c index c507fdc14c..b9715196b9 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_uninit.c +++ b/nuttx/binfmt/libnxflat/libnxflat_uninit.c @@ -42,7 +42,8 @@ #include #include #include -#include + +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/nuttx/binfmt/libnxflat/libnxflat_unload.c b/nuttx/binfmt/libnxflat/libnxflat_unload.c index 55a2e45e60..47c30bd55f 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_unload.c +++ b/nuttx/binfmt/libnxflat/libnxflat_unload.c @@ -43,7 +43,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/nuttx/binfmt/libnxflat/libnxflat_verify.c b/nuttx/binfmt/libnxflat/libnxflat_verify.c index da25d21c71..20af5d2f74 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_verify.c +++ b/nuttx/binfmt/libnxflat/libnxflat_verify.c @@ -42,8 +42,9 @@ #include #include #include + #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/nxflat.c b/nuttx/binfmt/nxflat.c index 4f5869bd92..babc51ff95 100644 --- a/nuttx/binfmt/nxflat.c +++ b/nuttx/binfmt/nxflat.c @@ -47,8 +47,8 @@ #include #include -#include -#include +#include +#include #ifdef CONFIG_NXFLAT diff --git a/nuttx/binfmt/symtab_findbyname.c b/nuttx/binfmt/symtab_findbyname.c index 201d7ba07d..c0343e2708 100644 --- a/nuttx/binfmt/symtab_findbyname.c +++ b/nuttx/binfmt/symtab_findbyname.c @@ -44,7 +44,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/symtab_findbyvalue.c b/nuttx/binfmt/symtab_findbyvalue.c index 4382ed5d8d..c47d5c7518 100644 --- a/nuttx/binfmt/symtab_findbyvalue.c +++ b/nuttx/binfmt/symtab_findbyvalue.c @@ -44,7 +44,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/symtab_findorderedbyname.c b/nuttx/binfmt/symtab_findorderedbyname.c index 61decf49ad..a678788e78 100644 --- a/nuttx/binfmt/symtab_findorderedbyname.c +++ b/nuttx/binfmt/symtab_findorderedbyname.c @@ -44,7 +44,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/symtab_findorderedbyvalue.c b/nuttx/binfmt/symtab_findorderedbyvalue.c index 92b107856d..bad4bf8cd7 100644 --- a/nuttx/binfmt/symtab_findorderedbyvalue.c +++ b/nuttx/binfmt/symtab_findorderedbyvalue.c @@ -44,7 +44,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/include/nuttx/binfmt.h b/nuttx/include/nuttx/binfmt/binfmt.h similarity index 97% rename from nuttx/include/nuttx/binfmt.h rename to nuttx/include/nuttx/binfmt/binfmt.h index 70beda3933..82e5f3557c 100644 --- a/nuttx/include/nuttx/binfmt.h +++ b/nuttx/include/nuttx/binfmt/binfmt.h @@ -1,7 +1,7 @@ /**************************************************************************** - * include/nuttx/binfmt.h + * include/nuttx/binfmt/binfmt.h * - * 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 @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __INCLUDE_NUTTX_BINFMT_H -#define __INCLUDE_NUTTX_BINFMT_H +#ifndef __INCLUDE_NUTTX_BINFMT_BINFMT_H +#define __INCLUDE_NUTTX_BINFMT_BINFMT_H /**************************************************************************** * Included Files @@ -205,5 +205,5 @@ EXTERN int exec(FAR const char *filename, FAR const char **argv, } #endif -#endif /* __INCLUDE_NUTTX_BINFMT_H */ +#endif /* __INCLUDE_NUTTX_BINFMT_BINFMT_H */ diff --git a/nuttx/include/nuttx/elf.h b/nuttx/include/nuttx/binfmt/elf.h similarity index 96% rename from nuttx/include/nuttx/elf.h rename to nuttx/include/nuttx/binfmt/elf.h index 4be2c23a04..8937790b13 100644 --- a/nuttx/include/nuttx/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -1,7 +1,7 @@ /**************************************************************************** - * include/nuttx/elf.h + * include/nuttx/binfmt/elf.h * - * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __INCLUDE_NUTTX_ELF_H -#define __INCLUDE_NUTTX_ELF_H +#ifndef __INCLUDE_NUTTX_BINFMT_ELF_H +#define __INCLUDE_NUTTX_BINFMT_ELF_H /**************************************************************************** * Included Files @@ -89,9 +89,9 @@ struct elf_loadinfo_s int filfd; /* Descriptor for the file being loaded */ - /* This is a copy of the ELF header (still in network order) */ + /* This is a copy of the ELF header */ - FAR struct elf_hdr_s header; + Elf32_Ehdr header; }; /**************************************************************************** @@ -123,7 +123,7 @@ extern "C" { * ****************************************************************************/ -EXTERN int elf_verifyheader(FAR const struct elf_hdr_s *header); +EXTERN int elf_verifyheader(FAR const Elf32_Ehdr *header); /**************************************************************************** * Name: elf_init @@ -256,4 +256,4 @@ EXTERN void elf_uninitialize(void); } #endif -#endif /* __INCLUDE_NUTTX_ELF_H */ +#endif /* __INCLUDE_NUTTX_BINFMT_ELF_H */ diff --git a/nuttx/include/nuttx/nxflat.h b/nuttx/include/nuttx/binfmt/nxflat.h similarity index 98% rename from nuttx/include/nuttx/nxflat.h rename to nuttx/include/nuttx/binfmt/nxflat.h index 59dcea854a..89e28fbcc1 100644 --- a/nuttx/include/nuttx/nxflat.h +++ b/nuttx/include/nuttx/binfmt/nxflat.h @@ -1,5 +1,5 @@ /**************************************************************************** - * include/nuttx/nxflat.h + * include/nuttx/binfmt/nxflat.h * * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __INCLUDE_NUTTX_NXFLAT_H -#define __INCLUDE_NUTTX_NXFLAT_H +#ifndef __INCLUDE_NUTTX_BINFMT_NXFLAT_H +#define __INCLUDE_NUTTX_BINFMT_NXFLAT_H /**************************************************************************** * Included Files @@ -261,4 +261,4 @@ EXTERN void nxflat_uninitialize(void); } #endif -#endif /* __INCLUDE_NUTTX_NXFLAT_H */ +#endif /* __INCLUDE_NUTTX_BINFMT_NXFLAT_H */ diff --git a/nuttx/include/nuttx/symtab.h b/nuttx/include/nuttx/binfmt/symtab.h similarity index 97% rename from nuttx/include/nuttx/symtab.h rename to nuttx/include/nuttx/binfmt/symtab.h index b302ab20a9..497327031d 100644 --- a/nuttx/include/nuttx/symtab.h +++ b/nuttx/include/nuttx/binfmt/symtab.h @@ -1,5 +1,5 @@ /**************************************************************************** - * include/nuttx/symtab.h + * include/nuttx/binfmt/symtab.h * * Copyright (C) 2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __INCLUDE_NUTTX_SYMTAB_H -#define __INCLUDE_NUTTX_SYMTAB_H +#ifndef __INCLUDE_NUTTX_BINFMT_SYMTAB_H +#define __INCLUDE_NUTTX_BINFMT_SYMTAB_H /**************************************************************************** * Included Files @@ -159,5 +159,5 @@ symtab_findorderedbyvalue(FAR const struct symtab_s *symtab, } #endif -#endif /* __INCLUDE_NUTTX_SYMTAB_H */ +#endif /* __INCLUDE_NUTTX_BINFMT_SYMTAB_H */ diff --git a/nuttx/tools/mksymtab.c b/nuttx/tools/mksymtab.c index c5a46a92be..e401812c00 100644 --- a/nuttx/tools/mksymtab.c +++ b/nuttx/tools/mksymtab.c @@ -222,7 +222,7 @@ int main(int argc, char **argv, char **envp) fprintf(outstream, "/* %s: Auto-generated symbol table. Do not edit */\n\n", symtab); fprintf(outstream, "#include \n"); - fprintf(outstream, "#include \n\n"); + fprintf(outstream, "#include \n\n"); /* Output all of the require header files */ From e2018e4d3085929dfc124fe41ed4b87e7eecc57d Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 24 Oct 2012 23:40:31 +0000 Subject: [PATCH 022/206] A little more ELF loader logic git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5253 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/binfmt/libelf/libelf.h | 13 +++ nuttx/binfmt/libelf/libelf_bind.c | 1 - nuttx/binfmt/libelf/libelf_init.c | 72 +++----------- nuttx/binfmt/libelf/libelf_load.c | 147 +++++++++++++++++++++++++++- nuttx/binfmt/libelf/libelf_read.c | 1 - nuttx/binfmt/libelf/libelf_unload.c | 17 ++-- nuttx/binfmt/libelf/libelf_verify.c | 42 +++++++- nuttx/include/elf.h | 9 +- nuttx/include/nuttx/binfmt/elf.h | 38 ++----- 9 files changed, 228 insertions(+), 112 deletions(-) diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h index 80d971bca2..ed352865c6 100644 --- a/nuttx/binfmt/libelf/libelf.h +++ b/nuttx/binfmt/libelf/libelf.h @@ -42,6 +42,8 @@ #include +#include + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -50,4 +52,15 @@ * Public Types ****************************************************************************/ +/**************************************************************************** + * Name: arch_checkarch + * + * Description: + * Given the ELF header in hdr, verify that the ELF file is appropriate + * for the current, configured architecture. + * + ****************************************************************************/ + +bool arch_checkarch(const struct Elf32_Ehdr *hdr); + #endif /* __BINFMT_LIBELF_LIBELF_H */ diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c index 87afe79c9f..74b713b9e3 100644 --- a/nuttx/binfmt/libelf/libelf_bind.c +++ b/nuttx/binfmt/libelf/libelf_bind.c @@ -46,7 +46,6 @@ #include #include -#include #include #include diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c index 71b6b92272..b024f2d19e 100644 --- a/nuttx/binfmt/libelf/libelf_init.c +++ b/nuttx/binfmt/libelf/libelf_init.c @@ -47,7 +47,6 @@ #include #include -#include #include /**************************************************************************** @@ -95,11 +94,7 @@ int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo) { - uint32_t datastart; - uint32_t dataend; - uint32_t bssstart; - uint32_t bssend; - int ret; + int ret; bvdbg("filename: %s loadinfo: %p\n", filename, loadinfo); @@ -116,72 +111,33 @@ int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo) return -errno; } - /* Read the ELF header from offset 0 */ + /* Read the ELF ehdr from offset 0 */ - ret = elf_read(loadinfo, (char*)&loadinfo->header, sizeof(Elf32_Ehdr), 0); + ret = elf_read(loadinfo, (char*)&loadinfo->ehdr, sizeof(Elf32_Ehdr), 0); if (ret < 0) { bdbg("Failed to read ELF header: %d\n", ret); return ret; } - elf_dumpbuffer("ELF header", (FAR const uint8_t*)&loadinfo->header, sizeof(Elf32_Ehdr)); + elf_dumpbuffer("ELF header", (FAR const uint8_t*)&loadinfo->ehdr, sizeof(Elf32_Ehdr)); /* Verify the ELF header */ - if (elf_verifyheader(&loadinfo->header) != 0) + ret = elf_verifyheader(&loadinfo->ehdr); + if (ret <0) { - /* This is not an error because we will be called to attempt loading - * EVERY binary. Returning -ENOEXEC simply informs the system that - * the file is not an ELF file. Besides, if there is something worth - * complaining about, nelf_verifyheader() has already - * done so. + /* This may not be an error because we will be called to attempt loading + * EVERY binary. If elf_verifyheader() does not recognize the ELF header, + * it will -ENOEXEC whcih simply informs the system that the file is not an + * ELF file. elf_verifyheader() will return other errors if the ELF header + * is not correctly formed. */ - bdbg("Bad ELF header\n"); - return -ENOEXEC; + bdbg("Bad ELF header: %d\n", ret); + return ret; } - /* Save all of the input values in the loadinfo structure - * and extract some additional information from the xflat - * header. Note that the information in the xflat header is in - * network order. - */ - - datastart = ntohl(loadinfo->header.h_datastart); - dataend = ntohl(loadinfo->header.h_dataend); - bssstart = dataend; - bssend = ntohl(loadinfo->header.h_bssend); - - /* And put this information into the loadinfo structure as well. - * - * Note that: - * - * isize = the address range from 0 up to datastart. - * datasize = the address range from datastart up to dataend - * bsssize = the address range from dataend up to bssend. - */ - - loadinfo->entryoffs = ntohl(loadinfo->header.h_entry); - loadinfo->isize = datastart; - - loadinfo->datasize = dataend - datastart; - loadinfo->bsssize = bssend - dataend; - loadinfo->stacksize = ntohl(loadinfo->header.h_stacksize); - - /* This is the initial dspace size. We'll re-calculate this later - * after the memory has been allocated. - */ - - loadinfo->dsize = bssend - datastart; - - /* Get the offset to the start of the relocations (we'll relocate - * this later). - */ - - loadinfo->relocstart = ntohl(loadinfo->header.h_relocstart); - loadinfo->reloccount = ntohs(loadinfo->header.h_reloccount); - - return 0; + return OK; } diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 26785f6b1c..41bafe04e1 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -40,14 +40,15 @@ #include #include -#include +#include + #include #include +#include #include #include #include -#include #include /**************************************************************************** @@ -66,6 +67,148 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: elf_filelen + * + * Description: + * Get the size of the ELF file + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +static inline int elf_filelen(FAR struct elf_loadinfo_s *loadinfo) +{ + struct stat buf; + int ret; + + /* Get the file stats */ + + ret = fstat(loadinfo->filfd, &buf); + if (ret < 0) + { + int errval = errno; + bdbg("Failed to fstat file: %d\n", errval); + return -errval; + } + + /* Verify that it is a regular file */ + + if (!S_ISREG(buf.st_mode)) + { + bdbg("Not a regular file. mode: %d\n", buf.st_mode); + return -errval; + } + + /* TODO: Verify that the file is readable */ + + /* Return the size of the file in the loadinfo structure */ + + loadinfo->filelen = buf.st_size; + return OK; +} + +/**************************************************************************** + * Name: elf_loadshdrs + * + * Description: + * Loads section headers into memory. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) +{ + size_t shdrsize; + ssize_t bytesread; + uint8_t buffer; + off_t offset; + int ret; + + DEBUGASSERT(loadinfo->shdrs == NULL); + + /* Verify that there are sections */ + + if (loadinfo->e_shum < 1) + { + bdbg("No section(?)\n"); + return -EINVAL; + } + + /* Get the total size of the section header table */ + + shdrsize = (size_t)loadinfo->ehdr.e_shentsize * (size_t)loadinfo->e_shum; + if(loadinfo->e_shoff + shdrsize > loadinfo->filelen) + { + bdbg("Insufficent space in file for section header table\n"); + return -ESPIPE; + } + + /* Allocate memory to hold a working copy of the sector header table */ + + loadinfo->shdrs = (FAR Elf32_Shdr*)kmalloc(shdrsize); + if (!loadinfo->shdrs) + { + bdbg("Failed to allocate the section header table. Size: %ld\n", (long)shdrsize); + return -ENOMEM; + } + + /* Seek to the start of the section header table */ + + offset = lseek(loadinfo->filfd, loadinfo->e_shoff, SEEK_SET); + if (offset == (off_t)-1) + { + int errval = errno; + bdbg("See to %ld failed: %d\n", (long)loadinfo->e_shoff, errval); + ret = -errval; + goto errout_with_alloc; + } + + /* Now load the section header table into the allocated memory */ + + buffer = loadinfo->shdrs; + while (shdrsize > 0) + { + bytesread = read(loadinfo->filfd, buffer, shdrsize); + if (bytes < 0) + { + int errval = errno; + + /* EINTR just means that we received a signal */ + + if (errno != EINTR) + { + bdbg("read() failed: %d\n", errval); + ret = -errval; + goto errout_with_alloc; + } + } + else if (bytes == 0) + { + bdbg("Unexpectged end of file\n"); + ret = -ENODATA; + goto errout_with_alloc; + } + else + { + buffer += bytesread; + shdrsize -= bytesread; + } + } + + return OK; + +errout_with_alloc: + kfree(loadinfo->shdrs); + loadinfo->shdrs = 0; + return ret; +} + /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c index 3770301747..35b9090f98 100644 --- a/nuttx/binfmt/libelf/libelf_read.c +++ b/nuttx/binfmt/libelf/libelf_read.c @@ -47,7 +47,6 @@ #include #include -#include #include /**************************************************************************** diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c index 9a198fc780..217a1981ef 100644 --- a/nuttx/binfmt/libelf/libelf_unload.c +++ b/nuttx/binfmt/libelf/libelf_unload.c @@ -76,20 +76,19 @@ int elf_unload(struct elf_loadinfo_s *loadinfo) { - /* Reset the contents of the info structure. */ + /* Release the all allocated memory */ - /* Release the memory segments */ - - if (loadinfo->ispace) + if (loadinfo->alloc) { - kfree((void*)loadinfo->ispace, loadinfo->isize); - loadinfo->ispace = 0; + kfree((void*)loadinfo->alloc); + loadinfo->alloc = NULL; + loadinfo->allocsize = 0; } - if (loadinfo->dspace) + if (loadinfo->shdrs) { - kfree((void*)loadinfo->dspace); - loadinfo->dspace = 0; + kfree((void*)loadinfo->shdrs); + loadinfo->shdrs = 0; } return OK; diff --git a/nuttx/binfmt/libelf/libelf_verify.c b/nuttx/binfmt/libelf/libelf_verify.c index 9139700b34..0e0dd8e1ae 100644 --- a/nuttx/binfmt/libelf/libelf_verify.c +++ b/nuttx/binfmt/libelf/libelf_verify.c @@ -42,7 +42,7 @@ #include #include #include -#include + #include /**************************************************************************** @@ -53,6 +53,8 @@ * Private Constant Data ****************************************************************************/ +static const char g_elfmagic[EI_MAGIC_SIZE] = { 0x7f, 'E', 'L', 'F' } + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -72,17 +74,47 @@ * 0 (OK) is returned on success and a negated errno is returned on * failure. * + * -ENOEXEC : Not an ELF file + * -EINVALID : Not a relocatable ELF file or not supported by the current, + * configured architecture. + * ****************************************************************************/ -int elf_verifyheader(const Elf32_Ehdr *header) +int elf_verifyheader(const Elf32_Ehdr *ehdr) { - if (!header) + if (!ehdr) { bdbg("NULL ELF header!"); return -ENOEXEC; } -#warning "Missing Logic" - return -ENOSYS; + /* Verify that the magic number indicates an ELF file */ + + if (memcmp(ehdr->e_ident, g_elfmagic, EI_MAGIC_SIZE) != 0) + { + bvdbg("Not ELF magic {%02x, %02x, %02x, %02x}\n", + ehdr->e_ident[0], ehdr->e_ident[1], ehdr->e_ident[2], ehdr->e_ident[3]); + return -ENOEXEC; + } + + /* Verify that this is a relocatable file */ + + if (ehdr->e_type != ET_REL) + { + bdbg("Not a relocatable file: e_type=%d\n", ehdr->e_type); + return -EINVALID; + } + + /* Verify that this file works with the currently configured architecture */ + + if (arch_checkarch(ehdr)) + { + bdbg("Not a supported architecture\n"); + return -ENOEXEC; + } + + /* Looks good so far... we still might find some problems later. */ + + return OK; } diff --git a/nuttx/include/elf.h b/nuttx/include/elf.h index 31818249fa..dbc615dcd0 100644 --- a/nuttx/include/elf.h +++ b/nuttx/include/elf.h @@ -86,16 +86,17 @@ /* Ehe ELF identifier */ #define EI_MAG0 0 /* File identification */ -#define EI_MAG1 1 /* File identification */ -#define EI_MAG2 2 /* File identification */ -#define EI_MAG3 3 /* File identification */ +#define EI_MAG1 1 /* " " " " */ +#define EI_MAG2 2 /* " " " " */ +#define EI_MAG3 3 /* " " " " */ #define EI_CLASS 4 /* File class */ #define EI_DATA 5 /* Data encoding */ #define EI_VERSION 6 /* File version */ #define EI_PAD 7 /* Start of padding bytes */ #define EI_NIDENT 16 /* Size of eident[] */ -#define EI_MAGIC { 0x7f, 'E', 'L', 'F' } +#define EI_MAGIC_SIZE 4 +#define EI_MAGIC {0x7f, 'E', 'L', 'F'} /* Values for EI_CLASS */ diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h index 8937790b13..95db7d16fd 100644 --- a/nuttx/include/nuttx/binfmt/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -60,38 +60,12 @@ struct elf_loadinfo_s { - /* Instruction Space (ISpace): This region contains the ELF file header - * plus everything from the text section. Ideally, will have only one mmap'ed - * text section instance in the system for each module. - */ - - uint32_t ispace; /* Address where hdr/text is loaded */ - uint32_t entryoffs; /* Offset from ispace to entry point */ - uint32_t isize; /* Size of ispace. */ - - /* Data Space (DSpace): This region contains all information that in referenced - * as data (other than the stack which is separately allocated). There will be - * a unique instance of DSpace (and stack) for each instance of a process. - */ - - FAR struct dspace_s *dspace; /* Allocated D-Space (data/bss/etc) */ - uint32_t datasize; /* Size of data segment in dspace */ - uint32_t bsssize; /* Size of bss segment in dspace */ - uint32_t stacksize; /* Size of stack (not allocated) */ - uint32_t dsize; /* Size of dspace (may be large than parts) */ - - /* This is temporary memory where relocation records will be loaded. */ - - uint32_t relocstart; /* Start of array of struct flat_reloc */ - uint16_t reloccount; /* Number of elements in reloc array */ - - /* File descriptors */ - - int filfd; /* Descriptor for the file being loaded */ - - /* This is a copy of the ELF header */ - - Elf32_Ehdr header; + uintptr_t alloc; /* Allocated memory with the ELF file is loaded */ + size_t allocsize; /* Size of the memory allocation */ + off_t filelen; /* Length of the entire ELF file */ + int filfd; /* Descriptor for the file being loaded */ + Elf32_Ehdr ehdr; /* Buffered ELF file header */ + FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */ }; /**************************************************************************** From fb0aa16107b4cf41c38bf433a8b58ff54de2f0d3 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 25 Oct 2012 01:23:03 +0000 Subject: [PATCH 023/206] A little more ELF loader logic git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5254 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/binfmt/libelf/Kconfig | 22 +++ nuttx/binfmt/libelf/libelf_load.c | 229 ++++++++++++++++++++++++------ nuttx/include/nuttx/binfmt/elf.h | 8 ++ 3 files changed, 218 insertions(+), 41 deletions(-) diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig index c47bc9f9eb..c6e00f6046 100644 --- a/nuttx/binfmt/libelf/Kconfig +++ b/nuttx/binfmt/libelf/Kconfig @@ -3,7 +3,29 @@ # see misc/tools/kconfig-language.txt. # +config ELF_ALIGN_LOG2 + int "Log2 Section Alignment" + default 2 + ---help--- + Align all sections to this Log2 value: 0->1, 1->2, 2->4, etc. + +config ELF_CONSTRUCTORS + bool "C++ Static Constructor Support" + default n + depends on HAVE_CXX + ---help--- + Build in support for C++ constructors in ELF modules. + +config ELF_SYMBOLS + bool "Export symbols from ELF modules" + default n + ---help--- + Allow symbols from one ELF module to be used by another. (NOT + fully implemented. + config ELF_DUMPBUFFER bool "Dump ELF buffers" default n depends on DEBUG && DEBUG_VERBOSE + ---help--- + Dump various ELF buffers for debug purposes diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 41bafe04e1..98e9abf381 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -55,6 +55,11 @@ * Pre-Processor Definitions ****************************************************************************/ +#define ELF_ALIGN_MASK ((1 << CONFIG_ELF_ALIGN_LOG2) - 1) +#define ELF_ALIGNUP(a) (((unsigned long)(a) + ELF_ALIGN_MASK) & ~ELF_ALIGN_MASK) +#define ELF_ALIGNDOWN(a) ((unsigned long)(a) & ~ELF_ALIGN_MASK) + + #ifndef MAX #define MAX(x,y) ((x) > (y) ? (x) : (y)) #endif @@ -110,6 +115,69 @@ static inline int elf_filelen(FAR struct elf_loadinfo_s *loadinfo) return OK; } +/**************************************************************************** + * Name: elf_readfile + * + * Description: + * Allocate memory for the file and read the section data into the + * allocated memory. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +static int elf_readfile(FAR struct elf_loadinfo_s *loadinfo, FAR void *buffer, + off_t offset, size_t nbytes) +{ + FAR uint8_t *buffer; + ssize_t bytesread; + off_t result; + + /* Seek to the start of the section header table */ + + result = lseek(loadinfo->filfd, offset, SEEK_SET); + if (result == (off_t)-1) + { + int errval = errno; + bdbg("Seel to %ld failed: %d\n", (long)offset, errval); + return -errval; + } + + /* Now load the file data into memory */ + + buffer = (FAR uint8_t *)loadinfo->shdrs; + while (shdrsize > 0) + { + bytesread = read(loadinfo->filfd, buffer, shdrsize); + if (bytes < 0) + { + int errval = errno; + + /* EINTR just means that we received a signal */ + + if (errno != EINTR) + { + bdbg("read() failed: %d\n", errval); + return -errval; + } + } + else if (bytes == 0) + { + bdbg("Unexpected end of file\n"); + return -ENODATA; + } + else + { + buffer += bytesread; + shdrsize -= bytesread; + } + } + + return OK; +} + /**************************************************************************** * Name: elf_loadshdrs * @@ -125,9 +193,6 @@ static inline int elf_filelen(FAR struct elf_loadinfo_s *loadinfo) static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) { size_t shdrsize; - ssize_t bytesread; - uint8_t buffer; - off_t offset; int ret; DEBUGASSERT(loadinfo->shdrs == NULL); @@ -158,49 +223,15 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) return -ENOMEM; } - /* Seek to the start of the section header table */ + /* Read the section header table into memory */ - offset = lseek(loadinfo->filfd, loadinfo->e_shoff, SEEK_SET); - if (offset == (off_t)-1) + ret = elf_readfile(loadinfo, loadinfo->shdrs, loadinfo->e_shoff, shdrsize); + if (ret < 0) { - int errval = errno; - bdbg("See to %ld failed: %d\n", (long)loadinfo->e_shoff, errval); - ret = -errval; + bdbg("Failed to read section header table: %d\n", ret); goto errout_with_alloc; } - /* Now load the section header table into the allocated memory */ - - buffer = loadinfo->shdrs; - while (shdrsize > 0) - { - bytesread = read(loadinfo->filfd, buffer, shdrsize); - if (bytes < 0) - { - int errval = errno; - - /* EINTR just means that we received a signal */ - - if (errno != EINTR) - { - bdbg("read() failed: %d\n", errval); - ret = -errval; - goto errout_with_alloc; - } - } - else if (bytes == 0) - { - bdbg("Unexpectged end of file\n"); - ret = -ENODATA; - goto errout_with_alloc; - } - else - { - buffer += bytesread; - shdrsize -= bytesread; - } - } - return OK; errout_with_alloc: @@ -209,6 +240,122 @@ errout_with_alloc: return ret; } +/**************************************************************************** + * Name: elf_allocsize + * + * Description: + * Calculate total memory allocation for the ELF file. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +static void elf_allocsize(struct load_info *loadinfo) +{ + size_t allocsize; + int i; + + /* Accumulate the size each section into memory that is marked SHF_ALLOC */ + + allocsize = 0; + for (i = 0; i < loadinfo->ehdr.e_shnum; i++) + { + FAR Elf32_Shdr *shdr = &loadinfo->shdrs[i]; + + /* SHF_ALLOC indicates that the section requires memory during + * execution. + */ + + if ((shdr->sh_flags & SHF_ALLOC) != 0) + { + allocsize += ELF_ALIGNUP(shdr->sh_size); + } + } + + /* Save the allocation size */ + + loadinfo->allocize = allocsize; +} + +/**************************************************************************** + * Name: elf_loadfile + * + * Description: + * Allocate memory for the file and read the section data into the + * allocated memory. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +static inline int elf_loadfile(FAR struct load_info *loadinfo) +{ + FAR uint8_t *dest; + int i; + + /* Allocate (and zero) memory for the ELF file. */ + + loadinfo->alloc = kzalloc(loadinfo->allocsize); + if (!loadinfo->alloc) + { + return -ENOMEM; + } + + /* Read each section into memory that is marked SHF_ALLOC + SHT_NOBITS */ + + bvdbg("Loaded sections:\n"); + dest = (FAR uint8_t*)loadinfo->alloc; + + for (i = 0; i < loadinfo->ehdr.e_shnum; i++) + { + FAR Elf32_Shdr *shdr = &loadinfo->shdrs[i]; + + /* SHF_ALLOC indicates that the section requires memory during + * execution */ + + if ((shdr->sh_flags & SHF_ALLOC) == 0) + { + continue; + } + + /* SHT_NOBITS indicates that there is no data in the file for the + * section. + */ + + if (shdr->sh_type != SHT_NOBITS) + { + /* Read the section data from sh_offset to dest */ + + ret = elf_readfile(loadinfo, dest, shdr->sh_offset, shdr->sh_size); + if (ret < 0) + { + bdbg("Failed to read section %d: %d\n", i, ret); + goto errout_with_alloc; + } + } + + /* Update sh_addr to point to copy in image. */ + + shdr->sh_addr = (uintptr_t)dest; + bvdbg("%d. 0x%lx %s\n", (long)shdr->sh_addr, loadinfo->secstrings + shdr->sh_name); + + /* Setup the memory pointer for the next time through the loop */ + + dest += ELF_ALIGNUP(shdr->sh_size); + } + + return OK; + +errout_with_alloc: + kfree(loadinfo->alloc); + loadinfo->alloc = 0; + return ret; +} + /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h index 95db7d16fd..d74018fc4c 100644 --- a/nuttx/include/nuttx/binfmt/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -49,6 +49,11 @@ /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ +/* Configuration ************************************************************/ + +#ifndef CONFIG_ELF_ALIGN_LOG2 +# define CONFIG_ELF_ALIGN_LOG2 2 +#endif /**************************************************************************** * Public Types @@ -63,6 +68,9 @@ struct elf_loadinfo_s uintptr_t alloc; /* Allocated memory with the ELF file is loaded */ size_t allocsize; /* Size of the memory allocation */ off_t filelen; /* Length of the entire ELF file */ +#ifdef CONFIG_ELF_CONSTRUCTORS + uintptr_t ctors; /* Static constructors */ +#endif int filfd; /* Descriptor for the file being loaded */ Elf32_Ehdr ehdr; /* Buffered ELF file header */ FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */ From 0506b554c82a0d7ca6128c11847595d37169777d Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 25 Oct 2012 01:34:21 +0000 Subject: [PATCH 024/206] Fix Kconfig files broken by last check-in git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5255 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/binfmt/Kconfig | 5 +++-- nuttx/binfmt/libelf/Kconfig | 4 ++-- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/nuttx/binfmt/Kconfig b/nuttx/binfmt/Kconfig index 3519536fb6..4d020163ee 100644 --- a/nuttx/binfmt/Kconfig +++ b/nuttx/binfmt/Kconfig @@ -19,7 +19,7 @@ config NXFLAT Enable support for the NXFLAT binary format. Default: n if NXFLAT -include binfmt/libnxflat/Kconfig +source binfmt/libnxflat/Kconfig endif config ELF @@ -29,8 +29,9 @@ config ELF Enable support for the ELF binary format. Default: n if ELF -include binfmt/libelf/Kconfig +source binfmt/libelf/Kconfig endif + endif config SYMTAB_ORDEREDBYNAME diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig index c6e00f6046..ba931b57e7 100644 --- a/nuttx/binfmt/libelf/Kconfig +++ b/nuttx/binfmt/libelf/Kconfig @@ -20,8 +20,8 @@ config ELF_SYMBOLS bool "Export symbols from ELF modules" default n ---help--- - Allow symbols from one ELF module to be used by another. (NOT - fully implemented. + Allow symbols from one ELF module to be used by another. NOT + fully implemented! config ELF_DUMPBUFFER bool "Dump ELF buffers" From a91b6552cdb1b147461b75128576012192d9e933 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 25 Oct 2012 03:13:11 +0000 Subject: [PATCH 025/206] A little more ELF loader logic git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5256 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/binfmt/libelf/libelf_init.c | 5 +- nuttx/binfmt/libelf/libelf_load.c | 111 ++++++++++-------------- nuttx/binfmt/libelf/libelf_read.c | 45 +++++----- nuttx/binfmt/libnxflat/libnxflat_init.c | 5 +- nuttx/binfmt/libnxflat/libnxflat_read.c | 12 +-- nuttx/include/nuttx/binfmt/elf.h | 4 +- 6 files changed, 80 insertions(+), 102 deletions(-) diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c index b024f2d19e..cf62666b97 100644 --- a/nuttx/binfmt/libelf/libelf_init.c +++ b/nuttx/binfmt/libelf/libelf_init.c @@ -107,8 +107,9 @@ int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo) loadinfo->filfd = open(filename, O_RDONLY); if (loadinfo->filfd < 0) { - bdbg("Failed to open ELF binary %s: %d\n", filename, ret); - return -errno; + int errval = errno; + bdbg("Failed to open ELF binary %s: %d\n", filename, errval); + return -errval; } /* Read the ELF ehdr from offset 0 */ diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 98e9abf381..c30c109ce3 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -115,69 +115,6 @@ static inline int elf_filelen(FAR struct elf_loadinfo_s *loadinfo) return OK; } -/**************************************************************************** - * Name: elf_readfile - * - * Description: - * Allocate memory for the file and read the section data into the - * allocated memory. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -static int elf_readfile(FAR struct elf_loadinfo_s *loadinfo, FAR void *buffer, - off_t offset, size_t nbytes) -{ - FAR uint8_t *buffer; - ssize_t bytesread; - off_t result; - - /* Seek to the start of the section header table */ - - result = lseek(loadinfo->filfd, offset, SEEK_SET); - if (result == (off_t)-1) - { - int errval = errno; - bdbg("Seel to %ld failed: %d\n", (long)offset, errval); - return -errval; - } - - /* Now load the file data into memory */ - - buffer = (FAR uint8_t *)loadinfo->shdrs; - while (shdrsize > 0) - { - bytesread = read(loadinfo->filfd, buffer, shdrsize); - if (bytes < 0) - { - int errval = errno; - - /* EINTR just means that we received a signal */ - - if (errno != EINTR) - { - bdbg("read() failed: %d\n", errval); - return -errval; - } - } - else if (bytes == 0) - { - bdbg("Unexpected end of file\n"); - return -ENODATA; - } - else - { - buffer += bytesread; - shdrsize -= bytesread; - } - } - - return OK; -} - /**************************************************************************** * Name: elf_loadshdrs * @@ -225,7 +162,7 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) /* Read the section header table into memory */ - ret = elf_readfile(loadinfo, loadinfo->shdrs, loadinfo->e_shoff, shdrsize); + ret = elf_read(loadinfo, loadinfo->shdrs, shdrsize, loadinfo->e_shoff); if (ret < 0) { bdbg("Failed to read section header table: %d\n", ret); @@ -330,7 +267,7 @@ static inline int elf_loadfile(FAR struct load_info *loadinfo) { /* Read the section data from sh_offset to dest */ - ret = elf_readfile(loadinfo, dest, shdr->sh_offset, shdr->sh_size); + ret = elf_read(loadinfo, dest, shdr->sh_size, shdr->sh_offset); if (ret < 0) { bdbg("Failed to read section %d: %d\n", i, ret); @@ -375,7 +312,47 @@ errout_with_alloc: int elf_load(FAR struct elf_loadinfo_s *loadinfo) { -# warning "Missing logic" - return -ENOSYS; + int ret; + + bvdbg("loadinfo: %p\n", loadinfo); + DEBUGASSERT(loadinfo && loadinfo->filfd >= 0); + + /* Get the length of the file. */ + + ret = elf_filelen(loadinfo); + { + return ret; + } + + /* Load section headers into memory */ + + ret = elf_loadshdrs(loadinfo); + if (ret < 0) + { + return ret; + } + + /* Determine total size to allocate */ + + elf_allocsize(loadinfo); + + /* Allocate memory and load sections into memory */ + + ret = elf_loadfile(loadinfo); + if (ret < 0) + { + goto errout_with_shdrs; + } + + return OK; + + /* Error exits */ + +errout_with_alloc: + kfree(loadinfo->alloc); +errout_with_shdrs: + kfree(loadinfo->shdrs); +errout: + return ret; } diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c index 35b9090f98..0b01cf096e 100644 --- a/nuttx/binfmt/libelf/libelf_read.c +++ b/nuttx/binfmt/libelf/libelf_read.c @@ -106,41 +106,41 @@ static inline void elf_dumpreaddata(char *buffer, int buflen) * ****************************************************************************/ -int elf_read(struct elf_loadinfo_s *loadinfo, char *buffer, int readsize, int offset) +int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer, + size_t readsize, off_t offset) { ssize_t nbytes; /* Number of bytes read */ off_t rpos; /* Position returned by lseek */ - char *bufptr; /* Next buffer location to read into */ - int bytesleft; /* Number of bytes of .data left to read */ - int bytesread; /* Total number of bytes read */ - bvdbg("Read %d bytes from offset %d\n", readsize, offset); + bvdbg("Read %ld bytes from offset %ld\n", (long)readsize, (long)offset); - /* Seek to the position in the object file where the initialized - * data is saved. - */ + /* Loop until all of the requested data has been read. */ - bytesread = 0; - bufptr = buffer; - bytesleft = readsize; - do + while (readsize > 0) { + /* Seek to the next read position */ + rpos = lseek(loadinfo->filfd, offset, SEEK_SET); if (rpos != offset) { - bdbg("Failed to seek to position %d: %d\n", offset, errno); - return -errno; + int errval = errno; + bdbg("Failed to seek to position %ld: %d\n", (long)offset, errval); + return -errval; } /* Read the file data at offset into the user buffer */ - nbytes = read(loadinfo->filfd, bufptr, bytesleft); + nbytes = read(loadinfo->filfd, buffer, readsize); if (nbytes < 0) { - if (errno != EINTR) + int errval = errno; + + /* EINTR just means that we received a signal */ + + if (errval != EINTR) { - bdbg("Read of .data failed: %d\n", errno); - return -errno; + bdbg("Read of .data failed: %d\n", errval); + return -errval; } } else if (nbytes == 0) @@ -150,15 +150,12 @@ int elf_read(struct elf_loadinfo_s *loadinfo, char *buffer, int readsize, int of } else { - bytesread += nbytes; - bytesleft -= nbytes; - bufptr += nbytes; - offset += nbytes; + readsize -= nbytes; + buffer += nbytes; + offset += nbytes; } } - while (bytesread < readsize); elf_dumpreaddata(buffer, readsize); return OK; } - diff --git a/nuttx/binfmt/libnxflat/libnxflat_init.c b/nuttx/binfmt/libnxflat/libnxflat_init.c index 20f06c6ab7..b7cac8d866 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_init.c +++ b/nuttx/binfmt/libnxflat/libnxflat_init.c @@ -112,8 +112,9 @@ int nxflat_init(const char *filename, struct nxflat_loadinfo_s *loadinfo) loadinfo->filfd = open(filename, O_RDONLY); if (loadinfo->filfd < 0) { - bdbg("Failed to open NXFLAT binary %s: %d\n", filename, ret); - return -errno; + int errval = errno; + bdbg("Failed to open NXFLAT binary %s: %d\n", filename, errval); + return -errval; } /* Read the NXFLAT header from offset 0 */ diff --git a/nuttx/binfmt/libnxflat/libnxflat_read.c b/nuttx/binfmt/libnxflat/libnxflat_read.c index da05bc3999..8deeb0805e 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_read.c +++ b/nuttx/binfmt/libnxflat/libnxflat_read.c @@ -129,8 +129,9 @@ int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, int readsize, rpos = lseek(loadinfo->filfd, offset, SEEK_SET); if (rpos != offset) { - bdbg("Failed to seek to position %d: %d\n", offset, errno); - return -errno; + int errval = errno; + bdbg("Failed to seek to position %d: %d\n", offset, errval); + return -errval; } /* Read the file data at offset into the user buffer */ @@ -138,10 +139,11 @@ int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, int readsize, nbytes = read(loadinfo->filfd, bufptr, bytesleft); if (nbytes < 0) { - if (errno != EINTR) + int errval = errno; + if (errval != EINTR) { - bdbg("Read of .data failed: %d\n", errno); - return -errno; + bdbg("Read of .data failed: %d\n", errval); + return -errval; } } else if (nbytes == 0) diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h index d74018fc4c..8e7658d5d8 100644 --- a/nuttx/include/nuttx/binfmt/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -165,8 +165,8 @@ EXTERN int elf_load(FAR struct elf_loadinfo_s *loadinfo); * ****************************************************************************/ -EXTERN int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR char *buffer, - FAR int readsize, int offset); +EXTER int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer, + size_t readsize, off_t offset); /**************************************************************************** * Name: elf_bind From 630862cd04e0f807f9d1d9d2ed8ba8f044dcedfa Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 25 Oct 2012 16:18:20 +0000 Subject: [PATCH 026/206] A little more ELF loader logic git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5257 42af7a65-404d-4744-a932-0658087f49c3 --- .../arm.h => arch/arm/src/common/arm-elf.h} | 8 +- nuttx/binfmt/Makefile | 4 +- nuttx/binfmt/elf.c | 84 ++++++--- nuttx/binfmt/libelf/Kconfig | 13 +- nuttx/binfmt/libelf/Make.defs | 3 +- nuttx/binfmt/libelf/libelf.h | 55 +++++- nuttx/binfmt/libelf/libelf_bind.c | 171 +++++++++++++++++- nuttx/binfmt/libelf/libelf_init.c | 4 +- nuttx/binfmt/libelf/libelf_load.c | 57 +++--- nuttx/binfmt/libelf/libelf_symbols.c | 134 ++++++++++++++ nuttx/binfmt/libelf/libelf_unload.c | 10 +- nuttx/binfmt/libelf/libelf_verify.c | 8 +- nuttx/binfmt/libnxflat/Make.defs | 1 + nuttx/include/elf.h | 74 ++++---- nuttx/include/nuttx/binfmt/elf.h | 95 ++++++---- 15 files changed, 568 insertions(+), 153 deletions(-) rename nuttx/{binfmt/libelf/arm.h => arch/arm/src/common/arm-elf.h} (94%) create mode 100644 nuttx/binfmt/libelf/libelf_symbols.c diff --git a/nuttx/binfmt/libelf/arm.h b/nuttx/arch/arm/src/common/arm-elf.h similarity index 94% rename from nuttx/binfmt/libelf/arm.h rename to nuttx/arch/arm/src/common/arm-elf.h index e80457b6e4..fac387b110 100644 --- a/nuttx/binfmt/libelf/arm.h +++ b/nuttx/arch/arm/src/common/arm-elf.h @@ -1,5 +1,5 @@ /**************************************************************************** - * binfmt/libelf/arm.h + * arch/arm/src/common/arm-elf.h * * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __BINFMT_LIBELF_ARM_H -#define __BINFMT_LIBELF_ARM_H +#ifndef __ARCH_ARM_SRC_ARM_ELF_H +#define __ARCH_ARM_SRC_ARM_ELF_H /**************************************************************************** * Included Files @@ -50,4 +50,4 @@ * Public Types ****************************************************************************/ -#endif /* __BINFMT_LIBELF_ARM_H */ +#endif /* __ARCH_ARM_SRC_ARM_ELF_H */ diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile index 1b98e3ede9..4724abeff0 100644 --- a/nuttx/binfmt/Makefile +++ b/nuttx/binfmt/Makefile @@ -56,6 +56,7 @@ BINFMT_CSRCS += symtab_findbyname.c symtab_findbyvalue.c \ VPATH = SUBDIRS = +DEPPATH = --dep-path . include libnxflat/Make.defs include libelf/Make.defs @@ -82,8 +83,7 @@ $(BIN): $(BINFMT_OBJS) done ; ) .depend: Makefile $(BINFMT_SRCS) - @$(MKDEP) --dep-path . --dep-path libnxflat \ - $(CC) -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep + @$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep @touch $@ depend: .depend diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c index fb3b5acd23..ba12a22ea4 100644 --- a/nuttx/binfmt/elf.c +++ b/nuttx/binfmt/elf.c @@ -64,6 +64,10 @@ # undef CONFIG_ELF_DUMPBUFFER #endif +#ifndef CONFIG_ELF_STACKSIZE +# define CONFIG_ELF_STACKSIZE 2048 +#endif + #ifdef CONFIG_ELF_DUMPBUFFER # define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n) #else @@ -104,33 +108,55 @@ static struct binfmt_s g_elfbinfmt = #if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT) static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo) { - unsigned long dsize = loadinfo->datasize + loadinfo->bsssize; + int i; bdbg("LOAD_INFO:\n"); - bdbg(" ISPACE:\n"); - bdbg(" ispace: %08lx\n", loadinfo->ispace); - bdbg(" entryoffs: %08lx\n", loadinfo->entryoffs); - bdbg(" isize: %08lx\n", loadinfo->isize); + bdbg(" alloc: %08lx\n", (long)loadinfo->alloc); + bdbg(" allocsize: %ld\n", (long)loadinfo->allocsize); + bdbg(" filelen: %ld\n", (long)loadinfo->filelen); +#ifdef CONFIG_ELF_CONSTRUCTORS + bdbg(" ctors: %08lx\n", (long)loadinfo->ctors); +#endif + bdbg(" filfd: %d\n", loadinfo->filfd); + bdbg(" symtabidx: %d\n", loadinfo->symtabidx); + bdbg(" strtabidx: %d\n", loadinfo->strtabidx); - bdbg(" DSPACE:\n"); - bdbg(" dspace: %08lx\n", loadinfo->dspace); - if (loadinfo->dspace != NULL) + bdbg("ELF Header:\n"); + bdbg(" e_ident: %02x %02x %02x %02x\n", + loadinfo->ehdr.e_ident[0], loadinfo->ehdr.e_ident[1], + loadinfo->ehdr.e_ident[2], loadinfo->ehdr.e_ident[3]); + bdbg(" e_type: %04x\n", loadinfo->ehdr.e_type); + bdbg(" e_machine: %04x\n", loadinfo->ehdr.e_machine); + bdbg(" e_version: %08x\n", loadinfo->ehdr.e_version); + bdbg(" e_entry: %08lx\n", (long)loadinfo->ehdr.e_entry); + bdbg(" e_phoff: %d\n", loadinfo->ehdr.e_phoff); + bdbg(" e_shoff: %d\n", loadinfo->ehdr.e_shoff); + bdbg(" e_flags: %08x\n" , loadinfo->ehdr.e_flags); + bdbg(" e_ehsize: %d\n", loadinfo->ehdr.e_ehsize); + bdbg(" e_phentsize: %d\n", loadinfo->ehdr.e_phentsize); + bdbg(" e_phnum: %d\n", loadinfo->ehdr.e_phnum); + bdbg(" e_shentsize: %d\n", loadinfo->ehdr.e_shentsize); + bdbg(" e_shnum: %d\n", loadinfo->ehdr.e_shnum); + bdbg(" e_shstrndx: %d\n", loadinfo->ehdr.e_shstrndx); + + if (loadinfo->shdr && loadinfo->ehdr.e_shum > 0) { - bdbg(" crefs: %d\n", loadinfo->dspace->crefs); - bdbg(" region: %08lx\n", loadinfo->dspace->region); + for (i = 0; i < loadinfo->ehdr.e_shum; i++) + { + FAR ELF32_Shdr *shdr = &loadinfo->shdr[i]; + bdbg("Sections %d:\n", i); + bdbg(" sh_name: %08x\n", shdr->sh_name); + bdbg(" sh_type: %08x\n", shdr->sh_type); + bdbg(" sh_flags: %08x\n", shdr->sh_flags); + bdbg(" sh_addr: %08x\n", shdr->sh_addr); + bdbg(" sh_offset: %d\n", shdr->sh_offset); + bdbg(" sh_size: %d\n", shdr->sh_size); + bdbg(" sh_link: %d\n", shdr->sh_link); + bdbg(" sh_info: %d\n", shdr->sh_info); + bdbg(" sh_addralign: %d\n", shdr->sh_addralign); + bdbg(" sh_entsize: %d\n", shdr->sh_entsize); + } } - bdbg(" datasize: %08lx\n", loadinfo->datasize); - bdbg(" bsssize: %08lx\n", loadinfo->bsssize); - bdbg(" (pad): %08lx\n", loadinfo->dsize - dsize); - bdbg(" stacksize: %08lx\n", loadinfo->stacksize); - bdbg(" dsize: %08lx\n", loadinfo->dsize); - - bdbg(" RELOCS:\n"); - bdbg(" relocstart: %08lx\n", loadinfo->relocstart); - bdbg(" reloccount: %d\n", loadinfo->reloccount); - - bdbg(" HANDLES:\n"); - bdbg(" filfd: %d\n", loadinfo->filfd); } #else # define elf_dumploadinfo(i) @@ -148,7 +174,7 @@ static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo) static int elf_loadbinary(struct binary_s *binp) { struct elf_loadinfo_s loadinfo; /* Contains globals for libelf */ - int ret; + int ret; bvdbg("Loading file: %s\n", binp->filename); @@ -183,14 +209,14 @@ static int elf_loadbinary(struct binary_s *binp) /* Return the load information */ - binp->entrypt = (main_t)(loadinfo.ispace + loadinfo.entryoffs); - binp->ispace = (void*)loadinfo.ispace; - binp->dspace = (void*)loadinfo.dspace; - binp->isize = loadinfo.isize; - binp->stacksize = loadinfo.stacksize; + binp->entrypt = (main_t)(loadinfo.alloc + loadinfo.ehdr.e_entry); + binp->ispace = (void*)loadinfo.alloc; + binp->dspace = NULL; + binp->isize = loadinfo.allocsize; + binp->stacksize = CONFIG_ELF_STACKSIZE; elf_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt, - MIN(binp->isize - loadinfo.entryoffs,512)); + MIN(binp->isize - loadinfo.ehdr.e_entry, 512)); elf_uninit(&loadinfo); return OK; diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig index ba931b57e7..f16dd4e906 100644 --- a/nuttx/binfmt/libelf/Kconfig +++ b/nuttx/binfmt/libelf/Kconfig @@ -9,6 +9,12 @@ config ELF_ALIGN_LOG2 ---help--- Align all sections to this Log2 value: 0->1, 1->2, 2->4, etc. +config ELF_STACKSIZE + int "ELF Stack Size" + default 2048 + ---help--- + This is the default stack size that will will be used when starting ELF binaries. + config ELF_CONSTRUCTORS bool "C++ Static Constructor Support" default n @@ -16,13 +22,6 @@ config ELF_CONSTRUCTORS ---help--- Build in support for C++ constructors in ELF modules. -config ELF_SYMBOLS - bool "Export symbols from ELF modules" - default n - ---help--- - Allow symbols from one ELF module to be used by another. NOT - fully implemented! - config ELF_DUMPBUFFER bool "Dump ELF buffers" default n diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs index 6299618637..82f5f3e64e 100644 --- a/nuttx/binfmt/libelf/Make.defs +++ b/nuttx/binfmt/libelf/Make.defs @@ -43,11 +43,12 @@ BINFMT_CSRCS += elf.c BINFMT_CSRCS = libelf_init.c libelf_uninit.c libelf_load.c \ libelf_unload.c libelf_verify.c libelf_read.c \ - libelf_bind.c + libelf_bind.c libelf_symbols.c # Hook the libelf subdirectory into the build VPATH += libelf SUBDIRS += libelf +DEPPATH += --dep-path libelf endif diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h index ed352865c6..a7ffbc6a69 100644 --- a/nuttx/binfmt/libelf/libelf.h +++ b/nuttx/binfmt/libelf/libelf.h @@ -42,8 +42,11 @@ #include +#include #include +#include + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -53,14 +56,58 @@ ****************************************************************************/ /**************************************************************************** - * Name: arch_checkarch + * Name: elf_verifyheader * * Description: - * Given the ELF header in hdr, verify that the ELF file is appropriate - * for the current, configured architecture. + * Given the header from a possible ELF executable, verify that it is + * an ELF executable. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. * ****************************************************************************/ -bool arch_checkarch(const struct Elf32_Ehdr *hdr); +int elf_verifyheader(FAR const Elf32_Ehdr *header); + +/**************************************************************************** + * Name: elf_read + * + * Description: + * Read 'readsize' bytes from the object file at 'offset' + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer, + size_t readsize, off_t offset); + +/**************************************************************************** + * Name: elf_findsymtab + * + * Description: + * Find the symbol table section. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_findsymtab(FAR struct elf_loadinfo_s *loadinfo); + +/**************************************************************************** + * Name: elf_readsym + * + * Description: + * Read the ELFT symbol structure at the specfied index into memory. + * + ****************************************************************************/ + +int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index, + FAR Elf32_Sym *sym); #endif /* __BINFMT_LIBELF_LIBELF_H */ diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c index 74b713b9e3..dd75809ec3 100644 --- a/nuttx/binfmt/libelf/libelf_bind.c +++ b/nuttx/binfmt/libelf/libelf_bind.c @@ -49,6 +49,8 @@ #include #include +#include "libelf.h" + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -79,6 +81,120 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: elf_readsym + * + * Description: + * Read the ELFT symbol structure at the specfied index into memory. + * + ****************************************************************************/ + +static inline int elf_readrel(FAR struct elf_loadinfo_s *loadinfo, + FAR const Elf32_Shdr *relsec, + int index, FAR Elf32_Rel *rel) +{ + off_t offset; + + /* Verify that the symbol table index lies within symbol table */ + + if (index < 0 || index > (relsec->sh_size / sizeof(Elf32_Rel))) + { + bdbg("Bad relocation symbol index: %d\n", index); + return -EINVAL; + } + + /* Get the file offset to the symbol table entry */ + + offset = relsec->sh_offset + sizeof(Elf32_Rel) * index; + + /* And, finally, read the symbol table entry into memory */ + + return elf_read(loadinfo, (FAR uint8_t*)rel, sizeof(Elf32_Rel), offset); +} + +/**************************************************************************** + * Name: elf_relocate and elf_relocateadd + * + * Description: + * Perform all relocations associated with a section. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx) +{ + FAR Elf32_Shdr *relsec = &loadinfo->shdr[relidx]; + FAR Elf32_Shdr *dstsec = &loadinfo->shdr[relsec->sh_info]; + Elf32_Rel rel; + Elf32_Sym sym; + uintptr_t addr; + int symidx; + int ret; + int i; + + /* Examine each relocation in the section */ + + for (i = 0; i < relsec->sh_size / sizeof(Elf32_Rel); i++) + { + /* Read the relocation entry into memory */ + + ret = elf_readrel(loadinfo, relsec, i, &rel); + if (ret < 0) + { + bdbg("Section %d reloc %d: Failed to read relocation entry: %d\n", + relidx, i, ret); + return ret; + } + + /* Get the symbol table index for the relocation. This is contained + * in a bit-field within the r_info element. + */ + + symidx = ELF32_R_SYM(rel.r_info); + + /* Read the symbol table entry into memory */ + + ret = elf_readsym(loadinfo, symidx, &sym); + if (ret < 0) + { + bdbg("Section %d reloc %d: Failed to read symbol[%d]: %d\n", + relidx, i, symidx, ret); + return ret; + } + + /* Calculate the relocation address */ + + if (rel.r_offset < 0 || rel.r_offset > dstsec->sh_size - sizeof(uint32_t)) + { + bdbg("Section %d reloc %d: Relocation address out of range, offset %d size %d\n", + relidx, i, rel.r_offset, dstsec->sh_size); + return -EINVAL; + } + + addr = dstsec->sh_addr + rel.r_offset; + + /* Now perform the architecture-specific relocation */ + + ret = arch_relocate(&rel, &sym, addr); + if (ret < 0) + { + bdbg("Section %d reloc %d: Relocation failed: %d\n", ret); + return ret; + } + } + + return OK; +} + +static int elf_relocateadd(FAR struct elf_loadinfo_s *loadinfo, int relidx) +{ + bdbg("Not implemented\n"); + return -ENOSYS; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -99,7 +215,58 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo, FAR const struct symtab_s *exports, int nexports) { -#warning "Missing logic" - return -ENOSYS; + int ret; + int i; + + /* Find the symbol and string tables */ + + ret = elf_findsymtab(loadinfo); + if (ret < 0) + { + return ret; + } + + /* Process relocations in every allocated section */ + + for (i = 1; i < loadinfo->ehdr.e_shnum; i++) + { + /* Get the index to the relocation section */ + + int infosec = loadinfo->shdr[i].sh_info; + if (infosec >= loadinfo->ehdr.e_shnum) + { + continue; + } + + /* Make sure that the section is allocated. We can't relocated + * sections that were not loaded into memory. + */ + + if ((loadinfo->shdr[infosec].sh_flags & SHF_ALLOC) == 0) + { + continue; + } + + /* Process the relocations by type */ + + if (loadinfo->shdr[i].sh_type == SHT_REL) + { + ret = elf_relocate(loadinfo, i); + } + else if (loadinfo->shdr[i].sh_type == SHT_RELA) + { + ret = elf_relocateadd(loadinfo, i); + } + + if (ret < 0) + { + break; + } + } + + /* Flush the instruction cache before starting the newly loaded module */ + + arch_flushicache((FAR void*)loadinfo->alloc, loadinfo->allocsize); + return ret; } diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c index cf62666b97..a3a320b165 100644 --- a/nuttx/binfmt/libelf/libelf_init.c +++ b/nuttx/binfmt/libelf/libelf_init.c @@ -49,6 +49,8 @@ #include +#include "libelf.h" + /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ @@ -114,7 +116,7 @@ int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo) /* Read the ELF ehdr from offset 0 */ - ret = elf_read(loadinfo, (char*)&loadinfo->ehdr, sizeof(Elf32_Ehdr), 0); + ret = elf_read(loadinfo, (FAR uint8_t*)&loadinfo->ehdr, sizeof(Elf32_Ehdr), 0); if (ret < 0) { bdbg("Failed to read ELF header: %d\n", ret); diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index c30c109ce3..127ebb3143 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -46,11 +46,15 @@ #include #include #include -#include +#include #include +#include +#include #include +#include "libelf.h" + /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ @@ -104,7 +108,7 @@ static inline int elf_filelen(FAR struct elf_loadinfo_s *loadinfo) if (!S_ISREG(buf.st_mode)) { bdbg("Not a regular file. mode: %d\n", buf.st_mode); - return -errval; + return -ENOENT; } /* TODO: Verify that the file is readable */ @@ -132,20 +136,20 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) size_t shdrsize; int ret; - DEBUGASSERT(loadinfo->shdrs == NULL); + DEBUGASSERT(loadinfo->shdr == NULL); /* Verify that there are sections */ - if (loadinfo->e_shum < 1) + if (loadinfo->ehdr.e_shnum < 1) { - bdbg("No section(?)\n"); + bdbg("No sections(?)\n"); return -EINVAL; } /* Get the total size of the section header table */ - shdrsize = (size_t)loadinfo->ehdr.e_shentsize * (size_t)loadinfo->e_shum; - if(loadinfo->e_shoff + shdrsize > loadinfo->filelen) + shdrsize = (size_t)loadinfo->ehdr.e_shentsize * (size_t)loadinfo->ehdr.e_shnum; + if(loadinfo->ehdr.e_shoff + shdrsize > loadinfo->filelen) { bdbg("Insufficent space in file for section header table\n"); return -ESPIPE; @@ -153,8 +157,8 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) /* Allocate memory to hold a working copy of the sector header table */ - loadinfo->shdrs = (FAR Elf32_Shdr*)kmalloc(shdrsize); - if (!loadinfo->shdrs) + loadinfo->shdr = (FAR Elf32_Shdr*)kmalloc(shdrsize); + if (!loadinfo->shdr) { bdbg("Failed to allocate the section header table. Size: %ld\n", (long)shdrsize); return -ENOMEM; @@ -162,7 +166,7 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) /* Read the section header table into memory */ - ret = elf_read(loadinfo, loadinfo->shdrs, shdrsize, loadinfo->e_shoff); + ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->shdr, shdrsize, loadinfo->ehdr.e_shoff); if (ret < 0) { bdbg("Failed to read section header table: %d\n", ret); @@ -172,8 +176,8 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) return OK; errout_with_alloc: - kfree(loadinfo->shdrs); - loadinfo->shdrs = 0; + kfree(loadinfo->shdr); + loadinfo->shdr = 0; return ret; } @@ -189,7 +193,7 @@ errout_with_alloc: * ****************************************************************************/ -static void elf_allocsize(struct load_info *loadinfo) +static void elf_allocsize(struct elf_loadinfo_s *loadinfo) { size_t allocsize; int i; @@ -199,7 +203,7 @@ static void elf_allocsize(struct load_info *loadinfo) allocsize = 0; for (i = 0; i < loadinfo->ehdr.e_shnum; i++) { - FAR Elf32_Shdr *shdr = &loadinfo->shdrs[i]; + FAR Elf32_Shdr *shdr = &loadinfo->shdr[i]; /* SHF_ALLOC indicates that the section requires memory during * execution. @@ -213,7 +217,7 @@ static void elf_allocsize(struct load_info *loadinfo) /* Save the allocation size */ - loadinfo->allocize = allocsize; + loadinfo->allocsize = allocsize; } /**************************************************************************** @@ -221,7 +225,8 @@ static void elf_allocsize(struct load_info *loadinfo) * * Description: * Allocate memory for the file and read the section data into the - * allocated memory. + * allocated memory. Section addresses in the shdr[] are updated to point + * to the corresponding position in the allocated memory. * * Returned Value: * 0 (OK) is returned on success and a negated errno is returned on @@ -229,14 +234,15 @@ static void elf_allocsize(struct load_info *loadinfo) * ****************************************************************************/ -static inline int elf_loadfile(FAR struct load_info *loadinfo) +static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo) { FAR uint8_t *dest; + int ret; int i; /* Allocate (and zero) memory for the ELF file. */ - loadinfo->alloc = kzalloc(loadinfo->allocsize); + loadinfo->alloc = (uintptr_t)kzalloc(loadinfo->allocsize); if (!loadinfo->alloc) { return -ENOMEM; @@ -249,7 +255,7 @@ static inline int elf_loadfile(FAR struct load_info *loadinfo) for (i = 0; i < loadinfo->ehdr.e_shnum; i++) { - FAR Elf32_Shdr *shdr = &loadinfo->shdrs[i]; + FAR Elf32_Shdr *shdr = &loadinfo->shdr[i]; /* SHF_ALLOC indicates that the section requires memory during * execution */ @@ -275,7 +281,7 @@ static inline int elf_loadfile(FAR struct load_info *loadinfo) } } - /* Update sh_addr to point to copy in image. */ + /* Update sh_addr to point to copy in memory */ shdr->sh_addr = (uintptr_t)dest; bvdbg("%d. 0x%lx %s\n", (long)shdr->sh_addr, loadinfo->secstrings + shdr->sh_name); @@ -288,7 +294,7 @@ static inline int elf_loadfile(FAR struct load_info *loadinfo) return OK; errout_with_alloc: - kfree(loadinfo->alloc); + kfree((FAR void*)loadinfo->alloc); loadinfo->alloc = 0; return ret; } @@ -344,15 +350,16 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) goto errout_with_shdrs; } + /* Find static constructors. */ +#warning "Missing logic" + return OK; /* Error exits */ -errout_with_alloc: - kfree(loadinfo->alloc); errout_with_shdrs: - kfree(loadinfo->shdrs); -errout: + kfree(loadinfo->shdr); + loadinfo->shdr = NULL; return ret; } diff --git a/nuttx/binfmt/libelf/libelf_symbols.c b/nuttx/binfmt/libelf/libelf_symbols.c new file mode 100644 index 0000000000..4788c874ca --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_symbols.c @@ -0,0 +1,134 @@ +/**************************************************************************** + * binfmt/libelf/libelf_symbols.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "libelf.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_findsymtab + * + * Description: + * Find the symbol table section. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_findsymtab(FAR struct elf_loadinfo_s *loadinfo) +{ + int i; + + /* Find the symbol table section header and its associated string table */ + + for (i = 1; i < loadinfo->ehdr.e_shnum; i++) + { + if (loadinfo->shdr[i].sh_type == SHT_SYMTAB) + { + loadinfo->symtabidx = i; + loadinfo->strtabidx = loadinfo->shdr[i].sh_link; + break; + } + } + + /* Verify that there is a symbol and string table */ + + if (loadinfo->symtabidx == 0) + { + bdbg("No symbols in ELF file\n"); + return -EINVAL; + } + + return OK; +} + +/**************************************************************************** + * Name: elf_readsym + * + * Description: + * Read the ELFT symbol structure at the specfied index into memory. + * + ****************************************************************************/ + +int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index, + FAR Elf32_Sym *sym) +{ + FAR Elf32_Shdr *symtab = &loadinfo->shdr[loadinfo->symtabidx]; + off_t offset; + + /* Verify that the symbol table index lies within symbol table */ + + if (index < 0 || index > (symtab->sh_size / sizeof(Elf32_Sym))) + { + bdbg("Bad relocation symbol index: %d\n", index); + return -EINVAL; + } + + /* Get the file offset to the symbol table entry */ + + offset = symtab->sh_offset + sizeof(Elf32_Sym) * index; + + /* And, finally, read the symbol table entry into memory */ + + return elf_read(loadinfo, (FAR uint8_t*)sym, sizeof(Elf32_Sym), offset); +} diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c index 217a1981ef..ca8d2b708a 100644 --- a/nuttx/binfmt/libelf/libelf_unload.c +++ b/nuttx/binfmt/libelf/libelf_unload.c @@ -39,10 +39,10 @@ #include -#include #include #include +#include #include /**************************************************************************** @@ -81,14 +81,14 @@ int elf_unload(struct elf_loadinfo_s *loadinfo) if (loadinfo->alloc) { kfree((void*)loadinfo->alloc); - loadinfo->alloc = NULL; + loadinfo->alloc = 0; loadinfo->allocsize = 0; } - if (loadinfo->shdrs) + if (loadinfo->shdr) { - kfree((void*)loadinfo->shdrs); - loadinfo->shdrs = 0; + kfree((void*)loadinfo->shdr); + loadinfo->shdr = NULL; } return OK; diff --git a/nuttx/binfmt/libelf/libelf_verify.c b/nuttx/binfmt/libelf/libelf_verify.c index 0e0dd8e1ae..c5f185ec3f 100644 --- a/nuttx/binfmt/libelf/libelf_verify.c +++ b/nuttx/binfmt/libelf/libelf_verify.c @@ -53,7 +53,7 @@ * Private Constant Data ****************************************************************************/ -static const char g_elfmagic[EI_MAGIC_SIZE] = { 0x7f, 'E', 'L', 'F' } +static const char g_elfmagic[EI_MAGIC_SIZE] = { 0x7f, 'E', 'L', 'F' }; /**************************************************************************** * Private Functions @@ -75,12 +75,12 @@ static const char g_elfmagic[EI_MAGIC_SIZE] = { 0x7f, 'E', 'L', 'F' } * failure. * * -ENOEXEC : Not an ELF file - * -EINVALID : Not a relocatable ELF file or not supported by the current, + * -EINVAL : Not a relocatable ELF file or not supported by the current, * configured architecture. * ****************************************************************************/ -int elf_verifyheader(const Elf32_Ehdr *ehdr) +int elf_verifyheader(FAR const Elf32_Ehdr *ehdr) { if (!ehdr) { @@ -102,7 +102,7 @@ int elf_verifyheader(const Elf32_Ehdr *ehdr) if (ehdr->e_type != ET_REL) { bdbg("Not a relocatable file: e_type=%d\n", ehdr->e_type); - return -EINVALID; + return -EINVAL; } /* Verify that this file works with the currently configured architecture */ diff --git a/nuttx/binfmt/libnxflat/Make.defs b/nuttx/binfmt/libnxflat/Make.defs index 59c3ce3344..4462e9a024 100644 --- a/nuttx/binfmt/libnxflat/Make.defs +++ b/nuttx/binfmt/libnxflat/Make.defs @@ -49,5 +49,6 @@ BINFMT_CSRCS = libnxflat_init.c libnxflat_uninit.c libnxflat_load.c \ VPATH += libnxflat SUBDIRS += libnxflat +DEPPATH += --dep-path libnxflat endif diff --git a/nuttx/include/elf.h b/nuttx/include/elf.h index dbc615dcd0..ec7aecf637 100644 --- a/nuttx/include/elf.h +++ b/nuttx/include/elf.h @@ -231,73 +231,73 @@ /* Figure 4.2: 32-Bit Data Types */ -typedef uint32_t ELF32_Addr /* Unsigned program address */ -typedef uint16_t ELF32_Half /* Unsigned medium integer */ -typedef uint32_t ELF32_Off /* Unsigned file offset */ -typedef int32_t ELF32_Sword /* Signed large integer */ -typedef uint32_t ELF32_Word /* Unsigned large integer */ +typedef uint32_t Elf32_Addr; /* Unsigned program address */ +typedef uint16_t Elf32_Half; /* Unsigned medium integer */ +typedef uint32_t Elf32_Off; /* Unsigned file offset */ +typedef int32_t Elf32_Sword; /* Signed large integer */ +typedef uint32_t Elf32_Word; /* Unsigned large integer */ /* Figure 4-3: ELF Header */ typedef struct { unsigned char e_ident[EI_NIDENT]; - ELF32_Half e_type; - ELF32_Half e_machine; - ELF32_Word e_version; - ELF32_Addr e_entry; - ELF32_Off e_phoff; - ELF32_Off e_shoff; - ELF32_Word e_flags; - ELF32_Half e_ehsize; - ELF32_Half e_phentsize; - ELF32_Half e_phnum; - ELF32_Half e_shentsize; - ELF32_Half e_shnum; - ELF32_Half e_shstrndx; + Elf32_Half e_type; + Elf32_Half e_machine; + Elf32_Word e_version; + Elf32_Addr e_entry; + Elf32_Off e_phoff; + Elf32_Off e_shoff; + Elf32_Word e_flags; + Elf32_Half e_ehsize; + Elf32_Half e_phentsize; + Elf32_Half e_phnum; + Elf32_Half e_shentsize; + Elf32_Half e_shnum; + Elf32_Half e_shstrndx; } Elf32_Ehdr; /* Figure 4-8: Section Header */ typedef struct { - ELF32_Word sh_name; - ELF32_Word sh_type; - ELF32_Word sh_flags; - ELF32_Addr sh_addr; - ELF32_Off sh_offset; - ELF32_Word sh_size; - ELF32_Word sh_link; - ELF32_Word sh_info; - ELF32_Word sh_addralign; - ELF32_Word sh_entsize; + Elf32_Word sh_name; + Elf32_Word sh_type; + Elf32_Word sh_flags; + Elf32_Addr sh_addr; + Elf32_Off sh_offset; + Elf32_Word sh_size; + Elf32_Word sh_link; + Elf32_Word sh_info; + Elf32_Word sh_addralign; + Elf32_Word sh_entsize; } Elf32_Shdr; /* Figure 4-15: Symbol Table Entry */ typedef struct { - ELF32_Word st_name; - ELF32_Addr st_value; - ELF32_Word st_size; + Elf32_Word st_name; + Elf32_Addr st_value; + Elf32_Word st_size; unsigned char st_info; unsigned char st_other; - ELF32_Half st_shndx; + Elf32_Half st_shndx; } Elf32_Sym; /* Figure 4-19: Relocation Entries */ typedef struct { - ELF32_Addr r_offset; - ELF32_Word r_info; + Elf32_Addr r_offset; + Elf32_Word r_info; } Elf32_Rel; typedef struct { - ELF32_Addr r_offset; - ELF32_Word r_info; - ELF32_Sword r_addend; + Elf32_Addr r_offset; + Elf32_Word r_info; + Elf32_Sword r_addend; } Elf32_Rela; /* Figure 5-1: Program Header */ diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h index 8e7658d5d8..dc28c5c6a1 100644 --- a/nuttx/include/nuttx/binfmt/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -42,9 +42,10 @@ #include +#include #include +#include #include -#include /**************************************************************************** * Pre-processor Definitions @@ -72,6 +73,8 @@ struct elf_loadinfo_s uintptr_t ctors; /* Static constructors */ #endif int filfd; /* Descriptor for the file being loaded */ + uint16_t symtabidx; /* Symbol table section index */ + uint16_t strtabidx; /* String table section index */ Elf32_Ehdr ehdr; /* Buffered ELF file header */ FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */ }; @@ -89,24 +92,9 @@ extern "C" { #endif /**************************************************************************** - * These are APIs exported by libelf (and may be used outside of NuttX): + * These are APIs exported by libelf (but are used only by the binfmt logic): ****************************************************************************/ -/**************************************************************************** - * Name: elf_verifyheader - * - * Description: - * Given the header from a possible ELF executable, verify that it is - * an ELF executable. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int elf_verifyheader(FAR const Elf32_Ehdr *header); - /**************************************************************************** * Name: elf_init * @@ -153,21 +141,6 @@ EXTERN int elf_uninit(FAR struct elf_loadinfo_s *loadinfo); EXTERN int elf_load(FAR struct elf_loadinfo_s *loadinfo); -/**************************************************************************** - * Name: elf_read - * - * Description: - * Read 'readsize' bytes from the object file at 'offset' - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTER int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer, - size_t readsize, off_t offset); - /**************************************************************************** * Name: elf_bind * @@ -233,6 +206,64 @@ EXTERN int elf_initialize(void); EXTERN void elf_uninitialize(void); +/**************************************************************************** + * Name: arch_checkarch + * + * Description: + * Given the ELF header in 'hdr', verify that the ELF file is appropriate + * for the current, configured architecture. Every architecture that uses + * the ELF loader must provide this function. + * + * Input Parameters: + * hdr - The ELF header read from the ELF file. + * + * Returned Value: + * True if the architecture supports this ELF file. + * + ****************************************************************************/ + +EXTERN bool arch_checkarch(FAR const Elf32_Ehdr *hdr); + +/**************************************************************************** + * Name: arch_relocate and arch_relocateadd + * + * Description: + * Perform on architecture-specific ELF relocation. Every architecture + * that uses the ELF loader must provide this function. + * + * Input Parameters: + * rel - The relocation type + * sym - The ELF symbol structure containing the fully resolved value. + * addr - The address that requires the relocation. + * + * Returned Value: + * Zero (OK) if the relocation was successful. Otherwise, a negated errno + * value indicating the cause of the relocation failure. + * + ****************************************************************************/ + +EXTERN int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, + uintptr_t addr); +EXTERN int arch_relocateadd(FAR const Elf32_Rela *rel, + FAR const Elf32_Sym *sym, uintptr_t addr); + +/**************************************************************************** + * Name: arch_flushicache + * + * Description: + * Flush the instruction cache. + * + * Input Parameters: + * addr - Start address to flush + * len - Number of bytes to flush + * + * Returned Value: + * True if the architecture supports this ELF file. + * + ****************************************************************************/ + +EXTERN bool arch_flushicache(FAR void *addr, size_t len); + #undef EXTERN #if defined(__cplusplus) } From c0a46ad696848fc17714a1578cd710835c56eae6 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 25 Oct 2012 16:37:31 +0000 Subject: [PATCH 027/206] Add x86 ELF support git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5258 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/arch/sim/src/Makefile | 4 + nuttx/arch/sim/src/up_elf.c | 139 +++++++++++++++++++++++++++++ nuttx/arch/x86/src/common/up_elf.c | 139 +++++++++++++++++++++++++++++ nuttx/binfmt/libelf/libelf_bind.c | 2 + nuttx/include/elf.h | 24 ++++- nuttx/include/nuttx/binfmt/elf.h | 7 +- 7 files changed, 313 insertions(+), 4 deletions(-) create mode 100644 nuttx/arch/sim/src/up_elf.c create mode 100644 nuttx/arch/x86/src/common/up_elf.c diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index c2c9a1413a..2006fcc216 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3513,4 +3513,6 @@ in is non-functional and is simply the framework for ELF support. * include/nuttx/binfmt.h, nxflat.h, elf.h, and symtab.h: Moved to include/nuttx/binfmt/. + * arch/sim/src/up_elf.c and arch/x86/src/common/up_elf.c: Add + for ELF modules. diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile index d74e1c005b..43210e37b9 100644 --- a/nuttx/arch/sim/src/Makefile +++ b/nuttx/arch/sim/src/Makefile @@ -60,6 +60,10 @@ endif endif endif +ifeq ($(CONFIG_ELF),y) +CSRCS += up_elf.c +endif + ifeq ($(CONFIG_FS_FAT),y) CSRCS += up_blockdevice.c up_deviceimage.c endif diff --git a/nuttx/arch/sim/src/up_elf.c b/nuttx/arch/sim/src/up_elf.c new file mode 100644 index 0000000000..c6aabdcef7 --- /dev/null +++ b/nuttx/arch/sim/src/up_elf.c @@ -0,0 +1,139 @@ +/**************************************************************************** + * arch/sim/src/up_elf.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "up_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define R_386_32 1 +#define R_386_PC32 2 + +#define ELF_BITS 32 +#define ELF_ARCH EM_386 + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: arch_checkarch + * + * Description: + * Given the ELF header in 'hdr', verify that the ELF file is appropriate + * for the current, configured architecture. Every architecture that uses + * the ELF loader must provide this function. + * + * Input Parameters: + * hdr - The ELF header read from the ELF file. + * + * Returned Value: + * True if the architecture supports this ELF file. + * + ****************************************************************************/ + +bool arch_checkarch(FAR const Elf32_Ehdr *hdr) +{ + return hdr->e_machine == EM_386 || hdr->e_machine == EM_486; +} + +/**************************************************************************** + * Name: arch_relocate and arch_relocateadd + * + * Description: + * Perform on architecture-specific ELF relocation. Every architecture + * that uses the ELF loader must provide this function. + * + * Input Parameters: + * rel - The relocation type + * sym - The ELF symbol structure containing the fully resolved value. + * addr - The address that requires the relocation. + * + * Returned Value: + * Zero (OK) if the relocation was successful. Otherwise, a negated errno + * value indicating the cause of the relocation failure. + * + ****************************************************************************/ + +int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, + uintptr_t addr) +{ + FAR uint32_t *ptr = (FAR uint32_t *)addr; + + switch (ELF_REL_TYPE(rel->r_info)) + { + case R_386_32: + *ptr += sym->st_value; + break; + + case R_386_PC32: + *ptr += sym->st_value - (uint32_t)ptr; + break; + + default: + return -EINVAL; + } + + return OK; +} + +int arch_relocateadd(FAR const Elf32_Rela *rel, FAR const Elf32_Sym *sym, + uintptr_t addr) +{ + bdbg("Not supported\n"); + return -ENOSYS; +} + diff --git a/nuttx/arch/x86/src/common/up_elf.c b/nuttx/arch/x86/src/common/up_elf.c new file mode 100644 index 0000000000..f159c8e518 --- /dev/null +++ b/nuttx/arch/x86/src/common/up_elf.c @@ -0,0 +1,139 @@ +/**************************************************************************** + * arch/x86/src/up_elf.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "up_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define R_386_32 1 +#define R_386_PC32 2 + +#define ELF_BITS 32 +#define ELF_ARCH EM_386 + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: arch_checkarch + * + * Description: + * Given the ELF header in 'hdr', verify that the ELF file is appropriate + * for the current, configured architecture. Every architecture that uses + * the ELF loader must provide this function. + * + * Input Parameters: + * hdr - The ELF header read from the ELF file. + * + * Returned Value: + * True if the architecture supports this ELF file. + * + ****************************************************************************/ + +bool arch_checkarch(FAR const Elf32_Ehdr *hdr) +{ + return hdr->e_machine == EM_386 || hdr->e_machine == EM_486; +} + +/**************************************************************************** + * Name: arch_relocate and arch_relocateadd + * + * Description: + * Perform on architecture-specific ELF relocation. Every architecture + * that uses the ELF loader must provide this function. + * + * Input Parameters: + * rel - The relocation type + * sym - The ELF symbol structure containing the fully resolved value. + * addr - The address that requires the relocation. + * + * Returned Value: + * Zero (OK) if the relocation was successful. Otherwise, a negated errno + * value indicating the cause of the relocation failure. + * + ****************************************************************************/ + +int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, + uintptr_t addr) +{ + FAR uint32_t *ptr = (FAR uint32_t *)addr; + + switch (ELF_REL_TYPE(rel->r_info)) + { + case R_386_32: + *ptr += sym->st_value; + break; + + case R_386_PC32: + *ptr += sym->st_value - (uint32_t)ptr; + break; + + default: + return -EINVAL; + } + + return OK; +} + +int arch_relocateadd(FAR const Elf32_Rela *rel, FAR const Elf32_Sym *sym, + uintptr_t addr) +{ + bdbg("Not supported\n"); + return -ENOSYS; +} + diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c index dd75809ec3..e9491af0e4 100644 --- a/nuttx/binfmt/libelf/libelf_bind.c +++ b/nuttx/binfmt/libelf/libelf_bind.c @@ -266,7 +266,9 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo, /* Flush the instruction cache before starting the newly loaded module */ +#ifdef CONFIG_ELF_ICACHE arch_flushicache((FAR void*)loadinfo->alloc, loadinfo->allocsize); +#endif return ret; } diff --git a/nuttx/include/elf.h b/nuttx/include/elf.h index ec7aecf637..1b36701fda 100644 --- a/nuttx/include/elf.h +++ b/nuttx/include/elf.h @@ -73,10 +73,28 @@ #define EM_386 3 /* Intel 80386 */ #define EM_68K 4 /* Motorola 68000 */ #define EM_88K 5 /* Motorola 88000 */ +#define EM_486 6 /* Intel 486+ */ #define EM_860 7 /* Intel 80860 */ -#define EM_MIPS 8 /* MIPS RS3000 Big-Endian */ -#define EM_MIPS_RS4_BE 10 /* MIPS RS4000 Big-Endian */ - /* 11-16 Reserved for future use */ +#define EM_MIPS 8 /* MIPS R3000 Big-Endian */ +#define EM_MIPS_RS4_BE 10 /* MIPS R4000 Big-Endian */ +#define EM_PARISC 15 /* HPPA */ +#define EM_SPARC32PLUS 18 /* Sun's "v8plus" */ +#define EM_PPC 20 /* PowerPC */ +#define EM_PPC64 21 /* PowerPC64 */ +#define EM_SH 42 /* SuperH */ +#define EM_SPARCV9 43 /* SPARC v9 64-bit */ +#define EM_IA_64 50 /* HP/Intel IA-64 */ +#define EM_X86_64 62 /* AMD x86-64 */ +#define EM_S390 22 /* IBM S/390 */ +#define EM_CRIS 76 /* Axis Communications 32-bit embedded processor */ +#define EM_V850 87 /* NEC v850 */ +#define EM_M32R 88 /* Renesas M32R */ +#define EM_H8_300 46 +#define EM_ALPHA 0x9026 +#define EM_CYGNUS_V850 0x9080 +#define EM_CYGNUS_M32R 0x9041 +#define EM_S390_OLD 0xa390 +#define EM_FRV 0x5441 /* Values for Elf32_Ehdr::e_version */ diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h index dc28c5c6a1..8a12c5019f 100644 --- a/nuttx/include/nuttx/binfmt/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -174,7 +174,7 @@ EXTERN int elf_bind(FAR struct elf_loadinfo_s *loadinfo, EXTERN int elf_unload(struct elf_loadinfo_s *loadinfo); /**************************************************************************** - * These are APIs used internally only by NuttX: + * These are APIs used outside of binfmt by NuttX: ****************************************************************************/ /**************************************************************************** * Name: elf_initialize @@ -206,6 +206,9 @@ EXTERN int elf_initialize(void); EXTERN void elf_uninitialize(void); +/**************************************************************************** + * These are APIs must be provided by architecture-specific logic: + ****************************************************************************/ /**************************************************************************** * Name: arch_checkarch * @@ -262,7 +265,9 @@ EXTERN int arch_relocateadd(FAR const Elf32_Rela *rel, * ****************************************************************************/ +#ifdef CONFIG_ELF_ICACHE EXTERN bool arch_flushicache(FAR void *addr, size_t len); +#endif #undef EXTERN #if defined(__cplusplus) From 9c65fe23b234977b27e37cb90a674fd8e38dc45a Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 25 Oct 2012 19:21:47 +0000 Subject: [PATCH 028/206] Finishes basic coding of ELF file support git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5259 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/binfmt/libelf/Kconfig | 17 +++ nuttx/binfmt/libelf/Make.defs | 4 + nuttx/binfmt/libelf/libelf.h | 69 +++++++++ nuttx/binfmt/libelf/libelf_bind.c | 44 +++++- nuttx/binfmt/libelf/libelf_ctors.c | 134 ++++++++++++++++++ nuttx/binfmt/libelf/libelf_load.c | 12 +- nuttx/binfmt/libelf/libelf_symbols.c | 204 ++++++++++++++++++++++++++- nuttx/binfmt/libelf/libelf_unload.c | 11 +- nuttx/include/nuttx/binfmt/elf.h | 9 +- 9 files changed, 493 insertions(+), 11 deletions(-) create mode 100644 nuttx/binfmt/libelf/libelf_ctors.c diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig index f16dd4e906..5dc4a2d9fe 100644 --- a/nuttx/binfmt/libelf/Kconfig +++ b/nuttx/binfmt/libelf/Kconfig @@ -15,6 +15,23 @@ config ELF_STACKSIZE ---help--- This is the default stack size that will will be used when starting ELF binaries. +config ELF_BUFFERSIZE + int "ELF I/O Buffer Size" + default 128 + ---help--- + This is an I/O buffer that is used to access the ELF file. Variable length items + will need to be read (such as symbol names). This is really just this initial + size of the buffer; it will be reallocated as necessary to hold large symbol + names). Default: 128 + +config ELF_BUFFERINCR + int "ELF I/O Buffer Realloc Increment" + default 32 + ---help--- + This is an I/O buffer that is used to access the ELF file. Variable length items + will need to be read (such as symbol names). This value specifies the size + increment to use each time the buffer is reallocated. Default: 32 + config ELF_CONSTRUCTORS bool "C++ Static Constructor Support" default n diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs index 82f5f3e64e..9e06537bd6 100644 --- a/nuttx/binfmt/libelf/Make.defs +++ b/nuttx/binfmt/libelf/Make.defs @@ -45,6 +45,10 @@ BINFMT_CSRCS = libelf_init.c libelf_uninit.c libelf_load.c \ libelf_unload.c libelf_verify.c libelf_read.c \ libelf_bind.c libelf_symbols.c +ifeq ($(CONFIG_ELF_CONSTRUCTORS),y) +BINFMT_CSRCS += libelf_ctors.c +endif + # Hook the libelf subdirectory into the build VPATH += libelf diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h index a7ffbc6a69..37a2ad872d 100644 --- a/nuttx/binfmt/libelf/libelf.h +++ b/nuttx/binfmt/libelf/libelf.h @@ -105,9 +105,78 @@ int elf_findsymtab(FAR struct elf_loadinfo_s *loadinfo); * Description: * Read the ELFT symbol structure at the specfied index into memory. * + * Input Parameters: + * loadinfo - Load state information + * index - Symbol table index + * sym - Location to return the table entry + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * ****************************************************************************/ int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index, FAR Elf32_Sym *sym); +/**************************************************************************** + * Name: elf_symvalue + * + * Description: + * Get the value of a symbol. The updated value of the symbol is returned + * in the st_value field of the symbol table entry. + * + * Input Parameters: + * loadinfo - Load state information + * sym - Symbol table entry (value might be undefined) + * exports - The symbol table to use for resolving undefined symbols. + * nexports - Number of symbols in the symbol table. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_symvalue(FAR struct elf_loadinfo_s *loadinfo, FAR Elf32_Sym *sym, + FAR const struct symtab_s *exports, int nexports); + +/**************************************************************************** + * Name: elf_findctors + * + * Description: + * Find C++ static constructors. + * + * Input Parameters: + * loadinfo - Load state information + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +#ifdef CONFIG_ELF_CONSTRUCTORS +int elf_findctors(FAR struct elf_loadinfo_s *loadinfo); +#endif + +/**************************************************************************** + * Name: elf_doctors + * + * Description: + * Execute C++ static constructors. + * + * Input Parameters: + * loadinfo - Load state information + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +#ifdef CONFIG_ELF_CONSTRUCTORS +int elf_doctors(FAR struct elf_loadinfo_s *loadinfo); +#endif + #endif /* __BINFMT_LIBELF_LIBELF_H */ diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c index e9491af0e4..e398521cca 100644 --- a/nuttx/binfmt/libelf/libelf_bind.c +++ b/nuttx/binfmt/libelf/libelf_bind.c @@ -46,6 +46,7 @@ #include #include +#include #include #include @@ -63,6 +64,10 @@ # undef CONFIG_ELF_DUMPBUFFER #endif +#ifndef CONFIG_ELF_BUFFERSIZE +# define CONFIG_ELF_BUFFERSIZE 128 +#endif + #ifdef CONFIG_ELF_DUMPBUFFER # define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n) #else @@ -124,7 +129,9 @@ static inline int elf_readrel(FAR struct elf_loadinfo_s *loadinfo, * ****************************************************************************/ -static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx) +static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx, + FAR const struct symtab_s *exports, int nexports) + { FAR Elf32_Shdr *relsec = &loadinfo->shdr[relidx]; FAR Elf32_Shdr *dstsec = &loadinfo->shdr[relsec->sh_info]; @@ -165,6 +172,16 @@ static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx) return ret; } + /* Get the value of the symbol (in sym.st_value) */ + + ret = elf_symvalue(loadinfo, &sym, exports, nexports); + if (ret < 0) + { + bdbg("Section %d reloc %d: Failed to get value of symbol[%d]: %d\n", + relidx, i, symidx, ret); + return ret; + } + /* Calculate the relocation address */ if (rel.r_offset < 0 || rel.r_offset > dstsec->sh_size - sizeof(uint32_t)) @@ -189,7 +206,8 @@ static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx) return OK; } -static int elf_relocateadd(FAR struct elf_loadinfo_s *loadinfo, int relidx) +static int elf_relocateadd(FAR struct elf_loadinfo_s *loadinfo, int relidx, + FAR const struct symtab_s *exports, int nexports) { bdbg("Not implemented\n"); return -ENOSYS; @@ -226,6 +244,18 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo, return ret; } + /* Allocate an I/O buffer. This buffer is used only by elf_symname() to + * accumulate the variable length symbol name. + */ + + loadinfo->iobuffer = (FAR uint8_t *)kmalloc(CONFIG_ELF_BUFFERSIZE); + if (!loadinfo->iobuffer) + { + bdbg("Failed to allocate an I/O buffer\n"); + return -ENOMEM; + } + loadinfo->buflen = CONFIG_ELF_BUFFERSIZE; + /* Process relocations in every allocated section */ for (i = 1; i < loadinfo->ehdr.e_shnum; i++) @@ -251,11 +281,11 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo, if (loadinfo->shdr[i].sh_type == SHT_REL) { - ret = elf_relocate(loadinfo, i); + ret = elf_relocate(loadinfo, i, exports, nexports); } else if (loadinfo->shdr[i].sh_type == SHT_RELA) { - ret = elf_relocateadd(loadinfo, i); + ret = elf_relocateadd(loadinfo, i, exports, nexports); } if (ret < 0) @@ -269,6 +299,12 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo, #ifdef CONFIG_ELF_ICACHE arch_flushicache((FAR void*)loadinfo->alloc, loadinfo->allocsize); #endif + + /* Free the I/O buffer */ + + kfree(loadinfo->iobuffer); + loadinfo->iobuffer = NULL; + loadinfo->buflen = 0; return ret; } diff --git a/nuttx/binfmt/libelf/libelf_ctors.c b/nuttx/binfmt/libelf/libelf_ctors.c new file mode 100644 index 0000000000..e8b095bb78 --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_ctors.c @@ -0,0 +1,134 @@ +/**************************************************************************** + * binfmt/libelf/libelf_ctors.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +#include "libelf" + +#ifdef CONFIG_ELF_CONSTRUCTORS + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +typedef FAR void (*ctor_t)(void); + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_findctors + * + * Description: + * Find C++ static constructors. + * + * Input Parameters: + * loadinfo - Load state information + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_findctors(FAR struct elf_loadinfo_s *loadinfo) +{ + /* Search through the shdr[] array in loadinfo for a section named .ctors */ +#warning "Missing logic" + + /* Get the address of the beginning of the constructros from the sh_addr + * field of the section. Save that in the ctors field of the loadinfo + * structure. + */ +#warning "Missing logic" + + /* Get the number of constructors from the sh_size field of the section. + * Save that number in the nctors field of the loadinfo structure. + */ +#warning "Missing logic" + return -ENOSYS; +} + +/**************************************************************************** + * Name: elf_doctors + * + * Description: + * Execute C++ static constructors. + * + * Input Parameters: + * loadinfo - Load state information + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_doctors(FAR struct elf_loadinfo_s *loadinfo) +{ + ctor_t ctor = (ctor_t)loadinfo->ctors; + int i; + + /* Execute each constructor */ + + for (i = 0; i < loadinfo->nctors; i++) + { + ctor(); + ctor++; + } +} + +#endif /* CONFIG_ELF_CONSTRUCTORS diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 127ebb3143..758f965483 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -327,6 +327,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) ret = elf_filelen(loadinfo); { + bdbg("elf_filelen failed: %d\n", ret); return ret; } @@ -335,6 +336,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) ret = elf_loadshdrs(loadinfo); if (ret < 0) { + bdbg("elf_loadshdrs failed: %d\n", ret); return ret; } @@ -347,11 +349,19 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) ret = elf_loadfile(loadinfo); if (ret < 0) { + bdbg("elf_loadfile failed: %d\n", ret); goto errout_with_shdrs; } /* Find static constructors. */ -#warning "Missing logic" + +#ifdef CONFIG_ELF_CONSTRUCTORS + ret = elf_findctors(loadinfo); + { + bdbg("elf_findctors failed: %d\n", ret); + goto errout_with_shdrs; + } +#endif return OK; diff --git a/nuttx/binfmt/libelf/libelf_symbols.c b/nuttx/binfmt/libelf/libelf_symbols.c index 4788c874ca..05f827963a 100644 --- a/nuttx/binfmt/libelf/libelf_symbols.c +++ b/nuttx/binfmt/libelf/libelf_symbols.c @@ -39,11 +39,14 @@ #include +#include +#include #include -#include #include +#include #include +#include #include "libelf.h" @@ -51,6 +54,10 @@ * Pre-Processor Definitions ****************************************************************************/ +#ifndef CONFIG_ELF_BUFFERINCR +# define CONFIG_ELF_BUFFERINCR 32 +#endif + /**************************************************************************** * Private Constant Data ****************************************************************************/ @@ -59,6 +66,101 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: elf_symname + * + * Description: + * Get the symbol name in loadinfo->iobuffer[]. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +static int elf_symname(FAR struct elf_loadinfo_s *loadinfo, + FAR const Elf32_Sym *sym) +{ + FAR uint8_t *buffer; + off_t offset; + size_t readlen; + size_t bytesread; + int ret; + + /* Get the file offset to the string that is the name of the symbol. The + * st_name member holds an offset into the file's symbol string table. + */ + + if (sym->st_name == 0) + { + bdbg("Symbol has no name\n"); + return -ENOENT; + } + + offset = loadinfo->shdr[loadinfo->strtabidx].sh_offset + sym->st_name; + + /* Loop until we get the entire symbol name into memory */ + + buffer = loadinfo->iobuffer; + bytesread = 0; + + for (;;) + { + /* Get the number of bytes to read */ + + readlen = loadinfo->buflen - bytesread; + if (offset + readlen > loadinfo->filelen) + { + readlen = loadinfo->filelen - offset; + if (readlen <= 0) + { + bdbg("At end of file\n"); + return -EINVAL; + } + } + + /* Read that number of bytes into the array */ + + buffer = &loadinfo->iobuffer[bytesread]; + ret = elf_read(loadinfo, buffer, readlen, offset); + if (ret < 0) + { + bdbg("Failed to read symbol name\n"); + return ret; + } + + bytesread += readlen; + + /* Did we read the NUL terminator? */ + + if (memchr(buffer, '\0', readlen) != NULL) + { + /* Yes, the buffer contains a NUL terminator. */ + + return OK; + } + + /* No.. then we have to read more */ + + buffer = realloc((FAR void *)loadinfo->iobuffer, + loadinfo->buflen + CONFIG_ELF_BUFFERINCR); + if (!buffer) + { + bdbg("Failed to reallocate the I/O buffer\n"); + return -ENOMEM; + } + + /* Save the new buffer info */ + + loadinfo->iobuffer = buffer; + loadinfo->buflen += CONFIG_ELF_BUFFERINCR; + } + + /* We will not get here */ + + return OK; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -108,6 +210,15 @@ int elf_findsymtab(FAR struct elf_loadinfo_s *loadinfo) * Description: * Read the ELFT symbol structure at the specfied index into memory. * + * Input Parameters: + * loadinfo - Load state information + * index - Symbol table index + * sym - Location to return the table entry + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * ****************************************************************************/ int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index, @@ -132,3 +243,94 @@ int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index, return elf_read(loadinfo, (FAR uint8_t*)sym, sizeof(Elf32_Sym), offset); } + +/**************************************************************************** + * Name: elf_symvalue + * + * Description: + * Get the value of a symbol. The updated value of the symbol is returned + * in the st_value field of the symbol table entry. + * + * Input Parameters: + * loadinfo - Load state information + * sym - Symbol table entry (value might be undefined) + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_symvalue(FAR struct elf_loadinfo_s *loadinfo, FAR Elf32_Sym *sym, + FAR const struct symtab_s *exports, int nexports) +{ + FAR const struct symtab_s *symbol; + uintptr_t secbase; + int ret; + + switch (sym->st_shndx) + { + case SHN_COMMON: + { + /* NuttX ELF modules should be compiled with -fno-common. */ + + bdbg("SHN_COMMON: Re-compile with -fno-common\n"); + return -EINVAL; + } + + case SHN_ABS: + { + /* st_value already holds the correct value */ + + bvdbg("SHN_ABS: st_value=%08lx\n", (long)sym->st_value); + return OK; + } + + case SHN_UNDEF: + { + /* Get the name of the undefined symbol */ + + ret = elf_symname(loadinfo, sym); + if (ret < 0) + { + bdbg("SHN_UNDEF: Failed to get symbol name: %d\n", ret); + return ret; + } + + /* Check if the base code exports a symbol of this name */ + +#ifdef CONFIG_SYMTAB_ORDEREDBYNAME + symbol = symtab_findorderedbyname(exports, (FAR char *)loadinfo->iobuffer, nexports); +#else + symbol = symtab_findbyname(exports, (FAR char *)loadinfo->iobuffer, nexports); +#endif + if (!symbol) + { + bdbg("SHN_UNDEF: Exported symbol \"%s\" not found\n", loadinfo->iobuffer); + return -ENOENT; + } + + /* Yes... add the exported symbol value to the ELF symbol table entry */ + + bvdbg("SHN_ABS: name=%s %08x+%08x=%08x\n", + loadinfo->iobuffer, sym->st_value, symbol->sym_value, + sym->st_value + symbol->sym_value); + + sym->st_value += (Elf32_Word)((uintptr_t)symbol->sym_value); + } + break; + + default: + { + secbase = loadinfo->shdr[sym->st_shndx].sh_addr; + + bvdbg("Other: %08x+%08x=%08x\n", + sym->st_value, secbase, sym->st_value + secbase); + + sym->st_value += secbase; + } + break; + } + + return OK; +} diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c index ca8d2b708a..3351064079 100644 --- a/nuttx/binfmt/libelf/libelf_unload.c +++ b/nuttx/binfmt/libelf/libelf_unload.c @@ -80,17 +80,24 @@ int elf_unload(struct elf_loadinfo_s *loadinfo) if (loadinfo->alloc) { - kfree((void*)loadinfo->alloc); + kfree((FAR void *)loadinfo->alloc); loadinfo->alloc = 0; loadinfo->allocsize = 0; } if (loadinfo->shdr) { - kfree((void*)loadinfo->shdr); + kfree((FAR void *)loadinfo->shdr); loadinfo->shdr = NULL; } + if (loadinfo->iobuffer) + { + kfree((FAR void *)loadinfo->iobuffer); + loadinfo->iobuffer = NULL; + loadinfo->buflen = 0; + } + return OK; } diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h index 8a12c5019f..6b13c10873 100644 --- a/nuttx/include/nuttx/binfmt/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -69,14 +69,17 @@ struct elf_loadinfo_s uintptr_t alloc; /* Allocated memory with the ELF file is loaded */ size_t allocsize; /* Size of the memory allocation */ off_t filelen; /* Length of the entire ELF file */ -#ifdef CONFIG_ELF_CONSTRUCTORS - uintptr_t ctors; /* Static constructors */ -#endif int filfd; /* Descriptor for the file being loaded */ +#ifdef CONFIG_ELF_CONSTRUCTORS + uintptr_t ctors; /* Location of static constructors in memory */ + uint16_t nctors; /* Number of constructors */ +#endif uint16_t symtabidx; /* Symbol table section index */ uint16_t strtabidx; /* String table section index */ + uint16_t buflen; /* size of iobuffer[] */ Elf32_Ehdr ehdr; /* Buffered ELF file header */ FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */ + uint8_t *iobuffer; /* File I/O buffer */ }; /**************************************************************************** From 92bbd36612825d29dcba9bab40657f197c4ff7b4 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 25 Oct 2012 20:06:46 +0000 Subject: [PATCH 029/206] Add an example for testing the ELF loader git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5260 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 3 +- apps/examples/Kconfig | 4 + apps/examples/Make.defs | 4 + apps/examples/Makefile | 2 +- apps/examples/elf/Kconfig | 13 + apps/examples/elf/Makefile | 98 ++++++ apps/examples/elf/elf_main | 224 +++++++++++++ apps/examples/elf/tests/Makefile | 100 ++++++ apps/examples/elf/tests/errno/Makefile | 59 ++++ apps/examples/elf/tests/errno/errno.c | 83 +++++ apps/examples/elf/tests/hello++/Makefile | 116 +++++++ apps/examples/elf/tests/hello++/hello++1.cpp | 60 ++++ apps/examples/elf/tests/hello++/hello++2.cpp | 123 +++++++ apps/examples/elf/tests/hello++/hello++3.cpp | 132 ++++++++ apps/examples/elf/tests/hello++/hello++4.cpp | 150 +++++++++ apps/examples/elf/tests/hello/Makefile | 58 ++++ apps/examples/elf/tests/hello/hello.c | 78 +++++ apps/examples/elf/tests/longjmp/Makefile | 58 ++++ apps/examples/elf/tests/longjmp/longjmp.c | 128 ++++++++ apps/examples/elf/tests/mkdirlist.sh | 35 ++ apps/examples/elf/tests/mksymtab.sh | 39 +++ apps/examples/elf/tests/mutex/Makefile | 58 ++++ apps/examples/elf/tests/mutex/mutex.c | 149 +++++++++ apps/examples/elf/tests/pthread/Makefile | 58 ++++ apps/examples/elf/tests/pthread/pthread.c | 143 ++++++++ apps/examples/elf/tests/signal/Makefile | 58 ++++ apps/examples/elf/tests/signal/signal.c | 308 ++++++++++++++++++ apps/examples/elf/tests/struct/Makefile | 59 ++++ apps/examples/elf/tests/struct/struct.h | 89 +++++ apps/examples/elf/tests/struct/struct_dummy.c | 65 ++++ apps/examples/elf/tests/struct/struct_main.c | 109 +++++++ apps/examples/elf/tests/task/Makefile | 58 ++++ apps/examples/elf/tests/task/task.c | 143 ++++++++ 33 files changed, 2862 insertions(+), 2 deletions(-) create mode 100644 apps/examples/elf/Kconfig create mode 100644 apps/examples/elf/Makefile create mode 100644 apps/examples/elf/elf_main create mode 100644 apps/examples/elf/tests/Makefile create mode 100644 apps/examples/elf/tests/errno/Makefile create mode 100644 apps/examples/elf/tests/errno/errno.c create mode 100644 apps/examples/elf/tests/hello++/Makefile create mode 100644 apps/examples/elf/tests/hello++/hello++1.cpp create mode 100644 apps/examples/elf/tests/hello++/hello++2.cpp create mode 100644 apps/examples/elf/tests/hello++/hello++3.cpp create mode 100644 apps/examples/elf/tests/hello++/hello++4.cpp create mode 100644 apps/examples/elf/tests/hello/Makefile create mode 100644 apps/examples/elf/tests/hello/hello.c create mode 100644 apps/examples/elf/tests/longjmp/Makefile create mode 100644 apps/examples/elf/tests/longjmp/longjmp.c create mode 100755 apps/examples/elf/tests/mkdirlist.sh create mode 100755 apps/examples/elf/tests/mksymtab.sh create mode 100644 apps/examples/elf/tests/mutex/Makefile create mode 100644 apps/examples/elf/tests/mutex/mutex.c create mode 100644 apps/examples/elf/tests/pthread/Makefile create mode 100644 apps/examples/elf/tests/pthread/pthread.c create mode 100644 apps/examples/elf/tests/signal/Makefile create mode 100644 apps/examples/elf/tests/signal/signal.c create mode 100644 apps/examples/elf/tests/struct/Makefile create mode 100644 apps/examples/elf/tests/struct/struct.h create mode 100644 apps/examples/elf/tests/struct/struct_dummy.c create mode 100644 apps/examples/elf/tests/struct/struct_main.c create mode 100644 apps/examples/elf/tests/task/Makefile create mode 100644 apps/examples/elf/tests/task/task.c diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 79de56614c..d25c497399 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -380,6 +380,7 @@ * apps/examples/nximage/nximage_main.c: Add a 5 second delay after the NX logo is presented so that there is time for the image to be verified. Suggested by Petteri Aimonen. -i * apps/Makefile: Small change that reduces the number of shell invocations + * apps/Makefile: Small change that reduces the number of shell invocations by one (Mike Smith). + * apps/examples/elf: Test example for the ELF loader. diff --git a/apps/examples/Kconfig b/apps/examples/Kconfig index 865268addb..a37308eaac 100644 --- a/apps/examples/Kconfig +++ b/apps/examples/Kconfig @@ -27,6 +27,10 @@ menu "DHCP Server Example" source "$APPSDIR/examples/dhcpd/Kconfig" endmenu +menu "ELF Loader Example" +source "$APPSDIR/examples/elf/Kconfig" +endmenu + menu "FTP Client Example" source "$APPSDIR/examples/ftpc/Kconfig" endmenu diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index d03b976d25..0733d94190 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -62,6 +62,10 @@ ifeq ($(CONFIG_EXAMPLES_DISCOVER),y) CONFIGURED_APPS += examples/discover endif +ifeq ($(CONFIG_EXAMPLES_ELF),y) +CONFIGURED_APPS += examples/elf +endif + ifeq ($(CONFIG_EXAMPLES_FTPC),y) CONFIGURED_APPS += examples/ftpc endif diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 453f99ce71..ef59e68221 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -37,7 +37,7 @@ # Sub-directories -SUBDIRS = adc buttons can cdcacm composite dhcpd discover ftpc ftpd hello +SUBDIRS = adc buttons can cdcacm composite dhcpd discover elf ftpc ftpd hello SUBDIRS += helloxx hidkbd igmp lcdrw mm modbus mount nettest nsh null nx SUBDIRS += nxconsole nxffs nxflat nxhello nximage nxlines nxtext ostest SUBDIRS += pashello pipe poll pwm qencoder rgmp romfs serloop telnetd diff --git a/apps/examples/elf/Kconfig b/apps/examples/elf/Kconfig new file mode 100644 index 0000000000..aca36f1b9b --- /dev/null +++ b/apps/examples/elf/Kconfig @@ -0,0 +1,13 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config EXAMPLES_ELF + bool "ELF Loader Example" + default n + ---help--- + Enable the ELF loader example + +if EXAMPLES_ELF +endif diff --git a/apps/examples/elf/Makefile b/apps/examples/elf/Makefile new file mode 100644 index 0000000000..640e8e427d --- /dev/null +++ b/apps/examples/elf/Makefile @@ -0,0 +1,98 @@ +############################################################################ +# apps/examples/elf/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +# ELF Example + +ASRCS = +CSRCS = elf_main.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: headers clean depend disclean + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +headers: + @$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) + +.built: $(OBJS) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) + @touch .built + +context: + +# We can't make dependencies in this directory because the required +# header files may not yet exist. + +.depend: + @touch $@ + +depend: .depend + +clean: + @rm -f *.o *~ .*.swp .built + $(call CLEAN) + +distclean: clean + @rm -f Make.dep .depend + +-include Make.dep diff --git a/apps/examples/elf/elf_main b/apps/examples/elf/elf_main new file mode 100644 index 0000000000..c58b13ffc2 --- /dev/null +++ b/apps/examples/elf/elf_main @@ -0,0 +1,224 @@ +/**************************************************************************** + * examples/elf/elf_main.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "tests/romfs.h" +#include "tests/dirlist.h" +#include "tests/symtab.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Check configuration. This is not all of the configuration settings that + * are required -- only the more obvious. + */ + +#if CONFIG_NFILE_DESCRIPTORS < 1 +# error "You must provide file descriptors via CONFIG_NFILE_DESCRIPTORS in your configuration file" +#endif + +#ifndef CONFIG_ELF +# error "You must select CONFIG_ELF in your configuration file" +#endif + +#ifndef CONFIG_FS_ROMFS +# error "You must select CONFIG_FS_ROMFS in your configuration file" +#endif + +#ifdef CONFIG_DISABLE_MOUNTPOINT +# error "You must not disable mountpoints via CONFIG_DISABLE_MOUNTPOINT in your configuration file" +#endif + +#ifdef CONFIG_BINFMT_DISABLE +# error "You must not disable loadable modules via CONFIG_BINFMT_DISABLE in your configuration file" +#endif + +/* Describe the ROMFS file system */ + +#define SECTORSIZE 512 +#define NSECTORS(b) (((b)+SECTORSIZE-1)/SECTORSIZE) +#define ROMFSDEV "/dev/ram0" +#define MOUNTPT "/mnt/romfs" + +/* If CONFIG_DEBUG is enabled, use dbg instead of printf so that the + * output will be synchronous with the debug output. + */ + +#ifdef CONFIG_CPP_HAVE_VARARGS +# ifdef CONFIG_DEBUG +# define message(format, arg...) dbg(format, ##arg) +# define err(format, arg...) dbg(format, ##arg) +# else +# define message(format, arg...) printf(format, ##arg) +# define err(format, arg...) fprintf(stderr, format, ##arg) +# endif +#else +# ifdef CONFIG_DEBUG +# define message dbg +# define err dbg +# else +# define message printf +# define err printf +# endif +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const char delimiter[] = + "****************************************************************************"; + +static char path[128]; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: testheader + ****************************************************************************/ + +static inline void testheader(FAR const char *progname) +{ + message("\n%s\n* Executing %s\n%s\n\n", delimiter, progname, delimiter); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_main + ****************************************************************************/ + +int elf_main(int argc, char *argv[]) +{ + struct binary_s bin; + int ret; + int i; + + /* Initialize the ELF binary loader */ + + message("Initializing the ELF binary loader\n"); + ret = elf_initialize(); + if (ret < 0) + { + err("ERROR: Initialization of the ELF loader failed: %d\n", ret); + exit(1); + } + + /* Create a ROM disk for the ROMFS filesystem */ + + message("Registering romdisk\n"); + ret = romdisk_register(0, romfs_img, NSECTORS(romfs_img_len), SECTORSIZE); + if (ret < 0) + { + err("ERROR: romdisk_register failed: %d\n", ret); + elf_uninitialize(); + exit(1); + } + + /* Mount the file system */ + + message("Mounting ROMFS filesystem at target=%s with source=%s\n", + MOUNTPT, ROMFSDEV); + + ret = mount(ROMFSDEV, MOUNTPT, "romfs", MS_RDONLY, NULL); + if (ret < 0) + { + err("ERROR: mount(%s,%s,romfs) failed: %s\n", + ROMFSDEV, MOUNTPT, errno); + elf_uninitialize(); + } + + /* Now excercise every progrm in the ROMFS file system */ + + for (i = 0; dirlist[i]; i++) + { + testheader(dirlist[i]); + + memset(&bin, 0, sizeof(struct binary_s)); + snprintf(path, 128, "%s/%s", MOUNTPT, dirlist[i]); + + bin.filename = path; + bin.exports = exports; + bin.nexports = NEXPORTS; + + ret = load_module(&bin); + if (ret < 0) + { + err("ERROR: Failed to load program '%s'\n", dirlist[i]); + exit(1); + } + + ret = exec_module(&bin, 50); + if (ret < 0) + { + err("ERROR: Failed to execute program '%s'\n", dirlist[i]); + unload_module(&bin); + } + + message("Wait a bit for test completion\n"); + sleep(4); + } + + message("End-of-Test.. Exit-ing\n"); + return 0; +} diff --git a/apps/examples/elf/tests/Makefile b/apps/examples/elf/tests/Makefile new file mode 100644 index 0000000000..c4a0eec4ca --- /dev/null +++ b/apps/examples/elf/tests/Makefile @@ -0,0 +1,100 @@ +############################################################################ +# apps/examples/elf/tests/Makefile +# +# 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. +# +############################################################################ + +# Most of these do no build yet +SUBDIRS = errno hello hello++ longjmp mutex pthread signal task struct + +ELF_DIR = $(APPDIR)/examples/elf +TESTS_DIR = $(ELF_DIR)/tests +ROMFS_DIR = $(TESTS_DIR)/romfs +ROMFS_IMG = $(TESTS_DIR)/romfs.img +ROMFS_HDR = $(TESTS_DIR)/romfs.h +ROMFS_DIRLIST = $(TESTS_DIR)/dirlist.h +SYMTAB = $(TESTS_DIR)/symtab.h + +define DIR_template +$(1)_$(2): + @$(MAKE) -C $(1) $(3) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" ROMFS_DIR="$(ROMFS_DIR)" CROSSDEV=$(CROSSDEV) +endef + +all: $(ROMFS_HDR) $(ROMFS_DIRLIST) $(SYMTAB) +.PHONY: all build clean install populate + +$(foreach DIR, $(SUBDIRS), $(eval $(call DIR_template,$(DIR),build, all))) +$(foreach DIR, $(SUBDIRS), $(eval $(call DIR_template,$(DIR),clean,clean))) +$(foreach DIR, $(SUBDIRS), $(eval $(call DIR_template,$(DIR),install,install))) + +# Build program(s) in each sud-directory + +build: $(foreach DIR, $(SUBDIRS), $(DIR)_build) + +# Install each program in the romfs directory + +install: $(foreach DIR, $(SUBDIRS), $(DIR)_install) + +# Create the romfs directory + +$(ROMFS_DIR): + @mkdir $(ROMFS_DIR) + +# Populate the romfs directory + +populate: $(ROMFS_DIR) build install + +# Create the romfs.img file from the populated romfs directory + +$(ROMFS_IMG): populate + @genromfs -f $@ -d $(ROMFS_DIR) -V "ELFTEST" + +# Create the romfs.h header file from the romfs.img file + +$(ROMFS_HDR) : $(ROMFS_IMG) + @(cd $(TESTS_DIR); xxd -i romfs.img | sed -e "s/^unsigned/static const unsigned/g" >$@) + +# Create the dirlist.h header file from the romfs directory + +$(ROMFS_DIRLIST) : populate + @$(TESTS_DIR)/mkdirlist.sh $(ROMFS_DIR) >$@ + +# Create the exported symbol table list from the derived *-thunk.S files + +$(SYMTAB): build + @$(TESTS_DIR)/mksymtab.sh $(TESTS_DIR) >$@ + +# Clean each subdirectory + +clean: $(foreach DIR, $(SUBDIRS), $(DIR)_clean) + @rm -f $(ROMFS_HDR) $(ROMFS_IMG) $(SYMTAB) + @rm -rf $(ROMFS_DIR) diff --git a/apps/examples/elf/tests/errno/Makefile b/apps/examples/elf/tests/errno/Makefile new file mode 100644 index 0000000000..d3b12aa2ec --- /dev/null +++ b/apps/examples/elf/tests/errno/Makefile @@ -0,0 +1,59 @@ +############################################################################ +# examples/elf/tests/hello/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs + +BIN = errno + +SRCS = $(BIN).c +OBJS = $(BIN:.c=.o) + +all: $(BIN) + +$(OBJS): %.o: %.c + @echo "CC: $<" + @$(CC) -c $(CFLAGS) $< -o $@ + +$(BIN): $(OBJS) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +clean: + @rm -f $(BIN) *.o *~ .*.swp core + +install: + @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + diff --git a/apps/examples/elf/tests/errno/errno.c b/apps/examples/elf/tests/errno/errno.c new file mode 100644 index 0000000000..adc88ddd3a --- /dev/null +++ b/apps/examples/elf/tests/errno/errno.c @@ -0,0 +1,83 @@ +/**************************************************************************** + * examples/elf/tests/errno/errno.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +static const char g_nonexistent[] = "aflav-sautga-ay"; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int main(int argc, char **argv) +{ + FILE *test_stream; + + /* Try using stdout and stderr explicitly. These are global variables + * exported from the base code. + */ + + fprintf(stdout, "Hello, World on stdout\n"); + fprintf(stderr, "Hello, World on stderr\n"); + + /* Try opening a non-existent file using buffered IO. */ + + test_stream = fopen(g_nonexistent, "r"); + if (test_stream) + { + fprintf(stderr, "Hmm... Delete \"%s\" and try this again\n", + g_nonexistent); + exit(1); + } + + /* Now print the errno on stderr. Errno is also a global + * variable exported by the base code. + */ + + fprintf(stderr, "We failed to open \"%s!\" errno is %d\n", + g_nonexistent, errno); + + return 0; +} diff --git a/apps/examples/elf/tests/hello++/Makefile b/apps/examples/elf/tests/hello++/Makefile new file mode 100644 index 0000000000..b3d07d2626 --- /dev/null +++ b/apps/examples/elf/tests/hello++/Makefile @@ -0,0 +1,116 @@ +############################################################################ +# examples/elf/tests/hello/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs + +BIN1 = hello++1 +BIN2 = hello++2 +BIN3 = hello++3 +#BIN4 = hello++4 +ALL_BIN = $(BIN1) $(BIN2) $(BIN3) $(BIN4) + +SRCS1 = $(BIN1).c +OBJS1 = $(SRCS1:.c=.o) + +SRCS2 = $(BIN2).c +OBJS2 = $(SRCS2:.c=.o) + +SRCS3 = $(BIN3).c +OBJS3 = $(SRCS3:.c=.o) + +#SRCS4 = $(BIN4).c +#OBJS4 = $(SRCS4:.c=.o) + +SRCS = $(SRCS1) $(SRCS2) $(SRCS3) $(SRCS4) +OBJS = $(OBJS1) $(OBJS2) $(OBJS3) $(OBJS4) + +LIBSTDC_STUBS_DIR = $(TOPDIR)/libxx +LIBSTDC_STUBS_LIB = $(LIBSTDC_STUBS_DIR)/liblibxx.a + +all: $(BIN1) $(BIN2) $(BIN3) $(BIN4) + +$(OBJS): %.o: %.cpp + @echo "CC: $<" + @$(CXX) -c $(CXXPICFLAGS) $< -o $@ + +# This contains libstdc++ stubs to that you can build C++ code +# without actually having libstdc++ + +$(LIBSTDC_STUBS_LIB): + @$(MAKE) -C $(LIBSTDC_STUBS_DIR) TOPDIR=$(TOPDIR) + +# BIN1 and BIN2 link just like C code because they contain no +# static constructors. BIN1 is equivalent to a C hello world; +# BIN2 contains a class that implements hello world, but it is +# not statically initialized. + +$(BIN1): $(OBJS1) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +$(BIN2): $(OBJS2) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +# BIN3 is equivalent to BIN2 except that is uses static initializers + +$(BIN3): $(OBJS3) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +# BIN4 is similar to BIN3 except that it uses the streams code from libstdc++ +# +# NOTE: libstdc++ is not available for NuttX as of this writing +# +#$(BIN4): $(OBJS4) +# @echo "LD: $<" +# @$(LD) $(LDELFFLAGS) -o $@ $^ + +clean: + @rm -f $(ALL_BIN) *.o *~ .*.swp core + +install: $(ALL_BIN) + @install -D $(BIN1) $(ROMFS_DIR)/$(BIN1) + @install -D $(BIN2) $(ROMFS_DIR)/$(BIN2) + @install -D $(BIN3) $(ROMFS_DIR)/$(BIN3) +# @install -D $(BIN4) $(ROMFS_DIR)/$(BIN4) + + + + + + + diff --git a/apps/examples/elf/tests/hello++/hello++1.cpp b/apps/examples/elf/tests/hello++/hello++1.cpp new file mode 100644 index 0000000000..22a7281886 --- /dev/null +++ b/apps/examples/elf/tests/hello++/hello++1.cpp @@ -0,0 +1,60 @@ +///////////////////////////////////////////////////////////////////////////// +// examples/elf/tests/hello++/hello++1.c +// +// 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. +// +///////////////////////////////////////////////////////////////////////////// +// +// This is an trivial version of "Hello, World" program. It illustrates +// that we can build C programs using the C++ compiler. +// +// - Building a C++ program to use the C library +// - No class creation +// - NO Streams +// - NO Static constructor and destructors +// +///////////////////////////////////////////////////////////////////////////// + +///////////////////////////////////////////////////////////////////////////// +// Included Files +///////////////////////////////////////////////////////////////////////////// + +#include + +///////////////////////////////////////////////////////////////////////////// +// Public Functions +///////////////////////////////////////////////////////////////////////////// + +int main(int argc, char **argv) +{ + printf("Hello, World!\n"); + return 0; +} diff --git a/apps/examples/elf/tests/hello++/hello++2.cpp b/apps/examples/elf/tests/hello++/hello++2.cpp new file mode 100644 index 0000000000..a8ba589bd3 --- /dev/null +++ b/apps/examples/elf/tests/hello++/hello++2.cpp @@ -0,0 +1,123 @@ +///////////////////////////////////////////////////////////////////////////// +// examples/elf/tests/hello++/hello++2.c +// +// 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. +// +///////////////////////////////////////////////////////////////////////////// +// +// This is an another trivial version of "Hello, World" design. It illustrates +// +// - Building a C++ program to use the C library +// - Basic class creation +// - NO Streams +// - NO Static constructor and destructors +// +///////////////////////////////////////////////////////////////////////////// + +///////////////////////////////////////////////////////////////////////////// +// Included Files +///////////////////////////////////////////////////////////////////////////// + +#include + +///////////////////////////////////////////////////////////////////////////// +// Classes +///////////////////////////////////////////////////////////////////////////// + +class CThingSayer +{ + const char *szWhatToSay; +public: + CThingSayer(void) + { + printf("CThingSayer::CThingSayer: I am!\n"); + szWhatToSay = (const char*)NULL; + } + + ~CThingSayer(void) + { + printf("CThingSayer::~CThingSayer: I cease to be\n"); + if (szWhatToSay) + { + printf("CThingSayer::~CThingSayer: I will never say '%s' again\n", + szWhatToSay); + } + szWhatToSay = (const char*)NULL; + } + + void Initialize(const char *czSayThis) + { + printf("CThingSayer::Initialize: When told, I will say '%s'\n", + czSayThis); + szWhatToSay = czSayThis; + } + + void SayThing(void) + { + printf("CThingSayer::SayThing: I am now saying '%s'\n", szWhatToSay); + } +}; + +///////////////////////////////////////////////////////////////////////////// +// Public Functions +///////////////////////////////////////////////////////////////////////////// + +int main(int argc, char **argv) +{ + CThingSayer *MyThingSayer; + + printf("main: Started. Creating MyThingSayer\n"); + + // Create an instance of the CThingSayer class + // We should see the message from constructor, CThingSayer::CThingSayer(), + + MyThingSayer = new CThingSayer; + printf("main: Created MyThingSayer=0x%08lx\n", (long)MyThingSayer); + + // Tell MyThingSayer that "Hello, World!" is the string to be said + + printf("main: Calling MyThingSayer->Initialize\n");; + MyThingSayer->Initialize("Hello, World!"); + + // Tell MyThingSayer to say the thing we told it to say + + printf("main: Calling MyThingSayer->SayThing\n");; + MyThingSayer->SayThing(); + + // We should see the message from the destructor, + // CThingSayer::~CThingSayer(), AFTER we see the following + + printf("main: Destroying MyThingSayer\n"); + delete MyThingSayer; + + printf("main: Returning\n");; + return 0; +} diff --git a/apps/examples/elf/tests/hello++/hello++3.cpp b/apps/examples/elf/tests/hello++/hello++3.cpp new file mode 100644 index 0000000000..eedaa6df0c --- /dev/null +++ b/apps/examples/elf/tests/hello++/hello++3.cpp @@ -0,0 +1,132 @@ +///////////////////////////////////////////////////////////////////////////// +// examples/elf/tests/hello++/hello++3.c +// +// 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. +// +///////////////////////////////////////////////////////////////////////////// +// +// This is an another trivial version of "Hello, World" design. It illustrates +// +// - Building a C++ program to use the C library and stdio +// - Basic class creation with virtual methods. +// - Static constructor and destructors (in main program only) +// - NO Streams +// +///////////////////////////////////////////////////////////////////////////// + +///////////////////////////////////////////////////////////////////////////// +// Included Files +///////////////////////////////////////////////////////////////////////////// + +#include + +///////////////////////////////////////////////////////////////////////////// +// Classes +///////////////////////////////////////////////////////////////////////////// + +class CThingSayer +{ + const char *szWhatToSay; +public: + CThingSayer(void); + virtual ~CThingSayer(void); + virtual void Initialize(const char *czSayThis); + virtual void SayThing(void); +}; + +// A static instance of the CThingSayer class. This instance MUST +// be constructed by the system BEFORE the program is started at +// main() and must be destructed by the system AFTER the main() +// returns to the system + +static CThingSayer MyThingSayer; + +// These are implementations of the methods of the CThingSayer class + +CThingSayer::CThingSayer(void) +{ + printf("CThingSayer::CThingSayer: I am!\n"); + szWhatToSay = (const char*)NULL; +} + +CThingSayer::~CThingSayer(void) +{ + printf("CThingSayer::~CThingSayer: I cease to be\n"); + if (szWhatToSay) + { + printf("CThingSayer::~CThingSayer: I will never say '%s' again\n", + szWhatToSay); + } + szWhatToSay = (const char*)NULL; +} + +void CThingSayer::Initialize(const char *czSayThis) +{ + printf("CThingSayer::Initialize: When told, I will say '%s'\n", + czSayThis); + szWhatToSay = czSayThis; +} + +void CThingSayer::SayThing(void) +{ + printf("CThingSayer::SayThing: I am now saying '%s'\n", szWhatToSay); +} + +///////////////////////////////////////////////////////////////////////////// +// Public Functions +///////////////////////////////////////////////////////////////////////////// + +int main(int argc, char **argv) +{ + // We should see the message from constructor, CThingSayer::CThingSayer(), + // BEFORE we see the following messages. That is proof that the + // C++ static initializer is working + + printf("main: Started. MyThingSayer should already exist\n"); + + // Tell MyThingSayer that "Hello, World!" is the string to be said + + printf("main: Calling MyThingSayer.Initialize\n");; + MyThingSayer.Initialize("Hello, World!"); + + // Tell MyThingSayer to say the thing we told it to say + + printf("main: Calling MyThingSayer.SayThing\n");; + MyThingSayer.SayThing(); + + // We are finished, return. We should see the message from the + // destructor, CThingSayer::~CThingSayer(), AFTER we see the following + // message. That is proof that the C++ static destructor logic + // is working + + printf("main: Returning. MyThingSayer should be destroyed\n");; + return 0; +} diff --git a/apps/examples/elf/tests/hello++/hello++4.cpp b/apps/examples/elf/tests/hello++/hello++4.cpp new file mode 100644 index 0000000000..1a9f2e28b7 --- /dev/null +++ b/apps/examples/elf/tests/hello++/hello++4.cpp @@ -0,0 +1,150 @@ +///////////////////////////////////////////////////////////////////////////// +// examples/elf/tests/hello++/hello++4.c +// +// 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. +// +///////////////////////////////////////////////////////////////////////////// +// +// This is an excessively complex version of "Hello, World" design to +// illustrate some basic properties of C++: +// +// - Building a C++ program +// - Streams / statically linked libstdc++ +// - Static constructor and destructors (in main program only) +// +///////////////////////////////////////////////////////////////////////////// + +///////////////////////////////////////////////////////////////////////////// +// Included Files +///////////////////////////////////////////////////////////////////////////// + +#include +#include + +#ifndef NULL +# define NULL ((void*)0L) +#endif + +///////////////////////////////////////////////////////////////////////////// +// Classes +///////////////////////////////////////////////////////////////////////////// + +using namespace std; + +// A hello world sayer class + +class CThingSayer +{ + const char *szWhatToSay; +public: + CThingSayer(void); + virtual ~CThingSayer(void); + virtual void Initialize(const char *czSayThis); + virtual void SayThing(void); +}; + +///////////////////////////////////////////////////////////////////////////// +// Private Data +///////////////////////////////////////////////////////////////////////////// + +// A static instance of the CThingSayer class. This instance MUST +// be constructed by the system BEFORE the program is started at +// main() and must be destructed by the system AFTER the main() +// returns to the system + +static CThingSayer MyThingSayer; + +///////////////////////////////////////////////////////////////////////////// +// Method Implementations +///////////////////////////////////////////////////////////////////////////// + +// These are implementations of the methods of the CThingSayer class + +CThingSayer::CThingSayer(void) +{ + cout << "CThingSayer::CThingSayer: I am!" << endl; + szWhatToSay = (const char*)NULL; +} + +CThingSayer::~CThingSayer(void) +{ + cout << "CThingSayer::~CThingSayer: I cease to be" << endl; + if (szWhatToSay) + { + cout << "CThingSayer::~CThingSayer: I will never say '" + << szWhatToSay << "' again" << endl; + } + szWhatToSay = (const char*)NULL; +} + +void CThingSayer::Initialize(const char *czSayThis) +{ + cout << "CThingSayer::Initialize: When told, I will say '" + << czSayThis << "'" << endl; + szWhatToSay = czSayThis; +} + +void CThingSayer::SayThing(void) +{ + cout << "CThingSayer::SayThing: I am now saying '" + << szWhatToSay << "'" << endl; +} + +///////////////////////////////////////////////////////////////////////////// +// Public Functions +///////////////////////////////////////////////////////////////////////////// + +int main(int argc, char **argv) +{ + // We should see the message from constructor, CThingSayer::CThingSayer(), + // BEFORE we see the following messages. That is proof that the + // C++ static initializer is working + + cout << "main: Started" << endl; + + // Tell MyThingSayer that "Hello, World!" is the string to be said + + cout << "main: Calling MyThingSayer.Initialize" << endl; + MyThingSayer.Initialize("Hello, World!"); + + // Tell MyThingSayer to say the thing we told it to say + + cout << "main: Calling MyThingSayer.SayThing" << endl; + MyThingSayer.SayThing(); + + // We are finished, return. We should see the message from the + // destructor, CThingSayer::~CThingSayer(), AFTER we see the following + // message. That is proof that the C++ static destructor logic + // is working + + cout << "main: Returning" << endl; + return 0; +} diff --git a/apps/examples/elf/tests/hello/Makefile b/apps/examples/elf/tests/hello/Makefile new file mode 100644 index 0000000000..3b9b06ac42 --- /dev/null +++ b/apps/examples/elf/tests/hello/Makefile @@ -0,0 +1,58 @@ +############################################################################ +# examples/elf/tests/hello/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs + +BIN = hello + +SRCS = $(BIN).c +OBJS = $(BIN:.c=.o) + +all: $(BIN) + +$(OBJS): %.o: %.c + @echo "CC: $<" + @$(CC) -c $(CFLAGS) $< -o $@ + +$(BIN): $(OBJS) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +clean: + @rm -f $(BIN) *.o *~ .*.swp core + +install: + @install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/hello/hello.c b/apps/examples/elf/tests/hello/hello.c new file mode 100644 index 0000000000..6b1d079d8a --- /dev/null +++ b/apps/examples/elf/tests/hello/hello.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * examples/elf/tests/hello/hello.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int main(int argc, char **argv) +{ + int i; + + /* Mandatory "Hello, world!" */ + + puts("Getting ready to say \"Hello, world\"\n"); + printf("Hello, world!\n"); + puts("It has been said.\n"); + + /* Print arguments */ + + printf("argc\t= %d\n", argc); + printf("argv\t= 0x%p\n", argv); + + for (i = 0; i < argc; i++) + { + printf("argv[%d]\t= ", i); + if (argv[i]) + { + printf("(0x%p) \"%s\"\n", argv[i], argv[i]); + } + else + { + printf("NULL?\n"); + } + } + + printf("argv[%d]\t= 0x%p\n", argc, argv[argc]); + printf("Goodbye, world!\n"); + return 0; +} diff --git a/apps/examples/elf/tests/longjmp/Makefile b/apps/examples/elf/tests/longjmp/Makefile new file mode 100644 index 0000000000..12d6e443cd --- /dev/null +++ b/apps/examples/elf/tests/longjmp/Makefile @@ -0,0 +1,58 @@ +############################################################################ +# examples/elf/tests/longjmp/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs + +BIN = longjmp + +SRCS = $(BIN).c +OBJS = $(BIN:.c=.o) + +all: $(BIN) + +$(OBJS): %.o: %.c + @echo "CC: $<" + @$(CC) -c $(CFLAGS) $< -o $@ + +$(BIN): $(OBJS) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +clean: + @rm -f $(BIN) *.o *~ .*.swp core + +install: + @install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/longjmp/longjmp.c b/apps/examples/elf/tests/longjmp/longjmp.c new file mode 100644 index 0000000000..2993c24dc6 --- /dev/null +++ b/apps/examples/elf/tests/longjmp/longjmp.c @@ -0,0 +1,128 @@ +/**************************************************************************** + * examples/elf/tests/longjmp/longjmp.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define MAIN_VAL 47 +#define FUNC_VAL 92 +#define LEAF_VAL 163 + +#define FUNCTION_ARG MAIN_VAL +#define LEAF_ARG (FUNCTION_ARG + FUNC_VAL) +#define SETJMP_RETURN (LEAF_ARG + LEAF_VAL) + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static jmp_buf env; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static int leaf(int *some_arg) +{ + int some_local_variable = *some_arg + LEAF_VAL; + + printf("leaf: received %d\n", *some_arg); + + if (*some_arg != LEAF_ARG) + printf("leaf: ERROR: expected %d\n", LEAF_ARG); + + printf("leaf: Calling longjmp() with %d\n", some_local_variable); + + longjmp(env, some_local_variable); +} + +static int function(int some_arg) +{ + int some_local_variable = some_arg + FUNC_VAL; + int retval; + + printf("function: received %d\n", some_arg); + + if (some_arg != FUNCTION_ARG) + printf("function: ERROR: expected %d\n", FUNCTION_ARG); + + printf("function: Calling leaf() with %d\n", some_local_variable); + + retval = leaf(&some_local_variable); + + printf("function: ERROR -- leaf returned!\n"); + return retval; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int main(int argc, char **argv) +{ + int value; + + printf("main: Calling setjmp\n"); + value = setjmp(env); + printf("main: setjmp returned %d\n", value); + + if (value == 0) + { + printf("main: Normal setjmp return\n"); + printf("main: Calling function with %d\n", MAIN_VAL); + function(MAIN_VAL); + printf("main: ERROR -- function returned!\n"); + return 1; + } + else if (value != SETJMP_RETURN) + { + printf("main: ERROR: Expected %d\n", SETJMP_RETURN); + return 1; + } + else + { + printf("main: SUCCESS: setjmp return from longjmp call\n"); + return 0; + } +} + diff --git a/apps/examples/elf/tests/mkdirlist.sh b/apps/examples/elf/tests/mkdirlist.sh new file mode 100755 index 0000000000..c790e74c4b --- /dev/null +++ b/apps/examples/elf/tests/mkdirlist.sh @@ -0,0 +1,35 @@ +#!/bin/bash + +usage="Usage: %0 " + +dir=$1 +if [ -z "$dir" ]; then + echo "ERROR: Missing " + echo "" + echo $usage + exit 1 +fi + +if [ ! -d "$dir" ]; then + echo "ERROR: Directory $dir does not exist" + echo "" + echo $usage + exit 1 +fi + +echo "#ifndef __EXAMPLES_ELF_TESTS_DIRLIST_H" +echo "#define __EXAMPLES_ELF_TESTS_DIRLIST_H" +echo "" +echo "static const char *dirlist[] =" +echo "{" + +for file in `ls $dir`; do + echo " \"$file\"," +done + +echo " NULL" +echo "};" +echo "" +echo "#endif /* __EXAMPLES_ELF_TESTS_DIRLIST_H */" + + diff --git a/apps/examples/elf/tests/mksymtab.sh b/apps/examples/elf/tests/mksymtab.sh new file mode 100755 index 0000000000..fa1a2d0302 --- /dev/null +++ b/apps/examples/elf/tests/mksymtab.sh @@ -0,0 +1,39 @@ +#!/bin/bash + +usage="Usage: %0 " + +dir=$1 +if [ -z "$dir" ]; then + echo "ERROR: Missing " + echo "" + echo $usage + exit 1 +fi + +if [ ! -d "$dir" ]; then + echo "ERROR: Directory $dir does not exist" + echo "" + echo $usage + exit 1 +fi + +varlist=`find $dir -name "*-thunk.S"| xargs grep -h asciz | cut -f3 | sort | uniq` + +echo "#ifndef __EXAMPLES_ELF_TESTS_SYMTAB_H" +echo "#define __EXAMPLES_ELF_TESTS_SYMTAB_H" +echo "" +echo "#include " +echo "" +echo "static const struct symtab_s exports[] = " +echo "{" + +for string in $varlist; do + var=`echo $string | sed -e "s/\"//g"` + echo " {$string, $var}," +done + +echo "};" +echo "#define NEXPORTS (sizeof(exports)/sizeof(struct symtab_s))" +echo "" +echo "#endif /* __EXAMPLES_ELF_TESTS_SYMTAB_H */" + diff --git a/apps/examples/elf/tests/mutex/Makefile b/apps/examples/elf/tests/mutex/Makefile new file mode 100644 index 0000000000..632fed9dd4 --- /dev/null +++ b/apps/examples/elf/tests/mutex/Makefile @@ -0,0 +1,58 @@ +############################################################################ +# examples/elf/tests/mutex/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs + +BIN = mutex + +SRCS = $(BIN).c +OBJS = $(BIN:.c=.o) + +all: $(BIN) + +$(OBJS): %.o: %.c + @echo "CC: $<" + @$(CC) -c $(CFLAGS) $< -o $@ + +$(BIN): $(OBJS) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +clean: + @rm -f $(BIN) *.o *~ .*.swp core + +install: + @install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/mutex/mutex.c b/apps/examples/elf/tests/mutex/mutex.c new file mode 100644 index 0000000000..2446e62ebf --- /dev/null +++ b/apps/examples/elf/tests/mutex/mutex.c @@ -0,0 +1,149 @@ +/**************************************************************************** + * examples/elf/tests/mutex/mutex.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static pthread_mutex_t mut; +static volatile int my_mutex = 0; +static unsigned long nloops[2] = {0, 0}; +static unsigned long nerrors[2] = {0, 0}; +static volatile bool bendoftest; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/* NOTE: it is necessary for functions that are referred to by function pointers + * pointer to be declared with global scope (at least for ARM). Otherwise, + * a relocation type that is not supported by ELF is generated by GCC. + */ + +void thread_func(void *parameter) +{ + int my_id = (int)parameter; + int my_ndx = my_id - 1; + int i; + + /* Loop 20 times. There is a 100 MS delay in the loop so this should + * take about 2 seconds. The main thread will stop this thread after + * 2 seconds by setting bendoftest in any event. + */ + + for (i = 0; i < 20 && !bendoftest; i++); + { + if ((pthread_mutex_lock(&mut)) != 0) + { + printf("ERROR thread %d: pthread_mutex_lock failed\n", my_id); + } + + if (my_mutex == 1) + { + printf("ERROR thread=%d: " + "my_mutex should be zero, instead my_mutex=%d\n", + my_id, my_mutex); + nerrors[my_ndx]++; + } + + my_mutex = 1; + usleep(100000); + my_mutex = 0; + + if ((pthread_mutex_unlock(&mut)) != 0) + { + printf("ERROR thread %d: pthread_mutex_unlock failed\n", my_id); + } + + nloops[my_ndx]++; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int main(int argc, char **argv) +{ + pthread_t thread1; + pthread_t thread2; + + /* Initialize the mutex */ + + pthread_mutex_init(&mut, NULL); + + /* Start two thread instances */ + + printf("Starting thread 1\n"); + bendoftest = false; + if ((pthread_create(&thread1, NULL, (void*)thread_func, (void*)1)) != 0) + { + fprintf(stderr, "Error in thread#1 creation\n"); + } + + printf("Starting thread 2\n"); + if ((pthread_create(&thread2, NULL, (void*)thread_func, (void*)2)) != 0) + { + fprintf(stderr, "Error in thread#2 creation\n"); + } + + /* Wait a bit for the threads to do their thing. */ + + sleep(2); + + /* Then ask them politely to stop running */ + + printf("Stopping threads\n"); + bendoftest = true; + pthread_join(thread1, NULL); + pthread_join(thread2, NULL); + + printf("\tThread1\tThread2\n"); + printf("Loops\t%ld\t%ld\n", nloops[0], nloops[1]); + printf("Errors\t%ld\t%ld\n", nerrors[0], nerrors[1]); + + return 0; +} + diff --git a/apps/examples/elf/tests/pthread/Makefile b/apps/examples/elf/tests/pthread/Makefile new file mode 100644 index 0000000000..fae6144c26 --- /dev/null +++ b/apps/examples/elf/tests/pthread/Makefile @@ -0,0 +1,58 @@ +############################################################################ +# examples/elf/tests/pthread/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs + +BIN = pthread + +SRCS = $(BIN).c +OBJS = $(BIN:.c=.o) + +all: $(BIN) + +$(OBJS): %.o: %.c + @echo "CC: $<" + @$(CC) -c $(CFLAGS) $< -o $@ + +$(BIN): $(OBJS) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +clean: + @rm -f $(BIN) *.o *~ .*.swp core + +install: + @install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/pthread/pthread.c b/apps/examples/elf/tests/pthread/pthread.c new file mode 100644 index 0000000000..f9a23ff332 --- /dev/null +++ b/apps/examples/elf/tests/pthread/pthread.c @@ -0,0 +1,143 @@ +/**************************************************************************** + * examples/elf/tests/pthread/pthread.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define CHILD_ARG ((void*)0x12345678) +#define CHILD_RET ((void*)0x87654321) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +enum exit_values_e +{ + TESTRESULT_SUCCESS = 0, + TESTRESULT_PTHREAD_ATTR_INIT_FAIL, + TESTRESULT_PTHREAD_CREATE_FAIL, + TESTRESULT_PTHREAD_JOIN_FAIL, + TESTRESULT_CHILD_ARG_FAIL, + TESTRESULT_CHILD_RETVAL_FAIL, +}; + +/**************************************************************************** + * External Functions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/* NOTE: it is necessary for functions that are referred to by function pointers + * pointer to be declared with global scope (at least for ARM). Otherwise, + * a relocation type that is not supported by ELF is generated by GCC. + */ + +void *child_start_routine(void *arg) +{ + printf("CHILD: started with arg=%d\n", (int)arg); + + if (arg != CHILD_ARG) + { + printf("CHILD: expected arg=%d\n", (int)CHILD_ARG); + return (void*)TESTRESULT_CHILD_ARG_FAIL; + } + sleep(2); + + printf("CHILD: returning %d\n", (int)CHILD_RET); + pthread_exit(CHILD_RET); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int main(int argc, char **argv) +{ + pthread_attr_t attr; + pthread_t thread; + void *retval; + int status; + + puts("PARENT: started\n"); + + status = pthread_attr_init(&attr); + if (status != 0) + { + printf("PARENT: pthread_attr_init() returned %d\n", status); + exit(TESTRESULT_PTHREAD_ATTR_INIT_FAIL); + } + + printf("PARENT: calling pthread_start with arg=%d\n", (int)CHILD_ARG); + status = pthread_create(&thread, &attr, child_start_routine, CHILD_ARG); + if (status != 0) + { + printf("PARENT: pthread_create() returned %d\n", status); + exit(TESTRESULT_PTHREAD_CREATE_FAIL); + } + + status = pthread_join(thread, &retval); + if (status != 0) + { + printf("PARENT pthread_join() returned %d\n", status); + + exit(TESTRESULT_PTHREAD_JOIN_FAIL); + } + + printf("PARENT child exitted with %d\n", (int)retval); + if (retval != CHILD_RET) + { + printf("PARENT child thread did not exit with %d\n", (int)CHILD_RET); + exit(TESTRESULT_CHILD_RETVAL_FAIL); + } + + puts("PARENT returning success\n"); + return TESTRESULT_SUCCESS; +} diff --git a/apps/examples/elf/tests/signal/Makefile b/apps/examples/elf/tests/signal/Makefile new file mode 100644 index 0000000000..2704440324 --- /dev/null +++ b/apps/examples/elf/tests/signal/Makefile @@ -0,0 +1,58 @@ +############################################################################ +# examples/elf/tests/signal/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs + +BIN = signal + +SRCS = $(BIN).c +OBJS = $(BIN:.c=.o) + +all: $(BIN) + +$(OBJS): %.o: %.c + @echo "CC: $<" + @$(CC) -c $(CFLAGS) $< -o $@ + +$(BIN): $(OBJS) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +clean: + @rm -f $(BIN) *.o *~ .*.swp core + +install: + @install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/signal/signal.c b/apps/examples/elf/tests/signal/signal.c new file mode 100644 index 0000000000..80d8c18ade --- /dev/null +++ b/apps/examples/elf/tests/signal/signal.c @@ -0,0 +1,308 @@ +/**************************************************************************** + * examples/elf/tests/signal/signal.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define USEC_PER_MSEC 1000 +#define MSEC_PER_SEC 1000 +#define USEC_PER_SEC (USEC_PER_MSEC * MSEC_PER_SEC) +#define SHORT_DELAY (USEC_PER_SEC / 3) + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static int sigusr1_rcvd = 0; +static int sigusr2_rcvd = 0; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sigusr1_sighandler + ****************************************************************************/ + +/* NOTE: it is necessary for functions that are referred to by function pointers + * pointer to be declared with global scope (at least for ARM). Otherwise, + * a relocation type that is not supported by ELF is generated by GCC. + */ + +void sigusr1_sighandler(int signo) +{ + printf("sigusr1_sighandler: Received SIGUSR1, signo=%d\n", signo); + sigusr1_rcvd = 1; +} + +/**************************************************************************** + * Name: sigusr2_sigaction + ***************************************************************************/ + +/* NOTE: it is necessary for functions that are referred to by function pointers + * pointer to be declared with global scope (at least for ARM). Otherwise, + * a relocation type that is not supported by ELF is generated by GCC. + */ + +#ifdef __USE_POSIX199309 +void sigusr2_sigaction(int signo, siginfo_t *siginfo, void *arg) +{ + printf("sigusr2_sigaction: Received SIGUSR2, signo=%d siginfo=%p arg=%p\n", + signo, siginfo, arg); + +#ifdef HAVE_SIGQUEUE + if (siginfo) + { + printf(" si_signo = %d\n", siginfo->si_signo); + printf(" si_errno = %d\n", siginfo->si_errno); + printf(" si_code = %d\n", siginfo->si_code); + printf(" si_pid = %d\n", siginfo->si_pid); + printf(" si_uid = %d\n", siginfo->si_uid); + printf(" si_status = %d\n", siginfo->si_status); + printf(" si_utime = %ld\n", (long)siginfo->si_utime); + printf(" si_stime = %ld\n", (long)siginfo->si_stime); + printf(" si_value = %d\n", siginfo->si_value.sival_int); + printf(" si_int = %d\n", siginfo->si_int); + printf(" si_ptr = %p\n", siginfo->si_ptr); + printf(" si_addr = %p\n", siginfo->si_addr); + printf(" si_band = %ld\n", siginfo->si_band); + printf(" si_fd = %d\n", siginfo->si_fd); + } +#endif + sigusr2_rcvd = 1; +} +#else +void sigusr2_sigaction(int signo) +{ + printf("sigusr2_sigaction: Received SIGUSR2, signo=%d\n", signo); + sigusr2_rcvd = 1; +} + +#endif + +/**************************************************************************** + * Name: sigusr2_sighandler + ****************************************************************************/ + +static void sigusr2_sighandler(int signo) +{ + printf("sigusr2_sighandler: Received SIGUSR2, signo=%d\n", signo); + sigusr2_rcvd = 1; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: main + ****************************************************************************/ + +int main(int argc, char **argv) +{ + struct sigaction act; + struct sigaction oact; + void (*old_sigusr1_sighandler)(int signo); + void (*old_sigusr2_sighandler)(int signo); + pid_t mypid = getpid(); +#if defined(__USE_POSIX199309) && defined(HAVE_SIGQUEUE) + sigval_t sigval; +#endif + int status; + + printf("Setting up signal handlers from pid=%d\n", mypid); + + /* Set up so that sigusr1_sighandler will respond to SIGUSR1 */ + + old_sigusr1_sighandler = signal(SIGUSR1, sigusr1_sighandler); + if (old_sigusr1_sighandler == SIG_ERR) + { + fprintf(stderr, "Failed to install SIGUSR1 handler, errno=%d\n", + errno); + exit(1); + } + + printf("Old SIGUSR1 sighandler at %p\n", old_sigusr1_sighandler); + printf("New SIGUSR1 sighandler at %p\n", sigusr1_sighandler); + + /* Set up so that sigusr2_sigaction will respond to SIGUSR2 */ + + memset(&act, 0, sizeof(struct sigaction)); + act.sa_sigaction = sigusr2_sigaction; + act.sa_flags = SA_SIGINFO; + + (void)sigemptyset(&act.sa_mask); + + status = sigaction(SIGUSR2, &act, &oact); + if (status != 0) + { + fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n", + errno); + exit(2); + } + + printf("Old SIGUSR2 sighandler at %p\n", oact.sa_handler); + printf("New SIGUSR2 sighandler at %p\n", sigusr2_sigaction); + printf("Raising SIGUSR1 from pid=%d\n", mypid); + + fflush(stdout); usleep(SHORT_DELAY); + + /* Send SIGUSR1 to ourselves via raise() */ + + status = raise(SIGUSR1); + if (status != 0) + { + fprintf(stderr, "Failed to raise SIGUSR1, errno=%d\n", errno); + exit(3); + } + + usleep(SHORT_DELAY); + printf("SIGUSR1 raised from pid=%d\n", mypid); + + /* Verify that we received SIGUSR1 */ + + if (sigusr1_rcvd == 0) + { + fprintf(stderr, "SIGUSR1 not received\n"); + exit(4); + } + sigusr1_rcvd = 0; + + /* Send SIGUSR2 to ourselves */ + + printf("Killing SIGUSR2 from pid=%d\n", mypid); + fflush(stdout); usleep(SHORT_DELAY); + +#if defined(__USE_POSIX199309) && defined(HAVE_SIGQUEUE) + /* Send SIGUSR2 to ourselves via sigqueue() */ + + sigval.sival_int = 87; + status = sigqueue(mypid, SIGUSR2, sigval); + if (status != 0) + { + fprintf(stderr, "Failed to queue SIGUSR2, errno=%d\n", errno); + exit(5); + } + + usleep(SHORT_DELAY); + printf("SIGUSR2 queued from pid=%d, sigval=97\n", mypid); +#else + /* Send SIGUSR2 to ourselves via kill() */ + + status = kill(mypid, SIGUSR2); + if (status != 0) + { + fprintf(stderr, "Failed to kill SIGUSR2, errno=%d\n", errno); + exit(5); + } + + usleep(SHORT_DELAY); + printf("SIGUSR2 killed from pid=%d\n", mypid); +#endif + /* Verify that SIGUSR2 was received */ + + if (sigusr2_rcvd == 0) + { + fprintf(stderr, "SIGUSR2 not received\n"); + exit(6); + } + sigusr2_rcvd = 0; + + /* Remove the sigusr2_sigaction handler and replace the SIGUSR2 + * handler with sigusr2_sighandler. + */ + + printf("Resetting SIGUSR2 signal handler from pid=%d\n", mypid); + + old_sigusr2_sighandler = signal(SIGUSR2, sigusr2_sighandler); + if (old_sigusr2_sighandler == SIG_ERR) + { + fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n", + errno); + exit(7); + } + + printf("Old SIGUSR2 sighandler at %p\n", old_sigusr2_sighandler); + printf("New SIGUSR2 sighandler at %p\n", sigusr2_sighandler); + + /* Verify that the handler that was removed was sigusr2_sigaction */ + + if ((void*)old_sigusr2_sighandler != (void*)sigusr2_sigaction) + { + fprintf(stderr, + "Old SIGUSR2 signhanlder (%p) is not sigusr2_sigation (%p)\n", + old_sigusr2_sighandler, sigusr2_sigaction); + exit(8); + } + + /* Send SIGUSR2 to ourselves via kill() */ + + printf("Killing SIGUSR2 from pid=%d\n", mypid); + fflush(stdout); usleep(SHORT_DELAY); + + status = kill(mypid, SIGUSR2); + if (status != 0) + { + fprintf(stderr, "Failed to kill SIGUSR2, errno=%d\n", errno); + exit(9); + } + + usleep(SHORT_DELAY); + printf("SIGUSR2 killed from pid=%d\n", mypid); + + /* Verify that SIGUSR2 was received */ + + if (sigusr2_rcvd == 0) + { + fprintf(stderr, "SIGUSR2 not received\n"); + exit(10); + } + sigusr2_rcvd = 0; + + return 0; +} diff --git a/apps/examples/elf/tests/struct/Makefile b/apps/examples/elf/tests/struct/Makefile new file mode 100644 index 0000000000..f98a65e25f --- /dev/null +++ b/apps/examples/elf/tests/struct/Makefile @@ -0,0 +1,59 @@ +############################################################################ +# examples/elf/tests/hello/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs + +CFLAGS += -I. + +BIN = struct +SRCS = struct_main.c struct_dummy.c +OBJS = $(SRCS:.c=.o) + +all: $(BIN) + +$(OBJS): %.o: %.c + @echo "CC: $<" + @$(CC) -c $(CFLAGS) $< -o $@ + +$(BIN): $(OBJS) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +clean: + @rm -f $(BIN) *.o *~ .*.swp core + +install: + @install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/struct/struct.h b/apps/examples/elf/tests/struct/struct.h new file mode 100644 index 0000000000..60ef3e5bd9 --- /dev/null +++ b/apps/examples/elf/tests/struct/struct.h @@ -0,0 +1,89 @@ +/**************************************************************************** + * examples/elf/tests/struct/struct.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __EXAMPLES_ELF_TESTS_STRUCT_STRUCT_H +#define __EXAMPLES_ELF_TESTS_STRUCT_STRUCT_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define DUMMY_SCALAR_VALUE1 42 +#define DUMMY_SCALAR_VALUE2 87 +#define DUMMY_SCALAR_VALUE3 117 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +typedef void (*dummy_t)(void); + +struct struct_dummy_s +{ + int n; /* This is a simple scalar value (DUMMY_SCALAR_VALUE3) */ +}; + +struct struct_s +{ + int n; /* This is a simple scalar value (DUMMY_SCALAR_VALUE1) */ + const int *pn; /* This is a pointer to a simple scalar value */ + const struct struct_dummy_s *ps; /* This is a pointer to a structure */ + dummy_t pf; /* This is a pointer to a function */ +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +extern int dummy_scalar; /* (DUMMY_SCALAR_VALUE2) */ +extern const struct struct_dummy_s dummy_struct; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +extern void dummyfunc(void); +extern const struct struct_s *getstruct(void); + +#endif /* __EXAMPLES_ELF_TESTS_STRUCT_STRUCT_H */ + + diff --git a/apps/examples/elf/tests/struct/struct_dummy.c b/apps/examples/elf/tests/struct/struct_dummy.c new file mode 100644 index 0000000000..8a82c20747 --- /dev/null +++ b/apps/examples/elf/tests/struct/struct_dummy.c @@ -0,0 +1,65 @@ +/**************************************************************************** + * examples/elf/tests/struct/struct_dummy.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include "struct.h" + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +const struct struct_s dummy = +{ + DUMMY_SCALAR_VALUE1, + &dummy_scalar, + &dummy_struct, + (dummy_t)dummyfunc +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +const struct struct_s *getstruct(void) +{ + return &dummy; +} + diff --git a/apps/examples/elf/tests/struct/struct_main.c b/apps/examples/elf/tests/struct/struct_main.c new file mode 100644 index 0000000000..99b1bc622e --- /dev/null +++ b/apps/examples/elf/tests/struct/struct_main.c @@ -0,0 +1,109 @@ +/**************************************************************************** + * examples/elf/tests/struct/struct_main.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include "struct.h" + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +const struct struct_dummy_s dummy_struct = +{ + DUMMY_SCALAR_VALUE3 +}; + +int dummy_scalar = DUMMY_SCALAR_VALUE2; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int main(int argc, char **argv) +{ + const struct struct_s *mystruct = getstruct(); + + printf("Calling getstruct()\n"); + mystruct = getstruct(); + printf("getstruct returned %p\n", mystruct); + printf(" n = %d (vs %d) %s\n", + mystruct->n, DUMMY_SCALAR_VALUE1, + mystruct->n == DUMMY_SCALAR_VALUE1 ? "PASS" : "FAIL"); + + printf(" pn = %p (vs %p) %s\n", + mystruct->pn, &dummy_scalar, + mystruct->pn == &dummy_scalar ? "PASS" : "FAIL"); + if (mystruct->pn == &dummy_scalar) + { + printf(" *pn = %d (vs %d) %s\n", + *mystruct->pn, DUMMY_SCALAR_VALUE2, + *mystruct->pn == DUMMY_SCALAR_VALUE2 ? "PASS" : "FAIL"); + } + + printf(" ps = %p (vs %p) %s\n", + mystruct->ps, &dummy_struct, + mystruct->ps == &dummy_struct ? "PASS" : "FAIL"); + if (mystruct->ps == &dummy_struct) + { + printf(" ps->n = %d (vs %d) %s\n", + mystruct->ps->n, DUMMY_SCALAR_VALUE3, + mystruct->ps->n == DUMMY_SCALAR_VALUE3 ? "PASS" : "FAIL"); + } + + printf(" pf = %p (vs %p) %s\n", + mystruct->pf, dummyfunc, + mystruct->pf == dummyfunc ? "PASS" : "FAIL"); + if (mystruct->pf == dummyfunc) + { + printf("Calling mystruct->pf()\n"); + mystruct->pf(); + } + + printf("Exit-ing\n"); + return 0; +} + +void dummyfunc(void) +{ + printf("In dummyfunc() -- PASS\n"); +} + + diff --git a/apps/examples/elf/tests/task/Makefile b/apps/examples/elf/tests/task/Makefile new file mode 100644 index 0000000000..28047965ed --- /dev/null +++ b/apps/examples/elf/tests/task/Makefile @@ -0,0 +1,58 @@ +############################################################################ +# examples/elf/tests/task/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs + +BIN = task + +SRCS = $(BIN).c +OBJS = $(BIN:.c=.o) + +all: $(BIN) + +$(OBJS): %.o: %.c + @echo "CC: $<" + @$(CC) -c $(CFLAGS) $< -o $@ + +$(BIN): $(OBJS) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +clean: + @rm -f $(BIN) *.o *~ .*.swp core + +install: + @install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/task/task.c b/apps/examples/elf/tests/task/task.c new file mode 100644 index 0000000000..15802fc009 --- /dev/null +++ b/apps/examples/elf/tests/task/task.c @@ -0,0 +1,143 @@ +/**************************************************************************** + * examples/elf/tests/task/parent.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static char child_name[] = "child"; +static char child_arg[] = "Hello from your parent!"; +static sem_t g_sem; + +#if CONFIG_TASK_NAME_SIZE == 0 +static char no_name[] = ""; +#endif + +/**************************************************************************** + * Privite Functions + ****************************************************************************/ + +/* NOTE: it is necessary for functions that are referred to by function pointers + * pointer to be declared with global scope (at least for ARM). Otherwise, + * a relocation type that is not supported by ELF is generated by GCC. + */ + + int child_task(int argc, char **argv) +{ + printf("Child: execv was successful!\n"); + printf("Child: argc=%d\n", argc); + + if (argc != 2) + { + printf("Child: expected argc to be 2\n"); + printf("Child: Exit-ting with status=2\n"); + exit(2); + } + printf("Child: argv[0]=\"%s\"\n", argv[0]); + +#if CONFIG_TASK_NAME_SIZE == 0 + if (strcmp(argv[0], no_name) != 0) + { + printf("Child: expected argv[0] to be \"%s\"\n", no_name); + printf("Child: Exit-ting with status=3\n"); + exit(3); + } +#else + if (strncmp(argv[0], child_name, CONFIG_TASK_NAME_SIZE) != 0) + { + printf("Child: expected argv[0] to be \"%s\"\n", child_name); + printf("Child: Exit-ting with status=3\n"); + exit(3); + } +#endif + + printf("Child: argv[1]=\"%s\"\n", argv[1]); + + if (strcmp(argv[1], child_arg) != 0) + { + printf("Child: expected argv[1] to be \"%s\"\n", child_arg); + printf("Child: Exit-ting with status=4\n"); + exit(4); + } + + printf("Child: Exit-ting with status=0\n"); + sem_post(&g_sem); + return 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int main(int argc, char **argv) +{ + pid_t parent_pid = getpid(); + char *child_argv[2]; + pid_t child_pid; + + printf("Parent: Started, pid=%d\n", parent_pid); + + sem_init(&g_sem, 0, 0); + + printf("Parent: Calling task_create()\n"); + + child_argv[0] = child_arg; + child_argv[1] = 0; + child_pid = task_create(child_name, 50, 512, child_task, (const char**)child_argv); + if (child_pid < 0) + { + printf("Parent: task_create failed: %d\n", errno); + } + + printf("Parent: Waiting for child (pid=%d)\n", child_pid); + sem_wait(&g_sem); + printf("Parent: Exit-ing\n"); + sem_destroy(&g_sem); + return 0; +} + From a6e577e3c4cab1f1636aaee7abcde4dbab8338f5 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 25 Oct 2012 22:10:56 +0000 Subject: [PATCH 030/206] More ELF loader changes git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5261 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/README.txt | 47 ++++++++++++++++++++++ apps/examples/elf/Kconfig | 16 ++++++++ apps/examples/elf/Makefile | 9 +++-- apps/examples/elf/{elf_main => elf_main.c} | 22 ++++++---- apps/examples/elf/tests/errno/Makefile | 2 +- apps/examples/elf/tests/hello++/Makefile | 2 +- apps/examples/elf/tests/hello/Makefile | 2 +- apps/examples/elf/tests/longjmp/Makefile | 2 +- apps/examples/elf/tests/mutex/Makefile | 2 +- apps/examples/elf/tests/pthread/Makefile | 2 +- apps/examples/elf/tests/signal/Makefile | 2 +- apps/examples/elf/tests/struct/Makefile | 2 +- apps/examples/elf/tests/task/Makefile | 2 +- nuttx/Makefile | 2 +- nuttx/arch/sim/src/up_elf.c | 4 +- nuttx/arch/x86/src/common/up_elf.c | 4 +- nuttx/binfmt/elf.c | 10 ++--- nuttx/binfmt/libelf/Make.defs | 2 +- nuttx/binfmt/libelf/libelf_load.c | 2 +- nuttx/binfmt/libnxflat/Make.defs | 2 +- nuttx/binfmt/nxflat.c | 4 +- nuttx/include/elf.h | 12 +++--- nuttx/tools/mkconfig.c | 2 +- 23 files changed, 117 insertions(+), 39 deletions(-) rename apps/examples/elf/{elf_main => elf_main.c} (91%) diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 763427e326..fa97bd64e3 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -297,6 +297,53 @@ examples/discover CONFIG_EXAMPLES_DISCOVER_DRIPADDR - Router IP address CONFIG_EXAMPLES_DISCOVER_NETMASK - Network Mask +examples/elf +^^^^^^^^^^^^ + + This example builds a small ELF loader test case. This includes several + test programs under examples/elf tests. These tests are build using + the relocatable ELF format and installed in a ROMFS file system. At run time, + each program in the ROMFS file system is executed. Requires CONFIG_ELF. + Other configuration options: + + CONFIG_EXAMPLES_ELF_DEVMINOR - The minor device number of the ROMFS block. + For example, the N in /dev/ramN. Used for registering the RAM block driver + that will hold the ROMFS file system containing the ELF executables to be + tested. Default: 0 + + CONFIG_EXAMPLES_ELF_DEVPATH - The path to the ROMFS block driver device. This + must match EXAMPLES_ELF_DEVMINOR. Used for registering the RAM block driver + that will hold the ROMFS file system containing the ELF executables to be + tested. Default: "/dev/ram0" + + NOTES: + + 1. Your top-level nuttx/Make.defs file must include an approproate definition, + LDELFFLAGS, to generate a relocatable ELF object. With GNU LD, this should + include '-r' and '-e main' (or _main on some platforms). + + LDELFFLAGS = -r -e main + + If you use GCC to link, you make also need to include '-nostdlib' or + '-nostartfiles' and '-nodefaultlibs'. + + 2. This example also requires genromfs. genromfs can be build as part of the + nuttx toolchain. Or can built from the genromfs sources that can be found + at misc/tools/genromfs-0.5.2.tar.gz. In any event, the PATH variable must + include the path to the genromfs executable. + + 3. ELF size: The ELF files in this example are, be default, quite large + because they include a lot of "build garbage". You can greately reduce the + size of the ELF binaries are using the objcopy --strip-unneeded command to + remove un-necessary information from the ELF files. + + 4. Simulator. You cannot use this example with the the NuttX simulator on + Cygwin. That is because the Cygwin GCC does not generate ELF file but + rather some Windows-native binary format. + + If you really want to do this, you can create a NuttX x86 buildroot toolchain + and use that be build the ELF executables for the ROMFS file system. + examples/ftpc ^^^^^^^^^^^^^ diff --git a/apps/examples/elf/Kconfig b/apps/examples/elf/Kconfig index aca36f1b9b..c62a98486e 100644 --- a/apps/examples/elf/Kconfig +++ b/apps/examples/elf/Kconfig @@ -10,4 +10,20 @@ config EXAMPLES_ELF Enable the ELF loader example if EXAMPLES_ELF +config EXAMPLES_ELF_DEVMINOR + int "ROMFS Minor Device Number" + default 0 + ---help--- + The minor device number of the ROMFS block. For example, the N in /dev/ramN. + Used for registering the RAM block driver that will hold the ROMFS file system + containing the ELF executables to be tested. Default: 0 + +config EXAMPLES_ELF_DEVPATH + string "ROMFS Devie Path" + default "/dev/ram0" + ---help--- + The path to the ROMFS block driver device. This must match EXAMPLES_ELF_DEVMINOR. + Used for registering the RAM block driver that will hold the ROMFS file system + containing the ELF executables to be tested. Default: "/dev/ram0" + endif diff --git a/apps/examples/elf/Makefile b/apps/examples/elf/Makefile index 640e8e427d..23a6bcb6fe 100644 --- a/apps/examples/elf/Makefile +++ b/apps/examples/elf/Makefile @@ -61,7 +61,7 @@ ROOTDEPPATH = --dep-path . VPATH = all: .built -.PHONY: headers clean depend disclean +.PHONY: headers clean_tests clean depend disclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -72,7 +72,7 @@ $(COBJS): %$(OBJEXT): %.c headers: @$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) -.built: $(OBJS) +.built: headers $(OBJS) @( for obj in $(OBJS) ; do \ $(call ARCHIVE, $(BIN), $${obj}); \ done ; ) @@ -88,7 +88,10 @@ context: depend: .depend -clean: +clean_tests: + @$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) clean + +clean: clean_tests @rm -f *.o *~ .*.swp .built $(call CLEAN) diff --git a/apps/examples/elf/elf_main b/apps/examples/elf/elf_main.c similarity index 91% rename from apps/examples/elf/elf_main rename to apps/examples/elf/elf_main.c index c58b13ffc2..5699dd2849 100644 --- a/apps/examples/elf/elf_main +++ b/apps/examples/elf/elf_main.c @@ -89,9 +89,16 @@ #define SECTORSIZE 512 #define NSECTORS(b) (((b)+SECTORSIZE-1)/SECTORSIZE) -#define ROMFSDEV "/dev/ram0" #define MOUNTPT "/mnt/romfs" +#ifndef CONFIG_EXAMPLES_ELF_DEVMINOR +# define CONFIG_EXAMPLES_ELF_DEVMINOR 0 +#endif + +#ifndef CONFIG_EXAMPLES_ELF_DEVPATH +# define CONFIG_EXAMPLES_ELF_DEVPATH "/dev/ram0" +#endif + /* If CONFIG_DEBUG is enabled, use dbg instead of printf so that the * output will be synchronous with the debug output. */ @@ -166,8 +173,9 @@ int elf_main(int argc, char *argv[]) /* Create a ROM disk for the ROMFS filesystem */ - message("Registering romdisk\n"); - ret = romdisk_register(0, romfs_img, NSECTORS(romfs_img_len), SECTORSIZE); + message("Registering romdisk at /dev/ram%d\n", CONFIG_EXAMPLES_ELF_DEVMINOR); + ret = romdisk_register(CONFIG_EXAMPLES_ELF_DEVMINOR, romfs_img, + NSECTORS(romfs_img_len), SECTORSIZE); if (ret < 0) { err("ERROR: romdisk_register failed: %d\n", ret); @@ -178,13 +186,13 @@ int elf_main(int argc, char *argv[]) /* Mount the file system */ message("Mounting ROMFS filesystem at target=%s with source=%s\n", - MOUNTPT, ROMFSDEV); + MOUNTPT, CONFIG_EXAMPLES_ELF_DEVPATH); - ret = mount(ROMFSDEV, MOUNTPT, "romfs", MS_RDONLY, NULL); + ret = mount(CONFIG_EXAMPLES_ELF_DEVPATH, MOUNTPT, "romfs", MS_RDONLY, NULL); if (ret < 0) { err("ERROR: mount(%s,%s,romfs) failed: %s\n", - ROMFSDEV, MOUNTPT, errno); + CONFIG_EXAMPLES_ELF_DEVPATH, MOUNTPT, errno); elf_uninitialize(); } @@ -219,6 +227,6 @@ int elf_main(int argc, char *argv[]) sleep(4); } - message("End-of-Test.. Exit-ing\n"); + message("End-of-Test.. Exiting\n"); return 0; } diff --git a/apps/examples/elf/tests/errno/Makefile b/apps/examples/elf/tests/errno/Makefile index d3b12aa2ec..3c299b16df 100644 --- a/apps/examples/elf/tests/errno/Makefile +++ b/apps/examples/elf/tests/errno/Makefile @@ -39,7 +39,7 @@ BIN = errno SRCS = $(BIN).c -OBJS = $(BIN:.c=.o) +OBJS = $(SRCS:.c=.o) all: $(BIN) diff --git a/apps/examples/elf/tests/hello++/Makefile b/apps/examples/elf/tests/hello++/Makefile index b3d07d2626..9de52cfa10 100644 --- a/apps/examples/elf/tests/hello++/Makefile +++ b/apps/examples/elf/tests/hello++/Makefile @@ -64,7 +64,7 @@ all: $(BIN1) $(BIN2) $(BIN3) $(BIN4) $(OBJS): %.o: %.cpp @echo "CC: $<" - @$(CXX) -c $(CXXPICFLAGS) $< -o $@ + @$(CXX) -c $(CXXFLAGS) $< -o $@ # This contains libstdc++ stubs to that you can build C++ code # without actually having libstdc++ diff --git a/apps/examples/elf/tests/hello/Makefile b/apps/examples/elf/tests/hello/Makefile index 3b9b06ac42..c3a3dacaf1 100644 --- a/apps/examples/elf/tests/hello/Makefile +++ b/apps/examples/elf/tests/hello/Makefile @@ -39,7 +39,7 @@ BIN = hello SRCS = $(BIN).c -OBJS = $(BIN:.c=.o) +OBJS = $(SRCS:.c=.o) all: $(BIN) diff --git a/apps/examples/elf/tests/longjmp/Makefile b/apps/examples/elf/tests/longjmp/Makefile index 12d6e443cd..d737718e05 100644 --- a/apps/examples/elf/tests/longjmp/Makefile +++ b/apps/examples/elf/tests/longjmp/Makefile @@ -39,7 +39,7 @@ BIN = longjmp SRCS = $(BIN).c -OBJS = $(BIN:.c=.o) +OBJS = $(SRCS:.c=.o) all: $(BIN) diff --git a/apps/examples/elf/tests/mutex/Makefile b/apps/examples/elf/tests/mutex/Makefile index 632fed9dd4..7f0a5493e9 100644 --- a/apps/examples/elf/tests/mutex/Makefile +++ b/apps/examples/elf/tests/mutex/Makefile @@ -39,7 +39,7 @@ BIN = mutex SRCS = $(BIN).c -OBJS = $(BIN:.c=.o) +OBJS = $(SRCS:.c=.o) all: $(BIN) diff --git a/apps/examples/elf/tests/pthread/Makefile b/apps/examples/elf/tests/pthread/Makefile index fae6144c26..8db290e6ea 100644 --- a/apps/examples/elf/tests/pthread/Makefile +++ b/apps/examples/elf/tests/pthread/Makefile @@ -39,7 +39,7 @@ BIN = pthread SRCS = $(BIN).c -OBJS = $(BIN:.c=.o) +OBJS = $(SRCS:.c=.o) all: $(BIN) diff --git a/apps/examples/elf/tests/signal/Makefile b/apps/examples/elf/tests/signal/Makefile index 2704440324..4338aa48da 100644 --- a/apps/examples/elf/tests/signal/Makefile +++ b/apps/examples/elf/tests/signal/Makefile @@ -39,7 +39,7 @@ BIN = signal SRCS = $(BIN).c -OBJS = $(BIN:.c=.o) +OBJS = $(SRCS:.c=.o) all: $(BIN) diff --git a/apps/examples/elf/tests/struct/Makefile b/apps/examples/elf/tests/struct/Makefile index f98a65e25f..c15d8fc476 100644 --- a/apps/examples/elf/tests/struct/Makefile +++ b/apps/examples/elf/tests/struct/Makefile @@ -38,7 +38,7 @@ CFLAGS += -I. -BIN = struct +BIN = struct SRCS = struct_main.c struct_dummy.c OBJS = $(SRCS:.c=.o) diff --git a/apps/examples/elf/tests/task/Makefile b/apps/examples/elf/tests/task/Makefile index 28047965ed..208b228b3a 100644 --- a/apps/examples/elf/tests/task/Makefile +++ b/apps/examples/elf/tests/task/Makefile @@ -39,7 +39,7 @@ BIN = task SRCS = $(BIN).c -OBJS = $(BIN:.c=.o) +OBJS = $(SRCS:.c=.o) all: $(BIN) diff --git a/nuttx/Makefile b/nuttx/Makefile index 7a058d88e9..73bffc3014 100644 --- a/nuttx/Makefile +++ b/nuttx/Makefile @@ -644,7 +644,7 @@ ifneq ($(APPDIR),) fi @$(MAKE) -C "$(TOPDIR)/$(APPDIR)" TOPDIR="$(TOPDIR)" distclean @if [ -r _SAVED_APPS_config ]; then \ - @mv _SAVED_APPS_config "$(TOPDIR)/$(APPDIR)/.config" || \ + mv _SAVED_APPS_config "$(TOPDIR)/$(APPDIR)/.config" || \ { echo "Copy of _SAVED_APPS_config failed" ; exit 1 ; } \ fi endif diff --git a/nuttx/arch/sim/src/up_elf.c b/nuttx/arch/sim/src/up_elf.c index c6aabdcef7..ca3b642dcd 100644 --- a/nuttx/arch/sim/src/up_elf.c +++ b/nuttx/arch/sim/src/up_elf.c @@ -40,7 +40,9 @@ #include #include +#include #include +#include #include #include @@ -113,7 +115,7 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, { FAR uint32_t *ptr = (FAR uint32_t *)addr; - switch (ELF_REL_TYPE(rel->r_info)) + switch (ELF32_R_TYPE(rel->r_info)) { case R_386_32: *ptr += sym->st_value; diff --git a/nuttx/arch/x86/src/common/up_elf.c b/nuttx/arch/x86/src/common/up_elf.c index f159c8e518..be166b480c 100644 --- a/nuttx/arch/x86/src/common/up_elf.c +++ b/nuttx/arch/x86/src/common/up_elf.c @@ -40,7 +40,9 @@ #include #include +#include #include +#include #include #include @@ -113,7 +115,7 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, { FAR uint32_t *ptr = (FAR uint32_t *)addr; - switch (ELF_REL_TYPE(rel->r_info)) + switch (ELF32_R_TYPE(rel->r_info)) { case R_386_32: *ptr += sym->st_value; diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c index ba12a22ea4..d9c3d0b9c9 100644 --- a/nuttx/binfmt/elf.c +++ b/nuttx/binfmt/elf.c @@ -139,11 +139,11 @@ static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo) bdbg(" e_shnum: %d\n", loadinfo->ehdr.e_shnum); bdbg(" e_shstrndx: %d\n", loadinfo->ehdr.e_shstrndx); - if (loadinfo->shdr && loadinfo->ehdr.e_shum > 0) + if (loadinfo->shdr && loadinfo->ehdr.e_shnum > 0) { - for (i = 0; i < loadinfo->ehdr.e_shum; i++) + for (i = 0; i < loadinfo->ehdr.e_shnum; i++) { - FAR ELF32_Shdr *shdr = &loadinfo->shdr[i]; + FAR Elf32_Shdr *shdr = &loadinfo->shdr[i]; bdbg("Sections %d:\n", i); bdbg(" sh_name: %08x\n", shdr->sh_name); bdbg(" sh_type: %08x\n", shdr->sh_type); @@ -184,7 +184,7 @@ static int elf_loadbinary(struct binary_s *binp) elf_dumploadinfo(&loadinfo); if (ret != 0) { - bdbg("Failed to initialize for load of NXFLT program: %d\n", ret); + bdbg("Failed to initialize for load of ELF program: %d\n", ret); goto errout; } @@ -194,7 +194,7 @@ static int elf_loadbinary(struct binary_s *binp) elf_dumploadinfo(&loadinfo); if (ret != 0) { - bdbg("Failed to load NXFLT program binary: %d\n", ret); + bdbg("Failed to load ELF program binary: %d\n", ret); goto errout_with_init; } diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs index 9e06537bd6..a70a127f80 100644 --- a/nuttx/binfmt/libelf/Make.defs +++ b/nuttx/binfmt/libelf/Make.defs @@ -41,7 +41,7 @@ BINFMT_CSRCS += elf.c # ELF library -BINFMT_CSRCS = libelf_init.c libelf_uninit.c libelf_load.c \ +BINFMT_CSRCS += libelf_init.c libelf_uninit.c libelf_load.c \ libelf_unload.c libelf_verify.c libelf_read.c \ libelf_bind.c libelf_symbols.c diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 758f965483..4a1a561c3c 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -283,8 +283,8 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo) /* Update sh_addr to point to copy in memory */ + bvdbg("%d. %08x->%08x\n", i, (long)shdr->sh_addr, (long)dest); shdr->sh_addr = (uintptr_t)dest; - bvdbg("%d. 0x%lx %s\n", (long)shdr->sh_addr, loadinfo->secstrings + shdr->sh_name); /* Setup the memory pointer for the next time through the loop */ diff --git a/nuttx/binfmt/libnxflat/Make.defs b/nuttx/binfmt/libnxflat/Make.defs index 4462e9a024..4f522e52b2 100644 --- a/nuttx/binfmt/libnxflat/Make.defs +++ b/nuttx/binfmt/libnxflat/Make.defs @@ -41,7 +41,7 @@ BINFMT_CSRCS += nxflat.c # NXFLAT library -BINFMT_CSRCS = libnxflat_init.c libnxflat_uninit.c libnxflat_load.c \ +BINFMT_CSRCS += libnxflat_init.c libnxflat_uninit.c libnxflat_load.c \ libnxflat_unload.c libnxflat_verify.c libnxflat_read.c \ libnxflat_bind.c diff --git a/nuttx/binfmt/nxflat.c b/nuttx/binfmt/nxflat.c index babc51ff95..8d0ecfdcd9 100644 --- a/nuttx/binfmt/nxflat.c +++ b/nuttx/binfmt/nxflat.c @@ -158,7 +158,7 @@ static int nxflat_loadbinary(struct binary_s *binp) nxflat_dumploadinfo(&loadinfo); if (ret != 0) { - bdbg("Failed to initialize for load of NXFLT program: %d\n", ret); + bdbg("Failed to initialize for load of NXFLAT program: %d\n", ret); goto errout; } @@ -168,7 +168,7 @@ static int nxflat_loadbinary(struct binary_s *binp) nxflat_dumploadinfo(&loadinfo); if (ret != 0) { - bdbg("Failed to load NXFLT program binary: %d\n", ret); + bdbg("Failed to load NXFLAT program binary: %d\n", ret); goto errout_with_init; } diff --git a/nuttx/include/elf.h b/nuttx/include/elf.h index 1b36701fda..c3fb2732d2 100644 --- a/nuttx/include/elf.h +++ b/nuttx/include/elf.h @@ -166,9 +166,9 @@ /* Definitions for Elf32_Sym::st_info */ -#define ELF32_ST_BIND(i) ((i)>>4) -#define ELF32_ST_TYPE(i) ((i)&0xf) -#define ELF32_ST_INFO(b,t) (((b)<<4)+((t)&0xf)) +#define ELF32_ST_BIND(i) ((i) >> 4) +#define ELF32_ST_TYPE(i) ((i) & 0xf) +#define ELF32_ST_INFO(b,t) (((b) << 4) | ((t) & 0xf)) /* Figure 4-16: Symbol Binding, ELF32_ST_BIND */ @@ -190,9 +190,9 @@ /* Definitions for Elf32_Rel*::r_info */ -#define ELF32_R_SYM(i) ((i)>>8) -#define ELF32_R_TYPE(i) ((unsigned char)(i)) -#define ELF32_R_INFO(s,t) (((s)<<8)+(unsigned char)(t)) +#define ELF32_R_SYM(i) ((i) >> 8) +#define ELF32_R_TYPE(i) ((i) & 0xff) +#define ELF32_R_INFO(s,t) (((s)<< 8) | ((t) & 0xff)) /* Figure 5-2: Segment Types, p_type */ diff --git a/nuttx/tools/mkconfig.c b/nuttx/tools/mkconfig.c index 2d2fff5c56..3e55f50974 100644 --- a/nuttx/tools/mkconfig.c +++ b/nuttx/tools/mkconfig.c @@ -116,7 +116,7 @@ int main(int argc, char **argv, char **envp) printf(" * configured (at present, NXFLAT is the only supported binary.\n"); printf(" * format).\n"); printf(" */\n\n"); - printf("#if !defined(CONFIG_NXFLAT)\n"); + printf("#if !defined(CONFIG_NXFLAT) && !defined(CONFIG_ELF)\n"); printf("# undef CONFIG_BINFMT_DISABLE\n"); printf("# define CONFIG_BINFMT_DISABLE 1\n"); printf("#endif\n\n"); From 247e94d02aaac98b5e8007f8d47f68072cadc69d Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 25 Oct 2012 23:52:50 +0000 Subject: [PATCH 031/206] Add an ARM ELF header file git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5262 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/include/elf.h | 243 +++++++++++++++++++++++++++++++++++ nuttx/include/elf.h | 5 +- 2 files changed, 247 insertions(+), 1 deletion(-) create mode 100644 nuttx/arch/arm/include/elf.h diff --git a/nuttx/arch/arm/include/elf.h b/nuttx/arch/arm/include/elf.h new file mode 100644 index 0000000000..d853853801 --- /dev/null +++ b/nuttx/arch/arm/include/elf.h @@ -0,0 +1,243 @@ +/**************************************************************************** + * arch/arm/include/syscall.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: "ELF for the ARM® Architecture," ARM IHI 0044D, current through + * ABI release 2.08, October 28, 2009, ARM Limited. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_INCLUDE_ELF_H +#define __ARCH_ARM_INCLUDE_ELF_H + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* 4.3.1 ELF Identification. Should have: + * + * e_machine = EM_ARM + * e_ident[EI_CLASS] = ELFCLASS32 + * e_ident[EI_DATA] = ELFDATA2LSB (little endian) or ELFDATA2MSB (big endian) + */ + +#if 0 /* Defined in include/elf.h */ +#define EM_ARM 40 +#endif + +/* Table 4-2, ARM-specific e_flags */ + +#define EF_ARM_EABI_MASK 0xff000000 +#define EF_ARM_EABI_UNKNOWN 0x00000000 +#define EF_ARM_EABI_VER1 0x01000000 +#define EF_ARM_EABI_VER2 0x02000000 +#define EF_ARM_EABI_VER3 0x03000000 +#define EF_ARM_EABI_VER4 0x04000000 +#define EF_ARM_EABI_VER5 0x05000000 + +#define EF_ARM_BE8 0x00800000 + +/* Table 4-4, Processor specific section types */ + +#define SHT_ARM_EXIDX 0x70000001 /* Exception Index table */ +#define SHT_ARM_PREEMPTMAP 0x70000002 /* BPABI DLL dynamic linking pre-emption map */ +#define SHT_ARM_ATTRIBUTES 0x70000003 /* Object file compatibility attributes */ +#define SHT_ARM_DEBUGOVERLAY 0x70000004 +#define SHT_ARM_OVERLAYSECTION 0x70000005 + +/* 4.7.1 Relocation codes + * + * S (when used on its own) is the address of the symbol. + * A is the addend for the relocation. + * P is the address of the place being relocated (derived from r_offset). + * Pa is the adjusted address of the place being relocated, defined as (P & 0xFFFFFFFC). + * T is 1 if the target symbol S has type STT_FUNC and the symbol addresses a Thumb instruction; + * it is 0 otherwise. + * B(S) is the addressing origin of the output segment defining the symbol S. + * GOT_ORG is the addressing origin of the Global Offset Table + * GOT(S) is the address of the GOT entry for the symbol S. + */ + +#define R_ARM_NONE 0 /* No relocation */ +#define R_ARM_PC24 1 /* ARM ((S + A) | T) - P */ +#define R_ARM_ABS32 2 /* Data (S + A) | T */ +#define R_ARM_REL32 3 /* Data ((S + A) | T) - P */ +#define R_ARM_LDR_PC_G0 4 /* ARM S + A - P */ +#define R_ARM_ABS16 5 /* Data S + A */ +#define R_ARM_ABS12 6 /* ARM S + A */ +#define R_ARM_THM_ABS5 7 /* Thumb16 S + A */ +#define R_ARM_ABS8 8 /* Data S + A */ +#define R_ARM_SBREL32 9 /* Data ((S + A) | T) - B(S) */ +#define R_ARM_THM_CALL 10 /* Thumb32 ((S + A) | T) - P */ +#define R_ARM_THM_PC8 11 /* Thumb16 S + A - Pa */ +#define R_ARM_BREL_ADJ 12 /* Data ?B(S) + A */ +#define R_ARM_TLS_DESC 13 /* Data */ +#define R_ARM_THM_SWI8 14 /* Obsolete */ +#define R_ARM_XPC25 15 /* Obsolete */ +#define R_ARM_THM_XPC22 16 /* Obsolete */ +#define R_ARM_TLS_DTPMOD32 17 /* Data Module[S] */ +#define R_ARM_TLS_DTPOFF32 18 /* Data S + A - TLS */ +#define R_ARM_TLS_TPOFF32 19 /* Data S + A - tp */ +#define R_ARM_COPY 20 /* Miscellaneous */ +#define R_ARM_GLOB_DAT 21 /* Data (S + A) | T */ +#define R_ARM_JUMP_SLOT 22 /* Data (S + A) | T */ +#define R_ARM_RELATIVE 23 /* Data B(S) + A */ +#define R_ARM_GOTOFF32 24 /* Data ((S + A) | T) - GOT_ORG */ +#define R_ARM_BASE_PREL 25 /* Data B(S) + A - P */ +#define R_ARM_GOT_BREL 26 /* Data GOT(S) + A - GOT_ORG */ +#define R_ARM_PLT32 27 /* ARM ((S + A) | T) - P */ +#define R_ARM_CALL 28 /* ARM ((S + A) | T) - P */ +#define R_ARM_JUMP24 29 /* ARM ((S + A) | T) - P */ +#define R_ARM_THM_JUMP24 30 /* Thumb32 ((S + A) | T) - P */ +#define R_ARM_BASE_ABS 31 /* Data B(S) + A */ +#define R_ARM_ALU_PCREL_7_0 32 /* Obsolete */ +#define R_ARM_ALU_PCREL_15_8 33 /* Obsolete */ +#define R_ARM_ALU_PCREL_23_15 34 /* Obsolete */ +#define R_ARM_LDR_SBREL_11_0_NC 35 /* ARM S + A - B(S) */ +#define R_ARM_ALU_SBREL_19_12_NC 36 /* ARM S + A - B(S) */ +#define R_ARM_ALU_SBREL_27_20_CK 37 /* ARM S + A - B(S) */ +#define R_ARM_TARGET1 38 /* Miscellaneous (S + A) | T or ((S + A) | T) - P */ +#define R_ARM_SBREL31 39 /* Data ((S + A) | T) - B(S) */ +#define R_ARM_V4BX 40 /* Miscellaneous */ +#define R_ARM_TARGET2 41 /* Miscellaneous */ +#define R_ARM_PREL31 42 /* Data ((S + A) | T) - P */ +#define R_ARM_MOVW_ABS_NC 43 /* ARM (S + A) | T */ +#define R_ARM_MOVT_ABS 44 /* ARM S + A */ +#define R_ARM_MOVW_PREL_NC 45 /* ARM ((S + A) | T) - P */ +#define R_ARM_MOVT_PREL 46 /* ARM S + A - P */ +#define R_ARM_THM_MOVW_ABS_NC 47 /* Thumb32 (S + A) | T */ +#define R_ARM_THM_MOVT_ABS 48 /* Thumb32 S + A */ +#define R_ARM_THM_MOVW_PREL_NC 49 /* Thumb32 ((S + A) | T) - P */ +#define R_ARM_THM_MOVT_PREL 50 /* Thumb32 S + A - P */ +#define R_ARM_THM_JUMP19 51 /* Thumb32 ((S + A) | T) - P */ +#define R_ARM_THM_JUMP6 52 /* Thumb16 S + A - P */ +#define R_ARM_THM_ALU_PREL_11_0 53 /* Thumb32 ((S + A) | T) - Pa */ +#define R_ARM_THM_PC12 54 /* Thumb32 S + A - Pa */ +#define R_ARM_ABS32_NOI 55 /* Data S + A */ +#define R_ARM_REL32_NOI 56 /* Data S + A - P */ +#define R_ARM_ALU_PC_G0_NC 57 /* ARM ((S + A) | T) - P */ +#define R_ARM_ALU_PC_G0 58 /* ARM ((S + A) | T) - P */ +#define R_ARM_ALU_PC_G1_NC 59 /* ARM ((S + A) | T) - P */ +#define R_ARM_ALU_PC_G1 60 /* ARM ((S + A) | T) - P */ +#define R_ARM_ALU_PC_G2 61 /* ARM ((S + A) | T) - P */ +#define R_ARM_LDR_PC_G1 62 /* ARM S + A - P */ +#define R_ARM_LDR_PC_G2 63 /* ARM S + A - P */ +#define R_ARM_LDRS_PC_G0 64 /* ARM S + A - P */ +#define R_ARM_LDRS_PC_G1 65 /* ARM S + A - P */ +#define R_ARM_LDRS_PC_G2 66 /* ARM S + A - P */ +#define R_ARM_LDC_PC_G0 67 /* ARM S + A - P */ +#define R_ARM_LDC_PC_G1 68 /* ARM S + A - P */ +#define R_ARM_LDC_PC_G2 69 /* ARM S + A - P */ +#define R_ARM_ALU_SB_G0_NC 70 /* ARM ((S + A) | T) - B(S) */ +#define R_ARM_ALU_SB_G0 71 /* ARM ((S + A) | T) - B(S) */ +#define R_ARM_ALU_SB_G1_NC 72 /* ARM ((S + A) | T) - B(S) */ +#define R_ARM_ALU_SB_G1 73 /* ARM ((S + A) | T) - B(S) */ +#define R_ARM_ALU_SB_G2 74 /* ARM ((S + A) | T) - B(S) */ +#define R_ARM_LDR_SB_G0 75 /* ARM S + A - B(S) */ +#define R_ARM_LDR_SB_G1 76 /* ARM S + A - B(S) */ +#define R_ARM_LDR_SB_G2 77 /* ARM S + A - B(S) */ +#define R_ARM_LDRS_SB_G0 78 /* ARM S + A - B(S) */ +#define R_ARM_LDRS_SB_G1 79 /* ARM S + A - B(S) */ +#define R_ARM_LDRS_SB_G2 80 /* ARM S + A - B(S) */ +#define R_ARM_LDC_SB_G0 81 /* ARM S + A - B(S) */ +#define R_ARM_LDC_SB_G1 82 /* ARM S + A - B(S) */ +#define R_ARM_LDC_SB_G2 83 /* ARM S + A - B(S) */ +#define R_ARM_MOVW_BREL_NC 84 /* ARM ((S + A) | T) - B(S) */ +#define R_ARM_MOVT_BREL 85 /* ARM S + A - B(S) */ +#define R_ARM_MOVW_BREL 86 /* ARM ((S + A) | T) - B(S) */ +#define R_ARM_THM_MOVW_BREL_NC 87 /* Thumb32 ((S + A) | T) - B(S) */ +#define R_ARM_THM_MOVT_BREL 88 /* Thumb32 S + A - B(S) */ +#define R_ARM_THM_MOVW_BREL 89 /* Thumb32 ((S + A) | T) - B(S) */ +#define R_ARM_TLS_GOTDESC 90 /* Data */ +#define R_ARM_TLS_CALL 91 /* ARM */ +#define R_ARM_TLS_DESCSEQ 92 /* ARM TLS relaxation */ +#define R_ARM_THM_TLS_CALL 93 /* Thumb32 */ +#define R_ARM_PLT32_ABS 94 /* Data PLT(S) + A */ +#define R_ARM_GOT_ABS 95 /* Data GOT(S) + A */ +#define R_ARM_GOT_PREL 96 /* Data GOT(S) + A - P */ +#define R_ARM_GOT_BREL12 97 /* ARM GOT(S) + A - GOT_ORG */ +#define R_ARM_GOTOFF12 98 /* ARM S + A - GOT_ORG */ +#define R_ARM_GOTRELAX 99 /* Miscellaneous */ +#define R_ARM_GNU_VTENTRY 100 /* Data */ +#define R_ARM_GNU_VTINHERIT 101 /* Data */ +#define R_ARM_THM_JUMP11 102 /* Thumb16 S + A - P */ +#define R_ARM_THM_JUMP8 103 /* Thumb16 S + A - P */ +#define R_ARM_TLS_GD32 104 /* Data GOT(S) + A - P */ +#define R_ARM_TLS_LDM32 105 /* Data GOT(S) + A - P */ +#define R_ARM_TLS_LDO32 106 /* Data S + A - TLS */ +#define R_ARM_TLS_IE32 107 /* Data GOT(S) + A - P */ +#define R_ARM_TLS_LE32 108 /* Data S + A - tp */ +#define R_ARM_TLS_LDO12 109 /* ARM S + A - TLS */ +#define R_ARM_TLS_LE12 110 /* ARM S + A - tp */ +#define R_ARM_TLS_IE12GP 111 /* ARM GOT(S) + A - GOT_ORG */ +#define R_ARM_ME_TOO 128 /* Obsolete */ +#define R_ARM_THM_TLS_DESCSEQ16 129 /* Thumb16 */ +#define R_ARM_THM_TLS_DESCSEQ32 130 /* Thumb32 */ + +/* 5.2.1 Platform architecture compatibility data */ + +#define PT_ARM_ARCHEXT_FMTMSK 0xff000000 +#define PT_ARM_ARCHEXT_PROFMSK 0x00ff0000 +#define PT_ARM_ARCHEXT_ARCHMSK 0x000000ff + +#define PT_ARM_ARCHEXT_FMT_OS 0x00000000 +#define PT_ARM_ARCHEXT_FMT_ABI 0x01000000 + +#define PT_ARM_ARCHEXT_PROF_NONE 0x00000000 +#define PT_ARM_ARCHEXT_PROF_ARM 0x00410000 +#define PT_ARM_ARCHEXT_PROF_RT 0x00520000 +#define PT_ARM_ARCHEXT_PROF_MC 0x004d0000 +#define PT_ARM_ARCHEXT_PROF_CLASSIC 0x00530000 + +#define PT_ARM_ARCHEXT_ARCH_UNKNOWN 0x00 +#define PT_ARM_ARCHEXT_ARCHv4 0x01 +#define PT_ARM_ARCHEXT_ARCHv4T 0x02 +#define PT_ARM_ARCHEXT_ARCHv5T 0x03 +#define PT_ARM_ARCHEXT_ARCHv5TE 0x04 +#define PT_ARM_ARCHEXT_ARCHv5TEJ 0x05 +#define PT_ARM_ARCHEXT_ARCHv6 0x06 +#define PT_ARM_ARCHEXT_ARCHv6KZ 0x07 +#define PT_ARM_ARCHEXT_ARCHv6T2 0x08 +#define PT_ARM_ARCHEXT_ARCHv6K 0x09 +#define PT_ARM_ARCHEXT_ARCHv7 0x0a +#define PT_ARM_ARCHEXT_ARCHv6M 0x0b +#define PT_ARM_ARCHEXT_ARCHv6SM 0x0c +#define PT_ARM_ARCHEXT_ARCHv7EM 0x0d + +/* Table 5-6, ARM-specific dynamic array tags */ + +#define DT_ARM_RESERVED1 0x70000000 +#define DT_ARM_SYMTABSZ 0x70000001 +#define DT_ARM_PREEMPTMAP 0x70000002 +#define DT_ARM_RESERVED2 0x70000003 + +#endif /* __ARCH_ARM_INCLUDE_ELF_H */ diff --git a/nuttx/include/elf.h b/nuttx/include/elf.h index c3fb2732d2..caf0b1876d 100644 --- a/nuttx/include/elf.h +++ b/nuttx/include/elf.h @@ -65,7 +65,9 @@ #define ET_LOPROC 0xff00 /* Processor-specific */ #define ET_HIPROC 0xffff /* Processor-specific */ -/* Values for Elf32_Ehdr::e_machine */ +/* Values for Elf32_Ehdr::e_machine (most of this were not included in the + * original SCO document but have been gleaned from elsewhere). + */ #define EM_NONE 0 /* No machine */ #define EM_M32 1 /* AT&T WE 32100 */ @@ -81,6 +83,7 @@ #define EM_SPARC32PLUS 18 /* Sun's "v8plus" */ #define EM_PPC 20 /* PowerPC */ #define EM_PPC64 21 /* PowerPC64 */ +#define EM_ARM 40 /* ARM */ #define EM_SH 42 /* SuperH */ #define EM_SPARCV9 43 /* SPARC v9 64-bit */ #define EM_IA_64 50 /* HP/Intel IA-64 */ From 7f2512627e20e6b07ee2cd1f08e8ba9f07f3cb42 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 26 Oct 2012 02:42:39 +0000 Subject: [PATCH 032/206] Rename elf.h to elf32.h; Additional ELF loader changes git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5263 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/README.txt | 8 ++ apps/examples/elf/elf_main.c | 2 +- apps/examples/nxflat/nxflat_main.c | 2 +- nuttx/ChangeLog | 2 + nuttx/arch/arm/include/elf.h | 2 +- nuttx/arch/sim/src/up_elf.c | 2 +- nuttx/arch/x86/src/common/up_elf.c | 2 +- nuttx/binfmt/elf.c | 2 +- nuttx/binfmt/libelf/gnu-elf.ld | 144 ++++++++------------------- nuttx/binfmt/libelf/libelf.h | 2 +- nuttx/binfmt/libelf/libelf_bind.c | 2 +- nuttx/binfmt/libelf/libelf_init.c | 2 +- nuttx/binfmt/libelf/libelf_load.c | 2 +- nuttx/binfmt/libelf/libelf_read.c | 2 +- nuttx/binfmt/libelf/libelf_symbols.c | 2 +- nuttx/include/{elf.h => elf32.h} | 8 +- nuttx/include/nuttx/binfmt/elf.h | 2 +- 17 files changed, 69 insertions(+), 119 deletions(-) rename nuttx/include/{elf.h => elf32.h} (99%) diff --git a/apps/examples/README.txt b/apps/examples/README.txt index fa97bd64e3..95d49a3fb7 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -344,6 +344,14 @@ examples/elf If you really want to do this, you can create a NuttX x86 buildroot toolchain and use that be build the ELF executables for the ROMFS file system. + 5. Linker scripts. You might also want to use a linker scripts to combine + sections better. An example linker script is at nuttx/binfmt/libelf/gnu-elf.ld. + That example might have to be tuned for your particular linker output to + position additional sections correctly. The GNU LD LDELFFLAGS then might + be: + + LDELFFLAGS = -r -e main -T$(TOPDIR)/binfmt/libelf/gnu-elf.ld + examples/ftpc ^^^^^^^^^^^^^ diff --git a/apps/examples/elf/elf_main.c b/apps/examples/elf/elf_main.c index 5699dd2849..3a6eae9d9e 100644 --- a/apps/examples/elf/elf_main.c +++ b/apps/examples/elf/elf_main.c @@ -174,7 +174,7 @@ int elf_main(int argc, char *argv[]) /* Create a ROM disk for the ROMFS filesystem */ message("Registering romdisk at /dev/ram%d\n", CONFIG_EXAMPLES_ELF_DEVMINOR); - ret = romdisk_register(CONFIG_EXAMPLES_ELF_DEVMINOR, romfs_img, + ret = romdisk_register(CONFIG_EXAMPLES_ELF_DEVMINOR, (FAR uint8_t *)romfs_img, NSECTORS(romfs_img_len), SECTORSIZE); if (ret < 0) { diff --git a/apps/examples/nxflat/nxflat_main.c b/apps/examples/nxflat/nxflat_main.c index 2c0030c608..638e960a00 100644 --- a/apps/examples/nxflat/nxflat_main.c +++ b/apps/examples/nxflat/nxflat_main.c @@ -167,7 +167,7 @@ int nxflat_main(int argc, char *argv[]) /* Create a ROM disk for the ROMFS filesystem */ message("Registering romdisk\n"); - ret = romdisk_register(0, romfs_img, NSECTORS(romfs_img_len), SECTORSIZE); + ret = romdisk_register(0, (FAR uint8_t *)romfs_img, NSECTORS(romfs_img_len), SECTORSIZE); if (ret < 0) { err("ERROR: romdisk_register failed: %d\n", ret); diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 2006fcc216..f1f048a353 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3515,4 +3515,6 @@ include/nuttx/binfmt/. * arch/sim/src/up_elf.c and arch/x86/src/common/up_elf.c: Add for ELF modules. + * arch/arm/include/elf.h: Added ARM ELF header file. + * include/elf32.h: Renamed elf.h to elf32.h. diff --git a/nuttx/arch/arm/include/elf.h b/nuttx/arch/arm/include/elf.h index d853853801..21b2c1c2c1 100644 --- a/nuttx/arch/arm/include/elf.h +++ b/nuttx/arch/arm/include/elf.h @@ -50,7 +50,7 @@ * e_ident[EI_DATA] = ELFDATA2LSB (little endian) or ELFDATA2MSB (big endian) */ -#if 0 /* Defined in include/elf.h */ +#if 0 /* Defined in include/elf32.h */ #define EM_ARM 40 #endif diff --git a/nuttx/arch/sim/src/up_elf.c b/nuttx/arch/sim/src/up_elf.c index ca3b642dcd..26a8971a72 100644 --- a/nuttx/arch/sim/src/up_elf.c +++ b/nuttx/arch/sim/src/up_elf.c @@ -40,7 +40,7 @@ #include #include -#include +#include #include #include diff --git a/nuttx/arch/x86/src/common/up_elf.c b/nuttx/arch/x86/src/common/up_elf.c index be166b480c..da3f7b9935 100644 --- a/nuttx/arch/x86/src/common/up_elf.c +++ b/nuttx/arch/x86/src/common/up_elf.c @@ -40,7 +40,7 @@ #include #include -#include +#include #include #include diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c index d9c3d0b9c9..9a0ac1873f 100644 --- a/nuttx/binfmt/elf.c +++ b/nuttx/binfmt/elf.c @@ -42,7 +42,7 @@ #include #include #include -#include +#include #include #include diff --git a/nuttx/binfmt/libelf/gnu-elf.ld b/nuttx/binfmt/libelf/gnu-elf.ld index 703f369812..bdf82836b3 100644 --- a/nuttx/binfmt/libelf/gnu-elf.ld +++ b/nuttx/binfmt/libelf/gnu-elf.ld @@ -1,7 +1,7 @@ /**************************************************************************** - * examples/elf/gnu-elf-gotoff.ld + * examples/elf/gnu-elf.ld * - * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -33,44 +33,11 @@ * ****************************************************************************/ -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 = . ; - + _stext = . ; *(.text) *(.text.*) *(.gnu.warning) @@ -79,99 +46,72 @@ SECTIONS *(.glue_7t) *(.jcr) - /* C++ support: The .init and .fini sections contain XFLAT- - * specific logic to manage static constructors and destructors. + /* C++ support: The .init and .fini sections contain 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 : + .rodata : { - /* In this model, .rodata is access using PC-relative addressing - * and, hence, must also reside in the .text section. - */ - - __data_start = . ; + _srodata = . ; *(.rodata) *(.rodata1) *(.rodata.*) *(.gnu.linkonce.r*) + _erodata = . ; + } + .data : + { + _sdata = . ; *(.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 + } + + /* 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. + */ + + .ctors : + { + _sctros = . ; + *(.ctors) + _edtors = . ; + } + + .ctors : + { + _sdtors = . ; + *(.dtors) + _edtors = . ; + } .bss : { - __bss_start = _edata ; - *(.dynsbss) - *(.sbss) - *(.sbss.*) - *(.scommon) - *(.dynbss) + _sbss = . ; *(.bss) *(.bss.*) - *(.bss*) + *(.sbss) + *(.sbss.*) *(.gnu.linkonce.b*) *(COMMON) - end = ALIGN( 0x10 ) ; - _end = ALIGN( 0x10 ) ; - } > DSPACE + _ebss = . ; + } - .got 0 : { *(.got.plt) *(.got) } - .junk 0 : { *(.rel*) *(.rela*) } /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } .stabstr 0 : { *(.stabstr) } .stab.excl 0 : { *(.stab.excl) } diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h index 37a2ad872d..0fb1362dcd 100644 --- a/nuttx/binfmt/libelf/libelf.h +++ b/nuttx/binfmt/libelf/libelf.h @@ -43,7 +43,7 @@ #include #include -#include +#include #include diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c index e398521cca..f41b5a0b6f 100644 --- a/nuttx/binfmt/libelf/libelf_bind.c +++ b/nuttx/binfmt/libelf/libelf_bind.c @@ -41,7 +41,7 @@ #include #include -#include +#include #include #include #include diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c index a3a320b165..f2744eae76 100644 --- a/nuttx/binfmt/libelf/libelf_init.c +++ b/nuttx/binfmt/libelf/libelf_init.c @@ -43,7 +43,7 @@ #include #include #include -#include +#include #include #include diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 4a1a561c3c..9378661e3c 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -45,7 +45,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c index 0b01cf096e..da41212f23 100644 --- a/nuttx/binfmt/libelf/libelf_read.c +++ b/nuttx/binfmt/libelf/libelf_read.c @@ -43,7 +43,7 @@ #include #include #include -#include +#include #include #include diff --git a/nuttx/binfmt/libelf/libelf_symbols.c b/nuttx/binfmt/libelf/libelf_symbols.c index 05f827963a..123f9f77f5 100644 --- a/nuttx/binfmt/libelf/libelf_symbols.c +++ b/nuttx/binfmt/libelf/libelf_symbols.c @@ -41,7 +41,7 @@ #include #include -#include +#include #include #include diff --git a/nuttx/include/elf.h b/nuttx/include/elf32.h similarity index 99% rename from nuttx/include/elf.h rename to nuttx/include/elf32.h index caf0b1876d..e16ae0091a 100644 --- a/nuttx/include/elf.h +++ b/nuttx/include/elf32.h @@ -1,5 +1,5 @@ /**************************************************************************** - * include/elf.h + * include/elf32.h * * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -36,8 +36,8 @@ * ****************************************************************************/ -#ifndef __INCLUDE_ELF_H -#define __INCLUDE_ELF_H +#ifndef __INCLUDE_ELF32_H +#define __INCLUDE_ELF32_H /**************************************************************************** * Included Files @@ -349,4 +349,4 @@ typedef struct //extern Elf32_Dyn _DYNAMIC[] ; -#endif /* __INCLUDE_ELF_H */ +#endif /* __INCLUDE_ELF32_H */ diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h index 6b13c10873..aa04adaf2d 100644 --- a/nuttx/include/nuttx/binfmt/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -45,7 +45,7 @@ #include #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions From 7bc6a69f461c9bed82608220960682f3090f742c Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 26 Oct 2012 19:53:20 +0000 Subject: [PATCH 033/206] ARM and ARMv7-M ELF support; STM32F4Discovery ELF loader test configuration git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5264 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/README.txt | 4 +- apps/examples/elf/tests/longjmp/longjmp.c | 4 + apps/examples/elf/tests/signal/signal.c | 12 +- apps/examples/nxflat/tests/longjmp/longjmp.c | 4 + apps/examples/nxflat/tests/signal/signal.c | 13 +- nuttx/ChangeLog | 6 +- nuttx/TODO | 7 +- nuttx/arch/arm/src/arm/up_elf.c | 256 ++++ nuttx/arch/arm/src/armv7-m/up_elf.c | 448 ++++++ nuttx/arch/arm/src/c5471/Make.defs | 4 + nuttx/arch/arm/src/calypso/Make.defs | 4 + nuttx/arch/arm/src/dm320/Make.defs | 4 + nuttx/arch/arm/src/imx/Make.defs | 4 + nuttx/arch/arm/src/kinetis/Make.defs | 4 + nuttx/arch/arm/src/lm3s/Make.defs | 4 + nuttx/arch/arm/src/lpc17xx/Make.defs | 4 + nuttx/arch/arm/src/lpc214x/Make.defs | 4 + nuttx/arch/arm/src/lpc2378/Make.defs | 4 + nuttx/arch/arm/src/lpc31xx/Make.defs | 4 + nuttx/arch/arm/src/lpc43xx/Make.defs | 4 + nuttx/arch/arm/src/sam3u/Make.defs | 4 + nuttx/arch/arm/src/stm32/Kconfig | 2 +- nuttx/arch/arm/src/stm32/Make.defs | 4 + nuttx/arch/arm/src/str71x/Make.defs | 4 + nuttx/arch/sim/src/up_elf.c | 2 - nuttx/arch/x86/src/common/up_elf.c | 2 - nuttx/binfmt/libelf/libelf_init.c | 57 +- nuttx/binfmt/libelf/libelf_load.c | 52 - nuttx/configs/stm32f4discovery/README.txt | 84 +- nuttx/configs/stm32f4discovery/elf/Make.defs | 191 +++ nuttx/configs/stm32f4discovery/elf/defconfig | 830 ++++++++++ nuttx/configs/stm32f4discovery/elf/setenv.sh | 79 + .../configs/stm32f4discovery/ostest/appconfig | 39 - .../configs/stm32f4discovery/ostest/defconfig | 1340 +++++++++-------- .../stm32f4discovery/scripts/gnu-elf.ld | 127 ++ nuttx/fs/fs_stat.c | 7 +- 36 files changed, 2851 insertions(+), 771 deletions(-) create mode 100644 nuttx/arch/arm/src/arm/up_elf.c create mode 100644 nuttx/arch/arm/src/armv7-m/up_elf.c create mode 100644 nuttx/configs/stm32f4discovery/elf/Make.defs create mode 100644 nuttx/configs/stm32f4discovery/elf/defconfig create mode 100755 nuttx/configs/stm32f4discovery/elf/setenv.sh delete mode 100644 nuttx/configs/stm32f4discovery/ostest/appconfig create mode 100644 nuttx/configs/stm32f4discovery/scripts/gnu-elf.ld diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 95d49a3fb7..bfb92b6b79 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -333,8 +333,8 @@ examples/elf include the path to the genromfs executable. 3. ELF size: The ELF files in this example are, be default, quite large - because they include a lot of "build garbage". You can greately reduce the - size of the ELF binaries are using the objcopy --strip-unneeded command to + because they include a lot of "build garbage". You can greatly reduce the + size of the ELF binaries are using the 'objcopy --strip-unneeded' command to remove un-necessary information from the ELF files. 4. Simulator. You cannot use this example with the the NuttX simulator on diff --git a/apps/examples/elf/tests/longjmp/longjmp.c b/apps/examples/elf/tests/longjmp/longjmp.c index 2993c24dc6..74d5594c4c 100644 --- a/apps/examples/elf/tests/longjmp/longjmp.c +++ b/apps/examples/elf/tests/longjmp/longjmp.c @@ -74,6 +74,10 @@ static int leaf(int *some_arg) printf("leaf: Calling longjmp() with %d\n", some_local_variable); longjmp(env, some_local_variable); + + /* We should not get here */ + + return -ERROR; } static int function(int some_arg) diff --git a/apps/examples/elf/tests/signal/signal.c b/apps/examples/elf/tests/signal/signal.c index 80d8c18ade..0d2e9e6cc2 100644 --- a/apps/examples/elf/tests/signal/signal.c +++ b/apps/examples/elf/tests/signal/signal.c @@ -93,7 +93,7 @@ void sigusr1_sighandler(int signo) void sigusr2_sigaction(int signo, siginfo_t *siginfo, void *arg) { printf("sigusr2_sigaction: Received SIGUSR2, signo=%d siginfo=%p arg=%p\n", - signo, siginfo, arg); + signo, siginfo, arg); #ifdef HAVE_SIGQUEUE if (siginfo) @@ -163,7 +163,7 @@ int main(int argc, char **argv) if (old_sigusr1_sighandler == SIG_ERR) { fprintf(stderr, "Failed to install SIGUSR1 handler, errno=%d\n", - errno); + errno); exit(1); } @@ -182,7 +182,7 @@ int main(int argc, char **argv) if (status != 0) { fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n", - errno); + errno); exit(2); } @@ -263,7 +263,7 @@ int main(int argc, char **argv) if (old_sigusr2_sighandler == SIG_ERR) { fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n", - errno); + errno); exit(7); } @@ -275,8 +275,8 @@ int main(int argc, char **argv) if ((void*)old_sigusr2_sighandler != (void*)sigusr2_sigaction) { fprintf(stderr, - "Old SIGUSR2 signhanlder (%p) is not sigusr2_sigation (%p)\n", - old_sigusr2_sighandler, sigusr2_sigaction); + "Old SIGUSR2 signhanlder (%p) is not sigusr2_sigation (%p)\n", + old_sigusr2_sighandler, sigusr2_sigaction); exit(8); } diff --git a/apps/examples/nxflat/tests/longjmp/longjmp.c b/apps/examples/nxflat/tests/longjmp/longjmp.c index 85571261c7..f430965146 100644 --- a/apps/examples/nxflat/tests/longjmp/longjmp.c +++ b/apps/examples/nxflat/tests/longjmp/longjmp.c @@ -74,6 +74,10 @@ static int leaf(int *some_arg) printf("leaf: Calling longjmp() with %d\n", some_local_variable); longjmp(env, some_local_variable); + + /* We should not get here */ + + return -ERROR; } static int function(int some_arg) diff --git a/apps/examples/nxflat/tests/signal/signal.c b/apps/examples/nxflat/tests/signal/signal.c index 95415fc871..2df5baaa24 100644 --- a/apps/examples/nxflat/tests/signal/signal.c +++ b/apps/examples/nxflat/tests/signal/signal.c @@ -38,6 +38,7 @@ ****************************************************************************/ #include + #include #include #include @@ -93,7 +94,7 @@ void sigusr1_sighandler(int signo) void sigusr2_sigaction(int signo, siginfo_t *siginfo, void *arg) { printf("sigusr2_sigaction: Received SIGUSR2, signo=%d siginfo=%p arg=%p\n", - signo, siginfo, arg); + signo, siginfo, arg); #ifdef HAVE_SIGQUEUE if (siginfo) @@ -163,7 +164,7 @@ int main(int argc, char **argv) if (old_sigusr1_sighandler == SIG_ERR) { fprintf(stderr, "Failed to install SIGUSR1 handler, errno=%d\n", - errno); + errno); exit(1); } @@ -182,7 +183,7 @@ int main(int argc, char **argv) if (status != 0) { fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n", - errno); + errno); exit(2); } @@ -263,7 +264,7 @@ int main(int argc, char **argv) if (old_sigusr2_sighandler == SIG_ERR) { fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n", - errno); + errno); exit(7); } @@ -275,8 +276,8 @@ int main(int argc, char **argv) if ((void*)old_sigusr2_sighandler != (void*)sigusr2_sigaction) { fprintf(stderr, - "Old SIGUSR2 signhanlder (%p) is not sigusr2_sigation (%p)\n", - old_sigusr2_sighandler, sigusr2_sigaction); + "Old SIGUSR2 signhanlder (%p) is not sigusr2_sigation (%p)\n", + old_sigusr2_sighandler, sigusr2_sigaction); exit(8); } diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f1f048a353..7c4a5a8cd8 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3517,4 +3517,8 @@ for ELF modules. * arch/arm/include/elf.h: Added ARM ELF header file. * include/elf32.h: Renamed elf.h to elf32.h. - + * configs/stm32f4discovery/ostest: Converted to use the new + Kconfig-based configuration system. + * configs/stm32f4discovery/elf and configs/stm32f4discovery/scripts/gnu-elf.ld + Add a configuration for testing the ARM ELF loader. + * binfmt/libelf: Can't use fstat(). NuttX does not yet support it. Damn! diff --git a/nuttx/TODO b/nuttx/TODO index 7b4daf2c16..c87137f642 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -14,7 +14,7 @@ nuttx/ (2) C++ Support (6) Binary loaders (binfmt/) (17) Network (net/, drivers/net) - (3) USB (drivers/usbdev, drivers/usbhost) + (4) USB (drivers/usbdev, drivers/usbhost) (11) Libraries (lib/) (9) File system/Generic drivers (fs/, drivers/) (5) Graphics subystem (graphics/) @@ -629,6 +629,11 @@ o USB (drivers/usbdev, drivers/usbhost) CDC/ACM serial driver might need the line coding data (that data is not used currenly, but it might be). + Title: USB HUB SUPPORT + Description: Add support for USB hubs + Status: Open + Priority: Low/Unknown. This is a feature enhancement. + o Libraries (lib/) ^^^^^^^^^^^^^^^^ diff --git a/nuttx/arch/arm/src/arm/up_elf.c b/nuttx/arch/arm/src/arm/up_elf.c new file mode 100644 index 0000000000..b78da02c19 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_elf.c @@ -0,0 +1,256 @@ +/**************************************************************************** + * arch/arm/src/arm/up_elf.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: arch_checkarch + * + * Description: + * Given the ELF header in 'hdr', verify that the ELF file is appropriate + * for the current, configured architecture. Every architecture that uses + * the ELF loader must provide this function. + * + * Input Parameters: + * hdr - The ELF header read from the ELF file. + * + * Returned Value: + * True if the architecture supports this ELF file. + * + ****************************************************************************/ + +bool arch_checkarch(FAR const Elf32_Ehdr *ehdr) +{ + /* Make sure it's an ARM executable */ + + if (ehdr->e_machine != EM_ARM) + { + bdbg("Not for ARM: e_machine=%04x\n", ehdr->e_machine); + return -ENOEXEC; + } + + /* Make sure that 32-bit objects are supported */ + + if (ehdr->e_ident[EI_CLASS] != ELFCLASS32) + { + bdbg("Need 32-bit objects: e_ident[EI_CLASS]=%02x\n", ehdr->e_ident[EI_CLASS]); + return -ENOEXEC; + } + + /* Verify endian-ness */ + +#ifdef CONFIG_ENDIAN_BIG + if (ehdr->e_ident[EI_DATA] != ELFDATA2MSB) +#else + if (ehdr->e_ident[EI_DATA] != ELFDATA2LSB) +#endif + { + bdbg("Wrong endian-ness: e_ident[EI_DATA]=%02x\n", ehdr->e_ident[EI_DATA]); + return -ENOEXEC; + } + + /* Make sure the entry point address is properly aligned */ + + if ((ehdr->e_entry & 3) != 0) + { + bdbg("Entry point is not properly aligned: %08x\n", ehdr->e_entry); + return -ENOEXEC + } + + /* TODO: Check ABI here. */ + return OK; +} + +/**************************************************************************** + * Name: arch_relocate and arch_relocateadd + * + * Description: + * Perform on architecture-specific ELF relocation. Every architecture + * that uses the ELF loader must provide this function. + * + * Input Parameters: + * rel - The relocation type + * sym - The ELF symbol structure containing the fully resolved value. + * addr - The address that requires the relocation. + * + * Returned Value: + * Zero (OK) if the relocation was successful. Otherwise, a negated errno + * value indicating the cause of the relocation failure. + * + ****************************************************************************/ + +int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, + uintptr_t addr) +{ + int32_t offset; + + switch (ELF32_R_TYPE(rel->r_info)) + { + case R_ARM_NONE: + { + /* No relocation */ + } + break; + + case R_ARM_PC24: + case R_ARM_CALL: + case R_ARM_JUMP24: + { + bvdbg("Performing PC24 [%d] link at addr %08lx [%08lx] to sym '%s' st_value=%08lx\n", + ELF32_R_TYPE(rel->r_info), (long)addr, (long)(*(uint32_t*)addr), + sym, (long)sym->st_value); + + offset = (*(uint32_t*)addr & 0x00ffffff) << 2; + if (offset & 0x02000000) + { + offset -= 0x04000000; + } + + offset += sym->st_value - addr; + if (offset & 3 || offset <= (int32_t) 0xfe000000 || offset >= (int32_t) 0x02000000) + { + bdbg(" ERROR: PC24 [%d] relocation out of range, offset=%08lx\n", + ELF32_R_TYPE(rel->r_info), offset); + + return -EINVAL; + } + + offset >>= 2; + + *(uint32_t*)addr &= 0xff000000; + *(uint32_t*)addr |= offset & 0x00ffffff; + } + break; + + case R_ARM_ABS32: + { + bvdbg("Performing ABS32 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", + (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value); + + *(uint32_t*)addr += sym->st_value; + } + break; + + case R_ARM_V4BX: + { + bvdbg("Performing V4BX link at addr=%08lx [%08lx]\n", + (long)addr, (long)(*(uint32_t*)addr)); + + /* Preserve only Rm and the condition code */ + + *(uint32_t*)addr &= 0xf000000f; + + /* Change instruction to 'mov pc, Rm' */ + + *(uint32_t*)addr |= 0x01a0f000; + } + break; + + case R_ARM_PREL31: + { + bvdbg("Performing PREL31 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", + (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value); + + offset = *(uint32_t*)addr + sym->st_value - addr; + *(uint32_t*)addr = offset & 0x7fffffff; + } + break; + + case R_ARM_MOVW_ABS_NC: + case R_ARM_MOVT_ABS: + { + bvdbg("Performing MOVx_ABS [%d] link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", + ELF32_R_TYPE(rel->r_info), (long)addr, (long)(*(uint32_t*)addr), + sym, (long)sym->st_value); + + offset = *(uint32_t*)addr; + offset = ((offset & 0xf0000) >> 4) | (offset & 0xfff); + offset = (offset ^ 0x8000) - 0x8000; + + offset += sym->st_value; + if (ELF32_R_TYPE(rel->r_info) == R_ARM_MOVT_ABS) + { + offset >>= 16; + } + + *(uint32_t*)addr &= 0xfff0f000; + *(uint32_t*)addr |= ((offset & 0xf000) << 4) | (offset & 0x0fff); + } + break; + + default: + bdbg("Unsupported relocation: %d\n", ELF32_R_TYPE(rel->r_info)); + return -EINVAL; + } + + return OK; +} + +int arch_relocateadd(FAR const Elf32_Rela *rel, FAR const Elf32_Sym *sym, + uintptr_t addr) +{ + bdbg("RELA relocation not supported\n"); + return -ENOSYS; +} + diff --git a/nuttx/arch/arm/src/armv7-m/up_elf.c b/nuttx/arch/arm/src/armv7-m/up_elf.c new file mode 100644 index 0000000000..5f77470fa1 --- /dev/null +++ b/nuttx/arch/arm/src/armv7-m/up_elf.c @@ -0,0 +1,448 @@ +/**************************************************************************** + * arch/arm/src/armv7-m/up_elf.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: arch_checkarch + * + * Description: + * Given the ELF header in 'hdr', verify that the ELF file is appropriate + * for the current, configured architecture. Every architecture that uses + * the ELF loader must provide this function. + * + * Input Parameters: + * hdr - The ELF header read from the ELF file. + * + * Returned Value: + * True if the architecture supports this ELF file. + * + ****************************************************************************/ + +bool arch_checkarch(FAR const Elf32_Ehdr *ehdr) +{ + /* Make sure it's an ARM executable */ + + if (ehdr->e_machine != EM_ARM) + { + bdbg("Not for ARM: e_machine=%04x\n", ehdr->e_machine); + return -ENOEXEC; + } + + /* Make sure that 32-bit objects are supported */ + + if (ehdr->e_ident[EI_CLASS] != ELFCLASS32) + { + bdbg("Need 32-bit objects: e_ident[EI_CLASS]=%02x\n", ehdr->e_ident[EI_CLASS]); + return -ENOEXEC; + } + + /* Verify endian-ness */ + +#ifdef CONFIG_ENDIAN_BIG + if (ehdr->e_ident[EI_DATA] != ELFDATA2MSB) +#else + if (ehdr->e_ident[EI_DATA] != ELFDATA2LSB) +#endif + { + bdbg("Wrong endian-ness: e_ident[EI_DATA]=%02x\n", ehdr->e_ident[EI_DATA]); + return -ENOEXEC; + } + + /* TODO: Check ABI here. */ + return OK; +} + +/**************************************************************************** + * Name: arch_relocate and arch_relocateadd + * + * Description: + * Perform on architecture-specific ELF relocation. Every architecture + * that uses the ELF loader must provide this function. + * + * Input Parameters: + * rel - The relocation type + * sym - The ELF symbol structure containing the fully resolved value. + * addr - The address that requires the relocation. + * + * Returned Value: + * Zero (OK) if the relocation was successful. Otherwise, a negated errno + * value indicating the cause of the relocation failure. + * + ****************************************************************************/ + +int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, + uintptr_t addr) +{ + int32_t offset; + uint32_t upper_insn; + uint32_t lower_insn; + + switch (ELF32_R_TYPE(rel->r_info)) + { + case R_ARM_NONE: + { + /* No relocation */ + } + break; + + case R_ARM_PC24: + case R_ARM_CALL: + case R_ARM_JUMP24: + { + bvdbg("Performing PC24 [%d] link at addr %08lx [%08lx] to sym '%s' st_value=%08lx\n", + ELF32_R_TYPE(rel->r_info), (long)addr, (long)(*(uint32_t*)addr), + sym, (long)sym->st_value); + + offset = (*(uint32_t*)addr & 0x00ffffff) << 2; + if (offset & 0x02000000) + { + offset -= 0x04000000; + } + + offset += sym->st_value - addr; + if (offset & 3 || offset <= (int32_t) 0xfe000000 || offset >= (int32_t) 0x02000000) + { + bdbg(" ERROR: PC24 [%d] relocation out of range, offset=%08lx\n", + ELF32_R_TYPE(rel->r_info), offset); + + return -EINVAL; + } + + offset >>= 2; + + *(uint32_t*)addr &= 0xff000000; + *(uint32_t*)addr |= offset & 0x00ffffff; + } + break; + + case R_ARM_ABS32: + { + bvdbg("Performing ABS32 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", + (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value); + + *(uint32_t*)addr += sym->st_value; + } + break; + + case R_ARM_THM_CALL: + case R_ARM_THM_JUMP24: + { + uint32_t S; + uint32_t J1; + uint32_t J2; + + /* Thumb BL and B.W instructions. Encoding: + * + * upper_insn: + * + * 1 1 1 1 1 1 + * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 + * +----------+---+-------------------------------+--------------+ + * |1 1 1 |OP1| OP2 | | 32-Bit Instructions + * +----------+---+--+-----+----------------------+--------------+ + * |1 1 1 | 1 0| S | imm10 | BL Instruction + * +----------+------+-----+-------------------------------------+ + * + * lower_insn: + * + * 1 1 1 1 1 1 + * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 + * +---+---------------------------------------------------------+ + * |OP | | 32-Bit Instructions + * +---+--+---+---+---+------------------------------------------+ + * |1 1 |J1 | 1 |J2 | imm11 | BL Instruction + * +------+---+---+---+------------------------------------------+ + * + * The branch target is encoded in these bits: + * + * S = upper_insn[10] + * imm10 = upper_insn[9:0] + * imm11 = lower_insn[10:0] + * J1 = lower_insn[13] + * J2 = lower_insn[11] + */ + + upper_insn = (uint32_t)(*(uint16_t*)addr); + lower_insn = (uint32_t)(*(uint16_t*)(addr + 2)); + + bvdbg("Performing JUMP24 [%d] link at addr=%08lx [%04x %04x] to sym=%p st_value=%08lx\n", + ELF32_R_TYPE(rel->r_info), (long)addr, (int)upper_insn, (int)lower_insn, + sym, (long)sym->st_value); + + /* Extract the 25-bit offset from the 32-bit instruction: + * + * offset[24] = S + * offset[23] = ~(J1 ^ S) + * offset[22 = ~(J2 ^ S)] + * offset[21:12] = imm10 + * offset[11:1] = imm11 + * offset[0] = 0 + */ + + S = (upper_insn >> 10) & 1; + J1 = (lower_insn >> 13) & 1; + J2 = (lower_insn >> 11) & 1; + + offset = (S << 24) | + ((~(J1 ^ S) & 1) << 23) | + ((~(J2 ^ S) & 1) << 22) | + ((upper_insn & 0x03ff) << 12) | + ((lower_insn & 0x07ff) << 1); + + /* Sign extend */ + + if (offset & 0x01000000) + { + offset -= 0x02000000; + } + + /* And perform the relocation */ + + bvdbg(" S=%d J1=%d J2=%d offset=%08lx branch target=%08lx\n", + S, J1, J2, (long)offset, offset + sym->st_value - addr); + + offset += sym->st_value - addr; + + /* Is this a function symbol? If so, then the branch target must be + * an odd Thumb address + */ + + if (ELF32_ST_TYPE(sym->st_info) == STT_FUNC && (offset & 1) == 0) + { + bdbg(" ERROR: JUMP24 [%d] requires odd offset, offset=%08lx\n", + ELF32_R_TYPE(rel->r_info), offset); + + return -EINVAL; + } + + /* Check the range of the offset */ + + if (offset <= (int32_t)0xff000000 || offset >= (int32_t)0x01000000) + { + bdbg(" ERROR: JUMP24 [%d] relocation out of range, offset=%08lx\n", + ELF32_R_TYPE(rel->r_info), offset); + + return -EINVAL; + } + + /* Now, reconstruct the 32-bit instruction using the new, relocated + * branch target. + */ + + S = (offset >> 24) & 1; + J1 = S ^ (~(offset >> 23) & 1); + J2 = S ^ (~(offset >> 22) & 1); + + upper_insn = ((upper_insn & 0xf800) | (S << 10) | ((offset >> 12) & 0x03ff)); + *(uint16_t*)addr = (uint16_t)upper_insn; + + lower_insn = ((lower_insn & 0xd000) | (J1 << 13) | (J2 << 11) | ((offset >> 1) & 0x07ff)); + *(uint16_t*)(addr + 2) = (uint16_t)lower_insn; + + bvdbg(" S=%d J1=%d J2=%d insn [%04x %04x]\n", + S, J1, J2, (int)upper_insn, (int)lower_insn); + } + break; + + case R_ARM_V4BX: + { + bvdbg("Performing V4BX link at addr=%08lx [%08lx]\n", + (long)addr, (long)(*(uint32_t*)addr)); + + /* Preserve only Rm and the condition code */ + + *(uint32_t*)addr &= 0xf000000f; + + /* Change instruction to 'mov pc, Rm' */ + + *(uint32_t*)addr |= 0x01a0f000; + } + break; + + case R_ARM_PREL31: + { + bvdbg("Performing PREL31 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", + (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value); + + offset = *(uint32_t*)addr + sym->st_value - addr; + *(uint32_t*)addr = offset & 0x7fffffff; + } + break; + + case R_ARM_MOVW_ABS_NC: + case R_ARM_MOVT_ABS: + { + bvdbg("Performing MOVx_ABS [%d] link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", + ELF32_R_TYPE(rel->r_info), (long)addr, (long)(*(uint32_t*)addr), + sym, (long)sym->st_value); + + offset = *(uint32_t*)addr; + offset = ((offset & 0xf0000) >> 4) | (offset & 0xfff); + offset = (offset ^ 0x8000) - 0x8000; + + offset += sym->st_value; + if (ELF32_R_TYPE(rel->r_info) == R_ARM_MOVT_ABS) + { + offset >>= 16; + } + + *(uint32_t*)addr &= 0xfff0f000; + *(uint32_t*)addr |= ((offset & 0xf000) << 4) | (offset & 0x0fff); + } + break; + + case R_ARM_THM_MOVW_ABS_NC: + case R_ARM_THM_MOVT_ABS: + { + /* Thumb BL and B.W instructions. Encoding: + * + * upper_insn: + * + * 1 1 1 1 1 1 + * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 + * +----------+---+-------------------------------+--------------+ + * |1 1 1 |OP1| OP2 | | 32-Bit Instructions + * +----------+---+--+-----+----------------------+--------------+ + * |1 1 1 | 1 0| i | 1 0 1 1 0 0 | imm4 | MOVT Instruction + * +----------+------+-----+----------------------+--------------+ + * + * lower_insn: + * + * 1 1 1 1 1 1 + * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 + * +---+---------------------------------------------------------+ + * |OP | | 32-Bit Instructions + * +---+--+-------+--------------+-------------------------------+ + * |0 |1 | imm3 | Rd | imm8 | MOVT Instruction + * +---+--+-------+--------------+-------------------------------+ + * + * The 16-bit immediate value is encoded in these bits: + * + * i = imm16[11] = upper_insn[10] + * imm4 = imm16[12:15] = upper_insn[3:0] + * imm3 = imm16[9:11] = lower_insn[14:12] + * imm8 = imm16[0:8] = lower_insn[7:0] + */ + + upper_insn = (uint32_t)(*(uint16_t*)addr); + lower_insn = (uint32_t)(*(uint16_t*)(addr + 2)); + + bvdbg("Performing MOVx [%d] link at addr=%08lx [%04x %04x] to sym=%p st_value=%08lx\n", + ELF32_R_TYPE(rel->r_info), (long)addr, (int)upper_insn, (int)lower_insn, + sym, (long)sym->st_value); + + /* Extract the 16-bit offset from the 32-bit instruction */ + + offset = ((upper_insn & 0x000f) << 12) | + ((upper_insn & 0x0400) << 1) | + ((lower_insn & 0x7000) >> 4) | + (lower_insn & 0x00ff); + + /* Sign extend */ + + offset = (offset ^ 0x8000) - 0x8000; + + /* And perform the relocation */ + + bvdbg(" S=%d J1=%d J2=%d offset=%08lx branch target=%08lx\n", + S, J1, J2, (long)offset, offset + sym->st_value); + + offset += sym->st_value; + + /* Update the immediate value in the instruction. For MOVW we want the bottom + * 16-bits; for MOVT we want the top 16-bits. + */ + + if (ELF32_R_TYPE(rel->r_info) == R_ARM_THM_MOVT_ABS) + { + offset >>= 16; + } + + upper_insn = ((upper_insn & 0xfbf0) | ((offset & 0xf000) >> 12) | ((offset & 0x0800) >> 1)); + *(uint16_t*)addr = (uint16_t)upper_insn; + + lower_insn = ((lower_insn & 0x8f00) | ((offset & 0x0700) << 4) | (offset & 0x00ff)); + *(uint16_t*)(addr + 2) = (uint16_t)lower_insn; + + bvdbg(" insn [%04x %04x]\n", + (int)upper_insn, (int)lower_insn); + } + break; + + default: + bdbg("Unsupported relocation: %d\n", ELF32_R_TYPE(rel->r_info)); + return -EINVAL; + } + + return OK; +} + +int arch_relocateadd(FAR const Elf32_Rela *rel, FAR const Elf32_Sym *sym, + uintptr_t addr) +{ + bdbg("RELA relocation not supported\n"); + return -ENOSYS; +} + diff --git a/nuttx/arch/arm/src/c5471/Make.defs b/nuttx/arch/arm/src/c5471/Make.defs index d1c2cf0ac7..2bc396fd36 100644 --- a/nuttx/arch/arm/src/c5471/Make.defs +++ b/nuttx/arch/arm/src/c5471/Make.defs @@ -44,6 +44,10 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ up_sigdeliver.c up_syscall.c up_unblocktask.c \ up_undefinedinsn.c up_usestack.c +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + CHIP_ASRCS = c5471_lowputc.S c5471_vectors.S CHIP_CSRCS = c5471_irq.c c5471_serial.c c5471_timerisr.c c5471_watchdog.c \ c5471_ethernet.c diff --git a/nuttx/arch/arm/src/calypso/Make.defs b/nuttx/arch/arm/src/calypso/Make.defs index 1552f17d14..db37ef02ba 100644 --- a/nuttx/arch/arm/src/calypso/Make.defs +++ b/nuttx/arch/arm/src/calypso/Make.defs @@ -48,6 +48,10 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ up_sigdeliver.c up_syscall.c up_unblocktask.c \ up_undefinedinsn.c up_usestack.c calypso_power.c +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + CHIP_ASRCS = calypso_lowputc.S CHIP_CSRCS = calypso_irq.c calypso_timer.c calypso_heap.c \ calypso_serial.c calypso_spi.c clock.c calypso_uwire.c diff --git a/nuttx/arch/arm/src/dm320/Make.defs b/nuttx/arch/arm/src/dm320/Make.defs index 9571966721..9087708ef5 100644 --- a/nuttx/arch/arm/src/dm320/Make.defs +++ b/nuttx/arch/arm/src/dm320/Make.defs @@ -45,6 +45,10 @@ CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \ up_sigdeliver.c up_syscall.c up_unblocktask.c \ up_undefinedinsn.c up_usestack.c +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + CHIP_ASRCS = dm320_lowputc.S dm320_restart.S CHIP_CSRCS = dm320_allocateheap.c dm320_boot.c dm320_decodeirq.c \ dm320_irq.c dm320_serial.c dm320_timerisr.c dm320_framebuffer.c diff --git a/nuttx/arch/arm/src/imx/Make.defs b/nuttx/arch/arm/src/imx/Make.defs index 3b2e6ad77c..a1c2e72e6b 100644 --- a/nuttx/arch/arm/src/imx/Make.defs +++ b/nuttx/arch/arm/src/imx/Make.defs @@ -45,6 +45,10 @@ CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \ up_sigdeliver.c up_syscall.c up_unblocktask.c \ up_undefinedinsn.c up_usestack.c +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + CHIP_ASRCS = imx_lowputc.S CHIP_CSRCS = imx_boot.c imx_gpio.c imx_allocateheap.c imx_irq.c \ imx_serial.c imx_timerisr.c imx_decodeirq.c imx_spi.c diff --git a/nuttx/arch/arm/src/kinetis/Make.defs b/nuttx/arch/arm/src/kinetis/Make.defs index 710db4d01e..65bc7b465a 100644 --- a/nuttx/arch/arm/src/kinetis/Make.defs +++ b/nuttx/arch/arm/src/kinetis/Make.defs @@ -58,6 +58,10 @@ CMN_CSRCS += up_etherstub.c endif endif +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + # Required Kinetis files CHIP_ASRCS = diff --git a/nuttx/arch/arm/src/lm3s/Make.defs b/nuttx/arch/arm/src/lm3s/Make.defs index ea4eda5833..8d29180277 100644 --- a/nuttx/arch/arm/src/lm3s/Make.defs +++ b/nuttx/arch/arm/src/lm3s/Make.defs @@ -48,6 +48,10 @@ ifeq ($(CONFIG_ARCH_MEMCPY),y) CMN_ASRCS += up_memcpy.S endif +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + CHIP_ASRCS = CHIP_CSRCS = lm3s_start.c lm3s_syscontrol.c lm3s_irq.c \ lm3s_gpio.c lm3s_gpioirq.c lm3s_timerisr.c lm3s_lowputc.c \ diff --git a/nuttx/arch/arm/src/lpc17xx/Make.defs b/nuttx/arch/arm/src/lpc17xx/Make.defs index baf2a45098..c7ef4a1474 100644 --- a/nuttx/arch/arm/src/lpc17xx/Make.defs +++ b/nuttx/arch/arm/src/lpc17xx/Make.defs @@ -58,6 +58,10 @@ CMN_CSRCS += up_etherstub.c endif endif +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + # Required LPC17xx files CHIP_ASRCS = diff --git a/nuttx/arch/arm/src/lpc214x/Make.defs b/nuttx/arch/arm/src/lpc214x/Make.defs index 41dc0911c6..ae5ed15fba 100644 --- a/nuttx/arch/arm/src/lpc214x/Make.defs +++ b/nuttx/arch/arm/src/lpc214x/Make.defs @@ -47,6 +47,10 @@ ifneq ($(CONFIG_DISABLE_SIGNALS),y) CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c endif +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + CHIP_ASRCS = lpc214x_lowputc.S CHIP_CSRCS = lpc214x_decodeirq.c lpc214x_irq.c lpc214x_timerisr.c \ lpc214x_serial.c diff --git a/nuttx/arch/arm/src/lpc2378/Make.defs b/nuttx/arch/arm/src/lpc2378/Make.defs index 9126fa2a1a..4fe75d9244 100644 --- a/nuttx/arch/arm/src/lpc2378/Make.defs +++ b/nuttx/arch/arm/src/lpc2378/Make.defs @@ -52,6 +52,10 @@ ifneq ($(CONFIG_DISABLE_SIGNALS),y) CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c endif +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + CHIP_ASRCS = lpc23xx_lowputc.S CHIP_CSRCS = lpc23xx_pllsetup.c lpc23xx_decodeirq.c lpc23xx_irq.c lpc23xx_timerisr.c \ lpc23xx_serial.c lpc23xx_io.c diff --git a/nuttx/arch/arm/src/lpc31xx/Make.defs b/nuttx/arch/arm/src/lpc31xx/Make.defs index 83dadc8c01..db63563efe 100644 --- a/nuttx/arch/arm/src/lpc31xx/Make.defs +++ b/nuttx/arch/arm/src/lpc31xx/Make.defs @@ -50,6 +50,10 @@ ifeq ($(CONFIG_PAGING),y) CMN_CSRCS += up_pginitialize.c up_checkmapping.c up_allocpage.c up_va2pte.c endif +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + CGU_ASRCS = CGU_CSRCS = lpc31_bcrndx.c lpc31_clkdomain.c lpc31_clkexten.c \ lpc31_clkfreq.c lpc31_clkinit.c lpc31_defclk.c \ diff --git a/nuttx/arch/arm/src/lpc43xx/Make.defs b/nuttx/arch/arm/src/lpc43xx/Make.defs index 0444a68fdc..cd78ddd5bc 100644 --- a/nuttx/arch/arm/src/lpc43xx/Make.defs +++ b/nuttx/arch/arm/src/lpc43xx/Make.defs @@ -57,6 +57,10 @@ ifeq ($(CONFIG_DEBUG_STACK),y) CMN_CSRCS += up_checkstack.c endif +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + ifeq ($(CONFIG_ARCH_FPU),y) CMN_ASRCS += up_fpu.S endif diff --git a/nuttx/arch/arm/src/sam3u/Make.defs b/nuttx/arch/arm/src/sam3u/Make.defs index b93e5bff73..daa1291699 100644 --- a/nuttx/arch/arm/src/sam3u/Make.defs +++ b/nuttx/arch/arm/src/sam3u/Make.defs @@ -58,6 +58,10 @@ ifeq ($(CONFIG_NUTTX_KERNEL),y) CHIP_CSRCS += up_mpu.c endif +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + # Required SAM3U files CHIP_ASRCS = diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index c9482b6d65..5fd0ae7a26 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -108,7 +108,7 @@ config ARCH_CHIP_STM32F407VE config ARCH_CHIP_STM32F407VG bool "STM32F407VG" - select ARCH_CORTEXM3 + select ARCH_CORTEXM4 select STM32_STM32F40XX config ARCH_CHIP_STM32F407ZE diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs index d516c0b4fc..1e6c0c4010 100644 --- a/nuttx/arch/arm/src/stm32/Make.defs +++ b/nuttx/arch/arm/src/stm32/Make.defs @@ -61,6 +61,10 @@ ifeq ($(CONFIG_DEBUG_STACK),y) CMN_CSRCS += up_checkstack.c endif +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + ifeq ($(CONFIG_ARCH_FPU),y) CMN_ASRCS += up_fpu.S endif diff --git a/nuttx/arch/arm/src/str71x/Make.defs b/nuttx/arch/arm/src/str71x/Make.defs index 545ce17352..32eaddcdb8 100644 --- a/nuttx/arch/arm/src/str71x/Make.defs +++ b/nuttx/arch/arm/src/str71x/Make.defs @@ -47,6 +47,10 @@ ifneq ($(CONFIG_DISABLE_SIGNALS),y) CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c endif +ifeq ($(CONFIG_ELF),y) +CMN_CSRCS += up_elf.c +endif + CHIP_ASRCS = CHIP_CSRCS = str71x_prccu.c str71x_lowputc.c str71x_decodeirq.c str71x_irq.c \ str71x_timerisr.c str71x_serial.c diff --git a/nuttx/arch/sim/src/up_elf.c b/nuttx/arch/sim/src/up_elf.c index 26a8971a72..80443d4d5a 100644 --- a/nuttx/arch/sim/src/up_elf.c +++ b/nuttx/arch/sim/src/up_elf.c @@ -47,8 +47,6 @@ #include #include -#include "up_internal.h" - /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ diff --git a/nuttx/arch/x86/src/common/up_elf.c b/nuttx/arch/x86/src/common/up_elf.c index da3f7b9935..fd80960bb9 100644 --- a/nuttx/arch/x86/src/common/up_elf.c +++ b/nuttx/arch/x86/src/common/up_elf.c @@ -47,8 +47,6 @@ #include #include -#include "up_internal.h" - /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c index f2744eae76..e1b9f73d69 100644 --- a/nuttx/binfmt/libelf/libelf_init.c +++ b/nuttx/binfmt/libelf/libelf_init.c @@ -40,6 +40,7 @@ #include #include + #include #include #include @@ -77,6 +78,52 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: elf_filelen + * + * Description: + * Get the size of the ELF file + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +static inline int elf_filelen(FAR struct elf_loadinfo_s *loadinfo, + FAR const char *filename) +{ + struct stat buf; + int ret; + + /* Get the file stats */ + + ret = stat(filename, &buf); + if (ret < 0) + { + int errval = errno; + bdbg("Failed to fstat file: %d\n", errval); + return -errval; + } + + /* Verify that it is a regular file */ + + if (!S_ISREG(buf.st_mode)) + { + bdbg("Not a regular file. mode: %d\n", buf.st_mode); + return -ENOENT; + } + + /* TODO: Verify that the file is readable. Not really important because + * we will detect this when we try to open the file read-only. + */ + + /* Return the size of the file in the loadinfo structure */ + + loadinfo->filelen = buf.st_size; + return OK; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -104,7 +151,15 @@ int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo) memset(loadinfo, 0, sizeof(struct elf_loadinfo_s)); - /* Open the binary file */ + /* Get the length of the file. */ + + ret = elf_filelen(loadinfo, filename); + { + bdbg("elf_filelen failed: %d\n", ret); + return ret; + } + + /* Open the binary file for reading (only) */ loadinfo->filfd = open(filename, O_RDONLY); if (loadinfo->filfd < 0) diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 9378661e3c..6526004f76 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -40,7 +40,6 @@ #include #include -#include #include #include @@ -76,49 +75,6 @@ * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: elf_filelen - * - * Description: - * Get the size of the ELF file - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -static inline int elf_filelen(FAR struct elf_loadinfo_s *loadinfo) -{ - struct stat buf; - int ret; - - /* Get the file stats */ - - ret = fstat(loadinfo->filfd, &buf); - if (ret < 0) - { - int errval = errno; - bdbg("Failed to fstat file: %d\n", errval); - return -errval; - } - - /* Verify that it is a regular file */ - - if (!S_ISREG(buf.st_mode)) - { - bdbg("Not a regular file. mode: %d\n", buf.st_mode); - return -ENOENT; - } - - /* TODO: Verify that the file is readable */ - - /* Return the size of the file in the loadinfo structure */ - - loadinfo->filelen = buf.st_size; - return OK; -} - /**************************************************************************** * Name: elf_loadshdrs * @@ -323,14 +279,6 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) bvdbg("loadinfo: %p\n", loadinfo); DEBUGASSERT(loadinfo && loadinfo->filfd >= 0); - /* Get the length of the file. */ - - ret = elf_filelen(loadinfo); - { - bdbg("elf_filelen failed: %d\n", ret); - return ret; - } - /* Load section headers into memory */ ret = elf_loadshdrs(loadinfo); diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index dc25b220e4..d1a55daa9d 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -982,43 +982,81 @@ can be selected as follow: Where is one of the following: + elf: + --- + + This configuration derives from the ostest configuration. It has + been modified to us apps/examples/elf in order to test the ELF + loader. + + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Default toolchain: + + CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + + 3. By default, this project assumes that you are *NOT* using the DFU + bootloader. + ostest: ------ This configuration directory, performs a simple OS test using - examples/ostest. By default, this project assumes that you are - using the DFU bootloader. + apps/examples/ostest. - Default toolchain: + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: - CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux / Mac OS X + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ - If you use the Atollic toolchain, then the FPU test can be enabled in the - examples/ostest by adding the following your NuttX configuration file: + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. - -CONFIG_ARCH_FPU=n : Enable FPU support - +CONFIG_ARCH_FPU=y + 2. Default toolchain: - -CONFIG_STM32_CODESOURCERYW=y : Disable the CodeSourcery toolchain - +CONFIG_STM32_CODESOURCERYW=n + CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux / Mac OS X - -CONFIG_STM32_ATOLLIC_LITE=n : Enable *one* the Atollic toolchains - CONFIG_STM32_ATOLLIC_PRO=n - -CONFIG_STM32_ATOLLIC_LITE=y : The "Lite" version - CONFIG_STM32_ATOLLIC_PRO=n : The "Pro" version + 3. By default, this project assumes that you are *NOT* using the DFU + bootloader. + + 4. If you use the Atollic toolchain, then the FPU test can be enabled in the + examples/ostest by adding the following your NuttX configuration file: - -CONFIG_INTELHEX_BINARY=y : Suppress generation FLASH download formats - +CONFIG_INTELHEX_BINARY=n : (Only necessary with the "Lite" version) + -CONFIG_ARCH_FPU=n : Enable FPU support + +CONFIG_ARCH_FPU=y - -CONFIG_HAVE_CXX=y : Suppress generation of C++ code - +CONFIG_HAVE_CXX=n : (Only necessary with the "Lite" version) + -CONFIG_STM32_CODESOURCERYW=y : Disable the CodeSourcery toolchain + +CONFIG_STM32_CODESOURCERYW=n - -CONFIG_SCHED_WAITPID=y : Enable the waitpid() API needed by the FPU test - +CONFIG_SCHED_WAITPID=n + -CONFIG_STM32_ATOLLIC_LITE=n : Enable *one* the Atollic toolchains + CONFIG_STM32_ATOLLIC_PRO=n + -CONFIG_STM32_ATOLLIC_LITE=y : The "Lite" version + CONFIG_STM32_ATOLLIC_PRO=n : The "Pro" version - The FPU test also needs to know the size of the FPU registers save area in - bytes (see arch/arm/include/armv7-m/irq_lazyfpu.h): + -CONFIG_INTELHEX_BINARY=y : Suppress generation FLASH download formats + +CONFIG_INTELHEX_BINARY=n : (Only necessary with the "Lite" version) - -CONFIG_EXAMPLES_OSTEST_FPUSIZE=(4*33) + -CONFIG_HAVE_CXX=y : Suppress generation of C++ code + +CONFIG_HAVE_CXX=n : (Only necessary with the "Lite" version) + + -CONFIG_SCHED_WAITPID=y : Enable the waitpid() API needed by the FPU test + +CONFIG_SCHED_WAITPID=n + + The FPU test also needs to know the size of the FPU registers save area in + bytes (see arch/arm/include/armv7-m/irq_lazyfpu.h): + + -CONFIG_EXAMPLES_OSTEST_FPUSIZE=(4*33) nsh: --- diff --git a/nuttx/configs/stm32f4discovery/elf/Make.defs b/nuttx/configs/stm32f4discovery/elf/Make.defs new file mode 100644 index 0000000000..7f5be08f06 --- /dev/null +++ b/nuttx/configs/stm32f4discovery/elf/Make.defs @@ -0,0 +1,191 @@ +############################################################################ +# configs/stm32f4discovery/elf/Make.defs +# +# 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 +include ${TOPDIR}/tools/Config.mk + +# Setup for the selected toolchain + +ifeq ($(CONFIG_STM32_CODESOURCERYW),y) + # CodeSourcery under Windows + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_CODESOURCERYL),y) + # CodeSourcery under Linux + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -O2 +endif +ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) + # Atollic toolchain under Windows + CROSSDEV = arm-atollic-eabi- + ARCROSSDEV = + WINTOOL = y +ifeq ($(CONFIG_ARCH_FPU),y) + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard +else + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +endif +ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) + # Atollic toolchain under Windows + CROSSDEV = arm-atollic-eabi- + ARCROSSDEV = arm-atollic-eabi- + WINTOOL = y +ifeq ($(CONFIG_ARCH_FPU),y) + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard +else + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +endif +ifeq ($(CONFIG_STM32_DEVKITARM),y) + # devkitARM under Windows + CROSSDEV = arm-eabi- + ARCROSSDEV = arm-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_RAISONANCE),y) + # Raisonance RIDE7 under Windows + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -Os +endif + +LDSCRIPT = ld.script + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/winlink.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + 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)/scripts/$(LDSCRIPT)}" + MAXOPTIMIZATION = -O2 +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)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +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 ("${CONFIG_DEBUG_SYMBOLS}","y") + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +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__ + +# NXFLAT module definitions + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +# ELF module definitions + +LDELFFLAGS = -r -e main +ifeq ($(WINTOOL),y) + LDELFFLAGS += -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/gnu-elf.ld}" +else + LDELFFLAGS += -T $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/gnu-elf.ld +endif + +# File extensions + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +# Linker flags + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + +# Host tools + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx/configs/stm32f4discovery/elf/defconfig b/nuttx/configs/stm32f4discovery/elf/defconfig new file mode 100644 index 0000000000..dd5bd28298 --- /dev/null +++ b/nuttx/configs/stm32f4discovery/elf/defconfig @@ -0,0 +1,830 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +# CONFIG_RAW_BINARY is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM3S is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM4=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARCH_FPU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set +CONFIG_ARCH_IRQPRIO=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +CONFIG_ARCH_CHIP_STM32F407VG=y +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +CONFIG_STM32_STM32F40XX=y +CONFIG_STM32_CODESOURCERYW=y +# CONFIG_STM32_CODESOURCERYL is not set +# CONFIG_STM32_ATOLLIC_LITE is not set +# CONFIG_STM32_ATOLLIC_PRO is not set +# CONFIG_STM32_DEVKITARM is not set +# CONFIG_STM32_RAISONANCE is not set +# CONFIG_STM32_BUILDROOT is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_BKPSRAM is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CCMDATARAM is not set +# CONFIG_STM32_CRYP is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_IWDG is not set +# CONFIG_STM32_OTGFS is not set +# CONFIG_STM32_OTGHS is not set +# CONFIG_STM32_PWR is not set +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_USART1 is not set +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +# CONFIG_STM32_WWDG is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +# CONFIG_STM32_CCMEXCLUDE is not set + +# +# USB Host Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_STACKDUMP=y + +# +# Board Settings +# +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=196608 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="stm32f4discovery" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2012 +CONFIG_START_MONTH=10 +CONFIG_START_DAY=26 +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=y +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_WAITPID is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="ostest_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_POLL is not set + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Stack and heap information +# +# CONFIG_CUSTOM_STACK is not set +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_SPI is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_USART2=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_CONFIG_SERIAL_NPOLLWAITERS=2 +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_FS_FAT is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_NXFFS is not set +CONFIG_FS_ROMFS=y + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +CONFIG_ELF=y +CONFIG_ELF_ALIGN_LOG2=2 +CONFIG_ELF_STACKSIZE=2048 +CONFIG_ELF_BUFFERSIZE=128 +CONFIG_ELF_BUFFERINCR=32 +CONFIG_SYMTAB_ORDEREDBYNAME=y + +# +# Library Routines +# +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_HAVE_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set +# CONFIG_HAVE_CXX is not set +# CONFIG_HAVE_CXXINITIALIZE is not set +# CONFIG_CXX_NEWLONG is not set + +# +# Application Configuration +# + +# +# Named Applications +# +# CONFIG_NAMEDAPP is not set + +# +# Examples +# + +# +# ADC Example +# + +# +# Buttons Example +# +# CONFIG_EXAMPLES_BUTTONS is not set + +# +# CAN Example +# +# CONFIG_EXAMPLES_CAN is not set + +# +# USB CDC/ACM Class Driver Example +# +# CONFIG_EXAMPLES_CDCACM is not set + +# +# USB composite Class Driver Example +# +# CONFIG_EXAMPLES_COMPOSITE is not set + +# +# DHCP Server Example +# +# CONFIG_EXAMPLES_DHCPD is not set + +# +# ELF Loader Example +# +CONFIG_EXAMPLES_ELF=y +CONFIG_EXAMPLES_ELF_DEVMINOR=0 +CONFIG_EXAMPLES_ELF_DEVPATH="/dev/ram0" + +# +# FTP Client Example +# +# CONFIG_EXAMPLES_FTPC is not set + +# +# FTP Server Example +# +# CONFIG_EXAMPLES_FTPD is not set + +# +# "Hello, World!" Example +# +# CONFIG_EXAMPLES_HELLO is not set + +# +# "Hello, World!" C++ Example +# +# CONFIG_EXAMPLES_HELLOXX is not set + +# +# USB HID Keyboard Example +# +# CONFIG_EXAMPLES_HIDKBD is not set + +# +# IGMP Example +# +# CONFIG_EXAMPLES_IGMP is not set + +# +# LCD Read/Write Example +# +# CONFIG_EXAMPLES_LCDRW is not set + +# +# Memory Management Example +# +# CONFIG_EXAMPLES_MM is not set + +# +# File System Mount Example +# +# CONFIG_EXAMPLES_MOUNT is not set + +# +# FreeModBus Example +# +# CONFIG_EXAMPLES_MODBUS is not set + +# +# Network Test Example +# +# CONFIG_EXAMPLES_NETTEST is not set + +# +# NuttShell (NSH) Example +# +# CONFIG_EXAMPLES_NSH is not set + +# +# NULL Example +# +# CONFIG_EXAMPLES_NULL is not set + +# +# NX Graphics Example +# +# CONFIG_EXAMPLES_NX is not set + +# +# NxConsole Example +# +# CONFIG_EXAMPLES_NXCONSOLE is not set + +# +# NXFFS File System Example +# +# CONFIG_EXAMPLES_NXFFS is not set + +# +# NXFLAT Example +# +# CONFIG_EXAMPLES_NXFLAT is not set + +# +# NX Graphics "Hello, World!" Example +# +# CONFIG_EXAMPLES_NXHELLO is not set + +# +# NX Graphics image Example +# +# CONFIG_EXAMPLES_NXIMAGE is not set + +# +# NX Graphics lines Example +# +# CONFIG_EXAMPLES_NXLINES is not set + +# +# NX Graphics Text Example +# +# CONFIG_EXAMPLES_NXTEXT is not set + +# +# OS Test Example +# +# CONFIG_EXAMPLES_OSTEST is not set + +# +# Pascal "Hello, World!"example +# +# CONFIG_EXAMPLES_PASHELLO is not set + +# +# Pipe Example +# +# CONFIG_EXAMPLES_PIPE is not set + +# +# Poll Example +# +# CONFIG_EXAMPLES_POLL is not set + +# +# Pulse Width Modulation (PWM) Example +# + +# +# Quadrature Encoder Example +# +# CONFIG_EXAMPLES_QENCODER is not set + +# +# RGMP Example +# +# CONFIG_EXAMPLES_RGMP is not set + +# +# ROMFS Example +# +# CONFIG_EXAMPLES_ROMFS is not set + +# +# sendmail Example +# +# CONFIG_EXAMPLES_SENDMAIL is not set + +# +# Serial Loopback Example +# +# CONFIG_EXAMPLES_SERLOOP is not set + +# +# Telnet Daemon Example +# +# CONFIG_EXAMPLES_TELNETD is not set + +# +# THTTPD Web Server Example +# +# CONFIG_EXAMPLES_THTTPD is not set + +# +# TIFF Generation Example +# +# CONFIG_EXAMPLES_TIFF is not set + +# +# Touchscreen Example +# +# CONFIG_EXAMPLES_TOUCHSCREEN is not set + +# +# UDP Example +# +# CONFIG_EXAMPLES_UDP is not set + +# +# UDP Discovery Daemon Example +# + +# +# uIP Web Server Example +# +# CONFIG_EXAMPLES_UIP is not set + +# +# USB Serial Test Example +# +# CONFIG_EXAMPLES_USBSERIAL is not set + +# +# USB Mass Storage Class Example +# +# CONFIG_EXAMPLES_USBMSC is not set + +# +# USB Serial Terminal Example +# +# CONFIG_EXAMPLES_USBTERM is not set + +# +# Watchdog timer Example +# +# CONFIG_EXAMPLES_WATCHDOG is not set + +# +# wget Example +# + +# +# WLAN Example +# +# CONFIG_EXAMPLES_WLAN is not set + +# +# XML RPC Example +# + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# + +# +# DHCP client +# +# CONFIG_NETUTILS_DHCPC is not set + +# +# DHCP server +# +# CONFIG_NETUTILS_DHCPD is not set + +# +# FTP client +# +# CONFIG_NETUTILS_FTPC is not set + +# +# FTP server +# +# CONFIG_NETUTILS_FTPD is not set + +# +# Name resolution +# +# CONFIG_NETUTILS_RESOLV is not set + +# +# SMTP +# +# CONFIG_NETUTILS_SMTP is not set + +# +# TFTP client +# +# CONFIG_NETUTILS_TELNETD is not set + +# +# TFTP client +# +# CONFIG_NETUTILS_TFTPC is not set + +# +# THTTPD web server +# +# CONFIG_NETUTILS_THTTPD is not set + +# +# uIP support library +# +# CONFIG_NETUTILS_UIPLIB is not set + +# +# uIP web client +# +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# uIP web server +# + +# +# UDP Discovery Utility +# + +# +# XML-RPC library +# + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +# CONFIG_NSH_LIBRARY is not set + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +# CONFIG_SYSTEM_READLINE is not set + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# 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/stm32f4discovery/elf/setenv.sh b/nuttx/configs/stm32f4discovery/elf/setenv.sh new file mode 100755 index 0000000000..8a1fdf06e0 --- /dev/null +++ b/nuttx/configs/stm32f4discovery/elf/setenv.sh @@ -0,0 +1,79 @@ +#!/bin/bash +# configs/stm32f4discovery/elf/setenv.sh +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +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" + +# This the the Cygwin path to the location where I built genromfs. If you use +# the buildroot toolchain, then genromfs can probably be found in TOOLCHAIN_DIR +export GENROMFS_PATH="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${GENROMFS_PATH}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm32f4discovery/ostest/appconfig b/nuttx/configs/stm32f4discovery/ostest/appconfig deleted file mode 100644 index 266c7e3278..0000000000 --- a/nuttx/configs/stm32f4discovery/ostest/appconfig +++ /dev/null @@ -1,39 +0,0 @@ -############################################################################ -# configs/stm32f4discovery/ostest/appconfig -# -# Copyright (C) 2011 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. -# -############################################################################ - -# Path to example in apps/examples containing the user_start entry point - -CONFIGURED_APPS += examples/ostest - diff --git a/nuttx/configs/stm32f4discovery/ostest/defconfig b/nuttx/configs/stm32f4discovery/ostest/defconfig index dba07f76b5..1683657303 100644 --- a/nuttx/configs/stm32f4discovery/ostest/defconfig +++ b/nuttx/configs/stm32f4discovery/ostest/defconfig @@ -1,310 +1,267 @@ -############################################################################ -# configs/stm32f4discovery/ostest/defconfig # -# Copyright (C) 2011 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration # -# 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. -# -############################################################################ -# -# Architecture Selection -# -CONFIG_ARCH="arm" -CONFIG_ARCH_ARM=y -CONFIG_ARCH_CORTEXM4=y -CONFIG_ARCH_CHIP="stm32" -CONFIG_ARCH_CHIP_STM32F407VG=y -CONFIG_ARCH_BOARD="stm32f4discovery" -CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y -CONFIG_BOARD_LOOPSPERMSEC=16717 -CONFIG_DRAM_SIZE=196608 -CONFIG_DRAM_START=0x20000000 -CONFIG_ARCH_IRQPRIO=y -CONFIG_ARCH_FPU=n -CONFIG_ARCH_INTERRUPTSTACK=0 -CONFIG_ARCH_STACKDUMP=y -CONFIG_ARCH_BOOTLOADER=n -CONFIG_ARCH_LEDS=y -CONFIG_ARCH_BUTTONS=n -CONFIG_ARCH_CALIBRATION=n -CONFIG_ARCH_DMA=n +CONFIG_NUTTX_NEWCONFIG=y # -# Identify toolchain and linker options +# Build Setup # -CONFIG_STM32_CODESOURCERYW=n -CONFIG_STM32_CODESOURCERYL=y -CONFIG_STM32_ATOLLIC_LITE=n -CONFIG_STM32_ATOLLIC_PRO=n -CONFIG_STM32_DEVKITARM=n -CONFIG_STM32_RAISONANCE=n -CONFIG_STM32_BUILDROOT=n +# CONFIG_EXPERIMENTAL is not set # -# JTAG Enable settings (by default only SW-DP is enabled): +# Build Configuration # -CONFIG_STM32_DFU=n -CONFIG_STM32_JTAG_FULL_ENABLE=n -CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n -CONFIG_STM32_JTAG_SW_ENABLE=y +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set # -# Individual subsystems can be enabled: +# Binary Output Formats # -# AHB1: -CONFIG_STM32_CRC=n -CONFIG_STM32_BKPSRAM=n -CONFIG_STM32_CCMDATARAM=n -CONFIG_STM32_DMA1=n -CONFIG_STM32_DMA2=n -CONFIG_STM32_ETHMAC=n -CONFIG_STM32_OTGHS=n -# AHB2: -CONFIG_STM32_DCMI=n -CONFIG_STM32_CRYP=n -CONFIG_STM32_HASH=n -CONFIG_STM32_RNG=n -CONFIG_STM32_OTGFS=n -# AHB3: -CONFIG_STM32_FSMC=n -# APB1: -CONFIG_STM32_TIM2=n -CONFIG_STM32_TIM3=n -CONFIG_STM32_TIM4=n -CONFIG_STM32_TIM5=n -CONFIG_STM32_TIM6=n -CONFIG_STM32_TIM7=n -CONFIG_STM32_TIM12=n -CONFIG_STM32_TIM13=n -CONFIG_STM32_TIM14=n -CONFIG_STM32_WWDG=n -CONFIG_STM32_IWDG=n -CONFIG_STM32_SPI2=n -CONFIG_STM32_SPI3=n -CONFIG_STM32_USART2=y -CONFIG_STM32_USART3=n -CONFIG_STM32_UART4=n -CONFIG_STM32_UART5=n -CONFIG_STM32_I2C1=n -CONFIG_STM32_I2C2=n -CONFIG_STM32_I2C3=n -CONFIG_STM32_CAN1=n -CONFIG_STM32_CAN2=n -CONFIG_STM32_DAC=n -CONFIG_STM32_PWR=n -# APB2: -CONFIG_STM32_TIM1=n -CONFIG_STM32_TIM8=n -CONFIG_STM32_USART1=n -CONFIG_STM32_USART6=n -CONFIG_STM32_ADC1=n -CONFIG_STM32_ADC2=n -CONFIG_STM32_ADC3=n -CONFIG_STM32_SDIO=n -CONFIG_STM32_SPI1=n -CONFIG_STM32_SYSCFG=y -CONFIG_STM32_TIM9=n -CONFIG_STM32_TIM10=n -CONFIG_STM32_TIM11=n - -# -# STM32F4Discovery specific serial device driver settings -# -CONFIG_USART1_SERIAL_CONSOLE=n -CONFIG_USART2_SERIAL_CONSOLE=y -CONFIG_USART3_SERIAL_CONSOLE=n -CONFIG_UART4_SERIAL_CONSOLE=n -CONFIG_UART5_SERIAL_CONSOLE=n - -CONFIG_USART1_TXBUFSIZE=128 -CONFIG_USART2_TXBUFSIZE=128 -CONFIG_USART3_TXBUFSIZE=128 -CONFIG_UART4_TXBUFSIZE=128 -CONFIG_UART5_TXBUFSIZE=128 - -CONFIG_USART1_RXBUFSIZE=128 -CONFIG_USART2_RXBUFSIZE=128 -CONFIG_USART3_RXBUFSIZE=128 -CONFIG_UART4_RXBUFSIZE=128 -CONFIG_UART5_RXBUFSIZE=128 - -CONFIG_USART1_BAUD=115200 -CONFIG_USART2_BAUD=115200 -CONFIG_USART3_BAUD=115200 -CONFIG_UART4_BAUD=115200 -CONFIG_UART5_BAUD=115200 - -CONFIG_USART1_BITS=8 -CONFIG_USART2_BITS=8 -CONFIG_USART3_BITS=8 -CONFIG_UART4_BITS=8 -CONFIG_UART5_BITS=8 - -CONFIG_USART1_PARITY=0 -CONFIG_USART2_PARITY=0 -CONFIG_USART3_PARITY=0 -CONFIG_UART4_PARITY=0 -CONFIG_UART5_PARITY=0 - -CONFIG_USART1_2STOP=0 -CONFIG_USART2_2STOP=0 -CONFIG_USART3_2STOP=0 -CONFIG_UART4_2STOP=0 -CONFIG_UART5_2STOP=0 - -# -# STM32F40xxx specific CAN device driver settings -# -CONFIG_CAN=n -CONFIG_CAN_EXTID=n -#CONFIG_CAN_FIFOSIZE -#CONFIG_CAN_NPENDINGRTR -CONFIG_CAN_LOOPBACK=n -CONFIG_CAN1_BAUD=700000 -CONFIG_CAN2_BAUD=700000 - -# -# STM32F40xxx Ethernet device driver settings -# -CONFIG_STM32_PHYADDR=1 -CONFIG_STM32_MII=y -CONFIG_STM32_MII_MCO1=y -CONFIG_STM32_MII_MCO2=n -CONFIG_STM32_RMII=n -CONFIG_STM32_AUTONEG=y -#CONFIG_STM32_ETHFD -#CONFIG_STM32_ETH100MBPS -CONFIG_STM32_PHYSR=16 -CONFIG_STM32_PHYSR_SPEED=0x0002 -CONFIG_STM32_PHYSR_100MBPS=0x0000 -CONFIG_STM32_PHYSR_MODE=0x0004 -CONFIG_STM32_PHYSR_FULLDUPLEX=0x0004 -CONFIG_STM32_ETH_PTP=n - -# -# General build options -# -CONFIG_RRLOAD_BINARY=n +# CONFIG_RRLOAD_BINARY is not set CONFIG_INTELHEX_BINARY=y -CONFIG_MOTOROLA_SREC=n +# CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # -# General OS setup +# Customize Header Files # -CONFIG_USER_ENTRYPOINT="ostest_main" -CONFIG_DEBUG=n -CONFIG_DEBUG_VERBOSE=n -CONFIG_DEBUG_SYMBOLS=n -CONFIG_HAVE_CXX=n -CONFIG_HAVE_CXXINITIALIZE=n -CONFIG_MM_REGIONS=2 -CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM3S is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM4=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARCH_FPU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set +CONFIG_ARCH_IRQPRIO=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +CONFIG_ARCH_CHIP_STM32F407VG=y +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +CONFIG_STM32_STM32F40XX=y +# CONFIG_STM32_CODESOURCERYW is not set +CONFIG_STM32_CODESOURCERYL=y +# CONFIG_STM32_ATOLLIC_LITE is not set +# CONFIG_STM32_ATOLLIC_PRO is not set +# CONFIG_STM32_DEVKITARM is not set +# CONFIG_STM32_RAISONANCE is not set +# CONFIG_STM32_BUILDROOT is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_BKPSRAM is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CCMDATARAM is not set +# CONFIG_STM32_CRYP is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_IWDG is not set +# CONFIG_STM32_OTGFS is not set +# CONFIG_STM32_OTGHS is not set +# CONFIG_STM32_PWR is not set +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_USART1 is not set +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +# CONFIG_STM32_WWDG is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +# CONFIG_STM32_CCMEXCLUDE is not set + +# +# USB Host Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_STACKDUMP=y + +# +# Board Settings +# +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=196608 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="stm32f4discovery" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 CONFIG_RR_INTERVAL=200 -CONFIG_SCHED_INSTRUMENTATION=n +# CONFIG_SCHED_INSTRUMENTATION is not set CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set CONFIG_START_YEAR=2009 CONFIG_START_MONTH=9 CONFIG_START_DAY=21 -CONFIG_GREGORIAN_TIME=n -CONFIG_JULIAN_TIME=n CONFIG_DEV_CONSOLE=y CONFIG_DEV_LOWCONSOLE=y -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=n +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set CONFIG_SDCLONE_DISABLE=y -CONFIG_SCHED_WORKQUEUE=n -CONFIG_SCHED_WORKPRIORITY=192 -CONFIG_SCHED_WORKPERIOD=50000 -CONFIG_SCHED_WORKSTACKSIZE=1024 -CONFIG_SIG_SIGWORK=4 -CONFIG_SCHED_WAITPID=n -CONFIG_SCHED_ATEXIT=n - -# -# Settings for NXFLAT -# -CONFIG_NXFLAT=n -CONFIG_NXFLAT_DUMPBUFFER=n -CONFIG_SYMTAB_ORDEREDBYNAME=y - -# -# The following can be used to disable categories of -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=n -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=n +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_WAITPID is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="elf_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set CONFIG_DISABLE_MOUNTPOINT=y CONFIG_DISABLE_ENVIRON=y CONFIG_DISABLE_POLL=y -# -# Misc libc settings -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve system performance -# -CONFIG_ARCH_MEMCPY=n -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n - # # Sizes of configurable things (0 disables) # @@ -314,9 +271,6 @@ CONFIG_NPTHREAD_KEYS=4 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 CONFIG_MAX_WDOGPARMS=2 @@ -324,424 +278,546 @@ CONFIG_PREALLOC_WDOGS=4 CONFIG_PREALLOC_TIMERS=4 # -# Filesystem configuration +# Stack and heap information # -CONFIG_FS_FAT=n -CONFIG_FAT_LCNAMES=n -CONFIG_FAT_LFN=n -CONFIG_FAT_MAXFNAME=32 -CONFIG_FS_NXFFS=n -CONFIG_FS_ROMFS=n +# CONFIG_CUSTOM_STACK is not set +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 # -# SPI-based MMC/SD driver +# Device Drivers # -CONFIG_MMCSD_NSLOTS=0 -CONFIG_MMCSD_READONLY=n -CONFIG_MMCSD_SPICLOCK=12500000 +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_SPI is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_USART2=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set # -# Block driver buffering +# USART2 Configuration # -CONFIG_FS_READAHEAD=n -CONFIG_FS_WRITEBUFFER=n +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set # -# SDIO-based MMC/SD driver +# System Logging Device Options # -CONFIG_SDIO_DMA=n -CONFIG_MMCSD_MULTIBLOCK_DISABLE=y -CONFIG_MMCSD_MMCSUPPORT=n -CONFIG_MMCSD_HAVECARDDETECT=n # -# TCP/IP and UDP support via uIP +# System Logging # -CONFIG_NET=n -CONFIG_NET_NOINTS=n -CONFIG_NET_MULTIBUFFER=y -CONFIG_NET_IPv6=n -CONFIG_NSOCKET_DESCRIPTORS=0 -CONFIG_NET_SOCKOPTS=y -CONFIG_NET_BUFSIZE=562 -CONFIG_NET_TCP=n -CONFIG_NET_TCP_CONNS=40 -CONFIG_NET_MAX_LISTENPORTS=40 -CONFIG_NET_UDP=n -CONFIG_NET_UDP_CHECKSUMS=y -#CONFIG_NET_UDP_CONNS=10 -CONFIG_NET_ICMP=n -CONFIG_NET_ICMP_PING=n -#CONFIG_NET_PINGADDRCONF=0 -CONFIG_NET_STATISTICS=y -#CONFIG_NET_RECEIVE_WINDOW= -CONFIG_NET_BROADCAST=n -#CONFIG_NET_ARPTAB_SIZE=8 -CONFIG_NET_ARP_IPIN=n -CONFIG_NET_MULTICAST=n +# CONFIG_RAMLOG is not set # -# UIP Network Utilities +# Networking Support # -CONFIG_NET_DHCP_LIGHT=n -CONFIG_NET_RESOLV_ENTRIES=4 +# CONFIG_NET is not set # -# RTC Configuration +# File Systems # -CONFIG_RTC=n -CONFIG_RTC_DATETIME=y -CONFIG_RTC_HIRES=n -CONFIG_RTC_FREQUENCY=1 -CONFIG_RTC_ALARM=n # -# STM32 USB OTG FS Device Configuration +# File system configuration # -CONFIG_USBDEV=n -CONFIG_USBDEV_ISOCHRONOUS=n -CONFIG_USBDEV_DUALSPEED=n -CONFIG_USBDEV_SELFPOWERED=y -CONFIG_USBDEV_REMOTEWAKEUP=n -CONFIG_USBDEV_MAXPOWER=100 -CONFIG_USBDEV_TRACE=n -CONFIG_USBDEV_TRACE_NRECORDS=128 +# CONFIG_FS_RAMMAP is not set # -# STM32 USB OTG FS Host Configuration +# System Logging # -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 +# CONFIG_SYSLOG is not set # -# USB Serial Device Configuration +# Graphics Support # -CONFIG_PL2303=n -CONFIG_PL2303_EPINTIN=1 -CONFIG_PL2303_EPBULKOUT=2 -CONFIG_PL2303_EPBULKIN=3 -CONFIG_PL2303_NWRREQS=4 -CONFIG_PL2303_NRDREQS=4 -CONFIG_PL2303_VENDORID=0x067b -CONFIG_PL2303_PRODUCTID=0x2303 -CONFIG_PL2303_VENDORSTR="Nuttx" -CONFIG_PL2303_PRODUCTSTR="USBdev Serial" -CONFIG_PL2303_RXBUFSIZE=512 -CONFIG_PL2303_TXBUFSIZE=512 +# CONFIG_NX is not set # -# USB serial device class driver (Standard CDC ACM class) +# Memory Management # -CONFIG_CDCACM=n -CONFIG_CDCACM_CONSOLE=n -#CONFIG_CDCACM_EP0MAXPACKET -CONFIG_CDCACM_EPINTIN=1 -#CONFIG_CDCACM_EPINTIN_FSSIZE -#CONFIG_CDCACM_EPINTIN_HSSIZE -CONFIG_CDCACM_EPBULKOUT=3 -#CONFIG_CDCACM_EPBULKOUT_FSSIZE -#CONFIG_CDCACM_EPBULKOUT_HSSIZE -CONFIG_CDCACM_EPBULKIN=2 -#CONFIG_CDCACM_EPBULKIN_FSSIZE -#CONFIG_CDCACM_EPBULKIN_HSSIZE -#CONFIG_CDCACM_NWRREQS -#CONFIG_CDCACM_NRDREQS -#CONFIG_CDCACM_VENDORID -#CONFIG_CDCACM_VENDORSTR -#CONFIG_CDCACM_PRODUCTID -#CONFIG_CDCACM_PRODUCTSTR -#CONFIG_CDCACM_RXBUFSIZE -#CONFIG_CDCACM_TXBUFSIZE +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_GRAN is not set # -# USB Storage Device Configuration +# Binary Formats # -CONFIG_USBMSC=n -CONFIG_USBMSC_EP0MAXPACKET=64 -CONFIG_USBMSC_EPBULKOUT=2 -CONFIG_USBMSC_EPBULKIN=5 -CONFIG_USBMSC_NRDREQS=2 -CONFIG_USBMSC_NWRREQS=2 -CONFIG_USBMSC_BULKINREQLEN=256 -CONFIG_USBMSC_BULKOUTREQLEN=256 -CONFIG_USBMSC_VENDORID=0x584e -CONFIG_USBMSC_VENDORSTR="NuttX" -CONFIG_USBMSC_PRODUCTID=0x5342 -CONFIG_USBMSC_PRODUCTSTR="USBdev Storage" -CONFIG_USBMSC_VERSIONNO=0x0399 -CONFIG_USBMSC_REMOVABLE=y +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_SYMTAB_ORDEREDBYNAME=y # -# Watchdog timer configuration +# Library Routines # -CONFIG_WATCHDOG=n +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_HAVE_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set +# CONFIG_HAVE_CXX is not set +# CONFIG_HAVE_CXXINITIALIZE is not set +# CONFIG_CXX_NEWLONG is not set # -# Graphics related configuration settings +# Application Configuration # -CONFIG_NX=n -CONFIG_NX_MULTIUSER=n -CONFIG_NX_NPLANES=1 -CONFIG_NX_DISABLE_1BPP=y -CONFIG_NX_DISABLE_2BPP=y -CONFIG_NX_DISABLE_4BPP=y -CONFIG_NX_DISABLE_8BPP=y -CONFIG_NX_DISABLE_16BPP=n -CONFIG_NX_DISABLE_24BPP=y -CONFIG_NX_DISABLE_32BPP=y -CONFIG_NX_PACKEDMSFIRST=n -CONFIG_NX_LCDDRIVER=y -CONFIG_LCD_MAXPOWER=1 -CONFIG_LCD_MAXCONTRAST=1 -CONFIG_NX_MOUSE=y -CONFIG_NX_KBD=y -#CONFIG_NXTK_BORDERWIDTH=4 -CONFIG_NXTK_BORDERCOLOR1=0xd69a -CONFIG_NXTK_BORDERCOLOR2=0xad55 -CONFIG_NXTK_AUTORAISE=n -CONFIG_NXFONT_SANS17X22=y -CONFIG_NXFONT_SANS20X26=n -CONFIG_NXFONT_SANS22X29=n -CONFIG_NXFONT_SANS23X27=n -CONFIG_NXFONT_SANS28X37=n -CONFIG_NXFONT_SANS17X23B=n -CONFIG_NXFONT_SANS20X27B=y -CONFIG_NXFONT_SANS22X29B=y -CONFIG_NXFONT_SANS28X37B=n -CONFIG_NXFONT_SANS40X49B=n -CONFIG_NXFONT_SERIF22X29=n -CONFIG_NXFONT_SERIF29X37=n -CONFIG_NXFONT_SERIF38X48=n -CONFIG_NXFONT_SERIF22X28B=n -CONFIG_NXFONT_SERIF27X38B=n -CONFIG_NXFONT_SERIF38X49B=n -CONFIG_NXFONTS_CHARBITS=7 -CONFIG_NX_BLOCKING=y -CONFIG_NX_MXSERVERMSGS=32 -CONFIG_NX_MXCLIENTMSGS=16 # -# NxWidgets -CONFIG_NXWIDGETS_BPP=16 -CONFIG_NXWIDGETS_DEFAULT_FONTID=5 +# Named Applications +# +# CONFIG_NAMEDAPP is not set # -# stm32f4discovery LCD Hardware Configuration +# Examples # -CONFIG_LCD_LANDSCAPE=n -CONFIG_LCD_PORTRAIT=n -CONFIG_LCD_RPORTRAIT=y -CONFIG_LCD_BACKLIGHT=y -CONFIG_LCD_PWM=n -CONFIG_STM32_AM240320_DISABLE=y -CONFIG_STM32_SPFD5408B_DISABLE=n -CONFIG_STM32_R61580_DISABLE=n # -# Settings for examples/uip +# ADC Example # -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_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 +# Buttons Example +# +# CONFIG_EXAMPLES_BUTTONS is not set # -# Settings for examples/ostest +# CAN Example # +# CONFIG_EXAMPLES_CAN is not set + +# +# USB CDC/ACM Class Driver Example +# +# CONFIG_EXAMPLES_CDCACM is not set + +# +# USB composite Class Driver Example +# +# CONFIG_EXAMPLES_COMPOSITE is not set + +# +# DHCP Server Example +# +# CONFIG_EXAMPLES_DHCPD is not set + +# +# ELF Loader Example +# +# CONFIG_EXAMPLES_ELF is not set + +# +# FTP Client Example +# +# CONFIG_EXAMPLES_FTPC is not set + +# +# FTP Server Example +# +# CONFIG_EXAMPLES_FTPD is not set + +# +# "Hello, World!" Example +# +# CONFIG_EXAMPLES_HELLO is not set + +# +# "Hello, World!" C++ Example +# +# CONFIG_EXAMPLES_HELLOXX is not set + +# +# USB HID Keyboard Example +# +# CONFIG_EXAMPLES_HIDKBD is not set + +# +# IGMP Example +# +# CONFIG_EXAMPLES_IGMP is not set + +# +# LCD Read/Write Example +# +# CONFIG_EXAMPLES_LCDRW is not set + +# +# Memory Management Example +# +# CONFIG_EXAMPLES_MM is not set + +# +# File System Mount Example +# +# CONFIG_EXAMPLES_MOUNT is not set + +# +# FreeModBus Example +# +# CONFIG_EXAMPLES_MODBUS is not set + +# +# Network Test Example +# +# CONFIG_EXAMPLES_NETTEST is not set + +# +# NuttShell (NSH) Example +# +# CONFIG_EXAMPLES_NSH is not set + +# +# NULL Example +# +# CONFIG_EXAMPLES_NULL is not set + +# +# NX Graphics Example +# +# CONFIG_EXAMPLES_NX is not set + +# +# NxConsole Example +# +# CONFIG_EXAMPLES_NXCONSOLE is not set + +# +# NXFFS File System Example +# +# CONFIG_EXAMPLES_NXFFS is not set + +# +# NXFLAT Example +# +# CONFIG_EXAMPLES_NXFLAT is not set + +# +# NX Graphics "Hello, World!" Example +# +# CONFIG_EXAMPLES_NXHELLO is not set + +# +# NX Graphics image Example +# +# CONFIG_EXAMPLES_NXIMAGE is not set + +# +# NX Graphics lines Example +# +# CONFIG_EXAMPLES_NXLINES is not set + +# +# NX Graphics Text Example +# +# CONFIG_EXAMPLES_NXTEXT is not set + +# +# OS Test Example +# +CONFIG_EXAMPLES_OSTEST=y +# CONFIG_EXAMPLES_OSTEST_BUILTIN is not set CONFIG_EXAMPLES_OSTEST_LOOPS=1 CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048 CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 # -# Settings for apps/nshlib +# Pascal "Hello, World!"example # -CONFIG_NSH_BUILTIN_APPS=y -CONFIG_NSH_FILEIOSIZE=512 -CONFIG_NSH_STRERROR=n -CONFIG_NSH_LINELEN=64 -CONFIG_NSH_NESTDEPTH=3 -CONFIG_NSH_DISABLESCRIPT=n -CONFIG_NSH_DISABLEBG=n -CONFIG_NSH_ROMFSETC=n -CONFIG_NSH_CONSOLE=y -#CONFIG_NSH_CONDEV="/dev/ttyS1" -CONFIG_NSH_TELNET=n -CONFIG_NSH_ARCHINIT=n -CONFIG_NSH_IOBUFFER_SIZE=512 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=y -CONFIG_NSH_IPADDR=0x0a000002 -CONFIG_NSH_DRIPADDR=0x0a000001 -CONFIG_NSH_NETMASK=0xffffff00 -CONFIG_NSH_ROMFSMOUNTPT="/etc" -CONFIG_NSH_INITSCRIPT="init.d/rcS" -CONFIG_NSH_ROMFSDEVNO=0 -CONFIG_NSH_ROMFSSECTSIZE=64 -CONFIG_NSH_FATDEVNO=1 -CONFIG_NSH_FATSECTSIZE=512 -CONFIG_NSH_FATNSECTORS=1024 -CONFIG_NSH_FATMOUNTPT="/tmp" +# CONFIG_EXAMPLES_PASHELLO is not set # -# Architecture-specific NSH options +# Pipe Example # -CONFIG_NSH_MMCSDSPIPORTNO=0 -CONFIG_NSH_MMCSDSLOTNO=0 -CONFIG_NSH_MMCSDMINOR=0 +# CONFIG_EXAMPLES_PIPE is not set # -# Settings for examples/nx +# Poll Example # -CONFIG_EXAMPLES_NX_BUILTIN=n -CONFIG_EXAMPLES_NX_VPLANE=0 -CONFIG_EXAMPLES_NX_DEVNO=0 -CONFIG_EXAMPLES_NX_BGCOLOR=0x0011 -CONFIG_EXAMPLES_NX_COLOR1=0xaedc -CONFIG_EXAMPLES_NX_COLOR2=0xe7ff -CONFIG_EXAMPLES_NX_TBCOLOR=0xd69a -CONFIG_EXAMPLES_NX_FONTID=0 -CONFIG_EXAMPLES_NX_FONTCOLOR=0x0000 -CONFIG_EXAMPLES_NX_BPP=16 -CONFIG_EXAMPLES_NX_RAWWINDOWS=n -CONFIG_EXAMPLES_NX_STACKSIZE=2048 -CONFIG_EXAMPLES_NX_CLIENTPRIO=80 -CONFIG_EXAMPLES_NX_SERVERPRIO=120 -CONFIG_EXAMPLES_NX_NOTIFYSIGNO=4 -CONFIG_EXAMPLES_NX_EXTERNINIT=n +# CONFIG_EXAMPLES_POLL is not set # -# Settings for examples/nxhello -# -CONFIG_EXAMPLES_NXHELLO_BUILTIN=n -CONFIG_EXAMPLES_NXHELLO_VPLANE=0 -CONFIG_EXAMPLES_NXHELLO_DEVNO=0 -CONFIG_EXAMPLES_NXHELLO_BGCOLOR=0x0011 -CONFIG_EXAMPLES_NXHELLO_FONTID=6 -CONFIG_EXAMPLES_NXHELLO_FONTCOLOR=0xffdf -CONFIG_EXAMPLES_NXHELLO_BPP=16 -CONFIG_EXAMPLES_NXHELLO_EXTERNINIT=n - -# -# Settings for examples/nximage -# -CONFIG_EXAMPLES_NXIMAGE_BUILTIN=n -CONFIG_EXAMPLES_NXIMAGE_VPLANE=0 -CONFIG_EXAMPLES_NXIMAGE_DEVNO=0 -CONFIG_EXAMPLES_NXIMAGE_BPP=16 -CONFIG_EXAMPLES_NXIMAGE_XSCALEp5=n -CONFIG_EXAMPLES_NXIMAGE_XSCALE1p5=y -CONFIG_EXAMPLES_NXIMAGE_XSCALE2p0=n -CONFIG_EXAMPLES_NXIMAGE_YSCALEp5=n -CONFIG_EXAMPLES_NXIMAGE_YSCALE1p5=y -CONFIG_EXAMPLES_NXIMAGE_YSCALE2p0=n -CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n - -# -# Settings for examples/nxlines -# -CONFIG_EXAMPLES_NXLINES_BUILTIN=n -CONFIG_EXAMPLES_NXLINES_VPLANE=0 -CONFIG_EXAMPLES_NXLINES_DEVNO=0 -CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 -CONFIG_EXAMPLES_NXLINES_LINEWIDTH=16 -CONFIG_EXAMPLES_NXLINES_LINECOLOR=0xffe0 -CONFIG_EXAMPLES_NXLINES_BORDERWIDTH=4 -CONFIG_EXAMPLES_NXLINES_BORDERCOLOR=0xffe0 -CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR=0xf7bb -CONFIG_EXAMPLES_NXLINES_BPP=16 -CONFIG_EXAMPLES_NXLINES_EXTERNINIT=n - -# -# Settings for examples/touchscreen -# -CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN=n -CONFIG_EXAMPLES_TOUCHSCREEN_MINOR=0 -CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH="/dev/input0" -CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES=25 - -# -# Settings for examples/buttons -# -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 -# -CONFIG_EXAMPLES_USBSERIAL_INONLY=n -CONFIG_EXAMPLES_USBSERIAL_OUTONLY=n -CONFIG_EXAMPLES_USBSERIAL_ONLYSMALL=n -CONFIG_EXAMPLES_USBSERIAL_ONLYBIG=n - -CONFIG_EXAMPLES_USBSERIAL_TRACEINIT=n -CONFIG_EXAMPLES_USBSERIAL_TRACECLASS=n -CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=n -CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n -CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n - -# -# Settings for examples/cdcacm -# -# Configuration prequisites: -# -CONFIG_EXAMPLES_CDCACM_DEVMINOR=0 -CONFIG_EXAMPLES_CDCACM_TRACEINIT=n -CONFIG_EXAMPLES_CDCACM_TRACECLASS=n -CONFIG_EXAMPLES_CDCACM_TRACETRANSFERS=n -CONFIG_EXAMPLES_CDCACM_TRACECONTROLLER=n -CONFIG_EXAMPLES_CDCACM_TRACEINTERRUPTS=n - -# -# Settings for examples/usbstorage -# -CONFIG_EXAMPLES_USBMSC_BUILTIN=n -CONFIG_EXAMPLES_USBMSC_NLUNS=1 -CONFIG_EXAMPLES_USBMSC_DEVMINOR1=0 -CONFIG_EXAMPLES_USBMSC_DEVPATH1="/dev/mmcsd0" -CONFIG_EXAMPLES_USBMSC_DEBUGMM=n -CONFIG_EXAMPLES_USBMSC_TRACEINIT=n -CONFIG_EXAMPLES_USBMSC_TRACECLASS=n -CONFIG_EXAMPLES_USBMSC_TRACETRANSFERS=n -CONFIG_EXAMPLES_USBMSC_TRACECONTROLLER=n -CONFIG_EXAMPLES_USBMSC_TRACEINTERRUPTS=n - -# -# Settings for examples/watchdog -# -# This test depends on these specific Watchdog/NSH configurations settings (your -# specific watchdog hardware settings might require additional settings). +# Pulse Width Modulation (PWM) Example # # -# Stack and heap information +# Quadrature Encoder Example # -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_IDLETHREAD_STACKSIZE=1024 -CONFIG_USERMAIN_STACKSIZE=2048 -CONFIG_PTHREAD_STACK_MIN=256 -CONFIG_PTHREAD_STACK_DEFAULT=2048 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= +# CONFIG_EXAMPLES_QENCODER is not set + +# +# RGMP Example +# +# CONFIG_EXAMPLES_RGMP is not set + +# +# ROMFS Example +# +# CONFIG_EXAMPLES_ROMFS is not set + +# +# sendmail Example +# +# CONFIG_EXAMPLES_SENDMAIL is not set + +# +# Serial Loopback Example +# +# CONFIG_EXAMPLES_SERLOOP is not set + +# +# Telnet Daemon Example +# +# CONFIG_EXAMPLES_TELNETD is not set + +# +# THTTPD Web Server Example +# +# CONFIG_EXAMPLES_THTTPD is not set + +# +# TIFF Generation Example +# +# CONFIG_EXAMPLES_TIFF is not set + +# +# Touchscreen Example +# +# CONFIG_EXAMPLES_TOUCHSCREEN is not set + +# +# UDP Example +# +# CONFIG_EXAMPLES_UDP is not set + +# +# UDP Discovery Daemon Example +# + +# +# uIP Web Server Example +# +# CONFIG_EXAMPLES_UIP is not set + +# +# USB Serial Test Example +# +# CONFIG_EXAMPLES_USBSERIAL is not set + +# +# USB Mass Storage Class Example +# +# CONFIG_EXAMPLES_USBMSC is not set + +# +# USB Serial Terminal Example +# +# CONFIG_EXAMPLES_USBTERM is not set + +# +# Watchdog timer Example +# +# CONFIG_EXAMPLES_WATCHDOG is not set + +# +# wget Example +# + +# +# WLAN Example +# +# CONFIG_EXAMPLES_WLAN is not set + +# +# XML RPC Example +# + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# + +# +# DHCP client +# +# CONFIG_NETUTILS_DHCPC is not set + +# +# DHCP server +# +# CONFIG_NETUTILS_DHCPD is not set + +# +# FTP client +# +# CONFIG_NETUTILS_FTPC is not set + +# +# FTP server +# +# CONFIG_NETUTILS_FTPD is not set + +# +# Name resolution +# +# CONFIG_NETUTILS_RESOLV is not set + +# +# SMTP +# +# CONFIG_NETUTILS_SMTP is not set + +# +# TFTP client +# +# CONFIG_NETUTILS_TELNETD is not set + +# +# TFTP client +# +# CONFIG_NETUTILS_TFTPC is not set + +# +# THTTPD web server +# +# CONFIG_NETUTILS_THTTPD is not set + +# +# uIP support library +# +# CONFIG_NETUTILS_UIPLIB is not set + +# +# uIP web client +# +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# uIP web server +# + +# +# UDP Discovery Utility +# + +# +# XML-RPC library +# + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +# CONFIG_NSH_LIBRARY is not set + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +# CONFIG_SYSTEM_READLINE is not set + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# 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/stm32f4discovery/scripts/gnu-elf.ld b/nuttx/configs/stm32f4discovery/scripts/gnu-elf.ld new file mode 100644 index 0000000000..0153cf5fad --- /dev/null +++ b/nuttx/configs/stm32f4discovery/scripts/gnu-elf.ld @@ -0,0 +1,127 @@ +/**************************************************************************** + * configs/stm32f4discovery/scripts/gnu-elf.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. + * + ****************************************************************************/ + +SECTIONS +{ + .text 0x00000000 : + { + _stext = . ; + *(.text) + *(.text.*) + *(.gnu.warning) + *(.stub) + *(.glue_7) + *(.glue_7t) + *(.jcr) + + /* C++ support: The .init and .fini sections contain specific logic + * to manage static constructors and destructors. + */ + + *(.gnu.linkonce.t.*) + *(.init) + *(.fini) + _etext = . ; + } + + .rodata : + { + _srodata = . ; + *(.rodata) + *(.rodata1) + *(.rodata.*) + *(.gnu.linkonce.r*) + _erodata = . ; + } + + .data : + { + _sdata = . ; + *(.data) + *(.data1) + *(.data.*) + *(.gnu.linkonce.d*) + _edata = . ; + } + + /* 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. + */ + + .ctors : + { + _sctros = . ; + *(.ctors) + _edtors = . ; + } + + .ctors : + { + _sdtors = . ; + *(.dtors) + _edtors = . ; + } + + .bss : + { + _sbss = . ; + *(.bss) + *(.bss.*) + *(.sbss) + *(.sbss.*) + *(.gnu.linkonce.b*) + *(COMMON) + _ebss = . ; + } + + /* 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/fs/fs_stat.c b/nuttx/fs/fs_stat.c index cf27e87a6c..4df25028f3 100644 --- a/nuttx/fs/fs_stat.c +++ b/nuttx/fs/fs_stat.c @@ -1,7 +1,7 @@ /**************************************************************************** * fs/fs_stat.c * - * Copyright (C) 2007-2009 , 2012Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -122,7 +122,8 @@ static inline int statroot(FAR struct stat *buf) /**************************************************************************** * Name: stat * - * Return: Zero on success; -1 on failure with errno set: + * Returned Value: + * Zero on success; -1 on failure with errno set: * * EACCES Search permission is denied for one of the directories in the * path prefix of path. @@ -134,7 +135,7 @@ static inline int statroot(FAR struct stat *buf) * ****************************************************************************/ -int stat(const char *path, FAR struct stat *buf) +int stat(FAR const char *path, FAR struct stat *buf) { FAR struct inode *inode; const char *relpath = NULL; From 1f1319f25bc2461eb8970ba0345768df440166ef Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 27 Oct 2012 00:04:47 +0000 Subject: [PATCH 034/206] The ELF loader is basically functional (needs more testing) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5265 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 1 + apps/examples/README.txt | 15 +- apps/examples/elf/Makefile | 36 ++-- apps/examples/elf/elf_main.c | 11 +- apps/examples/elf/tests/Makefile | 46 +++-- apps/examples/elf/tests/errno/Makefile | 2 +- apps/examples/elf/tests/hello/Makefile | 2 +- apps/examples/elf/tests/longjmp/Makefile | 2 +- apps/examples/elf/tests/mksymtab.sh | 50 ++++-- apps/examples/elf/tests/mutex/Makefile | 2 +- apps/examples/elf/tests/pthread/Makefile | 2 +- apps/examples/elf/tests/signal/Makefile | 2 +- apps/examples/elf/tests/signal/signal.c | 167 +++++++----------- apps/examples/elf/tests/struct/Makefile | 4 +- apps/examples/elf/tests/task/Makefile | 2 +- apps/examples/nxflat/tests/mksymtab.sh | 2 +- apps/examples/nxflat/tests/signal/signal.c | 170 +++++++------------ nuttx/ChangeLog | 2 + nuttx/arch/arm/src/armv7-m/up_elf.c | 47 ++--- nuttx/arch/arm/src/stm32/Kconfig | 6 +- nuttx/binfmt/libelf/libelf_bind.c | 5 +- nuttx/binfmt/libelf/libelf_init.c | 1 + nuttx/configs/stm32f4discovery/README.txt | 4 + nuttx/configs/stm32f4discovery/elf/Make.defs | 1 + nuttx/configs/stm32f4discovery/elf/defconfig | 7 +- 25 files changed, 291 insertions(+), 298 deletions(-) diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index d25c497399..14d107b3f4 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -383,4 +383,5 @@ * apps/Makefile: Small change that reduces the number of shell invocations by one (Mike Smith). * apps/examples/elf: Test example for the ELF loader. + * apps/examples/elf: The ELF module test example appears fully functional. diff --git a/apps/examples/README.txt b/apps/examples/README.txt index bfb92b6b79..70dffc9897 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -318,7 +318,12 @@ examples/elf NOTES: - 1. Your top-level nuttx/Make.defs file must include an approproate definition, + 1. CFLAGS should be provided in CELFFLAGS. RAM and FLASH memory regions + may require long allcs. For ARM, this might be: + + CELFFLAGS = $(CFLAGS) -mlong-calls + + 2. Your top-level nuttx/Make.defs file must alos include an approproate definition, LDELFFLAGS, to generate a relocatable ELF object. With GNU LD, this should include '-r' and '-e main' (or _main on some platforms). @@ -327,24 +332,24 @@ examples/elf If you use GCC to link, you make also need to include '-nostdlib' or '-nostartfiles' and '-nodefaultlibs'. - 2. This example also requires genromfs. genromfs can be build as part of the + 3. This example also requires genromfs. genromfs can be build as part of the nuttx toolchain. Or can built from the genromfs sources that can be found at misc/tools/genromfs-0.5.2.tar.gz. In any event, the PATH variable must include the path to the genromfs executable. - 3. ELF size: The ELF files in this example are, be default, quite large + 4. ELF size: The ELF files in this example are, be default, quite large because they include a lot of "build garbage". You can greatly reduce the size of the ELF binaries are using the 'objcopy --strip-unneeded' command to remove un-necessary information from the ELF files. - 4. Simulator. You cannot use this example with the the NuttX simulator on + 5. Simulator. You cannot use this example with the the NuttX simulator on Cygwin. That is because the Cygwin GCC does not generate ELF file but rather some Windows-native binary format. If you really want to do this, you can create a NuttX x86 buildroot toolchain and use that be build the ELF executables for the ROMFS file system. - 5. Linker scripts. You might also want to use a linker scripts to combine + 6. Linker scripts. You might also want to use a linker scripts to combine sections better. An example linker script is at nuttx/binfmt/libelf/gnu-elf.ld. That example might have to be tuned for your particular linker output to position additional sections correctly. The GNU LD LDELFFLAGS then might diff --git a/apps/examples/elf/Makefile b/apps/examples/elf/Makefile index 23a6bcb6fe..ea483e7a14 100644 --- a/apps/examples/elf/Makefile +++ b/apps/examples/elf/Makefile @@ -39,29 +39,29 @@ include $(APPDIR)/Make.defs # ELF Example -ASRCS = -CSRCS = elf_main.c +ASRCS = +CSRCS = elf_main.c symtab.c -AOBJS = $(ASRCS:.S=$(OBJEXT)) -COBJS = $(CSRCS:.c=$(OBJEXT)) +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) ifeq ($(WINTOOL),y) - BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = "$(APPDIR)/libapps$(LIBEXT)" + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif -ROOTDEPPATH = --dep-path . +ROOTDEPPATH = --dep-path . --dep-path tests -# Common build +# Build targets -VPATH = +VPATH = tests all: .built -.PHONY: headers clean_tests clean depend disclean +.PHONY: really_build clean_tests clean depend disclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -69,15 +69,21 @@ $(AOBJS): %$(OBJEXT): %.S $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) -headers: - @$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) +# This is a little messy. The build is broken into two pieces: (1) the +# tests/ subdir build that auto-generates several files, and (2) the real +# build. This is done because we need a fresh build context after auto- +# generating the source files. -.built: headers $(OBJS) +really_build: $(OBJS) @( for obj in $(OBJS) ; do \ $(call ARCHIVE, $(BIN), $${obj}); \ done ; ) @touch .built +.built: + @$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) + @$(MAKE) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" really_build + context: # We can't make dependencies in this directory because the required diff --git a/apps/examples/elf/elf_main.c b/apps/examples/elf/elf_main.c index 3a6eae9d9e..23a6b2d212 100644 --- a/apps/examples/elf/elf_main.c +++ b/apps/examples/elf/elf_main.c @@ -52,10 +52,10 @@ #include #include #include +#include #include "tests/romfs.h" #include "tests/dirlist.h" -#include "tests/symtab.h" /**************************************************************************** * Definitions @@ -134,6 +134,13 @@ static const char delimiter[] = static char path[128]; +/**************************************************************************** + * Symbols from Auto-Generated Code + ****************************************************************************/ + +extern const struct symtab_s exports[]; +extern const int nexports; + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -207,7 +214,7 @@ int elf_main(int argc, char *argv[]) bin.filename = path; bin.exports = exports; - bin.nexports = NEXPORTS; + bin.nexports = nexports; ret = load_module(&bin); if (ret < 0) diff --git a/apps/examples/elf/tests/Makefile b/apps/examples/elf/tests/Makefile index c4a0eec4ca..f834f6c780 100644 --- a/apps/examples/elf/tests/Makefile +++ b/apps/examples/elf/tests/Makefile @@ -34,35 +34,53 @@ ############################################################################ # Most of these do no build yet -SUBDIRS = errno hello hello++ longjmp mutex pthread signal task struct + +ALL_SUBDIRS = errno hello hello++ longjmp mutex pthread signal task struct +BUILD_SUBDIRS = errno hello task struct + +ifeq ($(CONFIG_HAVE_CXX),y) +BUILD_SUBDIRS += hello++ +endif + +ifeq ($(CONFIG_EXAMPLES_ELF_LONGJMP),y) +BUILD_SUBDIRS += longjmp +endif + +ifneq ($(CONFIG_DISABLE_PTHREAD),y) +BUILD_SUBDIRS += mutex pthread +endif + +ifneq ($(CONFIG_DISABLE_SIGNALS),y) +BUILD_SUBDIRS += signal +endif ELF_DIR = $(APPDIR)/examples/elf TESTS_DIR = $(ELF_DIR)/tests ROMFS_DIR = $(TESTS_DIR)/romfs ROMFS_IMG = $(TESTS_DIR)/romfs.img ROMFS_HDR = $(TESTS_DIR)/romfs.h -ROMFS_DIRLIST = $(TESTS_DIR)/dirlist.h -SYMTAB = $(TESTS_DIR)/symtab.h +DIRLIST_HDR = $(TESTS_DIR)/dirlist.h +SYMTAB_SRC = $(TESTS_DIR)/symtab.c define DIR_template $(1)_$(2): @$(MAKE) -C $(1) $(3) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" ROMFS_DIR="$(ROMFS_DIR)" CROSSDEV=$(CROSSDEV) endef -all: $(ROMFS_HDR) $(ROMFS_DIRLIST) $(SYMTAB) +all: $(ROMFS_HDR) $(DIRLIST_HDR) $(SYMTAB_SRC) .PHONY: all build clean install populate -$(foreach DIR, $(SUBDIRS), $(eval $(call DIR_template,$(DIR),build, all))) -$(foreach DIR, $(SUBDIRS), $(eval $(call DIR_template,$(DIR),clean,clean))) -$(foreach DIR, $(SUBDIRS), $(eval $(call DIR_template,$(DIR),install,install))) +$(foreach DIR, $(BUILD_SUBDIRS), $(eval $(call DIR_template,$(DIR),build, all))) +$(foreach DIR, $(ALL_SUBDIRS), $(eval $(call DIR_template,$(DIR),clean,clean))) +$(foreach DIR, $(BUILD_SUBDIRS), $(eval $(call DIR_template,$(DIR),install,install))) # Build program(s) in each sud-directory -build: $(foreach DIR, $(SUBDIRS), $(DIR)_build) +build: $(foreach DIR, $(BUILD_SUBDIRS), $(DIR)_build) # Install each program in the romfs directory -install: $(foreach DIR, $(SUBDIRS), $(DIR)_install) +install: $(foreach DIR, $(BUILD_SUBDIRS), $(DIR)_install) # Create the romfs directory @@ -85,16 +103,16 @@ $(ROMFS_HDR) : $(ROMFS_IMG) # Create the dirlist.h header file from the romfs directory -$(ROMFS_DIRLIST) : populate +$(DIRLIST_HDR) : populate @$(TESTS_DIR)/mkdirlist.sh $(ROMFS_DIR) >$@ # Create the exported symbol table list from the derived *-thunk.S files -$(SYMTAB): build - @$(TESTS_DIR)/mksymtab.sh $(TESTS_DIR) >$@ +$(SYMTAB_SRC): build + @$(TESTS_DIR)/mksymtab.sh -t varlist.tmp $(ROMFS_DIR) >$@ # Clean each subdirectory -clean: $(foreach DIR, $(SUBDIRS), $(DIR)_clean) - @rm -f $(ROMFS_HDR) $(ROMFS_IMG) $(SYMTAB) +clean: $(foreach DIR, $(ALL_SUBDIRS), $(DIR)_clean) + @rm -f $(ROMFS_HDR) $(ROMFS_IMG) $(SYMTAB_SRC) varlist.tmp @rm -rf $(ROMFS_DIR) diff --git a/apps/examples/elf/tests/errno/Makefile b/apps/examples/elf/tests/errno/Makefile index 3c299b16df..92cff9e12f 100644 --- a/apps/examples/elf/tests/errno/Makefile +++ b/apps/examples/elf/tests/errno/Makefile @@ -45,7 +45,7 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CFLAGS) $< -o $@ + @$(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" diff --git a/apps/examples/elf/tests/hello/Makefile b/apps/examples/elf/tests/hello/Makefile index c3a3dacaf1..e1c396c3c7 100644 --- a/apps/examples/elf/tests/hello/Makefile +++ b/apps/examples/elf/tests/hello/Makefile @@ -45,7 +45,7 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CFLAGS) $< -o $@ + @$(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" diff --git a/apps/examples/elf/tests/longjmp/Makefile b/apps/examples/elf/tests/longjmp/Makefile index d737718e05..0cafe05e37 100644 --- a/apps/examples/elf/tests/longjmp/Makefile +++ b/apps/examples/elf/tests/longjmp/Makefile @@ -45,7 +45,7 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CFLAGS) $< -o $@ + @$(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" diff --git a/apps/examples/elf/tests/mksymtab.sh b/apps/examples/elf/tests/mksymtab.sh index fa1a2d0302..56be10f73d 100755 --- a/apps/examples/elf/tests/mksymtab.sh +++ b/apps/examples/elf/tests/mksymtab.sh @@ -1,6 +1,24 @@ #!/bin/bash -usage="Usage: %0 " +usage="Usage: $0 [-t ] " + +# Check for the optional tempory file name + +tmpfile=varlist.tmp +if [ "X${1}" = "X-t" ]; then + shift + tmpfile=$1 + shift + + if [ -z "$tmpfile" ]; then + echo "ERROR: Missing " + echo "" + echo $usage + exit 1 + fi +fi + +# Check for the required ROMFS directory path dir=$1 if [ -z "$dir" ]; then @@ -17,23 +35,33 @@ if [ ! -d "$dir" ]; then exit 1 fi -varlist=`find $dir -name "*-thunk.S"| xargs grep -h asciz | cut -f3 | sort | uniq` +# Extract all of the undefined symbols from the ELF files and create a +# list of sorted, unique undefined variable names. -echo "#ifndef __EXAMPLES_ELF_TESTS_SYMTAB_H" -echo "#define __EXAMPLES_ELF_TESTS_SYMTAB_H" -echo "" +varlist=`find ${dir} -executable -type f | xargs nm | fgrep ' U ' | sed -e "s/^[ ]*//g" | cut -d' ' -f2 | sort | uniq` + +# Now output the symbol table as a structure in a C source file. All +# undefined symbols are declared as void* types. If the toolchain does +# any kind of checking for function vs. data objects, then this could +# faile + +echo "#include " echo "#include " echo "" -echo "static const struct symtab_s exports[] = " + +for var in $varlist; do + echo "extern void *${var};" +done + +echo "" +echo "const struct symtab_s exports[] = " echo "{" -for string in $varlist; do - var=`echo $string | sed -e "s/\"//g"` - echo " {$string, $var}," +for var in $varlist; do + echo " {\"${var}\", &${var}}," done echo "};" -echo "#define NEXPORTS (sizeof(exports)/sizeof(struct symtab_s))" echo "" -echo "#endif /* __EXAMPLES_ELF_TESTS_SYMTAB_H */" +echo "const int nexports = sizeof(exports) / sizeof(struct symtab_s);" diff --git a/apps/examples/elf/tests/mutex/Makefile b/apps/examples/elf/tests/mutex/Makefile index 7f0a5493e9..efce216d87 100644 --- a/apps/examples/elf/tests/mutex/Makefile +++ b/apps/examples/elf/tests/mutex/Makefile @@ -45,7 +45,7 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CFLAGS) $< -o $@ + @$(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" diff --git a/apps/examples/elf/tests/pthread/Makefile b/apps/examples/elf/tests/pthread/Makefile index 8db290e6ea..134fabe01a 100644 --- a/apps/examples/elf/tests/pthread/Makefile +++ b/apps/examples/elf/tests/pthread/Makefile @@ -45,7 +45,7 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CFLAGS) $< -o $@ + @$(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" diff --git a/apps/examples/elf/tests/signal/Makefile b/apps/examples/elf/tests/signal/Makefile index 4338aa48da..08710aeaa5 100644 --- a/apps/examples/elf/tests/signal/Makefile +++ b/apps/examples/elf/tests/signal/Makefile @@ -45,7 +45,7 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CFLAGS) $< -o $@ + @$(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" diff --git a/apps/examples/elf/tests/signal/signal.c b/apps/examples/elf/tests/signal/signal.c index 0d2e9e6cc2..b40da7a864 100644 --- a/apps/examples/elf/tests/signal/signal.c +++ b/apps/examples/elf/tests/signal/signal.c @@ -38,6 +38,7 @@ ****************************************************************************/ #include + #include #include #include @@ -66,22 +67,7 @@ static int sigusr2_rcvd = 0; ****************************************************************************/ /**************************************************************************** - * Name: sigusr1_sighandler - ****************************************************************************/ - -/* NOTE: it is necessary for functions that are referred to by function pointers - * pointer to be declared with global scope (at least for ARM). Otherwise, - * a relocation type that is not supported by ELF is generated by GCC. - */ - -void sigusr1_sighandler(int signo) -{ - printf("sigusr1_sighandler: Received SIGUSR1, signo=%d\n", signo); - sigusr1_rcvd = 1; -} - -/**************************************************************************** - * Name: sigusr2_sigaction + * Name: siguser_action ***************************************************************************/ /* NOTE: it is necessary for functions that are referred to by function pointers @@ -89,50 +75,33 @@ void sigusr1_sighandler(int signo) * a relocation type that is not supported by ELF is generated by GCC. */ -#ifdef __USE_POSIX199309 -void sigusr2_sigaction(int signo, siginfo_t *siginfo, void *arg) +void siguser_action(int signo, siginfo_t *siginfo, void *arg) { - printf("sigusr2_sigaction: Received SIGUSR2, signo=%d siginfo=%p arg=%p\n", + printf("siguser_action: Received signo=%d siginfo=%p arg=%p\n", signo, siginfo, arg); -#ifdef HAVE_SIGQUEUE + if (signo == SIGUSR1) + { + printf(" SIGUSR1 received\n"); + sigusr2_rcvd = 1; + } + else if (signo == SIGUSR2) + { + printf(" SIGUSR2 received\n"); + sigusr1_rcvd = 2; + } + else + { + printf(" ERROR: Unexpected signal\n"); + } + if (siginfo) { + printf("siginfo:\n"); printf(" si_signo = %d\n", siginfo->si_signo); - printf(" si_errno = %d\n", siginfo->si_errno); printf(" si_code = %d\n", siginfo->si_code); - printf(" si_pid = %d\n", siginfo->si_pid); - printf(" si_uid = %d\n", siginfo->si_uid); - printf(" si_status = %d\n", siginfo->si_status); - printf(" si_utime = %ld\n", (long)siginfo->si_utime); - printf(" si_stime = %ld\n", (long)siginfo->si_stime); printf(" si_value = %d\n", siginfo->si_value.sival_int); - printf(" si_int = %d\n", siginfo->si_int); - printf(" si_ptr = %p\n", siginfo->si_ptr); - printf(" si_addr = %p\n", siginfo->si_addr); - printf(" si_band = %ld\n", siginfo->si_band); - printf(" si_fd = %d\n", siginfo->si_fd); } -#endif - sigusr2_rcvd = 1; -} -#else -void sigusr2_sigaction(int signo) -{ - printf("sigusr2_sigaction: Received SIGUSR2, signo=%d\n", signo); - sigusr2_rcvd = 1; -} - -#endif - -/**************************************************************************** - * Name: sigusr2_sighandler - ****************************************************************************/ - -static void sigusr2_sighandler(int signo) -{ - printf("sigusr2_sighandler: Received SIGUSR2, signo=%d\n", signo); - sigusr2_rcvd = 1; } /**************************************************************************** @@ -146,39 +115,36 @@ static void sigusr2_sighandler(int signo) int main(int argc, char **argv) { struct sigaction act; - struct sigaction oact; - void (*old_sigusr1_sighandler)(int signo); - void (*old_sigusr2_sighandler)(int signo); + struct sigaction oact1; + struct sigaction oact2; pid_t mypid = getpid(); -#if defined(__USE_POSIX199309) && defined(HAVE_SIGQUEUE) - sigval_t sigval; -#endif + union sigval sigval; int status; printf("Setting up signal handlers from pid=%d\n", mypid); - /* Set up so that sigusr1_sighandler will respond to SIGUSR1 */ - - old_sigusr1_sighandler = signal(SIGUSR1, sigusr1_sighandler); - if (old_sigusr1_sighandler == SIG_ERR) - { - fprintf(stderr, "Failed to install SIGUSR1 handler, errno=%d\n", - errno); - exit(1); - } - - printf("Old SIGUSR1 sighandler at %p\n", old_sigusr1_sighandler); - printf("New SIGUSR1 sighandler at %p\n", sigusr1_sighandler); - - /* Set up so that sigusr2_sigaction will respond to SIGUSR2 */ + /* Set up so that siguser_action will respond to SIGUSR1 */ memset(&act, 0, sizeof(struct sigaction)); - act.sa_sigaction = sigusr2_sigaction; + act.sa_sigaction = siguser_action; act.sa_flags = SA_SIGINFO; (void)sigemptyset(&act.sa_mask); - status = sigaction(SIGUSR2, &act, &oact); + status = sigaction(SIGUSR1, &act, &oact1); + if (status != 0) + { + fprintf(stderr, "Failed to install SIGUSR1 handler, errno=%d\n", + errno); + exit(2); + } + + printf("Old SIGUSR1 sighandler at %p\n", oact1.sa_handler); + printf("New SIGUSR1 sighandler at %p\n", siguser_action); + + /* Set up so that siguser_action will respond to SIGUSR2 */ + + status = sigaction(SIGUSR2, &act, &oact2); if (status != 0) { fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n", @@ -186,18 +152,19 @@ int main(int argc, char **argv) exit(2); } - printf("Old SIGUSR2 sighandler at %p\n", oact.sa_handler); - printf("New SIGUSR2 sighandler at %p\n", sigusr2_sigaction); - printf("Raising SIGUSR1 from pid=%d\n", mypid); + printf("Old SIGUSR2 sighandler at %p\n", oact2.sa_handler); + printf("New SIGUSR2 sighandler at %p\n", siguser_action); + printf("Raising SIGUSR1 from pid=%d\n", mypid); fflush(stdout); usleep(SHORT_DELAY); - /* Send SIGUSR1 to ourselves via raise() */ + /* Send SIGUSR1 to ourselves via kill() */ - status = raise(SIGUSR1); + printf("Kill-ing SIGUSR1 from pid=%d\n", mypid); + status = kill(0, SIGUSR1); if (status != 0) { - fprintf(stderr, "Failed to raise SIGUSR1, errno=%d\n", errno); + fprintf(stderr, "Failed to kill SIGUSR1, errno=%d\n", errno); exit(3); } @@ -211,14 +178,14 @@ int main(int argc, char **argv) fprintf(stderr, "SIGUSR1 not received\n"); exit(4); } + sigusr1_rcvd = 0; /* Send SIGUSR2 to ourselves */ - printf("Killing SIGUSR2 from pid=%d\n", mypid); + printf("sigqueue-ing SIGUSR2 from pid=%d\n", mypid); fflush(stdout); usleep(SHORT_DELAY); -#if defined(__USE_POSIX199309) && defined(HAVE_SIGQUEUE) /* Send SIGUSR2 to ourselves via sigqueue() */ sigval.sival_int = 87; @@ -230,20 +197,8 @@ int main(int argc, char **argv) } usleep(SHORT_DELAY); - printf("SIGUSR2 queued from pid=%d, sigval=97\n", mypid); -#else - /* Send SIGUSR2 to ourselves via kill() */ + printf("SIGUSR2 queued from pid=%d, sigval=87\n", mypid); - status = kill(mypid, SIGUSR2); - if (status != 0) - { - fprintf(stderr, "Failed to kill SIGUSR2, errno=%d\n", errno); - exit(5); - } - - usleep(SHORT_DELAY); - printf("SIGUSR2 killed from pid=%d\n", mypid); -#endif /* Verify that SIGUSR2 was received */ if (sigusr2_rcvd == 0) @@ -251,32 +206,33 @@ int main(int argc, char **argv) fprintf(stderr, "SIGUSR2 not received\n"); exit(6); } + sigusr2_rcvd = 0; - /* Remove the sigusr2_sigaction handler and replace the SIGUSR2 + /* Remove the siguser_action handler and replace the SIGUSR2 * handler with sigusr2_sighandler. */ printf("Resetting SIGUSR2 signal handler from pid=%d\n", mypid); - old_sigusr2_sighandler = signal(SIGUSR2, sigusr2_sighandler); - if (old_sigusr2_sighandler == SIG_ERR) + status = sigaction(SIGUSR2, &oact2, &act); + if (status != 0) { - fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n", + fprintf(stderr, "Failed to install SIGUSR1 handler, errno=%d\n", errno); - exit(7); + exit(2); } - printf("Old SIGUSR2 sighandler at %p\n", old_sigusr2_sighandler); - printf("New SIGUSR2 sighandler at %p\n", sigusr2_sighandler); + printf("Old SIGUSR1 sighandler at %p\n", act.sa_handler); + printf("New SIGUSR1 sighandler at %p\n", oact1.sa_handler); - /* Verify that the handler that was removed was sigusr2_sigaction */ + /* Verify that the handler that was removed was siguser_action */ - if ((void*)old_sigusr2_sighandler != (void*)sigusr2_sigaction) + if ((void*)act.sa_handler != (void*)siguser_action) { fprintf(stderr, - "Old SIGUSR2 signhanlder (%p) is not sigusr2_sigation (%p)\n", - old_sigusr2_sighandler, sigusr2_sigaction); + "Old SIGUSR2 signal handler (%p) is not siguser_action (%p)\n", + act.sa_handler, siguser_action); exit(8); } @@ -302,6 +258,7 @@ int main(int argc, char **argv) fprintf(stderr, "SIGUSR2 not received\n"); exit(10); } + sigusr2_rcvd = 0; return 0; diff --git a/apps/examples/elf/tests/struct/Makefile b/apps/examples/elf/tests/struct/Makefile index c15d8fc476..3aa0e4a572 100644 --- a/apps/examples/elf/tests/struct/Makefile +++ b/apps/examples/elf/tests/struct/Makefile @@ -36,7 +36,7 @@ -include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs -CFLAGS += -I. +CELFFLAGS += -I. BIN = struct SRCS = struct_main.c struct_dummy.c @@ -46,7 +46,7 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CFLAGS) $< -o $@ + @$(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" diff --git a/apps/examples/elf/tests/task/Makefile b/apps/examples/elf/tests/task/Makefile index 208b228b3a..63a2eb211c 100644 --- a/apps/examples/elf/tests/task/Makefile +++ b/apps/examples/elf/tests/task/Makefile @@ -45,7 +45,7 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CFLAGS) $< -o $@ + @$(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" diff --git a/apps/examples/nxflat/tests/mksymtab.sh b/apps/examples/nxflat/tests/mksymtab.sh index 4b5347f17f..27abc4b41a 100755 --- a/apps/examples/nxflat/tests/mksymtab.sh +++ b/apps/examples/nxflat/tests/mksymtab.sh @@ -1,6 +1,6 @@ #!/bin/bash -usage="Usage: %0 " +usage="Usage: $0 " dir=$1 if [ -z "$dir" ]; then diff --git a/apps/examples/nxflat/tests/signal/signal.c b/apps/examples/nxflat/tests/signal/signal.c index 2df5baaa24..c5ea6bdcc5 100644 --- a/apps/examples/nxflat/tests/signal/signal.c +++ b/apps/examples/nxflat/tests/signal/signal.c @@ -1,7 +1,7 @@ /**************************************************************************** * examples/nxflat/tests/signal/signal.c * - * 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 @@ -67,73 +67,41 @@ static int sigusr2_rcvd = 0; ****************************************************************************/ /**************************************************************************** - * Name: sigusr1_sighandler - ****************************************************************************/ - -/* NOTE: it is necessary for functions that are referred to by function pointers - * pointer to be declared with global scope (at least for ARM). Otherwise, - * a relocation type that is not supported by NXFLAT is generated by GCC. - */ - -void sigusr1_sighandler(int signo) -{ - printf("sigusr1_sighandler: Received SIGUSR1, signo=%d\n", signo); - sigusr1_rcvd = 1; -} - -/**************************************************************************** - * Name: sigusr2_sigaction + * Name: siguser_action ***************************************************************************/ /* NOTE: it is necessary for functions that are referred to by function pointers * pointer to be declared with global scope (at least for ARM). Otherwise, - * a relocation type that is not supported by NXFLAT is generated by GCC. + * a relocation type that is not supported by ELF is generated by GCC. */ -#ifdef __USE_POSIX199309 -void sigusr2_sigaction(int signo, siginfo_t *siginfo, void *arg) +void siguser_action(int signo, siginfo_t *siginfo, void *arg) { - printf("sigusr2_sigaction: Received SIGUSR2, signo=%d siginfo=%p arg=%p\n", + printf("siguser_action: Received signo=%d siginfo=%p arg=%p\n", signo, siginfo, arg); -#ifdef HAVE_SIGQUEUE + if (signo == SIGUSR1) + { + printf(" SIGUSR1 received\n"); + sigusr2_rcvd = 1; + } + else if (signo == SIGUSR2) + { + printf(" SIGUSR2 received\n"); + sigusr1_rcvd = 2; + } + else + { + printf(" ERROR: Unexpected signal\n"); + } + if (siginfo) { + printf("siginfo:\n"); printf(" si_signo = %d\n", siginfo->si_signo); - printf(" si_errno = %d\n", siginfo->si_errno); printf(" si_code = %d\n", siginfo->si_code); - printf(" si_pid = %d\n", siginfo->si_pid); - printf(" si_uid = %d\n", siginfo->si_uid); - printf(" si_status = %d\n", siginfo->si_status); - printf(" si_utime = %ld\n", (long)siginfo->si_utime); - printf(" si_stime = %ld\n", (long)siginfo->si_stime); printf(" si_value = %d\n", siginfo->si_value.sival_int); - printf(" si_int = %d\n", siginfo->si_int); - printf(" si_ptr = %p\n", siginfo->si_ptr); - printf(" si_addr = %p\n", siginfo->si_addr); - printf(" si_band = %ld\n", siginfo->si_band); - printf(" si_fd = %d\n", siginfo->si_fd); } -#endif - sigusr2_rcvd = 1; -} -#else -void sigusr2_sigaction(int signo) -{ - printf("sigusr2_sigaction: Received SIGUSR2, signo=%d\n", signo); - sigusr2_rcvd = 1; -} - -#endif - -/**************************************************************************** - * Name: sigusr2_sighandler - ****************************************************************************/ - -static void sigusr2_sighandler(int signo) -{ - printf("sigusr2_sighandler: Received SIGUSR2, signo=%d\n", signo); - sigusr2_rcvd = 1; } /**************************************************************************** @@ -147,39 +115,36 @@ static void sigusr2_sighandler(int signo) int main(int argc, char **argv) { struct sigaction act; - struct sigaction oact; - void (*old_sigusr1_sighandler)(int signo); - void (*old_sigusr2_sighandler)(int signo); + struct sigaction oact1; + struct sigaction oact2; pid_t mypid = getpid(); -#if defined(__USE_POSIX199309) && defined(HAVE_SIGQUEUE) - sigval_t sigval; -#endif + union sigval sigval; int status; printf("Setting up signal handlers from pid=%d\n", mypid); - /* Set up so that sigusr1_sighandler will respond to SIGUSR1 */ - - old_sigusr1_sighandler = signal(SIGUSR1, sigusr1_sighandler); - if (old_sigusr1_sighandler == SIG_ERR) - { - fprintf(stderr, "Failed to install SIGUSR1 handler, errno=%d\n", - errno); - exit(1); - } - - printf("Old SIGUSR1 sighandler at %p\n", old_sigusr1_sighandler); - printf("New SIGUSR1 sighandler at %p\n", sigusr1_sighandler); - - /* Set up so that sigusr2_sigaction will respond to SIGUSR2 */ + /* Set up so that siguser_action will respond to SIGUSR1 */ memset(&act, 0, sizeof(struct sigaction)); - act.sa_sigaction = sigusr2_sigaction; + act.sa_sigaction = siguser_action; act.sa_flags = SA_SIGINFO; (void)sigemptyset(&act.sa_mask); - status = sigaction(SIGUSR2, &act, &oact); + status = sigaction(SIGUSR1, &act, &oact1); + if (status != 0) + { + fprintf(stderr, "Failed to install SIGUSR1 handler, errno=%d\n", + errno); + exit(2); + } + + printf("Old SIGUSR1 sighandler at %p\n", oact1.sa_handler); + printf("New SIGUSR1 sighandler at %p\n", siguser_action); + + /* Set up so that siguser_action will respond to SIGUSR2 */ + + status = sigaction(SIGUSR2, &act, &oact2); if (status != 0) { fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n", @@ -187,18 +152,19 @@ int main(int argc, char **argv) exit(2); } - printf("Old SIGUSR2 sighandler at %p\n", oact.sa_handler); - printf("New SIGUSR2 sighandler at %p\n", sigusr2_sigaction); - printf("Raising SIGUSR1 from pid=%d\n", mypid); + printf("Old SIGUSR2 sighandler at %p\n", oact2.sa_handler); + printf("New SIGUSR2 sighandler at %p\n", siguser_action); + printf("Raising SIGUSR1 from pid=%d\n", mypid); fflush(stdout); usleep(SHORT_DELAY); - /* Send SIGUSR1 to ourselves via raise() */ + /* Send SIGUSR1 to ourselves via kill() */ - status = raise(SIGUSR1); + printf("Kill-ing SIGUSR1 from pid=%d\n", mypid); + status = kill(0, SIGUSR1); if (status != 0) { - fprintf(stderr, "Failed to raise SIGUSR1, errno=%d\n", errno); + fprintf(stderr, "Failed to kill SIGUSR1, errno=%d\n", errno); exit(3); } @@ -212,14 +178,14 @@ int main(int argc, char **argv) fprintf(stderr, "SIGUSR1 not received\n"); exit(4); } + sigusr1_rcvd = 0; /* Send SIGUSR2 to ourselves */ - printf("Killing SIGUSR2 from pid=%d\n", mypid); + printf("sigqueue-ing SIGUSR2 from pid=%d\n", mypid); fflush(stdout); usleep(SHORT_DELAY); -#if defined(__USE_POSIX199309) && defined(HAVE_SIGQUEUE) /* Send SIGUSR2 to ourselves via sigqueue() */ sigval.sival_int = 87; @@ -231,20 +197,8 @@ int main(int argc, char **argv) } usleep(SHORT_DELAY); - printf("SIGUSR2 queued from pid=%d, sigval=97\n", mypid); -#else - /* Send SIGUSR2 to ourselves via kill() */ + printf("SIGUSR2 queued from pid=%d, sigval=87\n", mypid); - status = kill(mypid, SIGUSR2); - if (status != 0) - { - fprintf(stderr, "Failed to kill SIGUSR2, errno=%d\n", errno); - exit(5); - } - - usleep(SHORT_DELAY); - printf("SIGUSR2 killed from pid=%d\n", mypid); -#endif /* Verify that SIGUSR2 was received */ if (sigusr2_rcvd == 0) @@ -252,32 +206,33 @@ int main(int argc, char **argv) fprintf(stderr, "SIGUSR2 not received\n"); exit(6); } + sigusr2_rcvd = 0; - /* Remove the sigusr2_sigaction handler and replace the SIGUSR2 + /* Remove the siguser_action handler and replace the SIGUSR2 * handler with sigusr2_sighandler. */ printf("Resetting SIGUSR2 signal handler from pid=%d\n", mypid); - old_sigusr2_sighandler = signal(SIGUSR2, sigusr2_sighandler); - if (old_sigusr2_sighandler == SIG_ERR) + status = sigaction(SIGUSR2, &oact2, &act); + if (status != 0) { - fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n", + fprintf(stderr, "Failed to install SIGUSR1 handler, errno=%d\n", errno); - exit(7); + exit(2); } - printf("Old SIGUSR2 sighandler at %p\n", old_sigusr2_sighandler); - printf("New SIGUSR2 sighandler at %p\n", sigusr2_sighandler); + printf("Old SIGUSR1 sighandler at %p\n", act.sa_handler); + printf("New SIGUSR1 sighandler at %p\n", oact1.sa_handler); - /* Verify that the handler that was removed was sigusr2_sigaction */ + /* Verify that the handler that was removed was siguser_action */ - if ((void*)old_sigusr2_sighandler != (void*)sigusr2_sigaction) + if ((void*)act.sa_handler != (void*)siguser_action) { fprintf(stderr, - "Old SIGUSR2 signhanlder (%p) is not sigusr2_sigation (%p)\n", - old_sigusr2_sighandler, sigusr2_sigaction); + "Old SIGUSR2 signal handler (%p) is not siguser_action (%p)\n", + act.sa_handler, siguser_action); exit(8); } @@ -303,6 +258,7 @@ int main(int argc, char **argv) fprintf(stderr, "SIGUSR2 not received\n"); exit(10); } + sigusr2_rcvd = 0; return 0; diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 7c4a5a8cd8..a80e5009a8 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3522,3 +3522,5 @@ * configs/stm32f4discovery/elf and configs/stm32f4discovery/scripts/gnu-elf.ld Add a configuration for testing the ARM ELF loader. * binfmt/libelf: Can't use fstat(). NuttX does not yet support it. Damn! + * binfmt/libelf: The basic ELF module execution appears fully functional. + diff --git a/nuttx/arch/arm/src/armv7-m/up_elf.c b/nuttx/arch/arm/src/armv7-m/up_elf.c index 5f77470fa1..202c902b4b 100644 --- a/nuttx/arch/arm/src/armv7-m/up_elf.c +++ b/nuttx/arch/arm/src/armv7-m/up_elf.c @@ -218,8 +218,8 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, * The branch target is encoded in these bits: * * S = upper_insn[10] - * imm10 = upper_insn[9:0] - * imm11 = lower_insn[10:0] + * imm10 = upper_insn[0:9] + * imm11 = lower_insn[0:10] * J1 = lower_insn[13] * J2 = lower_insn[11] */ @@ -227,7 +227,7 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, upper_insn = (uint32_t)(*(uint16_t*)addr); lower_insn = (uint32_t)(*(uint16_t*)(addr + 2)); - bvdbg("Performing JUMP24 [%d] link at addr=%08lx [%04x %04x] to sym=%p st_value=%08lx\n", + bvdbg("Performing THM_JUMP24 [%d] link at addr=%08lx [%04x %04x] to sym=%p st_value=%08lx\n", ELF32_R_TYPE(rel->r_info), (long)addr, (int)upper_insn, (int)lower_insn, sym, (long)sym->st_value); @@ -235,9 +235,9 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, * * offset[24] = S * offset[23] = ~(J1 ^ S) - * offset[22 = ~(J2 ^ S)] - * offset[21:12] = imm10 - * offset[11:1] = imm11 + * offset[22] = ~(J2 ^ S)] + * offset[12:21] = imm10 + * offset[1:11] = imm11 * offset[0] = 0 */ @@ -245,11 +245,12 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, J1 = (lower_insn >> 13) & 1; J2 = (lower_insn >> 11) & 1; - offset = (S << 24) | - ((~(J1 ^ S) & 1) << 23) | - ((~(J2 ^ S) & 1) << 22) | - ((upper_insn & 0x03ff) << 12) | - ((lower_insn & 0x07ff) << 1); + offset = (S << 24) | /* S - > offset[24] */ + ((~(J1 ^ S) & 1) << 23) | /* J1 -> offset[23] */ + ((~(J2 ^ S) & 1) << 22) | /* J2 -> offset[22] */ + ((upper_insn & 0x03ff) << 12) | /* imm10 -> offset[12:21] */ + ((lower_insn & 0x07ff) << 1); /* imm11 -> offset[1:11] */ + /* 0 -> offset[0] */ /* Sign extend */ @@ -374,31 +375,31 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 * +---+---------------------------------------------------------+ * |OP | | 32-Bit Instructions - * +---+--+-------+--------------+-------------------------------+ - * |0 |1 | imm3 | Rd | imm8 | MOVT Instruction - * +---+--+-------+--------------+-------------------------------+ + * +---+----------+--------------+-------------------------------+ + * |0 | imm3 | Rd | imm8 | MOVT Instruction + * +---+----------+--------------+-------------------------------+ * * The 16-bit immediate value is encoded in these bits: * * i = imm16[11] = upper_insn[10] * imm4 = imm16[12:15] = upper_insn[3:0] - * imm3 = imm16[9:11] = lower_insn[14:12] - * imm8 = imm16[0:8] = lower_insn[7:0] + * imm3 = imm16[8:10] = lower_insn[14:12] + * imm8 = imm16[0:7] = lower_insn[7:0] */ upper_insn = (uint32_t)(*(uint16_t*)addr); lower_insn = (uint32_t)(*(uint16_t*)(addr + 2)); - bvdbg("Performing MOVx [%d] link at addr=%08lx [%04x %04x] to sym=%p st_value=%08lx\n", + bvdbg("Performing THM_MOVx [%d] link at addr=%08lx [%04x %04x] to sym=%p st_value=%08lx\n", ELF32_R_TYPE(rel->r_info), (long)addr, (int)upper_insn, (int)lower_insn, sym, (long)sym->st_value); /* Extract the 16-bit offset from the 32-bit instruction */ - offset = ((upper_insn & 0x000f) << 12) | - ((upper_insn & 0x0400) << 1) | - ((lower_insn & 0x7000) >> 4) | - (lower_insn & 0x00ff); + offset = ((upper_insn & 0x000f) << 12) | /* imm4 -> imm16[8:10] */ + ((upper_insn & 0x0400) << 1) | /* i -> imm16[11] */ + ((lower_insn & 0x7000) >> 4) | /* imm3 -> imm16[8:10] */ + (lower_insn & 0x00ff); /* imm8 -> imm16[0:7] */ /* Sign extend */ @@ -406,8 +407,8 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, /* And perform the relocation */ - bvdbg(" S=%d J1=%d J2=%d offset=%08lx branch target=%08lx\n", - S, J1, J2, (long)offset, offset + sym->st_value); + bvdbg(" offset=%08lx branch target=%08lx\n", + (long)offset, offset + sym->st_value); offset += sym->st_value; diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 5fd0ae7a26..acfac81aa0 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -636,9 +636,11 @@ config ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG config STM32_CCMEXCLUDE bool "Exclude CCM SRAM from the heap" depends on STM32_STM32F20XX || STM32_STM32F40XX - default y if ARCH_DMA + default y if ARCH_DMA || ELF ---help--- - Exclude CCM SRAM from the HEAP because it cannot be used for DMA. + Exclude CCM SRAM from the HEAP because (1) it cannot be used for DMA + and (2) it appears to be impossible to execute ELF modules from CCM + RAM. config STM32_FSMC_SRAM bool "External SRAM on FSMC" diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c index f41b5a0b6f..54ea8f1f04 100644 --- a/nuttx/binfmt/libelf/libelf_bind.c +++ b/nuttx/binfmt/libelf/libelf_bind.c @@ -142,7 +142,10 @@ static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx, int ret; int i; - /* Examine each relocation in the section */ + /* Examine each relocation in the section. 'relsec' is the section + * containing the relations. 'dstsec' is the section containing the data + * to be relocated. + */ for (i = 0; i < relsec->sh_size / sizeof(Elf32_Rel); i++) { diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c index e1b9f73d69..fa4b7983cb 100644 --- a/nuttx/binfmt/libelf/libelf_init.c +++ b/nuttx/binfmt/libelf/libelf_init.c @@ -154,6 +154,7 @@ int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo) /* Get the length of the file. */ ret = elf_filelen(loadinfo, filename); + if (ret < 0) { bdbg("elf_filelen failed: %d\n", ret); return ret; diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index d1a55daa9d..e8f0ae166b 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -1007,6 +1007,10 @@ Where is one of the following: 3. By default, this project assumes that you are *NOT* using the DFU bootloader. + 4. This configuration requires that you have the genromfs tool installed + on your system and that you have the full path to the installed genromfs + executable in PATH variable (see apps/examples/README.txt) + ostest: ------ This configuration directory, performs a simple OS test using diff --git a/nuttx/configs/stm32f4discovery/elf/Make.defs b/nuttx/configs/stm32f4discovery/elf/Make.defs index 7f5be08f06..c64102d174 100644 --- a/nuttx/configs/stm32f4discovery/elf/Make.defs +++ b/nuttx/configs/stm32f4discovery/elf/Make.defs @@ -160,6 +160,7 @@ LDNXFLATFLAGS = -e main -s 2048 # ELF module definitions +CELFFLAGS = $(CFLAGS) -mlong-calls LDELFFLAGS = -r -e main ifeq ($(WINTOOL),y) LDELFFLAGS += -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/gnu-elf.ld}" diff --git a/nuttx/configs/stm32f4discovery/elf/defconfig b/nuttx/configs/stm32f4discovery/elf/defconfig index dd5bd28298..6d72e4a9ee 100644 --- a/nuttx/configs/stm32f4discovery/elf/defconfig +++ b/nuttx/configs/stm32f4discovery/elf/defconfig @@ -179,7 +179,7 @@ CONFIG_STM32_USART2=y CONFIG_STM32_JTAG_SW_ENABLE=y # CONFIG_STM32_FORCEPOWER is not set # CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set -# CONFIG_STM32_CCMEXCLUDE is not set +CONFIG_STM32_CCMEXCLUDE=y # # USB Host Configuration @@ -251,7 +251,7 @@ CONFIG_SDCLONE_DISABLE=y # CONFIG_SCHED_WAITPID is not set # CONFIG_SCHED_ATEXIT is not set # CONFIG_SCHED_ONEXIT is not set -CONFIG_USER_ENTRYPOINT="ostest_main" +CONFIG_USER_ENTRYPOINT="elf_main" CONFIG_DISABLE_OS_API=y # CONFIG_DISABLE_CLOCK is not set # CONFIG_DISABLE_POSIX_TIMERS is not set @@ -387,6 +387,7 @@ CONFIG_ELF_ALIGN_LOG2=2 CONFIG_ELF_STACKSIZE=2048 CONFIG_ELF_BUFFERSIZE=128 CONFIG_ELF_BUFFERINCR=32 +# CONFIG_ELF_CONSTRUCTORS is not set CONFIG_SYMTAB_ORDEREDBYNAME=y # @@ -409,7 +410,7 @@ CONFIG_ARCH_LOWPUTC=y CONFIG_LIB_SENDFILE_BUFSIZE=512 # CONFIG_ARCH_ROMGETC is not set # CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set -# CONFIG_HAVE_CXX is not set +CONFIG_HAVE_CXX=y # CONFIG_HAVE_CXXINITIALIZE is not set # CONFIG_CXX_NEWLONG is not set From 54aa38368612e70a846674ceae13fe19677c01dc Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 27 Oct 2012 13:57:17 +0000 Subject: [PATCH 035/206] Support for relays on the Shenzhou board (Darcy Gong) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5266 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/shenzhou/include/board.h | 22 ++ nuttx/configs/shenzhou/src/Makefile | 4 + .../configs/shenzhou/src/shenzhou-internal.h | 10 +- nuttx/configs/shenzhou/src/up_relays.c | 276 ++++++++++++++++++ nuttx/configs/stm32f4discovery/README.txt | 7 +- 5 files changed, 316 insertions(+), 3 deletions(-) create mode 100644 nuttx/configs/shenzhou/src/up_relays.c diff --git a/nuttx/configs/shenzhou/include/board.h b/nuttx/configs/shenzhou/include/board.h index 2897ac2198..b0fc1b52d5 100644 --- a/nuttx/configs/shenzhou/include/board.h +++ b/nuttx/configs/shenzhou/include/board.h @@ -422,6 +422,28 @@ EXTERN void stm32_setleds(uint8_t ledset); EXTERN void stm32_lcdclear(uint16_t color); +/************************************************************************************ + * Relay control functions + * + * Description: + * Non-standard fucntions for relay control from the Shenzhou board. + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_RELAYS +EXTERN void up_relaysinit(void); +EXTERN void relays_setstat(int relays,bool stat); +EXTERN bool relays_getstat(int relays); +EXTERN void relays_setstats(uint32_t relays_stat); +EXTERN uint32_t relays_getstats(void); +EXTERN void relays_onoff(int relays,uint32_t mdelay); +EXTERN void relays_onoffs(uint32_t relays_stat,uint32_t mdelay); +EXTERN void relays_resetmode(int relays); +EXTERN void relays_powermode(int relays); +EXTERN void relays_resetmodes(uint32_t relays_stat); +EXTERN void relays_powermodes(uint32_t relays_stat); +#endif + #undef EXTERN #if defined(__cplusplus) } diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile index 0082a526a6..14dcd9fe68 100644 --- a/nuttx/configs/shenzhou/src/Makefile +++ b/nuttx/configs/shenzhou/src/Makefile @@ -56,6 +56,10 @@ ifeq ($(CONFIG_ARCH_BUTTONS),y) CSRCS += up_buttons.c endif +ifeq ($(CONFIG_ARCH_RELAYS),y) +CSRCS += up_relays.c +endif + ifeq ($(CONFIG_STM32_OTGFS),y) CSRCS += up_usb.c endif diff --git a/nuttx/configs/shenzhou/src/shenzhou-internal.h b/nuttx/configs/shenzhou/src/shenzhou-internal.h index f9cebc5e38..862a0250dc 100644 --- a/nuttx/configs/shenzhou/src/shenzhou-internal.h +++ b/nuttx/configs/shenzhou/src/shenzhou-internal.h @@ -387,10 +387,16 @@ * 58 PD11 SD_CS Active low: Pulled high (See also TFT LCD CN13, pin 32) */ -#define GPIO_SD_CD (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN14) -#define GPIO_SD_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ +#define GPIO_SD_CD (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN14) +#define GPIO_SD_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11) +/* Relays */ + +#define NUM_RELAYS 1 +#define GPIO_RELAYS_R00 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN0) + /**************************************************************************************************** * Public Types ****************************************************************************************************/ diff --git a/nuttx/configs/shenzhou/src/up_relays.c b/nuttx/configs/shenzhou/src/up_relays.c new file mode 100644 index 0000000000..075c7d5903 --- /dev/null +++ b/nuttx/configs/shenzhou/src/up_relays.c @@ -0,0 +1,276 @@ +/**************************************************************************** + * configs/shenzhou/src/up_relays.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 + +#include +#include "shenzhou-internal.h" +#include + +#ifdef CONFIG_ARCH_RELAYS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define RELAYS_MIN_RESET_TIME 5 +#define RELAYS_RESET_MTIME 5 +#define RELAYS_POWER_MTIME 50 + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static uint32_t g_relays_stat = 0; + +static const uint16_t g_relays[NUM_RELAYS] = +{ + GPIO_RELAYS_R00 +#ifdef GPIO_RELAYS_R01 + , GPIO_RELAYS_R01 +#endif +#ifdef GPIO_RELAYS_R02 + , GPIO_RELAYS_R02 +#endif +#ifdef GPIO_RELAYS_R03 + , GPIO_RELAYS_R03 +#endif +#ifdef GPIO_RELAYS_R04 + , GPIO_RELAYS_R04 +#endif +#ifdef GPIO_RELAYS_R05 + , GPIO_RELAYS_R05 +#endif +#ifdef GPIO_RELAYS_R06 + , GPIO_RELAYS_R06 +#endif +#ifdef GPIO_RELAYS_R07 + , GPIO_RELAYS_R07 +#endif +#ifdef GPIO_RELAYS_R08 + , GPIO_RELAYS_R08 +#endif +#ifdef GPIO_RELAYS_R09 + , GPIO_RELAYS_R09 +#endif +#ifdef GPIO_RELAYS_R10 + , GPIO_RELAYS_R10 +#endif +#ifdef GPIO_RELAYS_R11 + , GPIO_RELAYS_R11 +#endif +#ifdef GPIO_RELAYS_R12 + , GPIO_RELAYS_R12 +#endif +#ifdef GPIO_RELAYS_R13 + , GPIO_RELAYS_R13 +#endif +#ifdef GPIO_RELAYS_R14 + , GPIO_RELAYS_R14 +#endif +#ifdef GPIO_RELAYS_R15 + , GPIO_RELAYS_R15 +#endif +#ifdef GPIO_RELAYS_R16 + , GPIO_RELAYS_R16 +#endif +#ifdef GPIO_RELAYS_R17 + , GPIO_RELAYS_R17 +#endif +#ifdef GPIO_RELAYS_R18 + , GPIO_RELAYS_R18 +#endif +#ifdef GPIO_RELAYS_R19 + , GPIO_RELAYS_R19 +#endif +#ifdef GPIO_RELAYS_R20 + , GPIO_RELAYS_R20 +#endif +#ifdef GPIO_RELAYS_R21 + , GPIO_RELAYS_R21 +#endif +#ifdef GPIO_RELAYS_R22 + , GPIO_RELAYS_R22 +#endif +#ifdef GPIO_RELAYS_R23 + , GPIO_RELAYS_R23 +#endif +#ifdef GPIO_RELAYS_R24 + , GPIO_RELAYS_R24 +#endif +#ifdef GPIO_RELAYS_R25 + , GPIO_RELAYS_R25 +#endif +#ifdef GPIO_RELAYS_R26 + , GPIO_RELAYS_R26 +#endif +#ifdef GPIO_RELAYS_R27 + , GPIO_RELAYS_R27 +#endif +#ifdef GPIO_RELAYS_R28 + , GPIO_RELAYS_R28 +#endif +#ifdef GPIO_RELAYS_R29 + , GPIO_RELAYS_R29 +#endif +#ifdef GPIO_RELAYS_R30 + , GPIO_RELAYS_R30 +#endif +#ifdef GPIO_RELAYS_R31 + , GPIO_RELAYS_R31 +#endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +void up_relaysinit(void) +{ + int i; + + /* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are + * configured for some pins but NOT used in this file + */ + + for (i = 0; i < NUM_RELAYS; i++) + { + stm32_configgpio(g_relays[i]); + } +} + +void relays_setstat(int relays,bool stat) +{ + if ((unsigned)relays < NUM_RELAYS) + { + stm32_gpiowrite(g_relays[relays], stat); + if (!stat) + { + g_relays_stat &= ~(1 << relays); + } + else + { + g_relays_stat |= (1 << relays); + } + } +} + +bool relays_getstat(int relays) +{ + if ((unsigned)relays < NUM_RELAYS) + { + return (g_relays_stat & (1 << relays)) != 0; + } + + return false; +} + +void relays_setstats(uint32_t relays_stat) +{ + int i; + + for (i = 0; i < NUM_RELAYS; i++) + { + relays_setstat(i, (relays_stat & (1<0) + { + if (relays_getstat(relays)) + { + relays_setstat(relays, false); + usleep(RELAYS_MIN_RESET_TIME*1000*1000); + } + + relays_setstat(relays,true); + usleep(mdelay*100*1000); + relays_setstat(relays, false); + } + } +} + +void relays_onoffs(uint32_t relays_stat, uint32_t mdelay) +{ + int i; + + for (i = 0; i < NUM_RELAYS; i++) + { + relays_onoff(i, mdelay); + } +} + +void relays_resetmode(int relays) +{ + relays_onoff(relays, RELAYS_RESET_MTIME); +} + +void relays_powermode(int relays) +{ + relays_onoff(relays, RELAYS_POWER_MTIME); +} + +void relays_resetmodes(uint32_t relays_stat) +{ + relays_onoffs(relays_stat, RELAYS_RESET_MTIME); +} + +void relays_powermodes(uint32_t relays_stat) +{ + relays_onoffs(relays_stat, RELAYS_POWER_MTIME); +} + +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index e8f0ae166b..57db94e1e6 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -1007,7 +1007,12 @@ Where is one of the following: 3. By default, this project assumes that you are *NOT* using the DFU bootloader. - 4. This configuration requires that you have the genromfs tool installed + 4. It appears that you cannot excute from CCM RAM. This is why the + following definition appears in the defconfig file: + + CONFIG_STM32_CCMEXCLUDE=y + + 5. This configuration requires that you have the genromfs tool installed on your system and that you have the full path to the installed genromfs executable in PATH variable (see apps/examples/README.txt) From 4f104b5e3de5f9981280ed6a9cc6d825b62847d7 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 27 Oct 2012 18:21:26 +0000 Subject: [PATCH 036/206] Add port of cJSON from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5267 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 3 + apps/examples/Kconfig | 156 +-- apps/examples/Make.defs | 4 + apps/examples/Makefile | 6 +- apps/examples/README.txt | 13 + apps/examples/json/Kconfig | 14 + apps/examples/json/Makefile | 103 ++ apps/examples/json/README | 258 +++++ apps/examples/json/json_main.c | 325 +++++++ apps/include/netutils/cJSON.h | 206 ++++ apps/netutils/Kconfig | 42 +- apps/netutils/Make.defs | 4 + apps/netutils/Makefile | 3 +- apps/netutils/README.txt | 6 + apps/netutils/json/Kconfig | 18 + apps/netutils/json/Makefile | 91 ++ apps/netutils/json/README | 258 +++++ apps/netutils/json/cJSON.c | 1576 +++++++++++++++++++++++++++++++ nuttx/ChangeLog | 2 + nuttx/Documentation/README.html | 4 +- nuttx/README.txt | 3 + 21 files changed, 2894 insertions(+), 201 deletions(-) create mode 100644 apps/examples/json/Kconfig create mode 100644 apps/examples/json/Makefile create mode 100644 apps/examples/json/README create mode 100644 apps/examples/json/json_main.c create mode 100644 apps/include/netutils/cJSON.h create mode 100644 apps/netutils/json/Kconfig create mode 100644 apps/netutils/json/Makefile create mode 100644 apps/netutils/json/README create mode 100644 apps/netutils/json/cJSON.c diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 14d107b3f4..b75637ad23 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -384,4 +384,7 @@ by one (Mike Smith). * apps/examples/elf: Test example for the ELF loader. * apps/examples/elf: The ELF module test example appears fully functional. + * apps/netutils/json: Add a snapshot of the cJSON project. Contributed by + Darcy Gong. + * apps/examples/json: Test example for cJSON from Darcy Gong diff --git a/apps/examples/Kconfig b/apps/examples/Kconfig index a37308eaac..f851ad8bda 100644 --- a/apps/examples/Kconfig +++ b/apps/examples/Kconfig @@ -3,210 +3,56 @@ # see misc/tools/kconfig-language.txt. # -menu "ADC Example" source "$APPSDIR/examples/adc/Kconfig" -endmenu - -menu "Buttons Example" source "$APPSDIR/examples/buttons/Kconfig" -endmenu - -menu "CAN Example" source "$APPSDIR/examples/can/Kconfig" -endmenu - -menu "USB CDC/ACM Class Driver Example" source "$APPSDIR/examples/cdcacm/Kconfig" -endmenu - -menu "USB composite Class Driver Example" source "$APPSDIR/examples/composite/Kconfig" -endmenu - -menu "DHCP Server Example" source "$APPSDIR/examples/dhcpd/Kconfig" -endmenu - -menu "ELF Loader Example" source "$APPSDIR/examples/elf/Kconfig" -endmenu - -menu "FTP Client Example" source "$APPSDIR/examples/ftpc/Kconfig" -endmenu - -menu "FTP Server Example" source "$APPSDIR/examples/ftpd/Kconfig" -endmenu - -menu "\"Hello, World!\" Example" source "$APPSDIR/examples/hello/Kconfig" -endmenu - -menu "\"Hello, World!\" C++ Example" source "$APPSDIR/examples/helloxx/Kconfig" -endmenu - -menu "USB HID Keyboard Example" +source "$APPSDIR/examples/json/Kconfig" source "$APPSDIR/examples/hidkbd/Kconfig" -endmenu - -menu "IGMP Example" source "$APPSDIR/examples/igmp/Kconfig" -endmenu - -menu "LCD Read/Write Example" source "$APPSDIR/examples/lcdrw/Kconfig" -endmenu - -menu "Memory Management Example" source "$APPSDIR/examples/mm/Kconfig" -endmenu - -menu "File System Mount Example" source "$APPSDIR/examples/mount/Kconfig" -endmenu - -menu "FreeModBus Example" source "$APPSDIR/examples/modbus/Kconfig" -endmenu - -menu "Network Test Example" source "$APPSDIR/examples/nettest/Kconfig" -endmenu - -menu "NuttShell (NSH) Example" source "$APPSDIR/examples/nsh/Kconfig" -endmenu - -menu "NULL Example" source "$APPSDIR/examples/null/Kconfig" -endmenu - -menu "NX Graphics Example" source "$APPSDIR/examples/nx/Kconfig" -endmenu - -menu "NxConsole Example" source "$APPSDIR/examples/nxconsole/Kconfig" -endmenu - -menu "NXFFS File System Example" source "$APPSDIR/examples/nxffs/Kconfig" -endmenu - -menu "NXFLAT Example" source "$APPSDIR/examples/nxflat/Kconfig" -endmenu - -menu "NX Graphics \"Hello, World!\" Example" source "$APPSDIR/examples/nxhello/Kconfig" -endmenu - -menu "NX Graphics image Example" source "$APPSDIR/examples/nximage/Kconfig" -endmenu - -menu "NX Graphics lines Example" source "$APPSDIR/examples/nxlines/Kconfig" -endmenu - -menu "NX Graphics Text Example" source "$APPSDIR/examples/nxtext/Kconfig" -endmenu - -menu "OS Test Example" source "$APPSDIR/examples/ostest/Kconfig" -endmenu - -menu "Pascal \"Hello, World!\"example" source "$APPSDIR/examples/pashello/Kconfig" -endmenu - -menu "Pipe Example" source "$APPSDIR/examples/pipe/Kconfig" -endmenu - -menu "Poll Example" source "$APPSDIR/examples/poll/Kconfig" -endmenu - -menu "Pulse Width Modulation (PWM) Example" source "$APPSDIR/examples/pwm/Kconfig" -endmenu - -menu "Quadrature Encoder Example" source "$APPSDIR/examples/qencoder/Kconfig" -endmenu - -menu "RGMP Example" source "$APPSDIR/examples/rgmp/Kconfig" -endmenu - -menu "ROMFS Example" source "$APPSDIR/examples/romfs/Kconfig" -endmenu - -menu "sendmail Example" source "$APPSDIR/examples/sendmail/Kconfig" -endmenu - -menu "Serial Loopback Example" source "$APPSDIR/examples/serloop/Kconfig" -endmenu - -menu "Telnet Daemon Example" source "$APPSDIR/examples/telnetd/Kconfig" -endmenu - -menu "THTTPD Web Server Example" source "$APPSDIR/examples/thttpd/Kconfig" -endmenu - -menu "TIFF Generation Example" source "$APPSDIR/examples/tiff/Kconfig" -endmenu - -menu "Touchscreen Example" source "$APPSDIR/examples/touchscreen/Kconfig" -endmenu - -menu "UDP Example" source "$APPSDIR/examples/udp/Kconfig" -endmenu - -menu "UDP Discovery Daemon Example" source "$APPSDIR/examples/discover/Kconfig" -endmenu - -menu "uIP Web Server Example" source "$APPSDIR/examples/uip/Kconfig" -endmenu - -menu "USB Serial Test Example" source "$APPSDIR/examples/usbserial/Kconfig" -endmenu - -menu "USB Mass Storage Class Example" source "$APPSDIR/examples/usbstorage/Kconfig" -endmenu - -menu "USB Serial Terminal Example" source "$APPSDIR/examples/usbterm/Kconfig" -endmenu - -menu "Watchdog timer Example" source "$APPSDIR/examples/watchdog/Kconfig" -endmenu - -menu "wget Example" source "$APPSDIR/examples/wget/Kconfig" -endmenu - -menu "WLAN Example" source "$APPSDIR/examples/wlan/Kconfig" -endmenu - -menu "XML RPC Example" source "$APPSDIR/examples/xmlrpc/Kconfig" -endmenu diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index 0733d94190..ad5653c82e 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -90,6 +90,10 @@ ifeq ($(CONFIG_EXAMPLES_IGMP),y) CONFIGURED_APPS += examples/igmp endif +ifeq ($(CONFIG_EXAMPLES_JSON),y) +CONFIGURED_APPS += examples/json +endif + ifeq ($(CONFIG_EXAMPLES_LCDRW),y) CONFIGURED_APPS += examples/lcdrw endif diff --git a/apps/examples/Makefile b/apps/examples/Makefile index ef59e68221..0ebc300e4a 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -38,7 +38,7 @@ # Sub-directories SUBDIRS = adc buttons can cdcacm composite dhcpd discover elf ftpc ftpd hello -SUBDIRS += helloxx hidkbd igmp lcdrw mm modbus mount nettest nsh null nx +SUBDIRS += helloxx hidkbd igmp json lcdrw mm modbus mount nettest nsh null nx SUBDIRS += nxconsole nxffs nxflat nxhello nximage nxlines nxtext ostest SUBDIRS += pashello pipe poll pwm qencoder rgmp romfs serloop telnetd SUBDIRS += thttpd tiff touchscreen udp uip usbserial sendmail usbstorage @@ -57,8 +57,8 @@ SUBDIRS += usbterm watchdog wget wlan CNTXTDIRS = pwm ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) -CNTXTDIRS += adc can cdcacm composite discover ftpd dhcpd modbus nettest -CNTXTDIRS += qencoder telnetd watchdog +CNTXTDIRS += adc can cdcacm composite dhcpd discover ftpd json modbus +CNTXTDIRS += nettest qencoder telnetd watchdog endif ifeq ($(CONFIG_EXAMPLES_HELLO_BUILTIN),y) diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 70dffc9897..abf95e208d 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -542,6 +542,19 @@ examples/igmp CONFIGURED_APPS += uiplib +examples/json +^^^^^^^^^^^^^ + + This example exercises the cJSON implementation at apps/netutils/json. + This example contains logic taken from the cJSON project: + + http://sourceforge.net/projects/cjson/ + + The example corresponds to SVN revision r42 (with lots of changes for + NuttX coding standards). As of r42, the SVN repository was last updated + on 2011-10-10 so I presume that the code is stable and there is no risk + of maintaining duplicate logic in the NuttX repository. + examples/lcdrw ^^^^^^^^^^^^^^ diff --git a/apps/examples/json/Kconfig b/apps/examples/json/Kconfig new file mode 100644 index 0000000000..6d948f0d72 --- /dev/null +++ b/apps/examples/json/Kconfig @@ -0,0 +1,14 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config EXAMPLES_JSON + bool "JSON example" + default n + select NETUTILS_JSON + ---help--- + An example for the netutils/json library. + +if EXAMPLES_JSON +endif diff --git a/apps/examples/json/Makefile b/apps/examples/json/Makefile new file mode 100644 index 0000000000..c2fd26bff1 --- /dev/null +++ b/apps/examples/json/Makefile @@ -0,0 +1,103 @@ +############################################################################ +# apps/examples/json/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +# cJSON built-in application info + +APPNAME = json +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +ASRCS = +CSRCS = json_main.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: clean depend 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 + +.context: +ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) + $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) + @touch $@ +endif + +context: .context + +.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 Make.dep .depend + +-include Make.dep diff --git a/apps/examples/json/README b/apps/examples/json/README new file mode 100644 index 0000000000..de9a0b2ede --- /dev/null +++ b/apps/examples/json/README @@ -0,0 +1,258 @@ +apps/examples/json/README.txt +============================= + +This directory contains logic taken from the cJSON project: + +http://sourceforge.net/projects/cjson/ + +This corresponds to SVN revision r42 (with lots of changes for NuttX coding +standards). As of r42, the SVN repository was last updated on 2011-10-10 +so I presume that the code is stable and there is no risk of maintaining +duplicate logic in the NuttX repository. + +Contents +======== + + o License + o Welcome to cJSON + +License +======= + + Copyright (c) 2009 Dave Gamble + + Permission is hereby granted, free of charge, to any person obtaining a copy + of this software and associated documentation files (the "Software"), to deal + in the Software without restriction, including without limitation the rights + to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in + all copies or substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + THE SOFTWARE. + +Welcome to cJSON +================ + +cJSON aims to be the dumbest possible parser that you can get your job done with. +It's a single file of C, and a single header file. + +JSON is described best here: http://www.json.org/ +It's like XML, but fat-free. You use it to move data around, store things, or just +generally represent your program's state. + +First up, how do I build? +Add cJSON.c to your project, and put cJSON.h somewhere in the header search path. +For example, to build the test app: + +gcc cJSON.c test.c -o test -lm +./test + +As a library, cJSON exists to take away as much legwork as it can, but not get in your way. +As a point of pragmatism (i.e. ignoring the truth), I'm going to say that you can use it +in one of two modes: Auto and Manual. Let's have a quick run-through. + +I lifted some JSON from this page: http://www.json.org/fatfree.html +That page inspired me to write cJSON, which is a parser that tries to share the same +philosophy as JSON itself. Simple, dumb, out of the way. + +Some JSON: +{ + "name": "Jack (\"Bee\") Nimble", + "format": { + "type": "rect", + "width": 1920, + "height": 1080, + "interlace": false, + "frame rate": 24 + } +} + +Assume that you got this from a file, a webserver, or magic JSON elves, whatever, +you have a char * to it. Everything is a cJSON struct. +Get it parsed: + cJSON *root = cJSON_Parse(my_json_string); + +This is an object. We're in C. We don't have objects. But we do have structs. +What's the framerate? + + cJSON *format = cJSON_GetObjectItem(root,"format"); + int framerate = cJSON_GetObjectItem(format,"frame rate")->valueint; + +Want to change the framerate? + cJSON_GetObjectItem(format,"frame rate")->valueint=25; + +Back to disk? + char *rendered=cJSON_Print(root); + +Finished? Delete the root (this takes care of everything else). + cJSON_Delete(root); + +That's AUTO mode. If you're going to use Auto mode, you really ought to check pointers +before you dereference them. If you want to see how you'd build this struct in code? + cJSON *root,*fmt; + root=cJSON_CreateObject(); + cJSON_AddItemToObject(root, "name", cJSON_CreateString("Jack (\"Bee\") Nimble")); + cJSON_AddItemToObject(root, "format", fmt=cJSON_CreateObject()); + cJSON_AddStringToObject(fmt,"type", "rect"); + cJSON_AddNumberToObject(fmt,"width", 1920); + cJSON_AddNumberToObject(fmt,"height", 1080); + cJSON_AddFalseToObject (fmt,"interlace"); + cJSON_AddNumberToObject(fmt,"frame rate", 24); + +Hopefully we can agree that's not a lot of code? There's no overhead, no unnecessary setup. +Look at test.c for a bunch of nice examples, mostly all ripped off the json.org site, and +a few from elsewhere. + +What about manual mode? First up you need some detail. +Let's cover how the cJSON objects represent the JSON data. +cJSON doesn't distinguish arrays from objects in handling; just type. +Each cJSON has, potentially, a child, siblings, value, a name. + +The root object has: Object Type and a Child +The Child has name "name", with value "Jack ("Bee") Nimble", and a sibling: +Sibling has type Object, name "format", and a child. +That child has type String, name "type", value "rect", and a sibling: +Sibling has type Number, name "width", value 1920, and a sibling: +Sibling has type Number, name "height", value 1080, and a sibling: +Sibling hs type False, name "interlace", and a sibling: +Sibling has type Number, name "frame rate", value 24 + +Here's the structure: +typedef struct cJSON { + struct cJSON *next,*prev; + struct cJSON *child; + + int type; + + char *valuestring; + int valueint; + double valuedouble; + + char *string; +} cJSON; + +By default all values are 0 unless set by virtue of being meaningful. + +next/prev is a doubly linked list of siblings. next takes you to your sibling, +prev takes you back from your sibling to you. +Only objects and arrays have a "child", and it's the head of the doubly linked list. +A "child" entry will have prev==0, but next potentially points on. The last sibling has next=0. +The type expresses Null/True/False/Number/String/Array/Object, all of which are #defined in +cJSON.h + +A Number has valueint and valuedouble. If you're expecting an int, read valueint, if not read +valuedouble. + +Any entry which is in the linked list which is the child of an object will have a "string" +which is the "name" of the entry. When I said "name" in the above example, that's "string". +"string" is the JSON name for the 'variable name' if you will. + +Now you can trivially walk the lists, recursively, and parse as you please. +You can invoke cJSON_Parse to get cJSON to parse for you, and then you can take +the root object, and traverse the structure (which is, formally, an N-tree), +and tokenise as you please. If you wanted to build a callback style parser, this is how +you'd do it (just an example, since these things are very specific): + +void parse_and_callback(cJSON *item,const char *prefix) +{ + while (item) + { + char *newprefix=malloc(strlen(prefix)+strlen(item->name)+2); + sprintf(newprefix,"%s/%s",prefix,item->name); + int dorecurse=callback(newprefix, item->type, item); + if (item->child && dorecurse) parse_and_callback(item->child,newprefix); + item=item->next; + free(newprefix); + } +} + +The prefix process will build you a separated list, to simplify your callback handling. +The 'dorecurse' flag would let the callback decide to handle sub-arrays on it's own, or +let you invoke it per-item. For the item above, your callback might look like this: + +int callback(const char *name,int type,cJSON *item) +{ + if (!strcmp(name,"name")) { /* populate name */ } + else if (!strcmp(name,"format/type") { /* handle "rect" */ } + else if (!strcmp(name,"format/width") { /* 800 */ } + else if (!strcmp(name,"format/height") { /* 600 */ } + else if (!strcmp(name,"format/interlace") { /* false */ } + else if (!strcmp(name,"format/frame rate") { /* 24 */ } + return 1; +} + +Alternatively, you might like to parse iteratively. +You'd use: + +void parse_object(cJSON *item) +{ + int i; for (i=0;ichild; + while (subitem) + { + // handle subitem + if (subitem->child) parse_object(subitem->child); + + subitem=subitem->next; + } +} + +Of course, this should look familiar, since this is just a stripped-down version +of the callback-parser. + +This should cover most uses you'll find for parsing. The rest should be possible +to infer.. and if in doubt, read the source! There's not a lot of it! ;) + +In terms of constructing JSON data, the example code above is the right way to do it. +You can, of course, hand your sub-objects to other functions to populate. +Also, if you find a use for it, you can manually build the objects. +For instance, suppose you wanted to build an array of objects? + +cJSON *objects[24]; + +cJSON *Create_array_of_anything(cJSON **items,int num) +{ + int i;cJSON *prev, *root=cJSON_CreateArray(); + for (i=0;i<24;i++) + { + if (!i) root->child=objects[i]; + else prev->next=objects[i], objects[i]->prev=prev; + prev=objects[i]; + } + return root; +} + +and simply: Create_array_of_anything(objects,24); + +cJSON doesn't make any assumptions about what order you create things in. +You can attach the objects, as above, and later add children to each +of those objects. + +As soon as you call cJSON_Print, it renders the structure to text. + +The test.c code shows how to handle a bunch of typical cases. If you uncomment +the code, it'll load, parse and print a bunch of test files, also from json.org, +which are more complex than I'd care to try and stash into a const char array[]. + +Enjoy cJSON! + +- Dave Gamble, Aug 2009 diff --git a/apps/examples/json/json_main.c b/apps/examples/json/json_main.c new file mode 100644 index 0000000000..443be387bd --- /dev/null +++ b/apps/examples/json/json_main.c @@ -0,0 +1,325 @@ +/**************************************************************************** + * apps/examples/json/json_main.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * And derives from the cJSON Project which has an MIT license: + * + * Copyright (c) 2009 Dave Gamble + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* Used by some code below as an example datatype. */ + +struct record +{ + const char *precision; + double lat; + double lon; + const char *address; + const char *city; + const char *state; + const char *zip; + const char *country; +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: doit + * + * Description: + * Parse text to JSON, then render back to text, and print! + * + ****************************************************************************/ + +static void doit(const char *text) +{ + char *out; + cJSON *json; + json = cJSON_Parse(text); + if (!json) + { + printf("Error before: [%s]\n", cJSON_GetErrorPtr()); + } + else + { + out = cJSON_Print(json); + cJSON_Delete(json); + printf("%s\n", out); + free(out); + } +} + +/**************************************************************************** + * Name: dofile + * + * Description: + * Read a file, parse, render back, etc. + * + ****************************************************************************/ + +#if 0 /* Not used */ +static void dofile(char *filename) +{ + FILE *f = fopen(filename, "rb"); + fseek(f, 0, SEEK_END); + long len = ftell(f); + fseek(f, 0, SEEK_SET); + char *data = malloc(len + 1); + fread(data, 1, len, f); + fclose(f); + doit(data); + free(data); +} +#endif + +/**************************************************************************** + * Name: create_objects + * + * Description: + * Create a bunch of objects as demonstration. + * + ****************************************************************************/ + +static void create_objects(void) +{ + cJSON *root; + cJSON *fmt; + cJSON *img; + cJSON *thm; + cJSON *fld; + char *out; + int i; + + /* Our "days of the week" array */ + + static const char *strings[7] = + { + "Sunday", "Monday", "Tuesday", "Wednesday", + "Thursday", "Friday", "Saturday" + }; + + /* Our matrix: */ + + static const int numbers[3][3] = { {0, -1, 0}, {1, 0, 0}, {0, 0, 1} }; + + /* Our "gallery" item: */ + + static const int ids[4] = { 116, 943, 234, 38793 }; + + /* Our array of "records": */ + + static const struct record fields[2] = + { + {"zip", 37.7668, -1.223959e+2, "", "SAN FRANCISCO", "CA", "94107", "US"}, + {"zip", 37.371991, -1.22026e+2, "", "SUNNYVALE", "CA", "94085", "US"} + }; + + /* Here we construct some JSON standards, from the JSON site. */ + /* Our "Video" datatype: */ + + root = cJSON_CreateObject(); + cJSON_AddItemToObject(root, "name", cJSON_CreateString("Jack (\"Bee\") Nimble")); + cJSON_AddItemToObject(root, "format", fmt = cJSON_CreateObject()); + cJSON_AddStringToObject(fmt, "type", "rect"); + cJSON_AddNumberToObject(fmt, "width", 1920); + cJSON_AddNumberToObject(fmt, "height", 1080); + cJSON_AddFalseToObject(fmt, "interlace"); + cJSON_AddNumberToObject(fmt, "frame rate", 24); + out = cJSON_Print(root); + cJSON_Delete(root); + printf("%s\n", out); + free(out); + + /* Print to text, Delete the cJSON, print it, release the string. */ + + root = cJSON_CreateStringArray(strings, 7); + out = cJSON_Print(root); + cJSON_Delete(root); + printf("%s\n", out); + free(out); + + root = cJSON_CreateArray(); + for (i = 0; i < 3; i++) + { + cJSON_AddItemToArray(root, cJSON_CreateIntArray(numbers[i], 3)); + } + +/*cJSON_ReplaceItemInArray(root,1,cJSON_CreateString("Replacement")); */ + out = cJSON_Print(root); + cJSON_Delete(root); + printf("%s\n", out); + free(out); + + root = cJSON_CreateObject(); + cJSON_AddItemToObject(root, "Image", img = cJSON_CreateObject()); + cJSON_AddNumberToObject(img, "Width", 800); + cJSON_AddNumberToObject(img, "Height", 600); + cJSON_AddStringToObject(img, "Title", "View from 15th Floor"); + cJSON_AddItemToObject(img, "Thumbnail", thm = cJSON_CreateObject()); + cJSON_AddStringToObject(thm, "Url", "http:/*www.example.com/image/481989943"); + cJSON_AddNumberToObject(thm, "Height", 125); + cJSON_AddStringToObject(thm, "Width", "100"); + cJSON_AddItemToObject(img, "IDs", cJSON_CreateIntArray(ids, 4)); + out = cJSON_Print(root); + cJSON_Delete(root); + printf("%s\n", out); + free(out); + + root = cJSON_CreateArray(); + for (i = 0; i < 2; i++) + { + cJSON_AddItemToArray(root, fld = cJSON_CreateObject()); + cJSON_AddStringToObject(fld, "precision", fields[i].precision); + cJSON_AddNumberToObject(fld, "Latitude", fields[i].lat); + cJSON_AddNumberToObject(fld, "Longitude", fields[i].lon); + cJSON_AddStringToObject(fld, "Address", fields[i].address); + cJSON_AddStringToObject(fld, "City", fields[i].city); + cJSON_AddStringToObject(fld, "State", fields[i].state); + cJSON_AddStringToObject(fld, "Zip", fields[i].zip); + cJSON_AddStringToObject(fld, "Country", fields[i].country); + } + +/*cJSON_ReplaceItemInObject(cJSON_GetArrayItem(root,1),"City",cJSON_CreateIntArray(ids,4)); */ + out = cJSON_Print(root); + cJSON_Delete(root); + printf("%s\n", out); + free(out); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/**************************************************************************** + * Name: + * + * Description: + * + * + ****************************************************************************/ + +int json_main(int argc, const char *argv[]) +{ + /* a bunch of json: */ + + static const char text1[] = + "{\n" + " \"name\": \"Jack (\\\"Bee\\\") Nimble\",\n" + " \"format\": {\n" + " \"type\": \"rect\",\n" + " \"width\": 1920,\n" + " \"height\": 1080,\n" + " \"interlace\": false,\n" + " \"frame rate\": 24\n" + " }\n" + "}"; + + static const char text2[] = + "[\"Sunday\", \"Monday\", \"Tuesday\", \"Wednesday\", \"Thursday\", \"Friday\", \"Saturday\"]"; + + static const char text3[] = + "[\n" + " [0, -1, 0],\n" + " [1, 0, 0],\n" + " [0, 0, 1]\n" + "]\n"; + + static const char text4[] = + "{\n" + " \"Image\": {\n" + " \"Width\": 800,\n" + " \"Height\": 600,\n" + " \"Title\": \"View from 15th Floor\",\n" + " \"Thumbnail\": {\n" + " \"Url\": \"http:/*www.example.com/image/481989943\",\n" + " \"Height\": 125,\n" + " \"Width\": \"100\"\n" + " },\n" + " \"IDs\": [116, 943, 234, 38793]\n" + " }\n" + "}"; + + static const char text5[] = + "[\n" + " {\n" + " \"precision\": \"zip\",\n" + " \"Latitude\": 37.7668,\n" + " \"Longitude\": -122.3959,\n" + " \"Address\": \"\",\n" + " \"City\": \"SAN FRANCISCO\",\n" + " \"State\": \"CA\",\n" + " \"Zip\": \"94107\",\n" + " \"Country\": \"US\"\n" + " },\n" + " {\n" + " \"precision\": \"zip\",\n" + " \"Latitude\": 37.371991,\n" + " \"Longitude\": -122.026020,\n" + " \"Address\": \"\",\n" + " \"City\": \"SUNNYVALE\",\n" + " \"State\": \"CA\",\n" + " \"Zip\": \"94085\",\n" + " \"Country\": \"US\"\n" + " }\n" + "]"; + + /* Process each json textblock by parsing, then rebuilding: */ doit(text1); + + doit(text2); + doit(text3); + doit(text4); + doit(text5); + + /* Parse standard testfiles: */ + +#if 0 /* Not yet */ + dofile("../../tests/test1"); + dofile("../../tests/test2"); + dofile("../../tests/test3"); + dofile("../../tests/test4"); + dofile("../../tests/test5"); +#endif + + /* Now some samplecode for building objects concisely: */ + + create_objects(); + return 0; +} diff --git a/apps/include/netutils/cJSON.h b/apps/include/netutils/cJSON.h new file mode 100644 index 0000000000..3526782bdf --- /dev/null +++ b/apps/include/netutils/cJSON.h @@ -0,0 +1,206 @@ +/**************************************************************************** + * apps/netutils/json/cJSON.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * And derives from the cJSON Project which has an MIT license: + * + * Copyright (c) 2009 Dave Gamble + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + ****************************************************************************/ + +#ifndef __APPS_INCLUDE_NETUTILS_JSON_H +#define __APPS_INCLUDE_NETUTILS_JSON_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define cJSON_False 0 +#define cJSON_True 1 +#define cJSON_NULL 2 +#define cJSON_Number 3 +#define cJSON_String 4 +#define cJSON_Array 5 +#define cJSON_Object 6 + +#define cJSON_IsReference 256 + +#define cJSON_AddNullToObject(object,name) \ + cJSON_AddItemToObject(object, name, cJSON_CreateNull()) +#define cJSON_AddTrueToObject(object,name) \ + cJSON_AddItemToObject(object, name, cJSON_CreateTrue())cd +#define cJSON_AddFalseToObject(object,name) \ + cJSON_AddItemToObject(object, name, cJSON_CreateFalse()) +#define cJSON_AddNumberToObject(object,name,n) \ + cJSON_AddItemToObject(object, name, cJSON_CreateNumber(n)) +#define cJSON_AddStringToObject(object,name,s) \ + cJSON_AddItemToObject(object, name, cJSON_CreateString(s)) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* The cJSON structure: */ + +typedef struct cJSON +{ + /* next/prev allow you to walk array/object chains. Alternatively, use + * GetArraySize/GetArrayItem/GetObjectItem + */ + + struct cJSON *next,*prev; + + /* An array or object item will have a child pointer pointing to a chain + * of the items in the array/object. + */ + + struct cJSON *child; + + int type; /* The type of the item, as above. */ + char *valuestring; /* The item's string, if type==cJSON_String */ + int valueint; /* The item's number, if type==cJSON_Number */ + double valuedouble; /* The item's number, if type==cJSON_Number */ + + /* The item's name string, if this item is the child of, or is in the list + * of subitems of an object. + */ + + char *string; +} cJSON; + +typedef struct cJSON_Hooks +{ + void *(*malloc_fn)(size_t sz); + void (*free_fn)(void *ptr); +} cJSON_Hooks; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/* Supply malloc, realloc and free functions to cJSON */ + +void cJSON_InitHooks(cJSON_Hooks* hooks); + +/* Supply a block of JSON, and this returns a cJSON object you can + * interrogate. Call cJSON_Delete when finished. + */ + +cJSON *cJSON_Parse(const char *value); + +/* Render a cJSON entity to text for transfer/storage. Free the char* when + * finished. + */ + +char *cJSON_Print(cJSON *item); + +/* Render a cJSON entity to text for transfer/storage without any + * formatting. Free the char* when finished. + */ + +char *cJSON_PrintUnformatted(cJSON *item); + +/* Delete a cJSON entity and all subentities. */ + +void cJSON_Delete(cJSON *c); + +/* Returns the number of items in an array (or object). */ + +int cJSON_GetArraySize(cJSON *array); + +/* Retrieve item number "item" from array "array". Returns NULL if + * unsuccessful. + */ + +cJSON *cJSON_GetArrayItem(cJSON *array, int item); + +/* Get item "string" from object. Case insensitive. */ + +cJSON *cJSON_GetObjectItem(cJSON *object, const char *string); + +/* For analysing failed parses. This returns a pointer to the parse error. + * You'll probably need to look a few chars back to make sense of it. + * Defined when cJSON_Parse() returns 0. 0 when cJSON_Parse() succeeds. + */ + +const char *cJSON_GetErrorPtr(); + +/* These calls create a cJSON item of the appropriate type. */ + +cJSON *cJSON_CreateNull(); +cJSON *cJSON_CreateTrue(); +cJSON *cJSON_CreateFalse(); +cJSON *cJSON_CreateBool(int b); +cJSON *cJSON_CreateNumber(double num); +cJSON *cJSON_CreateString(const char *string); +cJSON *cJSON_CreateArray(); +cJSON *cJSON_CreateObject(); + +/* These utilities create an Array of count items. */ + +cJSON *cJSON_CreateIntArray(const int *numbers, int count); +cJSON *cJSON_CreateFloatArray(const float *numbers, int count); +cJSON *cJSON_CreateDoubleArray(const double *numbers, int count); +cJSON *cJSON_CreateStringArray(const char **strings, int count); + +/* Append item to the specified array/object. */ + +void cJSON_AddItemToArray(cJSON *array, cJSON *item); +void cJSON_AddItemToObject(cJSON *object, const char *string, cJSON *item); + +/* Append reference to item to the specified array/object. Use this when you + * want to add an existing cJSON to a new cJSON, but don't want to corrupt + * your existing cJSON. + */ + +void cJSON_AddItemReferenceToArray(cJSON *array, cJSON *item); +void cJSON_AddItemReferenceToObject(cJSON *object, const char *string, cJSON *item); + +/* Remove/Detatch items from Arrays/Objects. */ + +cJSON *cJSON_DetachItemFromArray(cJSON *array, int which); +void cJSON_DeleteItemFromArray(cJSON *array, int which); +cJSON *cJSON_DetachItemFromObject(cJSON *object, const char *string); +void cJSON_DeleteItemFromObject(cJSON *object, const char *string); + +/* Update array items. */ + +void cJSON_ReplaceItemInArray(cJSON *array, int which, cJSON *newitem); +void cJSON_ReplaceItemInObject(cJSON *object, const char *string, cJSON *newitem); + +#ifdef __cplusplus +} +#endif + +#endif /* __APPS_INCLUDE_NETUTILS_JSON_H */ diff --git a/apps/netutils/Kconfig b/apps/netutils/Kconfig index 4141e5b031..d59afb28eb 100644 --- a/apps/netutils/Kconfig +++ b/apps/netutils/Kconfig @@ -5,58 +5,18 @@ comment "Networking Utilities" -menu "DHCP client" source "$APPSDIR/netutils/dhcpc/Kconfig" -endmenu - -menu "DHCP server" source "$APPSDIR/netutils/dhcpd/Kconfig" -endmenu - -menu "FTP client" source "$APPSDIR/netutils/ftpc/Kconfig" -endmenu - -menu "FTP server" source "$APPSDIR/netutils/ftpd/Kconfig" -endmenu - -menu "Name resolution" +source "$APPSDIR/netutils/json/Kconfig" source "$APPSDIR/netutils/resolv/Kconfig" -endmenu - -menu "SMTP" source "$APPSDIR/netutils/smtp/Kconfig" -endmenu - -menu "TFTP client" source "$APPSDIR/netutils/telnetd/Kconfig" -endmenu - -menu "TFTP client" source "$APPSDIR/netutils/tftpc/Kconfig" -endmenu - -menu "THTTPD web server" source "$APPSDIR/netutils/thttpd/Kconfig" -endmenu - -menu "uIP support library" source "$APPSDIR/netutils/uiplib/Kconfig" -endmenu - -menu "uIP web client" source "$APPSDIR/netutils/webclient/Kconfig" -endmenu - -menu "uIP web server" source "$APPSDIR/netutils/webserver/Kconfig" -endmenu - -menu "UDP Discovery Utility" source "$APPSDIR/netutils/discover/Kconfig" -endmenu - -menu "XML-RPC library" source "$APPSDIR/netutils/xmlrpc/Kconfig" -endmenu diff --git a/apps/netutils/Make.defs b/apps/netutils/Make.defs index ae72ab0fd6..9fb25b80f7 100644 --- a/apps/netutils/Make.defs +++ b/apps/netutils/Make.defs @@ -50,6 +50,10 @@ ifeq ($(CONFIG_NETUTILS_FTPD),y) CONFIGURED_APPS += netutils/ftpd endif +ifeq ($(CONFIG_NETUTILS_JSON),y) +CONFIGURED_APPS += netutils/json +endif + ifeq ($(CONFIG_NETUTILS_RESOLV),y) CONFIGURED_APPS += netutils/resolv endif diff --git a/apps/netutils/Makefile b/apps/netutils/Makefile index 058b0f6294..e60771d327 100644 --- a/apps/netutils/Makefile +++ b/apps/netutils/Makefile @@ -37,8 +37,9 @@ # Sub-directories +SUBDIRS = json ifeq ($(CONFIG_NET),y) -SUBDIRS = uiplib dhcpc dhcpd discover ftpc ftpd resolv smtp telnetd +SUBDIRS += uiplib dhcpc dhcpd discover ftpc ftpd resolv smtp telnetd SUBDIRS += webclient webserver tftpc thttpd xmlrpc endif diff --git a/apps/netutils/README.txt b/apps/netutils/README.txt index e97bf5a618..eaf508d484 100644 --- a/apps/netutils/README.txt +++ b/apps/netutils/README.txt @@ -47,6 +47,12 @@ highly influenced by uIP) include: device class so that groups of devices can be discovered. It is also possible to address all classes with a kind of broadcast discover. (Contributed by Max Holtzberg). + json - cJSON is an ultra-lightweight, portable, single-file, + simple-as-can-be ANSI-C compliant JSON parser, under MIT + license. Embeddable Lightweight XML-RPC Server discussed at + http://www.drdobbs.com/web-development/an-embeddable-lightweight-xml-rpc-server/184405364. + This code was taken from http://sourceforge.net/projects/cjson/ + and adapted for NuttX by Darcy Gong. tftpc - TFTP client. See apps/include/netutils/tftp.h for interface information. telnetd - TELNET server. This is the Telnet logic adapted from diff --git a/apps/netutils/json/Kconfig b/apps/netutils/json/Kconfig new file mode 100644 index 0000000000..741ae56603 --- /dev/null +++ b/apps/netutils/json/Kconfig @@ -0,0 +1,18 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config NETUTILS_JSON + bool "cJSON library" + default n + ---help--- + Enables the cJSON library. cJSON is an ultra-lightweight, portable, + single-file, simple-as-can-be ANSI-C compliant JSON parser, under MIT + license. Embeddable Lightweight XML-RPC Server discussed at + http://www.drdobbs.com/web-development/an-embeddable-lightweight-xml-rpc-server/184405364. + This code was taken from http://sourceforge.net/projects/cjson/ and + adapted for NuttX by Darcy Gong. + +if NETUTILS_JSON +endif diff --git a/apps/netutils/json/Makefile b/apps/netutils/json/Makefile new file mode 100644 index 0000000000..1426a1a51f --- /dev/null +++ b/apps/netutils/json/Makefile @@ -0,0 +1,91 @@ +############################################################################ +# apps/netutils/json/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +ASRCS = +CSRCS = cJSON.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 + +context: + +.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 Make.dep .depend + +-include Make.dep diff --git a/apps/netutils/json/README b/apps/netutils/json/README new file mode 100644 index 0000000000..6d60da9348 --- /dev/null +++ b/apps/netutils/json/README @@ -0,0 +1,258 @@ +apps/netutils/json/README.txt +============================= + +This directory contains logic taken from the cJSON project: + +http://sourceforge.net/projects/cjson/ + +This corresponds to SVN revision r42 (with lots of changes for NuttX coding +standards). As of r42, the SVN repository was last updated on 2011-10-10 +so I presume that the code is stable and there is no risk of maintaining +duplicate logic in the NuttX repository. + +Contents +======== + + o License + o Welcome to cJSON + +License +======= + + Copyright (c) 2009 Dave Gamble + + Permission is hereby granted, free of charge, to any person obtaining a copy + of this software and associated documentation files (the "Software"), to deal + in the Software without restriction, including without limitation the rights + to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in + all copies or substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + THE SOFTWARE. + +Welcome to cJSON +================ + +cJSON aims to be the dumbest possible parser that you can get your job done with. +It's a single file of C, and a single header file. + +JSON is described best here: http://www.json.org/ +It's like XML, but fat-free. You use it to move data around, store things, or just +generally represent your program's state. + +First up, how do I build? +Add cJSON.c to your project, and put cJSON.h somewhere in the header search path. +For example, to build the test app: + +gcc cJSON.c test.c -o test -lm +./test + +As a library, cJSON exists to take away as much legwork as it can, but not get in your way. +As a point of pragmatism (i.e. ignoring the truth), I'm going to say that you can use it +in one of two modes: Auto and Manual. Let's have a quick run-through. + +I lifted some JSON from this page: http://www.json.org/fatfree.html +That page inspired me to write cJSON, which is a parser that tries to share the same +philosophy as JSON itself. Simple, dumb, out of the way. + +Some JSON: +{ + "name": "Jack (\"Bee\") Nimble", + "format": { + "type": "rect", + "width": 1920, + "height": 1080, + "interlace": false, + "frame rate": 24 + } +} + +Assume that you got this from a file, a webserver, or magic JSON elves, whatever, +you have a char * to it. Everything is a cJSON struct. +Get it parsed: + cJSON *root = cJSON_Parse(my_json_string); + +This is an object. We're in C. We don't have objects. But we do have structs. +What's the framerate? + + cJSON *format = cJSON_GetObjectItem(root,"format"); + int framerate = cJSON_GetObjectItem(format,"frame rate")->valueint; + +Want to change the framerate? + cJSON_GetObjectItem(format,"frame rate")->valueint=25; + +Back to disk? + char *rendered=cJSON_Print(root); + +Finished? Delete the root (this takes care of everything else). + cJSON_Delete(root); + +That's AUTO mode. If you're going to use Auto mode, you really ought to check pointers +before you dereference them. If you want to see how you'd build this struct in code? + cJSON *root,*fmt; + root=cJSON_CreateObject(); + cJSON_AddItemToObject(root, "name", cJSON_CreateString("Jack (\"Bee\") Nimble")); + cJSON_AddItemToObject(root, "format", fmt=cJSON_CreateObject()); + cJSON_AddStringToObject(fmt,"type", "rect"); + cJSON_AddNumberToObject(fmt,"width", 1920); + cJSON_AddNumberToObject(fmt,"height", 1080); + cJSON_AddFalseToObject (fmt,"interlace"); + cJSON_AddNumberToObject(fmt,"frame rate", 24); + +Hopefully we can agree that's not a lot of code? There's no overhead, no unnecessary setup. +Look at test.c for a bunch of nice examples, mostly all ripped off the json.org site, and +a few from elsewhere. + +What about manual mode? First up you need some detail. +Let's cover how the cJSON objects represent the JSON data. +cJSON doesn't distinguish arrays from objects in handling; just type. +Each cJSON has, potentially, a child, siblings, value, a name. + +The root object has: Object Type and a Child +The Child has name "name", with value "Jack ("Bee") Nimble", and a sibling: +Sibling has type Object, name "format", and a child. +That child has type String, name "type", value "rect", and a sibling: +Sibling has type Number, name "width", value 1920, and a sibling: +Sibling has type Number, name "height", value 1080, and a sibling: +Sibling hs type False, name "interlace", and a sibling: +Sibling has type Number, name "frame rate", value 24 + +Here's the structure: +typedef struct cJSON { + struct cJSON *next,*prev; + struct cJSON *child; + + int type; + + char *valuestring; + int valueint; + double valuedouble; + + char *string; +} cJSON; + +By default all values are 0 unless set by virtue of being meaningful. + +next/prev is a doubly linked list of siblings. next takes you to your sibling, +prev takes you back from your sibling to you. +Only objects and arrays have a "child", and it's the head of the doubly linked list. +A "child" entry will have prev==0, but next potentially points on. The last sibling has next=0. +The type expresses Null/True/False/Number/String/Array/Object, all of which are #defined in +cJSON.h + +A Number has valueint and valuedouble. If you're expecting an int, read valueint, if not read +valuedouble. + +Any entry which is in the linked list which is the child of an object will have a "string" +which is the "name" of the entry. When I said "name" in the above example, that's "string". +"string" is the JSON name for the 'variable name' if you will. + +Now you can trivially walk the lists, recursively, and parse as you please. +You can invoke cJSON_Parse to get cJSON to parse for you, and then you can take +the root object, and traverse the structure (which is, formally, an N-tree), +and tokenise as you please. If you wanted to build a callback style parser, this is how +you'd do it (just an example, since these things are very specific): + +void parse_and_callback(cJSON *item,const char *prefix) +{ + while (item) + { + char *newprefix=malloc(strlen(prefix)+strlen(item->name)+2); + sprintf(newprefix,"%s/%s",prefix,item->name); + int dorecurse=callback(newprefix, item->type, item); + if (item->child && dorecurse) parse_and_callback(item->child,newprefix); + item=item->next; + free(newprefix); + } +} + +The prefix process will build you a separated list, to simplify your callback handling. +The 'dorecurse' flag would let the callback decide to handle sub-arrays on it's own, or +let you invoke it per-item. For the item above, your callback might look like this: + +int callback(const char *name,int type,cJSON *item) +{ + if (!strcmp(name,"name")) { /* populate name */ } + else if (!strcmp(name,"format/type") { /* handle "rect" */ } + else if (!strcmp(name,"format/width") { /* 800 */ } + else if (!strcmp(name,"format/height") { /* 600 */ } + else if (!strcmp(name,"format/interlace") { /* false */ } + else if (!strcmp(name,"format/frame rate") { /* 24 */ } + return 1; +} + +Alternatively, you might like to parse iteratively. +You'd use: + +void parse_object(cJSON *item) +{ + int i; for (i=0;ichild; + while (subitem) + { + // handle subitem + if (subitem->child) parse_object(subitem->child); + + subitem=subitem->next; + } +} + +Of course, this should look familiar, since this is just a stripped-down version +of the callback-parser. + +This should cover most uses you'll find for parsing. The rest should be possible +to infer.. and if in doubt, read the source! There's not a lot of it! ;) + +In terms of constructing JSON data, the example code above is the right way to do it. +You can, of course, hand your sub-objects to other functions to populate. +Also, if you find a use for it, you can manually build the objects. +For instance, suppose you wanted to build an array of objects? + +cJSON *objects[24]; + +cJSON *Create_array_of_anything(cJSON **items,int num) +{ + int i;cJSON *prev, *root=cJSON_CreateArray(); + for (i=0;i<24;i++) + { + if (!i) root->child=objects[i]; + else prev->next=objects[i], objects[i]->prev=prev; + prev=objects[i]; + } + return root; +} + +and simply: Create_array_of_anything(objects,24); + +cJSON doesn't make any assumptions about what order you create things in. +You can attach the objects, as above, and later add children to each +of those objects. + +As soon as you call cJSON_Print, it renders the structure to text. + +The test.c code shows how to handle a bunch of typical cases. If you uncomment +the code, it'll load, parse and print a bunch of test files, also from json.org, +which are more complex than I'd care to try and stash into a const char array[]. + +Enjoy cJSON! + +- Dave Gamble, Aug 2009 diff --git a/apps/netutils/json/cJSON.c b/apps/netutils/json/cJSON.c new file mode 100644 index 0000000000..12eaab2433 --- /dev/null +++ b/apps/netutils/json/cJSON.c @@ -0,0 +1,1576 @@ +/**************************************************************************** + * apps/netutils/json/cJSON.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * And derives from the cJSON Project which has an MIT license: + * + * Copyright (c) 2009 Dave Gamble + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const char *ep; + +static const unsigned char firstByteMark[7] = + { 0x00, 0x00, 0xc0, 0xe0, 0xf0, 0xf8, 0xfc }; + +static void *(*cJSON_malloc)(size_t sz) = malloc; +static void (*cJSON_free)(void *ptr) = free; + +/**************************************************************************** + * Private Prototypes + ****************************************************************************/ + +static const char *parse_value(cJSON *item, const char *value); +static char *print_value(cJSON *item, int depth, int fmt); +static const char *parse_array(cJSON *item, const char *value); +static char *print_array(cJSON *item, int depth, int fmt); +static const char *parse_object(cJSON *item, const char *value); +static char *print_object(cJSON *item, int depth, int fmt); + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static char *cJSON_strdup(const char *str) +{ + size_t len; + char *copy; + + len = strlen(str) + 1; + if (!(copy = (char *)cJSON_malloc(len))) + { + return 0; + } + + memcpy(copy, str, len); + return copy; +} + +/* Internal constructor. */ + +static cJSON *cJSON_New_Item(void) +{ + cJSON *node = (cJSON *) cJSON_malloc(sizeof(cJSON)); + if (node) + { + memset(node, 0, sizeof(cJSON)); + } + + return node; +} + +static int cJSON_strcasecmp(const char *s1, const char *s2) +{ + if (!s1) + { + return (s1 == s2) ? 0 : 1; + } + + if (!s2) + { + return 1; + } + + for (; tolower(*s1) == tolower(*s2); ++s1, ++s2) + { + if (*s1 == 0) + { + return 0; + } + } + + return tolower(*(const unsigned char *)s1) - tolower(*(const unsigned char *)s2); +} + +/* Parse the input text to generate a number, and populate the result into item. */ + +static const char *parse_number(cJSON *item, const char *num) +{ + double n = 0, sign = 1, scale = 0; + int subscale = 0, signsubscale = 1; + + /* Could use sscanf for this? */ + /* Has sign? */ + + if (*num == '-') + { + sign = -1, num++; + } + + /* is zero */ + + if (*num == '0') + { + num++; + } + + /* Number? */ + + if (*num >= '1' && *num <= '9') + { + do + { + n = (n * 10.0) + (*num++ - '0'); + } + while (*num >= '0' && *num <= '9'); + } + + /* Fractional part? */ + + if (*num == '.' && num[1] >= '0' && num[1] <= '9') + { + num++; + do + { + n = (n * 10.0) + (*num++ - '0'), scale--; + } + while (*num >= '0' && *num <= '9'); + } + + /* Exponent? */ + + if (*num == 'e' || *num == 'E') + { + num++; + if (*num == '+') + { + num++; + } + + /* With sign? */ + + else if (*num == '-') + { + signsubscale = -1; + num++; + } + + /* Number? */ + + while (*num >= '0' && *num <= '9') + { + subscale = (subscale * 10) + (*num++ - '0'); + } + } + + /* number = +/- number.fraction * 10^+/-exponent */ + + n = sign * n * pow(10.0, (scale + subscale * signsubscale)); + item->valuedouble = n; + item->valueint = (int)n; + item->type = cJSON_Number; + return num; +} + +/* Render the number nicely from the given item into a string. */ + +static char *print_number(cJSON *item) +{ + char *str; + double d = item->valuedouble; + + if (fabs(((double)item->valueint) - d) <= DBL_EPSILON) /* && d<=INT_MAX && d>=INT_MIN) */ + { + /* 2^64+1 can be represented in 21 chars. */ + + str = (char *)cJSON_malloc(21); + if (str) + { + sprintf(str, "%d", item->valueint); + } + } + else + { + /* This is a nice tradeoff. */ + + str = (char *)cJSON_malloc(64); + if (str) + { + if (fabs(floor(d) - d) <= DBL_EPSILON) + { + sprintf(str, "%d", item->valueint); + } + else if (fabs(d) < 1.0e-6 || fabs(d) > 1.0e9) + { + sprintf(str, "%e", d); + } + else + { + sprintf(str, " %f", d); + } + } + } + + return str; +} + +/* Parse the input text into an unescaped cstring, and populate item. */ + +static const char *parse_string(cJSON *item, const char *str) +{ + const char *ptr = str + 1; + char *ptr2; + char *out; + int len = 0; + unsigned uc; + unsigned uc2; + + if (*str != '\"') + { + /* not a string! */ + + ep = str; + return 0; + } + + while (*ptr != '\"' && *ptr && ++len) + { + /* Skip escaped quotes. */ + + if (*ptr++ == '\\') + { + ptr++; + } + } + + /* This is how long we need for the string, roughly. */ + + out = (char *)cJSON_malloc(len + 1); + if (!out) + { + return 0; + } + + ptr = str + 1; + ptr2 = out; + while (*ptr != '\"' && *ptr) + { + if (*ptr != '\\') + { + *ptr2++ = *ptr++; + } + else + { + ptr++; + switch (*ptr) + { + case 'b': + *ptr2++ = '\b'; + break; + + case 'f': + *ptr2++ = '\f'; + break; + + case 'n': + *ptr2++ = '\n'; + break; + + case 'r': + *ptr2++ = '\r'; + break; + + case 't': + *ptr2++ = '\t'; + break; + + case 'u': + /* Transcode utf16 to utf8. */ + /* Get the unicode char. */ + + sscanf(ptr + 1, "%4x", &uc); + ptr += 4; + + /* Check for invalid. */ + + if ((uc >= 0xdc00 && uc <= 0xdfff) || uc == 0) + { + break; + } + + if (uc >= 0xd800 && uc <= 0xdbff) /* UTF16 surrogate pairs. */ + { + /* missing second-half of surrogate. */ + + if (ptr[1] != '\\' || ptr[2] != 'u') + { + break; + } + + sscanf(ptr + 3, "%4x", &uc2); + ptr += 6; + if (uc2 < 0xdc00 || uc2 > 0xdfff) + { + /* Invalid second-half of surrogate. */ + + break; + } + + uc = 0x10000 | ((uc & 0x3ff) << 10) | (uc2 & 0x3ff); + } + + len = 4; + if (uc < 0x80) + { + len = 1; + } + else if (uc < 0x800) + { + len = 2; + } + else if (uc < 0x10000) + { + len = 3; + } + + ptr2 += len; + + switch (len) + { + case 4: + *--ptr2 = ((uc | 0x80) & 0xbf); + uc >>= 6; + case 3: + *--ptr2 = ((uc | 0x80) & 0xbf); + uc >>= 6; + case 2: + *--ptr2 = ((uc | 0x80) & 0xbf); + uc >>= 6; + case 1: + *--ptr2 = (uc | firstByteMark[len]); + break; + } + + ptr2 += len; + break; + + default: + *ptr2++ = *ptr; + break; + } + ptr++; + } + } + + *ptr2 = 0; + if (*ptr == '\"') + { + ptr++; + } + + item->valuestring = out; + item->type = cJSON_String; + return ptr; +} + +/* Render the cstring provided to an escaped version that can be printed. */ + +static char *print_string_ptr(const char *str) +{ + const char *ptr; + char *ptr2, *out; + int len = 0; + unsigned char token; + + if (!str) + { + return cJSON_strdup(""); + } + + ptr = str; + while ((token = *ptr) && ++len) + { + if (strchr("\"\\\b\f\n\r\t", token)) + { + len++; + } + else if (token < 32) + { + len += 5; + } + + ptr++; + } + + out = (char *)cJSON_malloc(len + 3); + if (!out) + { + return 0; + } + + ptr2 = out; + ptr = str; + *ptr2++ = '\"'; + while (*ptr) + { + if ((unsigned char)*ptr > 31 && *ptr != '\"' && *ptr != '\\') + { + *ptr2++ = *ptr++; + } + else + { + *ptr2++ = '\\'; + switch (token = *ptr++) + { + case '\\': + *ptr2++ = '\\'; + break; + + case '\"': + *ptr2++ = '\"'; + break; + + case '\b': + *ptr2++ = 'b'; + break; + + case '\f': + *ptr2++ = 'f'; + break; + + case '\n': + *ptr2++ = 'n'; + break; + + case '\r': + *ptr2++ = 'r'; + break; + + case '\t': + *ptr2++ = 't'; + break; + + default: + /* Escape and print */ + + sprintf(ptr2, "u%04x", token); + ptr2 += 5; + break; + } + } + } + + *ptr2++ = '\"'; + *ptr2++ = 0; + return out; +} + +/* Invote print_string_ptr (which is useful) on an item. */ + +static char *print_string(cJSON *item) +{ + return print_string_ptr(item->valuestring); +} + +/* Utility to jump whitespace and cr/lf */ + +static const char *skip(const char *in) +{ + while (in && *in && (unsigned char)*in <= 32) + { + in++; + } + + return in; +} + +/* Parser core - when encountering text, process appropriately. */ + +static const char *parse_value(cJSON *item, const char *value) +{ + if (!value) + { + /* Fail on null. */ + + return 0; + } + + if (!strncmp(value, "null", 4)) + { + item->type = cJSON_NULL; + return value + 4; + } + + if (!strncmp(value, "false", 5)) + { + item->type = cJSON_False; + return value + 5; + } + + if (!strncmp(value, "true", 4)) + { + item->type = cJSON_True; + item->valueint = 1; + return value + 4; + } + + if (*value == '\"') + { + return parse_string(item, value); + } + + if (*value == '-' || (*value >= '0' && *value <= '9')) + { + return parse_number(item, value); + } + + if (*value == '[') + { + return parse_array(item, value); + } + + if (*value == '{') + { + return parse_object(item, value); + } + + /* Failure. */ + + ep = value; + return 0; +} + +/* Render a value to text. */ + +static char *print_value(cJSON *item, int depth, int fmt) +{ + char *out = 0; + if (!item) + { + return 0; + } + + switch ((item->type) & 255) + { + case cJSON_NULL: + out = cJSON_strdup("null"); + break; + + case cJSON_False: + out = cJSON_strdup("false"); + break; + + case cJSON_True: + out = cJSON_strdup("true"); + break; + + case cJSON_Number: + out = print_number(item); + break; + + case cJSON_String: + out = print_string(item); + break; + + case cJSON_Array: + out = print_array(item, depth, fmt); + break; + + case cJSON_Object: + out = print_object(item, depth, fmt); + break; + } + + return out; +} + +/* Build an array from input text. */ + +static const char *parse_array(cJSON *item, const char *value) +{ + cJSON *child; + + if (*value != '[') + { + /* not an array! */ + + ep = value; + return 0; + } + + item->type = cJSON_Array; + value = skip(value + 1); + if (*value == ']') + { + /* Empty array. */ + + return value + 1; + } + + item->child = child = cJSON_New_Item(); + if (!item->child) + { + /* Memory fail */ + + return 0; + } + + /* Skip any spacing, get the value. */ + + value = skip(parse_value(child, skip(value))); + if (!value) + { + return 0; + } + + while (*value == ',') + { + cJSON *new_item; + if (!(new_item = cJSON_New_Item())) + { + /* next = new_item; + new_item->prev = child; + child = new_item; + value = skip(parse_value(child, skip(value + 1))); + if (!value) + { + /* Memory fail */ + + return 0; + } + } + + if (*value == ']') + { + /* End of array */ + + return value + 1; + } + + /* Malformed */ + + ep = value; + return 0; +} + +/* Render an array to text */ + +static char *print_array(cJSON *item, int depth, int fmt) +{ + char **entries; + char *out = 0; + char *ptr; + char *ret; + int len = 5; + cJSON *child = item->child; + int numentries = 0; + int i = 0; + int fail = 0; + + /* How many entries in the array? */ + + while (child) + { + numentries++, child = child->next; + } + + /* Allocate an array to hold the values for each */ + + entries = (char **)cJSON_malloc(numentries * sizeof(char *)); + if (!entries) + { + return 0; + } + + memset(entries, 0, numentries * sizeof(char *)); + + /* Retrieve all the results: */ + + child = item->child; + while (child && !fail) + { + ret = print_value(child, depth + 1, fmt); + entries[i++] = ret; + if (ret) + { + len += strlen(ret) + 2 + (fmt ? 1 : 0); + } + else + { + fail = 1; + } + + child = child->next; + } + + /* If we didn't fail, try to malloc the output string */ + + if (!fail) + { + out = (char *)cJSON_malloc(len); + } + + /* If that fails, we fail. */ + + if (!out) + { + fail = 1; + } + + /* Handle failure. */ + + if (fail) + { + for (i = 0; i < numentries; i++) + { + if (entries[i]) + { + cJSON_free(entries[i]); + } + } + + cJSON_free(entries); + return 0; + } + + /* Compose the output array. */ + + *out = '['; + ptr = out + 1; + *ptr = 0; + for (i = 0; i < numentries; i++) + { + strcpy(ptr, entries[i]); + ptr += strlen(entries[i]); + if (i != numentries - 1) + { + *ptr++ = ','; + if (fmt) + { + *ptr++ = ' '; + } + + *ptr = 0; + } + cJSON_free(entries[i]); + } + + cJSON_free(entries); + *ptr++ = ']'; + *ptr++ = 0; + return out; +} + +/* Build an object from the text. */ + +static const char *parse_object(cJSON *item, const char *value) +{ + cJSON *child; + if (*value != '{') + { + /* Not an object! */ + + ep = value; + return 0; + } + + item->type = cJSON_Object; + value = skip(value + 1); + if (*value == '}') + { + /* Empty array. */ + + return value + 1; + } + + item->child = child = cJSON_New_Item(); + if (!item->child) + { + return 0; + } + + value = skip(parse_string(child, skip(value))); + if (!value) + { + return 0; + } + + child->string = child->valuestring; + child->valuestring = 0; + if (*value != ':') + { + ep = value; + return 0; + } + + /* Skip any spacing, get the value. */ + + value = skip(parse_value(child, skip(value + 1))); + if (!value) + { + return 0; + } + + while (*value == ',') + { + cJSON *new_item; + if (!(new_item = cJSON_New_Item())) + { + /* Memory fail */ + + return 0; + } + + child->next = new_item; + new_item->prev = child; + child = new_item; + value = skip(parse_string(child, skip(value + 1))); + if (!value) + { + return 0; + } + + child->string = child->valuestring; + child->valuestring = 0; + if (*value != ':') + { + ep = value; + return 0; + } + + /* Skip any spacing, get the value. */ + + value = skip(parse_value(child, skip(value + 1))); + if (!value) + { + return 0; + } + } + + if (*value == '}') + { + /* End of array */ + + return value + 1; + } + + /* Malformed */ + + ep = value; + return 0; +} + +/* Render an object to text. */ + +static char *print_object(cJSON *item, int depth, int fmt) +{ + char **entries = 0; + char **names = 0; + char *out = 0; + char *ptr; + char *ret; + char *str; + int len = 7; + int i = 0; + int j; + cJSON *child = item->child; + int numentries = 0; + int fail = 0; + + /* Count the number of entries. */ + + while (child) + { + numentries++, child = child->next; + } + + /* Allocate space for the names and the objects */ + + entries = (char **)cJSON_malloc(numentries * sizeof(char *)); + if (!entries) + { + return 0; + } + + names = (char **)cJSON_malloc(numentries * sizeof(char *)); + if (!names) + { + cJSON_free(entries); + return 0; + } + + memset(entries, 0, sizeof(char *) * numentries); + memset(names, 0, sizeof(char *) * numentries); + + /* Collect all the results into our arrays: */ + + child = item->child; + depth++; + if (fmt) + { + len += depth; + } + + while (child) + { + names[i] = str = print_string_ptr(child->string); + entries[i++] = ret = print_value(child, depth, fmt); + if (str && ret) + { + len += strlen(ret) + strlen(str) + 2 + (fmt ? 2 + depth : 0); + } + else + { + fail = 1; + } + + child = child->next; + } + + /* Try to allocate the output string */ + + if (!fail) + { + out = (char *)cJSON_malloc(len); + } + + if (!out) + { + fail = 1; + } + + /* Handle failure */ + + if (fail) + { + for (i = 0; i < numentries; i++) + { + if (names[i]) + { + cJSON_free(names[i]); + } + + if (entries[i]) + { + cJSON_free(entries[i]); + } + } + + cJSON_free(names); + cJSON_free(entries); + return 0; + } + + /* Compose the output: */ + + *out = '{'; + ptr = out + 1; + if (fmt) + { + *ptr++ = '\n'; + } + *ptr = 0; + + for (i = 0; i < numentries; i++) + { + if (fmt) + { + for (j = 0; j < depth; j++) + { + *ptr++ = '\t'; + } + } + + strcpy(ptr, names[i]); + ptr += strlen(names[i]); + *ptr++ = ':'; + if (fmt) + { + *ptr++ = '\t'; + } + + strcpy(ptr, entries[i]); + ptr += strlen(entries[i]); + if (i != numentries - 1) + { + *ptr++ = ','; + } + + if (fmt) + { + *ptr++ = '\n'; + } + + *ptr = 0; + cJSON_free(names[i]); + cJSON_free(entries[i]); + } + + cJSON_free(names); + cJSON_free(entries); + if (fmt) + { + for (i = 0; i < depth - 1; i++) + { + *ptr++ = '\t'; + } + } + + *ptr++ = '}'; + *ptr++ = 0; + return out; +} + +/* Utility for array list handling. */ + +static void suffix_object(cJSON *prev, cJSON *item) +{ + prev->next = item; + item->prev = prev; +} + +/* Utility for handling references. */ + +static cJSON *create_reference(cJSON *item) +{ + cJSON *ref = cJSON_New_Item(); + if (!ref) + { + return 0; + } + + memcpy(ref, item, sizeof(cJSON)); + ref->string = 0; + ref->type |= cJSON_IsReference; + ref->next = ref->prev = 0; + return ref; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +const char *cJSON_GetErrorPtr(void) +{ + return ep; +} + +void cJSON_InitHooks(cJSON_Hooks *hooks) +{ + if (!hooks) + { + /* Reset hooks */ + + cJSON_malloc = malloc; + cJSON_free = free; + return; + } + + cJSON_malloc = (hooks->malloc_fn) ? hooks->malloc_fn : malloc; + cJSON_free = (hooks->free_fn) ? hooks->free_fn : free; +} + +/* Delete a cJSON structure. */ + +void cJSON_Delete(cJSON *c) +{ + cJSON *next; + while (c) + { + next = c->next; + if (!(c->type & cJSON_IsReference) && c->child) + { + cJSON_Delete(c->child); + } + + if (!(c->type & cJSON_IsReference) && c->valuestring) + { + cJSON_free(c->valuestring); + } + + if (c->string) + { + cJSON_free(c->string); + } + + cJSON_free(c); + c = next; + } +} + +/* Parse an object - create a new root, and populate. */ + +cJSON *cJSON_Parse(const char *value) +{ + cJSON *c = cJSON_New_Item(); + ep = 0; + if (!c) + { + /* Memory fail */ + + return 0; + } + + if (!parse_value(c, skip(value))) + { + cJSON_Delete(c); + return 0; + } + + return c; +} + +/* Render a cJSON item/entity/structure to text. */ + +char *cJSON_Print(cJSON *item) +{ + return print_value(item, 0, 1); +} + +char *cJSON_PrintUnformatted(cJSON *item) +{ + return print_value(item, 0, 0); +} + +/* Get Array size/item / object item. */ + +int cJSON_GetArraySize(cJSON *array) +{ + cJSON *c = array->child; + int i = 0; + + while (c) + { + i++; + c = c->next; + } + + return i; +} + +cJSON *cJSON_GetArrayItem(cJSON *array, int item) +{ + cJSON *c = array->child; + + while (c && item > 0) + { + item--; + c = c->next; + } + + return c; +} + +cJSON *cJSON_GetObjectItem(cJSON *object, const char *string) +{ + cJSON *c = object->child; + + while (c && cJSON_strcasecmp(c->string, string)) + { + c = c->next; + } + + return c; +} + +/* Add item to array/object. */ +void cJSON_AddItemToArray(cJSON *array, cJSON *item) +{ + cJSON *c = array->child; + + if (!item) + { + return; + } + + if (!c) + { + array->child = item; + } + else + { + while (c && c->next) + { + c = c->next; + } + + suffix_object(c, item); + } +} + +void cJSON_AddItemToObject(cJSON *object, const char *string, cJSON *item) +{ + if (!item) + { + return; + } + + if (item->string) + { + cJSON_free(item->string); + } + + item->string = cJSON_strdup(string); + cJSON_AddItemToArray(object, item); +} + +void cJSON_AddItemReferenceToArray(cJSON *array, cJSON *item) +{ + cJSON_AddItemToArray(array, create_reference(item)); +} + +void cJSON_AddItemReferenceToObject(cJSON *object, const char *string, cJSON *item) +{ + cJSON_AddItemToObject(object, string, create_reference(item)); +} + +cJSON *cJSON_DetachItemFromArray(cJSON *array, int which) +{ + cJSON *c = array->child; + + while (c && which > 0) + { + c = c->next, which--; + } + + if (!c) + { + return 0; + } + + if (c->prev) + { + c->prev->next = c->next; + } + + if (c->next) + { + c->next->prev = c->prev; + } + + if (c == array->child) + { + array->child = c->next; + } + + c->prev = c->next = 0; + return c; +} + +void cJSON_DeleteItemFromArray(cJSON *array, int which) +{ + cJSON_Delete(cJSON_DetachItemFromArray(array, which)); +} + +cJSON *cJSON_DetachItemFromObject(cJSON *object, const char *string) +{ + int i = 0; + cJSON *c = object->child; + + while (c && cJSON_strcasecmp(c->string, string)) + { + i++; + c = c->next; + } + + if (c) + { + return cJSON_DetachItemFromArray(object, i); + } + + return 0; +} + +void cJSON_DeleteItemFromObject(cJSON *object, const char *string) +{ + cJSON_Delete(cJSON_DetachItemFromObject(object, string)); +} + +/* Replace array/object items with new ones. */ + +void cJSON_ReplaceItemInArray(cJSON *array, int which, cJSON *newitem) +{ + cJSON *c = array->child; + + while (c && which > 0) + { + c = c->next, which--; + } + + if (!c) + { + return; + } + + newitem->next = c->next; + newitem->prev = c->prev; + if (newitem->next) + { + newitem->next->prev = newitem; + } + + if (c == array->child) + { + array->child = newitem; + } + else + { + newitem->prev->next = newitem; + } + + c->next = c->prev = 0; + cJSON_Delete(c); +} + +void cJSON_ReplaceItemInObject(cJSON *object, const char *string, cJSON *newitem) +{ + int i = 0; + cJSON *c = object->child; + + while (c && cJSON_strcasecmp(c->string, string)) + { + i++; + c = c->next; + } + + if (c) + { + newitem->string = cJSON_strdup(string); + cJSON_ReplaceItemInArray(object, i, newitem); + } +} + +/* Create basic types: */ + +cJSON *cJSON_CreateNull() +{ + cJSON *item = cJSON_New_Item(); + if (item) + { + item->type = cJSON_NULL; + } + + return item; +} + +cJSON *cJSON_CreateTrue() +{ + cJSON *item = cJSON_New_Item(); + if (item) + { + item->type = cJSON_True; + } + + return item; +} + +cJSON *cJSON_CreateFalse() +{ + cJSON *item = cJSON_New_Item(); + if (item) + { + item->type = cJSON_False; + } + + return item; +} + +cJSON *cJSON_CreateBool(int b) +{ + cJSON *item = cJSON_New_Item(); + if (item) + { + item->type = b ? cJSON_True : cJSON_False; + } + + return item; +} + +cJSON *cJSON_CreateNumber(double num) +{ + cJSON *item = cJSON_New_Item(); + if (item) + { + item->type = cJSON_Number; + item->valuedouble = num; + item->valueint = (int)num; + } + + return item; +} + +cJSON *cJSON_CreateString(const char *string) +{ + cJSON *item = cJSON_New_Item(); + if (item) + { + item->type = cJSON_String; + item->valuestring = cJSON_strdup(string); + } + + return item; +} + +cJSON *cJSON_CreateArray() +{ + cJSON *item = cJSON_New_Item(); + if (item) + { + item->type = cJSON_Array; + } + + return item; +} + +cJSON *cJSON_CreateObject() +{ + cJSON *item = cJSON_New_Item(); + if (item) + { + item->type = cJSON_Object; + } + + return item; +} + +/* Create Arrays: */ + +cJSON *cJSON_CreateIntArray(const int *numbers, int count) +{ + cJSON *n = 0; + cJSON *p = 0; + cJSON *a = cJSON_CreateArray(); + int i; + + for (i = 0; a && i < count; i++) + { + n = cJSON_CreateNumber(numbers[i]); + if (!i) + { + a->child = n; + } + else + { + suffix_object(p, n); + } + + p = n; + } + + return a; +} + +cJSON *cJSON_CreateFloatArray(const float *numbers, int count) +{ + cJSON *n = 0; + cJSON *p = 0; + cJSON *a = cJSON_CreateArray(); + int i; + + for (i = 0; a && i < count; i++) + { + n = cJSON_CreateNumber(numbers[i]); + if (!i) + { + a->child = n; + } + else + { + suffix_object(p, n); + } + + p = n; + } + + return a; +} + +cJSON *cJSON_CreateDoubleArray(const double *numbers, int count) +{ + cJSON *n = 0; + cJSON *p = 0; + cJSON *a = cJSON_CreateArray(); + int i; + + for (i = 0; a && i < count; i++) + { + n = cJSON_CreateNumber(numbers[i]); + if (!i) + { + a->child = n; + } + else + { + suffix_object(p, n); + } + + p = n; + } + + return a; +} + +cJSON *cJSON_CreateStringArray(const char **strings, int count) +{ + cJSON *n = 0; + cJSON *p = 0; + cJSON *a = cJSON_CreateArray(); + int i; + + for (i = 0; a && i < count; i++) + { + n = cJSON_CreateString(strings[i]); + if (!i) + { + a->child = n; + } + else + { + suffix_object(p, n); + } + + p = n; + } + + return a; +} diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index a80e5009a8..3b39eabb4f 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3523,4 +3523,6 @@ Add a configuration for testing the ARM ELF loader. * binfmt/libelf: Can't use fstat(). NuttX does not yet support it. Damn! * binfmt/libelf: The basic ELF module execution appears fully functional. + * configs/shenzhou/src/up_relays.c: Add support for relays from the + Shenzhou board. Contributed by Darcy Gong. diff --git a/nuttx/Documentation/README.html b/nuttx/Documentation/README.html index 9424262609..5fef40fc16 100644 --- a/nuttx/Documentation/README.html +++ b/nuttx/Documentation/README.html @@ -8,7 +8,7 @@

    NuttX README Files

    -

    Last Updated: September 25, 2012

    +

    Last Updated: October 27, 2012

    @@ -247,6 +247,7 @@ `- apps/ |- README.txt |- examples/ + | |- json/README.txt | |- pashello/README.txt | `- README.txt |- graphics/ @@ -259,6 +260,7 @@ |- netutils/ | | |- discover/README.txt | | |- ftpc/README.txt + | | |- json/README.txt | | |- telnetd/README.txt | `- README.txt |- nshlib/ diff --git a/nuttx/README.txt b/nuttx/README.txt index d60da2d889..4c008e6f16 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -828,6 +828,7 @@ nuttx apps |- examples/ + | |- json/README.txt | |- pashello/README.txt | `- README.txt |- graphics/ @@ -843,6 +844,8 @@ apps | | `- README.txt | |- ftpc | | `- README.txt + | |- json + | | `- README.txt | |- telnetd | | `- README.txt | `- README.txt From 0b6dd037e6acaba9cba46754890cc43f9b8d1b5c Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 28 Oct 2012 13:20:36 +0000 Subject: [PATCH 037/206] DNS fixes from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5268 42af7a65-404d-4744-a932-0658087f49c3 --- apps/COPYING | 137 +++++++++++++++++++++++++++++++++ apps/ChangeLog.txt | 4 +- apps/include/netutils/resolv.h | 11 +++ apps/netutils/json/cJSON.c | 2 +- apps/netutils/resolv/resolv.c | 108 +++++++++++++++++++++----- apps/nshlib/Kconfig | 19 ++++- apps/nshlib/nsh_netinit.c | 10 ++- 7 files changed, 267 insertions(+), 24 deletions(-) create mode 100644 apps/COPYING diff --git a/apps/COPYING b/apps/COPYING new file mode 100644 index 0000000000..7e8fd8407a --- /dev/null +++ b/apps/COPYING @@ -0,0 +1,137 @@ +COPYING -- Describes the terms under which Nuttx is distributed. A +copy of the BSD-style licensing is included in this file. In my +words -- I believe that you should free to use NuttX in any +environment, private, private, commercial, open, closed, etc. +provided only that you repect the modest copyright notices as +described in license (below). Please feel free to contact me if you +have any licensing concerns. + +NuttX +^^^^^^ + +License for NuttX in general (authorship of individual files may vary): + + Copyright (C) 2007-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. + +uIP +^^^ + +Some lower-level networking middle-ware components of NuttX +derive from uIP which has a similar BSD style license: + + Copyright (c) 2001-2003, Adam Dunkels. + All rights reserved. + +FreeModbus +^^^^^^^^^ + +FreeModbus Libary: A portable Modbus implementation for Modbus ASCII/RTU. +Copyright (c) 2006 Christian Walter +All rights reserved. + +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. The name of the author may not be used to endorse or promote products + derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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. + +THTTPD +^^^^^^ + +Derived from the original THTTPD package: + + Copyright © 1995,1998,1999,2000,2001 by Jef Poskanzer . + All rights reserved. + +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. + +THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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. + +cJSON +^^^^^ + +Derives from the cJSON Project which has an MIT license: + + Copyright (c) 2009 Dave Gamble + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. + diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index b75637ad23..5020eb1c7c 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -387,4 +387,6 @@ * apps/netutils/json: Add a snapshot of the cJSON project. Contributed by Darcy Gong. * apps/examples/json: Test example for cJSON from Darcy Gong - + * apps/nshlib/nsh_netinit.c: Fix static IP DNS problem (Darcy Gong) + * apps/netutils/resolv/resolv.c: DNS fixes from Darcy Gong. + * COPYING: Licensing information added. diff --git a/apps/include/netutils/resolv.h b/apps/include/netutils/resolv.h index b0d93fd822..8d21427325 100644 --- a/apps/include/netutils/resolv.h +++ b/apps/include/netutils/resolv.h @@ -63,19 +63,30 @@ extern "C" { /* Functions. */ EXTERN int resolv_init(void); +EXTERN int resolv_create(int *sockfd); +EXTERN int resolv_release(int *sockfd); +EXTERN int resolv_gethostip_socket(int sockfd, const char *hostname, in_addr_t *ipaddr); +EXTERN int resolv_gethostip(const char *hostname, in_addr_t *ipaddr); #ifdef CONFIG_NET_IPv6 EXTERN void resolv_conf(FAR const struct in6_addr *dnsserver); EXTERN void resolv_getserver(FAR const struct in_addr *dnsserver); EXTERN int resolv_query(FAR const char *name, FAR struct sockaddr_in6 *addr); +EXTERN int resolv_query_socket(int sockfd, FAR const char *name, FAR struct sockaddr_in6 *addr); #else EXTERN void resolv_conf(FAR const struct in_addr *dnsserver); EXTERN void resolv_getserver(FAR struct in_addr *dnsserver); EXTERN int resolv_query(FAR const char *name, FAR struct sockaddr_in *addr); +EXTERN int resolv_query_socket(int sockfd, FAR const char *name, FAR struct sockaddr_in *addr); #endif EXTERN int dns_gethostip(const char *hostname, in_addr_t *ipaddr); +#define dns_init resolv_init +#define dns_bind resolv_create +#define dns_query resolv_gethostip_socket +#define dns_free resolv_release + #define dns_setserver resolv_conf #define dns_getserver resolv_getserver #define dns_whois resolv_query diff --git a/apps/netutils/json/cJSON.c b/apps/netutils/json/cJSON.c index 12eaab2433..85091c9487 100644 --- a/apps/netutils/json/cJSON.c +++ b/apps/netutils/json/cJSON.c @@ -36,7 +36,7 @@ #include #include -#include +#include #include #include #include diff --git a/apps/netutils/resolv/resolv.c b/apps/netutils/resolv/resolv.c index eb60c098e2..346cbe175f 100644 --- a/apps/netutils/resolv/resolv.c +++ b/apps/netutils/resolv/resolv.c @@ -202,9 +202,9 @@ static unsigned char *parse_name(unsigned char *query) */ #ifdef CONFIG_NET_IPv6 -static int send_query(const char *name, struct sockaddr_in6 *addr) +static int send_query_socket(int sockfd, const char *name, struct sockaddr_in6 *addr) #else -static int send_query(const char *name, struct sockaddr_in *addr) +static int send_query_socket(int sockfd, const char *name, struct sockaddr_in *addr) #endif { register struct dns_hdr *hdr; @@ -247,7 +247,16 @@ static int send_query(const char *name, struct sockaddr_in *addr) DEBUGASSERT(((struct sockaddr *)addr)->sa_family == AF_INET); #endif - return sendto(g_sockfd, buffer, query + 5 - buffer, 0, (struct sockaddr*)addr, ADDRLEN); + return sendto(sockfd, buffer, query + 5 - buffer, 0, (struct sockaddr*)addr, ADDRLEN); +} + +#ifdef CONFIG_NET_IPv6 +static int send_query(const char *name, struct sockaddr_in6 *addr) +#else +static int send_query(const char *name, struct sockaddr_in *addr) +#endif +{ + return send_query_socket(g_sockfd, name, addr); } /* Called when new UDP data arrives */ @@ -255,7 +264,7 @@ static int send_query(const char *name, struct sockaddr_in *addr) #ifdef CONFIG_NET_IPv6 #error "Not implemented" #else -int recv_response(struct sockaddr_in *addr) +int recv_response_socket(int sockfd, struct sockaddr_in *addr) #endif { unsigned char *nameptr; @@ -268,7 +277,7 @@ int recv_response(struct sockaddr_in *addr) /* Receive the response */ - ret = recv(g_sockfd, buffer, RECV_BUFFER_SIZE, 0); + ret = recv(sockfd, buffer, RECV_BUFFER_SIZE, 0); if (ret < 0) { return ret; @@ -377,15 +386,24 @@ int recv_response(struct sockaddr_in *addr) return ERROR; } +#ifdef CONFIG_NET_IPv6 +#error "Not implemented" +#else +int recv_response(struct sockaddr_in *addr) +#endif +{ + return recv_response_socket(g_sockfd, addr); +} + /**************************************************************************** * Public Functions ****************************************************************************/ /**************************************************************************** - * Name: dns_gethostip + * Name: resolv_gethostip ****************************************************************************/ -int dns_gethostip(const char *hostname, in_addr_t *ipaddr) +int resolv_gethostip_socket(int sockfd, const char *hostname, in_addr_t *ipaddr) { #ifdef CONFIG_HAVE_GETHOSTBYNAME @@ -421,7 +439,7 @@ int dns_gethostip(const char *hostname, in_addr_t *ipaddr) * the host name to an IP address. */ - if (resolv_query(hostname, &addr) < 0) + if (resolv_query_socket(sockfd, hostname, &addr) < 0) { /* Needs to set the errno here */ @@ -437,12 +455,32 @@ int dns_gethostip(const char *hostname, in_addr_t *ipaddr) #endif } +int resolv_gethostip(const char *hostname, in_addr_t *ipaddr) +{ + return resolv_gethostip_socket(g_sockfd, hostname, ipaddr); +} + +int dns_gethostip(const char *hostname, in_addr_t *ipaddr) +{ + int sockfd = -1; + int ret=ERROR; + + resolv_create(&sockfd); + if (sockfd >= 0) + { + ret = resolv_gethostip_socket(sockfd, hostname, ipaddr); + resolv_release(&sockfd); + } + + return ret; +} + /* Get the binding for name. */ #ifdef CONFIG_NET_IPv6 -int resolv_query(FAR const char *name, FAR struct sockaddr_in6 *addr) +int resolv_query_socket(int sockfd, FAR const char *name, FAR struct sockaddr_in6 *addr) #else -int resolv_query(FAR const char *name, FAR struct sockaddr_in *addr) +int resolv_query_socket(int sockfd, FAR const char *name, FAR struct sockaddr_in *addr) #endif { int retries; @@ -452,12 +490,12 @@ int resolv_query(FAR const char *name, FAR struct sockaddr_in *addr) for (retries = 0; retries < 3; retries++) { - if (send_query(name, &g_dnsserver) < 0) + if (send_query_socket(sockfd, name, &g_dnsserver) < 0) { return ERROR; } - ret = recv_response(addr); + ret = recv_response_socket(sockfd, addr); if (ret >= 0) { /* Response received successfully */ @@ -476,6 +514,15 @@ int resolv_query(FAR const char *name, FAR struct sockaddr_in *addr) return ERROR; } +#ifdef CONFIG_NET_IPv6 +int resolv_query(FAR const char *name, FAR struct sockaddr_in6 *addr) +#else +int resolv_query(FAR const char *name, FAR struct sockaddr_in *addr) +#endif +{ + return resolv_query_socket(g_sockfd, name, addr); +} + /* Obtain the currently configured DNS server. */ #ifdef CONFIG_NET_IPv6 @@ -508,13 +555,29 @@ void resolv_conf(const struct in_addr *dnsserver) #endif } -/* Initalize the resolver. */ +/* Release the resolver. */ -int resolv_init(void) +int resolv_release(int *sockfd) +{ + if (*sockfd >= 0) + { + close(*sockfd); + *sockfd = -1; + } + + return OK; +} + +/* Create the resolver. */ + +int resolv_create(int *sockfd) { struct timeval tv; - g_sockfd = socket(PF_INET, SOCK_DGRAM, 0); - if (g_sockfd < 0) + + if (*sockfd >= 0) resolv_release(sockfd); + + *sockfd = socket(PF_INET, SOCK_DGRAM, 0); + if (*sockfd < 0) { return ERROR; } @@ -523,12 +586,19 @@ int resolv_init(void) tv.tv_sec = 30; tv.tv_usec = 0; - if (setsockopt(g_sockfd, SOL_SOCKET, SO_RCVTIMEO, &tv, sizeof(struct timeval)) < 0) + if (setsockopt(*sockfd, SOL_SOCKET, SO_RCVTIMEO, &tv, sizeof(struct timeval)) < 0) { - close(g_sockfd); - g_sockfd = -1; + close(*sockfd); + *sockfd = -1; return ERROR; } return OK; } + +/* Initalize the resolver. */ + +int resolv_init(void) +{ + return resolv_create(&g_sockfd); +} diff --git a/apps/nshlib/Kconfig b/apps/nshlib/Kconfig index 9bca6658cb..e89a4cc3f9 100644 --- a/apps/nshlib/Kconfig +++ b/apps/nshlib/Kconfig @@ -490,7 +490,7 @@ config NSH_DHCPC config NSH_IPADDR hex "Target IP address" - default 0x10000002 + default 0xa0000002 depends on NSH_LIBRARY && NET && !NSH_DHCPC ---help--- If NSH_DHCPC is NOT set, then the static IP address must be provided. @@ -499,7 +499,7 @@ config NSH_IPADDR config NSH_DRIPADDR hex "Router IP address" - default 0x10000001 + default 0xa0000001 depends on NSH_LIBRARY && NET && !NSH_DHCPC ---help--- Default router IP address (aka, Gateway). This is a 32-bit integer @@ -513,6 +513,21 @@ config NSH_NETMASK Network mask. This is a 32-bit integer value in host order. So, as an example, 0xffffff00 would be 255.255.255.0. +config NSH_DNS + bool "Use DNS" + default n + depends on NSH_LIBRARY && NET && NET_UDP && NET_BROADCAST + ---help--- + Configure to use a DNS. + +config NSH_DNSIPADDR + hex "DNS IP address" + default 0xa0000001 + depends on NSH_DNS + ---help--- + Configure the DNS address. This is a 32-bit integer value in host + order. So, as an example, 0xa0000001 would be 10.0.0.1. + config NSH_NOMAC bool "Hardware has no MAC address" default n diff --git a/apps/nshlib/nsh_netinit.c b/apps/nshlib/nsh_netinit.c index bc845c4ed3..535efd6a3c 100644 --- a/apps/nshlib/nsh_netinit.c +++ b/apps/nshlib/nsh_netinit.c @@ -60,6 +60,10 @@ * Definitions ****************************************************************************/ +#if defined(CONFIG_NSH_DRIPADDR) && !defined(CONFIG_NSH_DNSIPADDR) +# define CONFIG_NSH_DNSIPADDR CONFIG_NSH_DRIPADDR +#endif + /**************************************************************************** * Private Types ****************************************************************************/ @@ -125,10 +129,14 @@ int nsh_netinit(void) addr.s_addr = HTONL(CONFIG_NSH_NETMASK); uip_setnetmask("eth0", &addr); -#if defined(CONFIG_NSH_DHCPC) +#if defined(CONFIG_NSH_DHCPC) || defined(CONFIG_NSH_DNS) /* Set up the resolver */ resolv_init(); +#if defined(CONFIG_NSH_DNS) + addr.s_addr = HTONL(CONFIG_NSH_DNSIPADDR); + resolv_conf(&addr.s_addr); +#endif #endif #if defined(CONFIG_NSH_DHCPC) From 5b7a650b16980bb2a395fa76df170d8948da72a9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 28 Oct 2012 14:31:57 +0000 Subject: [PATCH 038/206] Part I of port of Rhombus math library git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5269 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 +- nuttx/Documentation/NuttxPortingGuide.html | 3 - nuttx/configs/README.txt | 1 - nuttx/configs/amber/hello/defconfig | 1 - nuttx/configs/avr32dev1/nsh/defconfig | 1 - nuttx/configs/avr32dev1/ostest/defconfig | 1 - nuttx/configs/c5471evm/httpd/defconfig | 1 - nuttx/configs/c5471evm/nettest/defconfig | 1 - nuttx/configs/c5471evm/nsh/defconfig | 1 - nuttx/configs/c5471evm/ostest/defconfig | 1 - .../configs/compal_e88/nsh_highram/defconfig | 1 - .../compal_e99/nsh_compalram/defconfig | 1 - .../configs/compal_e99/nsh_highram/defconfig | 1 - nuttx/configs/demo9s12ne64/ostest/defconfig | 1 - nuttx/configs/ea3131/nsh/defconfig | 1 - nuttx/configs/ea3131/ostest/defconfig | 1 - nuttx/configs/ea3131/pgnsh/defconfig | 1 - nuttx/configs/ea3131/usbserial/defconfig | 1 - nuttx/configs/ea3131/usbstorage/defconfig | 1 - nuttx/configs/ea3152/ostest/defconfig | 1 - nuttx/configs/eagle100/httpd/defconfig | 1 - nuttx/configs/eagle100/nettest/defconfig | 1 - nuttx/configs/eagle100/nsh/defconfig | 1 - nuttx/configs/eagle100/nxflat/defconfig | 1 - nuttx/configs/eagle100/ostest/defconfig | 1 - nuttx/configs/eagle100/thttpd/defconfig | 1 - nuttx/configs/ekk-lm3s9b96/nsh/defconfig | 1 - nuttx/configs/ekk-lm3s9b96/ostest/defconfig | 1 - .../configs/ez80f910200kitg/ostest/defconfig | 1 - nuttx/configs/ez80f910200zco/dhcpd/defconfig | 1 - nuttx/configs/ez80f910200zco/httpd/defconfig | 1 - .../configs/ez80f910200zco/nettest/defconfig | 1 - nuttx/configs/ez80f910200zco/nsh/defconfig | 1 - nuttx/configs/ez80f910200zco/ostest/defconfig | 1 - nuttx/configs/ez80f910200zco/poll/defconfig | 1 - nuttx/configs/fire-stm32v2/nsh/defconfig | 1 - nuttx/configs/hymini-stm32v/buttons/defconfig | 1 - nuttx/configs/hymini-stm32v/nsh/defconfig | 1 - nuttx/configs/hymini-stm32v/nsh2/defconfig | 1 - nuttx/configs/hymini-stm32v/nx/defconfig | 1 - nuttx/configs/hymini-stm32v/nxlines/defconfig | 1 - .../configs/hymini-stm32v/usbserial/defconfig | 1 - .../hymini-stm32v/usbstorage/defconfig | 1 - nuttx/configs/kwikstik-k40/ostest/defconfig | 1 - nuttx/configs/lincoln60/nsh/defconfig | 1 - nuttx/configs/lincoln60/ostest/defconfig | 1 - nuttx/configs/lm3s6432-s2e/nsh/defconfig | 1 - nuttx/configs/lm3s6432-s2e/ostest/defconfig | 1 - nuttx/configs/lm3s6965-ek/nsh/defconfig | 1 - nuttx/configs/lm3s6965-ek/nx/defconfig | 1 - nuttx/configs/lm3s6965-ek/ostest/defconfig | 1 - nuttx/configs/lm3s8962-ek/nsh/defconfig | 1 - nuttx/configs/lm3s8962-ek/nx/defconfig | 1 - nuttx/configs/lm3s8962-ek/ostest/defconfig | 1 - nuttx/configs/lpc4330-xplorer/nsh/defconfig | 1 - .../configs/lpc4330-xplorer/ostest/defconfig | 1 - .../lpcxpresso-lpc1768/dhcpd/defconfig | 1 - .../configs/lpcxpresso-lpc1768/nsh/defconfig | 1 - nuttx/configs/lpcxpresso-lpc1768/nx/defconfig | 1 - .../lpcxpresso-lpc1768/ostest/defconfig | 1 - .../lpcxpresso-lpc1768/thttpd/defconfig | 1 - .../lpcxpresso-lpc1768/usbstorage/defconfig | 1 - nuttx/configs/m68332evb/defconfig | 1 - nuttx/configs/mbed/hidkbd/defconfig | 1 - nuttx/configs/mbed/nsh/defconfig | 1 - .../mcu123-lpc214x/composite/defconfig | 1 - nuttx/configs/mcu123-lpc214x/nsh/defconfig | 1 - nuttx/configs/mcu123-lpc214x/ostest/defconfig | 1 - .../mcu123-lpc214x/usbserial/defconfig | 1 - .../mcu123-lpc214x/usbstorage/defconfig | 1 - nuttx/configs/micropendous3/hello/defconfig | 1 - nuttx/configs/mirtoo/nsh/defconfig | 1 - nuttx/configs/mirtoo/nxffs/defconfig | 1 - nuttx/configs/mirtoo/ostest/defconfig | 1 - nuttx/configs/mx1ads/ostest/defconfig | 1 - nuttx/configs/ne64badge/ostest/defconfig | 1 - nuttx/configs/ntosd-dm320/nettest/defconfig | 1 - nuttx/configs/ntosd-dm320/nsh/defconfig | 1 - nuttx/configs/ntosd-dm320/ostest/defconfig | 1 - nuttx/configs/ntosd-dm320/poll/defconfig | 1 - nuttx/configs/ntosd-dm320/thttpd/defconfig | 1 - nuttx/configs/ntosd-dm320/udp/defconfig | 1 - nuttx/configs/ntosd-dm320/uip/defconfig | 1 - nuttx/configs/nucleus2g/nsh/defconfig | 1 - nuttx/configs/nucleus2g/ostest/defconfig | 1 - nuttx/configs/nucleus2g/usbserial/defconfig | 1 - nuttx/configs/nucleus2g/usbstorage/defconfig | 1 - .../configs/olimex-lpc1766stk/ftpc/defconfig | 1 - .../olimex-lpc1766stk/hidkbd/defconfig | 1 - .../olimex-lpc1766stk/nettest/defconfig | 1 - nuttx/configs/olimex-lpc1766stk/nsh/defconfig | 1 - nuttx/configs/olimex-lpc1766stk/nx/defconfig | 1 - .../olimex-lpc1766stk/ostest/defconfig | 1 - .../olimex-lpc1766stk/slip-httpd/defconfig | 1 - .../olimex-lpc1766stk/thttpd/defconfig | 1 - .../olimex-lpc1766stk/usbserial/defconfig | 1 - .../olimex-lpc1766stk/usbstorage/defconfig | 1 - .../configs/olimex-lpc1766stk/wlan/defconfig | 1 - nuttx/configs/olimex-lpc2378/nsh/defconfig | 1 - nuttx/configs/olimex-lpc2378/ostest/defconfig | 1 - nuttx/configs/olimex-stm32-p107/nsh/defconfig | 1 - .../olimex-stm32-p107/ostest/defconfig | 1 - .../configs/olimex-strp711/nettest/defconfig | 1 - nuttx/configs/olimex-strp711/nsh/defconfig | 1 - nuttx/configs/olimex-strp711/ostest/defconfig | 1 - nuttx/configs/pcblogic-pic32mx/nsh/defconfig | 1 - .../configs/pcblogic-pic32mx/ostest/defconfig | 1 - nuttx/configs/pic32-starterkit/nsh/defconfig | 1 - nuttx/configs/pic32-starterkit/nsh2/defconfig | 1 - .../configs/pic32-starterkit/ostest/defconfig | 1 - nuttx/configs/pic32mx7mmb/nsh/defconfig | 1 - nuttx/configs/pic32mx7mmb/ostest/defconfig | 1 - nuttx/configs/pjrc-8051/defconfig | 1 - nuttx/configs/qemu-i486/nsh/defconfig | 1 - nuttx/configs/qemu-i486/ostest/defconfig | 1 - nuttx/configs/rgmp/arm/default/defconfig | 1 - nuttx/configs/rgmp/arm/nsh/defconfig | 1 - nuttx/configs/rgmp/x86/default/defconfig | 1 - nuttx/configs/rgmp/x86/nsh/defconfig | 1 - nuttx/configs/sam3u-ek/knsh/defconfig | 1 - nuttx/configs/sam3u-ek/nsh/defconfig | 1 - nuttx/configs/sam3u-ek/nx/defconfig | 1 - nuttx/configs/sam3u-ek/ostest/defconfig | 1 - nuttx/configs/sam3u-ek/touchscreen/defconfig | 1 - nuttx/configs/shenzhou/nsh/defconfig | 1 - nuttx/configs/shenzhou/nxwm/defconfig | 1 - nuttx/configs/shenzhou/thttpd/defconfig | 1 - nuttx/configs/sim/mount/defconfig | 1 - nuttx/configs/sim/nettest/defconfig | 1 - nuttx/configs/sim/nsh/defconfig | 1 - nuttx/configs/sim/nsh2/defconfig | 1 - nuttx/configs/sim/nx/defconfig | 1 - nuttx/configs/sim/nx11/defconfig | 1 - nuttx/configs/sim/nxffs/defconfig | 1 - nuttx/configs/sim/nxwm/defconfig | 1 - nuttx/configs/sim/ostest/defconfig | 1 - nuttx/configs/sim/pashello/defconfig | 1 - nuttx/configs/sim/touchscreen/defconfig | 1 - nuttx/configs/skp16c26/ostest/defconfig | 1 - nuttx/configs/stm3210e-eval/RIDE/defconfig | 1 - nuttx/configs/stm3210e-eval/buttons/defconfig | 1 - .../configs/stm3210e-eval/composite/defconfig | 1 - nuttx/configs/stm3210e-eval/nsh/defconfig | 1 - nuttx/configs/stm3210e-eval/nsh2/defconfig | 1 - nuttx/configs/stm3210e-eval/nx/defconfig | 1 - .../configs/stm3210e-eval/nxconsole/defconfig | 1 - nuttx/configs/stm3210e-eval/nxlines/defconfig | 1 - nuttx/configs/stm3210e-eval/nxtext/defconfig | 1 - nuttx/configs/stm3210e-eval/ostest/defconfig | 1 - nuttx/configs/stm3210e-eval/pm/defconfig | 1 - .../configs/stm3210e-eval/usbserial/defconfig | 1 - .../stm3210e-eval/usbstorage/defconfig | 1 - nuttx/configs/stm3220g-eval/dhcpd/defconfig | 1 - nuttx/configs/stm3220g-eval/nettest/defconfig | 1 - nuttx/configs/stm3220g-eval/nsh/defconfig | 1 - nuttx/configs/stm3220g-eval/nsh2/defconfig | 1 - nuttx/configs/stm3220g-eval/nxwm/defconfig | 1 - nuttx/configs/stm3220g-eval/ostest/defconfig | 1 - nuttx/configs/stm3220g-eval/telnetd/defconfig | 1 - nuttx/configs/stm3240g-eval/dhcpd/defconfig | 1 - .../configs/stm3240g-eval/discover/defconfig | 1 - nuttx/configs/stm3240g-eval/nettest/defconfig | 1 - nuttx/configs/stm3240g-eval/nsh/defconfig | 1 - nuttx/configs/stm3240g-eval/nsh2/defconfig | 1 - .../configs/stm3240g-eval/nxconsole/defconfig | 1 - nuttx/configs/stm3240g-eval/nxwm/defconfig | 1 - nuttx/configs/stm3240g-eval/ostest/defconfig | 1 - nuttx/configs/stm3240g-eval/telnetd/defconfig | 1 - .../configs/stm3240g-eval/webserver/defconfig | 1 - nuttx/configs/stm3240g-eval/xmlrpc/defconfig | 1 - nuttx/configs/stm32f4discovery/elf/defconfig | 1 - nuttx/configs/stm32f4discovery/nsh/defconfig | 1 - .../stm32f4discovery/nxlines/defconfig | 1 - .../configs/stm32f4discovery/ostest/defconfig | 1 - nuttx/configs/stm32f4discovery/pm/defconfig | 1 - nuttx/configs/sure-pic32mx/nsh/defconfig | 1 - nuttx/configs/sure-pic32mx/ostest/defconfig | 1 - nuttx/configs/sure-pic32mx/usbnsh/defconfig | 1 - nuttx/configs/teensy/hello/defconfig | 1 - nuttx/configs/teensy/nsh/defconfig | 1 - nuttx/configs/teensy/usbstorage/defconfig | 1 - nuttx/configs/twr-k60n512/nsh/defconfig | 1 - nuttx/configs/twr-k60n512/ostest/defconfig | 1 - nuttx/configs/ubw32/nsh/defconfig | 1 - nuttx/configs/ubw32/ostest/defconfig | 1 - nuttx/configs/us7032evb1/nsh/defconfig | 1 - nuttx/configs/us7032evb1/ostest/defconfig | 1 - nuttx/configs/vsn/nsh/defconfig | 1 - nuttx/configs/xtrs/nsh/defconfig | 1 - nuttx/configs/xtrs/ostest/defconfig | 1 - nuttx/configs/xtrs/pashello/defconfig | 1 - .../configs/z16f2800100zcog/ostest/defconfig | 1 - .../z16f2800100zcog/pashello/defconfig | 1 - nuttx/configs/z80sim/nsh/defconfig | 1 - nuttx/configs/z80sim/ostest/defconfig | 1 - nuttx/configs/z80sim/pashello/defconfig | 1 - nuttx/configs/z8encore000zco/ostest/defconfig | 1 - nuttx/configs/z8f64200100kit/ostest/defconfig | 1 - nuttx/lib/Kconfig | 23 +- nuttx/lib/Makefile | 2 +- nuttx/lib/README.txt | 3 +- nuttx/lib/fixedmath/Make.defs | 43 +++ nuttx/lib/{math => fixedmath}/lib_b16atan2.c | 2 +- nuttx/lib/{math => fixedmath}/lib_b16cos.c | 2 +- nuttx/lib/{math => fixedmath}/lib_b16sin.c | 2 +- nuttx/lib/{math => fixedmath}/lib_fixedmath.c | 0 nuttx/lib/{math => fixedmath}/lib_rint.c | 2 +- nuttx/lib/math/Kconfig | 4 + nuttx/lib/math/Make.defs | 14 +- nuttx/lib/math/Makefile | 100 +++++++ nuttx/lib/math/lib_acos.c | 30 +++ nuttx/lib/math/lib_asin.c | 88 ++++++ nuttx/lib/math/lib_atan.c | 32 +++ nuttx/lib/math/lib_atan2.c | 120 +++++++++ nuttx/lib/math/lib_ceil.c | 37 +++ nuttx/lib/math/lib_cos.c | 31 +++ nuttx/lib/math/lib_cosh.c | 33 +++ nuttx/lib/math/lib_exp.c | 253 ++++++++++++++++++ nuttx/lib/math/lib_fabs.c | 30 +++ nuttx/lib/math/lib_floor.c | 37 +++ nuttx/lib/math/lib_fmod.c | 67 +++++ nuttx/lib/math/lib_frexp.c | 34 +++ nuttx/lib/math/lib_ldexp.c | 31 +++ nuttx/lib/math/lib_log.c | 113 ++++++++ nuttx/lib/math/lib_log10.c | 30 +++ nuttx/lib/math/lib_log2.c | 30 +++ nuttx/lib/math/lib_modf.c | 65 +++++ nuttx/lib/math/lib_pow.c | 30 +++ nuttx/lib/math/lib_sin.c | 152 +++++++++++ nuttx/lib/math/lib_sinh.c | 33 +++ nuttx/lib/math/lib_sqrt.c | 116 ++++++++ nuttx/lib/math/lib_tan.c | 31 +++ nuttx/lib/math/lib_tanh.c | 39 +++ 233 files changed, 1649 insertions(+), 214 deletions(-) create mode 100644 nuttx/lib/fixedmath/Make.defs rename nuttx/lib/{math => fixedmath}/lib_b16atan2.c (99%) rename nuttx/lib/{math => fixedmath}/lib_b16cos.c (98%) rename nuttx/lib/{math => fixedmath}/lib_b16sin.c (99%) rename nuttx/lib/{math => fixedmath}/lib_fixedmath.c (100%) rename nuttx/lib/{math => fixedmath}/lib_rint.c (99%) create mode 100644 nuttx/lib/math/Kconfig create mode 100644 nuttx/lib/math/Makefile create mode 100644 nuttx/lib/math/lib_acos.c create mode 100644 nuttx/lib/math/lib_asin.c create mode 100644 nuttx/lib/math/lib_atan.c create mode 100644 nuttx/lib/math/lib_atan2.c create mode 100644 nuttx/lib/math/lib_ceil.c create mode 100644 nuttx/lib/math/lib_cos.c create mode 100644 nuttx/lib/math/lib_cosh.c create mode 100644 nuttx/lib/math/lib_exp.c create mode 100644 nuttx/lib/math/lib_fabs.c create mode 100644 nuttx/lib/math/lib_floor.c create mode 100644 nuttx/lib/math/lib_fmod.c create mode 100644 nuttx/lib/math/lib_frexp.c create mode 100644 nuttx/lib/math/lib_ldexp.c create mode 100644 nuttx/lib/math/lib_log.c create mode 100644 nuttx/lib/math/lib_log10.c create mode 100644 nuttx/lib/math/lib_log2.c create mode 100644 nuttx/lib/math/lib_modf.c create mode 100644 nuttx/lib/math/lib_pow.c create mode 100644 nuttx/lib/math/lib_sin.c create mode 100644 nuttx/lib/math/lib_sinh.c create mode 100644 nuttx/lib/math/lib_sqrt.c create mode 100644 nuttx/lib/math/lib_tan.c create mode 100644 nuttx/lib/math/lib_tanh.c diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 3b39eabb4f..918cd8608a 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3525,4 +3525,7 @@ * binfmt/libelf: The basic ELF module execution appears fully functional. * configs/shenzhou/src/up_relays.c: Add support for relays from the Shenzhou board. Contributed by Darcy Gong. - + * lib/fixedmath: Moved the old lib/math to lib/fixedmath to make room for + the math library from the Rhombus OS + * lib/math: Now contains the math library from the Rhombus OS by Nick Johnson + (submitted by Darcy Gong). diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index d8ccfc3404..96c3012952 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -3719,9 +3719,6 @@ void (*notify)(FAR struct pm_callback_s *cb, enum pm_state_e pmstate); Make a raw binary format file used with many different loaders using the GNU objcopy program. This option should not be selected if you are not using the GNU toolchain.
  • -
  • CONFIG_HAVE_LIBM: - Toolchain supports libm.a -
  • CONFIG_HAVE_CXX: Toolchain supports C++ and CXX, CXXFLAGS, and COMPILEXX have been defined in the configurations Make.defs file. diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index c7f3db0e7b..4f96dc325b 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -171,7 +171,6 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_RAW_BINARY - make a raw binary format file used with many different loaders using the GNU objcopy program. This option should not be selected if you are not using the GNU toolchain. - CONFIG_HAVE_LIBM - toolchain supports libm.a CONFIG_HAVE_CXX - toolchain supports C++ and CXX, CXXFLAGS, and COMPILEXX have been defined in the configurations Make.defs file. diff --git a/nuttx/configs/amber/hello/defconfig b/nuttx/configs/amber/hello/defconfig index fece8db36b..2439279104 100644 --- a/nuttx/configs/amber/hello/defconfig +++ b/nuttx/configs/amber/hello/defconfig @@ -110,7 +110,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/avr32dev1/nsh/defconfig b/nuttx/configs/avr32dev1/nsh/defconfig index 7e75380c09..3ca2fac382 100755 --- a/nuttx/configs/avr32dev1/nsh/defconfig +++ b/nuttx/configs/avr32dev1/nsh/defconfig @@ -136,7 +136,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/avr32dev1/ostest/defconfig b/nuttx/configs/avr32dev1/ostest/defconfig index b70cbb6af4..ed7280dc60 100755 --- a/nuttx/configs/avr32dev1/ostest/defconfig +++ b/nuttx/configs/avr32dev1/ostest/defconfig @@ -136,7 +136,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/c5471evm/httpd/defconfig b/nuttx/configs/c5471evm/httpd/defconfig index 372fb330f7..52a0fc4bbe 100644 --- a/nuttx/configs/c5471evm/httpd/defconfig +++ b/nuttx/configs/c5471evm/httpd/defconfig @@ -86,7 +86,6 @@ CONFIG_NET_C5471_BASET10=n CONFIG_RRLOAD_BINARY=y CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/c5471evm/nettest/defconfig b/nuttx/configs/c5471evm/nettest/defconfig index 179b4c1854..6da9fa522f 100644 --- a/nuttx/configs/c5471evm/nettest/defconfig +++ b/nuttx/configs/c5471evm/nettest/defconfig @@ -57,7 +57,6 @@ CONFIG_DRAM_SIZE=285212672 CONFIG_RRLOAD_BINARY=y CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # C5471 specific device driver settings diff --git a/nuttx/configs/c5471evm/nsh/defconfig b/nuttx/configs/c5471evm/nsh/defconfig index 5746f833a2..6b583d31a5 100644 --- a/nuttx/configs/c5471evm/nsh/defconfig +++ b/nuttx/configs/c5471evm/nsh/defconfig @@ -86,7 +86,6 @@ CONFIG_NET_C5471_BASET10=n CONFIG_RRLOAD_BINARY=y CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/c5471evm/ostest/defconfig b/nuttx/configs/c5471evm/ostest/defconfig index e0c6297c13..04ac9677f4 100644 --- a/nuttx/configs/c5471evm/ostest/defconfig +++ b/nuttx/configs/c5471evm/ostest/defconfig @@ -86,7 +86,6 @@ CONFIG_NET_C5471_BASET10=n CONFIG_RRLOAD_BINARY=y CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/compal_e88/nsh_highram/defconfig b/nuttx/configs/compal_e88/nsh_highram/defconfig index 3cf0af6295..b429af6966 100644 --- a/nuttx/configs/compal_e88/nsh_highram/defconfig +++ b/nuttx/configs/compal_e88/nsh_highram/defconfig @@ -88,7 +88,6 @@ CONFIG_NET_C5471_BASET10=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/compal_e99/nsh_compalram/defconfig b/nuttx/configs/compal_e99/nsh_compalram/defconfig index f9bf23af66..52f99bf124 100644 --- a/nuttx/configs/compal_e99/nsh_compalram/defconfig +++ b/nuttx/configs/compal_e99/nsh_compalram/defconfig @@ -91,7 +91,6 @@ CONFIG_NET_C5471_BASET10=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/compal_e99/nsh_highram/defconfig b/nuttx/configs/compal_e99/nsh_highram/defconfig index f5323c664c..b1539c98c9 100644 --- a/nuttx/configs/compal_e99/nsh_highram/defconfig +++ b/nuttx/configs/compal_e99/nsh_highram/defconfig @@ -91,7 +91,6 @@ CONFIG_NET_C5471_BASET10=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/demo9s12ne64/ostest/defconfig b/nuttx/configs/demo9s12ne64/ostest/defconfig index a45fc7e474..5033d82011 100755 --- a/nuttx/configs/demo9s12ne64/ostest/defconfig +++ b/nuttx/configs/demo9s12ne64/ostest/defconfig @@ -102,7 +102,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=y CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # Setup for a two-pass build diff --git a/nuttx/configs/ea3131/nsh/defconfig b/nuttx/configs/ea3131/nsh/defconfig index 38caf93aaf..c97f521a52 100644 --- a/nuttx/configs/ea3131/nsh/defconfig +++ b/nuttx/configs/ea3131/nsh/defconfig @@ -109,7 +109,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ea3131/ostest/defconfig b/nuttx/configs/ea3131/ostest/defconfig index abc2c8ba54..c66ee51a44 100644 --- a/nuttx/configs/ea3131/ostest/defconfig +++ b/nuttx/configs/ea3131/ostest/defconfig @@ -109,7 +109,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ea3131/pgnsh/defconfig b/nuttx/configs/ea3131/pgnsh/defconfig index f03432e8de..c9e0963580 100644 --- a/nuttx/configs/ea3131/pgnsh/defconfig +++ b/nuttx/configs/ea3131/pgnsh/defconfig @@ -114,7 +114,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # Setup for a two-pass build diff --git a/nuttx/configs/ea3131/usbserial/defconfig b/nuttx/configs/ea3131/usbserial/defconfig index 3314de254b..1e8f5cf945 100644 --- a/nuttx/configs/ea3131/usbserial/defconfig +++ b/nuttx/configs/ea3131/usbserial/defconfig @@ -109,7 +109,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ea3131/usbstorage/defconfig b/nuttx/configs/ea3131/usbstorage/defconfig index a857523df3..d8088b5dfa 100644 --- a/nuttx/configs/ea3131/usbstorage/defconfig +++ b/nuttx/configs/ea3131/usbstorage/defconfig @@ -109,7 +109,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ea3152/ostest/defconfig b/nuttx/configs/ea3152/ostest/defconfig index 5b7b5b59df..34cf49dfba 100644 --- a/nuttx/configs/ea3152/ostest/defconfig +++ b/nuttx/configs/ea3152/ostest/defconfig @@ -109,7 +109,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/eagle100/httpd/defconfig b/nuttx/configs/eagle100/httpd/defconfig index 7c47f44674..7916569bc0 100644 --- a/nuttx/configs/eagle100/httpd/defconfig +++ b/nuttx/configs/eagle100/httpd/defconfig @@ -115,7 +115,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/eagle100/nettest/defconfig b/nuttx/configs/eagle100/nettest/defconfig index 4f27210454..6f47953863 100644 --- a/nuttx/configs/eagle100/nettest/defconfig +++ b/nuttx/configs/eagle100/nettest/defconfig @@ -115,7 +115,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/eagle100/nsh/defconfig b/nuttx/configs/eagle100/nsh/defconfig index 4848e957bf..b50413db0e 100644 --- a/nuttx/configs/eagle100/nsh/defconfig +++ b/nuttx/configs/eagle100/nsh/defconfig @@ -115,7 +115,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/eagle100/nxflat/defconfig b/nuttx/configs/eagle100/nxflat/defconfig index 01931b0d3a..98029ddd83 100644 --- a/nuttx/configs/eagle100/nxflat/defconfig +++ b/nuttx/configs/eagle100/nxflat/defconfig @@ -115,7 +115,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/eagle100/ostest/defconfig b/nuttx/configs/eagle100/ostest/defconfig index 13a316ca44..f3634aa55f 100644 --- a/nuttx/configs/eagle100/ostest/defconfig +++ b/nuttx/configs/eagle100/ostest/defconfig @@ -115,7 +115,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/eagle100/thttpd/defconfig b/nuttx/configs/eagle100/thttpd/defconfig index 412a89e9cf..d68d51acfc 100644 --- a/nuttx/configs/eagle100/thttpd/defconfig +++ b/nuttx/configs/eagle100/thttpd/defconfig @@ -115,7 +115,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/defconfig b/nuttx/configs/ekk-lm3s9b96/nsh/defconfig index 11407295fd..2a1a0552d2 100644 --- a/nuttx/configs/ekk-lm3s9b96/nsh/defconfig +++ b/nuttx/configs/ekk-lm3s9b96/nsh/defconfig @@ -132,7 +132,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/defconfig b/nuttx/configs/ekk-lm3s9b96/ostest/defconfig index 734ad031e2..c465cb8b7c 100644 --- a/nuttx/configs/ekk-lm3s9b96/ostest/defconfig +++ b/nuttx/configs/ekk-lm3s9b96/ostest/defconfig @@ -132,7 +132,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ez80f910200kitg/ostest/defconfig b/nuttx/configs/ez80f910200kitg/ostest/defconfig index 22b6275429..9ceb261b22 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/defconfig +++ b/nuttx/configs/ez80f910200kitg/ostest/defconfig @@ -94,7 +94,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ez80f910200zco/dhcpd/defconfig b/nuttx/configs/ez80f910200zco/dhcpd/defconfig index ea9844dc2e..a20e86a45a 100644 --- a/nuttx/configs/ez80f910200zco/dhcpd/defconfig +++ b/nuttx/configs/ez80f910200zco/dhcpd/defconfig @@ -97,7 +97,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ez80f910200zco/httpd/defconfig b/nuttx/configs/ez80f910200zco/httpd/defconfig index ddf34285ab..cccecf2bfc 100644 --- a/nuttx/configs/ez80f910200zco/httpd/defconfig +++ b/nuttx/configs/ez80f910200zco/httpd/defconfig @@ -97,7 +97,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ez80f910200zco/nettest/defconfig b/nuttx/configs/ez80f910200zco/nettest/defconfig index 7b1415bf4b..e018164b01 100644 --- a/nuttx/configs/ez80f910200zco/nettest/defconfig +++ b/nuttx/configs/ez80f910200zco/nettest/defconfig @@ -97,7 +97,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ez80f910200zco/nsh/defconfig b/nuttx/configs/ez80f910200zco/nsh/defconfig index fa701253d6..34fbe603d1 100644 --- a/nuttx/configs/ez80f910200zco/nsh/defconfig +++ b/nuttx/configs/ez80f910200zco/nsh/defconfig @@ -97,7 +97,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ez80f910200zco/ostest/defconfig b/nuttx/configs/ez80f910200zco/ostest/defconfig index f16ddee39f..1954b7a5d8 100644 --- a/nuttx/configs/ez80f910200zco/ostest/defconfig +++ b/nuttx/configs/ez80f910200zco/ostest/defconfig @@ -96,7 +96,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ez80f910200zco/poll/defconfig b/nuttx/configs/ez80f910200zco/poll/defconfig index 6ad505dc56..a98526466a 100644 --- a/nuttx/configs/ez80f910200zco/poll/defconfig +++ b/nuttx/configs/ez80f910200zco/poll/defconfig @@ -97,7 +97,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/fire-stm32v2/nsh/defconfig b/nuttx/configs/fire-stm32v2/nsh/defconfig index 5edde6ed12..f126c51fd6 100644 --- a/nuttx/configs/fire-stm32v2/nsh/defconfig +++ b/nuttx/configs/fire-stm32v2/nsh/defconfig @@ -509,7 +509,6 @@ CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" -# CONFIG_HAVE_LIBM is not set # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set diff --git a/nuttx/configs/hymini-stm32v/buttons/defconfig b/nuttx/configs/hymini-stm32v/buttons/defconfig index 44dcf3c41a..8ee2c1d763 100644 --- a/nuttx/configs/hymini-stm32v/buttons/defconfig +++ b/nuttx/configs/hymini-stm32v/buttons/defconfig @@ -162,7 +162,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/hymini-stm32v/nsh/defconfig b/nuttx/configs/hymini-stm32v/nsh/defconfig index 52da9f6f62..f18194bce5 100755 --- a/nuttx/configs/hymini-stm32v/nsh/defconfig +++ b/nuttx/configs/hymini-stm32v/nsh/defconfig @@ -160,7 +160,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/hymini-stm32v/nsh2/defconfig b/nuttx/configs/hymini-stm32v/nsh2/defconfig index fbd9d23b36..b11895c9b1 100644 --- a/nuttx/configs/hymini-stm32v/nsh2/defconfig +++ b/nuttx/configs/hymini-stm32v/nsh2/defconfig @@ -165,7 +165,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n CONFIG_RTC=y diff --git a/nuttx/configs/hymini-stm32v/nx/defconfig b/nuttx/configs/hymini-stm32v/nx/defconfig index e411baf835..b46c68e293 100644 --- a/nuttx/configs/hymini-stm32v/nx/defconfig +++ b/nuttx/configs/hymini-stm32v/nx/defconfig @@ -160,7 +160,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/hymini-stm32v/nxlines/defconfig b/nuttx/configs/hymini-stm32v/nxlines/defconfig index 689b17376a..863e7a327d 100644 --- a/nuttx/configs/hymini-stm32v/nxlines/defconfig +++ b/nuttx/configs/hymini-stm32v/nxlines/defconfig @@ -164,7 +164,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/hymini-stm32v/usbserial/defconfig b/nuttx/configs/hymini-stm32v/usbserial/defconfig index 7883db8273..a6ed06dee9 100755 --- a/nuttx/configs/hymini-stm32v/usbserial/defconfig +++ b/nuttx/configs/hymini-stm32v/usbserial/defconfig @@ -162,7 +162,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/hymini-stm32v/usbstorage/defconfig b/nuttx/configs/hymini-stm32v/usbstorage/defconfig index c3434e3a46..7d75577fe5 100755 --- a/nuttx/configs/hymini-stm32v/usbstorage/defconfig +++ b/nuttx/configs/hymini-stm32v/usbstorage/defconfig @@ -161,7 +161,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/kwikstik-k40/ostest/defconfig b/nuttx/configs/kwikstik-k40/ostest/defconfig index 2cf29894b2..a811ee0632 100755 --- a/nuttx/configs/kwikstik-k40/ostest/defconfig +++ b/nuttx/configs/kwikstik-k40/ostest/defconfig @@ -172,7 +172,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lincoln60/nsh/defconfig b/nuttx/configs/lincoln60/nsh/defconfig index 43944f0a68..bb08a7deca 100644 --- a/nuttx/configs/lincoln60/nsh/defconfig +++ b/nuttx/configs/lincoln60/nsh/defconfig @@ -149,7 +149,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lincoln60/ostest/defconfig b/nuttx/configs/lincoln60/ostest/defconfig index 6dd51eb07d..0576d018fa 100644 --- a/nuttx/configs/lincoln60/ostest/defconfig +++ b/nuttx/configs/lincoln60/ostest/defconfig @@ -155,7 +155,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lm3s6432-s2e/nsh/defconfig b/nuttx/configs/lm3s6432-s2e/nsh/defconfig index f0cf503efb..d203b29546 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/defconfig +++ b/nuttx/configs/lm3s6432-s2e/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lm3s6432-s2e/ostest/defconfig b/nuttx/configs/lm3s6432-s2e/ostest/defconfig index daeac0177d..02b7dbd314 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/defconfig +++ b/nuttx/configs/lm3s6432-s2e/ostest/defconfig @@ -131,7 +131,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lm3s6965-ek/nsh/defconfig b/nuttx/configs/lm3s6965-ek/nsh/defconfig index 2771a3dc93..5afac6e6fb 100755 --- a/nuttx/configs/lm3s6965-ek/nsh/defconfig +++ b/nuttx/configs/lm3s6965-ek/nsh/defconfig @@ -132,7 +132,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lm3s6965-ek/nx/defconfig b/nuttx/configs/lm3s6965-ek/nx/defconfig index 83b338161c..b6cb0cad5a 100755 --- a/nuttx/configs/lm3s6965-ek/nx/defconfig +++ b/nuttx/configs/lm3s6965-ek/nx/defconfig @@ -132,7 +132,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General SPI interface configuration diff --git a/nuttx/configs/lm3s6965-ek/ostest/defconfig b/nuttx/configs/lm3s6965-ek/ostest/defconfig index 0bfe9ef720..da35e55314 100755 --- a/nuttx/configs/lm3s6965-ek/ostest/defconfig +++ b/nuttx/configs/lm3s6965-ek/ostest/defconfig @@ -132,7 +132,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lm3s8962-ek/nsh/defconfig b/nuttx/configs/lm3s8962-ek/nsh/defconfig index 001a873874..2a80e84e70 100755 --- a/nuttx/configs/lm3s8962-ek/nsh/defconfig +++ b/nuttx/configs/lm3s8962-ek/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lm3s8962-ek/nx/defconfig b/nuttx/configs/lm3s8962-ek/nx/defconfig index dbae4b2aa7..51063f7558 100755 --- a/nuttx/configs/lm3s8962-ek/nx/defconfig +++ b/nuttx/configs/lm3s8962-ek/nx/defconfig @@ -131,7 +131,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General SPI interface configuration diff --git a/nuttx/configs/lm3s8962-ek/ostest/defconfig b/nuttx/configs/lm3s8962-ek/ostest/defconfig index aeb0a1ecf8..c540b1d7f6 100755 --- a/nuttx/configs/lm3s8962-ek/ostest/defconfig +++ b/nuttx/configs/lm3s8962-ek/ostest/defconfig @@ -131,7 +131,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lpc4330-xplorer/nsh/defconfig b/nuttx/configs/lpc4330-xplorer/nsh/defconfig index e4269ea67d..a97b9f789e 100644 --- a/nuttx/configs/lpc4330-xplorer/nsh/defconfig +++ b/nuttx/configs/lpc4330-xplorer/nsh/defconfig @@ -191,7 +191,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lpc4330-xplorer/ostest/defconfig b/nuttx/configs/lpc4330-xplorer/ostest/defconfig index d5ac58ef17..cddf7d0e8f 100644 --- a/nuttx/configs/lpc4330-xplorer/ostest/defconfig +++ b/nuttx/configs/lpc4330-xplorer/ostest/defconfig @@ -189,7 +189,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig index 01c54fa9fe..92aa13f7b0 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig @@ -154,7 +154,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig b/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig index 6d0be84007..0e149e1864 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig @@ -157,7 +157,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig b/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig index a94571a835..88a2cd7a22 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig @@ -153,7 +153,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General SPI interface configuration diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig b/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig index f58c78773e..1fa3e79bce 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig @@ -153,7 +153,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig b/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig index 08d251d431..3d014d2914 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig @@ -154,7 +154,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig index 08f4ad1cfa..8e51d52057 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig @@ -153,7 +153,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/m68332evb/defconfig b/nuttx/configs/m68332evb/defconfig index e3e8110a7d..39b3c77324 100644 --- a/nuttx/configs/m68332evb/defconfig +++ b/nuttx/configs/m68332evb/defconfig @@ -67,7 +67,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mbed/hidkbd/defconfig b/nuttx/configs/mbed/hidkbd/defconfig index 3ec6912765..3c31b2f926 100644 --- a/nuttx/configs/mbed/hidkbd/defconfig +++ b/nuttx/configs/mbed/hidkbd/defconfig @@ -153,7 +153,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mbed/nsh/defconfig b/nuttx/configs/mbed/nsh/defconfig index dba89ec7b7..fca08b577b 100755 --- a/nuttx/configs/mbed/nsh/defconfig +++ b/nuttx/configs/mbed/nsh/defconfig @@ -149,7 +149,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mcu123-lpc214x/composite/defconfig b/nuttx/configs/mcu123-lpc214x/composite/defconfig index 6a6e5819cf..0599fed14f 100644 --- a/nuttx/configs/mcu123-lpc214x/composite/defconfig +++ b/nuttx/configs/mcu123-lpc214x/composite/defconfig @@ -90,7 +90,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mcu123-lpc214x/nsh/defconfig b/nuttx/configs/mcu123-lpc214x/nsh/defconfig index 7a514163c3..e2d37a938c 100644 --- a/nuttx/configs/mcu123-lpc214x/nsh/defconfig +++ b/nuttx/configs/mcu123-lpc214x/nsh/defconfig @@ -90,7 +90,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mcu123-lpc214x/ostest/defconfig b/nuttx/configs/mcu123-lpc214x/ostest/defconfig index 724459e806..5fc7df5c75 100644 --- a/nuttx/configs/mcu123-lpc214x/ostest/defconfig +++ b/nuttx/configs/mcu123-lpc214x/ostest/defconfig @@ -90,7 +90,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mcu123-lpc214x/usbserial/defconfig b/nuttx/configs/mcu123-lpc214x/usbserial/defconfig index c746c5732b..c35d804868 100644 --- a/nuttx/configs/mcu123-lpc214x/usbserial/defconfig +++ b/nuttx/configs/mcu123-lpc214x/usbserial/defconfig @@ -90,7 +90,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig b/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig index d46ab7c3c5..a25f2e170b 100644 --- a/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig +++ b/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig @@ -90,7 +90,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/micropendous3/hello/defconfig b/nuttx/configs/micropendous3/hello/defconfig index 4e0ea0e997..63a8f249c8 100644 --- a/nuttx/configs/micropendous3/hello/defconfig +++ b/nuttx/configs/micropendous3/hello/defconfig @@ -105,7 +105,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mirtoo/nsh/defconfig b/nuttx/configs/mirtoo/nsh/defconfig index 4e3cb684e6..0883cc9ea0 100644 --- a/nuttx/configs/mirtoo/nsh/defconfig +++ b/nuttx/configs/mirtoo/nsh/defconfig @@ -163,7 +163,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mirtoo/nxffs/defconfig b/nuttx/configs/mirtoo/nxffs/defconfig index 31e3ef89b1..f2f5286e65 100644 --- a/nuttx/configs/mirtoo/nxffs/defconfig +++ b/nuttx/configs/mirtoo/nxffs/defconfig @@ -163,7 +163,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mirtoo/ostest/defconfig b/nuttx/configs/mirtoo/ostest/defconfig index a3af96fbcf..77b3e38b83 100644 --- a/nuttx/configs/mirtoo/ostest/defconfig +++ b/nuttx/configs/mirtoo/ostest/defconfig @@ -155,7 +155,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/mx1ads/ostest/defconfig b/nuttx/configs/mx1ads/ostest/defconfig index 9e425975df..55b3c72b8c 100644 --- a/nuttx/configs/mx1ads/ostest/defconfig +++ b/nuttx/configs/mx1ads/ostest/defconfig @@ -96,7 +96,6 @@ CONFIG_SPI2_DISABLE=y CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ne64badge/ostest/defconfig b/nuttx/configs/ne64badge/ostest/defconfig index ee36399f15..c101aa01b0 100755 --- a/nuttx/configs/ne64badge/ostest/defconfig +++ b/nuttx/configs/ne64badge/ostest/defconfig @@ -108,7 +108,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=y CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # Setup for a two-pass build diff --git a/nuttx/configs/ntosd-dm320/nettest/defconfig b/nuttx/configs/ntosd-dm320/nettest/defconfig index 1786380545..297df2173f 100644 --- a/nuttx/configs/ntosd-dm320/nettest/defconfig +++ b/nuttx/configs/ntosd-dm320/nettest/defconfig @@ -88,7 +88,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ntosd-dm320/nsh/defconfig b/nuttx/configs/ntosd-dm320/nsh/defconfig index 33cf33c24c..2b02c2d4e4 100644 --- a/nuttx/configs/ntosd-dm320/nsh/defconfig +++ b/nuttx/configs/ntosd-dm320/nsh/defconfig @@ -87,7 +87,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ntosd-dm320/ostest/defconfig b/nuttx/configs/ntosd-dm320/ostest/defconfig index 52ebe0bd9b..a9fca828af 100644 --- a/nuttx/configs/ntosd-dm320/ostest/defconfig +++ b/nuttx/configs/ntosd-dm320/ostest/defconfig @@ -88,7 +88,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ntosd-dm320/poll/defconfig b/nuttx/configs/ntosd-dm320/poll/defconfig index f27dcc2c32..08f75e6b6a 100644 --- a/nuttx/configs/ntosd-dm320/poll/defconfig +++ b/nuttx/configs/ntosd-dm320/poll/defconfig @@ -88,7 +88,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ntosd-dm320/thttpd/defconfig b/nuttx/configs/ntosd-dm320/thttpd/defconfig index becec2ef17..d2de4c167d 100644 --- a/nuttx/configs/ntosd-dm320/thttpd/defconfig +++ b/nuttx/configs/ntosd-dm320/thttpd/defconfig @@ -89,7 +89,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ntosd-dm320/udp/defconfig b/nuttx/configs/ntosd-dm320/udp/defconfig index 869f2e442e..de3b240560 100644 --- a/nuttx/configs/ntosd-dm320/udp/defconfig +++ b/nuttx/configs/ntosd-dm320/udp/defconfig @@ -88,7 +88,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ntosd-dm320/uip/defconfig b/nuttx/configs/ntosd-dm320/uip/defconfig index 19ffe452a9..281a63bd0c 100644 --- a/nuttx/configs/ntosd-dm320/uip/defconfig +++ b/nuttx/configs/ntosd-dm320/uip/defconfig @@ -88,7 +88,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/nucleus2g/nsh/defconfig b/nuttx/configs/nucleus2g/nsh/defconfig index 080c487705..5bc94e607e 100755 --- a/nuttx/configs/nucleus2g/nsh/defconfig +++ b/nuttx/configs/nucleus2g/nsh/defconfig @@ -149,7 +149,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/nucleus2g/ostest/defconfig b/nuttx/configs/nucleus2g/ostest/defconfig index 02eb316339..945e82a057 100755 --- a/nuttx/configs/nucleus2g/ostest/defconfig +++ b/nuttx/configs/nucleus2g/ostest/defconfig @@ -149,7 +149,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/nucleus2g/usbserial/defconfig b/nuttx/configs/nucleus2g/usbserial/defconfig index 300d30ab31..25804407f3 100755 --- a/nuttx/configs/nucleus2g/usbserial/defconfig +++ b/nuttx/configs/nucleus2g/usbserial/defconfig @@ -149,7 +149,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/nucleus2g/usbstorage/defconfig b/nuttx/configs/nucleus2g/usbstorage/defconfig index 7887818fbc..cc677b9f44 100755 --- a/nuttx/configs/nucleus2g/usbstorage/defconfig +++ b/nuttx/configs/nucleus2g/usbstorage/defconfig @@ -149,7 +149,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig b/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig index 6d1375e92c..7cf2e0e880 100755 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig @@ -159,7 +159,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig index 7c9fe4c4e5..ac94ecfb86 100755 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig @@ -159,7 +159,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig index 628ff01124..7e662fb97a 100755 --- a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig @@ -159,7 +159,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig index d5333a9f33..b12dd731a9 100755 --- a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig @@ -159,7 +159,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc1766stk/nx/defconfig b/nuttx/configs/olimex-lpc1766stk/nx/defconfig index d86b8b83fd..0235c29b5f 100755 --- a/nuttx/configs/olimex-lpc1766stk/nx/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/nx/defconfig @@ -155,7 +155,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General SPI interface configuration diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig index a11c022764..fcc2bba448 100755 --- a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig @@ -155,7 +155,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig index 32092d216f..94d5da763f 100755 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig @@ -158,7 +158,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig b/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig index 94ac19f42e..c14e1362b6 100755 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig @@ -156,7 +156,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig index 2bd892cc30..e1216d8968 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig @@ -155,7 +155,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig index 8b55cc94d8..2f91efe474 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig @@ -155,7 +155,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig index 4d73807e0c..aa896c30ce 100755 --- a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig @@ -150,7 +150,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc2378/nsh/defconfig b/nuttx/configs/olimex-lpc2378/nsh/defconfig index 7311d0c20f..30801a6ab4 100755 --- a/nuttx/configs/olimex-lpc2378/nsh/defconfig +++ b/nuttx/configs/olimex-lpc2378/nsh/defconfig @@ -110,7 +110,6 @@ CONFIG_UART2_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-lpc2378/ostest/defconfig b/nuttx/configs/olimex-lpc2378/ostest/defconfig index b96aadd87f..129bb7fbe5 100755 --- a/nuttx/configs/olimex-lpc2378/ostest/defconfig +++ b/nuttx/configs/olimex-lpc2378/ostest/defconfig @@ -110,7 +110,6 @@ CONFIG_UART2_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-stm32-p107/nsh/defconfig b/nuttx/configs/olimex-stm32-p107/nsh/defconfig index 67a153f9a2..9b9a72dcdb 100644 --- a/nuttx/configs/olimex-stm32-p107/nsh/defconfig +++ b/nuttx/configs/olimex-stm32-p107/nsh/defconfig @@ -198,7 +198,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-stm32-p107/ostest/defconfig b/nuttx/configs/olimex-stm32-p107/ostest/defconfig index 26a8470d26..21aa07875a 100644 --- a/nuttx/configs/olimex-stm32-p107/ostest/defconfig +++ b/nuttx/configs/olimex-stm32-p107/ostest/defconfig @@ -208,7 +208,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-strp711/nettest/defconfig b/nuttx/configs/olimex-strp711/nettest/defconfig index c401fe8c69..eb8c911088 100755 --- a/nuttx/configs/olimex-strp711/nettest/defconfig +++ b/nuttx/configs/olimex-strp711/nettest/defconfig @@ -128,7 +128,6 @@ CONFIG_UART3_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-strp711/nsh/defconfig b/nuttx/configs/olimex-strp711/nsh/defconfig index 985e3690ee..2deb556408 100644 --- a/nuttx/configs/olimex-strp711/nsh/defconfig +++ b/nuttx/configs/olimex-strp711/nsh/defconfig @@ -128,7 +128,6 @@ CONFIG_UART3_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/olimex-strp711/ostest/defconfig b/nuttx/configs/olimex-strp711/ostest/defconfig index cdac22b9f6..e60b7349f1 100644 --- a/nuttx/configs/olimex-strp711/ostest/defconfig +++ b/nuttx/configs/olimex-strp711/ostest/defconfig @@ -128,7 +128,6 @@ CONFIG_UART3_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/pcblogic-pic32mx/nsh/defconfig b/nuttx/configs/pcblogic-pic32mx/nsh/defconfig index 1e439e4667..3a480d7865 100644 --- a/nuttx/configs/pcblogic-pic32mx/nsh/defconfig +++ b/nuttx/configs/pcblogic-pic32mx/nsh/defconfig @@ -155,7 +155,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/pcblogic-pic32mx/ostest/defconfig b/nuttx/configs/pcblogic-pic32mx/ostest/defconfig index 868ba46695..da8ff40edb 100644 --- a/nuttx/configs/pcblogic-pic32mx/ostest/defconfig +++ b/nuttx/configs/pcblogic-pic32mx/ostest/defconfig @@ -155,7 +155,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/pic32-starterkit/nsh/defconfig b/nuttx/configs/pic32-starterkit/nsh/defconfig index 17cb151a76..17fbd6f4ec 100644 --- a/nuttx/configs/pic32-starterkit/nsh/defconfig +++ b/nuttx/configs/pic32-starterkit/nsh/defconfig @@ -215,7 +215,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/pic32-starterkit/nsh2/defconfig b/nuttx/configs/pic32-starterkit/nsh2/defconfig index c751591b21..0eec631180 100644 --- a/nuttx/configs/pic32-starterkit/nsh2/defconfig +++ b/nuttx/configs/pic32-starterkit/nsh2/defconfig @@ -215,7 +215,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/pic32-starterkit/ostest/defconfig b/nuttx/configs/pic32-starterkit/ostest/defconfig index c8e32419ea..e386b59360 100644 --- a/nuttx/configs/pic32-starterkit/ostest/defconfig +++ b/nuttx/configs/pic32-starterkit/ostest/defconfig @@ -215,7 +215,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/pic32mx7mmb/nsh/defconfig b/nuttx/configs/pic32mx7mmb/nsh/defconfig index 0523636563..c55e802093 100644 --- a/nuttx/configs/pic32mx7mmb/nsh/defconfig +++ b/nuttx/configs/pic32mx7mmb/nsh/defconfig @@ -215,7 +215,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/pic32mx7mmb/ostest/defconfig b/nuttx/configs/pic32mx7mmb/ostest/defconfig index 851f6022f2..a2e653a563 100644 --- a/nuttx/configs/pic32mx7mmb/ostest/defconfig +++ b/nuttx/configs/pic32mx7mmb/ostest/defconfig @@ -215,7 +215,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/pjrc-8051/defconfig b/nuttx/configs/pjrc-8051/defconfig index 0232376cf2..c223f64e18 100644 --- a/nuttx/configs/pjrc-8051/defconfig +++ b/nuttx/configs/pjrc-8051/defconfig @@ -66,7 +66,6 @@ CONFIG_LED_DEBUG=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/qemu-i486/nsh/defconfig b/nuttx/configs/qemu-i486/nsh/defconfig index 9085eb5fa4..b693c94f76 100644 --- a/nuttx/configs/qemu-i486/nsh/defconfig +++ b/nuttx/configs/qemu-i486/nsh/defconfig @@ -195,7 +195,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/qemu-i486/ostest/defconfig b/nuttx/configs/qemu-i486/ostest/defconfig index a9867fdc98..63c27a2317 100644 --- a/nuttx/configs/qemu-i486/ostest/defconfig +++ b/nuttx/configs/qemu-i486/ostest/defconfig @@ -127,7 +127,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/rgmp/arm/default/defconfig b/nuttx/configs/rgmp/arm/default/defconfig index 186c687248..a78500bf4c 100644 --- a/nuttx/configs/rgmp/arm/default/defconfig +++ b/nuttx/configs/rgmp/arm/default/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_STDBOOL_H=y CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/rgmp/arm/nsh/defconfig b/nuttx/configs/rgmp/arm/nsh/defconfig index 8fbbc7b8b4..bee14b0a2a 100644 --- a/nuttx/configs/rgmp/arm/nsh/defconfig +++ b/nuttx/configs/rgmp/arm/nsh/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_STDBOOL_H=y CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/rgmp/x86/default/defconfig b/nuttx/configs/rgmp/x86/default/defconfig index 9b4b58d89c..e36c397661 100644 --- a/nuttx/configs/rgmp/x86/default/defconfig +++ b/nuttx/configs/rgmp/x86/default/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_STDBOOL_H=y CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/rgmp/x86/nsh/defconfig b/nuttx/configs/rgmp/x86/nsh/defconfig index 7af320ff72..6afe9c9a9e 100644 --- a/nuttx/configs/rgmp/x86/nsh/defconfig +++ b/nuttx/configs/rgmp/x86/nsh/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_STDBOOL_H=y CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sam3u-ek/knsh/defconfig b/nuttx/configs/sam3u-ek/knsh/defconfig index 9aba512edf..416ca3fa3a 100755 --- a/nuttx/configs/sam3u-ek/knsh/defconfig +++ b/nuttx/configs/sam3u-ek/knsh/defconfig @@ -144,7 +144,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # Setup for a two-pass build diff --git a/nuttx/configs/sam3u-ek/nsh/defconfig b/nuttx/configs/sam3u-ek/nsh/defconfig index 02b9804183..69a2081ff2 100755 --- a/nuttx/configs/sam3u-ek/nsh/defconfig +++ b/nuttx/configs/sam3u-ek/nsh/defconfig @@ -139,7 +139,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/sam3u-ek/nx/defconfig b/nuttx/configs/sam3u-ek/nx/defconfig index 82e9e3cbc4..aae6aa5fa1 100755 --- a/nuttx/configs/sam3u-ek/nx/defconfig +++ b/nuttx/configs/sam3u-ek/nx/defconfig @@ -139,7 +139,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/sam3u-ek/ostest/defconfig b/nuttx/configs/sam3u-ek/ostest/defconfig index da582acb65..14b8eaa6ee 100755 --- a/nuttx/configs/sam3u-ek/ostest/defconfig +++ b/nuttx/configs/sam3u-ek/ostest/defconfig @@ -140,7 +140,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/sam3u-ek/touchscreen/defconfig b/nuttx/configs/sam3u-ek/touchscreen/defconfig index f3ced72cc4..cd1fec7d1d 100755 --- a/nuttx/configs/sam3u-ek/touchscreen/defconfig +++ b/nuttx/configs/sam3u-ek/touchscreen/defconfig @@ -146,7 +146,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/shenzhou/nsh/defconfig b/nuttx/configs/shenzhou/nsh/defconfig index fdc065c48e..b37da788e3 100644 --- a/nuttx/configs/shenzhou/nsh/defconfig +++ b/nuttx/configs/shenzhou/nsh/defconfig @@ -452,7 +452,6 @@ CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" -# CONFIG_HAVE_LIBM is not set # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set diff --git a/nuttx/configs/shenzhou/nxwm/defconfig b/nuttx/configs/shenzhou/nxwm/defconfig index e4316d1fe7..a5ccc8bfbe 100644 --- a/nuttx/configs/shenzhou/nxwm/defconfig +++ b/nuttx/configs/shenzhou/nxwm/defconfig @@ -552,7 +552,6 @@ CONFIG_STDIO_BUFFER_SIZE=64 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" -# CONFIG_HAVE_LIBM is not set # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set diff --git a/nuttx/configs/shenzhou/thttpd/defconfig b/nuttx/configs/shenzhou/thttpd/defconfig index 5fd158cc64..82884f4c3f 100644 --- a/nuttx/configs/shenzhou/thttpd/defconfig +++ b/nuttx/configs/shenzhou/thttpd/defconfig @@ -452,7 +452,6 @@ CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" -# CONFIG_HAVE_LIBM is not set # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set diff --git a/nuttx/configs/sim/mount/defconfig b/nuttx/configs/sim/mount/defconfig index b980b38dda..7caa878525 100644 --- a/nuttx/configs/sim/mount/defconfig +++ b/nuttx/configs/sim/mount/defconfig @@ -118,7 +118,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sim/nettest/defconfig b/nuttx/configs/sim/nettest/defconfig index d724046409..c216e2edc8 100644 --- a/nuttx/configs/sim/nettest/defconfig +++ b/nuttx/configs/sim/nettest/defconfig @@ -118,7 +118,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sim/nsh/defconfig b/nuttx/configs/sim/nsh/defconfig index cd1fc8c7b3..a217dd71d7 100644 --- a/nuttx/configs/sim/nsh/defconfig +++ b/nuttx/configs/sim/nsh/defconfig @@ -143,7 +143,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sim/nsh2/defconfig b/nuttx/configs/sim/nsh2/defconfig index 787e388c7d..0e93cd4810 100644 --- a/nuttx/configs/sim/nsh2/defconfig +++ b/nuttx/configs/sim/nsh2/defconfig @@ -153,7 +153,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sim/nx/defconfig b/nuttx/configs/sim/nx/defconfig index 5b48d72a71..d5cad6741b 100644 --- a/nuttx/configs/sim/nx/defconfig +++ b/nuttx/configs/sim/nx/defconfig @@ -129,7 +129,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sim/nx11/defconfig b/nuttx/configs/sim/nx11/defconfig index 43d57bd50a..0ac3362be2 100644 --- a/nuttx/configs/sim/nx11/defconfig +++ b/nuttx/configs/sim/nx11/defconfig @@ -136,7 +136,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sim/nxffs/defconfig b/nuttx/configs/sim/nxffs/defconfig index c30227bd84..79f5b0f93a 100644 --- a/nuttx/configs/sim/nxffs/defconfig +++ b/nuttx/configs/sim/nxffs/defconfig @@ -119,7 +119,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sim/nxwm/defconfig b/nuttx/configs/sim/nxwm/defconfig index d34202e05c..9029b3b2f1 100644 --- a/nuttx/configs/sim/nxwm/defconfig +++ b/nuttx/configs/sim/nxwm/defconfig @@ -153,7 +153,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sim/ostest/defconfig b/nuttx/configs/sim/ostest/defconfig index 0d3669a25b..a2fbd9f050 100644 --- a/nuttx/configs/sim/ostest/defconfig +++ b/nuttx/configs/sim/ostest/defconfig @@ -118,7 +118,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sim/pashello/defconfig b/nuttx/configs/sim/pashello/defconfig index e3cf3a7b5b..b40ec626ec 100644 --- a/nuttx/configs/sim/pashello/defconfig +++ b/nuttx/configs/sim/pashello/defconfig @@ -118,7 +118,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/sim/touchscreen/defconfig b/nuttx/configs/sim/touchscreen/defconfig index b112449b39..6a2e3e304d 100644 --- a/nuttx/configs/sim/touchscreen/defconfig +++ b/nuttx/configs/sim/touchscreen/defconfig @@ -135,7 +135,6 @@ CONFIG_ARCH_BZERO=n CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/skp16c26/ostest/defconfig b/nuttx/configs/skp16c26/ostest/defconfig index 8cb2eb4691..f3370d48cb 100644 --- a/nuttx/configs/skp16c26/ostest/defconfig +++ b/nuttx/configs/skp16c26/ostest/defconfig @@ -93,7 +93,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=y CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/RIDE/defconfig b/nuttx/configs/stm3210e-eval/RIDE/defconfig index f4593d5ea0..7032bd975b 100755 --- a/nuttx/configs/stm3210e-eval/RIDE/defconfig +++ b/nuttx/configs/stm3210e-eval/RIDE/defconfig @@ -165,7 +165,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/buttons/defconfig b/nuttx/configs/stm3210e-eval/buttons/defconfig index ac3f108874..37b1cf968c 100644 --- a/nuttx/configs/stm3210e-eval/buttons/defconfig +++ b/nuttx/configs/stm3210e-eval/buttons/defconfig @@ -176,7 +176,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/composite/defconfig b/nuttx/configs/stm3210e-eval/composite/defconfig index 18c2164d36..fa485f4df5 100755 --- a/nuttx/configs/stm3210e-eval/composite/defconfig +++ b/nuttx/configs/stm3210e-eval/composite/defconfig @@ -174,7 +174,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/nsh/defconfig b/nuttx/configs/stm3210e-eval/nsh/defconfig index facfe105a1..1341c58916 100755 --- a/nuttx/configs/stm3210e-eval/nsh/defconfig +++ b/nuttx/configs/stm3210e-eval/nsh/defconfig @@ -174,7 +174,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/nsh2/defconfig b/nuttx/configs/stm3210e-eval/nsh2/defconfig index c30691cc98..0ce49deb5c 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/defconfig +++ b/nuttx/configs/stm3210e-eval/nsh2/defconfig @@ -217,7 +217,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/nx/defconfig b/nuttx/configs/stm3210e-eval/nx/defconfig index 0833e7a787..6569c9a652 100644 --- a/nuttx/configs/stm3210e-eval/nx/defconfig +++ b/nuttx/configs/stm3210e-eval/nx/defconfig @@ -174,7 +174,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/nxconsole/defconfig b/nuttx/configs/stm3210e-eval/nxconsole/defconfig index 637967efc5..070bcde42a 100644 --- a/nuttx/configs/stm3210e-eval/nxconsole/defconfig +++ b/nuttx/configs/stm3210e-eval/nxconsole/defconfig @@ -174,7 +174,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/nxlines/defconfig b/nuttx/configs/stm3210e-eval/nxlines/defconfig index 0a124407af..8517f45e52 100644 --- a/nuttx/configs/stm3210e-eval/nxlines/defconfig +++ b/nuttx/configs/stm3210e-eval/nxlines/defconfig @@ -174,7 +174,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/nxtext/defconfig b/nuttx/configs/stm3210e-eval/nxtext/defconfig index 14e20946e4..d554a0a7a9 100644 --- a/nuttx/configs/stm3210e-eval/nxtext/defconfig +++ b/nuttx/configs/stm3210e-eval/nxtext/defconfig @@ -174,7 +174,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig index 8585235ec4..abb4b925ca 100755 --- a/nuttx/configs/stm3210e-eval/ostest/defconfig +++ b/nuttx/configs/stm3210e-eval/ostest/defconfig @@ -186,7 +186,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/pm/defconfig b/nuttx/configs/stm3210e-eval/pm/defconfig index f7ae420e4f..00d307c64c 100644 --- a/nuttx/configs/stm3210e-eval/pm/defconfig +++ b/nuttx/configs/stm3210e-eval/pm/defconfig @@ -227,7 +227,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/usbserial/defconfig b/nuttx/configs/stm3210e-eval/usbserial/defconfig index ac3ff1c9a3..0672be24d9 100755 --- a/nuttx/configs/stm3210e-eval/usbserial/defconfig +++ b/nuttx/configs/stm3210e-eval/usbserial/defconfig @@ -175,7 +175,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3210e-eval/usbstorage/defconfig b/nuttx/configs/stm3210e-eval/usbstorage/defconfig index 160d952370..57facca011 100755 --- a/nuttx/configs/stm3210e-eval/usbstorage/defconfig +++ b/nuttx/configs/stm3210e-eval/usbstorage/defconfig @@ -174,7 +174,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3220g-eval/dhcpd/defconfig b/nuttx/configs/stm3220g-eval/dhcpd/defconfig index 762607bd05..39f2427fd7 100644 --- a/nuttx/configs/stm3220g-eval/dhcpd/defconfig +++ b/nuttx/configs/stm3220g-eval/dhcpd/defconfig @@ -228,7 +228,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3220g-eval/nettest/defconfig b/nuttx/configs/stm3220g-eval/nettest/defconfig index 9262e8c24e..a186ad67ce 100644 --- a/nuttx/configs/stm3220g-eval/nettest/defconfig +++ b/nuttx/configs/stm3220g-eval/nettest/defconfig @@ -228,7 +228,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3220g-eval/nsh/defconfig b/nuttx/configs/stm3220g-eval/nsh/defconfig index ca1d914de2..92741b91fb 100644 --- a/nuttx/configs/stm3220g-eval/nsh/defconfig +++ b/nuttx/configs/stm3220g-eval/nsh/defconfig @@ -251,7 +251,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3220g-eval/nsh2/defconfig b/nuttx/configs/stm3220g-eval/nsh2/defconfig index 324c920d72..98b8b1923e 100644 --- a/nuttx/configs/stm3220g-eval/nsh2/defconfig +++ b/nuttx/configs/stm3220g-eval/nsh2/defconfig @@ -251,7 +251,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3220g-eval/nxwm/defconfig b/nuttx/configs/stm3220g-eval/nxwm/defconfig index 41f365257e..32d9c31ebb 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/defconfig +++ b/nuttx/configs/stm3220g-eval/nxwm/defconfig @@ -251,7 +251,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3220g-eval/ostest/defconfig b/nuttx/configs/stm3220g-eval/ostest/defconfig index b8663a72a9..2f69fdc24b 100644 --- a/nuttx/configs/stm3220g-eval/ostest/defconfig +++ b/nuttx/configs/stm3220g-eval/ostest/defconfig @@ -228,7 +228,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3220g-eval/telnetd/defconfig b/nuttx/configs/stm3220g-eval/telnetd/defconfig index 28670bb476..c41c370881 100644 --- a/nuttx/configs/stm3220g-eval/telnetd/defconfig +++ b/nuttx/configs/stm3220g-eval/telnetd/defconfig @@ -228,7 +228,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3240g-eval/dhcpd/defconfig b/nuttx/configs/stm3240g-eval/dhcpd/defconfig index e33b62f871..dd0342d70b 100644 --- a/nuttx/configs/stm3240g-eval/dhcpd/defconfig +++ b/nuttx/configs/stm3240g-eval/dhcpd/defconfig @@ -234,7 +234,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3240g-eval/discover/defconfig b/nuttx/configs/stm3240g-eval/discover/defconfig index 7c1163b9b4..d7165573c9 100644 --- a/nuttx/configs/stm3240g-eval/discover/defconfig +++ b/nuttx/configs/stm3240g-eval/discover/defconfig @@ -472,7 +472,6 @@ CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" -# CONFIG_HAVE_LIBM is not set # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set diff --git a/nuttx/configs/stm3240g-eval/nettest/defconfig b/nuttx/configs/stm3240g-eval/nettest/defconfig index 813912b848..5c5053dda8 100644 --- a/nuttx/configs/stm3240g-eval/nettest/defconfig +++ b/nuttx/configs/stm3240g-eval/nettest/defconfig @@ -234,7 +234,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig index 8c7c290782..1501e32d1b 100644 --- a/nuttx/configs/stm3240g-eval/nsh/defconfig +++ b/nuttx/configs/stm3240g-eval/nsh/defconfig @@ -256,7 +256,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3240g-eval/nsh2/defconfig b/nuttx/configs/stm3240g-eval/nsh2/defconfig index 53b0896d81..4e5eff8bd8 100644 --- a/nuttx/configs/stm3240g-eval/nsh2/defconfig +++ b/nuttx/configs/stm3240g-eval/nsh2/defconfig @@ -258,7 +258,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3240g-eval/nxconsole/defconfig b/nuttx/configs/stm3240g-eval/nxconsole/defconfig index f87acc69e4..5eada6ab2b 100644 --- a/nuttx/configs/stm3240g-eval/nxconsole/defconfig +++ b/nuttx/configs/stm3240g-eval/nxconsole/defconfig @@ -257,7 +257,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3240g-eval/nxwm/defconfig b/nuttx/configs/stm3240g-eval/nxwm/defconfig index d1fa395ddb..39ffcd07d3 100644 --- a/nuttx/configs/stm3240g-eval/nxwm/defconfig +++ b/nuttx/configs/stm3240g-eval/nxwm/defconfig @@ -257,7 +257,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3240g-eval/ostest/defconfig b/nuttx/configs/stm3240g-eval/ostest/defconfig index cc7a9ac58b..3c29fca51c 100644 --- a/nuttx/configs/stm3240g-eval/ostest/defconfig +++ b/nuttx/configs/stm3240g-eval/ostest/defconfig @@ -233,7 +233,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3240g-eval/telnetd/defconfig b/nuttx/configs/stm3240g-eval/telnetd/defconfig index 4ab86aeb99..8d5b449744 100644 --- a/nuttx/configs/stm3240g-eval/telnetd/defconfig +++ b/nuttx/configs/stm3240g-eval/telnetd/defconfig @@ -234,7 +234,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3240g-eval/webserver/defconfig b/nuttx/configs/stm3240g-eval/webserver/defconfig index 8921d503ce..1ea4cf9438 100644 --- a/nuttx/configs/stm3240g-eval/webserver/defconfig +++ b/nuttx/configs/stm3240g-eval/webserver/defconfig @@ -257,7 +257,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm3240g-eval/xmlrpc/defconfig b/nuttx/configs/stm3240g-eval/xmlrpc/defconfig index 20639dac42..308203e273 100644 --- a/nuttx/configs/stm3240g-eval/xmlrpc/defconfig +++ b/nuttx/configs/stm3240g-eval/xmlrpc/defconfig @@ -465,7 +465,6 @@ CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" -# CONFIG_HAVE_LIBM is not set # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set diff --git a/nuttx/configs/stm32f4discovery/elf/defconfig b/nuttx/configs/stm32f4discovery/elf/defconfig index 6d72e4a9ee..5bbef5e73a 100644 --- a/nuttx/configs/stm32f4discovery/elf/defconfig +++ b/nuttx/configs/stm32f4discovery/elf/defconfig @@ -397,7 +397,6 @@ CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" -# CONFIG_HAVE_LIBM is not set # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set diff --git a/nuttx/configs/stm32f4discovery/nsh/defconfig b/nuttx/configs/stm32f4discovery/nsh/defconfig index c216c5997c..4461c08ce2 100644 --- a/nuttx/configs/stm32f4discovery/nsh/defconfig +++ b/nuttx/configs/stm32f4discovery/nsh/defconfig @@ -239,7 +239,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm32f4discovery/nxlines/defconfig b/nuttx/configs/stm32f4discovery/nxlines/defconfig index e1e4f21316..737b015b1f 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/defconfig +++ b/nuttx/configs/stm32f4discovery/nxlines/defconfig @@ -239,7 +239,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/stm32f4discovery/ostest/defconfig b/nuttx/configs/stm32f4discovery/ostest/defconfig index 1683657303..ccd9c648aa 100644 --- a/nuttx/configs/stm32f4discovery/ostest/defconfig +++ b/nuttx/configs/stm32f4discovery/ostest/defconfig @@ -387,7 +387,6 @@ CONFIG_SYMTAB_ORDEREDBYNAME=y CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 -# CONFIG_HAVE_LIBM is not set # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set diff --git a/nuttx/configs/stm32f4discovery/pm/defconfig b/nuttx/configs/stm32f4discovery/pm/defconfig index 07a99c764d..6785ec46ed 100644 --- a/nuttx/configs/stm32f4discovery/pm/defconfig +++ b/nuttx/configs/stm32f4discovery/pm/defconfig @@ -240,7 +240,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/sure-pic32mx/nsh/defconfig b/nuttx/configs/sure-pic32mx/nsh/defconfig index 8025f968c3..ae7b4b83e3 100644 --- a/nuttx/configs/sure-pic32mx/nsh/defconfig +++ b/nuttx/configs/sure-pic32mx/nsh/defconfig @@ -162,7 +162,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/sure-pic32mx/ostest/defconfig b/nuttx/configs/sure-pic32mx/ostest/defconfig index f3c3fee36b..95c0448510 100644 --- a/nuttx/configs/sure-pic32mx/ostest/defconfig +++ b/nuttx/configs/sure-pic32mx/ostest/defconfig @@ -156,7 +156,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/sure-pic32mx/usbnsh/defconfig b/nuttx/configs/sure-pic32mx/usbnsh/defconfig index cdebb2953b..cfdc83d4be 100644 --- a/nuttx/configs/sure-pic32mx/usbnsh/defconfig +++ b/nuttx/configs/sure-pic32mx/usbnsh/defconfig @@ -162,7 +162,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/teensy/hello/defconfig b/nuttx/configs/teensy/hello/defconfig index 83176f57e9..05349bf473 100644 --- a/nuttx/configs/teensy/hello/defconfig +++ b/nuttx/configs/teensy/hello/defconfig @@ -105,7 +105,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/teensy/nsh/defconfig b/nuttx/configs/teensy/nsh/defconfig index 0908f02430..f8e71d7e94 100755 --- a/nuttx/configs/teensy/nsh/defconfig +++ b/nuttx/configs/teensy/nsh/defconfig @@ -105,7 +105,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/teensy/usbstorage/defconfig b/nuttx/configs/teensy/usbstorage/defconfig index 94cc301db3..08b8fd842e 100755 --- a/nuttx/configs/teensy/usbstorage/defconfig +++ b/nuttx/configs/teensy/usbstorage/defconfig @@ -105,7 +105,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/twr-k60n512/nsh/defconfig b/nuttx/configs/twr-k60n512/nsh/defconfig index d8ccd6a6d3..d4b8f77fa8 100644 --- a/nuttx/configs/twr-k60n512/nsh/defconfig +++ b/nuttx/configs/twr-k60n512/nsh/defconfig @@ -171,7 +171,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/twr-k60n512/ostest/defconfig b/nuttx/configs/twr-k60n512/ostest/defconfig index 8909add134..8505ac12d8 100644 --- a/nuttx/configs/twr-k60n512/ostest/defconfig +++ b/nuttx/configs/twr-k60n512/ostest/defconfig @@ -171,7 +171,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ubw32/nsh/defconfig b/nuttx/configs/ubw32/nsh/defconfig index afa4e10c8a..a6fe0051d4 100644 --- a/nuttx/configs/ubw32/nsh/defconfig +++ b/nuttx/configs/ubw32/nsh/defconfig @@ -155,7 +155,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/ubw32/ostest/defconfig b/nuttx/configs/ubw32/ostest/defconfig index 0849fe800e..857684409e 100644 --- a/nuttx/configs/ubw32/ostest/defconfig +++ b/nuttx/configs/ubw32/ostest/defconfig @@ -155,7 +155,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=y CONFIG_MOTOROLA_SREC=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/us7032evb1/nsh/defconfig b/nuttx/configs/us7032evb1/nsh/defconfig index 02d42aebe5..7dd5dc6983 100644 --- a/nuttx/configs/us7032evb1/nsh/defconfig +++ b/nuttx/configs/us7032evb1/nsh/defconfig @@ -95,7 +95,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=y CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/us7032evb1/ostest/defconfig b/nuttx/configs/us7032evb1/ostest/defconfig index f92a55461e..286c619989 100644 --- a/nuttx/configs/us7032evb1/ostest/defconfig +++ b/nuttx/configs/us7032evb1/ostest/defconfig @@ -95,7 +95,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=y CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/vsn/nsh/defconfig b/nuttx/configs/vsn/nsh/defconfig index 8c59b42981..a43deab6f1 100755 --- a/nuttx/configs/vsn/nsh/defconfig +++ b/nuttx/configs/vsn/nsh/defconfig @@ -214,7 +214,6 @@ CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_MOTOROLA_SREC=y CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/xtrs/nsh/defconfig b/nuttx/configs/xtrs/nsh/defconfig index b8bd5d6f28..7065ad8d5c 100644 --- a/nuttx/configs/xtrs/nsh/defconfig +++ b/nuttx/configs/xtrs/nsh/defconfig @@ -55,7 +55,6 @@ CONFIG_UART_TXBUFSIZE=256 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n CONFIG_LINKER_START_AREA=0x5200 CONFIG_LINKER_CODE_AREA=0x5300 diff --git a/nuttx/configs/xtrs/ostest/defconfig b/nuttx/configs/xtrs/ostest/defconfig index 9c88c5d8fb..5759b9105f 100644 --- a/nuttx/configs/xtrs/ostest/defconfig +++ b/nuttx/configs/xtrs/ostest/defconfig @@ -55,7 +55,6 @@ CONFIG_UART_TXBUFSIZE=256 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n CONFIG_LINKER_START_AREA=0x5200 CONFIG_LINKER_CODE_AREA=0x5300 diff --git a/nuttx/configs/xtrs/pashello/defconfig b/nuttx/configs/xtrs/pashello/defconfig index d187ccec58..0d80ec0741 100644 --- a/nuttx/configs/xtrs/pashello/defconfig +++ b/nuttx/configs/xtrs/pashello/defconfig @@ -55,7 +55,6 @@ CONFIG_UART_TXBUFSIZE=256 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n CONFIG_LINKER_START_AREA=0x5200 CONFIG_LINKER_CODE_AREA=0x5300 diff --git a/nuttx/configs/z16f2800100zcog/ostest/defconfig b/nuttx/configs/z16f2800100zcog/ostest/defconfig index 24cca2a6aa..0bfb09ea81 100644 --- a/nuttx/configs/z16f2800100zcog/ostest/defconfig +++ b/nuttx/configs/z16f2800100zcog/ostest/defconfig @@ -73,7 +73,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/z16f2800100zcog/pashello/defconfig b/nuttx/configs/z16f2800100zcog/pashello/defconfig index daf98c7d6e..1c2fb80f20 100644 --- a/nuttx/configs/z16f2800100zcog/pashello/defconfig +++ b/nuttx/configs/z16f2800100zcog/pashello/defconfig @@ -73,7 +73,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/z80sim/nsh/defconfig b/nuttx/configs/z80sim/nsh/defconfig index 87195b6e86..5dd0cdc4b3 100644 --- a/nuttx/configs/z80sim/nsh/defconfig +++ b/nuttx/configs/z80sim/nsh/defconfig @@ -55,7 +55,6 @@ CONFIG_UART_TXBUFSIZE=64 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/z80sim/ostest/defconfig b/nuttx/configs/z80sim/ostest/defconfig index 4fbca2e16a..9fa525259e 100644 --- a/nuttx/configs/z80sim/ostest/defconfig +++ b/nuttx/configs/z80sim/ostest/defconfig @@ -55,7 +55,6 @@ CONFIG_UART_TXBUFSIZE=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/z80sim/pashello/defconfig b/nuttx/configs/z80sim/pashello/defconfig index 1c50f71ff0..db32f93fb8 100644 --- a/nuttx/configs/z80sim/pashello/defconfig +++ b/nuttx/configs/z80sim/pashello/defconfig @@ -55,7 +55,6 @@ CONFIG_UART_TXBUFSIZE=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/z8encore000zco/ostest/defconfig b/nuttx/configs/z8encore000zco/ostest/defconfig index 2fb427105f..35ed60abad 100644 --- a/nuttx/configs/z8encore000zco/ostest/defconfig +++ b/nuttx/configs/z8encore000zco/ostest/defconfig @@ -71,7 +71,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/configs/z8f64200100kit/ostest/defconfig b/nuttx/configs/z8f64200100kit/ostest/defconfig index d9c5a51a5b..3384346986 100644 --- a/nuttx/configs/z8f64200100kit/ostest/defconfig +++ b/nuttx/configs/z8f64200100kit/ostest/defconfig @@ -71,7 +71,6 @@ CONFIG_UART1_2STOP=0 CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n # # General OS setup diff --git a/nuttx/lib/Kconfig b/nuttx/lib/Kconfig index ddd5e2dde5..77cf626656 100644 --- a/nuttx/lib/Kconfig +++ b/nuttx/lib/Kconfig @@ -30,12 +30,27 @@ config LIB_HOMEDIR ---help--- The home directory to use with operations like such as 'cd ~' -config HAVE_LIBM - bool "Architecture-specific libm.a" +config LIBM + bool "Math library" default n + depends on !ARCH_MATH_H ---help--- - Architecture specific logic provides an implementation of libm.a - and a math.h header file that can be found at include/arch/math.h. + By default, no math library will be provided by NuttX. In this this case, it + is assumed that (1) no math library is required, or (2) you will be using the + math.h header file and the libm library provided by your toolchain. + + This is may be a very good choice is possible because your toolchain may have + have a highly optimized version of libm. + + Another possibility is that you have a custom, architecture-specific math + libary and that the corresponding math.h file resides at arch//include/math.h. + The option is selected via ARCH_MATH_H. If ARCH_MATH_H is selected,then the include/nuttx/math.h + header file will be copied to include/math.h where it can be used by your applications. + + If ARCH_MATH_H is not defined, then this option can be selected to build a generic, + math library built into NuttX. This math library comes from the Rhombus OS and + was written by Nick Johnson. The Rhombus OS math library port was contributed by + Darcy Gong. config NOPRINTF_FIELDWIDTH bool "Disable sprintf support fieldwidth" diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile index fc8f0c4dda..5c62967ce8 100644 --- a/nuttx/lib/Makefile +++ b/nuttx/lib/Makefile @@ -50,7 +50,7 @@ include pthread/Make.defs include semaphore/Make.defs include signal/Make.defs include mqueue/Make.defs -include math/Make.defs +include fixedmath/Make.defs include net/Make.defs include time/Make.defs include libgen/Make.defs diff --git a/nuttx/lib/README.txt b/nuttx/lib/README.txt index 63d1c343c0..e99304841b 100644 --- a/nuttx/lib/README.txt +++ b/nuttx/lib/README.txt @@ -26,7 +26,8 @@ in the include/ directory provides the prototype for library functions. So we have: libgen - libgen.h - math - math.h and fixedmath.h + fixedmath - fixedmath.h + math - math.h mqueue - pthread.h net - Various network-related header files: netinet/ether.h, arpa/inet.h pthread - pthread.h diff --git a/nuttx/lib/fixedmath/Make.defs b/nuttx/lib/fixedmath/Make.defs new file mode 100644 index 0000000000..578e330153 --- /dev/null +++ b/nuttx/lib/fixedmath/Make.defs @@ -0,0 +1,43 @@ +############################################################################ +# lib/fixedmath/Make.defs +# +# 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. +# +############################################################################ + +# Add the fixed precision math C files to the build + +CSRCS += lib_rint.c lib_fixedmath.c lib_b16sin.c lib_b16cos.c lib_b16atan2.c + +# Add the fixed precision math directory to the build + +DEPPATH += --dep-path fixedmath +VPATH += :fixedmath diff --git a/nuttx/lib/math/lib_b16atan2.c b/nuttx/lib/fixedmath/lib_b16atan2.c similarity index 99% rename from nuttx/lib/math/lib_b16atan2.c rename to nuttx/lib/fixedmath/lib_b16atan2.c index 8792fa0879..69d132f80f 100644 --- a/nuttx/lib/math/lib_b16atan2.c +++ b/nuttx/lib/fixedmath/lib_b16atan2.c @@ -1,5 +1,5 @@ /**************************************************************************** - * lib/math/lib_b16atan2.c + * lib/fixedmath/lib_b16atan2.c * * Copyright (C) 2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/nuttx/lib/math/lib_b16cos.c b/nuttx/lib/fixedmath/lib_b16cos.c similarity index 98% rename from nuttx/lib/math/lib_b16cos.c rename to nuttx/lib/fixedmath/lib_b16cos.c index 7547871f63..3e9229029e 100644 --- a/nuttx/lib/math/lib_b16cos.c +++ b/nuttx/lib/fixedmath/lib_b16cos.c @@ -1,5 +1,5 @@ /**************************************************************************** - * lib/math/lib_b16cos.c + * lib/fixedmath/lib_b16cos.c * * Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/nuttx/lib/math/lib_b16sin.c b/nuttx/lib/fixedmath/lib_b16sin.c similarity index 99% rename from nuttx/lib/math/lib_b16sin.c rename to nuttx/lib/fixedmath/lib_b16sin.c index 1eee179934..491b0ec782 100644 --- a/nuttx/lib/math/lib_b16sin.c +++ b/nuttx/lib/fixedmath/lib_b16sin.c @@ -1,5 +1,5 @@ /**************************************************************************** - * lib/math/lib_b16sin.c + * lib/fixedmath/lib_b16sin.c * * Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/nuttx/lib/math/lib_fixedmath.c b/nuttx/lib/fixedmath/lib_fixedmath.c similarity index 100% rename from nuttx/lib/math/lib_fixedmath.c rename to nuttx/lib/fixedmath/lib_fixedmath.c diff --git a/nuttx/lib/math/lib_rint.c b/nuttx/lib/fixedmath/lib_rint.c similarity index 99% rename from nuttx/lib/math/lib_rint.c rename to nuttx/lib/fixedmath/lib_rint.c index bd861ecedc..3a6407b8c0 100644 --- a/nuttx/lib/math/lib_rint.c +++ b/nuttx/lib/fixedmath/lib_rint.c @@ -1,5 +1,5 @@ /************************************************************ - * lib/math/lib_rint.c + * lib/fixedmath/lib_rint.c * * Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/nuttx/lib/math/Kconfig b/nuttx/lib/math/Kconfig new file mode 100644 index 0000000000..ae2bf31307 --- /dev/null +++ b/nuttx/lib/math/Kconfig @@ -0,0 +1,4 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# diff --git a/nuttx/lib/math/Make.defs b/nuttx/lib/math/Make.defs index 126cd2f471..f656e1a735 100644 --- a/nuttx/lib/math/Make.defs +++ b/nuttx/lib/math/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # lib/math/Make.defs # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -33,11 +33,17 @@ # ############################################################################ -# Add the math C files to the build +if ($(CONFIG_LIBM),y) -CSRCS += lib_rint.c lib_fixedmath.c lib_b16sin.c lib_b16cos.c lib_b16atan2.c +# Add the floating point math C files to the build -# Add the math directory to the build +CSRCS += lib_acos.c lib_asin.c lib_atan.c lib_atan2.c lib_ceil.c lib_cos.c +CSRCS += lib_cosh.c lib_exp.c lib_fabs.c lib_floor.c lib_fmod.c lib_frexp.c +CRRCS += lib_ldexp.c lib_log.c lib_log10.c lib_log2.c lib_modf.c lib_pow.c +CSRCS += lib_sin.c lib_sinh.c lib_sqrt.c lib_tan.c lib_tanh.c + +# Add the floating point math directory to the build DEPPATH += --dep-path math VPATH += :math +endif diff --git a/nuttx/lib/math/Makefile b/nuttx/lib/math/Makefile new file mode 100644 index 0000000000..56be0f0abd --- /dev/null +++ b/nuttx/lib/math/Makefile @@ -0,0 +1,100 @@ +############################################################################ +# nuttx/lib/math/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 +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +# NSH Library + +ASRCS = +CSRCS = + +ifeq ($(CONFIG_MATHEXT_LIBRARY),y) +CSRCS += m_cos.c m_log2.c m_fmod.c m_sin.c m_fabs.c m_exp.c m_asin.c m_tan.c \ + m_modf.c m_ldexp.c m_acos.c m_frexp.c m_atan.c m_log.c m_tanh.c m_ceil.c \ + m_sinh.c m_sqrt.c m_pow.c m_cosh.c m_floor.c m_atan2.c m_log10.c +endif + +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 . +VPATH = + +# Build targets + +all: .built +.PHONY: context .depend 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 + +context: + +.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 Make.dep .depend + +-include Make.dep + diff --git a/nuttx/lib/math/lib_acos.c b/nuttx/lib/math/lib_acos.c new file mode 100644 index 0000000000..83650d132a --- /dev/null +++ b/nuttx/lib/math/lib_acos.c @@ -0,0 +1,30 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float acosf(float x) { + return (M_PI_2 - asinf(x)); +} + +double acos(double x) { + return (M_PI_2 - asin(x)); +} + +long double acosl(long double x) { + return (M_PI_2 - asinl(x)); +} diff --git a/nuttx/lib/math/lib_asin.c b/nuttx/lib/math/lib_asin.c new file mode 100644 index 0000000000..9d72e8042d --- /dev/null +++ b/nuttx/lib/math/lib_asin.c @@ -0,0 +1,88 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float asinf(float x) { + long double y, y_sin, y_cos; + + y = 0; + + while (1) { + y_sin = sinf(y); + y_cos = cosf(y); + + if (y > M_PI_2 || y < -M_PI_2) { + y = fmodf(y, M_PI); + } + + if (y_sin + DBL_EPSILON >= x && y_sin - DBL_EPSILON <= x) { + break; + } + + y = y - (y_sin - x) / y_cos; + } + + return y; +} + +double asin(double x) { + long double y, y_sin, y_cos; + + y = 0; + + while (1) { + y_sin = sin(y); + y_cos = cos(y); + + if (y > M_PI_2 || y < -M_PI_2) { + y = fmod(y, M_PI); + } + + if (y_sin + DBL_EPSILON >= x && y_sin - DBL_EPSILON <= x) { + break; + } + + y = y - (y_sin - x) / y_cos; + } + + return y; +} + +long double asinl(long double x) { + long double y, y_sin, y_cos; + + y = 0; + + while (1) { + y_sin = sinl(y); + y_cos = cosl(y); + + if (y > M_PI_2 || y < -M_PI_2) { + y = fmodl(y, M_PI); + } + + if (y_sin + LDBL_EPSILON >= x && y_sin - LDBL_EPSILON <= x) { + break; + } + + y = y - (y_sin - x) / y_cos; + } + + return y; +} + diff --git a/nuttx/lib/math/lib_atan.c b/nuttx/lib/math/lib_atan.c new file mode 100644 index 0000000000..e909e5a8e3 --- /dev/null +++ b/nuttx/lib/math/lib_atan.c @@ -0,0 +1,32 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include +#include +#include + +float atanf(float x) { + return asinf(x / sqrtf(x * x + 1)); +} + +double atan(double x) { + return asin(x / sqrt(x * x + 1)); +} + +long double atanl(long double x) { + return asinl(x / sqrtl(x * x + 1)); +} diff --git a/nuttx/lib/math/lib_atan2.c b/nuttx/lib/math/lib_atan2.c new file mode 100644 index 0000000000..b4ded0c168 --- /dev/null +++ b/nuttx/lib/math/lib_atan2.c @@ -0,0 +1,120 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float atan2f(float y, float x) { + + if (y == 0.0) { + if (x >= 0.0) { + return 0.0; + } + else { + return M_PI; + } + } + else if (y > 0.0) { + if (x == 0.0) { + return M_PI_2; + } + else if (x > 0.0) { + return atanf(y / x); + } + else { + return M_PI - atanf(y / x); + } + } + else { + if (x == 0.0) { + return M_PI + M_PI_2; + } + else if (x > 0.0) { + return 2 * M_PI - atanf(y / x); + } + else { + return M_PI + atanf(y / x); + } + } +} + +double atan2(double y, double x) { + + if (y == 0.0) { + if (x >= 0.0) { + return 0.0; + } + else { + return M_PI; + } + } + else if (y > 0.0) { + if (x == 0.0) { + return M_PI_2; + } + else if (x > 0.0) { + return atan(y / x); + } + else { + return M_PI - atan(y / x); + } + } + else { + if (x == 0.0) { + return M_PI + M_PI_2; + } + else if (x > 0.0) { + return 2 * M_PI - atan(y / x); + } + else { + return M_PI + atan(y / x); + } + } +} + +long double atan2l(long double y, long double x) { + + if (y == 0.0) { + if (x >= 0.0) { + return 0.0; + } + else { + return M_PI; + } + } + else if (y > 0.0) { + if (x == 0.0) { + return M_PI_2; + } + else if (x > 0.0) { + return atanl(y / x); + } + else { + return M_PI - atanl(y / x); + } + } + else { + if (x == 0.0) { + return M_PI + M_PI_2; + } + else if (x > 0.0) { + return 2 * M_PI - atanl(y / x); + } + else { + return M_PI + atanl(y / x); + } + } +} diff --git a/nuttx/lib/math/lib_ceil.c b/nuttx/lib/math/lib_ceil.c new file mode 100644 index 0000000000..c2447c0b85 --- /dev/null +++ b/nuttx/lib/math/lib_ceil.c @@ -0,0 +1,37 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float ceilf(float x) { + modff(x, &x); + if (x > 0.0) x += 1.0; + return x; +} + +double ceil(double x) { + modf(x, &x); + if (x > 0.0) x += 1.0; + return x; +} + +long double ceill(long double x) { + modfl(x, &x); + if (x > 0.0) x += 1.0; + return x; +} + diff --git a/nuttx/lib/math/lib_cos.c b/nuttx/lib/math/lib_cos.c new file mode 100644 index 0000000000..f8732b041a --- /dev/null +++ b/nuttx/lib/math/lib_cos.c @@ -0,0 +1,31 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include +#include + +float cosf(float x) { + return sinf(x + M_PI_2); +} + +double cos(double x) { + return sin(x + M_PI_2); +} + +long double cosl(long double x) { + return sinl(x + M_PI_2); +} diff --git a/nuttx/lib/math/lib_cosh.c b/nuttx/lib/math/lib_cosh.c new file mode 100644 index 0000000000..1069903112 --- /dev/null +++ b/nuttx/lib/math/lib_cosh.c @@ -0,0 +1,33 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float coshf(float x) { + x = expf(x); + return ((x + (1.0 / x)) / 2.0); +} + +double cosh(double x) { + x = exp(x); + return ((x + (1.0 / x)) / 2.0); +} + +long double coshl(long double x) { + x = expl(x); + return ((x + (1.0 / x)) / 2.0); +} diff --git a/nuttx/lib/math/lib_exp.c b/nuttx/lib/math/lib_exp.c new file mode 100644 index 0000000000..a70cb10e7c --- /dev/null +++ b/nuttx/lib/math/lib_exp.c @@ -0,0 +1,253 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include +#include +#include +#include + +#define M_E2 (M_E * M_E) +#define M_E4 (M_E2 * M_E2) +#define M_E8 (M_E4 * M_E4) +#define M_E16 (M_E8 * M_E8) +#define M_E32 (M_E16 * M_E16) +#define M_E64 (M_E32 * M_E32) +#define M_E128 (M_E64 * M_E64) +#define M_E256 (M_E128 * M_E128) +#define M_E512 (M_E256 * M_E256) +#define M_E1024 (M_E512 * M_E512) + +static double _expi_square_tbl[11] = { + M_E, // e^1 + M_E2, // e^2 + M_E4, // e^4 + M_E8, // e^8 + M_E16, // e^16 + M_E32, // e^32 + M_E64, // e^64 + M_E128, // e^128 + M_E256, // e^256 + M_E512, // e^512 + M_E1024, // e^1024 +}; + +static double _expi(size_t n) { + size_t i; + double val; + + if (n > 1024) { + return INFINITY; + } + + val = 1.0; + + for (i = 0; n; i++) { + if (n & (1 << i)) { + n &= ~(1 << i); + val *= _expi_square_tbl[i]; + } + } + + return val; +} + +static float _flt_inv_fact[] = { + 1.0 / 1.0, // 1/0! + 1.0 / 1.0, // 1/1! + 1.0 / 2.0, // 1/2! + 1.0 / 6.0, // 1/3! + 1.0 / 24.0, // 1/4! + 1.0 / 120.0, // 1/5! + 1.0 / 720.0, // 1/6! + 1.0 / 5040.0, // 1/7! + 1.0 / 40320.0, // 1/8! + 1.0 / 362880.0, // 1/9! + 1.0 / 3628800.0, // 1/10! +}; + +float expf(float x) { + size_t int_part; + bool invert; + float value; + float x0; + size_t i; + + if (x == 0) { + return 1; + } + else if (x < 0) { + invert = true; + x = -x; + } + else { + invert = false; + } + + /* extract integer component */ + int_part = (size_t) x; + + /* set x to fractional component */ + x -= (float) int_part; + + /* perform Taylor series approximation with eleven terms */ + value = 0.0; + x0 = 1.0; + for (i = 0; i < 10; i++) { + value += x0 * _flt_inv_fact[i]; + x0 *= x; + } + + /* multiply by exp of the integer component */ + value *= _expi(int_part); + + if (invert) { + return (1.0 / value); + } + else { + return value; + } +} + +static double _dbl_inv_fact[] = { + 1.0 / 1.0, // 1 / 0! + 1.0 / 1.0, // 1 / 1! + 1.0 / 2.0, // 1 / 2! + 1.0 / 6.0, // 1 / 3! + 1.0 / 24.0, // 1 / 4! + 1.0 / 120.0, // 1 / 5! + 1.0 / 720.0, // 1 / 6! + 1.0 / 5040.0, // 1 / 7! + 1.0 / 40320.0, // 1 / 8! + 1.0 / 362880.0, // 1 / 9! + 1.0 / 3628800.0, // 1 / 10! + 1.0 / 39916800.0, // 1 / 11! + 1.0 / 479001600.0, // 1 / 12! + 1.0 / 6227020800.0, // 1 / 13! + 1.0 / 87178291200.0, // 1 / 14! + 1.0 / 1307674368000.0, // 1 / 15! + 1.0 / 20922789888000.0, // 1 / 16! + 1.0 / 355687428096000.0, // 1 / 17! + 1.0 / 6402373705728000.0, // 1 / 18! +}; + +double exp(double x) { + size_t int_part; + bool invert; + double value; + double x0; + size_t i; + + if (x == 0) { + return 1; + } + else if (x < 0) { + invert = true; + x = -x; + } + else { + invert = false; + } + + /* extract integer component */ + int_part = (size_t) x; + + /* set x to fractional component */ + x -= (double) int_part; + + /* perform Taylor series approximation with nineteen terms */ + value = 0.0; + x0 = 1.0; + for (i = 0; i < 19; i++) { + value += x0 * _dbl_inv_fact[i]; + x0 *= x; + } + + /* multiply by exp of the integer component */ + value *= _expi(int_part); + + if (invert) { + return (1.0 / value); + } + else { + return value; + } +} + +static long double _ldbl_inv_fact[] = { + 1.0 / 1.0, // 1 / 0! + 1.0 / 1.0, // 1 / 1! + 1.0 / 2.0, // 1 / 2! + 1.0 / 6.0, // 1 / 3! + 1.0 / 24.0, // 1 / 4! + 1.0 / 120.0, // 1 / 5! + 1.0 / 720.0, // 1 / 6! + 1.0 / 5040.0, // 1 / 7! + 1.0 / 40320.0, // 1 / 8! + 1.0 / 362880.0, // 1 / 9! + 1.0 / 3628800.0, // 1 / 10! + 1.0 / 39916800.0, // 1 / 11! + 1.0 / 479001600.0, // 1 / 12! + 1.0 / 6227020800.0, // 1 / 13! + 1.0 / 87178291200.0, // 1 / 14! + 1.0 / 1307674368000.0, // 1 / 15! + 1.0 / 20922789888000.0, // 1 / 16! + 1.0 / 355687428096000.0, // 1 / 17! + 1.0 / 6402373705728000.0, // 1 / 18! +}; + +long double expl(long double x) { + size_t int_part; + bool invert; + long double value; + long double x0; + size_t i; + + if (x == 0) { + return 1; + } + else if (x < 0) { + invert = true; + x = -x; + } + else { + invert = false; + } + + /* extract integer component */ + int_part = (size_t) x; + + /* set x to fractional component */ + x -= (long double) int_part; + + /* perform Taylor series approximation with nineteen terms */ + value = 0.0; + x0 = 1.0; + for (i = 0; i < 19; i++) { + value += x0 * _ldbl_inv_fact[i]; + x0 *= x; + } + + /* multiply by exp of the integer component */ + value *= _expi(int_part); + + if (invert) { + return (1.0 / value); + } + else { + return value; + } +} diff --git a/nuttx/lib/math/lib_fabs.c b/nuttx/lib/math/lib_fabs.c new file mode 100644 index 0000000000..f479aa123d --- /dev/null +++ b/nuttx/lib/math/lib_fabs.c @@ -0,0 +1,30 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float fabsf(float x) { + return ((x < 0) ? -x : x); +} + +double fabs(double x) { + return ((x < 0) ? -x : x); +} + +long double fabsl(long double x) { + return ((x < 0) ? -x : x); +} diff --git a/nuttx/lib/math/lib_floor.c b/nuttx/lib/math/lib_floor.c new file mode 100644 index 0000000000..a6979ac8a1 --- /dev/null +++ b/nuttx/lib/math/lib_floor.c @@ -0,0 +1,37 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float floorf(float x) { + modff(x, &x); + if (x < 0.0) x -= 1.0; + return x; +} + +double floor(double x) { + modf(x, &x); + if (x < 0.0) x -= 1.0; + return x; +} + +long double floorl(long double x) { + modfl(x, &x); + if (x < 0.0) x -= 1.0; + return x; +} + diff --git a/nuttx/lib/math/lib_fmod.c b/nuttx/lib/math/lib_fmod.c new file mode 100644 index 0000000000..532fa33608 --- /dev/null +++ b/nuttx/lib/math/lib_fmod.c @@ -0,0 +1,67 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +/* If GCC/CLang builtins are available, use them */ +#ifdef __GNUC__ + +float fmodf(float x, float div) { + return __builtin_fmodf(x, div); +} + +double fmod(double x, double div) { + return __builtin_fmod(x, div); +} + +long double fmodl(long double x, long double div) { + return __builtin_fmodl(x, div); +} + +#else + +float fmodf(float x, float div) { + float n0; + + x /= div; + x = modff(x, &n0); + x *= div; + + return x; +} + +double fmod(double x, double div) { + double n0; + + x /= div; + x = modf(x, &n0); + x *= div; + + return x; +} + +long double fmodl(long double x, long double div) { + long double n0; + + x /= div; + x = modfl(x, &n0); + x *= div; + + return x; +} + +#endif diff --git a/nuttx/lib/math/lib_frexp.c b/nuttx/lib/math/lib_frexp.c new file mode 100644 index 0000000000..102609dbe8 --- /dev/null +++ b/nuttx/lib/math/lib_frexp.c @@ -0,0 +1,34 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float frexpf(float x, int *exp) { + *exp = (int) ceilf(log2f(x)); + return x / ldexpf(1.0, *exp); +} + +double frexp(double x, int *exp) { + *exp = (int) ceil(log2(x)); + return x / ldexp(1.0, *exp); +} + +long double frexpl(long double x, int *exp) { + *exp = (int) ceill(log2(x)); + return x / ldexpl(1.0, *exp); +} + diff --git a/nuttx/lib/math/lib_ldexp.c b/nuttx/lib/math/lib_ldexp.c new file mode 100644 index 0000000000..2ca79221a0 --- /dev/null +++ b/nuttx/lib/math/lib_ldexp.c @@ -0,0 +1,31 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float ldexpf(float x, int n) { + return (x * powf(2.0, (float) n)); +} + +double ldexp(double x, int n) { + return (x * pow(2.0, (double) n)); +} + +long double ldexpl(long double x, int n) { + return (x * powl(2.0, (long double) n)); +} + diff --git a/nuttx/lib/math/lib_log.c b/nuttx/lib/math/lib_log.c new file mode 100644 index 0000000000..62af0368aa --- /dev/null +++ b/nuttx/lib/math/lib_log.c @@ -0,0 +1,113 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float logf(float x) { + float y, y_old, ey, epsilon; + + y = 0.0; + y_old = 1.0; + epsilon = FLT_EPSILON; + + while (y > y_old + epsilon || y < y_old - epsilon) { + y_old = y; + ey = exp(y); + y -= (ey - x) / ey; + + if (y > 700.0) { + y = 700.0; + } + if (y < -700.0) { + y = -700.0; + } + + epsilon = (fabs(y) > 1.0) ? fabs(y) * FLT_EPSILON : FLT_EPSILON; + } + + if (y == 700.0) { + return INFINITY; + } + if (y == -700.0) { + return INFINITY; + } + + return y; +} + +double log(double x) { + double y, y_old, ey, epsilon; + + y = 0.0; + y_old = 1.0; + epsilon = DBL_EPSILON; + + while (y > y_old + epsilon || y < y_old - epsilon) { + y_old = y; + ey = exp(y); + y -= (ey - x) / ey; + + if (y > 700.0) { + y = 700.0; + } + if (y < -700.0) { + y = -700.0; + } + + epsilon = (fabs(y) > 1.0) ? fabs(y) * DBL_EPSILON : DBL_EPSILON; + } + + if (y == 700.0) { + return INFINITY; + } + if (y == -700.0) { + return INFINITY; + } + + return y; +} + +long double logl(long double x) { + long double y, y_old, ey, epsilon; + + y = 0.0; + y_old = 1.0; + epsilon = 1e-6; //fixme + + while (y > y_old + epsilon || y < y_old - epsilon) { + y_old = y; + ey = expl(y); + y -= (ey - x) / ey; + + if (y > 700.0) { + y = 700.0; + } + if (y < -700.0) { + y = -700.0; + } + } + + if (y == 700.0) { + return INFINITY; + } + if (y == -700.0) { + return INFINITY; + } + + return y; +} + diff --git a/nuttx/lib/math/lib_log10.c b/nuttx/lib/math/lib_log10.c new file mode 100644 index 0000000000..855480ad6c --- /dev/null +++ b/nuttx/lib/math/lib_log10.c @@ -0,0 +1,30 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float log10f(float x) { + return (logf(x) / M_LN10); +} + +double log10(double x) { + return (log(x) / M_LN10); +} + +long double log10l(long double x) { + return (logl(x) / M_LN10); +} diff --git a/nuttx/lib/math/lib_log2.c b/nuttx/lib/math/lib_log2.c new file mode 100644 index 0000000000..f8eb541b20 --- /dev/null +++ b/nuttx/lib/math/lib_log2.c @@ -0,0 +1,30 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float log2f(float x) { + return (logf(x) / M_LN2); +} + +double log2(double x) { + return (log(x) / M_LN2); +} + +long double log2l(long double x) { + return (logl(x) / M_LN2); +} diff --git a/nuttx/lib/math/lib_modf.c b/nuttx/lib/math/lib_modf.c new file mode 100644 index 0000000000..1e6fadc11b --- /dev/null +++ b/nuttx/lib/math/lib_modf.c @@ -0,0 +1,65 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include +#include + +float modff(float x, float *iptr) { + if (fabsf(x) >= 8388608.0) { + *iptr = x; + return 0.0; + } + else if (fabs(x) < 1.0) { + *iptr = 0.0; + return x; + } + else { + *iptr = (float) (int) x; + return (x - *iptr); + } +} + +double modf(double x, double *iptr) { + if (fabs(x) >= 4503599627370496.0) { + *iptr = x; + return 0.0; + } + else if (fabs(x) < 1.0) { + *iptr = 0.0; + return x; + } + else { + *iptr = (double) (int64_t) x; + return (x - *iptr); + } +} + +long double modfl(long double x, long double *iptr) { + if (fabs(x) >= 4503599627370496.0) { + *iptr = x; + return 0.0; + } + else if (fabs(x) < 1.0) { + *iptr = 0.0; + return x; + } + else { + *iptr = (long double) (int64_t) x; + return (x - *iptr); + } +} + diff --git a/nuttx/lib/math/lib_pow.c b/nuttx/lib/math/lib_pow.c new file mode 100644 index 0000000000..b353359eb2 --- /dev/null +++ b/nuttx/lib/math/lib_pow.c @@ -0,0 +1,30 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float powf(float b, float e) { + return expf(e * logf(b)); +} + +double pow(double b, double e) { + return exp(e * log(b)); +} + +long double powl(long double b, long double e) { + return expl(e * logl(b)); +} diff --git a/nuttx/lib/math/lib_sin.c b/nuttx/lib/math/lib_sin.c new file mode 100644 index 0000000000..e862104fd6 --- /dev/null +++ b/nuttx/lib/math/lib_sin.c @@ -0,0 +1,152 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include +#include +#include + +static float _flt_inv_fact[] = { + 1.0 / 1.0, // 1 / 1! + 1.0 / 6.0, // 1 / 3! + 1.0 / 120.0, // 1 / 5! + 1.0 / 5040.0, // 1 / 7! + 1.0 / 362880.0, // 1 / 9! + 1.0 / 39916800.0, // 1 / 11! +}; + +float sinf(float x) { + float x_squared; + float sin_x; + size_t i; + + /* move x to [-pi, pi) */ + x = fmodf(x, 2 * M_PI); + if (x >= M_PI) x -= 2 * M_PI; + if (x < -M_PI) x += 2 * M_PI; + + /* move x to [-pi/2, pi/2) */ + if (x >= M_PI_2) x = M_PI - x; + if (x < -M_PI_2) x = -M_PI - x; + + x_squared = x * x; + sin_x = 0.0; + + /* perform Taylor series approximation for sin(x) with six terms */ + for (i = 0; i < 6; i++) { + if (i % 2 == 0) { + sin_x += x * _flt_inv_fact[i]; + } + else { + sin_x -= x * _flt_inv_fact[i]; + } + + x *= x_squared; + } + + return sin_x; +} + +static double _dbl_inv_fact[] = { + 1.0 / 1.0, // 1 / 1! + 1.0 / 6.0, // 1 / 3! + 1.0 / 120.0, // 1 / 5! + 1.0 / 5040.0, // 1 / 7! + 1.0 / 362880.0, // 1 / 9! + 1.0 / 39916800.0, // 1 / 11! + 1.0 / 6227020800.0, // 1 / 13! + 1.0 / 1307674368000.0, // 1 / 15! + 1.0 / 355687428096000.0, // 1 / 17! + 1.0 / 121645100408832000.0, // 1 / 19! +}; + +double sin(double x) { + double x_squared; + double sin_x; + size_t i; + + /* move x to [-pi, pi) */ + x = fmod(x, 2 * M_PI); + if (x >= M_PI) x -= 2 * M_PI; + if (x < -M_PI) x += 2 * M_PI; + + /* move x to [-pi/2, pi/2) */ + if (x >= M_PI_2) x = M_PI - x; + if (x < -M_PI_2) x = -M_PI - x; + + x_squared = x * x; + sin_x = 0.0; + + /* perform Taylor series approximation for sin(x) with ten terms */ + for (i = 0; i < 10; i++) { + if (i % 2 == 0) { + sin_x += x * _dbl_inv_fact[i]; + } + else { + sin_x -= x * _dbl_inv_fact[i]; + } + + x *= x_squared; + } + + return sin_x; +} + +static long double _ldbl_inv_fact[] = { + 1.0 / 1.0, // 1 / 1! + 1.0 / 6.0, // 1 / 3! + 1.0 / 120.0, // 1 / 5! + 1.0 / 5040.0, // 1 / 7! + 1.0 / 362880.0, // 1 / 9! + 1.0 / 39916800.0, // 1 / 11! + 1.0 / 6227020800.0, // 1 / 13! + 1.0 / 1307674368000.0, // 1 / 15! + 1.0 / 355687428096000.0, // 1 / 17! + 1.0 / 121645100408832000.0, // 1 / 19! +}; + +long double sinl(long double x) { + long double x_squared; + long double sin_x; + size_t i; + + /* move x to [-pi, pi) */ + x = fmodl(x, 2 * M_PI); + if (x >= M_PI) x -= 2 * M_PI; + if (x < -M_PI) x += 2 * M_PI; + + /* move x to [-pi/2, pi/2) */ + if (x >= M_PI_2) x = M_PI - x; + if (x < -M_PI_2) x = -M_PI - x; + + x_squared = x * x; + sin_x = 0.0; + + /* perform Taylor series approximation for sin(x) with ten terms */ + for (i = 0; i < 10; i++) { + if (i % 2 == 0) { + sin_x += x * _ldbl_inv_fact[i]; + } + else { + sin_x -= x * _ldbl_inv_fact[i]; + } + + x *= x_squared; + } + + return sin_x; +} + diff --git a/nuttx/lib/math/lib_sinh.c b/nuttx/lib/math/lib_sinh.c new file mode 100644 index 0000000000..10276d821e --- /dev/null +++ b/nuttx/lib/math/lib_sinh.c @@ -0,0 +1,33 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float sinhf(float x) { + x = expf(x); + return ((x - (1.0 / x)) / 2.0); +} + +double sinh(double x) { + x = exp(x); + return ((x - (1.0 / x)) / 2.0); +} + +long double sinhl(long double x) { + x = expl(x); + return ((x - (1.0 / x)) / 2.0); +} diff --git a/nuttx/lib/math/lib_sqrt.c b/nuttx/lib/math/lib_sqrt.c new file mode 100644 index 0000000000..206a7fe82a --- /dev/null +++ b/nuttx/lib/math/lib_sqrt.c @@ -0,0 +1,116 @@ +/* + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include +#include +#include + +static float __sqrt_approx(float x) { + int32_t i; + + // floats + bit manipulation = +inf fun! + i = *((int32_t*) &x); + i = 0x1FC00000 + (i >> 1); + x = *((float*) &i); + + return x; +} + +float sqrtf(float x) { + float y; + + // filter out invalid/trivial inputs + if (x < 0.0) { errno = EDOM; return NAN; } + if (isnan(x)) return NAN; + if (isinf(x)) return INFINITY; + if (x == 0.0) return 0.0; + + // guess square root (using bit manipulation) + y = __sqrt_approx(x); + + // perform three iterations of approximation + // this number (3) is definitely optimal + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + + return y; +} + +double sqrt(double x) { + long double y, y1; + + // filter out invalid/trivial inputs + if (x < 0.0) { errno = EDOM; return NAN; } + if (isnan(x)) return NAN; + if (isinf(x)) return INFINITY; + if (x == 0.0) return 0.0; + + // guess square root (using bit manipulation) + y = __sqrt_approx(x); + + // perform four iterations of approximation + // this number (4) is definitely optimal + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + + // if guess was terribe (out of range of float) + // repeat approximation until convergence + if (y * y < x - 1.0 || y * y > x + 1.0) { + y1 = -1.0; + while (y != y1) { + y1 = y; + y = 0.5 * (y + x / y); + } + } + + return y; +} + +long double sqrtl(long double x) { + long double y, y1; + + // filter out invalid/trivial inputs + if (x < 0.0) { errno = EDOM; return NAN; } + if (isnan(x)) return NAN; + if (isinf(x)) return INFINITY; + if (x == 0.0) return 0.0; + + // guess square root (using bit manipulation) + y = __sqrt_approx(x); + + // perform four iterations of approximation + // this number (4) is definitely optimal + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + + // if guess was terribe (out of range of float) + // repeat approximation until convergence + if (y * y < x - 1.0 || y * y > x + 1.0) { + y1 = -1.0; + while (y != y1) { + y1 = y; + y = 0.5 * (y + x / y); + } + } + + return y; +} diff --git a/nuttx/lib/math/lib_tan.c b/nuttx/lib/math/lib_tan.c new file mode 100644 index 0000000000..c336a6260d --- /dev/null +++ b/nuttx/lib/math/lib_tan.c @@ -0,0 +1,31 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include +#include + +float tanf(float x) { + return (sinf(x) / cosf(x)); +} + +double tan(double x) { + return (sin(x) / cos(x)); +} + +long double tanl(long double x) { + return (sinl(x) / cosl(x)); +} diff --git a/nuttx/lib/math/lib_tanh.c b/nuttx/lib/math/lib_tanh.c new file mode 100644 index 0000000000..c6a1a1c875 --- /dev/null +++ b/nuttx/lib/math/lib_tanh.c @@ -0,0 +1,39 @@ +/* + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#include +#include + +float tanhf(float x) { + float x0 = expf(x); + float x1 = 1.0 / x0; + + return ((x0 + x1) / (x0 - x1)); +} + +double tanh(double x) { + double x0 = exp(x); + double x1 = 1.0 / x0; + + return ((x0 + x1) / (x0 - x1)); +} + +long double tanhl(long double x) { + long double x0 = exp(x); + long double x1 = 1.0 / x0; + + return ((x0 + x1) / (x0 - x1)); +} From 0e190d4cf7f3d151592414d8bc3d3eaf77e0b0e8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 28 Oct 2012 18:42:09 +0000 Subject: [PATCH 039/206] lib/math files not follow coding standard; float, double, and long double versions in separate files to reduce size of dumb link git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5270 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/COPYING | 22 ++ nuttx/ChangeLog | 7 + nuttx/Kconfig | 11 + nuttx/Makefile | 36 +++- nuttx/include/nuttx/compiler.h | 8 +- nuttx/include/nuttx/float.h | 225 +++++++++++++++++++ nuttx/include/nuttx/math.h | 262 ++++++++++++++++++++++- nuttx/lib/Kconfig | 22 +- nuttx/lib/Makefile | 1 + nuttx/lib/lib_internal.h | 54 +++-- nuttx/lib/math/Kconfig | 22 ++ nuttx/lib/math/Make.defs | 15 +- nuttx/lib/math/Makefile | 100 --------- nuttx/lib/math/lib_acos.c | 44 ++-- nuttx/lib/math/lib_acosf.c | 41 ++++ nuttx/lib/math/lib_acosl.c | 46 ++++ nuttx/lib/math/lib_asin.c | 111 ++++------ nuttx/lib/math/lib_asinf.c | 65 ++++++ nuttx/lib/math/lib_asinl.c | 69 ++++++ nuttx/lib/math/lib_atan.c | 44 ++-- nuttx/lib/math/lib_atan2.c | 176 ++++++--------- nuttx/lib/math/lib_atan2f.c | 81 +++++++ nuttx/lib/math/lib_atan2l.c | 87 ++++++++ nuttx/lib/math/lib_atanf.c | 43 ++++ nuttx/lib/math/lib_atanl.c | 48 +++++ nuttx/lib/math/lib_ceil.c | 57 +++-- nuttx/lib/math/lib_ceilf.c | 47 ++++ nuttx/lib/math/lib_ceill.c | 52 +++++ nuttx/lib/math/lib_cos.c | 47 ++-- nuttx/lib/math/lib_cosf.c | 41 ++++ nuttx/lib/math/lib_cosh.c | 50 +++-- nuttx/lib/math/lib_coshf.c | 42 ++++ nuttx/lib/math/lib_coshl.c | 47 ++++ nuttx/lib/math/lib_cosl.c | 46 ++++ nuttx/lib/math/lib_exp.c | 332 +++++++++-------------------- nuttx/lib/math/lib_expf.c | 112 ++++++++++ nuttx/lib/math/lib_expl.c | 126 +++++++++++ nuttx/lib/math/lib_fabs.c | 44 ++-- nuttx/lib/math/lib_fabsf.c | 41 ++++ nuttx/lib/math/lib_fabsl.c | 46 ++++ nuttx/lib/math/lib_floor.c | 57 +++-- nuttx/lib/math/lib_floorf.c | 47 ++++ nuttx/lib/math/lib_floorl.c | 52 +++++ nuttx/lib/math/lib_fmod.c | 83 +++----- nuttx/lib/math/lib_fmodf.c | 47 ++++ nuttx/lib/math/lib_fmodl.c | 52 +++++ nuttx/lib/math/lib_frexp.c | 49 +++-- nuttx/lib/math/lib_frexpf.c | 42 ++++ nuttx/lib/math/lib_frexpl.c | 47 ++++ nuttx/lib/math/lib_ldexp.c | 45 ++-- nuttx/lib/math/lib_ldexpf.c | 41 ++++ nuttx/lib/math/lib_ldexpl.c | 46 ++++ nuttx/lib/math/lib_libexpi.c | 103 +++++++++ nuttx/lib/math/lib_libsqrtapprox.c | 50 +++++ nuttx/lib/math/lib_log.c | 149 +++++-------- nuttx/lib/math/lib_log10.c | 44 ++-- nuttx/lib/math/lib_log10f.c | 41 ++++ nuttx/lib/math/lib_log10l.c | 46 ++++ nuttx/lib/math/lib_log2.c | 44 ++-- nuttx/lib/math/lib_log2f.c | 41 ++++ nuttx/lib/math/lib_log2l.c | 46 ++++ nuttx/lib/math/lib_logf.c | 77 +++++++ nuttx/lib/math/lib_logl.c | 80 +++++++ nuttx/lib/math/lib_modf.c | 89 ++++---- nuttx/lib/math/lib_modff.c | 55 +++++ nuttx/lib/math/lib_modfl.c | 61 ++++++ nuttx/lib/math/lib_pow.c | 44 ++-- nuttx/lib/math/lib_powf.c | 41 ++++ nuttx/lib/math/lib_powl.c | 46 ++++ nuttx/lib/math/lib_sin.c | 220 ++++++++----------- nuttx/lib/math/lib_sinf.c | 104 +++++++++ nuttx/lib/math/lib_sinh.c | 48 +++-- nuttx/lib/math/lib_sinhf.c | 42 ++++ nuttx/lib/math/lib_sinhl.c | 47 ++++ nuttx/lib/math/lib_sinl.c | 114 ++++++++++ nuttx/lib/math/lib_sqrt.c | 177 +++++++-------- nuttx/lib/math/lib_sqrtf.c | 84 ++++++++ nuttx/lib/math/lib_sqrtl.c | 101 +++++++++ nuttx/lib/math/lib_tan.c | 45 ++-- nuttx/lib/math/lib_tanf.c | 41 ++++ nuttx/lib/math/lib_tanh.c | 54 +++-- nuttx/lib/math/lib_tanhf.c | 44 ++++ nuttx/lib/math/lib_tanhl.c | 49 +++++ nuttx/lib/math/lib_tanl.c | 46 ++++ 84 files changed, 4442 insertions(+), 1209 deletions(-) create mode 100644 nuttx/include/nuttx/float.h delete mode 100644 nuttx/lib/math/Makefile create mode 100644 nuttx/lib/math/lib_acosf.c create mode 100644 nuttx/lib/math/lib_acosl.c create mode 100644 nuttx/lib/math/lib_asinf.c create mode 100644 nuttx/lib/math/lib_asinl.c create mode 100644 nuttx/lib/math/lib_atan2f.c create mode 100644 nuttx/lib/math/lib_atan2l.c create mode 100644 nuttx/lib/math/lib_atanf.c create mode 100644 nuttx/lib/math/lib_atanl.c create mode 100644 nuttx/lib/math/lib_ceilf.c create mode 100644 nuttx/lib/math/lib_ceill.c create mode 100644 nuttx/lib/math/lib_cosf.c create mode 100644 nuttx/lib/math/lib_coshf.c create mode 100644 nuttx/lib/math/lib_coshl.c create mode 100644 nuttx/lib/math/lib_cosl.c create mode 100644 nuttx/lib/math/lib_expf.c create mode 100644 nuttx/lib/math/lib_expl.c create mode 100644 nuttx/lib/math/lib_fabsf.c create mode 100644 nuttx/lib/math/lib_fabsl.c create mode 100644 nuttx/lib/math/lib_floorf.c create mode 100644 nuttx/lib/math/lib_floorl.c create mode 100644 nuttx/lib/math/lib_fmodf.c create mode 100644 nuttx/lib/math/lib_fmodl.c create mode 100644 nuttx/lib/math/lib_frexpf.c create mode 100644 nuttx/lib/math/lib_frexpl.c create mode 100644 nuttx/lib/math/lib_ldexpf.c create mode 100644 nuttx/lib/math/lib_ldexpl.c create mode 100644 nuttx/lib/math/lib_libexpi.c create mode 100644 nuttx/lib/math/lib_libsqrtapprox.c create mode 100644 nuttx/lib/math/lib_log10f.c create mode 100644 nuttx/lib/math/lib_log10l.c create mode 100644 nuttx/lib/math/lib_log2f.c create mode 100644 nuttx/lib/math/lib_log2l.c create mode 100644 nuttx/lib/math/lib_logf.c create mode 100644 nuttx/lib/math/lib_logl.c create mode 100644 nuttx/lib/math/lib_modff.c create mode 100644 nuttx/lib/math/lib_modfl.c create mode 100644 nuttx/lib/math/lib_powf.c create mode 100644 nuttx/lib/math/lib_powl.c create mode 100644 nuttx/lib/math/lib_sinf.c create mode 100644 nuttx/lib/math/lib_sinhf.c create mode 100644 nuttx/lib/math/lib_sinhl.c create mode 100644 nuttx/lib/math/lib_sinl.c create mode 100644 nuttx/lib/math/lib_sqrtf.c create mode 100644 nuttx/lib/math/lib_sqrtl.c create mode 100644 nuttx/lib/math/lib_tanf.c create mode 100644 nuttx/lib/math/lib_tanhf.c create mode 100644 nuttx/lib/math/lib_tanhl.c create mode 100644 nuttx/lib/math/lib_tanl.c diff --git a/nuttx/COPYING b/nuttx/COPYING index 1956fb6c72..4cf66a5965 100644 --- a/nuttx/COPYING +++ b/nuttx/COPYING @@ -192,6 +192,28 @@ lib/string/lib_vikmemcpy.c 3. This notice may not be removed or altered from any source distribution. +lib/math +^^^^^^^^ + + If you enable CONFIG_LIB, you will build the math library at lib/math. + This library was taken from the math library developed for the Rhombus + OS by Nick Johnson (https://github.com/nickbjohnson4224/rhombus). This + port was contributed by Darcy Gong. The Rhombus math library has this + compatible MIT license: + + Copyright (C) 2009-2011 Nick Johnson + + Permission to use, copy, modify, and distribute this software for any + purpose with or without fee is hereby granted, provided that the above + copyright notice and this permission notice appear in all copies. + + THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + Documents/rss.gif ^^^^^^^^^^^^^^^^^ diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 918cd8608a..723f534bc5 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3529,3 +3529,10 @@ the math library from the Rhombus OS * lib/math: Now contains the math library from the Rhombus OS by Nick Johnson (submitted by Darcy Gong). + * include/float.h: Add a first cut at the float.h header file. This + really should be an architecture/toolchain-specific header file. It + is only used if CONFIG_ARCH_FLOAT_H is defined. + * lib/math: Files now conform to coding standards. Separated float, + double, and long double versions of code into separate files so that + they don't draw in so much un-necessary code when doing a dumb link. + diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 8239dec02d..2d5b9e5851 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -192,6 +192,17 @@ config ARCH_MATH_H that don't select ARCH_MATH_H, the redirecting math.h header file will stay out-of-the-way in include/nuttx/. +config ARCH_FLOAT_H + bool "float.h" + default n + ---help--- + The float.h header file defines the properties of your floating + point implementation. It would always be best to use your + toolchain's float.h header file but if none is avaiable, a default + float.h header file will provided if this option is selected. However + there is no assurance that the settings in this float.h are actually + correct for your platform! + config ARCH_STDARG_H bool "stdarg.h" default n diff --git a/nuttx/Makefile b/nuttx/Makefile index 73bffc3014..0813098c6a 100644 --- a/nuttx/Makefile +++ b/nuttx/Makefile @@ -263,15 +263,47 @@ all: $(BIN) # Target used to copy include/nuttx/math.h. If CONFIG_ARCH_MATH_H is # defined, then there is an architecture specific math.h header file # that will be included indirectly from include/math.h. But first, we -# have to copy math.h from include/nuttx/. to include/. +# have to copy math.h from include/nuttx/. to include/. Logic within +# include/nuttx/math.h will hand the redirection to the architecture- +# specific math.h header file. +# +# If the CONFIG_LIBM is defined, the Rhombus libm will be built at lib/math. +# Definitions and prototypes for the Rhombus libm are also contained in +# include/nuttx/math.h and so the file must also be copied in that case. +# +# If neither CONFIG_ARCH_MATH_H nor CONFIG_LIBM is defined, then no math.h +# header file will be provided. You would want that behavior if (1) you +# don't use libm, or (2) you want to use the math.h and libm provided +# within your toolchain. ifeq ($(CONFIG_ARCH_MATH_H),y) +NEED_MATH_H = y +else +ifeq ($(CONFIG_LIBM),y) +NEED_MATH_H = y +endif +endif + +ifeq ($(NEED_MATH_H),y) include/math.h: include/nuttx/math.h @cp -f include/nuttx/math.h include/math.h else include/math.h: endif +# The float.h header file defines the properties of your floating point +# implementation. It would always be best to use your toolchain's float.h +# header file but if none is avaiable, a default float.h header file will +# provided if this option is selected. However there is no assurance that +# the settings in this float.h are actually correct for your platform! + +ifeq ($(CONFIG_ARCH_FLOAT_H),y) +include/float.h: include/nuttx/float.h + @cp -f include/nuttx/float.h include/float.h +else +include/float.h: +endif + # Target used to copy include/nuttx/stdarg.h. If CONFIG_ARCH_STDARG_H is # defined, then there is an architecture specific stdarg.h header file # that will be included indirectly from include/stdarg.h. But first, we @@ -364,7 +396,7 @@ dirlinks: include/arch include/arch/board include/arch/chip $(ARCH_SRC)/board $( # the config.h and version.h header files in the include/nuttx directory and # the establishment of symbolic links to configured directories. -context: check_context include/nuttx/config.h include/nuttx/version.h include/math.h include/stdarg.h dirlinks +context: check_context include/nuttx/config.h include/nuttx/version.h include/math.h include/float.h include/stdarg.h dirlinks @for dir in $(CONTEXTDIRS) ; do \ $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" context; \ done diff --git a/nuttx/include/nuttx/compiler.h b/nuttx/include/nuttx/compiler.h index bbb23d01d9..510f7d4117 100644 --- a/nuttx/include/nuttx/compiler.h +++ b/nuttx/include/nuttx/compiler.h @@ -196,8 +196,9 @@ /* GCC supports both types double and long long */ -# define CONFIG_HAVE_DOUBLE 1 # define CONFIG_HAVE_LONG_LONG 1 +# define CONFIG_HAVE_DOUBLE 1 +# define CONFIG_HAVE_LONG_DOUBLE 1 /* Structures and unions can be assigned and passed as values */ @@ -301,6 +302,7 @@ # undef CONFIG_HAVE_LONG_LONG # undef CONFIG_HAVE_DOUBLE +# undef CONFIG_HAVE_LONG_DOUBLE /* Structures and unions cannot be passed as values or used * in assignments. @@ -403,8 +405,9 @@ * simply do not support long long or double. */ -# undef CONFIG_HAVE_DOUBLE # undef CONFIG_HAVE_LONG_LONG +# undef CONFIG_HAVE_DOUBLE +# undef CONFIG_HAVE_LONG_DOUBLE /* Structures and unions can be assigned and passed as values */ @@ -441,6 +444,7 @@ # define inline # undef CONFIG_HAVE_LONG_LONG # undef CONFIG_HAVE_DOUBLE +# undef CONFIG_HAVE_LONG_DOUBLE # undef CONFIG_CAN_PASS_STRUCTS #endif diff --git a/nuttx/include/nuttx/float.h b/nuttx/include/nuttx/float.h new file mode 100644 index 0000000000..a8e4aa28b5 --- /dev/null +++ b/nuttx/include/nuttx/float.h @@ -0,0 +1,225 @@ +/**************************************************************************** + * include/nuttx/float.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: http://pubs.opengroup.org/onlinepubs/009695399/basedefs/float.h.html + * + * 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 __INCLUDE_NUTTX_FLOAT_H +#define __INCLUDE_NUTTX_FLOAT_H + +/* TODO: These values could vary with architectures toolchains. This + * logic should be move at least to the include/arch directory. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Radix of exponent representation, b. */ + +#define FLT_RADIX 2 + +/* Number of base-FLT_RADIX digits in the floating-point significand, p. */ + +#define FLT_MANT_DIG 24 + +#if CONFIG_HAVE_DOUBLE +# define DBL_MANT_DIG 53 +#else +# define DBL_MANT_DIG FLT_MANT_DIG +#endif + +#ifdef CONFIG_HAVE_LONG_DOUBLE +# define LDBL_MANT_DIG DBL_MANT_DIG /* FIX ME */ +#else +# define LDBL_MANT_DIG DBL_MANT_DIG +#endif + +/* Number of decimal digits, n, such that any floating-point number in the + * widest supported floating type with pmax radix b digits can be rounded + * to a floating-point number with n decimal digits and back again without + * change to the value. + */ + +#define DECIMAL_DIG 10 + +/* Number of decimal digits, q, such that any floating-point number with q + * decimal digits can be rounded into a floating-point number with p radix + * b digits and back again without change to the q decimal digits. + */ + +#define FLT_DIG 6 + +#if CONFIG_HAVE_DOUBLE +# define DBL_DIG 15 /* 10 */ +#else +# define DBL_DIG FLT_DIG +#endif + +#ifdef CONFIG_HAVE_LONG_DOUBLE +# define LDBL_DIG DBL_DIG /* FIX ME */ +#else +# define LDBL_DIG DBL_DIG +#endif + +/* Minimum negative integer such that FLT_RADIX raised to that power minus + * 1 is a normalized floating-point number, emin. + */ + +#define FLT_MIN_EXP (-125) + +#if CONFIG_HAVE_DOUBLE +# define DBL_MIN_EXP (-1021) +#else +# define DBL_MIN_EXP FLT_MIN_EXP +#endif + +#ifdef CONFIG_HAVE_LONG_DOUBLE +# define LDBL_MIN_EXP DBL_MIN_EXP /* FIX ME */ +#else +# define LDBL_MIN_EXP DBL_MIN_EXP +#endif + +/* inimum negative integer such that 10 raised to that power is in the range + * of normalized floating-point numbers. + */ + +#define FLT_MIN_10_EXP (-37) + +#if CONFIG_HAVE_DOUBLE +# define DBL_MIN_10_EXP (-307) /* -37 */ +#else +# define DBL_MIN_10_EXP FLT_MIN_10_EXP +#endif + +#ifdef CONFIG_HAVE_LONG_DOUBLE +# define LDBL_MIN_10_EXP DBL_MIN_10_EXP /* FIX ME */ +#else +# define LDBL_MIN_10_EXP DBL_MIN_10_EXP +#endif + +/* Maximum integer such that FLT_RADIX raised to that power minus 1 is a + * representable finite floating-point number, emax. + */ + +#define FLT_MAX_EXP 128 + +#if CONFIG_HAVE_DOUBLE +# define DBL_MAX_EXP 1024 +#else +# define DBL_MAX_EXP FLT_MAX_EXP +#endif + +#ifdef CONFIG_HAVE_LONG_DOUBLE +# define LDBL_MAX_EXP DBL_MAX_EXP /* FIX ME */ +#else +# define LDBL_MAX_EXP DBL_MAX_EXP +#endif + +/* Maximum integer such that 10 raised to that power is in the range of + * representable finite floating-point numbers. + */ + +#define FLT_MAX_10_EXP 38 /* 37 */ + +#if CONFIG_HAVE_DOUBLE +# define DBL_MAX_10_EXP 308 /* 37 */ +#else +# define DBL_MAX_10_EXP FLT_MAX_10_EXP +#endif + +#ifdef CONFIG_HAVE_LONG_DOUBLE +# define LDBL_MAX_10_EXP DBL_MAX_10_EXP /* FIX ME */ +#else +# define LDBL_MAX_10_EXP DBL_MAX_10_EXP +#endif + +/* Maximum representable finite floating-point number. */ + +#define FLT_MAX 3.40282347e+38F /* 1E+37 */ + +#if CONFIG_HAVE_DOUBLE +# define DBL_MAX 1.7976931348623157e+308 /* 1E+37 */ +#else +# define DBL_MAX FLT_MAX +#endif + +#ifdef CONFIG_HAVE_LONG_DOUBLE +# define LDBL_MAX DBL_MAX /* FIX ME */ +#else +# define LDBL_MAX DBL_MAX +#endif + +/* The difference between 1 and the least value greater than 1 that is + * representable in the given floating-point type, b1-p. + */ + +#define FLT_EPSILON 1.1920929e-07F /* 1E-5 */ + +#if CONFIG_HAVE_DOUBLE +# define DBL_EPSILON 2.2204460492503131e-16 /* 1E-9 */ +#else +# define DBL_EPSILON FLT_EPSILON +#endif + +#ifdef CONFIG_HAVE_LONG_DOUBLE +# define LDBL_EPSILON DBL_EPSILON /* FIX ME */ +#else +# define LDBL_EPSILON DBL_EPSILON +#endif + +/* Minimum normalized positive floating-point number, bemin -1. */ + +#define FLT_MIN 1.17549435e-38F /* 1E-37 */ + +#if CONFIG_HAVE_DOUBLE +#define DBL_MIN 2.2250738585072014e-308 /* 1E-37 */ +#else +# define DBL_MIN FLT_MIN +#endif + +#ifdef CONFIG_HAVE_LONG_DOUBLE +# define LDBL_MIN DBL_MIN /* FIX ME */ +#else +# define LDBL_MIN DBL_MIN +#endif + +#endif /* __INCLUDE_NUTTX_FLOAT_H */ diff --git a/nuttx/include/nuttx/math.h b/nuttx/include/nuttx/math.h index 84dbea6e03..160926d070 100644 --- a/nuttx/include/nuttx/math.h +++ b/nuttx/include/nuttx/math.h @@ -50,14 +50,272 @@ #ifdef CONFIG_ARCH_MATH_H # include -#endif + +/* If CONFIG_LIB is enabled, then the math library at lib/math will be + * built. This library was taken from the math library developed for the + * Rhombus OS by Nick Johnson (https://github.com/nickbjohnson4224/rhombus). + * The port or the Rhombus math library was contributed by Darcy Gong. + */ + +#else if defined CONFIG_LIBM /**************************************************************************** - * Type Definitions + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * ****************************************************************************/ +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* General Constants ********************************************************/ + +#define INFINITY (1.0/0.0) +#define NAN (0.0/0.0) +#define HUGE_VAL INFINITY + +#define isnan(x) ((x) != (x)) +#define isinf(x) (((x) == INFINITY) || ((x) == -INFINITY)) + +/* Exponential and Logarithmic constants ************************************/ + +#define M_E 2.7182818284590452353602874713526625 +#define M_SQRT2 1.4142135623730950488016887242096981 +#define M_SQRT1_2 0.7071067811865475244008443621048490 +#define M_LOG2E 1.4426950408889634073599246810018921 +#define M_LOG10E 0.4342944819032518276511289189166051 +#define M_LN2 0.6931471805599453094172321214581765 +#define M_LN10 2.3025850929940456840179914546843642 + +/* Trigonometric Constants **************************************************/ + +#define M_PI 3.1415926535897932384626433832795029 +#define M_PI_2 1.5707963267948966192313216916397514 +#define M_PI_4 0.7853981633974483096156608458198757 +#define M_1_PI 0.3183098861837906715377675267450287 +#define M_2_PI 0.6366197723675813430755350534900574 +#define M_2_SQRTPI 1.1283791670955125738961589031215452 + /**************************************************************************** * Public Function Prototypes ****************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif + +/* General Functions ********************************************************/ + +float ceilf (float x); +#if CONFIG_HAVE_DOUBLE +double ceil (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double ceill (long double x); +#endif + +float floorf(float x); +#if CONFIG_HAVE_DOUBLE +double floor (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double floorl(long double x); +#endif + +float fabsf (float x); +#if CONFIG_HAVE_DOUBLE +double fabs (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double fabsl (long double x); +#endif + +float modff (float x, float *iptr); +#if CONFIG_HAVE_DOUBLE +double modf (double x, double *iptr); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double modfl (long double x, long double *iptr); +#endif + +float fmodf (float x, float div); +#if CONFIG_HAVE_DOUBLE +double fmod (double x, double div); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double fmodl (long double x, long double div); +#endif + +/* Exponential and Logarithmic Functions ************************************/ + +float powf (float b, float e); +#if CONFIG_HAVE_DOUBLE +double pow (double b, double e); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double powl (long double b, long double e); +#endif + +float expf (float x); +#if CONFIG_HAVE_DOUBLE +double exp (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double expl (long double x); +#endif + +float logf (float x); +#if CONFIG_HAVE_DOUBLE +double log (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double logl (long double x); +#endif + +float log10f(float x); +#if CONFIG_HAVE_DOUBLE +double log10 (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double log10l(long double x); +#endif + +float log2f (float x); +#if CONFIG_HAVE_DOUBLE +double log2 (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double log2l (long double x); +#endif + +float sqrtf (float x); +#if CONFIG_HAVE_DOUBLE +double sqrt (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double sqrtl (long double x); +#endif + +float ldexpf(float x, int n); +#if CONFIG_HAVE_DOUBLE +double ldexp (double x, int n); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double ldexpl(long double x, int n); +#endif + +float frexpf(float x, int *exp); +#if CONFIG_HAVE_DOUBLE +double frexp (double x, int *exp); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double frexpl(long double x, int *exp); +#endif + +/* Trigonometric Functions **************************************************/ + +float sinf (float x); +#if CONFIG_HAVE_DOUBLE +double sin (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double sinl (long double x); +#endif + +float cosf (float x); +#if CONFIG_HAVE_DOUBLE +double cos (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double cosl (long double x); +#endif + +float tanf (float x); +#if CONFIG_HAVE_DOUBLE +double tan (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double tanl (long double x); +#endif + +float asinf (float x); +#if CONFIG_HAVE_DOUBLE +double asin (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double asinl (long double x); +#endif + +float acosf (float x); +#if CONFIG_HAVE_DOUBLE +double acos (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double acosl (long double x); +#endif + +float atanf (float x); +#if CONFIG_HAVE_DOUBLE +double atan (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double atanl (long double x); +#endif + +float atan2f(float y, float x); +#if CONFIG_HAVE_DOUBLE +double atan2 (double y, double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double atan2l(long double y, long double x); +#endif + +float sinhf (float x); +#if CONFIG_HAVE_DOUBLE +double sinh (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double sinhl (long double x); +#endif + +float coshf (float x); +#if CONFIG_HAVE_DOUBLE +double cosh (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double coshl (long double x); +#endif + +float tanhf (float x); +#if CONFIG_HAVE_DOUBLE +double tanh (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double tanhl (long double x); +#endif + +#if defined(__cplusplus) +} +#endif + +#endif /* CONFIG_LIBM */ #endif /* __INCLUDE_NUTTX_MATH_H */ diff --git a/nuttx/lib/Kconfig b/nuttx/lib/Kconfig index 77cf626656..440e9c3e25 100644 --- a/nuttx/lib/Kconfig +++ b/nuttx/lib/Kconfig @@ -30,27 +30,7 @@ config LIB_HOMEDIR ---help--- The home directory to use with operations like such as 'cd ~' -config LIBM - bool "Math library" - default n - depends on !ARCH_MATH_H - ---help--- - By default, no math library will be provided by NuttX. In this this case, it - is assumed that (1) no math library is required, or (2) you will be using the - math.h header file and the libm library provided by your toolchain. - - This is may be a very good choice is possible because your toolchain may have - have a highly optimized version of libm. - - Another possibility is that you have a custom, architecture-specific math - libary and that the corresponding math.h file resides at arch//include/math.h. - The option is selected via ARCH_MATH_H. If ARCH_MATH_H is selected,then the include/nuttx/math.h - header file will be copied to include/math.h where it can be used by your applications. - - If ARCH_MATH_H is not defined, then this option can be selected to build a generic, - math library built into NuttX. This math library comes from the Rhombus OS and - was written by Nick Johnson. The Rhombus OS math library port was contributed by - Darcy Gong. +source lib/math/Kconfig config NOPRINTF_FIELDWIDTH bool "Disable sprintf support fieldwidth" diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile index 5c62967ce8..406c2276ef 100644 --- a/nuttx/lib/Makefile +++ b/nuttx/lib/Makefile @@ -50,6 +50,7 @@ include pthread/Make.defs include semaphore/Make.defs include signal/Make.defs include mqueue/Make.defs +include math/Make.defs include fixedmath/Make.defs include net/Make.defs include time/Make.defs diff --git a/nuttx/lib/lib_internal.h b/nuttx/lib/lib_internal.h index c3d9bfd18e..5da0ac9249 100644 --- a/nuttx/lib/lib_internal.h +++ b/nuttx/lib/lib_internal.h @@ -117,56 +117,56 @@ extern bool g_dbgenable; /* Defined in lib_streamsem.c */ #if CONFIG_NFILE_STREAMS > 0 -extern void stream_semtake(FAR struct streamlist *list); -extern void stream_semgive(FAR struct streamlist *list); +void stream_semtake(FAR struct streamlist *list); +void stream_semgive(FAR struct streamlist *list); #endif /* Defined in lib_libnoflush.c */ #ifdef CONFIG_STDIO_LINEBUFFER -extern int lib_noflush(FAR struct lib_outstream_s *this); +int lib_noflush(FAR struct lib_outstream_s *this); #endif /* Defined in lib_libsprintf.c */ -extern int lib_sprintf(FAR struct lib_outstream_s *obj, +int lib_sprintf(FAR struct lib_outstream_s *obj, const char *fmt, ...); /* Defined lib_libvsprintf.c */ -extern int lib_vsprintf(FAR struct lib_outstream_s *obj, - FAR const char *src, va_list ap); +int lib_vsprintf(FAR struct lib_outstream_s *obj, + FAR const char *src, va_list ap); /* Defined lib_rawprintf.c */ -extern int lib_rawvprintf(const char *src, va_list ap); +int lib_rawvprintf(const char *src, va_list ap); /* Defined lib_lowprintf.c */ -extern int lib_lowvprintf(const char *src, va_list ap); +int lib_lowvprintf(const char *src, va_list ap); /* Defined in lib_dtoa.c */ #ifdef CONFIG_LIBC_FLOATINGPOINT -extern char *__dtoa(double d, int mode, int ndigits, - int *decpt, int *sign, char **rve); +char *__dtoa(double d, int mode, int ndigits, int *decpt, int *sign, + char **rve); #endif /* Defined in lib_libwrite.c */ -extern ssize_t lib_fwrite(FAR const void *ptr, size_t count, FAR FILE *stream); +ssize_t lib_fwrite(FAR const void *ptr, size_t count, FAR FILE *stream); /* Defined in lib_libfread.c */ -extern ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream); +ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream); /* Defined in lib_libfflush.c */ -extern ssize_t lib_fflush(FAR FILE *stream, bool bforce); +ssize_t lib_fflush(FAR FILE *stream, bool bforce); /* Defined in lib_rdflush.c */ -extern int lib_rdflush(FAR FILE *stream); +int lib_rdflush(FAR FILE *stream); /* Defined in lib_wrflush.c */ @@ -175,25 +175,37 @@ int lib_wrflush(FAR FILE *stream); /* Defined in lib_sem.c */ #if CONFIG_STDIO_BUFFER_SIZE > 0 -extern void lib_sem_initialize(FAR struct file_struct *stream); -extern void lib_take_semaphore(FAR struct file_struct *stream); -extern void lib_give_semaphore(FAR struct file_struct *stream); +void lib_sem_initialize(FAR struct file_struct *stream); +void lib_take_semaphore(FAR struct file_struct *stream); +void lib_give_semaphore(FAR struct file_struct *stream); #endif /* Defined in lib_libgetbase.c */ -extern int lib_getbase(const char *nptr, const char **endptr); +int lib_getbase(const char *nptr, const char **endptr); /* Defined in lib_skipspace.c */ -extern void lib_skipspace(const char **pptr); +void lib_skipspace(const char **pptr); /* Defined in lib_isbasedigit.c */ -extern bool lib_isbasedigit(int ch, int base, int *value); +bool lib_isbasedigit(int ch, int base, int *value); /* Defined in lib_checkbase.c */ -extern int lib_checkbase(int base, const char **pptr); +int lib_checkbase(int base, const char **pptr); + +/* Defined in lib_expi.c */ + +#ifdef CONFIG_LIBM +double lib_expi(size_t n); +#endif + +/* Defined in lib_libsqrtapprox.c */ + +#ifdef CONFIG_LIBM +float lib_sqrtapprox(float x); +#endif #endif /* __LIB_LIB_INTERNAL_H */ diff --git a/nuttx/lib/math/Kconfig b/nuttx/lib/math/Kconfig index ae2bf31307..c24bfd53f3 100644 --- a/nuttx/lib/math/Kconfig +++ b/nuttx/lib/math/Kconfig @@ -2,3 +2,25 @@ # For a description of the syntax of this configuration file, # see misc/tools/kconfig-language.txt. # + +config LIBM + bool "Math library" + default n + depends on !ARCH_MATH_H + ---help--- + By default, no math library will be provided by NuttX. In this this case, it + is assumed that (1) no math library is required, or (2) you will be using the + math.h header file and the libm library provided by your toolchain. + + This is may be a very good choice is possible because your toolchain may have + have a highly optimized version of libm. + + Another possibility is that you have a custom, architecture-specific math + libary and that the corresponding math.h file resides at arch//include/math.h. + The option is selected via ARCH_MATH_H. If ARCH_MATH_H is selected,then the include/nuttx/math.h + header file will be copied to include/math.h where it can be used by your applications. + + If ARCH_MATH_H is not defined, then this option can be selected to build a generic, + math library built into NuttX. This math library comes from the Rhombus OS and + was written by Nick Johnson. The Rhombus OS math library port was contributed by + Darcy Gong. diff --git a/nuttx/lib/math/Make.defs b/nuttx/lib/math/Make.defs index f656e1a735..8e2e60f12d 100644 --- a/nuttx/lib/math/Make.defs +++ b/nuttx/lib/math/Make.defs @@ -33,17 +33,30 @@ # ############################################################################ -if ($(CONFIG_LIBM),y) +ifeq ($(CONFIG_LIBM),y) # Add the floating point math C files to the build +CSRCS += lib_acosf.c lib_asinf.c lib_atan2f.c lib_atanf.c lib_ceilf.c lib_cosf.c +CSRCS += lib_coshf.c lib_expf.c lib_fabsf.c lib_floorf.c lib_fmodf.c lib_frexpf.c +CSRCS += lib_ldexpf.c lib_logf.c lib_log10f.c lib_log2f.c lib_modff.c lib_powf.c +CSRCS += lib_sinf.c lib_sinhf.c lib_sqrtf.c lib_tanf.c lib_tanhf.c + CSRCS += lib_acos.c lib_asin.c lib_atan.c lib_atan2.c lib_ceil.c lib_cos.c CSRCS += lib_cosh.c lib_exp.c lib_fabs.c lib_floor.c lib_fmod.c lib_frexp.c CRRCS += lib_ldexp.c lib_log.c lib_log10.c lib_log2.c lib_modf.c lib_pow.c CSRCS += lib_sin.c lib_sinh.c lib_sqrt.c lib_tan.c lib_tanh.c +CSRCS += lib_acosl.c lib_asinl.c lib_atan2l.c lib_atanl.c lib_ceill.c lib_cosl.c +CSRCS += lib_coshl.c lib_expl.c lib_fabsl.c lib_floorl.c lib_fmodl.c lib_frexpl.c +CSRCS += lib_ldexpl.c lib_logl.c lib_log10l.c lib_log2l.c lib_modfl.c lib_powl.c +CSRCS += lib_sinl.c lib_sinhl.c lib_sqrtl.c lib_tanl.c lib_tanhl.c + +CSRCS += lib_libexpi.c lib_libsqrtapprox.c + # Add the floating point math directory to the build DEPPATH += --dep-path math VPATH += :math + endif diff --git a/nuttx/lib/math/Makefile b/nuttx/lib/math/Makefile deleted file mode 100644 index 56be0f0abd..0000000000 --- a/nuttx/lib/math/Makefile +++ /dev/null @@ -1,100 +0,0 @@ -############################################################################ -# nuttx/lib/math/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 --include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs - -# NSH Library - -ASRCS = -CSRCS = - -ifeq ($(CONFIG_MATHEXT_LIBRARY),y) -CSRCS += m_cos.c m_log2.c m_fmod.c m_sin.c m_fabs.c m_exp.c m_asin.c m_tan.c \ - m_modf.c m_ldexp.c m_acos.c m_frexp.c m_atan.c m_log.c m_tanh.c m_ceil.c \ - m_sinh.c m_sqrt.c m_pow.c m_cosh.c m_floor.c m_atan2.c m_log10.c -endif - -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 . -VPATH = - -# Build targets - -all: .built -.PHONY: context .depend 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 - -context: - -.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 Make.dep .depend - --include Make.dep - diff --git a/nuttx/lib/math/lib_acos.c b/nuttx/lib/math/lib_acos.c index 83650d132a..4c5aa67c0a 100644 --- a/nuttx/lib/math/lib_acos.c +++ b/nuttx/lib/math/lib_acos.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_acos.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009, 2010 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,19 +22,25 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float acosf(float x) { - return (M_PI_2 - asinf(x)); -} - -double acos(double x) { - return (M_PI_2 - asin(x)); -} - -long double acosl(long double x) { - return (M_PI_2 - asinl(x)); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double acos(double x) +{ + return (M_PI_2 - asin(x)); } +#endif diff --git a/nuttx/lib/math/lib_acosf.c b/nuttx/lib/math/lib_acosf.c new file mode 100644 index 0000000000..e14a73a6ea --- /dev/null +++ b/nuttx/lib/math/lib_acosf.c @@ -0,0 +1,41 @@ +/************************************************************************ + * lib/math/lib_acosf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float acosf(float x) +{ + return (M_PI_2 - asinf(x)); +} diff --git a/nuttx/lib/math/lib_acosl.c b/nuttx/lib/math/lib_acosl.c new file mode 100644 index 0000000000..3b6fa8aa9d --- /dev/null +++ b/nuttx/lib/math/lib_acosl.c @@ -0,0 +1,46 @@ +/************************************************************************ + * lib/math/lib_acos.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double acosl(long double x) +{ + return (M_PI_2 - asinl(x)); +} +#endif diff --git a/nuttx/lib/math/lib_asin.c b/nuttx/lib/math/lib_asin.c index 9d72e8042d..1469d1ed89 100644 --- a/nuttx/lib/math/lib_asin.c +++ b/nuttx/lib/math/lib_asin.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_sin.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,77 +22,48 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include #include -float asinf(float x) { - long double y, y_sin, y_cos; +/************************************************************************ + * Public Functions + ************************************************************************/ - y = 0; +#if CONFIG_HAVE_DOUBLE +double asin(double x) +{ + long double y, y_sin, y_cos; - while (1) { - y_sin = sinf(y); - y_cos = cosf(y); + y = 0; - if (y > M_PI_2 || y < -M_PI_2) { - y = fmodf(y, M_PI); - } + while (1) + { + y_sin = sin(y); + y_cos = cos(y); - if (y_sin + DBL_EPSILON >= x && y_sin - DBL_EPSILON <= x) { - break; - } + if (y > M_PI_2 || y < -M_PI_2) + { + y = fmod(y, M_PI); + } - y = y - (y_sin - x) / y_cos; - } + if (y_sin + DBL_EPSILON >= x && y_sin - DBL_EPSILON <= x) + { + break; + } - return y; + y = y - (y_sin - x) / y_cos; + } + + return y; } - -double asin(double x) { - long double y, y_sin, y_cos; - - y = 0; - - while (1) { - y_sin = sin(y); - y_cos = cos(y); - - if (y > M_PI_2 || y < -M_PI_2) { - y = fmod(y, M_PI); - } - - if (y_sin + DBL_EPSILON >= x && y_sin - DBL_EPSILON <= x) { - break; - } - - y = y - (y_sin - x) / y_cos; - } - - return y; -} - -long double asinl(long double x) { - long double y, y_sin, y_cos; - - y = 0; - - while (1) { - y_sin = sinl(y); - y_cos = cosl(y); - - if (y > M_PI_2 || y < -M_PI_2) { - y = fmodl(y, M_PI); - } - - if (y_sin + LDBL_EPSILON >= x && y_sin - LDBL_EPSILON <= x) { - break; - } - - y = y - (y_sin - x) / y_cos; - } - - return y; -} - +#endif diff --git a/nuttx/lib/math/lib_asinf.c b/nuttx/lib/math/lib_asinf.c new file mode 100644 index 0000000000..17669a9346 --- /dev/null +++ b/nuttx/lib/math/lib_asinf.c @@ -0,0 +1,65 @@ +/************************************************************************ + * lib/math/lib_sinf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float asinf(float x) +{ + long double y, y_sin, y_cos; + + y = 0; + + while (1) + { + y_sin = sinf(y); + y_cos = cosf(y); + + if (y > M_PI_2 || y < -M_PI_2) + { + y = fmodf(y, M_PI); + } + + if (y_sin + FLT_EPSILON >= x && y_sin - FLT_EPSILON <= x) + { + break; + } + + y = y - (y_sin - x) / y_cos; + } + + return y; +} + diff --git a/nuttx/lib/math/lib_asinl.c b/nuttx/lib/math/lib_asinl.c new file mode 100644 index 0000000000..bd1cb70ee9 --- /dev/null +++ b/nuttx/lib/math/lib_asinl.c @@ -0,0 +1,69 @@ +/************************************************************************ + * lib/math/lib_sinl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double asinl(long double x) +{ + long double y, y_sin, y_cos; + + y = 0; + + while (1) + { + y_sin = sinl(y); + y_cos = cosl(y); + + if (y > M_PI_2 || y < -M_PI_2) + { + y = fmodl(y, M_PI); + } + + if (y_sin + LDBL_EPSILON >= x && y_sin - LDBL_EPSILON <= x) + { + break; + } + + y = y - (y_sin - x) / y_cos; + } + + return y; +} +#endif diff --git a/nuttx/lib/math/lib_atan.c b/nuttx/lib/math/lib_atan.c index e909e5a8e3..2b7f6e3a6f 100644 --- a/nuttx/lib/math/lib_atan.c +++ b/nuttx/lib/math/lib_atan.c @@ -1,5 +1,15 @@ -/* - * Copyright (C) 2009-2011 Nick Johnson +/************************************************************************ + * lib/math/lib_atan.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any * purpose with or without fee is hereby granted, provided that the above @@ -12,21 +22,27 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include #include #include -float atanf(float x) { - return asinf(x / sqrtf(x * x + 1)); -} +/************************************************************************ + * Public Functions + ************************************************************************/ -double atan(double x) { - return asin(x / sqrt(x * x + 1)); -} - -long double atanl(long double x) { - return asinl(x / sqrtl(x * x + 1)); +#if CONFIG_HAVE_DOUBLE +double atan(double x) +{ + return asin(x / sqrt(x * x + 1)); } +#endif diff --git a/nuttx/lib/math/lib_atan2.c b/nuttx/lib/math/lib_atan2.c index b4ded0c168..bfb33657c6 100644 --- a/nuttx/lib/math/lib_atan2.c +++ b/nuttx/lib/math/lib_atan2.c @@ -1,5 +1,15 @@ -/* - * Copyright (C) 2009, 2010 Nick Johnson +/************************************************************************ + * lib/math/lib_atan2.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any * purpose with or without fee is hereby granted, provided that the above @@ -12,109 +22,65 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float atan2f(float y, float x) { - - if (y == 0.0) { - if (x >= 0.0) { - return 0.0; - } - else { - return M_PI; - } - } - else if (y > 0.0) { - if (x == 0.0) { - return M_PI_2; - } - else if (x > 0.0) { - return atanf(y / x); - } - else { - return M_PI - atanf(y / x); - } - } - else { - if (x == 0.0) { - return M_PI + M_PI_2; - } - else if (x > 0.0) { - return 2 * M_PI - atanf(y / x); - } - else { - return M_PI + atanf(y / x); - } - } -} - -double atan2(double y, double x) { - - if (y == 0.0) { - if (x >= 0.0) { - return 0.0; - } - else { - return M_PI; - } - } - else if (y > 0.0) { - if (x == 0.0) { - return M_PI_2; - } - else if (x > 0.0) { - return atan(y / x); - } - else { - return M_PI - atan(y / x); - } - } - else { - if (x == 0.0) { - return M_PI + M_PI_2; - } - else if (x > 0.0) { - return 2 * M_PI - atan(y / x); - } - else { - return M_PI + atan(y / x); - } - } -} - -long double atan2l(long double y, long double x) { - - if (y == 0.0) { - if (x >= 0.0) { - return 0.0; - } - else { - return M_PI; - } - } - else if (y > 0.0) { - if (x == 0.0) { - return M_PI_2; - } - else if (x > 0.0) { - return atanl(y / x); - } - else { - return M_PI - atanl(y / x); - } - } - else { - if (x == 0.0) { - return M_PI + M_PI_2; - } - else if (x > 0.0) { - return 2 * M_PI - atanl(y / x); - } - else { - return M_PI + atanl(y / x); - } - } +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double atan2(double y, double x) +{ + if (y == 0.0) + { + if (x >= 0.0) + { + return 0.0; + } + else + { + return M_PI; + } + } + else if (y > 0.0) + { + if (x == 0.0) + { + return M_PI_2; + } + else if (x > 0.0) + { + return atan(y / x); + } + else + { + return M_PI - atan(y / x); + } + } + else + { + if (x == 0.0) + { + return M_PI + M_PI_2; + } + else if (x > 0.0) + { + return 2 * M_PI - atan(y / x); + } + else + { + return M_PI + atan(y / x); + } + } } +#endif diff --git a/nuttx/lib/math/lib_atan2f.c b/nuttx/lib/math/lib_atan2f.c new file mode 100644 index 0000000000..a60d32c655 --- /dev/null +++ b/nuttx/lib/math/lib_atan2f.c @@ -0,0 +1,81 @@ +/************************************************************************ + * lib/math/lib_atan2f.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float atan2f(float y, float x) +{ + if (y == 0.0) + { + if (x >= 0.0) + { + return 0.0; + } + else + { + return M_PI; + } + } + else if (y > 0.0) + { + if (x == 0.0) + { + return M_PI_2; + } + else if (x > 0.0) + { + return atanf(y / x); + } + else + { + return M_PI - atanf(y / x); + } + } + else + { + if (x == 0.0) + { + return M_PI + M_PI_2; + } + else if (x > 0.0) + { + return 2 * M_PI - atanf(y / x); + } + else + { + return M_PI + atanf(y / x); + } + } +} diff --git a/nuttx/lib/math/lib_atan2l.c b/nuttx/lib/math/lib_atan2l.c new file mode 100644 index 0000000000..d7891b6286 --- /dev/null +++ b/nuttx/lib/math/lib_atan2l.c @@ -0,0 +1,87 @@ +/************************************************************************ + * lib/math/lib_atan2l.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double atan2l(long double y, long double x) +{ + + if (y == 0.0) + { + if (x >= 0.0) + { + return 0.0; + } + else + { + return M_PI; + } + } + else if (y > 0.0) + { + if (x == 0.0) + { + return M_PI_2; + } + else if (x > 0.0) + { + return atanl(y / x); + } + else + { + return M_PI - atanl(y / x); + } + } + else + { + if (x == 0.0) + { + return M_PI + M_PI_2; + } + else if (x > 0.0) + { + return 2 * M_PI - atanl(y / x); + } + else + { + return M_PI + atanl(y / x); + } + } +} +#endif diff --git a/nuttx/lib/math/lib_atanf.c b/nuttx/lib/math/lib_atanf.c new file mode 100644 index 0000000000..7c540dd163 --- /dev/null +++ b/nuttx/lib/math/lib_atanf.c @@ -0,0 +1,43 @@ +/************************************************************************ + * lib/math/lib_atanf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float atanf(float x) +{ + return asinf(x / sqrtf(x * x + 1)); +} diff --git a/nuttx/lib/math/lib_atanl.c b/nuttx/lib/math/lib_atanl.c new file mode 100644 index 0000000000..c8fa239f9d --- /dev/null +++ b/nuttx/lib/math/lib_atanl.c @@ -0,0 +1,48 @@ +/************************************************************************ + * lib/math/lib_atanl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include +#include +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double atanl(long double x) +{ + return asinl(x / sqrtl(x * x + 1)); +} +#endif diff --git a/nuttx/lib/math/lib_ceil.c b/nuttx/lib/math/lib_ceil.c index c2447c0b85..12e223128c 100644 --- a/nuttx/lib/math/lib_ceil.c +++ b/nuttx/lib/math/lib_ceil.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_ceil.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,26 +22,31 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float ceilf(float x) { - modff(x, &x); - if (x > 0.0) x += 1.0; - return x; +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double ceil(double x) +{ + modf(x, &x); + if (x > 0.0) + { + x += 1.0; + } + + return x; } - -double ceil(double x) { - modf(x, &x); - if (x > 0.0) x += 1.0; - return x; -} - -long double ceill(long double x) { - modfl(x, &x); - if (x > 0.0) x += 1.0; - return x; -} - +#endif diff --git a/nuttx/lib/math/lib_ceilf.c b/nuttx/lib/math/lib_ceilf.c new file mode 100644 index 0000000000..0721ffc22a --- /dev/null +++ b/nuttx/lib/math/lib_ceilf.c @@ -0,0 +1,47 @@ +/************************************************************************ + * lib/math/lib_ceilf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float ceilf(float x) +{ + modff(x, &x); + if (x > 0.0) + { + x += 1.0; + } + + return x; +} diff --git a/nuttx/lib/math/lib_ceill.c b/nuttx/lib/math/lib_ceill.c new file mode 100644 index 0000000000..5a0010aa21 --- /dev/null +++ b/nuttx/lib/math/lib_ceill.c @@ -0,0 +1,52 @@ +/************************************************************************ + * lib/math/lib_ceil;.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double ceill(long double x) +{ + modfl(x, &x); + if (x > 0.0) + { + x += 1.0; + } + + return x; +} +#endif diff --git a/nuttx/lib/math/lib_cos.c b/nuttx/lib/math/lib_cos.c index f8732b041a..09808bd9f7 100644 --- a/nuttx/lib/math/lib_cos.c +++ b/nuttx/lib/math/lib_cos.c @@ -1,5 +1,15 @@ -/* - * Copyright (C) 2009, 2010 Nick Johnson +/************************************************************************ + * lib/math/lib_cos.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any * purpose with or without fee is hereby granted, provided that the above @@ -12,20 +22,25 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float cosf(float x) { - return sinf(x + M_PI_2); -} - -double cos(double x) { - return sin(x + M_PI_2); -} - -long double cosl(long double x) { - return sinl(x + M_PI_2); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double cos(double x) +{ + return sin(x + M_PI_2); } +#endif diff --git a/nuttx/lib/math/lib_cosf.c b/nuttx/lib/math/lib_cosf.c new file mode 100644 index 0000000000..093a8a0024 --- /dev/null +++ b/nuttx/lib/math/lib_cosf.c @@ -0,0 +1,41 @@ +/************************************************************************ + * lib/math/lib_cosf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float cosf(float x) +{ + return sinf(x + M_PI_2); +} diff --git a/nuttx/lib/math/lib_cosh.c b/nuttx/lib/math/lib_cosh.c index 1069903112..de4f42d7a1 100644 --- a/nuttx/lib/math/lib_cosh.c +++ b/nuttx/lib/math/lib_cosh.c @@ -1,5 +1,15 @@ -/* - * Copyright (C) 2009, 2010 Nick Johnson +/************************************************************************ + * lib/math/lib_cosh.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any * purpose with or without fee is hereby granted, provided that the above @@ -12,22 +22,26 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float coshf(float x) { - x = expf(x); - return ((x + (1.0 / x)) / 2.0); -} - -double cosh(double x) { - x = exp(x); - return ((x + (1.0 / x)) / 2.0); -} - -long double coshl(long double x) { - x = expl(x); - return ((x + (1.0 / x)) / 2.0); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double cosh(double x) +{ + x = exp(x); + return ((x + (1.0 / x)) / 2.0); } +#endif diff --git a/nuttx/lib/math/lib_coshf.c b/nuttx/lib/math/lib_coshf.c new file mode 100644 index 0000000000..d5e5ea14de --- /dev/null +++ b/nuttx/lib/math/lib_coshf.c @@ -0,0 +1,42 @@ +/************************************************************************ + * lib/math/lib_coshf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float coshf(float x) +{ + x = expf(x); + return ((x + (1.0 / x)) / 2.0); +} diff --git a/nuttx/lib/math/lib_coshl.c b/nuttx/lib/math/lib_coshl.c new file mode 100644 index 0000000000..d439127453 --- /dev/null +++ b/nuttx/lib/math/lib_coshl.c @@ -0,0 +1,47 @@ +/************************************************************************ + * lib/math/lib_coshl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double coshl(long double x) +{ + x = expl(x); + return ((x + (1.0 / x)) / 2.0); +} +#endif diff --git a/nuttx/lib/math/lib_cosl.c b/nuttx/lib/math/lib_cosl.c new file mode 100644 index 0000000000..5b73218127 --- /dev/null +++ b/nuttx/lib/math/lib_cosl.c @@ -0,0 +1,46 @@ +/************************************************************************ + * lib/math/lib_cosl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double cosl(long double x) +{ + return sinl(x + M_PI_2); +} +#endif diff --git a/nuttx/lib/math/lib_exp.c b/nuttx/lib/math/lib_exp.c index a70cb10e7c..5b54dbaac1 100644 --- a/nuttx/lib/math/lib_exp.c +++ b/nuttx/lib/math/lib_exp.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_exp.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,242 +22,104 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include -#include -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -#define M_E2 (M_E * M_E) -#define M_E4 (M_E2 * M_E2) -#define M_E8 (M_E4 * M_E4) -#define M_E16 (M_E8 * M_E8) -#define M_E32 (M_E16 * M_E16) -#define M_E64 (M_E32 * M_E32) -#define M_E128 (M_E64 * M_E64) -#define M_E256 (M_E128 * M_E128) -#define M_E512 (M_E256 * M_E256) -#define M_E1024 (M_E512 * M_E512) +#include +#include -static double _expi_square_tbl[11] = { - M_E, // e^1 - M_E2, // e^2 - M_E4, // e^4 - M_E8, // e^8 - M_E16, // e^16 - M_E32, // e^32 - M_E64, // e^64 - M_E128, // e^128 - M_E256, // e^256 - M_E512, // e^512 - M_E1024, // e^1024 +#include + +#include "lib_internal.h" + +#if CONFIG_HAVE_DOUBLE + +/************************************************************************ + * Private Data + ************************************************************************/ + +static double _dbl_inv_fact[] = +{ + 1.0 / 1.0, // 1 / 0! + 1.0 / 1.0, // 1 / 1! + 1.0 / 2.0, // 1 / 2! + 1.0 / 6.0, // 1 / 3! + 1.0 / 24.0, // 1 / 4! + 1.0 / 120.0, // 1 / 5! + 1.0 / 720.0, // 1 / 6! + 1.0 / 5040.0, // 1 / 7! + 1.0 / 40320.0, // 1 / 8! + 1.0 / 362880.0, // 1 / 9! + 1.0 / 3628800.0, // 1 / 10! + 1.0 / 39916800.0, // 1 / 11! + 1.0 / 479001600.0, // 1 / 12! + 1.0 / 6227020800.0, // 1 / 13! + 1.0 / 87178291200.0, // 1 / 14! + 1.0 / 1307674368000.0, // 1 / 15! + 1.0 / 20922789888000.0, // 1 / 16! + 1.0 / 355687428096000.0, // 1 / 17! + 1.0 / 6402373705728000.0, // 1 / 18! }; -static double _expi(size_t n) { - size_t i; - double val; +/************************************************************************ + * Public Functions + ************************************************************************/ - if (n > 1024) { - return INFINITY; - } +double exp(double x) +{ + size_t int_part; + bool invert; + double value; + double x0; + size_t i; - val = 1.0; + if (x == 0) + { + return 1; + } + else if (x < 0) + { + invert = true; + x = -x; + } + else + { + invert = false; + } - for (i = 0; n; i++) { - if (n & (1 << i)) { - n &= ~(1 << i); - val *= _expi_square_tbl[i]; - } - } + /* Extract integer component */ - return val; -} - -static float _flt_inv_fact[] = { - 1.0 / 1.0, // 1/0! - 1.0 / 1.0, // 1/1! - 1.0 / 2.0, // 1/2! - 1.0 / 6.0, // 1/3! - 1.0 / 24.0, // 1/4! - 1.0 / 120.0, // 1/5! - 1.0 / 720.0, // 1/6! - 1.0 / 5040.0, // 1/7! - 1.0 / 40320.0, // 1/8! - 1.0 / 362880.0, // 1/9! - 1.0 / 3628800.0, // 1/10! -}; - -float expf(float x) { - size_t int_part; - bool invert; - float value; - float x0; - size_t i; - - if (x == 0) { - return 1; - } - else if (x < 0) { - invert = true; - x = -x; - } - else { - invert = false; - } - - /* extract integer component */ - int_part = (size_t) x; - - /* set x to fractional component */ - x -= (float) int_part; - - /* perform Taylor series approximation with eleven terms */ - value = 0.0; - x0 = 1.0; - for (i = 0; i < 10; i++) { - value += x0 * _flt_inv_fact[i]; - x0 *= x; - } - - /* multiply by exp of the integer component */ - value *= _expi(int_part); - - if (invert) { - return (1.0 / value); - } - else { - return value; - } -} - -static double _dbl_inv_fact[] = { - 1.0 / 1.0, // 1 / 0! - 1.0 / 1.0, // 1 / 1! - 1.0 / 2.0, // 1 / 2! - 1.0 / 6.0, // 1 / 3! - 1.0 / 24.0, // 1 / 4! - 1.0 / 120.0, // 1 / 5! - 1.0 / 720.0, // 1 / 6! - 1.0 / 5040.0, // 1 / 7! - 1.0 / 40320.0, // 1 / 8! - 1.0 / 362880.0, // 1 / 9! - 1.0 / 3628800.0, // 1 / 10! - 1.0 / 39916800.0, // 1 / 11! - 1.0 / 479001600.0, // 1 / 12! - 1.0 / 6227020800.0, // 1 / 13! - 1.0 / 87178291200.0, // 1 / 14! - 1.0 / 1307674368000.0, // 1 / 15! - 1.0 / 20922789888000.0, // 1 / 16! - 1.0 / 355687428096000.0, // 1 / 17! - 1.0 / 6402373705728000.0, // 1 / 18! -}; - -double exp(double x) { - size_t int_part; - bool invert; - double value; - double x0; - size_t i; - - if (x == 0) { - return 1; - } - else if (x < 0) { - invert = true; - x = -x; - } - else { - invert = false; - } - - /* extract integer component */ - int_part = (size_t) x; - - /* set x to fractional component */ - x -= (double) int_part; - - /* perform Taylor series approximation with nineteen terms */ - value = 0.0; - x0 = 1.0; - for (i = 0; i < 19; i++) { - value += x0 * _dbl_inv_fact[i]; - x0 *= x; - } - - /* multiply by exp of the integer component */ - value *= _expi(int_part); - - if (invert) { - return (1.0 / value); - } - else { - return value; - } -} - -static long double _ldbl_inv_fact[] = { - 1.0 / 1.0, // 1 / 0! - 1.0 / 1.0, // 1 / 1! - 1.0 / 2.0, // 1 / 2! - 1.0 / 6.0, // 1 / 3! - 1.0 / 24.0, // 1 / 4! - 1.0 / 120.0, // 1 / 5! - 1.0 / 720.0, // 1 / 6! - 1.0 / 5040.0, // 1 / 7! - 1.0 / 40320.0, // 1 / 8! - 1.0 / 362880.0, // 1 / 9! - 1.0 / 3628800.0, // 1 / 10! - 1.0 / 39916800.0, // 1 / 11! - 1.0 / 479001600.0, // 1 / 12! - 1.0 / 6227020800.0, // 1 / 13! - 1.0 / 87178291200.0, // 1 / 14! - 1.0 / 1307674368000.0, // 1 / 15! - 1.0 / 20922789888000.0, // 1 / 16! - 1.0 / 355687428096000.0, // 1 / 17! - 1.0 / 6402373705728000.0, // 1 / 18! -}; - -long double expl(long double x) { - size_t int_part; - bool invert; - long double value; - long double x0; - size_t i; - - if (x == 0) { - return 1; - } - else if (x < 0) { - invert = true; - x = -x; - } - else { - invert = false; - } - - /* extract integer component */ - int_part = (size_t) x; - - /* set x to fractional component */ - x -= (long double) int_part; - - /* perform Taylor series approximation with nineteen terms */ - value = 0.0; - x0 = 1.0; - for (i = 0; i < 19; i++) { - value += x0 * _ldbl_inv_fact[i]; - x0 *= x; - } - - /* multiply by exp of the integer component */ - value *= _expi(int_part); - - if (invert) { - return (1.0 / value); - } - else { - return value; - } + int_part = (size_t) x; + + /* Set x to fractional component */ + + x -= (double)int_part; + + /* Perform Taylor series approximation with nineteen terms */ + + value = 0.0; + x0 = 1.0; + for (i = 0; i < 19; i++) + { + value += x0 * _dbl_inv_fact[i]; + x0 *= x; + } + + /* Multiply by exp of the integer component */ + + value *= lib_expi(int_part); + + if (invert) + { + return (1.0 / value); + } + else + { + return value; + } } +#endif diff --git a/nuttx/lib/math/lib_expf.c b/nuttx/lib/math/lib_expf.c new file mode 100644 index 0000000000..eac4641c67 --- /dev/null +++ b/nuttx/lib/math/lib_expf.c @@ -0,0 +1,112 @@ +/************************************************************************ + * lib/math/lib_expf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include "lib_internal.h" + +/************************************************************************ + * Private Data + ************************************************************************/ + +static float _flt_inv_fact[] = +{ + 1.0 / 1.0, // 1/0! + 1.0 / 1.0, // 1/1! + 1.0 / 2.0, // 1/2! + 1.0 / 6.0, // 1/3! + 1.0 / 24.0, // 1/4! + 1.0 / 120.0, // 1/5! + 1.0 / 720.0, // 1/6! + 1.0 / 5040.0, // 1/7! + 1.0 / 40320.0, // 1/8! + 1.0 / 362880.0, // 1/9! + 1.0 / 3628800.0, // 1/10! +}; + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float expf(float x) +{ + size_t int_part; + bool invert; + float value; + float x0; + size_t i; + + if (x == 0) + { + return 1; + } + else if (x < 0) + { + invert = true; + x = -x; + } + else + { + invert = false; + } + + /* Extract integer component */ + + int_part = (size_t) x; + + /* set x to fractional component */ + + x -= (float)int_part; + + /* Perform Taylor series approximation with eleven terms */ + + value = 0.0; + x0 = 1.0; + for (i = 0; i < 10; i++) + { + value += x0 * _flt_inv_fact[i]; + x0 *= x; + } + + /* Multiply by exp of the integer component */ + + value *= lib_expi(int_part); + + if (invert) + { + return (1.0 / value); + } + else + { + return value; + } +} diff --git a/nuttx/lib/math/lib_expl.c b/nuttx/lib/math/lib_expl.c new file mode 100644 index 0000000000..cd5e6a500c --- /dev/null +++ b/nuttx/lib/math/lib_expl.c @@ -0,0 +1,126 @@ +/************************************************************************ + * lib/math/lib_expl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include +#include + +#include "lib_internal.h" + +#if CONFIG_HAVE_LONG_DOUBLE + +/************************************************************************ + * Private Data + ************************************************************************/ + +static long double _ldbl_inv_fact[] = +{ + 1.0 / 1.0, // 1 / 0! + 1.0 / 1.0, // 1 / 1! + 1.0 / 2.0, // 1 / 2! + 1.0 / 6.0, // 1 / 3! + 1.0 / 24.0, // 1 / 4! + 1.0 / 120.0, // 1 / 5! + 1.0 / 720.0, // 1 / 6! + 1.0 / 5040.0, // 1 / 7! + 1.0 / 40320.0, // 1 / 8! + 1.0 / 362880.0, // 1 / 9! + 1.0 / 3628800.0, // 1 / 10! + 1.0 / 39916800.0, // 1 / 11! + 1.0 / 479001600.0, // 1 / 12! + 1.0 / 6227020800.0, // 1 / 13! + 1.0 / 87178291200.0, // 1 / 14! + 1.0 / 1307674368000.0, // 1 / 15! + 1.0 / 20922789888000.0, // 1 / 16! + 1.0 / 355687428096000.0, // 1 / 17! + 1.0 / 6402373705728000.0, // 1 / 18! +}; + +/************************************************************************ + * Public Functions + ************************************************************************/ + +long double expl(long double x) +{ + size_t int_part; + bool invert; + long double value; + long double x0; + size_t i; + + if (x == 0) + { + return 1; + } + else if (x < 0) + { + invert = true; + x = -x; + } + else + { + invert = false; + } + + /* Extract integer component */ + + int_part = (size_t) x; + + /* Set x to fractional component */ + + x -= (long double)int_part; + + /* Perform Taylor series approximation with nineteen terms */ + + value = 0.0; + x0 = 1.0; + for (i = 0; i < 19; i++) + { + value += x0 * _ldbl_inv_fact[i]; + x0 *= x; + } + + /* Multiply by exp of the integer component */ + + value *= lib_expi(int_part); + + if (invert) + { + return (1.0 / value); + } + else + { + return value; + } +} +#endif diff --git a/nuttx/lib/math/lib_fabs.c b/nuttx/lib/math/lib_fabs.c index f479aa123d..a635b0b41d 100644 --- a/nuttx/lib/math/lib_fabs.c +++ b/nuttx/lib/math/lib_fabs.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_fabs.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009, 2010 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,19 +22,25 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float fabsf(float x) { - return ((x < 0) ? -x : x); -} - -double fabs(double x) { - return ((x < 0) ? -x : x); -} - -long double fabsl(long double x) { - return ((x < 0) ? -x : x); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double fabs(double x) +{ + return ((x < 0) ? -x : x); } +#endif diff --git a/nuttx/lib/math/lib_fabsf.c b/nuttx/lib/math/lib_fabsf.c new file mode 100644 index 0000000000..0ea186ca03 --- /dev/null +++ b/nuttx/lib/math/lib_fabsf.c @@ -0,0 +1,41 @@ +/************************************************************************ + * lib/math/lib_fabsf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float fabsf(float x) +{ + return ((x < 0) ? -x : x); +} diff --git a/nuttx/lib/math/lib_fabsl.c b/nuttx/lib/math/lib_fabsl.c new file mode 100644 index 0000000000..f1e37e3f1a --- /dev/null +++ b/nuttx/lib/math/lib_fabsl.c @@ -0,0 +1,46 @@ +/************************************************************************ + * lib/math/lib_fabsl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double fabsl(long double x) +{ + return ((x < 0) ? -x : x); +} +#endif diff --git a/nuttx/lib/math/lib_floor.c b/nuttx/lib/math/lib_floor.c index a6979ac8a1..895b9a5034 100644 --- a/nuttx/lib/math/lib_floor.c +++ b/nuttx/lib/math/lib_floor.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_floor.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,26 +22,31 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float floorf(float x) { - modff(x, &x); - if (x < 0.0) x -= 1.0; - return x; +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double floor(double x) +{ + modf(x, &x); + if (x < 0.0) + { + x -= 1.0; + } + + return x; } - -double floor(double x) { - modf(x, &x); - if (x < 0.0) x -= 1.0; - return x; -} - -long double floorl(long double x) { - modfl(x, &x); - if (x < 0.0) x -= 1.0; - return x; -} - +#endif diff --git a/nuttx/lib/math/lib_floorf.c b/nuttx/lib/math/lib_floorf.c new file mode 100644 index 0000000000..2becb5fac9 --- /dev/null +++ b/nuttx/lib/math/lib_floorf.c @@ -0,0 +1,47 @@ +/************************************************************************ + * lib/math/lib_floorf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float floorf(float x) +{ + modff(x, &x); + if (x < 0.0) + { + x -= 1.0; + } + + return x; +} diff --git a/nuttx/lib/math/lib_floorl.c b/nuttx/lib/math/lib_floorl.c new file mode 100644 index 0000000000..2c70112973 --- /dev/null +++ b/nuttx/lib/math/lib_floorl.c @@ -0,0 +1,52 @@ +/************************************************************************ + * lib/math/lib_floorl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double floorl(long double x) +{ + modfl(x, &x); + if (x < 0.0) + { + x -= 1.0; + } + + return x; +} +#endif diff --git a/nuttx/lib/math/lib_fmod.c b/nuttx/lib/math/lib_fmod.c index 532fa33608..c55151d750 100644 --- a/nuttx/lib/math/lib_fmod.c +++ b/nuttx/lib/math/lib_fmod.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_fmod.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,56 +22,31 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -/* If GCC/CLang builtins are available, use them */ -#ifdef __GNUC__ +#include +#include -float fmodf(float x, float div) { - return __builtin_fmodf(x, div); +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double fmod(double x, double div) +{ + double n0; + + x /= div; + x = modf(x, &n0); + x *= div; + + return x; } - -double fmod(double x, double div) { - return __builtin_fmod(x, div); -} - -long double fmodl(long double x, long double div) { - return __builtin_fmodl(x, div); -} - -#else - -float fmodf(float x, float div) { - float n0; - - x /= div; - x = modff(x, &n0); - x *= div; - - return x; -} - -double fmod(double x, double div) { - double n0; - - x /= div; - x = modf(x, &n0); - x *= div; - - return x; -} - -long double fmodl(long double x, long double div) { - long double n0; - - x /= div; - x = modfl(x, &n0); - x *= div; - - return x; -} - #endif diff --git a/nuttx/lib/math/lib_fmodf.c b/nuttx/lib/math/lib_fmodf.c new file mode 100644 index 0000000000..085786f172 --- /dev/null +++ b/nuttx/lib/math/lib_fmodf.c @@ -0,0 +1,47 @@ +/************************************************************************ + * lib/math/lib_fmodf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float fmodf(float x, float div) +{ + float n0; + + x /= div; + x = modff(x, &n0); + x *= div; + + return x; +} diff --git a/nuttx/lib/math/lib_fmodl.c b/nuttx/lib/math/lib_fmodl.c new file mode 100644 index 0000000000..c9b3ca7847 --- /dev/null +++ b/nuttx/lib/math/lib_fmodl.c @@ -0,0 +1,52 @@ +/************************************************************************ + * lib/math/lib_fmodl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double fmodl(long double x, long double div) +{ + long double n0; + + x /= div; + x = modfl(x, &n0); + x *= div; + + return x; +} +#endif diff --git a/nuttx/lib/math/lib_frexp.c b/nuttx/lib/math/lib_frexp.c index 102609dbe8..6de67f8b5f 100644 --- a/nuttx/lib/math/lib_frexp.c +++ b/nuttx/lib/math/lib_frexp.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_frexp.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,23 +22,26 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float frexpf(float x, int *exp) { - *exp = (int) ceilf(log2f(x)); - return x / ldexpf(1.0, *exp); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double frexp(double x, int *exponent) +{ + *exponent = (int)ceil(log2(x)); + return x / ldexp(1.0, *exponent); } - -double frexp(double x, int *exp) { - *exp = (int) ceil(log2(x)); - return x / ldexp(1.0, *exp); -} - -long double frexpl(long double x, int *exp) { - *exp = (int) ceill(log2(x)); - return x / ldexpl(1.0, *exp); -} - +#endif diff --git a/nuttx/lib/math/lib_frexpf.c b/nuttx/lib/math/lib_frexpf.c new file mode 100644 index 0000000000..1fb0df3d89 --- /dev/null +++ b/nuttx/lib/math/lib_frexpf.c @@ -0,0 +1,42 @@ +/************************************************************************ + * lib/math/lib_frexpf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float frexpf(float x, int *exponent) +{ + *exponent = (int)ceilf(log2f(x)); + return x / ldexpf(1.0, *exponent); +} diff --git a/nuttx/lib/math/lib_frexpl.c b/nuttx/lib/math/lib_frexpl.c new file mode 100644 index 0000000000..7a0d3c408b --- /dev/null +++ b/nuttx/lib/math/lib_frexpl.c @@ -0,0 +1,47 @@ +/************************************************************************ + * lib/math/lib_frexpl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double frexpl(long double x, int *exponent) +{ + *exponent = (int)ceill(log2(x)); + return x / ldexpl(1.0, *exponent); +} +#endif diff --git a/nuttx/lib/math/lib_ldexp.c b/nuttx/lib/math/lib_ldexp.c index 2ca79221a0..ca428dc074 100644 --- a/nuttx/lib/math/lib_ldexp.c +++ b/nuttx/lib/math/lib_ldexp.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_ldexp.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,20 +22,25 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float ldexpf(float x, int n) { - return (x * powf(2.0, (float) n)); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double ldexp(double x, int n) +{ + return (x * pow(2.0, (double)n)); } - -double ldexp(double x, int n) { - return (x * pow(2.0, (double) n)); -} - -long double ldexpl(long double x, int n) { - return (x * powl(2.0, (long double) n)); -} - +#endif diff --git a/nuttx/lib/math/lib_ldexpf.c b/nuttx/lib/math/lib_ldexpf.c new file mode 100644 index 0000000000..c61d633d5c --- /dev/null +++ b/nuttx/lib/math/lib_ldexpf.c @@ -0,0 +1,41 @@ +/************************************************************************ + * lib/math/lib_ldexpf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float ldexpf(float x, int n) +{ + return (x * powf(2.0, (float)n)); +} diff --git a/nuttx/lib/math/lib_ldexpl.c b/nuttx/lib/math/lib_ldexpl.c new file mode 100644 index 0000000000..0f77bff111 --- /dev/null +++ b/nuttx/lib/math/lib_ldexpl.c @@ -0,0 +1,46 @@ +/************************************************************************ + * lib/math/lib_ldexpl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double ldexpl(long double x, int n) +{ + return (x * powl(2.0, (long double)n)); +} +#endif diff --git a/nuttx/lib/math/lib_libexpi.c b/nuttx/lib/math/lib_libexpi.c new file mode 100644 index 0000000000..d2bb971a21 --- /dev/null +++ b/nuttx/lib/math/lib_libexpi.c @@ -0,0 +1,103 @@ +/************************************************************************ + * lib/math/lib_libexpi.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +#define M_E2 (M_E * M_E) +#define M_E4 (M_E2 * M_E2) +#define M_E8 (M_E4 * M_E4) +#define M_E16 (M_E8 * M_E8) +#define M_E32 (M_E16 * M_E16) +#define M_E64 (M_E32 * M_E32) +#define M_E128 (M_E64 * M_E64) +#define M_E256 (M_E128 * M_E128) +#define M_E512 (M_E256 * M_E256) +#define M_E1024 (M_E512 * M_E512) + +/************************************************************************ + * Private Data + ************************************************************************/ + +static double _expi_square_tbl[11] = +{ + M_E, // e^1 + M_E2, // e^2 + M_E4, // e^4 + M_E8, // e^8 + M_E16, // e^16 + M_E32, // e^32 + M_E64, // e^64 + M_E128, // e^128 + M_E256, // e^256 + M_E512, // e^512 + M_E1024, // e^1024 +}; + +/************************************************************************ + * Public Functions + ************************************************************************/ + +static double lib_expi(size_t n) +{ + size_t i; + double val; + + if (n > 1024) + { + return INFINITY; + } + + val = 1.0; + + for (i = 0; n; i++) + { + if (n & (1 << i)) + { + n &= ~(1 << i); + val *= _expi_square_tbl[i]; + } + } + + return val; +} + diff --git a/nuttx/lib/math/lib_libsqrtapprox.c b/nuttx/lib/math/lib_libsqrtapprox.c new file mode 100644 index 0000000000..5c556c3a0e --- /dev/null +++ b/nuttx/lib/math/lib_libsqrtapprox.c @@ -0,0 +1,50 @@ +/************************************************************************ + * lib/math/lib_libsqrtapprox.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float lib_sqrtapprox(float x) +{ + int32_t i; + + /* Floats + bit manipulation = +inf fun! */ + + i = *((int32_t *) & x); + i = 0x1fc00000 + (i >> 1); + x = *((float *)&i); + + return x; +} diff --git a/nuttx/lib/math/lib_log.c b/nuttx/lib/math/lib_log.c index 62af0368aa..4dd51e87ce 100644 --- a/nuttx/lib/math/lib_log.c +++ b/nuttx/lib/math/lib_log.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_log.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009, 2010 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,102 +22,61 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include #include -float logf(float x) { - float y, y_old, ey, epsilon; +/************************************************************************ + * Public Functions + ************************************************************************/ - y = 0.0; - y_old = 1.0; - epsilon = FLT_EPSILON; +#if CONFIG_HAVE_DOUBLE +double log(double x) +{ + double y, y_old, ey, epsilon; - while (y > y_old + epsilon || y < y_old - epsilon) { - y_old = y; - ey = exp(y); - y -= (ey - x) / ey; + y = 0.0; + y_old = 1.0; + epsilon = DBL_EPSILON; - if (y > 700.0) { - y = 700.0; - } - if (y < -700.0) { - y = -700.0; - } + while (y > y_old + epsilon || y < y_old - epsilon) + { + y_old = y; + ey = exp(y); + y -= (ey - x) / ey; - epsilon = (fabs(y) > 1.0) ? fabs(y) * FLT_EPSILON : FLT_EPSILON; - } + if (y > 700.0) + { + y = 700.0; + } - if (y == 700.0) { - return INFINITY; - } - if (y == -700.0) { - return INFINITY; - } + if (y < -700.0) + { + y = -700.0; + } - return y; + epsilon = (fabs(y) > 1.0) ? fabs(y) * DBL_EPSILON : DBL_EPSILON; + } + + if (y == 700.0) + { + return INFINITY; + } + + if (y == -700.0) + { + return INFINITY; + } + + return y; } - -double log(double x) { - double y, y_old, ey, epsilon; - - y = 0.0; - y_old = 1.0; - epsilon = DBL_EPSILON; - - while (y > y_old + epsilon || y < y_old - epsilon) { - y_old = y; - ey = exp(y); - y -= (ey - x) / ey; - - if (y > 700.0) { - y = 700.0; - } - if (y < -700.0) { - y = -700.0; - } - - epsilon = (fabs(y) > 1.0) ? fabs(y) * DBL_EPSILON : DBL_EPSILON; - } - - if (y == 700.0) { - return INFINITY; - } - if (y == -700.0) { - return INFINITY; - } - - return y; -} - -long double logl(long double x) { - long double y, y_old, ey, epsilon; - - y = 0.0; - y_old = 1.0; - epsilon = 1e-6; //fixme - - while (y > y_old + epsilon || y < y_old - epsilon) { - y_old = y; - ey = expl(y); - y -= (ey - x) / ey; - - if (y > 700.0) { - y = 700.0; - } - if (y < -700.0) { - y = -700.0; - } - } - - if (y == 700.0) { - return INFINITY; - } - if (y == -700.0) { - return INFINITY; - } - - return y; -} - +#endif diff --git a/nuttx/lib/math/lib_log10.c b/nuttx/lib/math/lib_log10.c index 855480ad6c..a6534407e1 100644 --- a/nuttx/lib/math/lib_log10.c +++ b/nuttx/lib/math/lib_log10.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_log10.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009, 2010 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,19 +22,25 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float log10f(float x) { - return (logf(x) / M_LN10); -} - -double log10(double x) { - return (log(x) / M_LN10); -} - -long double log10l(long double x) { - return (logl(x) / M_LN10); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double log10(double x) +{ + return (log(x) / M_LN10); } +#endif diff --git a/nuttx/lib/math/lib_log10f.c b/nuttx/lib/math/lib_log10f.c new file mode 100644 index 0000000000..651071920f --- /dev/null +++ b/nuttx/lib/math/lib_log10f.c @@ -0,0 +1,41 @@ +/************************************************************************ + * lib/math/lib_log10f.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float log10f(float x) +{ + return (logf(x) / M_LN10); +} diff --git a/nuttx/lib/math/lib_log10l.c b/nuttx/lib/math/lib_log10l.c new file mode 100644 index 0000000000..8702ed5a55 --- /dev/null +++ b/nuttx/lib/math/lib_log10l.c @@ -0,0 +1,46 @@ +/************************************************************************ + * lib/math/lib_log10l.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double log10l(long double x) +{ + return (logl(x) / M_LN10); +} +#endif diff --git a/nuttx/lib/math/lib_log2.c b/nuttx/lib/math/lib_log2.c index f8eb541b20..377d78e292 100644 --- a/nuttx/lib/math/lib_log2.c +++ b/nuttx/lib/math/lib_log2.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_log2.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009, 2010 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,19 +22,25 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float log2f(float x) { - return (logf(x) / M_LN2); -} - -double log2(double x) { - return (log(x) / M_LN2); -} - -long double log2l(long double x) { - return (logl(x) / M_LN2); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double log2(double x) +{ + return (log(x) / M_LN2); } +#endif diff --git a/nuttx/lib/math/lib_log2f.c b/nuttx/lib/math/lib_log2f.c new file mode 100644 index 0000000000..e160ca59e3 --- /dev/null +++ b/nuttx/lib/math/lib_log2f.c @@ -0,0 +1,41 @@ +/************************************************************************ + * lib/math/lib_log2f.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float log2f(float x) +{ + return (logf(x) / M_LN2); +} diff --git a/nuttx/lib/math/lib_log2l.c b/nuttx/lib/math/lib_log2l.c new file mode 100644 index 0000000000..cd25c32f11 --- /dev/null +++ b/nuttx/lib/math/lib_log2l.c @@ -0,0 +1,46 @@ +/************************************************************************ + * lib/math/lib_log2l.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double log2l(long double x) +{ + return (logl(x) / M_LN2); +} +#endif diff --git a/nuttx/lib/math/lib_logf.c b/nuttx/lib/math/lib_logf.c new file mode 100644 index 0000000000..1d31aa0c0b --- /dev/null +++ b/nuttx/lib/math/lib_logf.c @@ -0,0 +1,77 @@ +/************************************************************************ + * lib/math/lib_logf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float logf(float x) +{ + float y, y_old, ey, epsilon; + + y = 0.0; + y_old = 1.0; + epsilon = FLT_EPSILON; + + while (y > y_old + epsilon || y < y_old - epsilon) + { + y_old = y; + ey = exp(y); + y -= (ey - x) / ey; + + if (y > 700.0) + { + y = 700.0; + } + + if (y < -700.0) + { + y = -700.0; + } + + epsilon = (fabs(y) > 1.0) ? fabs(y) * FLT_EPSILON : FLT_EPSILON; + } + + if (y == 700.0) + { + return INFINITY; + } + + if (y == -700.0) + { + return INFINITY; + } + + return y; +} diff --git a/nuttx/lib/math/lib_logl.c b/nuttx/lib/math/lib_logl.c new file mode 100644 index 0000000000..df0031943f --- /dev/null +++ b/nuttx/lib/math/lib_logl.c @@ -0,0 +1,80 @@ +/************************************************************************ + * lib/math/lib_lol.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double logl(long double x) +{ + long double y, y_old, ey, epsilon; + + y = 0.0; + y_old = 1.0; + epsilon = LDBL_EPSILON; + + while (y > y_old + epsilon || y < y_old - epsilon) + { + y_old = y; + ey = expl(y); + y -= (ey - x) / ey; + + if (y > 700.0) + { + y = 700.0; + } + + if (y < -700.0) + { + y = -700.0; + } + } + + if (y == 700.0) + { + return INFINITY; + } + + if (y == -700.0) + { + return INFINITY; + } + + return y; +} +#endif diff --git a/nuttx/lib/math/lib_modf.c b/nuttx/lib/math/lib_modf.c index 1e6fadc11b..3b33cde428 100644 --- a/nuttx/lib/math/lib_modf.c +++ b/nuttx/lib/math/lib_modf.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_modf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,54 +22,37 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ -#include -#include #include +#include -float modff(float x, float *iptr) { - if (fabsf(x) >= 8388608.0) { - *iptr = x; - return 0.0; - } - else if (fabs(x) < 1.0) { - *iptr = 0.0; - return x; - } - else { - *iptr = (float) (int) x; - return (x - *iptr); - } +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double modf(double x, double *iptr) +{ + if (fabs(x) >= 4503599627370496.0) + { + *iptr = x; + return 0.0; + } + else if (fabs(x) < 1.0) + { + *iptr = 0.0; + return x; + } + else + { + *iptr = (double)(int64_t) x; + return (x - *iptr); + } } - -double modf(double x, double *iptr) { - if (fabs(x) >= 4503599627370496.0) { - *iptr = x; - return 0.0; - } - else if (fabs(x) < 1.0) { - *iptr = 0.0; - return x; - } - else { - *iptr = (double) (int64_t) x; - return (x - *iptr); - } -} - -long double modfl(long double x, long double *iptr) { - if (fabs(x) >= 4503599627370496.0) { - *iptr = x; - return 0.0; - } - else if (fabs(x) < 1.0) { - *iptr = 0.0; - return x; - } - else { - *iptr = (long double) (int64_t) x; - return (x - *iptr); - } -} - +#endif diff --git a/nuttx/lib/math/lib_modff.c b/nuttx/lib/math/lib_modff.c new file mode 100644 index 0000000000..4eec2ae17f --- /dev/null +++ b/nuttx/lib/math/lib_modff.c @@ -0,0 +1,55 @@ +/************************************************************************ + * lib/math/lib_modff.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float modff(float x, float *iptr) +{ + if (fabsf(x) >= 8388608.0) + { + *iptr = x; + return 0.0; + } + else if (fabs(x) < 1.0) + { + *iptr = 0.0; + return x; + } + else + { + *iptr = (float)(int)x; + return (x - *iptr); + } +} diff --git a/nuttx/lib/math/lib_modfl.c b/nuttx/lib/math/lib_modfl.c new file mode 100644 index 0000000000..55b17eae6d --- /dev/null +++ b/nuttx/lib/math/lib_modfl.c @@ -0,0 +1,61 @@ +/************************************************************************ + * lib/math/lib_modfl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double modfl(long double x, long double *iptr) +{ + if (fabs(x) >= 4503599627370496.0) + { + *iptr = x; + return 0.0; + } + else if (fabs(x) < 1.0) + { + *iptr = 0.0; + return x; + } + else + { + *iptr = (long double)(int64_t) x; + return (x - *iptr); + } +} +#endif diff --git a/nuttx/lib/math/lib_pow.c b/nuttx/lib/math/lib_pow.c index b353359eb2..66f6a2d2e1 100644 --- a/nuttx/lib/math/lib_pow.c +++ b/nuttx/lib/math/lib_pow.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_pow.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009, 2010 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,19 +22,25 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float powf(float b, float e) { - return expf(e * logf(b)); -} - -double pow(double b, double e) { - return exp(e * log(b)); -} - -long double powl(long double b, long double e) { - return expl(e * logl(b)); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double pow(double b, double e) +{ + return exp(e * log(b)); } +#endif diff --git a/nuttx/lib/math/lib_powf.c b/nuttx/lib/math/lib_powf.c new file mode 100644 index 0000000000..a43f9cf82a --- /dev/null +++ b/nuttx/lib/math/lib_powf.c @@ -0,0 +1,41 @@ +/************************************************************************ + * lib/math/lib_powf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float powf(float b, float e) +{ + return expf(e * logf(b)); +} diff --git a/nuttx/lib/math/lib_powl.c b/nuttx/lib/math/lib_powl.c new file mode 100644 index 0000000000..6a820df26b --- /dev/null +++ b/nuttx/lib/math/lib_powl.c @@ -0,0 +1,46 @@ +/************************************************************************ + * lib/math/lib_powl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double powl(long double b, long double e) +{ + return expl(e * logl(b)); +} +#endif diff --git a/nuttx/lib/math/lib_sin.c b/nuttx/lib/math/lib_sin.c index e862104fd6..2d21d2309c 100644 --- a/nuttx/lib/math/lib_sin.c +++ b/nuttx/lib/math/lib_sin.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_sin.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,141 +22,93 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -static float _flt_inv_fact[] = { - 1.0 / 1.0, // 1 / 1! - 1.0 / 6.0, // 1 / 3! - 1.0 / 120.0, // 1 / 5! - 1.0 / 5040.0, // 1 / 7! - 1.0 / 362880.0, // 1 / 9! - 1.0 / 39916800.0, // 1 / 11! +#include +#include + +#include +#include + +#if CONFIG_HAVE_DOUBLE + +/************************************************************************ + * Private Data + ************************************************************************/ + +static double _dbl_inv_fact[] = +{ + 1.0 / 1.0, // 1 / 1! + 1.0 / 6.0, // 1 / 3! + 1.0 / 120.0, // 1 / 5! + 1.0 / 5040.0, // 1 / 7! + 1.0 / 362880.0, // 1 / 9! + 1.0 / 39916800.0, // 1 / 11! + 1.0 / 6227020800.0, // 1 / 13! + 1.0 / 1307674368000.0, // 1 / 15! + 1.0 / 355687428096000.0, // 1 / 17! + 1.0 / 121645100408832000.0, // 1 / 19! }; -float sinf(float x) { - float x_squared; - float sin_x; - size_t i; - - /* move x to [-pi, pi) */ - x = fmodf(x, 2 * M_PI); - if (x >= M_PI) x -= 2 * M_PI; - if (x < -M_PI) x += 2 * M_PI; +/************************************************************************ + * Public Functions + ************************************************************************/ - /* move x to [-pi/2, pi/2) */ - if (x >= M_PI_2) x = M_PI - x; - if (x < -M_PI_2) x = -M_PI - x; +double sin(double x) +{ + double x_squared; + double sin_x; + size_t i; - x_squared = x * x; - sin_x = 0.0; + /* Move x to [-pi, pi) */ - /* perform Taylor series approximation for sin(x) with six terms */ - for (i = 0; i < 6; i++) { - if (i % 2 == 0) { - sin_x += x * _flt_inv_fact[i]; - } - else { - sin_x -= x * _flt_inv_fact[i]; - } + x = fmod(x, 2 * M_PI); + if (x >= M_PI) + { + x -= 2 * M_PI; + } - x *= x_squared; - } + if (x < -M_PI) + { + x += 2 * M_PI; + } - return sin_x; + /* Move x to [-pi/2, pi/2) */ + + if (x >= M_PI_2) + { + x = M_PI - x; + } + + if (x < -M_PI_2) + { + x = -M_PI - x; + } + + x_squared = x * x; + sin_x = 0.0; + + /* Perform Taylor series approximation for sin(x) with ten terms */ + + for (i = 0; i < 10; i++) + { + if (i % 2 == 0) + { + sin_x += x * _dbl_inv_fact[i]; + } + else + { + sin_x -= x * _dbl_inv_fact[i]; + } + + x *= x_squared; + } + + return sin_x; } - -static double _dbl_inv_fact[] = { - 1.0 / 1.0, // 1 / 1! - 1.0 / 6.0, // 1 / 3! - 1.0 / 120.0, // 1 / 5! - 1.0 / 5040.0, // 1 / 7! - 1.0 / 362880.0, // 1 / 9! - 1.0 / 39916800.0, // 1 / 11! - 1.0 / 6227020800.0, // 1 / 13! - 1.0 / 1307674368000.0, // 1 / 15! - 1.0 / 355687428096000.0, // 1 / 17! - 1.0 / 121645100408832000.0, // 1 / 19! -}; - -double sin(double x) { - double x_squared; - double sin_x; - size_t i; - - /* move x to [-pi, pi) */ - x = fmod(x, 2 * M_PI); - if (x >= M_PI) x -= 2 * M_PI; - if (x < -M_PI) x += 2 * M_PI; - - /* move x to [-pi/2, pi/2) */ - if (x >= M_PI_2) x = M_PI - x; - if (x < -M_PI_2) x = -M_PI - x; - - x_squared = x * x; - sin_x = 0.0; - - /* perform Taylor series approximation for sin(x) with ten terms */ - for (i = 0; i < 10; i++) { - if (i % 2 == 0) { - sin_x += x * _dbl_inv_fact[i]; - } - else { - sin_x -= x * _dbl_inv_fact[i]; - } - - x *= x_squared; - } - - return sin_x; -} - -static long double _ldbl_inv_fact[] = { - 1.0 / 1.0, // 1 / 1! - 1.0 / 6.0, // 1 / 3! - 1.0 / 120.0, // 1 / 5! - 1.0 / 5040.0, // 1 / 7! - 1.0 / 362880.0, // 1 / 9! - 1.0 / 39916800.0, // 1 / 11! - 1.0 / 6227020800.0, // 1 / 13! - 1.0 / 1307674368000.0, // 1 / 15! - 1.0 / 355687428096000.0, // 1 / 17! - 1.0 / 121645100408832000.0, // 1 / 19! -}; - -long double sinl(long double x) { - long double x_squared; - long double sin_x; - size_t i; - - /* move x to [-pi, pi) */ - x = fmodl(x, 2 * M_PI); - if (x >= M_PI) x -= 2 * M_PI; - if (x < -M_PI) x += 2 * M_PI; - - /* move x to [-pi/2, pi/2) */ - if (x >= M_PI_2) x = M_PI - x; - if (x < -M_PI_2) x = -M_PI - x; - - x_squared = x * x; - sin_x = 0.0; - - /* perform Taylor series approximation for sin(x) with ten terms */ - for (i = 0; i < 10; i++) { - if (i % 2 == 0) { - sin_x += x * _ldbl_inv_fact[i]; - } - else { - sin_x -= x * _ldbl_inv_fact[i]; - } - - x *= x_squared; - } - - return sin_x; -} - +#endif diff --git a/nuttx/lib/math/lib_sinf.c b/nuttx/lib/math/lib_sinf.c new file mode 100644 index 0000000000..e298bbba49 --- /dev/null +++ b/nuttx/lib/math/lib_sinf.c @@ -0,0 +1,104 @@ +/************************************************************************ + * lib/math/lib_sinf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +/************************************************************************ + * Private Data + ************************************************************************/ + +static float _flt_inv_fact[] = +{ + 1.0 / 1.0, // 1 / 1! + 1.0 / 6.0, // 1 / 3! + 1.0 / 120.0, // 1 / 5! + 1.0 / 5040.0, // 1 / 7! + 1.0 / 362880.0, // 1 / 9! + 1.0 / 39916800.0, // 1 / 11! +}; + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float sinf(float x) +{ + float x_squared; + float sin_x; + size_t i; + + /* Move x to [-pi, pi) */ + + x = fmodf(x, 2 * M_PI); + if (x >= M_PI) + { + x -= 2 * M_PI; + } + + if (x < -M_PI) + { + x += 2 * M_PI; + } + + /* Move x to [-pi/2, pi/2) */ + + if (x >= M_PI_2) + { + x = M_PI - x; + } + + if (x < -M_PI_2) + { + x = -M_PI - x; + } + + x_squared = x * x; + sin_x = 0.0; + + /* Perform Taylor series approximation for sin(x) with six terms */ + + for (i = 0; i < 6; i++) + { + if (i % 2 == 0) + { + sin_x += x * _flt_inv_fact[i]; + } + else + { + sin_x -= x * _flt_inv_fact[i]; + } + + x *= x_squared; + } + + return sin_x; +} diff --git a/nuttx/lib/math/lib_sinh.c b/nuttx/lib/math/lib_sinh.c index 10276d821e..a22652302c 100644 --- a/nuttx/lib/math/lib_sinh.c +++ b/nuttx/lib/math/lib_sinh.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_sinh.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009, 2010 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,22 +22,26 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float sinhf(float x) { - x = expf(x); - return ((x - (1.0 / x)) / 2.0); -} - -double sinh(double x) { - x = exp(x); - return ((x - (1.0 / x)) / 2.0); -} - -long double sinhl(long double x) { - x = expl(x); - return ((x - (1.0 / x)) / 2.0); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double sinh(double x) +{ + x = exp(x); + return ((x - (1.0 / x)) / 2.0); } +#endif diff --git a/nuttx/lib/math/lib_sinhf.c b/nuttx/lib/math/lib_sinhf.c new file mode 100644 index 0000000000..e15cb14dc4 --- /dev/null +++ b/nuttx/lib/math/lib_sinhf.c @@ -0,0 +1,42 @@ +/************************************************************************ + * lib/math/lib_sinhf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float sinhf(float x) +{ + x = expf(x); + return ((x - (1.0 / x)) / 2.0); +} diff --git a/nuttx/lib/math/lib_sinhl.c b/nuttx/lib/math/lib_sinhl.c new file mode 100644 index 0000000000..442586ffb8 --- /dev/null +++ b/nuttx/lib/math/lib_sinhl.c @@ -0,0 +1,47 @@ +/************************************************************************ + * lib/math/lib_sinhl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double sinhl(long double x) +{ + x = expl(x); + return ((x - (1.0 / x)) / 2.0); +} +#endif diff --git a/nuttx/lib/math/lib_sinl.c b/nuttx/lib/math/lib_sinl.c new file mode 100644 index 0000000000..f8d9e00edf --- /dev/null +++ b/nuttx/lib/math/lib_sinl.c @@ -0,0 +1,114 @@ +/************************************************************************ + * lib/math/lib_sinl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include +#include + +#if CONFIG_HAVE_LONG_DOUBLE + +/************************************************************************ + * Private Data + ************************************************************************/ + +static long double _ldbl_inv_fact[] = +{ + 1.0 / 1.0, // 1 / 1! + 1.0 / 6.0, // 1 / 3! + 1.0 / 120.0, // 1 / 5! + 1.0 / 5040.0, // 1 / 7! + 1.0 / 362880.0, // 1 / 9! + 1.0 / 39916800.0, // 1 / 11! + 1.0 / 6227020800.0, // 1 / 13! + 1.0 / 1307674368000.0, // 1 / 15! + 1.0 / 355687428096000.0, // 1 / 17! + 1.0 / 121645100408832000.0, // 1 / 19! +}; + +/************************************************************************ + * Public Functions + ************************************************************************/ + +long double sinl(long double x) +{ + long double x_squared; + long double sin_x; + size_t i; + + /* Move x to [-pi, pi) */ + + x = fmodl(x, 2 * M_PI); + if (x >= M_PI) + { + x -= 2 * M_PI; + } + + if (x < -M_PI) + { + x += 2 * M_PI; + } + + /* Move x to [-pi/2, pi/2) */ + + if (x >= M_PI_2) + { + x = M_PI - x; + } + + if (x < -M_PI_2) + { + x = -M_PI - x; + } + + x_squared = x * x; + sin_x = 0.0; + + /* Perform Taylor series approximation for sin(x) with ten terms */ + + for (i = 0; i < 10; i++) + { + if (i % 2 == 0) + { + sin_x += x * _ldbl_inv_fact[i]; + } + else + { + sin_x -= x * _ldbl_inv_fact[i]; + } + + x *= x_squared; + } + + return sin_x; +} +#endif diff --git a/nuttx/lib/math/lib_sqrt.c b/nuttx/lib/math/lib_sqrt.c index 206a7fe82a..96f0d5409e 100644 --- a/nuttx/lib/math/lib_sqrt.c +++ b/nuttx/lib/math/lib_sqrt.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_sqrt.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009-2011 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,105 +22,78 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include #include -#include -static float __sqrt_approx(float x) { - int32_t i; +#include "lib_internal.h" - // floats + bit manipulation = +inf fun! - i = *((int32_t*) &x); - i = 0x1FC00000 + (i >> 1); - x = *((float*) &i); +/************************************************************************ + * Public Functions + ************************************************************************/ - return x; -} - -float sqrtf(float x) { - float y; - - // filter out invalid/trivial inputs - if (x < 0.0) { errno = EDOM; return NAN; } - if (isnan(x)) return NAN; - if (isinf(x)) return INFINITY; - if (x == 0.0) return 0.0; - - // guess square root (using bit manipulation) - y = __sqrt_approx(x); - - // perform three iterations of approximation - // this number (3) is definitely optimal - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - - return y; -} - -double sqrt(double x) { - long double y, y1; - - // filter out invalid/trivial inputs - if (x < 0.0) { errno = EDOM; return NAN; } - if (isnan(x)) return NAN; - if (isinf(x)) return INFINITY; - if (x == 0.0) return 0.0; - - // guess square root (using bit manipulation) - y = __sqrt_approx(x); - - // perform four iterations of approximation - // this number (4) is definitely optimal - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - - // if guess was terribe (out of range of float) - // repeat approximation until convergence - if (y * y < x - 1.0 || y * y > x + 1.0) { - y1 = -1.0; - while (y != y1) { - y1 = y; - y = 0.5 * (y + x / y); - } - } - - return y; -} - -long double sqrtl(long double x) { - long double y, y1; - - // filter out invalid/trivial inputs - if (x < 0.0) { errno = EDOM; return NAN; } - if (isnan(x)) return NAN; - if (isinf(x)) return INFINITY; - if (x == 0.0) return 0.0; - - // guess square root (using bit manipulation) - y = __sqrt_approx(x); - - // perform four iterations of approximation - // this number (4) is definitely optimal - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - - // if guess was terribe (out of range of float) - // repeat approximation until convergence - if (y * y < x - 1.0 || y * y > x + 1.0) { - y1 = -1.0; - while (y != y1) { - y1 = y; - y = 0.5 * (y + x / y); - } - } - - return y; +#if CONFIG_HAVE_DOUBLE +double sqrt(double x) +{ + long double y, y1; + + if (x < 0.0) + { + errno = EDOM; + return NAN; + } + + if (isnan(x)) + { + return NAN; + } + + if (isinf(x)) + { + return INFINITY; + } + + if (x == 0.0) + { + return 0.0; + } + + /* Guess square root (using bit manipulation) */ + + y = lib_sqrtapprox(x); + + /* Perform four iterations of approximation. This number (4) is + * definitely optimal + */ + + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + + /* If guess was terribe (out of range of float). Repeat approximation + * until convergence. + */ + + if (y * y < x - 1.0 || y * y > x + 1.0) + { + y1 = -1.0; + while (y != y1) + { + y1 = y; + y = 0.5 * (y + x / y); + } + } + + return y; } +#endif diff --git a/nuttx/lib/math/lib_sqrtf.c b/nuttx/lib/math/lib_sqrtf.c new file mode 100644 index 0000000000..81817a0406 --- /dev/null +++ b/nuttx/lib/math/lib_sqrtf.c @@ -0,0 +1,84 @@ +/************************************************************************ + * lib/math/lib_sqrtf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include +#include + +#include "lib_internal.h" + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float sqrtf(float x) +{ + float y; + + /* Filter out invalid/trivial inputs */ + + if (x < 0.0) + { + errno = EDOM; + return NAN; + } + + if (isnan(x)) + { + return NAN; + } + + if (isinf(x)) + { + return INFINITY; + } + + if (x == 0.0) + { + return 0.0; + } + + /* Guess square root (using bit manipulation) */ + + y = lib_sqrtapprox(x); + + /* Perform three iterations of approximation. This number (3) is + * definitely optimal + */ + + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + + return y; +} diff --git a/nuttx/lib/math/lib_sqrtl.c b/nuttx/lib/math/lib_sqrtl.c new file mode 100644 index 0000000000..f305092e7b --- /dev/null +++ b/nuttx/lib/math/lib_sqrtl.c @@ -0,0 +1,101 @@ +/************************************************************************ + * lib/math/lib_sqrtl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009-2011 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include +#include + +#include "lib_internal.h" + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double sqrtl(long double x) +{ + long double y, y1; + + /* Filter out invalid/trivial inputs */ + + if (x < 0.0) + { + errno = EDOM; + return NAN; + } + + if (isnan(x)) + { + return NAN; + } + + if (isinf(x)) + { + return INFINITY; + } + + if (x == 0.0) + { + return 0.0; + } + + /* Guess square root (using bit manipulation) */ + + y = lib_sqrtapprox(x); + + /* Perform four iterations of approximation. This number (4) is + * definitely optimal + */ + + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + y = 0.5 * (y + x / y); + + /* If guess was terribe (out of range of float). Repeat approximation + * until convergence + */ + + if (y * y < x - 1.0 || y * y > x + 1.0) + { + y1 = -1.0; + while (y != y1) + { + y1 = y; + y = 0.5 * (y + x / y); + } + } + + return y; +} +#endif diff --git a/nuttx/lib/math/lib_tan.c b/nuttx/lib/math/lib_tan.c index c336a6260d..a9a1d8ebee 100644 --- a/nuttx/lib/math/lib_tan.c +++ b/nuttx/lib/math/lib_tan.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_tan.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009, 2010 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,20 +22,25 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float tanf(float x) { - return (sinf(x) / cosf(x)); -} - -double tan(double x) { - return (sin(x) / cos(x)); -} - -long double tanl(long double x) { - return (sinl(x) / cosl(x)); +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double tan(double x) +{ + return (sin(x) / cos(x)); } +#endif diff --git a/nuttx/lib/math/lib_tanf.c b/nuttx/lib/math/lib_tanf.c new file mode 100644 index 0000000000..3db3bda265 --- /dev/null +++ b/nuttx/lib/math/lib_tanf.c @@ -0,0 +1,41 @@ +/************************************************************************ + * lib/math/lib_tanf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float tanf(float x) +{ + return (sinf(x) / cosf(x)); +} diff --git a/nuttx/lib/math/lib_tanh.c b/nuttx/lib/math/lib_tanh.c index c6a1a1c875..5cc1d9176c 100644 --- a/nuttx/lib/math/lib_tanh.c +++ b/nuttx/lib/math/lib_tanh.c @@ -1,4 +1,14 @@ -/* +/************************************************************************ + * lib/math/lib_tanh.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * * Copyright (C) 2009, 2010 Nick Johnson * * Permission to use, copy, modify, and distribute this software for any @@ -12,28 +22,28 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ************************************************************************/ -#include -#include +/************************************************************************ + * Included Files + ************************************************************************/ -float tanhf(float x) { - float x0 = expf(x); - float x1 = 1.0 / x0; +#include +#include - return ((x0 + x1) / (x0 - x1)); -} - -double tanh(double x) { - double x0 = exp(x); - double x1 = 1.0 / x0; - - return ((x0 + x1) / (x0 - x1)); -} - -long double tanhl(long double x) { - long double x0 = exp(x); - long double x1 = 1.0 / x0; - - return ((x0 + x1) / (x0 - x1)); +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_DOUBLE +double tanh(double x) +{ + double x0 = exp(x); + double x1 = 1.0 / x0; + + return ((x0 + x1) / (x0 - x1)); } +#endif diff --git a/nuttx/lib/math/lib_tanhf.c b/nuttx/lib/math/lib_tanhf.c new file mode 100644 index 0000000000..94d15cc60d --- /dev/null +++ b/nuttx/lib/math/lib_tanhf.c @@ -0,0 +1,44 @@ +/************************************************************************ + * lib/math/lib_tanhf.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +float tanhf(float x) +{ + float x0 = expf(x); + float x1 = 1.0 / x0; + + return ((x0 + x1) / (x0 - x1)); +} diff --git a/nuttx/lib/math/lib_tanhl.c b/nuttx/lib/math/lib_tanhl.c new file mode 100644 index 0000000000..8b897451e4 --- /dev/null +++ b/nuttx/lib/math/lib_tanhl.c @@ -0,0 +1,49 @@ +/************************************************************************ + * lib/math/lib_tanhl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double tanhl(long double x) +{ + long double x0 = exp(x); + long double x1 = 1.0 / x0; + + return ((x0 + x1) / (x0 - x1)); +} +#endif diff --git a/nuttx/lib/math/lib_tanl.c b/nuttx/lib/math/lib_tanl.c new file mode 100644 index 0000000000..c4c3712c1c --- /dev/null +++ b/nuttx/lib/math/lib_tanl.c @@ -0,0 +1,46 @@ +/************************************************************************ + * lib/math/lib_tanl.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Ported by: Darcy Gong + * + * It derives from the Rhombs OS math library by Nick Johnson which has + * a compatibile, MIT-style license: + * + * Copyright (C) 2009, 2010 Nick Johnson + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include + +/************************************************************************ + * Public Functions + ************************************************************************/ + +#if CONFIG_HAVE_LONG_DOUBLE +long double tanl(long double x) +{ + return (sinl(x) / cosl(x)); +} +#endif From 61c97b1ddcc40f068e549d12dc8e63445d3ee4f5 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 28 Oct 2012 20:20:39 +0000 Subject: [PATCH 040/206] Ooops... last version of file was still in editor git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5271 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/lib/math/lib_exp.c | 1 + 1 file changed, 1 insertion(+) diff --git a/nuttx/lib/math/lib_exp.c b/nuttx/lib/math/lib_exp.c index 5b54dbaac1..350229860a 100644 --- a/nuttx/lib/math/lib_exp.c +++ b/nuttx/lib/math/lib_exp.c @@ -32,6 +32,7 @@ #include #include +#include #include #include "lib_internal.h" From 71fad980c5dfe057dd380a05f1ca1e0bfad2ef1f Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 29 Oct 2012 00:52:23 +0000 Subject: [PATCH 041/206] Finish implemention of ELF loader static constructor support. Still some issues. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5272 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/README.txt | 2 + apps/examples/elf/tests/Makefile | 8 +- apps/examples/elf/tests/hello++/Makefile | 116 -------- apps/examples/elf/tests/hello++/hello++1.cpp | 60 ---- apps/examples/elf/tests/hello++/hello++2.cpp | 123 --------- apps/examples/elf/tests/hello++/hello++3.cpp | 132 --------- apps/examples/elf/tests/hello++/hello++4.cpp | 150 ---------- nuttx/arch/arm/src/armv7-m/up_elf.c | 2 +- nuttx/binfmt/elf.c | 1 + nuttx/binfmt/libelf/Make.defs | 2 +- nuttx/binfmt/libelf/libelf.h | 45 ++- nuttx/binfmt/libelf/libelf_bind.c | 15 +- nuttx/binfmt/libelf/libelf_ctors.c | 274 +++++++++++++++++-- nuttx/binfmt/libelf/libelf_iobuffer.c | 136 +++++++++ nuttx/binfmt/libelf/libelf_load.c | 29 +- nuttx/binfmt/libelf/libelf_symbols.c | 17 +- nuttx/binfmt/libelf/libelf_uninit.c | 50 ++++ nuttx/binfmt/libelf/libelf_unload.c | 21 +- nuttx/configs/stm32f4discovery/elf/Make.defs | 2 + nuttx/configs/stm32f4discovery/elf/defconfig | 270 +----------------- nuttx/include/nuttx/binfmt/elf.h | 5 +- 21 files changed, 532 insertions(+), 928 deletions(-) delete mode 100644 apps/examples/elf/tests/hello++/Makefile delete mode 100644 apps/examples/elf/tests/hello++/hello++1.cpp delete mode 100644 apps/examples/elf/tests/hello++/hello++2.cpp delete mode 100644 apps/examples/elf/tests/hello++/hello++3.cpp delete mode 100644 apps/examples/elf/tests/hello++/hello++4.cpp create mode 100644 nuttx/binfmt/libelf/libelf_iobuffer.c diff --git a/apps/examples/README.txt b/apps/examples/README.txt index abf95e208d..907467bb17 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -323,6 +323,8 @@ examples/elf CELFFLAGS = $(CFLAGS) -mlong-calls + Similarly for C++ flags which must be provided in CXXELFFLAGS. + 2. Your top-level nuttx/Make.defs file must alos include an approproate definition, LDELFFLAGS, to generate a relocatable ELF object. With GNU LD, this should include '-r' and '-e main' (or _main on some platforms). diff --git a/apps/examples/elf/tests/Makefile b/apps/examples/elf/tests/Makefile index f834f6c780..d2192cb1e4 100644 --- a/apps/examples/elf/tests/Makefile +++ b/apps/examples/elf/tests/Makefile @@ -33,13 +33,15 @@ # ############################################################################ -# Most of these do no build yet +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs -ALL_SUBDIRS = errno hello hello++ longjmp mutex pthread signal task struct +ALL_SUBDIRS = errno hello helloxx longjmp mutex pthread signal task struct BUILD_SUBDIRS = errno hello task struct ifeq ($(CONFIG_HAVE_CXX),y) -BUILD_SUBDIRS += hello++ +BUILD_SUBDIRS += helloxx endif ifeq ($(CONFIG_EXAMPLES_ELF_LONGJMP),y) diff --git a/apps/examples/elf/tests/hello++/Makefile b/apps/examples/elf/tests/hello++/Makefile deleted file mode 100644 index 9de52cfa10..0000000000 --- a/apps/examples/elf/tests/hello++/Makefile +++ /dev/null @@ -1,116 +0,0 @@ -############################################################################ -# examples/elf/tests/hello/Makefile -# -# 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. -# -############################################################################ - --include $(TOPDIR)/.config --include $(TOPDIR)/Make.defs - -BIN1 = hello++1 -BIN2 = hello++2 -BIN3 = hello++3 -#BIN4 = hello++4 -ALL_BIN = $(BIN1) $(BIN2) $(BIN3) $(BIN4) - -SRCS1 = $(BIN1).c -OBJS1 = $(SRCS1:.c=.o) - -SRCS2 = $(BIN2).c -OBJS2 = $(SRCS2:.c=.o) - -SRCS3 = $(BIN3).c -OBJS3 = $(SRCS3:.c=.o) - -#SRCS4 = $(BIN4).c -#OBJS4 = $(SRCS4:.c=.o) - -SRCS = $(SRCS1) $(SRCS2) $(SRCS3) $(SRCS4) -OBJS = $(OBJS1) $(OBJS2) $(OBJS3) $(OBJS4) - -LIBSTDC_STUBS_DIR = $(TOPDIR)/libxx -LIBSTDC_STUBS_LIB = $(LIBSTDC_STUBS_DIR)/liblibxx.a - -all: $(BIN1) $(BIN2) $(BIN3) $(BIN4) - -$(OBJS): %.o: %.cpp - @echo "CC: $<" - @$(CXX) -c $(CXXFLAGS) $< -o $@ - -# This contains libstdc++ stubs to that you can build C++ code -# without actually having libstdc++ - -$(LIBSTDC_STUBS_LIB): - @$(MAKE) -C $(LIBSTDC_STUBS_DIR) TOPDIR=$(TOPDIR) - -# BIN1 and BIN2 link just like C code because they contain no -# static constructors. BIN1 is equivalent to a C hello world; -# BIN2 contains a class that implements hello world, but it is -# not statically initialized. - -$(BIN1): $(OBJS1) - @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ - -$(BIN2): $(OBJS2) - @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ - -# BIN3 is equivalent to BIN2 except that is uses static initializers - -$(BIN3): $(OBJS3) - @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ - -# BIN4 is similar to BIN3 except that it uses the streams code from libstdc++ -# -# NOTE: libstdc++ is not available for NuttX as of this writing -# -#$(BIN4): $(OBJS4) -# @echo "LD: $<" -# @$(LD) $(LDELFFLAGS) -o $@ $^ - -clean: - @rm -f $(ALL_BIN) *.o *~ .*.swp core - -install: $(ALL_BIN) - @install -D $(BIN1) $(ROMFS_DIR)/$(BIN1) - @install -D $(BIN2) $(ROMFS_DIR)/$(BIN2) - @install -D $(BIN3) $(ROMFS_DIR)/$(BIN3) -# @install -D $(BIN4) $(ROMFS_DIR)/$(BIN4) - - - - - - - diff --git a/apps/examples/elf/tests/hello++/hello++1.cpp b/apps/examples/elf/tests/hello++/hello++1.cpp deleted file mode 100644 index 22a7281886..0000000000 --- a/apps/examples/elf/tests/hello++/hello++1.cpp +++ /dev/null @@ -1,60 +0,0 @@ -///////////////////////////////////////////////////////////////////////////// -// examples/elf/tests/hello++/hello++1.c -// -// 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. -// -///////////////////////////////////////////////////////////////////////////// -// -// This is an trivial version of "Hello, World" program. It illustrates -// that we can build C programs using the C++ compiler. -// -// - Building a C++ program to use the C library -// - No class creation -// - NO Streams -// - NO Static constructor and destructors -// -///////////////////////////////////////////////////////////////////////////// - -///////////////////////////////////////////////////////////////////////////// -// Included Files -///////////////////////////////////////////////////////////////////////////// - -#include - -///////////////////////////////////////////////////////////////////////////// -// Public Functions -///////////////////////////////////////////////////////////////////////////// - -int main(int argc, char **argv) -{ - printf("Hello, World!\n"); - return 0; -} diff --git a/apps/examples/elf/tests/hello++/hello++2.cpp b/apps/examples/elf/tests/hello++/hello++2.cpp deleted file mode 100644 index a8ba589bd3..0000000000 --- a/apps/examples/elf/tests/hello++/hello++2.cpp +++ /dev/null @@ -1,123 +0,0 @@ -///////////////////////////////////////////////////////////////////////////// -// examples/elf/tests/hello++/hello++2.c -// -// 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. -// -///////////////////////////////////////////////////////////////////////////// -// -// This is an another trivial version of "Hello, World" design. It illustrates -// -// - Building a C++ program to use the C library -// - Basic class creation -// - NO Streams -// - NO Static constructor and destructors -// -///////////////////////////////////////////////////////////////////////////// - -///////////////////////////////////////////////////////////////////////////// -// Included Files -///////////////////////////////////////////////////////////////////////////// - -#include - -///////////////////////////////////////////////////////////////////////////// -// Classes -///////////////////////////////////////////////////////////////////////////// - -class CThingSayer -{ - const char *szWhatToSay; -public: - CThingSayer(void) - { - printf("CThingSayer::CThingSayer: I am!\n"); - szWhatToSay = (const char*)NULL; - } - - ~CThingSayer(void) - { - printf("CThingSayer::~CThingSayer: I cease to be\n"); - if (szWhatToSay) - { - printf("CThingSayer::~CThingSayer: I will never say '%s' again\n", - szWhatToSay); - } - szWhatToSay = (const char*)NULL; - } - - void Initialize(const char *czSayThis) - { - printf("CThingSayer::Initialize: When told, I will say '%s'\n", - czSayThis); - szWhatToSay = czSayThis; - } - - void SayThing(void) - { - printf("CThingSayer::SayThing: I am now saying '%s'\n", szWhatToSay); - } -}; - -///////////////////////////////////////////////////////////////////////////// -// Public Functions -///////////////////////////////////////////////////////////////////////////// - -int main(int argc, char **argv) -{ - CThingSayer *MyThingSayer; - - printf("main: Started. Creating MyThingSayer\n"); - - // Create an instance of the CThingSayer class - // We should see the message from constructor, CThingSayer::CThingSayer(), - - MyThingSayer = new CThingSayer; - printf("main: Created MyThingSayer=0x%08lx\n", (long)MyThingSayer); - - // Tell MyThingSayer that "Hello, World!" is the string to be said - - printf("main: Calling MyThingSayer->Initialize\n");; - MyThingSayer->Initialize("Hello, World!"); - - // Tell MyThingSayer to say the thing we told it to say - - printf("main: Calling MyThingSayer->SayThing\n");; - MyThingSayer->SayThing(); - - // We should see the message from the destructor, - // CThingSayer::~CThingSayer(), AFTER we see the following - - printf("main: Destroying MyThingSayer\n"); - delete MyThingSayer; - - printf("main: Returning\n");; - return 0; -} diff --git a/apps/examples/elf/tests/hello++/hello++3.cpp b/apps/examples/elf/tests/hello++/hello++3.cpp deleted file mode 100644 index eedaa6df0c..0000000000 --- a/apps/examples/elf/tests/hello++/hello++3.cpp +++ /dev/null @@ -1,132 +0,0 @@ -///////////////////////////////////////////////////////////////////////////// -// examples/elf/tests/hello++/hello++3.c -// -// 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. -// -///////////////////////////////////////////////////////////////////////////// -// -// This is an another trivial version of "Hello, World" design. It illustrates -// -// - Building a C++ program to use the C library and stdio -// - Basic class creation with virtual methods. -// - Static constructor and destructors (in main program only) -// - NO Streams -// -///////////////////////////////////////////////////////////////////////////// - -///////////////////////////////////////////////////////////////////////////// -// Included Files -///////////////////////////////////////////////////////////////////////////// - -#include - -///////////////////////////////////////////////////////////////////////////// -// Classes -///////////////////////////////////////////////////////////////////////////// - -class CThingSayer -{ - const char *szWhatToSay; -public: - CThingSayer(void); - virtual ~CThingSayer(void); - virtual void Initialize(const char *czSayThis); - virtual void SayThing(void); -}; - -// A static instance of the CThingSayer class. This instance MUST -// be constructed by the system BEFORE the program is started at -// main() and must be destructed by the system AFTER the main() -// returns to the system - -static CThingSayer MyThingSayer; - -// These are implementations of the methods of the CThingSayer class - -CThingSayer::CThingSayer(void) -{ - printf("CThingSayer::CThingSayer: I am!\n"); - szWhatToSay = (const char*)NULL; -} - -CThingSayer::~CThingSayer(void) -{ - printf("CThingSayer::~CThingSayer: I cease to be\n"); - if (szWhatToSay) - { - printf("CThingSayer::~CThingSayer: I will never say '%s' again\n", - szWhatToSay); - } - szWhatToSay = (const char*)NULL; -} - -void CThingSayer::Initialize(const char *czSayThis) -{ - printf("CThingSayer::Initialize: When told, I will say '%s'\n", - czSayThis); - szWhatToSay = czSayThis; -} - -void CThingSayer::SayThing(void) -{ - printf("CThingSayer::SayThing: I am now saying '%s'\n", szWhatToSay); -} - -///////////////////////////////////////////////////////////////////////////// -// Public Functions -///////////////////////////////////////////////////////////////////////////// - -int main(int argc, char **argv) -{ - // We should see the message from constructor, CThingSayer::CThingSayer(), - // BEFORE we see the following messages. That is proof that the - // C++ static initializer is working - - printf("main: Started. MyThingSayer should already exist\n"); - - // Tell MyThingSayer that "Hello, World!" is the string to be said - - printf("main: Calling MyThingSayer.Initialize\n");; - MyThingSayer.Initialize("Hello, World!"); - - // Tell MyThingSayer to say the thing we told it to say - - printf("main: Calling MyThingSayer.SayThing\n");; - MyThingSayer.SayThing(); - - // We are finished, return. We should see the message from the - // destructor, CThingSayer::~CThingSayer(), AFTER we see the following - // message. That is proof that the C++ static destructor logic - // is working - - printf("main: Returning. MyThingSayer should be destroyed\n");; - return 0; -} diff --git a/apps/examples/elf/tests/hello++/hello++4.cpp b/apps/examples/elf/tests/hello++/hello++4.cpp deleted file mode 100644 index 1a9f2e28b7..0000000000 --- a/apps/examples/elf/tests/hello++/hello++4.cpp +++ /dev/null @@ -1,150 +0,0 @@ -///////////////////////////////////////////////////////////////////////////// -// examples/elf/tests/hello++/hello++4.c -// -// 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. -// -///////////////////////////////////////////////////////////////////////////// -// -// This is an excessively complex version of "Hello, World" design to -// illustrate some basic properties of C++: -// -// - Building a C++ program -// - Streams / statically linked libstdc++ -// - Static constructor and destructors (in main program only) -// -///////////////////////////////////////////////////////////////////////////// - -///////////////////////////////////////////////////////////////////////////// -// Included Files -///////////////////////////////////////////////////////////////////////////// - -#include -#include - -#ifndef NULL -# define NULL ((void*)0L) -#endif - -///////////////////////////////////////////////////////////////////////////// -// Classes -///////////////////////////////////////////////////////////////////////////// - -using namespace std; - -// A hello world sayer class - -class CThingSayer -{ - const char *szWhatToSay; -public: - CThingSayer(void); - virtual ~CThingSayer(void); - virtual void Initialize(const char *czSayThis); - virtual void SayThing(void); -}; - -///////////////////////////////////////////////////////////////////////////// -// Private Data -///////////////////////////////////////////////////////////////////////////// - -// A static instance of the CThingSayer class. This instance MUST -// be constructed by the system BEFORE the program is started at -// main() and must be destructed by the system AFTER the main() -// returns to the system - -static CThingSayer MyThingSayer; - -///////////////////////////////////////////////////////////////////////////// -// Method Implementations -///////////////////////////////////////////////////////////////////////////// - -// These are implementations of the methods of the CThingSayer class - -CThingSayer::CThingSayer(void) -{ - cout << "CThingSayer::CThingSayer: I am!" << endl; - szWhatToSay = (const char*)NULL; -} - -CThingSayer::~CThingSayer(void) -{ - cout << "CThingSayer::~CThingSayer: I cease to be" << endl; - if (szWhatToSay) - { - cout << "CThingSayer::~CThingSayer: I will never say '" - << szWhatToSay << "' again" << endl; - } - szWhatToSay = (const char*)NULL; -} - -void CThingSayer::Initialize(const char *czSayThis) -{ - cout << "CThingSayer::Initialize: When told, I will say '" - << czSayThis << "'" << endl; - szWhatToSay = czSayThis; -} - -void CThingSayer::SayThing(void) -{ - cout << "CThingSayer::SayThing: I am now saying '" - << szWhatToSay << "'" << endl; -} - -///////////////////////////////////////////////////////////////////////////// -// Public Functions -///////////////////////////////////////////////////////////////////////////// - -int main(int argc, char **argv) -{ - // We should see the message from constructor, CThingSayer::CThingSayer(), - // BEFORE we see the following messages. That is proof that the - // C++ static initializer is working - - cout << "main: Started" << endl; - - // Tell MyThingSayer that "Hello, World!" is the string to be said - - cout << "main: Calling MyThingSayer.Initialize" << endl; - MyThingSayer.Initialize("Hello, World!"); - - // Tell MyThingSayer to say the thing we told it to say - - cout << "main: Calling MyThingSayer.SayThing" << endl; - MyThingSayer.SayThing(); - - // We are finished, return. We should see the message from the - // destructor, CThingSayer::~CThingSayer(), AFTER we see the following - // message. That is proof that the C++ static destructor logic - // is working - - cout << "main: Returning" << endl; - return 0; -} diff --git a/nuttx/arch/arm/src/armv7-m/up_elf.c b/nuttx/arch/arm/src/armv7-m/up_elf.c index 202c902b4b..1cc1fa32a2 100644 --- a/nuttx/arch/arm/src/armv7-m/up_elf.c +++ b/nuttx/arch/arm/src/armv7-m/up_elf.c @@ -282,7 +282,7 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, if (offset <= (int32_t)0xff000000 || offset >= (int32_t)0x01000000) { - bdbg(" ERROR: JUMP24 [%d] relocation out of range, offset=%08lx\n", + bdbg(" ERROR: JUMP24 [%d] relocation out of range, branch taget=%08lx\n", ELF32_R_TYPE(rel->r_info), offset); return -EINVAL; diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c index 9a0ac1873f..57123ed95d 100644 --- a/nuttx/binfmt/elf.c +++ b/nuttx/binfmt/elf.c @@ -116,6 +116,7 @@ static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo) bdbg(" filelen: %ld\n", (long)loadinfo->filelen); #ifdef CONFIG_ELF_CONSTRUCTORS bdbg(" ctors: %08lx\n", (long)loadinfo->ctors); + bdbg(" nctors: %d\n", loadinfo->nctors); #endif bdbg(" filfd: %d\n", loadinfo->filfd); bdbg(" symtabidx: %d\n", loadinfo->symtabidx); diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs index a70a127f80..cf2507a995 100644 --- a/nuttx/binfmt/libelf/Make.defs +++ b/nuttx/binfmt/libelf/Make.defs @@ -43,7 +43,7 @@ BINFMT_CSRCS += elf.c BINFMT_CSRCS += libelf_init.c libelf_uninit.c libelf_load.c \ libelf_unload.c libelf_verify.c libelf_read.c \ - libelf_bind.c libelf_symbols.c + libelf_bind.c libelf_symbols.c libelf_iobuffer.c ifeq ($(CONFIG_ELF_CONSTRUCTORS),y) BINFMT_CSRCS += libelf_ctors.c diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h index 0fb1362dcd..0d13515cc9 100644 --- a/nuttx/binfmt/libelf/libelf.h +++ b/nuttx/binfmt/libelf/libelf.h @@ -141,6 +141,49 @@ int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index, int elf_symvalue(FAR struct elf_loadinfo_s *loadinfo, FAR Elf32_Sym *sym, FAR const struct symtab_s *exports, int nexports); +/**************************************************************************** + * Name: elf_freebuffers + * + * Description: + * Release all working buffers. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_freebuffers(FAR struct elf_loadinfo_s *loadinfo); + +/**************************************************************************** + * Name: elf_allocbuffer + * + * Description: + * Perform the initial allocation of the I/O buffer, if it has not already + * been allocated. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_allocbuffer(FAR struct elf_loadinfo_s *loadinfo); + +/**************************************************************************** + * Name: elf_reallocbuffer + * + * Description: + * Increase the size of I/O buffer by the specified buffer increment. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_reallocbuffer(FAR struct elf_loadinfo_s *loadinfo, size_t increment); + /**************************************************************************** * Name: elf_findctors * @@ -157,7 +200,7 @@ int elf_symvalue(FAR struct elf_loadinfo_s *loadinfo, FAR Elf32_Sym *sym, ****************************************************************************/ #ifdef CONFIG_ELF_CONSTRUCTORS -int elf_findctors(FAR struct elf_loadinfo_s *loadinfo); +int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo); #endif /**************************************************************************** diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c index 54ea8f1f04..ef1b4fc8fd 100644 --- a/nuttx/binfmt/libelf/libelf_bind.c +++ b/nuttx/binfmt/libelf/libelf_bind.c @@ -46,7 +46,6 @@ #include #include -#include #include #include @@ -247,17 +246,16 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo, return ret; } - /* Allocate an I/O buffer. This buffer is used only by elf_symname() to + /* Allocate an I/O buffer. This buffer is used by elf_symname() to * accumulate the variable length symbol name. */ - loadinfo->iobuffer = (FAR uint8_t *)kmalloc(CONFIG_ELF_BUFFERSIZE); - if (!loadinfo->iobuffer) + ret = elf_allocbuffer(loadinfo); + if (ret < 0) { - bdbg("Failed to allocate an I/O buffer\n"); + bdbg("elf_allocbuffer failed: %d\n", ret); return -ENOMEM; } - loadinfo->buflen = CONFIG_ELF_BUFFERSIZE; /* Process relocations in every allocated section */ @@ -303,11 +301,6 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo, arch_flushicache((FAR void*)loadinfo->alloc, loadinfo->allocsize); #endif - /* Free the I/O buffer */ - - kfree(loadinfo->iobuffer); - loadinfo->iobuffer = NULL; - loadinfo->buflen = 0; return ret; } diff --git a/nuttx/binfmt/libelf/libelf_ctors.c b/nuttx/binfmt/libelf/libelf_ctors.c index e8b095bb78..c53923d44f 100644 --- a/nuttx/binfmt/libelf/libelf_ctors.c +++ b/nuttx/binfmt/libelf/libelf_ctors.c @@ -39,11 +39,15 @@ #include +#include +#include +#include #include +#include #include -#include "libelf" +#include "libelf.h" #ifdef CONFIG_ELF_CONSTRUCTORS @@ -55,8 +59,6 @@ * Private Types ****************************************************************************/ -typedef FAR void (*ctor_t)(void); - /**************************************************************************** * Private Constant Data ****************************************************************************/ @@ -66,9 +68,111 @@ typedef FAR void (*ctor_t)(void); ****************************************************************************/ /**************************************************************************** - * Public Functions + * Name: elf_sectname + * + * Description: + * Get the symbol name in loadinfo->iobuffer[]. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * ****************************************************************************/ +static inline int elf_sectname(FAR struct elf_loadinfo_s *loadinfo, + FAR const Elf32_Shdr *shdr) +{ + FAR Elf32_Shdr *shstr; + FAR uint8_t *buffer; + off_t offset; + size_t readlen; + size_t bytesread; + int shstrndx; + int ret; + + /* Get the section header table index of the entry associated with the + * section name string table. If the file has no section name string table, + * this member holds the value SH_UNDEF. + */ + + shstrndx = loadinfo->ehdr.e_shstrndx; + if (shstrndx == SHN_UNDEF) + { + bdbg("No section header string table\n"); + return -EINVAL; + } + + /* Get the section name string table section header */ + + shstr = &loadinfo->shdr[shstrndx]; + + /* Get the file offset to the string that is the name of the section. This + * is the sum of: + * + * shstr->sh_offset: The file offset to the first byte of the section + * header string table data. + * shdr->sh_name: The offset to the name of the section in the section + * name table + */ + + offset = shstr->sh_offset + shdr->sh_name; + + /* Loop until we get the entire section name into memory */ + + buffer = loadinfo->iobuffer; + bytesread = 0; + + for (;;) + { + /* Get the number of bytes to read */ + + readlen = loadinfo->buflen - bytesread; + if (offset + readlen > loadinfo->filelen) + { + readlen = loadinfo->filelen - offset; + if (readlen <= 0) + { + bdbg("At end of file\n"); + return -EINVAL; + } + } + + /* Read that number of bytes into the array */ + + buffer = &loadinfo->iobuffer[bytesread]; + ret = elf_read(loadinfo, buffer, readlen, offset); + if (ret < 0) + { + bdbg("Failed to read section name\n"); + return ret; + } + + bytesread += readlen; + + /* Did we read the NUL terminator? */ + + if (memchr(buffer, '\0', readlen) != NULL) + { + /* Yes, the buffer contains a NUL terminator. */ + + return OK; + } + + /* No.. then we have to read more */ + + ret = elf_reallocbuffer(loadinfo, CONFIG_ELF_BUFFERINCR); + if (ret < 0) + { + bdbg("elf_reallocbuffer failed: %d\n", ret); + return ret; + } + } + + /* We will not get here */ + + return OK; +} + /**************************************************************************** * Name: elf_findctors * @@ -79,27 +183,157 @@ typedef FAR void (*ctor_t)(void); * loadinfo - Load state information * * Returned Value: + * On success, the index to the CTOR section is returned; A negated errno + * value is returned on failure. + * + ****************************************************************************/ + +static inline int elf_findctors(FAR struct elf_loadinfo_s *loadinfo) +{ + FAR const Elf32_Shdr *shdr; + int ret; + int i; + + /* Search through the shdr[] array in loadinfo for a section named .ctors */ + + for (i = 0; i < loadinfo->ehdr.e_shnum; i++) + { + /* Get the name of this section */ + + shdr = &loadinfo->shdr[i]; + ret = elf_sectname(loadinfo, shdr); + if (ret < 0) + { + bdbg("elf_sectname failed: %d\n", ret); + return ret; + } + + /* Check if the name of this section if ".ctors" */ + + bvdbg("%d. Comparing \"%s\" and .ctors\"\n", i, loadinfo->iobuffer); + + if (strcmp(".ctors", (FAR const char *)loadinfo->iobuffer) == 0) + { + /* We found it... return the index */ + + return i; + } + } + + /* We failed to find the .ctors sections. This may not be an error; maybe + * there are no static constructors. + */ + + return -ENOENT; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_loadctors + * + * Description: + * Load points to static constructors into an in-memory array. + * + * Input Parameters: + * loadinfo - Load state information + * + * Returned Value: * 0 (OK) is returned on success and a negated errno is returned on * failure. * ****************************************************************************/ -int elf_findctors(FAR struct elf_loadinfo_s *loadinfo) +int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) { - /* Search through the shdr[] array in loadinfo for a section named .ctors */ -#warning "Missing logic" + FAR Elf32_Shdr *shdr; + size_t ctorsize; + int ctoridx; + int ret; + int i; - /* Get the address of the beginning of the constructros from the sh_addr - * field of the section. Save that in the ctors field of the loadinfo - * structure. + DEBUGASSERT(loadinfo->ctors == NULL); + + /* Allocate an I/O buffer. This buffer is used by elf_sectname() to + * accumulate the variable length symbol name. */ -#warning "Missing logic" - /* Get the number of constructors from the sh_size field of the section. - * Save that number in the nctors field of the loadinfo structure. - */ -#warning "Missing logic" - return -ENOSYS; + ret = elf_allocbuffer(loadinfo); + if (ret < 0) + { + bdbg("elf_allocbuffer failed: %d\n", ret); + return -ENOMEM; + } + + /* Find the index to the section named ".ctors" */ + + ctoridx = elf_findctors(loadinfo); + if (ctoridx < 0) + { + /* This may not be a failure. -ENOENT indicates that the file has no + * static constructor section. + */ + + bvdbg("elf_findctors failed: %d\n", ctoridx); + return ret == -ENOENT ? OK : ret; + } + + /* Now we can get a pointer to the .ctor section in the section header + * table. + */ + + shdr = &loadinfo->shdr[ctoridx]; + + /* Allocate memory to hold a copy of the .ctor section */ + + ctorsize = shdr->sh_size; + loadinfo->nctors = ctorsize / sizeof(elf_ctor_t); + + bvdbg("ctoridx=%d ctorsize=%d sizeof(elf_ctor_t)=%d nctors=%d\n", + ctoridx, ctorsize, sizeof(elf_ctor_t), loadinfo->nctors); + + /* Check if there are any constructors. It is not an error if there + * are none. + */ + + if (loadinfo->nctors > 0) + { + /* Check an assumption that we made above */ + + DEBUGASSERT(shdr->sh_entsize == sizeof(elf_ctor_t)); + + loadinfo->ctors = (elf_ctor_t)kmalloc(ctorsize); + if (!loadinfo->ctors) + { + bdbg("Failed to allocate memory for .ctors\n"); + return -ENOMEM; + } + + /* Read the section header table into memory */ + + ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->ctors, ctorsize, + shdr->sh_offset); + if (ret < 0) + { + bdbg("Failed to allocate .ctors: %d\n", ret); + } + + /* Fix up all of the .ctor addresses */ + + for (i = 0; i < loadinfo->nctors; i++) + { + FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->ctors)[i]); + + bvdbg("ctor %d: %08lx + %08lx = %08lx\n", i, + *ptr, loadinfo->alloc, *ptr + loadinfo->alloc); + + *ptr += loadinfo->alloc; + } + } + + return OK; } /**************************************************************************** @@ -119,16 +353,20 @@ int elf_findctors(FAR struct elf_loadinfo_s *loadinfo) int elf_doctors(FAR struct elf_loadinfo_s *loadinfo) { - ctor_t ctor = (ctor_t)loadinfo->ctors; + elf_ctor_t ctor = (elf_ctor_t)loadinfo->ctors; int i; /* Execute each constructor */ for (i = 0; i < loadinfo->nctors; i++) { + bvdbg("Calling ctor %d at %p\n", i, (FAR void *)ctor); + ctor(); ctor++; } + + return OK; } -#endif /* CONFIG_ELF_CONSTRUCTORS +#endif /* CONFIG_ELF_CONSTRUCTORS */ diff --git a/nuttx/binfmt/libelf/libelf_iobuffer.c b/nuttx/binfmt/libelf/libelf_iobuffer.c new file mode 100644 index 0000000000..ead99ca099 --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_iobuffer.c @@ -0,0 +1,136 @@ +/**************************************************************************** + * binfmt/libelf/elf_iobuffer.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "libelf.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_allocbuffer + * + * Description: + * Perform the initial allocation of the I/O buffer, if it has not already + * been allocated. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_allocbuffer(FAR struct elf_loadinfo_s *loadinfo) +{ + /* Has a buffer been allocated> */ + + if (!loadinfo->iobuffer) + { + /* No.. allocate one now */ + + loadinfo->iobuffer = (FAR uint8_t *)kmalloc(CONFIG_ELF_BUFFERSIZE); + if (!loadinfo->iobuffer) + { + bdbg("Failed to allocate an I/O buffer\n"); + return -ENOMEM; + } + + loadinfo->buflen = CONFIG_ELF_BUFFERSIZE; + } + + return OK; +} + +/**************************************************************************** + * Name: elf_reallocbuffer + * + * Description: + * Increase the size of I/O buffer by the specified buffer increment. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_reallocbuffer(FAR struct elf_loadinfo_s *loadinfo, size_t increment) +{ + FAR void *buffer; + size_t newsize; + + /* Get the new size of the allocation */ + + newsize = loadinfo->buflen + increment; + + /* And perform the reallocation */ + + buffer = krealloc((FAR void *)loadinfo->iobuffer, newsize); + if (!buffer) + { + bdbg("Failed to reallocate the I/O buffer\n"); + return -ENOMEM; + } + + /* Save the new buffer info */ + + loadinfo->iobuffer = buffer; + loadinfo->buflen = newsize; + return OK; +} + diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 6526004f76..505e2c8131 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -126,14 +126,8 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) if (ret < 0) { bdbg("Failed to read section header table: %d\n", ret); - goto errout_with_alloc; } - return OK; - -errout_with_alloc: - kfree(loadinfo->shdr); - loadinfo->shdr = 0; return ret; } @@ -233,7 +227,7 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo) if (ret < 0) { bdbg("Failed to read section %d: %d\n", i, ret); - goto errout_with_alloc; + return ret; } } @@ -248,11 +242,6 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo) } return OK; - -errout_with_alloc: - kfree((FAR void*)loadinfo->alloc); - loadinfo->alloc = 0; - return ret; } /**************************************************************************** @@ -285,7 +274,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) if (ret < 0) { bdbg("elf_loadshdrs failed: %d\n", ret); - return ret; + goto errout_with_buffers; } /* Determine total size to allocate */ @@ -298,16 +287,17 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) if (ret < 0) { bdbg("elf_loadfile failed: %d\n", ret); - goto errout_with_shdrs; + goto errout_with_buffers; } /* Find static constructors. */ #ifdef CONFIG_ELF_CONSTRUCTORS - ret = elf_findctors(loadinfo); + ret = elf_loadctors(loadinfo); + if (ret < 0) { - bdbg("elf_findctors failed: %d\n", ret); - goto errout_with_shdrs; + bdbg("elf_loadctors failed: %d\n", ret); + goto errout_with_buffers; } #endif @@ -315,9 +305,8 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) /* Error exits */ -errout_with_shdrs: - kfree(loadinfo->shdr); - loadinfo->shdr = NULL; +errout_with_buffers: + elf_freebuffers(loadinfo); return ret; } diff --git a/nuttx/binfmt/libelf/libelf_symbols.c b/nuttx/binfmt/libelf/libelf_symbols.c index 123f9f77f5..2d94b11af0 100644 --- a/nuttx/binfmt/libelf/libelf_symbols.c +++ b/nuttx/binfmt/libelf/libelf_symbols.c @@ -101,7 +101,6 @@ static int elf_symname(FAR struct elf_loadinfo_s *loadinfo, /* Loop until we get the entire symbol name into memory */ - buffer = loadinfo->iobuffer; bytesread = 0; for (;;) @@ -125,7 +124,7 @@ static int elf_symname(FAR struct elf_loadinfo_s *loadinfo, ret = elf_read(loadinfo, buffer, readlen, offset); if (ret < 0) { - bdbg("Failed to read symbol name\n"); + bdbg("elf_read failed: %d\n", ret); return ret; } @@ -142,18 +141,12 @@ static int elf_symname(FAR struct elf_loadinfo_s *loadinfo, /* No.. then we have to read more */ - buffer = realloc((FAR void *)loadinfo->iobuffer, - loadinfo->buflen + CONFIG_ELF_BUFFERINCR); - if (!buffer) + ret = elf_reallocbuffer(loadinfo, CONFIG_ELF_BUFFERINCR); + if (ret < 0) { - bdbg("Failed to reallocate the I/O buffer\n"); - return -ENOMEM; + bdbg("elf_reallocbuffer failed: %d\n", ret); + return ret; } - - /* Save the new buffer info */ - - loadinfo->iobuffer = buffer; - loadinfo->buflen += CONFIG_ELF_BUFFERINCR; } /* We will not get here */ diff --git a/nuttx/binfmt/libelf/libelf_uninit.c b/nuttx/binfmt/libelf/libelf_uninit.c index e5fa2e6c33..06bb896816 100644 --- a/nuttx/binfmt/libelf/libelf_uninit.c +++ b/nuttx/binfmt/libelf/libelf_uninit.c @@ -42,8 +42,12 @@ #include #include #include + +#include #include +#include "libelf.h" + /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ @@ -75,6 +79,12 @@ int elf_uninit(struct elf_loadinfo_s *loadinfo) { + /* Free all working buffers */ + + elf_freebuffers(loadinfo); + + /* Close the ELF file */ + if (loadinfo->filfd >= 0) { close(loadinfo->filfd); @@ -83,3 +93,43 @@ int elf_uninit(struct elf_loadinfo_s *loadinfo) return OK; } +/**************************************************************************** + * Name: elf_freebuffers + * + * Description: + * Release all working buffers. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_freebuffers(struct elf_loadinfo_s *loadinfo) +{ + /* Release all working allocations */ + + if (loadinfo->shdr) + { + kfree((FAR void *)loadinfo->shdr); + loadinfo->shdr = NULL; + } + +#ifdef CONFIG_ELF_CONSTRUCTORS + if (loadinfo->ctors) + { + kfree((FAR void *)loadinfo->ctors); + loadinfo->ctors = NULL; + loadinfo->nctors = 0; + } +#endif + + if (loadinfo->iobuffer) + { + kfree((FAR void *)loadinfo->iobuffer); + loadinfo->iobuffer = NULL; + loadinfo->buflen = 0; + } + + return OK; +} diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c index 3351064079..d7a8827111 100644 --- a/nuttx/binfmt/libelf/libelf_unload.c +++ b/nuttx/binfmt/libelf/libelf_unload.c @@ -45,6 +45,8 @@ #include #include +#include "libelf.h" + /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ @@ -76,7 +78,11 @@ int elf_unload(struct elf_loadinfo_s *loadinfo) { - /* Release the all allocated memory */ + /* Free all working buffers */ + + elf_freebuffers(loadinfo); + + /* Release memory holding the relocated ELF image */ if (loadinfo->alloc) { @@ -85,19 +91,6 @@ int elf_unload(struct elf_loadinfo_s *loadinfo) loadinfo->allocsize = 0; } - if (loadinfo->shdr) - { - kfree((FAR void *)loadinfo->shdr); - loadinfo->shdr = NULL; - } - - if (loadinfo->iobuffer) - { - kfree((FAR void *)loadinfo->iobuffer); - loadinfo->iobuffer = NULL; - loadinfo->buflen = 0; - } - return OK; } diff --git a/nuttx/configs/stm32f4discovery/elf/Make.defs b/nuttx/configs/stm32f4discovery/elf/Make.defs index c64102d174..7df9b13da6 100644 --- a/nuttx/configs/stm32f4discovery/elf/Make.defs +++ b/nuttx/configs/stm32f4discovery/elf/Make.defs @@ -161,6 +161,8 @@ LDNXFLATFLAGS = -e main -s 2048 # ELF module definitions CELFFLAGS = $(CFLAGS) -mlong-calls +CXXELFFLAGS = $(CXXFLAGS) -mlong-calls + LDELFFLAGS = -r -e main ifeq ($(WINTOOL),y) LDELFFLAGS += -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/gnu-elf.ld}" diff --git a/nuttx/configs/stm32f4discovery/elf/defconfig b/nuttx/configs/stm32f4discovery/elf/defconfig index 5bbef5e73a..59c221a0ca 100644 --- a/nuttx/configs/stm32f4discovery/elf/defconfig +++ b/nuttx/configs/stm32f4discovery/elf/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # # CONFIG_ARCH_STDBOOL_H is not set # CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set # CONFIG_ARCH_STDARG_H is not set # @@ -387,7 +388,7 @@ CONFIG_ELF_ALIGN_LOG2=2 CONFIG_ELF_STACKSIZE=2048 CONFIG_ELF_BUFFERSIZE=128 CONFIG_ELF_BUFFERINCR=32 -# CONFIG_ELF_CONSTRUCTORS is not set +CONFIG_ELF_CONSTRUCTORS=y CONFIG_SYMTAB_ORDEREDBYNAME=y # @@ -397,6 +398,7 @@ CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" +# CONFIG_LIBM is not set # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set @@ -425,264 +427,57 @@ CONFIG_HAVE_CXX=y # # Examples # - -# -# ADC Example -# - -# -# Buttons Example -# # CONFIG_EXAMPLES_BUTTONS is not set - -# -# CAN Example -# # CONFIG_EXAMPLES_CAN is not set - -# -# USB CDC/ACM Class Driver Example -# # CONFIG_EXAMPLES_CDCACM is not set - -# -# USB composite Class Driver Example -# # CONFIG_EXAMPLES_COMPOSITE is not set - -# -# DHCP Server Example -# # CONFIG_EXAMPLES_DHCPD is not set - -# -# ELF Loader Example -# CONFIG_EXAMPLES_ELF=y CONFIG_EXAMPLES_ELF_DEVMINOR=0 CONFIG_EXAMPLES_ELF_DEVPATH="/dev/ram0" - -# -# FTP Client Example -# # CONFIG_EXAMPLES_FTPC is not set - -# -# FTP Server Example -# # CONFIG_EXAMPLES_FTPD is not set - -# -# "Hello, World!" Example -# # CONFIG_EXAMPLES_HELLO is not set - -# -# "Hello, World!" C++ Example -# # CONFIG_EXAMPLES_HELLOXX is not set - -# -# USB HID Keyboard Example -# +# CONFIG_EXAMPLES_JSON is not set # CONFIG_EXAMPLES_HIDKBD is not set - -# -# IGMP Example -# # CONFIG_EXAMPLES_IGMP is not set - -# -# LCD Read/Write Example -# # CONFIG_EXAMPLES_LCDRW is not set - -# -# Memory Management Example -# # CONFIG_EXAMPLES_MM is not set - -# -# File System Mount Example -# # CONFIG_EXAMPLES_MOUNT is not set - -# -# FreeModBus Example -# # CONFIG_EXAMPLES_MODBUS is not set - -# -# Network Test Example -# # CONFIG_EXAMPLES_NETTEST is not set - -# -# NuttShell (NSH) Example -# # CONFIG_EXAMPLES_NSH is not set - -# -# NULL Example -# # CONFIG_EXAMPLES_NULL is not set - -# -# NX Graphics Example -# # CONFIG_EXAMPLES_NX is not set - -# -# NxConsole Example -# # CONFIG_EXAMPLES_NXCONSOLE is not set - -# -# NXFFS File System Example -# # CONFIG_EXAMPLES_NXFFS is not set - -# -# NXFLAT Example -# # CONFIG_EXAMPLES_NXFLAT is not set - -# -# NX Graphics "Hello, World!" Example -# # CONFIG_EXAMPLES_NXHELLO is not set - -# -# NX Graphics image Example -# # CONFIG_EXAMPLES_NXIMAGE is not set - -# -# NX Graphics lines Example -# # CONFIG_EXAMPLES_NXLINES is not set - -# -# NX Graphics Text Example -# # CONFIG_EXAMPLES_NXTEXT is not set - -# -# OS Test Example -# # CONFIG_EXAMPLES_OSTEST is not set - -# -# Pascal "Hello, World!"example -# # CONFIG_EXAMPLES_PASHELLO is not set - -# -# Pipe Example -# # CONFIG_EXAMPLES_PIPE is not set - -# -# Poll Example -# # CONFIG_EXAMPLES_POLL is not set - -# -# Pulse Width Modulation (PWM) Example -# - -# -# Quadrature Encoder Example -# # CONFIG_EXAMPLES_QENCODER is not set - -# -# RGMP Example -# # CONFIG_EXAMPLES_RGMP is not set - -# -# ROMFS Example -# # CONFIG_EXAMPLES_ROMFS is not set - -# -# sendmail Example -# # CONFIG_EXAMPLES_SENDMAIL is not set - -# -# Serial Loopback Example -# # CONFIG_EXAMPLES_SERLOOP is not set - -# -# Telnet Daemon Example -# # CONFIG_EXAMPLES_TELNETD is not set - -# -# THTTPD Web Server Example -# # CONFIG_EXAMPLES_THTTPD is not set - -# -# TIFF Generation Example -# # CONFIG_EXAMPLES_TIFF is not set - -# -# Touchscreen Example -# # CONFIG_EXAMPLES_TOUCHSCREEN is not set - -# -# UDP Example -# # CONFIG_EXAMPLES_UDP is not set - -# -# UDP Discovery Daemon Example -# - -# -# uIP Web Server Example -# # CONFIG_EXAMPLES_UIP is not set - -# -# USB Serial Test Example -# # CONFIG_EXAMPLES_USBSERIAL is not set - -# -# USB Mass Storage Class Example -# # CONFIG_EXAMPLES_USBMSC is not set - -# -# USB Serial Terminal Example -# # CONFIG_EXAMPLES_USBTERM is not set - -# -# Watchdog timer Example -# # CONFIG_EXAMPLES_WATCHDOG is not set - -# -# wget Example -# - -# -# WLAN Example -# # CONFIG_EXAMPLES_WLAN is not set -# -# XML RPC Example -# - # # Interpreters # @@ -700,74 +495,19 @@ CONFIG_EXAMPLES_ELF_DEVPATH="/dev/ram0" # # Networking Utilities # - -# -# DHCP client -# # CONFIG_NETUTILS_DHCPC is not set - -# -# DHCP server -# # CONFIG_NETUTILS_DHCPD is not set - -# -# FTP client -# # CONFIG_NETUTILS_FTPC is not set - -# -# FTP server -# # CONFIG_NETUTILS_FTPD is not set - -# -# Name resolution -# +# CONFIG_NETUTILS_JSON is not set # CONFIG_NETUTILS_RESOLV is not set - -# -# SMTP -# # CONFIG_NETUTILS_SMTP is not set - -# -# TFTP client -# # CONFIG_NETUTILS_TELNETD is not set - -# -# TFTP client -# # CONFIG_NETUTILS_TFTPC is not set - -# -# THTTPD web server -# # CONFIG_NETUTILS_THTTPD is not set - -# -# uIP support library -# # CONFIG_NETUTILS_UIPLIB is not set - -# -# uIP web client -# # CONFIG_NETUTILS_WEBCLIENT is not set -# -# uIP web server -# - -# -# UDP Discovery Utility -# - -# -# XML-RPC library -# - # # ModBus # diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h index aa04adaf2d..4770d82a3f 100644 --- a/nuttx/include/nuttx/binfmt/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -59,6 +59,9 @@ /**************************************************************************** * Public Types ****************************************************************************/ +/* The type of one C++ constructor */ + +typedef FAR void (*elf_ctor_t)(void); /* This struct provides a desciption of the currently loaded instantiation * of an ELF binary. @@ -71,7 +74,7 @@ struct elf_loadinfo_s off_t filelen; /* Length of the entire ELF file */ int filfd; /* Descriptor for the file being loaded */ #ifdef CONFIG_ELF_CONSTRUCTORS - uintptr_t ctors; /* Location of static constructors in memory */ + elf_ctor_t ctors; /* Pointer to a list of constructors */ uint16_t nctors; /* Number of constructors */ #endif uint16_t symtabidx; /* Symbol table section index */ From 5681b615ec10265a27677bc2ca98fa385460afec Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 29 Oct 2012 19:32:05 +0000 Subject: [PATCH 042/206] C++ constructors work with ELF load now git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5273 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/elf/elf_main.c | 80 ++++- apps/examples/elf/tests/helloxx/Makefile | 124 ++++++++ apps/examples/elf/tests/helloxx/hello++1.cpp | 60 ++++ apps/examples/elf/tests/helloxx/hello++2.cpp | 123 ++++++++ apps/examples/elf/tests/helloxx/hello++3.cpp | 132 ++++++++ apps/examples/elf/tests/helloxx/hello++4.cpp | 150 +++++++++ nuttx/arch/arm/src/arm/up_elf.c | 1 + nuttx/arch/arm/src/armv7-m/up_elf.c | 1 + nuttx/binfmt/Kconfig | 7 + nuttx/binfmt/binfmt_dumpmodule.c | 10 +- nuttx/binfmt/binfmt_execmodule.c | 60 +++- nuttx/binfmt/binfmt_unloadmodule.c | 76 ++++- nuttx/binfmt/elf.c | 28 +- nuttx/binfmt/libelf/Kconfig | 7 - nuttx/binfmt/libelf/Make.defs | 8 +- nuttx/binfmt/libelf/libelf.h | 54 ++-- nuttx/binfmt/libelf/libelf_ctors.c | 290 +++++------------- nuttx/binfmt/libelf/libelf_load.c | 58 +--- nuttx/binfmt/libelf/libelf_sections.c | 284 +++++++++++++++++ nuttx/binfmt/libelf/libelf_uninit.c | 9 - nuttx/binfmt/libelf/libelf_unload.c | 20 ++ nuttx/binfmt/libnxflat/libnxflat_load.c | 18 -- nuttx/binfmt/nxflat.c | 12 +- nuttx/configs/stm32f4discovery/elf/Make.defs | 4 +- nuttx/configs/stm32f4discovery/elf/defconfig | 2 +- .../stm32f4discovery/scripts/gnu-elf.ld | 14 +- nuttx/include/nuttx/binfmt/binfmt.h | 25 +- nuttx/include/nuttx/binfmt/elf.h | 19 +- 28 files changed, 1282 insertions(+), 394 deletions(-) create mode 100644 apps/examples/elf/tests/helloxx/Makefile create mode 100644 apps/examples/elf/tests/helloxx/hello++1.cpp create mode 100644 apps/examples/elf/tests/helloxx/hello++2.cpp create mode 100644 apps/examples/elf/tests/helloxx/hello++3.cpp create mode 100644 apps/examples/elf/tests/helloxx/hello++4.cpp create mode 100644 nuttx/binfmt/libelf/libelf_sections.c diff --git a/apps/examples/elf/elf_main.c b/apps/examples/elf/elf_main.c index 23a6b2d212..669de430dd 100644 --- a/apps/examples/elf/elf_main.c +++ b/apps/examples/elf/elf_main.c @@ -41,6 +41,7 @@ #include #include + #include #include #include @@ -129,6 +130,9 @@ * Private Data ****************************************************************************/ +static unsigned int g_mminitial; /* Initial memory usage */ +static unsigned int g_mmstep; /* Memory Usage at beginning of test step */ + static const char delimiter[] = "****************************************************************************"; @@ -145,6 +149,53 @@ extern const int nexports; * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: mm_update + ****************************************************************************/ + +static void mm_update(FAR unsigned int *previous, FAR const char *msg) +{ + struct mallinfo mmcurrent; + + /* Get the current memory usage */ + +#ifdef CONFIG_CAN_PASS_STRUCTS + mmcurrent = mallinfo(); +#else + (void)mallinfo(&mmcurrent); +#endif + + /* Show the change from the previous time */ + + printf("\nMemory Usage %s:\n", msg); + printf(" Before: %8u After: %8u Change: %8d\n", + *previous, mmcurrent.uordblks, (int)mmcurrent.uordblks - (int)*previous); + + /* Set up for the next test */ + + *previous = mmcurrent.uordblks; +} + +/**************************************************************************** + * Name: mm_initmonitor + ****************************************************************************/ + +static void mm_initmonitor(void) +{ + struct mallinfo mmcurrent; + +#ifdef CONFIG_CAN_PASS_STRUCTS + mmcurrent = mallinfo(); +#else + (void)mallinfo(&mmcurrent); +#endif + + g_mminitial = mmcurrent.uordblks; + g_mmstep = mmcurrent.uordblks; + + printf("Initial memory usage: %d\n", mmcurrent.uordblks); +} + /**************************************************************************** * Name: testheader ****************************************************************************/ @@ -168,6 +219,10 @@ int elf_main(int argc, char *argv[]) int ret; int i; + /* Initialize the memory monitor */ + + mm_initmonitor(); + /* Initialize the ELF binary loader */ message("Initializing the ELF binary loader\n"); @@ -178,6 +233,8 @@ int elf_main(int argc, char *argv[]) exit(1); } + mm_update(&g_mmstep, "after elf_initialize"); + /* Create a ROM disk for the ROMFS filesystem */ message("Registering romdisk at /dev/ram%d\n", CONFIG_EXAMPLES_ELF_DEVMINOR); @@ -190,6 +247,8 @@ int elf_main(int argc, char *argv[]) exit(1); } + mm_update(&g_mmstep, "after romdisk_register"); + /* Mount the file system */ message("Mounting ROMFS filesystem at target=%s with source=%s\n", @@ -203,7 +262,9 @@ int elf_main(int argc, char *argv[]) elf_uninitialize(); } - /* Now excercise every progrm in the ROMFS file system */ + mm_update(&g_mmstep, "after mount"); + + /* Now excercise every program in the ROMFS file system */ for (i = 0; dirlist[i]; i++) { @@ -223,17 +284,26 @@ int elf_main(int argc, char *argv[]) exit(1); } + mm_update(&g_mmstep, "after load_module"); + ret = exec_module(&bin, 50); + + mm_update(&g_mmstep, "after exec_module"); + if (ret < 0) { err("ERROR: Failed to execute program '%s'\n", dirlist[i]); - unload_module(&bin); + } + else + { + message("Wait a bit for test completion\n"); + sleep(4); } - message("Wait a bit for test completion\n"); - sleep(4); + unload_module(&bin); + mm_update(&g_mmstep, "after unload_module"); } - message("End-of-Test.. Exiting\n"); + mm_update(&g_mmstep, "End-of-Test"); return 0; } diff --git a/apps/examples/elf/tests/helloxx/Makefile b/apps/examples/elf/tests/helloxx/Makefile new file mode 100644 index 0000000000..d115fbeaf4 --- /dev/null +++ b/apps/examples/elf/tests/helloxx/Makefile @@ -0,0 +1,124 @@ +############################################################################ +# examples/elf/tests/helloxx/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs + +BIN1 = hello++1 +BIN2 = hello++2 +ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) +BIN3 = hello++3 +endif +#BIN4 = hello++4 +ALL_BIN = $(BIN1) $(BIN2) $(BIN3) $(BIN4) + +SRCS1 = $(BIN1).c +OBJS1 = $(SRCS1:.c=.o) + +SRCS2 = $(BIN2).c +OBJS2 = $(SRCS2:.c=.o) + +ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) +SRCS3 = $(BIN3).c +OBJS3 = $(SRCS3:.c=.o) +endif + +#SRCS4 = $(BIN4).c +#OBJS4 = $(SRCS4:.c=.o) + +SRCS = $(SRCS1) $(SRCS2) $(SRCS3) $(SRCS4) +OBJS = $(OBJS1) $(OBJS2) $(OBJS3) $(OBJS4) + +LIBSTDC_STUBS_DIR = $(TOPDIR)/libxx +LIBSTDC_STUBS_LIB = $(LIBSTDC_STUBS_DIR)/liblibxx.a + +all: $(BIN1) $(BIN2) $(BIN3) $(BIN4) + +$(OBJS): %.o: %.cpp + @echo "CC: $<" + @$(CXX) -c $(CXXELFFLAGS) $< -o $@ + +# This contains libstdc++ stubs to that you can build C++ code +# without actually having libstdc++ + +$(LIBSTDC_STUBS_LIB): + @$(MAKE) -C $(LIBSTDC_STUBS_DIR) TOPDIR=$(TOPDIR) + +# BIN1 and BIN2 link just like C code because they contain no +# static constructors. BIN1 is equivalent to a C hello world; +# BIN2 contains a class that implements hello world, but it is +# not statically initialized. + +$(BIN1): $(OBJS1) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +$(BIN2): $(OBJS2) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ + +# BIN3 is equivalent to BIN2 except that is uses static initializers + +ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) +$(BIN3): $(OBJS3) + @echo "LD: $<" + @$(LD) $(LDELFFLAGS) -o $@ $^ +endif + +# BIN4 is similar to BIN3 except that it uses the streams code from libstdc++ +# +# NOTE: libstdc++ is not available for NuttX as of this writing +# +#$(BIN4): $(OBJS4) +# @echo "LD: $<" +# @$(LD) $(LDELFFLAGS) -o $@ $^ + +clean: + @rm -f $(ALL_BIN) *.o *~ .*.swp core + +install: $(ALL_BIN) + @install -D $(BIN1) $(ROMFS_DIR)/$(BIN1) + @install -D $(BIN2) $(ROMFS_DIR)/$(BIN2) +ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) + @install -D $(BIN3) $(ROMFS_DIR)/$(BIN3) +endif +# @install -D $(BIN4) $(ROMFS_DIR)/$(BIN4) + + + + + + + diff --git a/apps/examples/elf/tests/helloxx/hello++1.cpp b/apps/examples/elf/tests/helloxx/hello++1.cpp new file mode 100644 index 0000000000..9ab9d4dedf --- /dev/null +++ b/apps/examples/elf/tests/helloxx/hello++1.cpp @@ -0,0 +1,60 @@ +///////////////////////////////////////////////////////////////////////////// +// examples/elf/tests/helloxx/hello++1.c +// +// 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. +// +///////////////////////////////////////////////////////////////////////////// +// +// This is an trivial version of "Hello, World" program. It illustrates +// that we can build C programs using the C++ compiler. +// +// - Building a C++ program to use the C library +// - No class creation +// - NO Streams +// - NO Static constructor and destructors +// +///////////////////////////////////////////////////////////////////////////// + +///////////////////////////////////////////////////////////////////////////// +// Included Files +///////////////////////////////////////////////////////////////////////////// + +#include + +///////////////////////////////////////////////////////////////////////////// +// Public Functions +///////////////////////////////////////////////////////////////////////////// + +int main(int argc, char **argv) +{ + printf("Hello, World!\n"); + return 0; +} diff --git a/apps/examples/elf/tests/helloxx/hello++2.cpp b/apps/examples/elf/tests/helloxx/hello++2.cpp new file mode 100644 index 0000000000..f1268dda57 --- /dev/null +++ b/apps/examples/elf/tests/helloxx/hello++2.cpp @@ -0,0 +1,123 @@ +///////////////////////////////////////////////////////////////////////////// +// examples/elf/tests/helloxx/hello++2.c +// +// 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. +// +///////////////////////////////////////////////////////////////////////////// +// +// This is an another trivial version of "Hello, World" design. It illustrates +// +// - Building a C++ program to use the C library +// - Basic class creation +// - NO Streams +// - NO Static constructor and destructors +// +///////////////////////////////////////////////////////////////////////////// + +///////////////////////////////////////////////////////////////////////////// +// Included Files +///////////////////////////////////////////////////////////////////////////// + +#include + +///////////////////////////////////////////////////////////////////////////// +// Classes +///////////////////////////////////////////////////////////////////////////// + +class CThingSayer +{ + const char *szWhatToSay; +public: + CThingSayer(void) + { + printf("CThingSayer::CThingSayer: I am!\n"); + szWhatToSay = (const char*)NULL; + } + + ~CThingSayer(void) + { + printf("CThingSayer::~CThingSayer: I cease to be\n"); + if (szWhatToSay) + { + printf("CThingSayer::~CThingSayer: I will never say '%s' again\n", + szWhatToSay); + } + szWhatToSay = (const char*)NULL; + } + + void Initialize(const char *czSayThis) + { + printf("CThingSayer::Initialize: When told, I will say '%s'\n", + czSayThis); + szWhatToSay = czSayThis; + } + + void SayThing(void) + { + printf("CThingSayer::SayThing: I am now saying '%s'\n", szWhatToSay); + } +}; + +///////////////////////////////////////////////////////////////////////////// +// Public Functions +///////////////////////////////////////////////////////////////////////////// + +int main(int argc, char **argv) +{ + CThingSayer *MyThingSayer; + + printf("main: Started. Creating MyThingSayer\n"); + + // Create an instance of the CThingSayer class + // We should see the message from constructor, CThingSayer::CThingSayer(), + + MyThingSayer = new CThingSayer; + printf("main: Created MyThingSayer=0x%08lx\n", (long)MyThingSayer); + + // Tell MyThingSayer that "Hello, World!" is the string to be said + + printf("main: Calling MyThingSayer->Initialize\n");; + MyThingSayer->Initialize("Hello, World!"); + + // Tell MyThingSayer to say the thing we told it to say + + printf("main: Calling MyThingSayer->SayThing\n");; + MyThingSayer->SayThing(); + + // We should see the message from the destructor, + // CThingSayer::~CThingSayer(), AFTER we see the following + + printf("main: Destroying MyThingSayer\n"); + delete MyThingSayer; + + printf("main: Returning\n");; + return 0; +} diff --git a/apps/examples/elf/tests/helloxx/hello++3.cpp b/apps/examples/elf/tests/helloxx/hello++3.cpp new file mode 100644 index 0000000000..6661a3fd1e --- /dev/null +++ b/apps/examples/elf/tests/helloxx/hello++3.cpp @@ -0,0 +1,132 @@ +///////////////////////////////////////////////////////////////////////////// +// examples/elf/tests/helloxx/hello++3.c +// +// 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. +// +///////////////////////////////////////////////////////////////////////////// +// +// This is an another trivial version of "Hello, World" design. It illustrates +// +// - Building a C++ program to use the C library and stdio +// - Basic class creation with virtual methods. +// - Static constructor and destructors (in main program only) +// - NO Streams +// +///////////////////////////////////////////////////////////////////////////// + +///////////////////////////////////////////////////////////////////////////// +// Included Files +///////////////////////////////////////////////////////////////////////////// + +#include + +///////////////////////////////////////////////////////////////////////////// +// Classes +///////////////////////////////////////////////////////////////////////////// + +class CThingSayer +{ + const char *szWhatToSay; +public: + CThingSayer(void); + virtual ~CThingSayer(void); + virtual void Initialize(const char *czSayThis); + virtual void SayThing(void); +}; + +// A static instance of the CThingSayer class. This instance MUST +// be constructed by the system BEFORE the program is started at +// main() and must be destructed by the system AFTER the main() +// returns to the system + +static CThingSayer MyThingSayer; + +// These are implementations of the methods of the CThingSayer class + +CThingSayer::CThingSayer(void) +{ + printf("CThingSayer::CThingSayer: I am!\n"); + szWhatToSay = (const char*)NULL; +} + +CThingSayer::~CThingSayer(void) +{ + printf("CThingSayer::~CThingSayer: I cease to be\n"); + if (szWhatToSay) + { + printf("CThingSayer::~CThingSayer: I will never say '%s' again\n", + szWhatToSay); + } + szWhatToSay = (const char*)NULL; +} + +void CThingSayer::Initialize(const char *czSayThis) +{ + printf("CThingSayer::Initialize: When told, I will say '%s'\n", + czSayThis); + szWhatToSay = czSayThis; +} + +void CThingSayer::SayThing(void) +{ + printf("CThingSayer::SayThing: I am now saying '%s'\n", szWhatToSay); +} + +///////////////////////////////////////////////////////////////////////////// +// Public Functions +///////////////////////////////////////////////////////////////////////////// + +int main(int argc, char **argv) +{ + // We should see the message from constructor, CThingSayer::CThingSayer(), + // BEFORE we see the following messages. That is proof that the + // C++ static initializer is working + + printf("main: Started. MyThingSayer should already exist\n"); + + // Tell MyThingSayer that "Hello, World!" is the string to be said + + printf("main: Calling MyThingSayer.Initialize\n");; + MyThingSayer.Initialize("Hello, World!"); + + // Tell MyThingSayer to say the thing we told it to say + + printf("main: Calling MyThingSayer.SayThing\n");; + MyThingSayer.SayThing(); + + // We are finished, return. We should see the message from the + // destructor, CThingSayer::~CThingSayer(), AFTER we see the following + // message. That is proof that the C++ static destructor logic + // is working + + printf("main: Returning. MyThingSayer should be destroyed\n");; + return 0; +} diff --git a/apps/examples/elf/tests/helloxx/hello++4.cpp b/apps/examples/elf/tests/helloxx/hello++4.cpp new file mode 100644 index 0000000000..7db2564ed9 --- /dev/null +++ b/apps/examples/elf/tests/helloxx/hello++4.cpp @@ -0,0 +1,150 @@ +///////////////////////////////////////////////////////////////////////////// +// examples/elf/tests/helloxx/hello++4.c +// +// 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. +// +///////////////////////////////////////////////////////////////////////////// +// +// This is an excessively complex version of "Hello, World" design to +// illustrate some basic properties of C++: +// +// - Building a C++ program +// - Streams / statically linked libstdc++ +// - Static constructor and destructors (in main program only) +// +///////////////////////////////////////////////////////////////////////////// + +///////////////////////////////////////////////////////////////////////////// +// Included Files +///////////////////////////////////////////////////////////////////////////// + +#include +#include + +#ifndef NULL +# define NULL ((void*)0L) +#endif + +///////////////////////////////////////////////////////////////////////////// +// Classes +///////////////////////////////////////////////////////////////////////////// + +using namespace std; + +// A hello world sayer class + +class CThingSayer +{ + const char *szWhatToSay; +public: + CThingSayer(void); + virtual ~CThingSayer(void); + virtual void Initialize(const char *czSayThis); + virtual void SayThing(void); +}; + +///////////////////////////////////////////////////////////////////////////// +// Private Data +///////////////////////////////////////////////////////////////////////////// + +// A static instance of the CThingSayer class. This instance MUST +// be constructed by the system BEFORE the program is started at +// main() and must be destructed by the system AFTER the main() +// returns to the system + +static CThingSayer MyThingSayer; + +///////////////////////////////////////////////////////////////////////////// +// Method Implementations +///////////////////////////////////////////////////////////////////////////// + +// These are implementations of the methods of the CThingSayer class + +CThingSayer::CThingSayer(void) +{ + cout << "CThingSayer::CThingSayer: I am!" << endl; + szWhatToSay = (const char*)NULL; +} + +CThingSayer::~CThingSayer(void) +{ + cout << "CThingSayer::~CThingSayer: I cease to be" << endl; + if (szWhatToSay) + { + cout << "CThingSayer::~CThingSayer: I will never say '" + << szWhatToSay << "' again" << endl; + } + szWhatToSay = (const char*)NULL; +} + +void CThingSayer::Initialize(const char *czSayThis) +{ + cout << "CThingSayer::Initialize: When told, I will say '" + << czSayThis << "'" << endl; + szWhatToSay = czSayThis; +} + +void CThingSayer::SayThing(void) +{ + cout << "CThingSayer::SayThing: I am now saying '" + << szWhatToSay << "'" << endl; +} + +///////////////////////////////////////////////////////////////////////////// +// Public Functions +///////////////////////////////////////////////////////////////////////////// + +int main(int argc, char **argv) +{ + // We should see the message from constructor, CThingSayer::CThingSayer(), + // BEFORE we see the following messages. That is proof that the + // C++ static initializer is working + + cout << "main: Started" << endl; + + // Tell MyThingSayer that "Hello, World!" is the string to be said + + cout << "main: Calling MyThingSayer.Initialize" << endl; + MyThingSayer.Initialize("Hello, World!"); + + // Tell MyThingSayer to say the thing we told it to say + + cout << "main: Calling MyThingSayer.SayThing" << endl; + MyThingSayer.SayThing(); + + // We are finished, return. We should see the message from the + // destructor, CThingSayer::~CThingSayer(), AFTER we see the following + // message. That is proof that the C++ static destructor logic + // is working + + cout << "main: Returning" << endl; + return 0; +} diff --git a/nuttx/arch/arm/src/arm/up_elf.c b/nuttx/arch/arm/src/arm/up_elf.c index b78da02c19..2dd8366aa0 100644 --- a/nuttx/arch/arm/src/arm/up_elf.c +++ b/nuttx/arch/arm/src/arm/up_elf.c @@ -184,6 +184,7 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, break; case R_ARM_ABS32: + case R_ARM_TARGET1: /* New ABI: TARGET1 always treated as ABS32 */ { bvdbg("Performing ABS32 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value); diff --git a/nuttx/arch/arm/src/armv7-m/up_elf.c b/nuttx/arch/arm/src/armv7-m/up_elf.c index 1cc1fa32a2..b838a69057 100644 --- a/nuttx/arch/arm/src/armv7-m/up_elf.c +++ b/nuttx/arch/arm/src/armv7-m/up_elf.c @@ -178,6 +178,7 @@ int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, break; case R_ARM_ABS32: + case R_ARM_TARGET1: /* New ABI: TARGET1 always treated as ABS32 */ { bvdbg("Performing ABS32 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value); diff --git a/nuttx/binfmt/Kconfig b/nuttx/binfmt/Kconfig index 4d020163ee..ae02c276a1 100644 --- a/nuttx/binfmt/Kconfig +++ b/nuttx/binfmt/Kconfig @@ -34,6 +34,13 @@ endif endif +config BINFMT_CONSTRUCTORS + bool "C++ Static Constructor Support" + default n + depends on HAVE_CXX && ELF # FIX ME: Currently only supported for ELF + ---help--- + Build in support for C++ constructors in loaded modules. + config SYMTAB_ORDEREDBYNAME bool "Symbol Tables Ordered by Name" default n diff --git a/nuttx/binfmt/binfmt_dumpmodule.c b/nuttx/binfmt/binfmt_dumpmodule.c index 06e97e4572..e095c4a67a 100644 --- a/nuttx/binfmt/binfmt_dumpmodule.c +++ b/nuttx/binfmt/binfmt_dumpmodule.c @@ -1,7 +1,7 @@ /**************************************************************************** * binfmt/binfmt_dumpmodule.c * - * 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 @@ -90,8 +90,12 @@ int dump_module(FAR const struct binary_s *bin) bdbg(" filename: %s\n", bin->filename); bdbg(" argv: %p\n", bin->argv); bdbg(" entrypt: %p\n", bin->entrypt); - bdbg(" ispace: %p size=%d\n", bin->ispace, bin->isize); - bdbg(" dspace: %p\n", bin->dspace); + bdbg(" mapped: %p size=%d\n", bin->mapped, bin->mapsize); + bdbg(" alloc: %p %p\n", bin->alloc[0], bin->alloc[1]); +#ifdef CONFIG_BINFMT_CONSTRUCTORS + bdbg(" ctors: %p nctors=%d\n", bin->ctors, bin->nctors); + bdbg(" dtors: %p ndtors=%d\n", bin->dtors, bin->ndtors); +#endif bdbg(" stacksize: %d\n", bin->stacksize); } return OK; diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c index bc76d4acfc..b00248183b 100644 --- a/nuttx/binfmt/binfmt_execmodule.c +++ b/nuttx/binfmt/binfmt_execmodule.c @@ -70,6 +70,39 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: exec_ctors + * + * Description: + * Execute C++ static constructors. + * + * Input Parameters: + * loadinfo - Load state information + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +#ifdef CONFIG_BINFMT_CONSTRUCTORS +static inline void exec_ctors(FAR const struct binary_s *binp) +{ + elf_ctor_t *ctor = binp->ctors; + int i; + + /* Execute each constructor */ + + for (i = 0; i < binp->nctors; i++) + { + bvdbg("Calling ctor %d at %p\n", i, (FAR void *)ctor); + + (*ctor)(); + ctor++; + } +} +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -87,7 +120,7 @@ * ****************************************************************************/ -int exec_module(FAR const struct binary_s *bin, int priority) +int exec_module(FAR const struct binary_s *binp, int priority) { FAR _TCB *tcb; #ifndef CONFIG_CUSTOM_STACK @@ -100,14 +133,14 @@ int exec_module(FAR const struct binary_s *bin, int priority) /* Sanity checking */ #ifdef CONFIG_DEBUG - if (!bin || !bin->ispace || !bin->entrypt || bin->stacksize <= 0) + if (!binp || !binp->entrypt || binp->stacksize <= 0) { err = EINVAL; goto errout; } #endif - bdbg("Executing %s\n", bin->filename); + bdbg("Executing %s\n", binp->filename); /* Allocate a TCB for the new task. */ @@ -121,7 +154,7 @@ int exec_module(FAR const struct binary_s *bin, int priority) /* Allocate the stack for the new task */ #ifndef CONFIG_CUSTOM_STACK - stack = (FAR uint32_t*)malloc(bin->stacksize); + stack = (FAR uint32_t*)malloc(binp->stacksize); if (!tcb) { err = ENOMEM; @@ -130,11 +163,13 @@ int exec_module(FAR const struct binary_s *bin, int priority) /* Initialize the task */ - ret = task_init(tcb, bin->filename, priority, stack, bin->stacksize, bin->entrypt, bin->argv); + ret = task_init(tcb, binp->filename, priority, stack, + binp->stacksize, binp->entrypt, binp->argv); #else /* Initialize the task */ - ret = task_init(tcb, bin->filename, priority, stack, bin->entrypt, bin->argv); + ret = task_init(tcb, binp->filename, priority, stack, + binp->entrypt, binp->argv); #endif if (ret < 0) { @@ -143,10 +178,12 @@ int exec_module(FAR const struct binary_s *bin, int priority) goto errout_with_stack; } - /* Add the DSpace address as the PIC base address */ + /* Add the D-Space address as the PIC base address. By convention, this + * must be the first allocated address space. + */ #ifdef CONFIG_PIC - tcb->dspace = bin->dspace; + tcb->dspace = binp->alloc[0]; /* Re-initialize the task's initial state to account for the new PIC base */ @@ -157,6 +194,12 @@ int exec_module(FAR const struct binary_s *bin, int priority) pid = tcb->pid; + /* Execute all of the C++ static constructors */ + +#ifdef CONFIG_BINFMT_CONSTRUCTORS + exec_ctors(binp); +#endif + /* Then activate the task at the provided priority */ ret = task_activate(tcb); @@ -166,6 +209,7 @@ int exec_module(FAR const struct binary_s *bin, int priority) bdbg("task_activate() failed: %d\n", err); goto errout_with_stack; } + return (int)pid; errout_with_stack: diff --git a/nuttx/binfmt/binfmt_unloadmodule.c b/nuttx/binfmt/binfmt_unloadmodule.c index 0de9dfccd1..15b2383570 100644 --- a/nuttx/binfmt/binfmt_unloadmodule.c +++ b/nuttx/binfmt/binfmt_unloadmodule.c @@ -1,7 +1,7 @@ /**************************************************************************** * binfmt/binfmt_loadmodule.c * - * 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 @@ -67,6 +67,39 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: exec_dtors + * + * Description: + * Execute C++ static constructors. + * + * Input Parameters: + * loadinfo - Load state information + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +#ifdef CONFIG_BINFMT_CONSTRUCTORS +static inline void exec_dtors(FAR const struct binary_s *binp) +{ + elf_dtor_t *dtor = binp->dtors; + int i; + + /* Execute each destructor */ + + for (i = 0; i < binp->ndtors; i++) + { + bvdbg("Calling dtor %d at %p\n", i, (FAR void *)dtor); + + (*dtor)(); + dtor++; + } +} +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -76,7 +109,12 @@ * * Description: * Unload a (non-executing) module from memory. If the module has - * been started (via exec_module), calling this will be fatal. + * been started (via exec_module) and has not exited, calling this will + * be fatal. + * + * However, this function must be called after the module exist. How + * this is done is up to your logic. Perhaps you register it to be + * called by on_exit()? * * Returned Value: * This is a NuttX internal function so it follows the convention that @@ -85,22 +123,40 @@ * ****************************************************************************/ -int unload_module(FAR const struct binary_s *bin) +int unload_module(FAR const struct binary_s *binp) { - if (bin) + int i; + + if (binp) { - if (bin->ispace) + + /* Execute C++ desctructors */ + +#ifdef CONFIG_BINFMT_CONSTRUCTORS + exec_dtors(binp); +#endif + + /* Unmap mapped address spaces */ + + if (binp->mapped) { - bvdbg("Unmapping ISpace: %p\n", bin->ispace); - munmap(bin->ispace, bin->isize); + bvdbg("Unmapping address space: %p\n", binp->mapped); + + munmap(binp->mapped, binp->mapsize); } - if (bin->dspace) + /* Free allocated address spaces */ + + for (i = 0; i < BINFMT_NALLOC; i++) { - bvdbg("Freeing DSpace: %p\n", bin->dspace); - free(bin->dspace); + if (binp->alloc[i]) + { + bvdbg("Freeing alloc[%d]: %p\n", i, binp->alloc[i]); + free(binp->alloc[i]); + } } } + return OK; } diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c index 57123ed95d..26057ffc10 100644 --- a/nuttx/binfmt/elf.c +++ b/nuttx/binfmt/elf.c @@ -114,7 +114,7 @@ static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo) bdbg(" alloc: %08lx\n", (long)loadinfo->alloc); bdbg(" allocsize: %ld\n", (long)loadinfo->allocsize); bdbg(" filelen: %ld\n", (long)loadinfo->filelen); -#ifdef CONFIG_ELF_CONSTRUCTORS +#ifdef CONFIG_BINFMT_CONSTRUCTORS bdbg(" ctors: %08lx\n", (long)loadinfo->ctors); bdbg(" nctors: %d\n", loadinfo->nctors); #endif @@ -211,13 +211,31 @@ static int elf_loadbinary(struct binary_s *binp) /* Return the load information */ binp->entrypt = (main_t)(loadinfo.alloc + loadinfo.ehdr.e_entry); - binp->ispace = (void*)loadinfo.alloc; - binp->dspace = NULL; - binp->isize = loadinfo.allocsize; + binp->alloc[0] = (FAR void *)loadinfo.alloc; binp->stacksize = CONFIG_ELF_STACKSIZE; +#ifdef CONFIG_BINFMT_CONSTRUCTORS + /* Save information about constructors. NOTE: desctructors are not + * yet supported. + */ + + binp->ctors = loadinfo.ctors; + binp->nctors = loadinfo.nctors; + + /* Was memory allocated for constructors? */ + + if (!loadinfo.newabi) + { + /* Yes.. save the allocation address so that it can be freed by + * unload module. + */ + + binp->alloc[1] = (FAR void *)loadinfo.ctors; + } +#endif + elf_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt, - MIN(binp->isize - loadinfo.ehdr.e_entry, 512)); + MIN(loadinfo.allocsize - loadinfo.ehdr.e_entry, 512)); elf_uninit(&loadinfo); return OK; diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig index 5dc4a2d9fe..f6f579276c 100644 --- a/nuttx/binfmt/libelf/Kconfig +++ b/nuttx/binfmt/libelf/Kconfig @@ -32,13 +32,6 @@ config ELF_BUFFERINCR will need to be read (such as symbol names). This value specifies the size increment to use each time the buffer is reallocated. Default: 32 -config ELF_CONSTRUCTORS - bool "C++ Static Constructor Support" - default n - depends on HAVE_CXX - ---help--- - Build in support for C++ constructors in ELF modules. - config ELF_DUMPBUFFER bool "Dump ELF buffers" default n diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs index cf2507a995..26198ade2a 100644 --- a/nuttx/binfmt/libelf/Make.defs +++ b/nuttx/binfmt/libelf/Make.defs @@ -41,11 +41,11 @@ BINFMT_CSRCS += elf.c # ELF library -BINFMT_CSRCS += libelf_init.c libelf_uninit.c libelf_load.c \ - libelf_unload.c libelf_verify.c libelf_read.c \ - libelf_bind.c libelf_symbols.c libelf_iobuffer.c +BINFMT_CSRCS += libelf_bind.c libelf_init.c libelf_iobuffer.c libelf_load.c \ + libelf_read.c libelf_sections.c libelf_symbols.c libelf_uninit.c \ + libelf_unload.c libelf_verify.c -ifeq ($(CONFIG_ELF_CONSTRUCTORS),y) +ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) BINFMT_CSRCS += libelf_ctors.c endif diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h index 0d13515cc9..bea92496ab 100644 --- a/nuttx/binfmt/libelf/libelf.h +++ b/nuttx/binfmt/libelf/libelf.h @@ -85,6 +85,39 @@ int elf_verifyheader(FAR const Elf32_Ehdr *header); int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer, size_t readsize, off_t offset); +/**************************************************************************** + * Name: elf_loadshdrs + * + * Description: + * Loads section headers into memory. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo); + +/**************************************************************************** + * Name: elf_findsection + * + * Description: + * A section by its name. + * + * Input Parameters: + * loadinfo - Load state information + * sectname - Name of the section to find + * + * Returned Value: + * On success, the index to the section is returned; A negated errno value + * is returned on failure. + * + ****************************************************************************/ + +int elf_findsection(FAR struct elf_loadinfo_s *loadinfo, + FAR const char *sectname); + /**************************************************************************** * Name: elf_findsymtab * @@ -199,27 +232,8 @@ int elf_reallocbuffer(FAR struct elf_loadinfo_s *loadinfo, size_t increment); * ****************************************************************************/ -#ifdef CONFIG_ELF_CONSTRUCTORS +#ifdef CONFIG_BINFMT_CONSTRUCTORS int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo); #endif -/**************************************************************************** - * Name: elf_doctors - * - * Description: - * Execute C++ static constructors. - * - * Input Parameters: - * loadinfo - Load state information - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -#ifdef CONFIG_ELF_CONSTRUCTORS -int elf_doctors(FAR struct elf_loadinfo_s *loadinfo); -#endif - #endif /* __BINFMT_LIBELF_LIBELF_H */ diff --git a/nuttx/binfmt/libelf/libelf_ctors.c b/nuttx/binfmt/libelf/libelf_ctors.c index c53923d44f..a57fc37d93 100644 --- a/nuttx/binfmt/libelf/libelf_ctors.c +++ b/nuttx/binfmt/libelf/libelf_ctors.c @@ -49,7 +49,7 @@ #include "libelf.h" -#ifdef CONFIG_ELF_CONSTRUCTORS +#ifdef CONFIG_BINFMT_CONSTRUCTORS /**************************************************************************** * Pre-Processor Definitions @@ -67,166 +67,6 @@ * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: elf_sectname - * - * Description: - * Get the symbol name in loadinfo->iobuffer[]. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -static inline int elf_sectname(FAR struct elf_loadinfo_s *loadinfo, - FAR const Elf32_Shdr *shdr) -{ - FAR Elf32_Shdr *shstr; - FAR uint8_t *buffer; - off_t offset; - size_t readlen; - size_t bytesread; - int shstrndx; - int ret; - - /* Get the section header table index of the entry associated with the - * section name string table. If the file has no section name string table, - * this member holds the value SH_UNDEF. - */ - - shstrndx = loadinfo->ehdr.e_shstrndx; - if (shstrndx == SHN_UNDEF) - { - bdbg("No section header string table\n"); - return -EINVAL; - } - - /* Get the section name string table section header */ - - shstr = &loadinfo->shdr[shstrndx]; - - /* Get the file offset to the string that is the name of the section. This - * is the sum of: - * - * shstr->sh_offset: The file offset to the first byte of the section - * header string table data. - * shdr->sh_name: The offset to the name of the section in the section - * name table - */ - - offset = shstr->sh_offset + shdr->sh_name; - - /* Loop until we get the entire section name into memory */ - - buffer = loadinfo->iobuffer; - bytesread = 0; - - for (;;) - { - /* Get the number of bytes to read */ - - readlen = loadinfo->buflen - bytesread; - if (offset + readlen > loadinfo->filelen) - { - readlen = loadinfo->filelen - offset; - if (readlen <= 0) - { - bdbg("At end of file\n"); - return -EINVAL; - } - } - - /* Read that number of bytes into the array */ - - buffer = &loadinfo->iobuffer[bytesread]; - ret = elf_read(loadinfo, buffer, readlen, offset); - if (ret < 0) - { - bdbg("Failed to read section name\n"); - return ret; - } - - bytesread += readlen; - - /* Did we read the NUL terminator? */ - - if (memchr(buffer, '\0', readlen) != NULL) - { - /* Yes, the buffer contains a NUL terminator. */ - - return OK; - } - - /* No.. then we have to read more */ - - ret = elf_reallocbuffer(loadinfo, CONFIG_ELF_BUFFERINCR); - if (ret < 0) - { - bdbg("elf_reallocbuffer failed: %d\n", ret); - return ret; - } - } - - /* We will not get here */ - - return OK; -} - -/**************************************************************************** - * Name: elf_findctors - * - * Description: - * Find C++ static constructors. - * - * Input Parameters: - * loadinfo - Load state information - * - * Returned Value: - * On success, the index to the CTOR section is returned; A negated errno - * value is returned on failure. - * - ****************************************************************************/ - -static inline int elf_findctors(FAR struct elf_loadinfo_s *loadinfo) -{ - FAR const Elf32_Shdr *shdr; - int ret; - int i; - - /* Search through the shdr[] array in loadinfo for a section named .ctors */ - - for (i = 0; i < loadinfo->ehdr.e_shnum; i++) - { - /* Get the name of this section */ - - shdr = &loadinfo->shdr[i]; - ret = elf_sectname(loadinfo, shdr); - if (ret < 0) - { - bdbg("elf_sectname failed: %d\n", ret); - return ret; - } - - /* Check if the name of this section if ".ctors" */ - - bvdbg("%d. Comparing \"%s\" and .ctors\"\n", i, loadinfo->iobuffer); - - if (strcmp(".ctors", (FAR const char *)loadinfo->iobuffer) == 0) - { - /* We found it... return the index */ - - return i; - } - } - - /* We failed to find the .ctors sections. This may not be an error; maybe - * there are no static constructors. - */ - - return -ENOENT; -} - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -267,16 +107,21 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) return -ENOMEM; } - /* Find the index to the section named ".ctors" */ + /* Find the index to the section named ".ctors." NOTE: On old ABI system, + * .ctors is the name of the section containing the list of constructors; + * On newer systems, the similar section is called .init_array. It is + * expected that the linker script will force the sectino name to be ".ctors" + * in either case. + */ - ctoridx = elf_findctors(loadinfo); + ctoridx = elf_findsection(loadinfo, ".ctors"); if (ctoridx < 0) { /* This may not be a failure. -ENOENT indicates that the file has no * static constructor section. */ - bvdbg("elf_findctors failed: %d\n", ctoridx); + bvdbg("elf_findsection .ctors section failed: %d\n", ctoridx); return ret == -ENOENT ? OK : ret; } @@ -286,7 +131,9 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) shdr = &loadinfo->shdr[ctoridx]; - /* Allocate memory to hold a copy of the .ctor section */ + /* Get the size of the .ctor section and the number of constructors that + * will need to be called. + */ ctorsize = shdr->sh_size; loadinfo->nctors = ctorsize / sizeof(elf_ctor_t); @@ -302,71 +149,72 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) { /* Check an assumption that we made above */ - DEBUGASSERT(shdr->sh_entsize == sizeof(elf_ctor_t)); + DEBUGASSERT(shdr->sh_size == loadinfo->nctors * sizeof(elf_ctor_t)); - loadinfo->ctors = (elf_ctor_t)kmalloc(ctorsize); - if (!loadinfo->ctors) + /* In the old ABI, the .ctors section is not allocated. In that case, + * we need to allocate memory to hold the .ctors and then copy the + * from the file into the allocated memory. + * + * SHF_ALLOC indicates that the section requires memory during + * execution. + */ + + if ((shdr->sh_flags & SHF_ALLOC) == 0) { - bdbg("Failed to allocate memory for .ctors\n"); - return -ENOMEM; + /* Not loaded -> Old ABI. */ + + loadinfo->newabi = false; + + /* Allocate memory to hold a copy of the .ctor section */ + + loadinfo->ctors = (elf_ctor_t*)kmalloc(ctorsize); + if (!loadinfo->ctors) + { + bdbg("Failed to allocate memory for .ctors\n"); + return -ENOMEM; + } + + /* Read the section header table into memory */ + + ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->ctors, ctorsize, + shdr->sh_offset); + if (ret < 0) + { + bdbg("Failed to allocate .ctors: %d\n", ret); + return ret; + } + + /* Fix up all of the .ctor addresses. Since the addresses + * do not lie in allocated memory, there will be no relocation + * section for them. + */ + + for (i = 0; i < loadinfo->nctors; i++) + { + FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->ctors)[i]); + + bvdbg("ctor %d: %08lx + %08lx = %08lx\n", + i, *ptr, loadinfo->alloc, *ptr + loadinfo->alloc); + + *ptr += loadinfo->alloc; + } } - - /* Read the section header table into memory */ - - ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->ctors, ctorsize, - shdr->sh_offset); - if (ret < 0) + else { - bdbg("Failed to allocate .ctors: %d\n", ret); - } + /* Loaded -> New ABI. */ - /* Fix up all of the .ctor addresses */ + loadinfo->newabi = true; - for (i = 0; i < loadinfo->nctors; i++) - { - FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->ctors)[i]); - - bvdbg("ctor %d: %08lx + %08lx = %08lx\n", i, - *ptr, loadinfo->alloc, *ptr + loadinfo->alloc); - - *ptr += loadinfo->alloc; + /* Save the address of the .ctors (actually, .init_array) where it was + * loaded into memory. Since the .ctors lie in allocated memory, they + * will be relocated via the normal mechanism. + */ + + loadinfo->ctors = (elf_ctor_t*)shdr->sh_addr; } } return OK; } -/**************************************************************************** - * Name: elf_doctors - * - * Description: - * Execute C++ static constructors. - * - * Input Parameters: - * loadinfo - Load state information - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_doctors(FAR struct elf_loadinfo_s *loadinfo) -{ - elf_ctor_t ctor = (elf_ctor_t)loadinfo->ctors; - int i; - - /* Execute each constructor */ - - for (i = 0; i < loadinfo->nctors; i++) - { - bvdbg("Calling ctor %d at %p\n", i, (FAR void *)ctor); - - ctor(); - ctor++; - } - - return OK; -} - -#endif /* CONFIG_ELF_CONSTRUCTORS */ +#endif /* CONFIG_BINFMT_CONSTRUCTORS */ diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 505e2c8131..221ae8d438 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -75,62 +75,6 @@ * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: elf_loadshdrs - * - * Description: - * Loads section headers into memory. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) -{ - size_t shdrsize; - int ret; - - DEBUGASSERT(loadinfo->shdr == NULL); - - /* Verify that there are sections */ - - if (loadinfo->ehdr.e_shnum < 1) - { - bdbg("No sections(?)\n"); - return -EINVAL; - } - - /* Get the total size of the section header table */ - - shdrsize = (size_t)loadinfo->ehdr.e_shentsize * (size_t)loadinfo->ehdr.e_shnum; - if(loadinfo->ehdr.e_shoff + shdrsize > loadinfo->filelen) - { - bdbg("Insufficent space in file for section header table\n"); - return -ESPIPE; - } - - /* Allocate memory to hold a working copy of the sector header table */ - - loadinfo->shdr = (FAR Elf32_Shdr*)kmalloc(shdrsize); - if (!loadinfo->shdr) - { - bdbg("Failed to allocate the section header table. Size: %ld\n", (long)shdrsize); - return -ENOMEM; - } - - /* Read the section header table into memory */ - - ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->shdr, shdrsize, loadinfo->ehdr.e_shoff); - if (ret < 0) - { - bdbg("Failed to read section header table: %d\n", ret); - } - - return ret; -} - /**************************************************************************** * Name: elf_allocsize * @@ -292,7 +236,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) /* Find static constructors. */ -#ifdef CONFIG_ELF_CONSTRUCTORS +#ifdef CONFIG_BINFMT_CONSTRUCTORS ret = elf_loadctors(loadinfo); if (ret < 0) { diff --git a/nuttx/binfmt/libelf/libelf_sections.c b/nuttx/binfmt/libelf/libelf_sections.c new file mode 100644 index 0000000000..c417935446 --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_sections.c @@ -0,0 +1,284 @@ +/**************************************************************************** + * binfmt/libelf/libelf_sections.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include "libelf.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_sectname + * + * Description: + * Get the symbol name in loadinfo->iobuffer[]. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +static inline int elf_sectname(FAR struct elf_loadinfo_s *loadinfo, + FAR const Elf32_Shdr *shdr) +{ + FAR Elf32_Shdr *shstr; + FAR uint8_t *buffer; + off_t offset; + size_t readlen; + size_t bytesread; + int shstrndx; + int ret; + + /* Get the section header table index of the entry associated with the + * section name string table. If the file has no section name string table, + * this member holds the value SH_UNDEF. + */ + + shstrndx = loadinfo->ehdr.e_shstrndx; + if (shstrndx == SHN_UNDEF) + { + bdbg("No section header string table\n"); + return -EINVAL; + } + + /* Get the section name string table section header */ + + shstr = &loadinfo->shdr[shstrndx]; + + /* Get the file offset to the string that is the name of the section. This + * is the sum of: + * + * shstr->sh_offset: The file offset to the first byte of the section + * header string table data. + * shdr->sh_name: The offset to the name of the section in the section + * name table + */ + + offset = shstr->sh_offset + shdr->sh_name; + + /* Loop until we get the entire section name into memory */ + + buffer = loadinfo->iobuffer; + bytesread = 0; + + for (;;) + { + /* Get the number of bytes to read */ + + readlen = loadinfo->buflen - bytesread; + if (offset + readlen > loadinfo->filelen) + { + readlen = loadinfo->filelen - offset; + if (readlen <= 0) + { + bdbg("At end of file\n"); + return -EINVAL; + } + } + + /* Read that number of bytes into the array */ + + buffer = &loadinfo->iobuffer[bytesread]; + ret = elf_read(loadinfo, buffer, readlen, offset); + if (ret < 0) + { + bdbg("Failed to read section name\n"); + return ret; + } + + bytesread += readlen; + + /* Did we read the NUL terminator? */ + + if (memchr(buffer, '\0', readlen) != NULL) + { + /* Yes, the buffer contains a NUL terminator. */ + + return OK; + } + + /* No.. then we have to read more */ + + ret = elf_reallocbuffer(loadinfo, CONFIG_ELF_BUFFERINCR); + if (ret < 0) + { + bdbg("elf_reallocbuffer failed: %d\n", ret); + return ret; + } + } + + /* We will not get here */ + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_loadshdrs + * + * Description: + * Loads section headers into memory. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) +{ + size_t shdrsize; + int ret; + + DEBUGASSERT(loadinfo->shdr == NULL); + + /* Verify that there are sections */ + + if (loadinfo->ehdr.e_shnum < 1) + { + bdbg("No sections(?)\n"); + return -EINVAL; + } + + /* Get the total size of the section header table */ + + shdrsize = (size_t)loadinfo->ehdr.e_shentsize * (size_t)loadinfo->ehdr.e_shnum; + if(loadinfo->ehdr.e_shoff + shdrsize > loadinfo->filelen) + { + bdbg("Insufficent space in file for section header table\n"); + return -ESPIPE; + } + + /* Allocate memory to hold a working copy of the sector header table */ + + loadinfo->shdr = (FAR Elf32_Shdr*)kmalloc(shdrsize); + if (!loadinfo->shdr) + { + bdbg("Failed to allocate the section header table. Size: %ld\n", (long)shdrsize); + return -ENOMEM; + } + + /* Read the section header table into memory */ + + ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->shdr, shdrsize, loadinfo->ehdr.e_shoff); + if (ret < 0) + { + bdbg("Failed to read section header table: %d\n", ret); + } + + return ret; +} + +/**************************************************************************** + * Name: elf_findsection + * + * Description: + * A section by its name. + * + * Input Parameters: + * loadinfo - Load state information + * sectname - Name of the section to find + * + * Returned Value: + * On success, the index to the section is returned; A negated errno value + * is returned on failure. + * + ****************************************************************************/ + +int elf_findsection(FAR struct elf_loadinfo_s *loadinfo, + FAR const char *sectname) +{ + FAR const Elf32_Shdr *shdr; + int ret; + int i; + + /* Search through the shdr[] array in loadinfo for a section named 'sectname' */ + + for (i = 0; i < loadinfo->ehdr.e_shnum; i++) + { + /* Get the name of this section */ + + shdr = &loadinfo->shdr[i]; + ret = elf_sectname(loadinfo, shdr); + if (ret < 0) + { + bdbg("elf_sectname failed: %d\n", ret); + return ret; + } + + /* Check if the name of this section is 'sectname' */ + + bvdbg("%d. Comparing \"%s\" and .\"%s\"\n", + i, loadinfo->iobuffer, sectname); + + if (strcmp((FAR const char *)loadinfo->iobuffer, sectname) == 0) + { + /* We found it... return the index */ + + return i; + } + } + + /* We failed to find a section with this name. */ + + return -ENOENT; +} diff --git a/nuttx/binfmt/libelf/libelf_uninit.c b/nuttx/binfmt/libelf/libelf_uninit.c index 06bb896816..3ec6f6c61c 100644 --- a/nuttx/binfmt/libelf/libelf_uninit.c +++ b/nuttx/binfmt/libelf/libelf_uninit.c @@ -115,15 +115,6 @@ int elf_freebuffers(struct elf_loadinfo_s *loadinfo) loadinfo->shdr = NULL; } -#ifdef CONFIG_ELF_CONSTRUCTORS - if (loadinfo->ctors) - { - kfree((FAR void *)loadinfo->ctors); - loadinfo->ctors = NULL; - loadinfo->nctors = 0; - } -#endif - if (loadinfo->iobuffer) { kfree((FAR void *)loadinfo->iobuffer); diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c index d7a8827111..8102f7bf2f 100644 --- a/nuttx/binfmt/libelf/libelf_unload.c +++ b/nuttx/binfmt/libelf/libelf_unload.c @@ -91,6 +91,26 @@ int elf_unload(struct elf_loadinfo_s *loadinfo) loadinfo->allocsize = 0; } + /* Release any allocated constructor memory */ + +#ifdef CONFIG_BINFMT_CONSTRUCTORS + if (loadinfo->ctors) + { + /* In the old ABI, the .ctors section is not make for allocation. In + * that case, we need to free the working buffer that was used to hold + * the constructors. + */ + + if (!loadinfo->newabi) + { + kfree((FAR void *)loadinfo->ctors); + } + + loadinfo->ctors = NULL; + loadinfo->nctors = 0; + } +#endif + return OK; } diff --git a/nuttx/binfmt/libnxflat/libnxflat_load.c b/nuttx/binfmt/libnxflat/libnxflat_load.c index 02f035072d..b6693ea36a 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_load.c +++ b/nuttx/binfmt/libnxflat/libnxflat_load.c @@ -62,24 +62,6 @@ * Private Constant Data ****************************************************************************/ -#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_BINFMT) -static const char g_relocrel32i[] = "RELOC_REL32I"; -static const char g_relocrel32d[] = "RELOC_REL32D"; -static const char g_relocabs32[] = "RELOC_AB32"; -static const char g_undefined[] = "UNDEFINED"; - -static const char *g_reloctype[] = -{ - g_relocrel32i, - g_relocrel32d, - g_relocabs32, - g_undefined -}; -# define RELONAME(rl) g_reloctype[NXFLAT_RELOC_TYPE(rl)] -#else -# define RELONAME(rl) "(no name)" -#endif - /**************************************************************************** * Private Functions ****************************************************************************/ diff --git a/nuttx/binfmt/nxflat.c b/nuttx/binfmt/nxflat.c index 8d0ecfdcd9..5973a96a98 100644 --- a/nuttx/binfmt/nxflat.c +++ b/nuttx/binfmt/nxflat.c @@ -181,16 +181,18 @@ static int nxflat_loadbinary(struct binary_s *binp) goto errout_with_load; } - /* Return the load information */ + /* Return the load information. By convention, D-space address + * space is stored as the first allocated memory. + */ binp->entrypt = (main_t)(loadinfo.ispace + loadinfo.entryoffs); - binp->ispace = (void*)loadinfo.ispace; - binp->dspace = (void*)loadinfo.dspace; - binp->isize = loadinfo.isize; + binp->mapped = (void*)loadinfo.ispace; + binp->alloc[0] = (void*)loadinfo.dspace; + binp->mapsize = loadinfo.isize; binp->stacksize = loadinfo.stacksize; nxflat_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt, - MIN(binp->isize - loadinfo.entryoffs,512)); + MIN(loadinfo.isize - loadinfo.entryoffs, 512)); nxflat_uninit(&loadinfo); return OK; diff --git a/nuttx/configs/stm32f4discovery/elf/Make.defs b/nuttx/configs/stm32f4discovery/elf/Make.defs index 7df9b13da6..035a03e71a 100644 --- a/nuttx/configs/stm32f4discovery/elf/Make.defs +++ b/nuttx/configs/stm32f4discovery/elf/Make.defs @@ -160,8 +160,8 @@ LDNXFLATFLAGS = -e main -s 2048 # ELF module definitions -CELFFLAGS = $(CFLAGS) -mlong-calls -CXXELFFLAGS = $(CXXFLAGS) -mlong-calls +CELFFLAGS = $(CFLAGS) -mlong-calls # --target1-abs +CXXELFFLAGS = $(CXXFLAGS) -mlong-calls # --target1-abs LDELFFLAGS = -r -e main ifeq ($(WINTOOL),y) diff --git a/nuttx/configs/stm32f4discovery/elf/defconfig b/nuttx/configs/stm32f4discovery/elf/defconfig index 59c221a0ca..67f5bf365a 100644 --- a/nuttx/configs/stm32f4discovery/elf/defconfig +++ b/nuttx/configs/stm32f4discovery/elf/defconfig @@ -388,7 +388,7 @@ CONFIG_ELF_ALIGN_LOG2=2 CONFIG_ELF_STACKSIZE=2048 CONFIG_ELF_BUFFERSIZE=128 CONFIG_ELF_BUFFERINCR=32 -CONFIG_ELF_CONSTRUCTORS=y +CONFIG_BINFMT_CONSTRUCTORS=y CONFIG_SYMTAB_ORDEREDBYNAME=y # diff --git a/nuttx/configs/stm32f4discovery/scripts/gnu-elf.ld b/nuttx/configs/stm32f4discovery/scripts/gnu-elf.ld index 0153cf5fad..1f29f02f5b 100644 --- a/nuttx/configs/stm32f4discovery/scripts/gnu-elf.ld +++ b/nuttx/configs/stm32f4discovery/scripts/gnu-elf.ld @@ -51,8 +51,8 @@ SECTIONS */ *(.gnu.linkonce.t.*) - *(.init) - *(.fini) + *(.init) /* Old ABI */ + *(.fini) /* Old ABI */ _etext = . ; } @@ -86,15 +86,17 @@ SECTIONS .ctors : { - _sctros = . ; - *(.ctors) + _sctors = . ; + *(.ctors) /* Old ABI: Unallocated */ + *(.init_array) /* New ABI: Allocated */ _edtors = . ; } - .ctors : + .dtors : { _sdtors = . ; - *(.dtors) + *(.dtors) /* Old ABI: Unallocated */ + *(.fini_array) /* New ABI: Allocated */ _edtors = . ; } diff --git a/nuttx/include/nuttx/binfmt/binfmt.h b/nuttx/include/nuttx/binfmt/binfmt.h index 82e5f3557c..0c18bfc49a 100644 --- a/nuttx/include/nuttx/binfmt/binfmt.h +++ b/nuttx/include/nuttx/binfmt/binfmt.h @@ -49,9 +49,15 @@ * Pre-processor Definitions ****************************************************************************/ +#define BINFMT_NALLOC 2 + /**************************************************************************** * Public Types ****************************************************************************/ +/* The type of one C++ constructor or destructor */ + +typedef FAR void (*elf_ctor_t)(void); +typedef FAR void (*elf_dtor_t)(void); /* This describes the file to be loaded */ @@ -70,9 +76,15 @@ struct binary_s */ main_t entrypt; /* Entry point into a program module */ - FAR void *ispace; /* Memory-mapped, I-space (.text) address */ - FAR struct dspace_s *dspace; /* Address of the allocated .data/.bss space */ - size_t isize; /* Size of the I-space region (needed for munmap) */ + FAR void *mapped; /* Memory-mapped, address space */ + FAR void *alloc[BINFMT_NALLOC]; /* Allocated address spaces */ +#ifdef CONFIG_BINFMT_CONSTRUCTORS + elf_ctor_t *ctors; /* Pointer to a list of constructors */ + elf_dtor_t *dtors; /* Pointer to a list of destructors */ + uint16_t nctors; /* Number of constructors in the list */ + uint16_t ndtors; /* Number of destructors in the list */ +#endif + size_t mapsize; /* Size of the mapped address region (needed for munmap) */ size_t stacksize; /* Size of the stack in bytes (unallocated) */ }; @@ -151,7 +163,12 @@ EXTERN int load_module(FAR struct binary_s *bin); * * Description: * Unload a (non-executing) module from memory. If the module has - * been started (via exec_module), calling this will be fatal. + * been started (via exec_module) and has not exited, calling this will + * be fatal. + * + * However, this function must be called after the module exist. How + * this is done is up to your logic. Perhaps you register it to be + * called by on_exit()? * * Returned Value: * This is a NuttX internal function so it follows the convention that diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h index 4770d82a3f..2e3cb86236 100644 --- a/nuttx/include/nuttx/binfmt/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -43,10 +43,13 @@ #include #include + #include #include #include +#include + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -59,9 +62,6 @@ /**************************************************************************** * Public Types ****************************************************************************/ -/* The type of one C++ constructor */ - -typedef FAR void (*elf_ctor_t)(void); /* This struct provides a desciption of the currently loaded instantiation * of an ELF binary. @@ -72,17 +72,18 @@ struct elf_loadinfo_s uintptr_t alloc; /* Allocated memory with the ELF file is loaded */ size_t allocsize; /* Size of the memory allocation */ off_t filelen; /* Length of the entire ELF file */ - int filfd; /* Descriptor for the file being loaded */ -#ifdef CONFIG_ELF_CONSTRUCTORS - elf_ctor_t ctors; /* Pointer to a list of constructors */ + Elf32_Ehdr ehdr; /* Buffered ELF file header */ + FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */ + uint8_t *iobuffer; /* File I/O buffer */ +#ifdef CONFIG_BINFMT_CONSTRUCTORS + elf_ctor_t *ctors; /* Pointer to a list of constructors */ + bool newabi; /* True: ctors in 'alloc' */ uint16_t nctors; /* Number of constructors */ #endif uint16_t symtabidx; /* Symbol table section index */ uint16_t strtabidx; /* String table section index */ uint16_t buflen; /* size of iobuffer[] */ - Elf32_Ehdr ehdr; /* Buffered ELF file header */ - FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */ - uint8_t *iobuffer; /* File I/O buffer */ + int filfd; /* Descriptor for the file being loaded */ }; /**************************************************************************** From b48508c844dbd558e728c5695136696b5dfea1fc Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 29 Oct 2012 20:43:35 +0000 Subject: [PATCH 043/206] C++ static destructors work with ELF load too now git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5274 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/binfmt/binfmt_dumpmodule.c | 2 +- nuttx/binfmt/binfmt_execmodule.c | 2 +- nuttx/binfmt/binfmt_unloadmodule.c | 2 +- nuttx/binfmt/elf.c | 30 ++-- nuttx/binfmt/libelf/Make.defs | 2 +- nuttx/binfmt/libelf/libelf.h | 19 +++ nuttx/binfmt/libelf/libelf_bind.c | 2 +- nuttx/binfmt/libelf/libelf_ctors.c | 35 ++--- nuttx/binfmt/libelf/libelf_dtors.c | 215 ++++++++++++++++++++++++++++ nuttx/binfmt/libelf/libelf_load.c | 31 ++-- nuttx/binfmt/libelf/libelf_unload.c | 39 ++--- nuttx/include/nuttx/binfmt/binfmt.h | 10 +- nuttx/include/nuttx/binfmt/elf.h | 44 ++++-- 13 files changed, 344 insertions(+), 89 deletions(-) create mode 100644 nuttx/binfmt/libelf/libelf_dtors.c diff --git a/nuttx/binfmt/binfmt_dumpmodule.c b/nuttx/binfmt/binfmt_dumpmodule.c index e095c4a67a..40cbe4b213 100644 --- a/nuttx/binfmt/binfmt_dumpmodule.c +++ b/nuttx/binfmt/binfmt_dumpmodule.c @@ -91,7 +91,7 @@ int dump_module(FAR const struct binary_s *bin) bdbg(" argv: %p\n", bin->argv); bdbg(" entrypt: %p\n", bin->entrypt); bdbg(" mapped: %p size=%d\n", bin->mapped, bin->mapsize); - bdbg(" alloc: %p %p\n", bin->alloc[0], bin->alloc[1]); + bdbg(" alloc: %p %p %p\n", bin->alloc[0], bin->alloc[1], bin->alloc[2]); #ifdef CONFIG_BINFMT_CONSTRUCTORS bdbg(" ctors: %p nctors=%d\n", bin->ctors, bin->nctors); bdbg(" dtors: %p ndtors=%d\n", bin->dtors, bin->ndtors); diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c index b00248183b..37f4459660 100644 --- a/nuttx/binfmt/binfmt_execmodule.c +++ b/nuttx/binfmt/binfmt_execmodule.c @@ -88,7 +88,7 @@ #ifdef CONFIG_BINFMT_CONSTRUCTORS static inline void exec_ctors(FAR const struct binary_s *binp) { - elf_ctor_t *ctor = binp->ctors; + binfmt_ctor_t *ctor = binp->ctors; int i; /* Execute each constructor */ diff --git a/nuttx/binfmt/binfmt_unloadmodule.c b/nuttx/binfmt/binfmt_unloadmodule.c index 15b2383570..52243fcf78 100644 --- a/nuttx/binfmt/binfmt_unloadmodule.c +++ b/nuttx/binfmt/binfmt_unloadmodule.c @@ -85,7 +85,7 @@ #ifdef CONFIG_BINFMT_CONSTRUCTORS static inline void exec_dtors(FAR const struct binary_s *binp) { - elf_dtor_t *dtor = binp->dtors; + binfmt_dtor_t *dtor = binp->dtors; int i; /* Execute each destructor */ diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c index 26057ffc10..ea1e7b0ca8 100644 --- a/nuttx/binfmt/elf.c +++ b/nuttx/binfmt/elf.c @@ -111,12 +111,16 @@ static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo) int i; bdbg("LOAD_INFO:\n"); - bdbg(" alloc: %08lx\n", (long)loadinfo->alloc); - bdbg(" allocsize: %ld\n", (long)loadinfo->allocsize); + bdbg(" elfalloc: %08lx\n", (long)loadinfo->elfalloc); + bdbg(" elfsize: %ld\n", (long)loadinfo->elfsize); bdbg(" filelen: %ld\n", (long)loadinfo->filelen); #ifdef CONFIG_BINFMT_CONSTRUCTORS + bdbg(" ctoralloc: %08lx\n", (long)loadinfo->ctoralloc); bdbg(" ctors: %08lx\n", (long)loadinfo->ctors); bdbg(" nctors: %d\n", loadinfo->nctors); + bdbg(" dtoralloc: %08lx\n", (long)loadinfo->dtoralloc); + bdbg(" dtors: %08lx\n", (long)loadinfo->dtors); + bdbg(" ndtors: %d\n", loadinfo->ndtors); #endif bdbg(" filfd: %d\n", loadinfo->filfd); bdbg(" symtabidx: %d\n", loadinfo->symtabidx); @@ -210,8 +214,8 @@ static int elf_loadbinary(struct binary_s *binp) /* Return the load information */ - binp->entrypt = (main_t)(loadinfo.alloc + loadinfo.ehdr.e_entry); - binp->alloc[0] = (FAR void *)loadinfo.alloc; + binp->entrypt = (main_t)(loadinfo.elfalloc + loadinfo.ehdr.e_entry); + binp->alloc[0] = (FAR void *)loadinfo.elfalloc; binp->stacksize = CONFIG_ELF_STACKSIZE; #ifdef CONFIG_BINFMT_CONSTRUCTORS @@ -219,19 +223,13 @@ static int elf_loadbinary(struct binary_s *binp) * yet supported. */ - binp->ctors = loadinfo.ctors; - binp->nctors = loadinfo.nctors; + binp->alloc[1] = loadinfo.ctoralloc; + binp->ctors = loadinfo.ctors; + binp->nctors = loadinfo.nctors; - /* Was memory allocated for constructors? */ - - if (!loadinfo.newabi) - { - /* Yes.. save the allocation address so that it can be freed by - * unload module. - */ - - binp->alloc[1] = (FAR void *)loadinfo.ctors; - } + binp->alloc[2] = loadinfo.dtoralloc; + binp->dtors = loadinfo.dtors; + binp->ndtors = loadinfo.ndtors; #endif elf_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt, diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs index 26198ade2a..c8857c3f74 100644 --- a/nuttx/binfmt/libelf/Make.defs +++ b/nuttx/binfmt/libelf/Make.defs @@ -46,7 +46,7 @@ BINFMT_CSRCS += libelf_bind.c libelf_init.c libelf_iobuffer.c libelf_load.c \ libelf_unload.c libelf_verify.c ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) -BINFMT_CSRCS += libelf_ctors.c +BINFMT_CSRCS += libelf_ctors.c libelf_dtors.c endif # Hook the libelf subdirectory into the build diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h index bea92496ab..5b0be9ab02 100644 --- a/nuttx/binfmt/libelf/libelf.h +++ b/nuttx/binfmt/libelf/libelf.h @@ -236,4 +236,23 @@ int elf_reallocbuffer(FAR struct elf_loadinfo_s *loadinfo, size_t increment); int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo); #endif +/**************************************************************************** + * Name: elf_loaddtors + * + * Description: + * Load pointers to static destructors into an in-memory array. + * + * Input Parameters: + * loadinfo - Load state information + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +#ifdef CONFIG_BINFMT_CONSTRUCTORS +int elf_loaddtors(FAR struct elf_loadinfo_s *loadinfo); +#endif + #endif /* __BINFMT_LIBELF_LIBELF_H */ diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c index ef1b4fc8fd..e35087b1de 100644 --- a/nuttx/binfmt/libelf/libelf_bind.c +++ b/nuttx/binfmt/libelf/libelf_bind.c @@ -298,7 +298,7 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo, /* Flush the instruction cache before starting the newly loaded module */ #ifdef CONFIG_ELF_ICACHE - arch_flushicache((FAR void*)loadinfo->alloc, loadinfo->allocsize); + arch_flushicache((FAR void*)loadinfo->elfalloc, loadinfo->elfsize); #endif return ret; diff --git a/nuttx/binfmt/libelf/libelf_ctors.c b/nuttx/binfmt/libelf/libelf_ctors.c index a57fc37d93..20f1256e2e 100644 --- a/nuttx/binfmt/libelf/libelf_ctors.c +++ b/nuttx/binfmt/libelf/libelf_ctors.c @@ -75,7 +75,7 @@ * Name: elf_loadctors * * Description: - * Load points to static constructors into an in-memory array. + * Load pointers to static constructors into an in-memory array. * * Input Parameters: * loadinfo - Load state information @@ -96,8 +96,8 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) DEBUGASSERT(loadinfo->ctors == NULL); - /* Allocate an I/O buffer. This buffer is used by elf_sectname() to - * accumulate the variable length symbol name. + /* Allocate an I/O buffer if necessary. This buffer is used by + * elf_sectname() to accumulate the variable length symbol name. */ ret = elf_allocbuffer(loadinfo); @@ -110,7 +110,7 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) /* Find the index to the section named ".ctors." NOTE: On old ABI system, * .ctors is the name of the section containing the list of constructors; * On newer systems, the similar section is called .init_array. It is - * expected that the linker script will force the sectino name to be ".ctors" + * expected that the linker script will force the section name to be ".ctors" * in either case. */ @@ -136,10 +136,10 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) */ ctorsize = shdr->sh_size; - loadinfo->nctors = ctorsize / sizeof(elf_ctor_t); + loadinfo->nctors = ctorsize / sizeof(binfmt_ctor_t); - bvdbg("ctoridx=%d ctorsize=%d sizeof(elf_ctor_t)=%d nctors=%d\n", - ctoridx, ctorsize, sizeof(elf_ctor_t), loadinfo->nctors); + bvdbg("ctoridx=%d ctorsize=%d sizeof(binfmt_ctor_t)=%d nctors=%d\n", + ctoridx, ctorsize, sizeof(binfmt_ctor_t), loadinfo->nctors); /* Check if there are any constructors. It is not an error if there * are none. @@ -149,7 +149,7 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) { /* Check an assumption that we made above */ - DEBUGASSERT(shdr->sh_size == loadinfo->nctors * sizeof(elf_ctor_t)); + DEBUGASSERT(shdr->sh_size == loadinfo->nctors * sizeof(binfmt_ctor_t)); /* In the old ABI, the .ctors section is not allocated. In that case, * we need to allocate memory to hold the .ctors and then copy the @@ -161,19 +161,17 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) if ((shdr->sh_flags & SHF_ALLOC) == 0) { - /* Not loaded -> Old ABI. */ - - loadinfo->newabi = false; - /* Allocate memory to hold a copy of the .ctor section */ - loadinfo->ctors = (elf_ctor_t*)kmalloc(ctorsize); - if (!loadinfo->ctors) + loadinfo->ctoralloc = (binfmt_ctor_t*)kmalloc(ctorsize); + if (!loadinfo->ctoralloc) { bdbg("Failed to allocate memory for .ctors\n"); return -ENOMEM; } + loadinfo->ctors = (binfmt_ctor_t *)loadinfo->ctoralloc; + /* Read the section header table into memory */ ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->ctors, ctorsize, @@ -194,23 +192,20 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->ctors)[i]); bvdbg("ctor %d: %08lx + %08lx = %08lx\n", - i, *ptr, loadinfo->alloc, *ptr + loadinfo->alloc); + i, *ptr, loadinfo->elfalloc, *ptr + loadinfo->elfalloc); - *ptr += loadinfo->alloc; + *ptr += loadinfo->elfalloc; } } else { - /* Loaded -> New ABI. */ - - loadinfo->newabi = true; /* Save the address of the .ctors (actually, .init_array) where it was * loaded into memory. Since the .ctors lie in allocated memory, they * will be relocated via the normal mechanism. */ - loadinfo->ctors = (elf_ctor_t*)shdr->sh_addr; + loadinfo->ctors = (binfmt_ctor_t*)shdr->sh_addr; } } diff --git a/nuttx/binfmt/libelf/libelf_dtors.c b/nuttx/binfmt/libelf/libelf_dtors.c new file mode 100644 index 0000000000..c0c73a3373 --- /dev/null +++ b/nuttx/binfmt/libelf/libelf_dtors.c @@ -0,0 +1,215 @@ +/**************************************************************************** + * binfmt/libelf/libelf_dtors.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include "libelf.h" + +#ifdef CONFIG_BINFMT_CONSTRUCTORS + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: elf_loaddtors + * + * Description: + * Load pointers to static destructors into an in-memory array. + * + * Input Parameters: + * loadinfo - Load state information + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +int elf_loaddtors(FAR struct elf_loadinfo_s *loadinfo) +{ + FAR Elf32_Shdr *shdr; + size_t dtorsize; + int dtoridx; + int ret; + int i; + + DEBUGASSERT(loadinfo->dtors == NULL); + + /* Allocate an I/O buffer if necessary. This buffer is used by + * elf_sectname() to accumulate the variable length symbol name. + */ + + ret = elf_allocbuffer(loadinfo); + if (ret < 0) + { + bdbg("elf_allocbuffer failed: %d\n", ret); + return -ENOMEM; + } + + /* Find the index to the section named ".dtors." NOTE: On old ABI system, + * .dtors is the name of the section containing the list of destructors; + * On newer systems, the similar section is called .fini_array. It is + * expected that the linker script will force the section name to be ".dtors" + * in either case. + */ + + dtoridx = elf_findsection(loadinfo, ".dtors"); + if (dtoridx < 0) + { + /* This may not be a failure. -ENOENT indicates that the file has no + * static destructor section. + */ + + bvdbg("elf_findsection .dtors section failed: %d\n", dtoridx); + return ret == -ENOENT ? OK : ret; + } + + /* Now we can get a pointer to the .dtor section in the section header + * table. + */ + + shdr = &loadinfo->shdr[dtoridx]; + + /* Get the size of the .dtor section and the number of destructors that + * will need to be called. + */ + + dtorsize = shdr->sh_size; + loadinfo->ndtors = dtorsize / sizeof(binfmt_dtor_t); + + bvdbg("dtoridx=%d dtorsize=%d sizeof(binfmt_dtor_t)=%d ndtors=%d\n", + dtoridx, dtorsize, sizeof(binfmt_dtor_t), loadinfo->ndtors); + + /* Check if there are any destructors. It is not an error if there + * are none. + */ + + if (loadinfo->ndtors > 0) + { + /* Check an assumption that we made above */ + + DEBUGASSERT(shdr->sh_size == loadinfo->ndtors * sizeof(binfmt_dtor_t)); + + /* In the old ABI, the .dtors section is not allocated. In that case, + * we need to allocate memory to hold the .dtors and then copy the + * from the file into the allocated memory. + * + * SHF_ALLOC indicates that the section requires memory during + * execution. + */ + + if ((shdr->sh_flags & SHF_ALLOC) == 0) + { + /* Allocate memory to hold a copy of the .dtor section */ + + loadinfo->ctoralloc = (binfmt_dtor_t*)kmalloc(dtorsize); + if (!loadinfo->ctoralloc) + { + bdbg("Failed to allocate memory for .dtors\n"); + return -ENOMEM; + } + + loadinfo->dtors = (binfmt_dtor_t *)loadinfo->ctoralloc; + + /* Read the section header table into memory */ + + ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->dtors, dtorsize, + shdr->sh_offset); + if (ret < 0) + { + bdbg("Failed to allocate .dtors: %d\n", ret); + return ret; + } + + /* Fix up all of the .dtor addresses. Since the addresses + * do not lie in allocated memory, there will be no relocation + * section for them. + */ + + for (i = 0; i < loadinfo->ndtors; i++) + { + FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->dtors)[i]); + + bvdbg("dtor %d: %08lx + %08lx = %08lx\n", + i, *ptr, loadinfo->elfalloc, *ptr + loadinfo->elfalloc); + + *ptr += loadinfo->elfalloc; + } + } + else + { + + /* Save the address of the .dtors (actually, .init_array) where it was + * loaded into memory. Since the .dtors lie in allocated memory, they + * will be relocated via the normal mechanism. + */ + + loadinfo->dtors = (binfmt_dtor_t*)shdr->sh_addr; + } + } + + return OK; +} + +#endif /* CONFIG_BINFMT_CONSTRUCTORS */ diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c index 221ae8d438..b1ac44e21f 100644 --- a/nuttx/binfmt/libelf/libelf_load.c +++ b/nuttx/binfmt/libelf/libelf_load.c @@ -76,7 +76,7 @@ ****************************************************************************/ /**************************************************************************** - * Name: elf_allocsize + * Name: elf_elfsize * * Description: * Calculate total memory allocation for the ELF file. @@ -87,14 +87,14 @@ * ****************************************************************************/ -static void elf_allocsize(struct elf_loadinfo_s *loadinfo) +static void elf_elfsize(struct elf_loadinfo_s *loadinfo) { - size_t allocsize; + size_t elfsize; int i; /* Accumulate the size each section into memory that is marked SHF_ALLOC */ - allocsize = 0; + elfsize = 0; for (i = 0; i < loadinfo->ehdr.e_shnum; i++) { FAR Elf32_Shdr *shdr = &loadinfo->shdr[i]; @@ -105,13 +105,13 @@ static void elf_allocsize(struct elf_loadinfo_s *loadinfo) if ((shdr->sh_flags & SHF_ALLOC) != 0) { - allocsize += ELF_ALIGNUP(shdr->sh_size); + elfsize += ELF_ALIGNUP(shdr->sh_size); } } /* Save the allocation size */ - loadinfo->allocsize = allocsize; + loadinfo->elfsize = elfsize; } /**************************************************************************** @@ -136,8 +136,8 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo) /* Allocate (and zero) memory for the ELF file. */ - loadinfo->alloc = (uintptr_t)kzalloc(loadinfo->allocsize); - if (!loadinfo->alloc) + loadinfo->elfalloc = (uintptr_t)kzalloc(loadinfo->elfsize); + if (!loadinfo->elfalloc) { return -ENOMEM; } @@ -145,7 +145,7 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo) /* Read each section into memory that is marked SHF_ALLOC + SHT_NOBITS */ bvdbg("Loaded sections:\n"); - dest = (FAR uint8_t*)loadinfo->alloc; + dest = (FAR uint8_t*)loadinfo->elfalloc; for (i = 0; i < loadinfo->ehdr.e_shnum; i++) { @@ -223,7 +223,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) /* Determine total size to allocate */ - elf_allocsize(loadinfo); + elf_elfsize(loadinfo); /* Allocate memory and load sections into memory */ @@ -234,7 +234,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) goto errout_with_buffers; } - /* Find static constructors. */ + /* Load static constructors and destructors. */ #ifdef CONFIG_BINFMT_CONSTRUCTORS ret = elf_loadctors(loadinfo); @@ -243,6 +243,13 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) bdbg("elf_loadctors failed: %d\n", ret); goto errout_with_buffers; } + + ret = elf_loaddtors(loadinfo); + if (ret < 0) + { + bdbg("elf_loaddtors failed: %d\n", ret); + goto errout_with_buffers; + } #endif return OK; @@ -250,7 +257,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo) /* Error exits */ errout_with_buffers: - elf_freebuffers(loadinfo); + elf_unload(loadinfo); return ret; } diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c index 8102f7bf2f..532fc606fb 100644 --- a/nuttx/binfmt/libelf/libelf_unload.c +++ b/nuttx/binfmt/libelf/libelf_unload.c @@ -84,31 +84,34 @@ int elf_unload(struct elf_loadinfo_s *loadinfo) /* Release memory holding the relocated ELF image */ - if (loadinfo->alloc) + if (loadinfo->elfalloc != 0) { - kfree((FAR void *)loadinfo->alloc); - loadinfo->alloc = 0; - loadinfo->allocsize = 0; + kfree((FAR void *)loadinfo->elfalloc); + loadinfo->elfalloc = 0; } - /* Release any allocated constructor memory */ + loadinfo->elfsize = 0; + + /* Release memory used to hold static constructors and destructors */ #ifdef CONFIG_BINFMT_CONSTRUCTORS - if (loadinfo->ctors) + if (loadinfo->ctoralloc != 0) { - /* In the old ABI, the .ctors section is not make for allocation. In - * that case, we need to free the working buffer that was used to hold - * the constructors. - */ - - if (!loadinfo->newabi) - { - kfree((FAR void *)loadinfo->ctors); - } - - loadinfo->ctors = NULL; - loadinfo->nctors = 0; + kfree(loadinfo->ctoralloc); + loadinfo->ctoralloc = NULL; } + + loadinfo->ctors = NULL; + loadinfo->nctors = 0; + + if (loadinfo->dtoralloc != 0) + { + kfree(loadinfo->dtoralloc); + loadinfo->dtoralloc = NULL; + } + + loadinfo->dtors = NULL; + loadinfo->ndtors = 0; #endif return OK; diff --git a/nuttx/include/nuttx/binfmt/binfmt.h b/nuttx/include/nuttx/binfmt/binfmt.h index 0c18bfc49a..49ab37264f 100644 --- a/nuttx/include/nuttx/binfmt/binfmt.h +++ b/nuttx/include/nuttx/binfmt/binfmt.h @@ -49,15 +49,15 @@ * Pre-processor Definitions ****************************************************************************/ -#define BINFMT_NALLOC 2 +#define BINFMT_NALLOC 3 /**************************************************************************** * Public Types ****************************************************************************/ /* The type of one C++ constructor or destructor */ -typedef FAR void (*elf_ctor_t)(void); -typedef FAR void (*elf_dtor_t)(void); +typedef FAR void (*binfmt_ctor_t)(void); +typedef FAR void (*binfmt_dtor_t)(void); /* This describes the file to be loaded */ @@ -79,8 +79,8 @@ struct binary_s FAR void *mapped; /* Memory-mapped, address space */ FAR void *alloc[BINFMT_NALLOC]; /* Allocated address spaces */ #ifdef CONFIG_BINFMT_CONSTRUCTORS - elf_ctor_t *ctors; /* Pointer to a list of constructors */ - elf_dtor_t *dtors; /* Pointer to a list of destructors */ + FAR binfmt_ctor_t *ctors; /* Pointer to a list of constructors */ + FAR binfmt_dtor_t *dtors; /* Pointer to a list of destructors */ uint16_t nctors; /* Number of constructors in the list */ uint16_t ndtors; /* Number of destructors in the list */ #endif diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h index 2e3cb86236..432e57f0f8 100644 --- a/nuttx/include/nuttx/binfmt/elf.h +++ b/nuttx/include/nuttx/binfmt/elf.h @@ -59,6 +59,17 @@ # define CONFIG_ELF_ALIGN_LOG2 2 #endif +/* Allocation array size and indices */ + +#define LIBELF_ELF_ALLOC 0 +#ifdef CONFIG_BINFMT_CONSTRUCTORS +# define LIBELF_CTORS_ALLOC 1 +# define LIBELF_CTPRS_ALLOC 2 +# define LIBELF_NALLOC 3 +#else +# define LIBELF_NALLOC 1 +#endif + /**************************************************************************** * Public Types ****************************************************************************/ @@ -69,21 +80,28 @@ struct elf_loadinfo_s { - uintptr_t alloc; /* Allocated memory with the ELF file is loaded */ - size_t allocsize; /* Size of the memory allocation */ - off_t filelen; /* Length of the entire ELF file */ - Elf32_Ehdr ehdr; /* Buffered ELF file header */ - FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */ - uint8_t *iobuffer; /* File I/O buffer */ + /* The alloc[] array holds memory that persists after the ELF module has + * been loaded. + */ + + uintptr_t elfalloc; /* Memory allocated when ELF file was loaded */ + size_t elfsize; /* Size of the ELF memory allocation */ + off_t filelen; /* Length of the entire ELF file */ + Elf32_Ehdr ehdr; /* Buffered ELF file header */ + FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */ + uint8_t *iobuffer; /* File I/O buffer */ #ifdef CONFIG_BINFMT_CONSTRUCTORS - elf_ctor_t *ctors; /* Pointer to a list of constructors */ - bool newabi; /* True: ctors in 'alloc' */ - uint16_t nctors; /* Number of constructors */ + FAR void *ctoralloc; /* Memory allocated for ctors */ + FAR void *dtoralloc; /* Memory allocated dtors */ + FAR binfmt_ctor_t *ctors; /* Pointer to a list of constructors */ + FAR binfmt_dtor_t *dtors; /* Pointer to a list of destructors */ + uint16_t nctors; /* Number of constructors */ + uint16_t ndtors; /* Number of destructors */ #endif - uint16_t symtabidx; /* Symbol table section index */ - uint16_t strtabidx; /* String table section index */ - uint16_t buflen; /* size of iobuffer[] */ - int filfd; /* Descriptor for the file being loaded */ + uint16_t symtabidx; /* Symbol table section index */ + uint16_t strtabidx; /* String table section index */ + uint16_t buflen; /* size of iobuffer[] */ + int filfd; /* Descriptor for the file being loaded */ }; /**************************************************************************** From 5c160fad8347bee7f0df734ca7a9c263ce3e3dfe Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 29 Oct 2012 20:50:27 +0000 Subject: [PATCH 044/206] libm compilation fixes from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5275 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/lib/math/Make.defs | 2 +- nuttx/lib/math/lib_acos.c | 2 +- nuttx/lib/math/lib_acosl.c | 2 +- nuttx/lib/math/lib_asin.c | 2 +- nuttx/lib/math/lib_asinl.c | 2 +- nuttx/lib/math/lib_atan.c | 2 +- nuttx/lib/math/lib_atan2.c | 2 +- nuttx/lib/math/lib_atan2l.c | 2 +- nuttx/lib/math/lib_atanl.c | 2 +- nuttx/lib/math/lib_ceil.c | 2 +- nuttx/lib/math/lib_ceill.c | 2 +- nuttx/lib/math/lib_cos.c | 2 +- nuttx/lib/math/lib_cosh.c | 2 +- nuttx/lib/math/lib_coshl.c | 2 +- nuttx/lib/math/lib_cosl.c | 2 +- nuttx/lib/math/lib_exp.c | 2 +- nuttx/lib/math/lib_expl.c | 2 +- nuttx/lib/math/lib_fabs.c | 2 +- nuttx/lib/math/lib_fabsl.c | 2 +- nuttx/lib/math/lib_floor.c | 2 +- nuttx/lib/math/lib_floorl.c | 2 +- nuttx/lib/math/lib_fmod.c | 2 +- nuttx/lib/math/lib_fmodl.c | 2 +- nuttx/lib/math/lib_frexp.c | 2 +- nuttx/lib/math/lib_frexpl.c | 2 +- nuttx/lib/math/lib_ldexp.c | 2 +- nuttx/lib/math/lib_ldexpl.c | 2 +- nuttx/lib/math/lib_libexpi.c | 2 +- nuttx/lib/math/lib_log.c | 2 +- nuttx/lib/math/lib_log10.c | 2 +- nuttx/lib/math/lib_log10l.c | 2 +- nuttx/lib/math/lib_log2.c | 2 +- nuttx/lib/math/lib_log2l.c | 2 +- nuttx/lib/math/lib_logl.c | 2 +- nuttx/lib/math/lib_modf.c | 2 +- nuttx/lib/math/lib_modfl.c | 2 +- nuttx/lib/math/lib_pow.c | 2 +- nuttx/lib/math/lib_powl.c | 2 +- nuttx/lib/math/lib_sin.c | 2 +- nuttx/lib/math/lib_sinh.c | 2 +- nuttx/lib/math/lib_sinhl.c | 2 +- nuttx/lib/math/lib_sinl.c | 2 +- nuttx/lib/math/lib_sqrt.c | 2 +- nuttx/lib/math/lib_sqrtl.c | 2 +- nuttx/lib/math/lib_tan.c | 2 +- nuttx/lib/math/lib_tanh.c | 2 +- nuttx/lib/math/lib_tanhl.c | 2 +- nuttx/lib/math/lib_tanl.c | 2 +- 48 files changed, 48 insertions(+), 48 deletions(-) diff --git a/nuttx/lib/math/Make.defs b/nuttx/lib/math/Make.defs index 8e2e60f12d..73d0be6f3b 100644 --- a/nuttx/lib/math/Make.defs +++ b/nuttx/lib/math/Make.defs @@ -44,7 +44,7 @@ CSRCS += lib_sinf.c lib_sinhf.c lib_sqrtf.c lib_tanf.c lib_tanhf.c CSRCS += lib_acos.c lib_asin.c lib_atan.c lib_atan2.c lib_ceil.c lib_cos.c CSRCS += lib_cosh.c lib_exp.c lib_fabs.c lib_floor.c lib_fmod.c lib_frexp.c -CRRCS += lib_ldexp.c lib_log.c lib_log10.c lib_log2.c lib_modf.c lib_pow.c +CSRCS += lib_ldexp.c lib_log.c lib_log10.c lib_log2.c lib_modf.c lib_pow.c CSRCS += lib_sin.c lib_sinh.c lib_sqrt.c lib_tan.c lib_tanh.c CSRCS += lib_acosl.c lib_asinl.c lib_atan2l.c lib_atanl.c lib_ceill.c lib_cosl.c diff --git a/nuttx/lib/math/lib_acos.c b/nuttx/lib/math/lib_acos.c index 4c5aa67c0a..d5ec36b9ff 100644 --- a/nuttx/lib/math/lib_acos.c +++ b/nuttx/lib/math/lib_acos.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double acos(double x) { return (M_PI_2 - asin(x)); diff --git a/nuttx/lib/math/lib_acosl.c b/nuttx/lib/math/lib_acosl.c index 3b6fa8aa9d..9113305776 100644 --- a/nuttx/lib/math/lib_acosl.c +++ b/nuttx/lib/math/lib_acosl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double acosl(long double x) { return (M_PI_2 - asinl(x)); diff --git a/nuttx/lib/math/lib_asin.c b/nuttx/lib/math/lib_asin.c index 1469d1ed89..61b9535310 100644 --- a/nuttx/lib/math/lib_asin.c +++ b/nuttx/lib/math/lib_asin.c @@ -39,7 +39,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double asin(double x) { long double y, y_sin, y_cos; diff --git a/nuttx/lib/math/lib_asinl.c b/nuttx/lib/math/lib_asinl.c index bd1cb70ee9..dbb2bc3a2e 100644 --- a/nuttx/lib/math/lib_asinl.c +++ b/nuttx/lib/math/lib_asinl.c @@ -39,7 +39,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double asinl(long double x) { long double y, y_sin, y_cos; diff --git a/nuttx/lib/math/lib_atan.c b/nuttx/lib/math/lib_atan.c index 2b7f6e3a6f..b4db8fb313 100644 --- a/nuttx/lib/math/lib_atan.c +++ b/nuttx/lib/math/lib_atan.c @@ -40,7 +40,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double atan(double x) { return asin(x / sqrt(x * x + 1)); diff --git a/nuttx/lib/math/lib_atan2.c b/nuttx/lib/math/lib_atan2.c index bfb33657c6..82d1f47ec3 100644 --- a/nuttx/lib/math/lib_atan2.c +++ b/nuttx/lib/math/lib_atan2.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double atan2(double y, double x) { if (y == 0.0) diff --git a/nuttx/lib/math/lib_atan2l.c b/nuttx/lib/math/lib_atan2l.c index d7891b6286..07fcd9669b 100644 --- a/nuttx/lib/math/lib_atan2l.c +++ b/nuttx/lib/math/lib_atan2l.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double atan2l(long double y, long double x) { diff --git a/nuttx/lib/math/lib_atanl.c b/nuttx/lib/math/lib_atanl.c index c8fa239f9d..0fa2030988 100644 --- a/nuttx/lib/math/lib_atanl.c +++ b/nuttx/lib/math/lib_atanl.c @@ -40,7 +40,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double atanl(long double x) { return asinl(x / sqrtl(x * x + 1)); diff --git a/nuttx/lib/math/lib_ceil.c b/nuttx/lib/math/lib_ceil.c index 12e223128c..0e76029967 100644 --- a/nuttx/lib/math/lib_ceil.c +++ b/nuttx/lib/math/lib_ceil.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double ceil(double x) { modf(x, &x); diff --git a/nuttx/lib/math/lib_ceill.c b/nuttx/lib/math/lib_ceill.c index 5a0010aa21..a24b56f683 100644 --- a/nuttx/lib/math/lib_ceill.c +++ b/nuttx/lib/math/lib_ceill.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double ceill(long double x) { modfl(x, &x); diff --git a/nuttx/lib/math/lib_cos.c b/nuttx/lib/math/lib_cos.c index 09808bd9f7..aa672b8559 100644 --- a/nuttx/lib/math/lib_cos.c +++ b/nuttx/lib/math/lib_cos.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double cos(double x) { return sin(x + M_PI_2); diff --git a/nuttx/lib/math/lib_cosh.c b/nuttx/lib/math/lib_cosh.c index de4f42d7a1..1be44d2933 100644 --- a/nuttx/lib/math/lib_cosh.c +++ b/nuttx/lib/math/lib_cosh.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double cosh(double x) { x = exp(x); diff --git a/nuttx/lib/math/lib_coshl.c b/nuttx/lib/math/lib_coshl.c index d439127453..4576b88769 100644 --- a/nuttx/lib/math/lib_coshl.c +++ b/nuttx/lib/math/lib_coshl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double coshl(long double x) { x = expl(x); diff --git a/nuttx/lib/math/lib_cosl.c b/nuttx/lib/math/lib_cosl.c index 5b73218127..25dd861393 100644 --- a/nuttx/lib/math/lib_cosl.c +++ b/nuttx/lib/math/lib_cosl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double cosl(long double x) { return sinl(x + M_PI_2); diff --git a/nuttx/lib/math/lib_exp.c b/nuttx/lib/math/lib_exp.c index 350229860a..1e3120453d 100644 --- a/nuttx/lib/math/lib_exp.c +++ b/nuttx/lib/math/lib_exp.c @@ -37,7 +37,7 @@ #include "lib_internal.h" -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE /************************************************************************ * Private Data diff --git a/nuttx/lib/math/lib_expl.c b/nuttx/lib/math/lib_expl.c index cd5e6a500c..053103c9bb 100644 --- a/nuttx/lib/math/lib_expl.c +++ b/nuttx/lib/math/lib_expl.c @@ -37,7 +37,7 @@ #include "lib_internal.h" -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE /************************************************************************ * Private Data diff --git a/nuttx/lib/math/lib_fabs.c b/nuttx/lib/math/lib_fabs.c index a635b0b41d..ff99ceb642 100644 --- a/nuttx/lib/math/lib_fabs.c +++ b/nuttx/lib/math/lib_fabs.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double fabs(double x) { return ((x < 0) ? -x : x); diff --git a/nuttx/lib/math/lib_fabsl.c b/nuttx/lib/math/lib_fabsl.c index f1e37e3f1a..5313d897da 100644 --- a/nuttx/lib/math/lib_fabsl.c +++ b/nuttx/lib/math/lib_fabsl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double fabsl(long double x) { return ((x < 0) ? -x : x); diff --git a/nuttx/lib/math/lib_floor.c b/nuttx/lib/math/lib_floor.c index 895b9a5034..f0c4477a04 100644 --- a/nuttx/lib/math/lib_floor.c +++ b/nuttx/lib/math/lib_floor.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double floor(double x) { modf(x, &x); diff --git a/nuttx/lib/math/lib_floorl.c b/nuttx/lib/math/lib_floorl.c index 2c70112973..e38ce80ed3 100644 --- a/nuttx/lib/math/lib_floorl.c +++ b/nuttx/lib/math/lib_floorl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double floorl(long double x) { modfl(x, &x); diff --git a/nuttx/lib/math/lib_fmod.c b/nuttx/lib/math/lib_fmod.c index c55151d750..939e7e18ad 100644 --- a/nuttx/lib/math/lib_fmod.c +++ b/nuttx/lib/math/lib_fmod.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double fmod(double x, double div) { double n0; diff --git a/nuttx/lib/math/lib_fmodl.c b/nuttx/lib/math/lib_fmodl.c index c9b3ca7847..51c5e95ec8 100644 --- a/nuttx/lib/math/lib_fmodl.c +++ b/nuttx/lib/math/lib_fmodl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double fmodl(long double x, long double div) { long double n0; diff --git a/nuttx/lib/math/lib_frexp.c b/nuttx/lib/math/lib_frexp.c index 6de67f8b5f..56feee8639 100644 --- a/nuttx/lib/math/lib_frexp.c +++ b/nuttx/lib/math/lib_frexp.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double frexp(double x, int *exponent) { *exponent = (int)ceil(log2(x)); diff --git a/nuttx/lib/math/lib_frexpl.c b/nuttx/lib/math/lib_frexpl.c index 7a0d3c408b..87708ad86c 100644 --- a/nuttx/lib/math/lib_frexpl.c +++ b/nuttx/lib/math/lib_frexpl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double frexpl(long double x, int *exponent) { *exponent = (int)ceill(log2(x)); diff --git a/nuttx/lib/math/lib_ldexp.c b/nuttx/lib/math/lib_ldexp.c index ca428dc074..4c7b2b721b 100644 --- a/nuttx/lib/math/lib_ldexp.c +++ b/nuttx/lib/math/lib_ldexp.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double ldexp(double x, int n) { return (x * pow(2.0, (double)n)); diff --git a/nuttx/lib/math/lib_ldexpl.c b/nuttx/lib/math/lib_ldexpl.c index 0f77bff111..b9a0f4a865 100644 --- a/nuttx/lib/math/lib_ldexpl.c +++ b/nuttx/lib/math/lib_ldexpl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double ldexpl(long double x, int n) { return (x * powl(2.0, (long double)n)); diff --git a/nuttx/lib/math/lib_libexpi.c b/nuttx/lib/math/lib_libexpi.c index d2bb971a21..1ec947a71a 100644 --- a/nuttx/lib/math/lib_libexpi.c +++ b/nuttx/lib/math/lib_libexpi.c @@ -77,7 +77,7 @@ static double _expi_square_tbl[11] = * Public Functions ************************************************************************/ -static double lib_expi(size_t n) +double lib_expi(size_t n) { size_t i; double val; diff --git a/nuttx/lib/math/lib_log.c b/nuttx/lib/math/lib_log.c index 4dd51e87ce..1350ba4fea 100644 --- a/nuttx/lib/math/lib_log.c +++ b/nuttx/lib/math/lib_log.c @@ -39,7 +39,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double log(double x) { double y, y_old, ey, epsilon; diff --git a/nuttx/lib/math/lib_log10.c b/nuttx/lib/math/lib_log10.c index a6534407e1..47854fca44 100644 --- a/nuttx/lib/math/lib_log10.c +++ b/nuttx/lib/math/lib_log10.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double log10(double x) { return (log(x) / M_LN10); diff --git a/nuttx/lib/math/lib_log10l.c b/nuttx/lib/math/lib_log10l.c index 8702ed5a55..65892262a8 100644 --- a/nuttx/lib/math/lib_log10l.c +++ b/nuttx/lib/math/lib_log10l.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double log10l(long double x) { return (logl(x) / M_LN10); diff --git a/nuttx/lib/math/lib_log2.c b/nuttx/lib/math/lib_log2.c index 377d78e292..0aa1e80101 100644 --- a/nuttx/lib/math/lib_log2.c +++ b/nuttx/lib/math/lib_log2.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double log2(double x) { return (log(x) / M_LN2); diff --git a/nuttx/lib/math/lib_log2l.c b/nuttx/lib/math/lib_log2l.c index cd25c32f11..21d26d4d7b 100644 --- a/nuttx/lib/math/lib_log2l.c +++ b/nuttx/lib/math/lib_log2l.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double log2l(long double x) { return (logl(x) / M_LN2); diff --git a/nuttx/lib/math/lib_logl.c b/nuttx/lib/math/lib_logl.c index df0031943f..577f9cee2e 100644 --- a/nuttx/lib/math/lib_logl.c +++ b/nuttx/lib/math/lib_logl.c @@ -39,7 +39,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double logl(long double x) { long double y, y_old, ey, epsilon; diff --git a/nuttx/lib/math/lib_modf.c b/nuttx/lib/math/lib_modf.c index 3b33cde428..9dc6284c20 100644 --- a/nuttx/lib/math/lib_modf.c +++ b/nuttx/lib/math/lib_modf.c @@ -36,7 +36,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double modf(double x, double *iptr) { if (fabs(x) >= 4503599627370496.0) diff --git a/nuttx/lib/math/lib_modfl.c b/nuttx/lib/math/lib_modfl.c index 55b17eae6d..3b04571f3a 100644 --- a/nuttx/lib/math/lib_modfl.c +++ b/nuttx/lib/math/lib_modfl.c @@ -39,7 +39,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double modfl(long double x, long double *iptr) { if (fabs(x) >= 4503599627370496.0) diff --git a/nuttx/lib/math/lib_pow.c b/nuttx/lib/math/lib_pow.c index 66f6a2d2e1..af0a55d32f 100644 --- a/nuttx/lib/math/lib_pow.c +++ b/nuttx/lib/math/lib_pow.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double pow(double b, double e) { return exp(e * log(b)); diff --git a/nuttx/lib/math/lib_powl.c b/nuttx/lib/math/lib_powl.c index 6a820df26b..f5fbf042e9 100644 --- a/nuttx/lib/math/lib_powl.c +++ b/nuttx/lib/math/lib_powl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double powl(long double b, long double e) { return expl(e * logl(b)); diff --git a/nuttx/lib/math/lib_sin.c b/nuttx/lib/math/lib_sin.c index 2d21d2309c..c04d6b88b9 100644 --- a/nuttx/lib/math/lib_sin.c +++ b/nuttx/lib/math/lib_sin.c @@ -35,7 +35,7 @@ #include #include -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE /************************************************************************ * Private Data diff --git a/nuttx/lib/math/lib_sinh.c b/nuttx/lib/math/lib_sinh.c index a22652302c..f33852433b 100644 --- a/nuttx/lib/math/lib_sinh.c +++ b/nuttx/lib/math/lib_sinh.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double sinh(double x) { x = exp(x); diff --git a/nuttx/lib/math/lib_sinhl.c b/nuttx/lib/math/lib_sinhl.c index 442586ffb8..b0fea29149 100644 --- a/nuttx/lib/math/lib_sinhl.c +++ b/nuttx/lib/math/lib_sinhl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double sinhl(long double x) { x = expl(x); diff --git a/nuttx/lib/math/lib_sinl.c b/nuttx/lib/math/lib_sinl.c index f8d9e00edf..a69b548cb3 100644 --- a/nuttx/lib/math/lib_sinl.c +++ b/nuttx/lib/math/lib_sinl.c @@ -35,7 +35,7 @@ #include #include -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE /************************************************************************ * Private Data diff --git a/nuttx/lib/math/lib_sqrt.c b/nuttx/lib/math/lib_sqrt.c index 96f0d5409e..d77997f7cd 100644 --- a/nuttx/lib/math/lib_sqrt.c +++ b/nuttx/lib/math/lib_sqrt.c @@ -41,7 +41,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double sqrt(double x) { long double y, y1; diff --git a/nuttx/lib/math/lib_sqrtl.c b/nuttx/lib/math/lib_sqrtl.c index f305092e7b..6674fe50f8 100644 --- a/nuttx/lib/math/lib_sqrtl.c +++ b/nuttx/lib/math/lib_sqrtl.c @@ -41,7 +41,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double sqrtl(long double x) { long double y, y1; diff --git a/nuttx/lib/math/lib_tan.c b/nuttx/lib/math/lib_tan.c index a9a1d8ebee..bce14b3270 100644 --- a/nuttx/lib/math/lib_tan.c +++ b/nuttx/lib/math/lib_tan.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double tan(double x) { return (sin(x) / cos(x)); diff --git a/nuttx/lib/math/lib_tanh.c b/nuttx/lib/math/lib_tanh.c index 5cc1d9176c..46fddd06df 100644 --- a/nuttx/lib/math/lib_tanh.c +++ b/nuttx/lib/math/lib_tanh.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_DOUBLE +#ifdef CONFIG_HAVE_DOUBLE double tanh(double x) { double x0 = exp(x); diff --git a/nuttx/lib/math/lib_tanhl.c b/nuttx/lib/math/lib_tanhl.c index 8b897451e4..23c11d6672 100644 --- a/nuttx/lib/math/lib_tanhl.c +++ b/nuttx/lib/math/lib_tanhl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double tanhl(long double x) { long double x0 = exp(x); diff --git a/nuttx/lib/math/lib_tanl.c b/nuttx/lib/math/lib_tanl.c index c4c3712c1c..4973aa073c 100644 --- a/nuttx/lib/math/lib_tanl.c +++ b/nuttx/lib/math/lib_tanl.c @@ -38,7 +38,7 @@ * Public Functions ************************************************************************/ -#if CONFIG_HAVE_LONG_DOUBLE +#ifdef CONFIG_HAVE_LONG_DOUBLE long double tanl(long double x) { return (sinl(x) / cosl(x)); From 228c77b4d4682c790cc0539d0fc03eb0c6bb2ea6 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 29 Oct 2012 21:18:51 +0000 Subject: [PATCH 045/206] Update documentation to at least reference the ELF loader. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5276 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Documentation/NuttX.html | 13 +++-- nuttx/Documentation/NuttxPortingGuide.html | 55 +++++++++++++++++++--- nuttx/configs/README.txt | 36 ++++++++++++-- 3 files changed, 92 insertions(+), 12 deletions(-) diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index 06b61a4de5..f3f13d38a2 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -8,7 +8,7 @@

    NuttX RTOS

    -

    Last Updated: September 29, 2012

    +

    Last Updated: October 29, 2012

    @@ -448,13 +448,20 @@
  • ROMFS filesystem support.
  • + +
    + +

    +

  • Loadable ELF Modules. + Support for separately linked, loadable ELF modules. +

    +

  • NXFLAT. - A new binary format call NXFLAT that can be used to - execute separately linked programs in place in a file system. + NXFLAT is a binary format that can be XIP from a file system.

    diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index 96c3012952..dd9d66881f 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -12,7 +12,7 @@

    NuttX RTOS Porting Guide

    -

    Last Updated: October 20, 2012

    +

    Last Updated: October 29, 2012

    @@ -4070,11 +4070,6 @@ build desciptors by task_create() when a new task is started. If set, all sockets will appear to be closed in the new task.
  • -
  • - CONFIG_NXFLAT: Enable support for the NXFLAT binary format. - This format will support execution of NuttX binaries located - in a ROMFS file system (see apps/examples/nxflat). -
  • CONFIG_SCHED_WORKQUEUE: Create a dedicated "worker" thread to handle delayed processing from interrupt handlers. This feature @@ -4144,6 +4139,54 @@ build
  • +

    + Binary Loaders: +

    +
      +
    • + CONFIG_BINFMT_DISABLE: By default, support for loadable binary formats is built. + This logic may be suppressed be defining this setting. +
    • +
    • + CONFIG_BINFMT_CONSTRUCTORS: Build in support for C++ constructors in loaded modules. +
    • +
    • + CONFIG_SYMTAB_ORDEREDBYNAME: Symbol tables are order by name (rather than value). +
    • +
    • + CONFIG_NXFLAT: Enable support for the NXFLAT binary format. + This format will support execution of NuttX binaries located + in a ROMFS file system (see apps/examples/nxflat). +
    • +
    • + CONFIG_ELF: Enable support for the ELF binary format. + This format will support execution of ELF binaries copied from a file system and relocated into RAM (see apps/examples/elf). +
    • +

      + If CONFIG_ELF is selected, then these additional options are available: +

      +
    • + CONFIG_ELF_ALIGN_LOG2: Align all sections to this Log2 value: 0->1, 1->2, 2->4, etc. +
    • +
    • + CONFIG_ELF_STACKSIZE: This is the default stack size that will will be used when starting ELF binaries. +
    • +
    • + CONFIG_ELF_BUFFERSIZE: This is an I/O buffer that is used to access the ELF file. Variable length items will need to be read (such as symbol names). + This is really just this initial size of the buffer; it will be reallocated as necessary to hold large symbol names). + Default: 128 +
    • +
    • + CONFIG_ELF_BUFFERINCR: This is an I/O buffer that is used to access the ELF file. Variable length items will need to be read (such as symbol names). + This value specifies the size increment to use each time the buffer is reallocated. + Default: 32 +
    • +
    • + CONFIG_ELF_DUMPBUFFER: Dump various ELF buffers for debug purposes. + This option requires CONFIG_DEBUG and CONFIG_DEBUG_VERBOSE. +
    • +
    +

    System Logging:

    diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 4f96dc325b..7caffa2bf1 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -371,9 +371,6 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_SDCLONE_DISABLE. Disable cloning of all socket desciptors by task_create() when a new task is started. If set, all sockets will appear to be closed in the new task. - CONFIG_NXFLAT. Enable support for the NXFLAT binary format. - This format will support execution of NuttX binaries located - in a ROMFS filesystem (see examples/nxflat). CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to handle delayed processing from interrupt handlers. This feature is required for some drivers but, if there are not complaints, @@ -417,6 +414,39 @@ defconfig -- This is a configuration file similar to the Linux where 'app' is the application name. If not defined, CONFIG_USER_ENTRYPOINT defaults to user_start. + Binary Loaders: + CONFIG_BINFMT_DISABLE - By default, support for loadable binary formats + is built. + This logic may be suppressed be defining this setting. + CONFIG_BINFMT_CONSTRUCTORS - Build in support for C++ constructors in + loaded modules. + CONFIG_SYMTAB_ORDEREDBYNAME - Symbol tables are order by name (rather + than value). + CONFIG_NXFLAT. Enable support for the NXFLAT binary format. This format + will support execution of NuttX binaries located in a ROMFS filesystem + (see examples/nxflat). + CONFIG_ELF - Enable support for the ELF binary format. This format will + support execution of ELF binaries copied from a file system and + relocated into RAM. + + If CONFIG_ELF is selected, then these additional options are available: + + CONFIG_ELF_ALIGN_LOG2 - Align all sections to this Log2 value: 0->1, + 1->2, 2->4, etc. + CONFIG_ELF_STACKSIZE - This is the default stack size that will will + be used when starting ELF binaries. + CONFIG_ELF_BUFFERSIZE - This is an I/O buffer that is used to access + the ELF file. Variable length items will need to be read (such as + symbol names). This is really just this initial size of the buffer; + it will be reallocated as necessary to hold large symbol names). + Default: 128 + CONFIG_ELF_BUFFERINCR - This is an I/O buffer that is used to access + the ELF file. Variable length items will need to be read (such as + symbol names). This value specifies the size increment to use each + time the buffer is reallocated. Default: 32 + CONFIG_ELF_DUMPBUFFER - Dump various ELF buffers for debug purposes. + This option requires CONFIG_DEBUG and CONFIG_DEBUG_VERBOSE. + System Logging: CONFIG_SYSLOG enables general system logging support. CONFIG_SYSLOG_DEVPATH - The full path to the system logging device. Default From ce2653116a6d2a59f4d976418e662883a6d47210 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 29 Oct 2012 21:47:14 +0000 Subject: [PATCH 046/206] More documentation updated to reference the ELF loader. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5277 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 ++ nuttx/Documentation/NuttX.html | 27 +++++++++++++++++++++++---- nuttx/configs/README.txt | 4 ++-- 3 files changed, 27 insertions(+), 6 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 723f534bc5..cb14281de2 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3535,4 +3535,6 @@ * lib/math: Files now conform to coding standards. Separated float, double, and long double versions of code into separate files so that they don't draw in so much un-necessary code when doing a dumb link. + * binfmt/libelf: The ELF loader is working correctly with C++ static + constructors and destructors and all. diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index f3f13d38a2..fc0291846c 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -452,16 +452,19 @@

    -

  • Loadable ELF Modules. - Support for separately linked, loadable ELF modules. +
  • + Support for separately linked, loadable ELF modules. +

  • -

  • NXFLAT. - NXFLAT is a binary format that can be XIP from a file system. +
  • + NXFLAT. + NXFLAT is a binary format that can be XIP from a file system. +
  • @@ -548,6 +551,14 @@

    + +
    + +

    +

  • Includes floating point math library.
  • +

    + + @@ -571,6 +582,14 @@

    + +
    + +

    +

  • A port cJSON
  • +

    + +
    diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 7caffa2bf1..0849837c1f 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -424,10 +424,10 @@ defconfig -- This is a configuration file similar to the Linux than value). CONFIG_NXFLAT. Enable support for the NXFLAT binary format. This format will support execution of NuttX binaries located in a ROMFS filesystem - (see examples/nxflat). + (see apps/examples/nxflat). CONFIG_ELF - Enable support for the ELF binary format. This format will support execution of ELF binaries copied from a file system and - relocated into RAM. + relocated into RAM (see apps/examples/elf). If CONFIG_ELF is selected, then these additional options are available: From 5022f81174678bf7f032e8ee614552659565497b Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 30 Oct 2012 14:32:52 +0000 Subject: [PATCH 047/206] Add documentation for the binary loader git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5278 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 1 + nuttx/Documentation/NuttX.html | 27 +- nuttx/Documentation/NuttXBinfmt.html | 467 ++++++++++++++++++++ nuttx/Documentation/NuttXDocumentation.html | 1 + nuttx/Documentation/NuttxPortingGuide.html | 10 +- nuttx/Documentation/NuttxUserGuide.html | 6 +- nuttx/README.txt | 22 +- nuttx/binfmt/libelf/gnu-elf.ld | 16 +- nuttx/configs/README.txt | 9 + nuttx/include/nuttx/binfmt/symtab.h | 2 +- 10 files changed, 534 insertions(+), 27 deletions(-) create mode 100644 nuttx/Documentation/NuttXBinfmt.html diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index cb14281de2..df9e345fe2 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3537,4 +3537,5 @@ they don't draw in so much un-necessary code when doing a dumb link. * binfmt/libelf: The ELF loader is working correctly with C++ static constructors and destructors and all. + * Documentation/NuttXBinfmt.html: Add documentionof the binary loader. diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index fc0291846c..0c98d4ad2e 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -453,17 +453,14 @@

  • - Support for separately linked, loadable ELF modules. -
  • -

    - - -
    - -

    -

  • - NXFLAT. - NXFLAT is a binary format that can be XIP from a file system. + A binary loader with support for the following formats: +
      +
    • Separately linked ELF modules.
    • +
    • + Separately linked NXFLAT modules. + NXFLAT is a binary format that can be XIP from a file system. +
    • +
  • @@ -630,7 +627,7 @@

  • A NuttX port of Jeff Poskanzer's THTTPD HTTP server - integrated with NXFLAT to provide true, embedded CGI. + integrated with the NuttX binary loader to provide true, embedded CGI.
  • @@ -3691,7 +3688,11 @@ buildroot-1.10 2011-05-06 <gnutt@nuttx.org> - NXFLAT Binary Format + NuttX Binary Loader + + + + NXFLAT Binary Format diff --git a/nuttx/Documentation/NuttXBinfmt.html b/nuttx/Documentation/NuttXBinfmt.html new file mode 100644 index 0000000000..8d70d0135a --- /dev/null +++ b/nuttx/Documentation/NuttXBinfmt.html @@ -0,0 +1,467 @@ + + +NuttX Binary Loader + + +

    + + + + +
    +

    NuttX Binary Loader

    +

    Last Updated: October 30, 2012

    +
    +

    + + + + + +
    +

    Table of Contents

    +
    + + + + + + + +
    +

    1.0 Introduction

    +
    + +

    + Binary Loaders. + The purpose of a binary loader is to load and execute modules in various binary formats that reside in a file system. + Loading refers instiating the binary module in some fashion, usually copy all or some of the binary module into memory and then linking the module with other components. + In most architectures, it is thebase FLASH code that is the primary component that the binary module must link with because that is where the RTOS and primary tasks reside. + Program modules can then be executed after they have been loaded. +

    + +

    + Binary Formats. + The binary loader provides generic support for different binary formats. + It supports a registration interface that allows the number of support binary formats to be loaded at run time. + Each binary format provides a common, interface for use by the binary loader. + When asked to load a binary, the binary loader will query each registered binary format, providing it with the path of the binary object to be loaded. + The binary loader will stop when first binary format the recognizes the binary object and successfully loads it or when all registered binary formats have attempt loading the binary object and failed. +

    + +

    + At present, the following binary formats are support by NuttX: +

    +
      +
    • + ELF. + Standard ELF formatted files. +
    • +
    • + NXFLAT. + NuttX NXFLAT formatted files. + More information about the NXFLAT binary format can be found in the + NXFLAT documentation. +
    + +

    + Executables and Libraries + The generic binary loader logic does not care what it is that it being loaded. It could load an executable program or a library. + There are no strict rules, but a library will tend to export symbols and a program will tend to import symbols: The program will use the symbols exported by the library. + However, at this point in time, none of the supported binary formts support exporting of symbols. +

    + +

    + binfmt. + In the NuttX source code, the short name binfmt is used to refer to the NuttX binary loader. + This is the name of the directory containing the binary loader and the name of the header files and variables used by the binary loader. +

    + +

    + The name binfmt is the same name used by the Linux binary loader. + However, the NuttX binary loader is an independent development and shares nothing with the Linux binary loader other the same name and the same basic functionality. +

    + + + + + +
    +

    2.0 Binary Loader Interface

    +
    + +

    2.1 Binary Loader Header Files

    +

    + The interface to the binary loader is described in the header file + + include/nuttx/binfmt/binfmt.h. + A brief summary of the data structurs and interfaces prototyped in that header file are listed below. +

    + +

    2.2 Binary Loader Data Structures

    + +

    + When a binary format registers with the binary loader, it provides a pointer to a write-able instance of the following data structure: +

    +
      +struct binfmt_s
      +{
      +  FAR struct binfmt_s *next;             /* Supports a singly-linked list */
      +  int (*load)(FAR struct binary_s *bin); /* Verify and load binary into memory */
      +};
      +
    + +

    + The load method is used to load the binary format into memory. + It returns either OK (0) meaning that the binary object was loaded successfully, or a negater errno indicating why the object was not loaded. +

    + +

    + The type struct binary_s is use both to (2) describe the binary object to be loaded, and if successfully loaded, (2) to provide information about where and how the binary object was loaded. + That structure is shown below: +

    +
      +struct symtab_s;
      +struct binary_s
      +{
      +  /* Information provided to the loader to load and bind a module */
      +
      +  FAR const char *filename;            /* Full path to the binary to be loaded */
      +  FAR const char **argv;               /* Argument list */
      +  FAR const struct symtab_s *exports;  /* Table of exported symbols */
      +  int nexports;                        /* The number of symbols in exports[] */
      +
      +  /* Information provided from the loader (if successful) describing the
      +   * resources used by the loaded module.
      +   */
      +
      +  main_t entrypt;                      /* Entry point into a program module */
      +  FAR void *mapped;                    /* Memory-mapped, address space */
      +  FAR void *alloc[BINFMT_NALLOC];      /* Allocated address spaces */
      +#ifdef CONFIG_BINFMT_CONSTRUCTORS
      +  FAR binfmt_ctor_t *ctors;            /* Pointer to a list of constructors */
      +  FAR binfmt_dtor_t *dtors;            /* Pointer to a list of destructors */
      +  uint16_t nctors;                     /* Number of constructors in the list */
      +  uint16_t ndtors;                     /* Number of destructors in the list */
      +#endif
      +  size_t mapsize;                      /* Size of the mapped address region (needed for munmap) */
      +  size_t stacksize;                    /* Size of the stack in bytes (unallocated) */
      +};
      +
    + +

    + Where the types binfmt_ctor_t and binfmt_dtor_t define the type of one C++ constructor or destructor: +

    + +
      +typedef FAR void (*binfmt_ctor_t)(void);
      +typedef FAR void (*binfmt_dtor_t)(void);
      +
    + +

    2.3 Binary Loader Function Interfaces

    + + + +

    2.3.1 register_binfmt()

    + +

    Function Prototype:

    +
      +#include <:nuttx/binfmt/binfmt.h>
      +int register_binfmt(FAR struct binfmt_s *binfmt);
      +
    +

    Description:

    +
      +Register a loader for a binary format. +
    +

    Returned Value:

    +
      +This is a NuttX internal function so it follows the convention that 0 (OK) is returned on success and a negated errno is returned on failure. +
    + +

    2.3.2 unregister_binfmt()

    +

    Function Prototype:

    +
      +#include <:nuttx/binfmt/binfmt.h>
      +int unregister_binfmt(FAR struct binfmt_s *binfmt);
      +
    +

    Description:

    +
      +Register a loader for a binary format. +
    +

    Returned Value:

    +
      +This is a NuttX internal function so it follows the convention that 0 (OK) is returned on success and a negated errno is returned on failure. +
    + +

    2.3.3 load_module()

    +

    Function Prototype:

    +
      +#include <:nuttx/binfmt/binfmt.h>
      +int load_module(FAR struct binary_s *bin);
      +
    +

    Description:

    +
      +Load a module into memory, bind it to an exported symbol take, and prep the module for execution. +
    +

    Returned Value:

    +
      +This is an end-user function, so it follows the normal convention: +Returns 0 (OK) on success. +On failure, it returns -1 (ERROR) with errno set appropriately. +
    + +

    2.3.4 unload_module()

    +

    Function Prototype:

    +
      +#include <:nuttx/binfmt/binfmt.h>
      +int unload_module(FAR const struct binary_s *bin);
      +
    +

    Description:

    +
      +

      + Unload a (non-executing) module from memory. + If the module has been started (via exec_module()) and has not exited, calling this will be fatal. +

      +

      + However, this function must be called after the module exist. + How this is done is up to your logic. + Perhaps you register it to be called by on_exit()? +

    +

    Returned Value:

    +
      +This is a NuttX internal function so it follows the convention that 0 (OK) is returned on success and a negated errno is returned on failure. +
    + +

    2.3.5 exec_module()

    +

    Function Prototype:

    +
      +#include <:nuttx/binfmt/binfmt.h>
      +int exec_module(FAR const struct binary_s *bin, int priority);
      +
    +

    Description:

    +
      +Execute a module that has been loaded into memory by load_module(). +
    +

    Returned Value:

    +
      +This is an end-user function, so it follows the normal convention: +Returns 0 (OK) on success. +On failure, it returns -1 (ERROR) with errno set appropriately. +
    + +

    2.3.7 exec()

    +

    Function Prototype:

    +
      +#include <:nuttx/binfmt/binfmt.h>
      +int exec(FAR const char *filename, FAR const char **argv,
      +         FAR const struct symtab_s *exports, int nexports);
      +
    +

    Description:

    +
      +This is a convenience function that wraps load_ and exec_module() into one call. +
    +

    Input Parameters:

    +
      +
    • filename: Fulll path to the binary to be loaded.
    • +
    • argv: Argument list.
    • +
    • exports: Table of exported symbols.
    • +
    • exports: The number of symbols in exports.
    • +
    +

    Returned Value:

    +
      +This is an end-user function, so it follows the normal convention: +Returns 0 (OK) on success. +On failure, it returns -1 (ERROR) with errno set appropriately. +
    + + + + + +
    +

    3.0 Symbol Tables

    +
    + +

    + Symbol Tables. + Symbol tables are lists of name value mappings: + The name is a string that identifies a symbol, and the value is an address in memory where the symbol of that name has been positioned. + In most NuttX architectures symbol tables are required, as a minimum, in order to dynamically link the loaded binary object with the base code on FLASH. + Since the binary object was separately built and separately linked, these symbols will appear as undefined symbols in the binary object. + The binary loader will use the symbol table to look up the symbol by its name and to provide the address associated with the symbol as needed to perform the dynamic linking of the binary object to the base FLASH code. +

    + +

    3.1 Symbol Table Header Files

    +

    + The interface to the symbol table logic is described in the header file + + include/nuttx/binfmt/symtab.h. + A brief summary of the data structurs and interfaces prototyped in that header file are listed below. +

    + +

    3.2 Symbol Table Data Structures

    +

    + struct symbtab_s describes one entry in the symbol table. +

    + +
      +struct symtab_s
      +{
      +  FAR const char *sym_name;          /* A pointer to the symbol name string */
      +  FAR const void *sym_value;         /* The value associated witht the string */
      +};
      +
    + +

    + A symbol table is a fixed size array of struct symtab_s. + The information is intentionally minimal and supports only: +

    +
      +
    1. + Function pointers as sym_values. + Of other kinds of values need to be supported, then typing information would also need to be included in the structure. +
    2. +
    3. + Fixed size arrays. + There is no explicit provisional for dyanamically adding or removing entries from the symbol table (realloc might be used for that purpose if needed). + The intention is to support only fixed size arrays completely defined at compilation or link time. +
    4. +
    + +

    3.3 Symbol Table Function Interfaces

    + + + +

    3.3.1 symtab_findbyname()

    +

    Function Prototype:

    +
      +#include <:nuttx/binfmt/symtab.h>
      +FAR const struct symtab_s *
      +symtab_findbyname(FAR const struct symtab_s *symtab,
      +                  FAR const char *name, int nsyms);
      +
    +

    Description:

    +
      + Find the symbol in the symbol table with the matching name. + This version assumes that table is not ordered with respect to symbol name and, hence, access time will be linear with respect to nsyms. +
    +

    Returned Value:

    +
      + A reference to the symbol table entry if an entry with the matching name is found; +NULL is returned if the entry is not found. +
    + +

    3.3.2 symtab_findorderedbyname()

    +

    Function Prototype:

    +
      +#include <:nuttx/binfmt/symtab.h>
      +FAR const struct symtab_s *
      +symtab_findorderedbyname(FAR const struct symtab_s *symtab,
      +                         FAR const char *name, int nsyms);
      +
    +

    Description:

    +
      + Find the symbol in the symbol table with the matching name. + This version assumes that table ordered with respect to symbol name. +
    +

    Returned Value:

    +
      + A reference to the symbol table entry if an entry with the matching name is found; + NULL is returned if the entry is not found. +
    + +

    3.3.3 symtab_findbyvalue()

    +

    Function Prototype:

    +
      +#include <:nuttx/binfmt/symtab.h>
      +FAR const struct symtab_s *
      +symtab_findbyvalue(FAR const struct symtab_s *symtab,
      +                   FAR void *value, int nsyms);
      +
    +

    Description:

    +
      + Find the symbol in the symbol table whose value closest (but not greater than), the provided value. + This version assumes that table is not ordered with respect to symbol name and, hence, access time will be linear with respect to nsyms. +
    +

    Returned Value:

    +
      + A reference to the symbol table entry if an entry with the matching name is found; + NULL is returned if the entry is not found. +
    + +

    3.3.4 symtab_findorderedbyvalue()

    +

    Function Prototype:

    +
      +#include <:nuttx/binfmt/symtab.h>
      +FAR const struct symtab_s *
      +symtab_findorderedbyvalue(FAR const struct symtab_s *symtab,
      +                          FAR void *value, int nsyms);
      +
    +

    Description:

    +
      + Find the symbol in the symbol table whose value closest (but not greater than), the provided value. + This version assumes that table is ordered with respect to symbol name. +
    +

    Returned Value:

    +
      + A reference to the symbol table entry if an entry with the matching name is found; + NULL is returned if the entry is not found. +
    + + + + + +
    +

    4.0 Configuration Variables

    +
    + +
      +

      + CONFIG_BINFMT_DISABLE: + By default, support for loadable binary formats is built. + This logic may be suppressed be defining this setting. +

      +

      + CONFIG_BINFMT_CONSTRUCTORS: + Build in support for C++ constructors in loaded modules. +

      +

      + CONFIG_SYMTAB_ORDEREDBYNAME: + Symbol tables are order by name (rather than value). +

      +
    + +

    + Additional configuration options may be required for the each enabled binary format. +

    + + diff --git a/nuttx/Documentation/NuttXDocumentation.html b/nuttx/Documentation/NuttXDocumentation.html index b26c831753..b502adc687 100644 --- a/nuttx/Documentation/NuttXDocumentation.html +++ b/nuttx/Documentation/NuttXDocumentation.html @@ -32,6 +32,7 @@
  • User Guide
  • Porting Guide
  • NuttShell (NSH)
  • +
  • Binary Loader
  • NXFLAT
  • NX Graphics
  • NxWidgets
  • diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index dd9d66881f..a2c58b41f8 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -12,7 +12,7 @@

    NuttX RTOS Porting Guide

    -

    Last Updated: October 29, 2012

    +

    Last Updated: October 30, 2012

    @@ -4580,6 +4580,14 @@ build So for the architectures that define CONFIG_ARCH_MATH_H=y, include/math.h will be the redirecting math.h header file; for the architectures that don't select CONFIG_ARCH_MATH_H, the redirecting math.h header file will stay out-of-the-way in include/nuttx/.

    +
  • CONFIG_ARCH_FLOAT_H. +

    + If you enable the generic, built-in math library, then that math library will expect your toolchain to provide the standard float.h header file. + The float.h header file defines the properties of your floating point implementation. + It would always be best to use your toolchain's float.h header file but if none is avaiable, a default float.h header file will provided if this option is selected. + However, there is no assurance that the settings in this float.h are actually correct for your platform! +

    +
  • CONFIG_ARCH_STDARG_H.

    There is also a redirecting version of stdarg.h in the source tree as well. diff --git a/nuttx/Documentation/NuttxUserGuide.html b/nuttx/Documentation/NuttxUserGuide.html index 457347727c..24dc6b6ab7 100644 --- a/nuttx/Documentation/NuttxUserGuide.html +++ b/nuttx/Documentation/NuttxUserGuide.html @@ -186,8 +186,10 @@ paragraphs.

    Executing Programs within a File System. NuttX also provides internal interfaces for the execution of separately built programs that reside in a file system. - These internal interfaces are, however, non-standard and are documented - elsewhere. + These internal interfaces are, however, non-standard and are documented with the + NuttX binary loader and + NXFLAT. +

    Task Control Interfaces. The following task control interfaces are provided by NuttX:

    diff --git a/nuttx/README.txt b/nuttx/README.txt index 4c008e6f16..d567d88c8c 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -154,9 +154,15 @@ Notes about Header Files Even though you should not use a foreign C-Library, you may still need to use other, external libraries with NuttX. In particular, you may - need to use the math library, libm.a. The math libary header file, - math.h, is a special case. If you do nothing, the standard math.h - header file that is provided with your toolchain will be used. + need to use the math library, libm.a. NuttX supports a generic, built-in + math library that can be enabled using CONFIG_LIBM=y. However, you may + still want to use a higher performance external math library that has + been tuned for your CPU. Sometimes such such tuned math libraries are + bundled with your toolchain. + + The math libary header file, math.h, is a then special case. If you do + nothing, the standard math.h header file that is provided with your + toolchain will be used. If you have a custom, architecture specific math.h header file, then that header file should be placed at arch//include/math.h. There @@ -171,6 +177,16 @@ Notes about Header Files than to include that archicture-specific math.h header file as the system math.h header file. + float.h + + If you enable the generic, built-in math library, then that math library + will expect your toolchain to provide the standard float.h header file. + The float.h header file defines the properties of your floating point + implementation. It would always be best to use your toolchain's float.h + header file but if none is avaiable, a default float.h header file will + provided if this option is selected. However, there is no assurance that + the settings in this float.h are actually correct for your platform! + stdarg.h In most cases, the correct version of stdarg.h is the version provided with your toolchain. However, sometimes there are issues with with using your toolchains stdarg.h. For example, it may attempt to draw in header files that do not exist in NuttX or perhaps the header files that is uses are not compatible with the NuttX header files. In those cases, you can use an architecture-specific stdarg.h header file by defining CONFIG_ARCH_STDARG_H=y. diff --git a/nuttx/binfmt/libelf/gnu-elf.ld b/nuttx/binfmt/libelf/gnu-elf.ld index bdf82836b3..b2a3dc1131 100644 --- a/nuttx/binfmt/libelf/gnu-elf.ld +++ b/nuttx/binfmt/libelf/gnu-elf.ld @@ -1,5 +1,5 @@ /**************************************************************************** - * examples/elf/gnu-elf.ld + * binfmt/libelf/gnu-elf.ld * * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -51,8 +51,8 @@ SECTIONS */ *(.gnu.linkonce.t.*) - *(.init) - *(.fini) + *(.init) /* Old ABI */ + *(.fini) /* Old ABI */ _etext = . ; } @@ -86,15 +86,17 @@ SECTIONS .ctors : { - _sctros = . ; - *(.ctors) + _sctors = . ; + *(.ctors) /* Old ABI: Unallocated */ + *(.init_array) /* New ABI: Allocated */ _edtors = . ; } - .ctors : + .dtors : { _sdtors = . ; - *(.dtors) + *(.dtors) /* Old ABI: Unallocated */ + *(.fini_array) /* New ABI: Allocated */ _edtors = . ; } diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 0849837c1f..cca4d7f324 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -723,6 +723,15 @@ defconfig -- This is a configuration file similar to the Linux don't select CONFIG_ARCH_MATH_H, the redirecting math.h header file will stay out-of-the-way in include/nuttx/. + CONFIG_ARCH_FLOAT_H + If you enable the generic, built-in math library, then that math library + will expect your toolchain to provide the standard float.h header file. + The float.h header file defines the properties of your floating point + implementation. It would always be best to use your toolchain's float.h + header file but if none is avaiable, a default float.h header file will + provided if this option is selected. However, there is no assurance that + the settings in this float.h are actually correct for your platform! + CONFIG_ARCH_STDARG_H - There is also a redirecting version of stdarg.h in the source tree as well. It also resides out-of-the-way at include/nuttx/stdarg.h. This is because you should normally use your toolchain's stdarg.h file. But diff --git a/nuttx/include/nuttx/binfmt/symtab.h b/nuttx/include/nuttx/binfmt/symtab.h index 497327031d..346c6099fd 100644 --- a/nuttx/include/nuttx/binfmt/symtab.h +++ b/nuttx/include/nuttx/binfmt/symtab.h @@ -54,7 +54,7 @@ * is a fixed size array of struct symtab_s. The information is intentionally * minimal and supports only: * - * 1. Function points as sym_values. Of other kinds of values need to be + * 1. Function pointers as sym_values. Of other kinds of values need to be * supported, then typing information would also need to be included in * the structure. * From 20ede8d196a4c555505b2628a756e8382739b067 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 30 Oct 2012 19:25:50 +0000 Subject: [PATCH 048/206] Documentation update git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5279 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Documentation/NuttXBinfmt.html | 10 +- nuttx/Documentation/NuttxUserGuide.html | 1417 ++++++++++++----------- nuttx/sched/sched_getscheduler.c | 1 + 3 files changed, 725 insertions(+), 703 deletions(-) diff --git a/nuttx/Documentation/NuttXBinfmt.html b/nuttx/Documentation/NuttXBinfmt.html index 8d70d0135a..71c5b0a003 100644 --- a/nuttx/Documentation/NuttXBinfmt.html +++ b/nuttx/Documentation/NuttXBinfmt.html @@ -50,8 +50,8 @@

    Binary Loaders. The purpose of a binary loader is to load and execute modules in various binary formats that reside in a file system. - Loading refers instiating the binary module in some fashion, usually copy all or some of the binary module into memory and then linking the module with other components. - In most architectures, it is thebase FLASH code that is the primary component that the binary module must link with because that is where the RTOS and primary tasks reside. + Loading refers instantiating the binary module in some fashion, usually copy all or some of the binary module into memory and then linking the module with other components. + In most architectures, it is the base FLASH code that is the primary component that the binary module must link with because that is where the RTOS and primary tasks reside. Program modules can then be executed after they have been loaded.

    @@ -76,14 +76,14 @@ NXFLAT. NuttX NXFLAT formatted files. More information about the NXFLAT binary format can be found in the - NXFLAT documentation. + NXFLAT documentation.

    Executables and Libraries The generic binary loader logic does not care what it is that it being loaded. It could load an executable program or a library. There are no strict rules, but a library will tend to export symbols and a program will tend to import symbols: The program will use the symbols exported by the library. - However, at this point in time, none of the supported binary formts support exporting of symbols. + However, at this point in time, none of the supported binary formats support exporting of symbols.

    @@ -128,7 +128,7 @@ struct binfmt_s

    The load method is used to load the binary format into memory. - It returns either OK (0) meaning that the binary object was loaded successfully, or a negater errno indicating why the object was not loaded. + It returns either OK (0) meaning that the binary object was loaded successfully, or a negated errno indicating why the object was not loaded.

    diff --git a/nuttx/Documentation/NuttxUserGuide.html b/nuttx/Documentation/NuttxUserGuide.html index 24dc6b6ab7..586b744c71 100644 --- a/nuttx/Documentation/NuttxUserGuide.html +++ b/nuttx/Documentation/NuttxUserGuide.html @@ -123,7 +123,7 @@ is discussed. Input Parameters: All input parameters are listed along with brief descriptions of each input parameter.

    -Returned Values: All possible values returned by the interface +Returned Value: All possible values returned by the interface function are listed. Values returned as side-effects (through pointer input parameters or through global variables) will be addressed in the description of the interface function. @@ -207,10 +207,10 @@ paragraphs.

    Function Prototype: -

    -   #include <sched.h>
    -   int task_create(char *name, int priority, int stack_size, main_t entry, const char *argv[]);
    -
    +
      +#include <sched.h>
      +int task_create(char *name, int priority, int stack_size, main_t entry, const char *argv[]);
      +

    Description: @@ -249,18 +249,18 @@ paragraphs.

    Input Parameters:

      -
    • name. Name of the new task
    • -
    • priority. Priority of the new task
    • -
    • stack_size. size (in bytes) of the stack needed
    • -
    • entry. Entry point of a new task
    • -
    • argv. A pointer to an array of input parameters. Up to +
    • name. Name of the new task
    • +
    • priority. Priority of the new task
    • +
    • stack_size. size (in bytes) of the stack needed
    • +
    • entry. Entry point of a new task
    • +
    • argv. A pointer to an array of input parameters. Up to CONFIG_MAX_TASK_ARG parameters may be provided. If fewer than CONFIG_MAX_TASK_ARG parameters are passed, the list should be terminated with a NULL argv[] value. If no parameters are required, argv may be NULL.

    - Returned Values: + Returned Value:

    • @@ -316,13 +316,13 @@ VxWorks provides the following similar interface:

      Input Parameters:

        -
      • tcb. Address of the new task's TCB -
      • name. Name of the new task (not used) -
      • priority. Priority of the new task -
      • stack. Start of the pre-allocated stack -
      • stack_size. size (in bytes) of the pre-allocated stack -
      • entry. Entry point of a new task -
      • argv. A pointer to an array of input parameters. Up to +
      • tcb. Address of the new task's TCB +
      • name. Name of the new task (not used) +
      • priority. Priority of the new task +
      • stack. Start of the pre-allocated stack +
      • stack_size. size (in bytes) of the pre-allocated stack +
      • entry. Entry point of a new task +
      • argv. A pointer to an array of input parameters. Up to CONFIG_MAX_TASK_ARG parameters may be provided. If fewer than CONFIG_MAX_TASK_ARG parameters are passed, the list should be terminated with a NULL argv[] value. @@ -330,7 +330,7 @@ VxWorks provides the following similar interface:

      -Returned Values: +Returned Value:

      • OK, or ERROR if the task cannot be initialized.

        @@ -370,7 +370,7 @@ VxWorks provides the following similar interface: Function Prototype:
             #include <sched.h>
        -    int task_activate( _TCB *tcb );
        +    int task_activate(_TCB *tcb);
         

        @@ -380,12 +380,12 @@ scheduler.

        Input Parameters:

          -
        • tcb. The TCB for the task for the task (same as the +
        • tcb. The TCB for the task for the task (same as the task_init argument).

        -Returned Values: +Returned Value:

        • OK, or ERROR if the task cannot be activated (errno is not set).
        @@ -401,7 +401,7 @@ mechanism to initialize and start a new task. POSIX Compatibility: This is a NON-POSIX interface. VxWorks provides the following similar interface:
        -    STATUS taskActivate( int tid );
        +    STATUS taskActivate(int tid);
         

        @@ -418,50 +418,55 @@ the pointer to the WIND_TCB cast to an integer.

        Function Prototype: -

        -    #include <sched.h>
        -    int task_delete( pid_t pid );
        -
        +
          +#include <sched.h>
          +int task_delete(pid_t pid);
          +

        -Description: This function causes a specified task to cease -to exist -- its stack and TCB will be deallocated. This function -is the companion to task_create(). + Description: + This function causes a specified task to cease to exist -- its stack and TCB will be deallocated. + This function is the companion to task_create().

        Input Parameters:

          -
        • pid. The task ID of the task to delete. An ID of -zero signifies the calling task. +
        • + pid. + The task ID of the task to delete. + An ID of zero signifies the calling task. + Any attempt by the calling task will be automatically re-directed to exit().
        -

        -Returned Values: +Returned Value:

          -
        • OK, or ERROR if the task cannot be deleted. -This function can fail if the provided pid does not correspond to a task (errno is not set) +
        • + OK, or ERROR if the task cannot be deleted. + This function can fail if the provided pid does not correspond to a task (errno is not set). +
        -

        Assumptions/Limitations:

        -task_delete() must be used with caution: If the task holds resources -(for example, allocated memory or semaphores needed by other tasks), then -task_delete() can strand those resources. + task_delete() must be used with caution: + If the task holds resources (for example, allocated memory or semaphores needed by other tasks), then task_delete() can strand those resources. +

        -POSIX Compatibility: This is a NON-POSIX interface. -VxWorks provides the following similar interface: -

        -    STATUS taskDelete( int tid );
        -
        +POSIX Compatibility: + This is a NON-POSIX interface. + VxWorks provides the following similar interface: +

        +
          +STATUS taskDelete(int tid);
          +

        The NuttX task_delete() differs from VxWorks' taskDelete() in the following ways:

          -
        • No support is provided for calling the tasks deletion routines -(because taskDeleteHookAdd() is not supported). -
        • Deletion of self is not supported. Use _exit(); +
        • No support is provided for calling the tasks deletion routines (because the VxWorks taskDeleteHookAdd() is not supported). + However, if atexit() or on_exit support is enabled, those will be called when the task deleted. +
        • Deletion of self is supported, but only because task_delete() will re-direct processing to exit().

        2.1.5 exit

        @@ -470,10 +475,10 @@ VxWorks provides the following similar interface: Function Prototype:
             #include <sched.h>
        -    void exit( int code );
        +    void exit(int code);
         
             #include <nuttx/unistd.h>
        -    void _exit( int code );
        +    void _exit(int code);
         

        @@ -484,11 +489,11 @@ execute any function registered with atexit() or on_exit() Input Parameters:

          -
        • code. (ignored) +
        • code. (ignored)

        -Returned Values: None. +Returned Value: None.

        Assumptions/Limitations: @@ -496,49 +501,59 @@ execute any function registered with atexit() or on_exit() POSIX Compatibility: This is equivalent to the ANSI interface:

        -    void exit( int code );
        +    void exit(int code);
         
        And the UNIX interface:
        -    void _exit( int code );
        +    void _exit(int code);
         

        The NuttX exit() differs from ANSI exit() in the following ways:

          -
        • The code parameter is ignored. +
        • The code parameter is ignored.

        2.1.6 task_restart

        -

        -Function Prototype: -

        -    #include <sched.h>
        -    int task_restart( pid_t pid );
        -
        - +Function Prototype: +
          +#include <sched.h>
          +int task_restart(pid_t pid);
          +

        -Description: This function "restarts" a task. -The task is first terminated and then reinitialized with same -ID, priority, original entry point, stack size, and parameters -it had when it was first started. + Description: + This function "restarts" a task. + The task is first terminated and then reinitialized with same ID, priority, original entry point, stack size, and parameters it had when it was first started.

        -NOTE: The normal task exit clean up is not performed. -For example, file descriptors are not closed; -any files opened prior to the restart will remain opened after the task is restarted. + NOTES:

        +
          +
        1. + The normal task exit clean up is not performed. + For example, file descriptors are not closed; any files opened prior to the restart will remain opened after the task is restarted. +
        2. +
        3. + Memory allocated by the task before it was restart is not freed. + A task that is subject to being restart must be designed in such a way as to avoid memory leaks. +
        4. +
        5. + Initialized data is not reset. + All global or static data is left in the same state as when the task was terminated. + This feature may be used by restart task to detect that it has been restarted, for example. +
        6. +

        Input Parameters:

          -
        • pid. The task ID of the task to delete. An ID of -zero signifies the calling task. +
        • pid. + The task ID of the task to delete. + An ID of zero would signify the calling task (However, support for a task to restart itself has not been implemented).
        -

        -Returned Values: +Returned Value:

        • OK, or ERROR if the task ID is invalid or the task could @@ -546,9 +561,8 @@ zero signifies the calling task. This function can fail if: (1) A pid of zero or the pid of the calling task is provided (functionality not implemented) (2) The pid is not associated with any task known to the system. -
        • +
        -

        Assumptions/Limitations:

        @@ -562,9 +576,13 @@ VxWorks provides the following similar interface: The NuttX task_restart() differs from VxWorks' taskRestart() in the following ways:

          -
        • Restart of the currently running task is not supported. -
        • The VxWorks description says that the ID, priority, etc. take -the value that they had when the task was terminated. +
        • + Restart of the currently running task is not supported by NuttX. +
        • +
        • + The VxWorks description says that the ID, priority, etc. take + the value that they had when the task was terminated. +

        2.1.7 getpid

        @@ -573,7 +591,7 @@ the value that they had when the task was terminated. Function Prototype:
             #include <unistd.h>
        -    pid_t getpid( void );
        +    pid_t getpid(void);
         

        @@ -583,7 +601,7 @@ level.

        Input Parameters: None.

        -Returned Values: +Returned Value:

        • The task ID of the calling task.
        @@ -663,9 +681,9 @@ Compatible with the POSIX interface of the same name.

      - Returned Values: - On success, sched_setparam() returns 0 (OK). - On error, -1 (ERROR) is returned, and errno is set appropriately. + Returned Value: + On success, sched_setparam() returns 0 (OK). + On error, -1 (ERROR) is returned, and errno is set appropriately.

        @@ -721,9 +739,9 @@ of the task specified by pid.

      -Returned Values: +Returned Value:

        -
      • 0 (OK) if successful, otherwise -1 (ERROR). +
      • 0 (OK) if successful, otherwise -1 (ERROR).

      @@ -734,101 +752,90 @@ interface of the same name.

      2.2.3 sched_setscheduler

      -Function Prototype: -

      -    #include <sched.h>
      -    int sched_setscheduler (pid_t pid, int policy, const struct sched_param *param);
      -
      + Function Prototype: +

      +
        +#include <sched.h>
        +int sched_setscheduler (pid_t pid, int policy, const struct sched_param *param);
        +

      Description: - sched_setscheduler() sets both the scheduling policy - and the priority for the task identified by pid. - If pid equals zero, the scheduler of the calling - thread will be set. - The parameter 'param' holds the priority of the thread under the new policy. + sched_setscheduler() sets both the scheduling policyand the priority for the task identified by pid. + If pid equals zero, the scheduler of the calling thread will be set. + The parameter param holds the priority of the thread under the new policy.

      -Input Parameters: + Input Parameters: +

      • - pid. The task ID of the task. If pid is zero, the - priority of the calling task is set. + pid. + The task ID of the task. + If pid is zero, the priority of the calling task is set.
      • - policy. Scheduling policy requested (either SCHED_FIFO or SCHED_RR). + policy. + Scheduling policy requested (either SCHED_FIFO or SCHED_RR).
      • - param. A structure whose member sched_priority is the - integer priority. The range of valid priority numbers is from - SCHED_PRIORITY_MIN through SCHED_PRIORITY_MAX. + param. + A structure whose member sched_priority is the integer priority. + The range of valid priority numbers is from SCHED_PRIORITY_MIN through SCHED_PRIORITY_MAX.

      - Returned Values: - On success, sched_setscheduler() returns OK (zero). On - error, ERROR (-1) is returned, and errno is set appropriately: + Returned Value: + On success, sched_setscheduler() returns OK (zero). On + error, ERROR (-1) is returned, and errno is set appropriately:

        -
      • EINVAL The scheduling policy is not one of the - recognized policies.
      • -
      • ESRCH The task whose ID is pid could not be found.
      • +
      • EINVAL: The scheduling policy is not one of the recognized policies.
      • +
      • ESRCH: The task whose ID is pid could not be found.
      -

      -Assumptions/Limitations: + Assumptions/Limitations: +

      - POSIX Compatibility: Comparable to the POSIX -interface of the same name. + POSIX Compatibility: Comparable to the POSIX interface of the same name. +

      2.2.4 sched_getscheduler

      Function Prototype: -

      -    #include <sched.h>
      -    int sched_getscheduler (pid_t pid);
      -
      +
        +#include <sched.h>
        +int sched_getscheduler (pid_t pid);
        +

      Description: - sched_getscheduler() returns the scheduling policy - currently applied to the task identified by pid. If - pid equals zero, the policy of the calling process will + sched_getscheduler() returns the scheduling policy + currently applied to the task identified by pid. If + pid equals zero, the policy of the calling process will be retrieved. - * - * Inputs: - * - * Return Value: - - This function returns the current scheduling -policy.

      Input Parameters:

        -
      • pid. +
      • pid. The task ID of the task to query. - If pid is zero, the calling task is queried. + If pid is zero, the calling task is queried.

      -Returned Values: +Returned Value:

      • - On success, sched_getscheduler() returns the policy for - the task (either SCHED_FIFO or SCHED_RR). - On error, ERROR (-1) is returned, and errno is set appropriately: + On success, sched_getscheduler() returns the policy for + the task (either SCHED_FIFO or SCHED_RR). + On error, ERROR (-1) is returned, and errno is set appropriately:
          -
        • ESRCH The task whose ID is pid could not be found.
        • +
        • ESRCH: The task whose ID is pid could not be found.

      Assumptions/Limitations:

      - POSIX Compatibility: Comparable to the POSIX -interface of the same name. -Differences from the full POSIX implementation include: -

        -
      • Does not report errors via errno. -
      + POSIX Compatibility: Comparable to the POSIX interface of the same name.

      2.2.5 sched_yield

      @@ -836,7 +843,7 @@ Differences from the full POSIX implementation include: Function Prototype:
           #include <sched.h>
      -    int sched_yield( void );
      +    int sched_yield(void);
       

      @@ -845,9 +852,9 @@ up the CPU (only to other tasks at the same priority).

      Input Parameters: None.

      -Returned Values: +Returned Value:

        -
      • 0 (OK) or -1 (ERROR) +
      • 0 (OK) or -1 (ERROR)

      @@ -871,13 +878,13 @@ possible task priority for a specified scheduling policy.

      Input Parameters:

        -
      • policy. Scheduling policy requested. +
      • policy. Scheduling policy requested.

      -Returned Values: +Returned Value:

        -
      • The maximum priority value or -1 (ERROR). +
      • The maximum priority value or -1 (ERROR).

      @@ -901,13 +908,13 @@ possible task priority for a specified scheduling policy.

      Input Parameters:

        -
      • policy. Scheduling policy requested. +
      • policy. Scheduling policy requested.

      -Returned Values: +Returned Value:

        -
      • The minimum priority value or -1 (ERROR) +
      • The minimum priority value or -1 (ERROR)

      @@ -927,9 +934,9 @@ interface of the same name.

      Description: - sched_rr_get_interval() writes the timeslice interval - for task identified by pid into the timespec structure - pointed to by interval. If pid is zero, the timeslice + sched_rr_get_interval() writes the timeslice interval + for task identified by pid into the timespec structure + pointed to by interval. If pid is zero, the timeslice for the calling process is written into 'interval. The identified process should be running under the SCHED_RR scheduling policy.' @@ -938,21 +945,21 @@ interface of the same name. Input Parameters:

        -
      • pid. The task ID of the task. If pid is zero, the +
      • pid. The task ID of the task. If pid is zero, the priority of the calling task is returned. -
      • interval. A structure used to return the time slice. +
      • interval. A structure used to return the time slice.

      - Returned Values: + Returned Value: On success, sched_rr_get_interval() returns OK (0). On error, ERROR (-1) is returned, and errno is set to:

        -
      • EFAULT Cannot copy to interval
      • -
      • EINVAL Invalid pid.
      • -
      • ENOSYS The system call is not yet implemented.
      • -
      • ESRCH The process whose ID is pid could not be found.
      • +
      • EFAULT: Cannot copy to interval
      • +
      • EINVAL: Invalid pid.
      • +
      • ENOSYS: The system call is not yet implemented.
      • +
      • ESRCH: The process whose ID is pid could not be found.

      @@ -989,7 +996,7 @@ priority of the calling task is returned. Function Prototype:

           #include <sched.h>
      -    int sched_lock( void );
      +    int sched_lock(void);
       

      @@ -1001,7 +1008,7 @@ number of times) or until it blocks itself.

      Input Parameters: None.

      -Returned Values: +Returned Value:

      • OK or ERROR.
      @@ -1012,7 +1019,7 @@ number of times) or until it blocks itself. POSIX Compatibility: This is a NON-POSIX interface. VxWorks provides the comparable interface:
      -    STATUS taskLock( void );
      +    STATUS taskLock(void);
       

      2.3.2 sched_unlock

      @@ -1021,7 +1028,7 @@ VxWorks provides the comparable interface: Function Prototype:
           #include <sched.h>
      -    int sched_unlock( void );
      +    int sched_unlock(void);
       

      @@ -1034,7 +1041,7 @@ eligible to preempt the current task will execute.

      Input Parameters: None.

      -Returned Values: +Returned Value:

      • OK or ERROR.
      @@ -1045,7 +1052,7 @@ eligible to preempt the current task will execute. POSIX Compatibility: This is a NON-POSIX interface. VxWorks provides the comparable interface:
      -    STATUS taskUnlock( void );
      +    STATUS taskUnlock(void);
       

      2.3.3 sched_lockcount

      @@ -1054,7 +1061,7 @@ VxWorks provides the comparable interface: Function Prototype:
           #include <sched.h>
      -    int32_t sched_lockcount( void )
      +    int32_t sched_lockcount(void)
       

      @@ -1065,7 +1072,7 @@ on this thread of execution.

      Input Parameters: None.

      -Returned Values: +Returned Value:

      • The current value of the lockCount.
      @@ -1152,7 +1159,7 @@ on this thread of execution.

    - If the calling process has SA_NOCLDWAIT set or has SIGCHLD set to SIG_IGN, and the process has no unwaited-for children that were transformed into zombie processes, the calling thread will block until all of the children of the process containing the calling thread terminate, and waitpid() will fail and set errno to ECHILD. + If the calling process has SA_NOCLDWAIT set or has SIGCHLD set to SIG_IGN, and the process has no unwaited-for children that were transformed into zombie processes, the calling thread will block until all of the children of the process containing the calling thread terminate, and waitpid() will fail and set errno to ECHILD.

    If waitpid() returns because the status of a child process is available, these functions will return a value equal to the process ID of the child process. @@ -1204,7 +1211,7 @@ on this thread of execution.

  • - Returned Values: + Returned Value:

    If waitpid() returns because the status of a child process is available, it will return a value equal to the process ID of the child process for which status is reported. @@ -1261,10 +1268,10 @@ on this thread of execution. Input Parameters:

      -
    • func. A pointer to the function to be called when the task exits.
    • +
    • func. A pointer to the function to be called when the task exits.

    - Returned Values: + Returned Value: On success, atexit() returns OK (0). On error, ERROR (-1) is returned, and errno is set to indicate the cause of the failure.

    @@ -1301,11 +1308,11 @@ on this thread of execution. Input Parameters:

      -
    • func. A pointer to the function to be called when the task exits.
    • -
    • arg. An argument that will be provided to the on_exit() function when the task exits.
    • +
    • func. A pointer to the function to be called when the task exits.
    • +
    • arg. An argument that will be provided to the on_exit() function when the task exits.

    - Returned Values: + Returned Value: On success, on_exit() returns OK (0). On error, ERROR (-1) is returned, and errno is set to indicate the cause of the failure.

    @@ -1355,7 +1362,7 @@ on this thread of execution. Function Prototype:
         #include <mqueue.h>
    -    mqd_t mq_open( const char *mqName, int oflags, ... );
    +    mqd_t mq_open(const char *mqName, int oflags, ...);
     

    @@ -1367,27 +1374,27 @@ until it is closed by a successful call to mq_close().

    Input Parameters:

      -
    • mqName. Name of the queue to open -
    • oflags. Open flags. These may be any combination of: +
    • mqName. Name of the queue to open +
    • oflags. Open flags. These may be any combination of:
        -
      • O_RDONLY. Open for read access. -
      • O_WRONLY. Open for write access. -
      • O_RDWR. Open for both read & write access. -
      • O_CREAT. Create message queue if it does not already +
      • O_RDONLY. Open for read access. +
      • O_WRONLY. Open for write access. +
      • O_RDWR. Open for both read & write access. +
      • O_CREAT. Create message queue if it does not already exist. -
      • O_EXCL. Name must not exist when opened. -
      • O_NONBLOCK. Don't wait for data. +
      • O_EXCL. Name must not exist when opened. +
      • O_NONBLOCK. Don't wait for data.
      -
    • ... Optional parameters. +
    • ... Optional parameters. When the O_CREAT flag is specified, POSIX requires that a third and fourth parameter be supplied:
        -
      • mode. The mode parameter is of type mode_t. In the POSIX +
      • mode. The mode parameter is of type mode_t. In the POSIX specification, this mode value provides file permission bits for the message queue. This parameter is required but not used in the present implementation. -
      • attr. A pointer to an mq_attr that is provided to initialize. +
      • attr. A pointer to an mq_attr that is provided to initialize. the message queue. If attr is NULL, then the messages queue is created with implementation-defined default message queue attributes. If attr is non-NULL, then the message queue mq_maxmsg attribute is set to the @@ -1401,9 +1408,9 @@ message that can be sent or received. Other elements of attr are ignored

      -Returned Values: +Returned Value:

        -
      • A message queue descriptor or -1 (ERROR) +
      • A message queue descriptor or -1 (ERROR)

      @@ -1424,7 +1431,7 @@ message size is limited at 22 bytes. Function Prototype:

           #include <mqueue.h>
      -    int mq_close( mqd_t mqdes );
      +    int mq_close(mqd_t mqdes);
       

      @@ -1434,30 +1441,32 @@ The mq_close() deallocates any system resources allocated by the system for use by this task for its message queue.

      If the calling task has attached a notification request to the message -queue via this mqdes (see mq_notify()), this attachment will be +queue via this mqdes (see mq_notify()), this attachment will be removed and the message queue is available for another task to attach for notification.

      Input Parameters:

        -
      • mqdes. Message queue descriptor. +
      • mqdes. Message queue descriptor.

      -Returned Values: +Returned Value:

        -
      • 0 (OK) if the message queue is closed successfully, otherwise, --1 (ERROR). +
      • 0 (OK) if the message queue is closed successfully, otherwise, +-1 (ERROR).

      Assumptions/Limitations:

        -
      • The behavior of a task that is blocked on either a mq_send() or -mq_receive() is undefined when mq_close() is called. -
      • The result of using this message queue descriptor after successful -return from mq_close() is undefined. +
      • + The behavior of a task that is blocked on either a mq_send() or mq_receive() is undefined when mq_close() is called. +
      • +
      • + The result of using this message queue descriptor after successful return from mq_close() is undefined. +

      POSIX Compatibility: Comparable to the POSIX interface @@ -1469,7 +1478,7 @@ of the same name. Function Prototype:

           #include <mqueue.h>
      -    int mq_unlink( const char *mqName );
      +    int mq_unlink(const char *mqName);
       

      @@ -1481,11 +1490,11 @@ closed.

      Input Parameters:

        -
      • mqName. Name of the message queue +
      • mqName. Name of the message queue

      -Returned Values: None. +Returned Value: None.

      Assumptions/Limitations:

      @@ -1502,8 +1511,7 @@ interface of the same name.

      Description: - This function adds the specified message, msg, - to the message queue, mqdes. + This function adds the specified message, msg, to the message queue, mqdes. The msglen parameter specifies the length of the message in bytes pointed to by msg. This length must not exceed the maximum message length from the mq_getattr().

      @@ -1523,8 +1531,22 @@ interface of the same name. is not queued and ERROR is returned.

      -NOTE: mq_send() may be called from an interrupt handler. -

      + NOTE: + mq_send() may be called from an interrupt handler. + However, it behaves differently when called from the interrupt level: +

      +
        +
      • + It does not check the size of the queue. + It will always post the message, even if there is already too many messages in queue. + This is because the interrupt handler does not have the option of waiting for the message queue to become non-full. +
      • +
      • + It doesn't allocate new memory (because you cannot allocate memory from an interrup handler). + Instead, there are are pool of pre-allocated message structures that may be used just for sending messages from interrupt handlers. + The number of such pre-allocated messages is a configuration parameter. +
      • +

      Input Parameters:

      @@ -1535,7 +1557,7 @@ interface of the same name.
    • prio. The priority of the message.

    - Returned Values: + Returned Value: On success, mq_send() returns 0 (OK); on error, -1 (ERROR) is returned, with errno set to indicate the error: @@ -1618,7 +1640,7 @@ interface of the same name.

  • prio. The priority of the message.
  • - Returned Values: + Returned Value: On success, mq_send() returns 0 (OK); on error, -1 (ERROR) is returned, with errno set to indicate the error: @@ -1689,7 +1711,7 @@ interface of the same name.

  • prio. If not NULL, the location to store message priority.

    - Returned Values:. + Returned Value:. One success, the length of the selected message in bytes is returned. On failure, -1 (ERROR) is returned and the errno is set appropriately:

    @@ -1770,7 +1792,7 @@ interface of the same name.
  • abstime. The absolute time to wait until a timeout is declared.

    - Returned Values:. + Returned Value:. One success, the length of the selected message in bytes is returned. On failure, -1 (ERROR) is returned and the errno is set appropriately:

    @@ -1848,7 +1870,7 @@ interface of the same name.

    - Returned Values: + Returned Value: On success mq_notify() returns 0; on error, -1 is returned, with errno set to indicate the error:

      @@ -1881,10 +1903,10 @@ interface of the same name. another task is waiting for the message queue to become non-empty. This is inconsistent with the POSIX specification which states, "If a process has registered for notification of message arrival at a message queue and - some process is blocked in mq_receive waiting to receive a message - when a message arrives at the queue, the arriving message shall satisfy the - appropriate mq_receive() ... The resulting behavior is as if the - message queue remains empty, and no notification shall be sent." + some process is blocked in mq_receive waiting to receive a message + when a message arrives at the queue, the arriving message will satisfy the + appropriate mq_receive() ... The resulting behavior is as if the + message queue remains empty, and no notification will be sent."

    @@ -1895,8 +1917,8 @@ interface of the same name. Function Prototype:
         #include <mqueue.h>
    -    int mq_setattr( mqd_t mqdes, const struct mq_attr *mqStat,
    -                     struct mq_attr *oldMqStat);
    +    int mq_setattr(mqd_t mqdes, const struct mq_attr *mqStat,
    +                   struct mq_attr *oldMqStat);
     

    @@ -1910,16 +1932,16 @@ would have been returned by mq_getattr()).

    Input Parameters:

      -
    • mqdes. Message queue descriptor -
    • mqStat. New attributes -
    • oldMqState. Old attributes +
    • mqdes. Message queue descriptor +
    • mqStat. New attributes +
    • oldMqState. Old attributes

    -Returned Values: +Returned Value:

      -
    • 0 (OK) if attributes are set successfully, otherwise -1 -(ERROR). +
    • 0 (OK) if attributes are set successfully, otherwise -1 +(ERROR).

    @@ -1934,7 +1956,7 @@ interface of the same name. Function Prototype:

         #include <mqueue.h>
    -    int mq_getattr( mqd_t mqdes, struct mq_attr *mqStat);
    +    int mq_getattr(mqd_t mqdes, struct mq_attr *mqStat);
     

    @@ -1943,22 +1965,22 @@ attributes associated with the specified message queue.

    Input Parameters:

      -
    • mqdes. Message queue descriptor -
    • mqStat. Buffer in which to return attributes. The returned +
    • mqdes. Message queue descriptor +
    • mqStat. Buffer in which to return attributes. The returned attributes include:
        -
      • mq_maxmsg. Max number of messages in queue. -
      • mq_msgsize. Max message size. -
      • mq_flags. Queue flags. -
      • mq_curmsgs. Number of messages currently in queue. +
      • mq_maxmsg. Max number of messages in queue. +
      • mq_msgsize. Max message size. +
      • mq_flags. Queue flags. +
      • mq_curmsgs. Number of messages currently in queue.

    -Returned Values: +Returned Value:

      -
    • 0 (OK) if attributes provided, -1 (ERROR) otherwise. +
    • 0 (OK) if attributes provided, -1 (ERROR) otherwise.

    @@ -2121,7 +2143,7 @@ interface of the same name. Function Prototype:

         #include <semaphore.h>
    -    int sem_init ( sem_t *sem, int pshared, unsigned int value );
    +    int sem_init(sem_t *sem, int pshared, unsigned int value);
     

    @@ -2130,22 +2152,22 @@ sem. Following a successful call to sem_init(), the semaphore may be used in subsequent calls to sem_wait(), sem_post(), and sem_trywait(). The semaphore remains usable until it is destroyed.

    -Only sem itself may be used for performing synchronization. The -result of referring to copies of sem in calls to sem_wait(), -sem_trywait(), sem_post(), and sem_destroy(), is +Only sem itself may be used for performing synchronization. The +result of referring to copies of sem in calls to sem_wait(), +sem_trywait(), sem_post(), and sem_destroy(), is not defined.

    Input Parameters:

      -
    • sem. Semaphore to be initialized -
    • pshared. Process sharing (not used) -
    • value. Semaphore initialization value +
    • sem. Semaphore to be initialized +
    • pshared. Process sharing (not used) +
    • value. Semaphore initialization value

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) if unsuccessful. +
    • 0 (OK), or -1 (ERROR) if unsuccessful.

    @@ -2164,29 +2186,29 @@ Differences from the full POSIX implementation include: Function Prototype:

         #include <semaphore.h>
    -    int sem_destroy ( sem_t *sem );
    +    int sem_destroy(sem_t *sem);
     

    Description: This function is used to destroy the un-named semaphore -indicated by sem. Only a semaphore that was created using -sem_init() may be destroyed using sem_destroy(). The effect -of calling sem_destroy() with a named semaphore is undefined. The -effect of subsequent use of the semaphore sem is undefined until -sem is re-initialized by another call to sem_init(). +indicated by sem. Only a semaphore that was created using +sem_init() may be destroyed using sem_destroy(). The effect +of calling sem_destroy() with a named semaphore is undefined. The +effect of subsequent use of the semaphore sem is undefined until +sem is re-initialized by another call to sem_init().

    The effect of destroying a semaphore upon which other tasks are currently blocked is undefined.

    Input Parameters:

      -
    • sem. Semaphore to be destroyed. +
    • sem. Semaphore to be destroyed.

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) if unsuccessful. +
    • 0 (OK), or -1 (ERROR) if unsuccessful.

    @@ -2201,7 +2223,7 @@ interface of the same name. Function Prototype:

         #include <semaphore.h>
    -    sem_t *sem_open ( const char *name, int oflag, ...);
    +    sem_t *sem_open(const char *name, int oflag, ...);
     

    @@ -2219,35 +2241,35 @@ been no calls to sem_unlink()).

    Input Parameters:

      -
    • name. Semaphore name -
    • oflag. Semaphore creation options. This may one of +
    • name. Semaphore name +
    • oflag. Semaphore creation options. This may one of the following bit settings:
        -
      • oflag = 0: Connect to the semaphore only if it already +
      • oflag = 0: Connect to the semaphore only if it already exists. -
      • oflag = O_CREAT: Connect to the semaphore if it exists, +
      • oflag = O_CREAT: Connect to the semaphore if it exists, otherwise create the semaphore. -
      • oflag = O_CREAT with O_EXCL (O_CREAT|O_EXCL): Create +
      • oflag = O_CREAT with O_EXCL (O_CREAT|O_EXCL): Create a new semaphore unless one of this name already exists.
    • ... Optional parameters. NOTE: When the O_CREAT flag is specified, POSIX requires that a third and fourth parameter be supplied:
        -
      • mode. The mode parameter is of type mode_t. +
      • mode. The mode parameter is of type mode_t. This parameter is required but not used in the present implementation. -
      • value. The value parameter is type unsigned int. The semaphore -is created with an initial value of value. Valid initial values for -semaphores must be less than or equal to SEM_VALUE_MAX (defined in +
      • value. The value parameter is type unsigned int. The semaphore +is created with an initial value of value. Valid initial values for +semaphores must be less than or equal to SEM_VALUE_MAX (defined in include/limits.h).

    -Returned Values: +Returned Value:

      -
    • A pointer to sem_t or -1 (ERROR) if unsuccessful. +
    • A pointer to sem_t or -1 (ERROR) if unsuccessful.

    @@ -2267,7 +2289,7 @@ just a counting semaphore. Function Prototype:

         #include <semaphore.h>
    -    int sem_close ( sem_t *sem );
    +    int sem_close(sem_t *sem);
     

    @@ -2286,13 +2308,13 @@ that another calling task has already locked.

    Input Parameters:

      -
    • sem. Semaphore descriptor +
    • sem. Semaphore descriptor

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) if unsuccessful. +
    • 0 (OK), or -1 (ERROR) if unsuccessful.

    @@ -2312,7 +2334,7 @@ interface of the same name. Function Prototype:

         #include <semaphore.h>
    -    int sem_unlink ( const char *name );
    +    int sem_unlink(const char *name);
     

    @@ -2324,13 +2346,13 @@ sem_close().

    Input Parameters:

      -
    • name. Semaphore name +
    • name. Semaphore name

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) if unsuccessful. +
    • 0 (OK), or -1 (ERROR) if unsuccessful.

    @@ -2358,7 +2380,7 @@ same name should be created after sem_unlink() is called. Function Prototype:

         #include <semaphore.h>
    -    int sem_wait ( sem_t *sem );
    +    int sem_wait(sem_t *sem);
     

    @@ -2369,23 +2391,23 @@ the lock or the call is interrupted by a signal.

    Input Parameters:

      -
    • sem. Semaphore descriptor. +
    • sem. Semaphore descriptor.

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) is unsuccessful +
    • 0 (OK), or -1 (ERROR) is unsuccessful

    -If sem_wait returns -1 (ERROR) then the cause of the failure +If sem_wait returns -1 (ERROR) then the cause of the failure will be indicated by the thread-specific errno. The following lists the possible values for errno:

      -
    • EINVAL: Indicates that the sem input parameter is +
    • EINVAL: Indicates that the sem input parameter is not valid. -
    • EINTR: Indicates that the wait was interrupt by a signal +
    • EINTR: Indicates that the wait was interrupt by a signal received by this task. In this case, the semaphore has not be acquired.

    @@ -2401,7 +2423,7 @@ interface of the same name.

         #include <semaphore.h>
         #include <time.h>
    -    int sem_wait ( sem_t *sem, const struct timespec *abstime);
    +    int sem_wait(sem_t *sem, const struct timespec *abstime);
     

    @@ -2416,20 +2438,20 @@ interface of the same name. Input Parameters:

    • - sem. Semaphore descriptor. + sem. Semaphore descriptor.
    • - abstime. The absolute time to wait until a timeout is declared. + abstime. The absolute time to wait until a timeout is declared.

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) is unsuccessful +
    • 0 (OK), or -1 (ERROR) is unsuccessful

    -If sem_wait returns -1 (ERROR) then the cause of the failure +If sem_wait returns -1 (ERROR) then the cause of the failure will be indicated by the thread-specific errno. The following lists the possible values for errno:

    @@ -2437,7 +2459,7 @@ The following lists the possible values for errno

  • EINVAL: - Indicates that the sem input parameter is not valid or the + Indicates that the sem input parameter is not valid or the thread would have blocked, and the abstime parameter specified a nanoseconds field value less than zero or greater than or equal to 1000 million. @@ -2469,7 +2491,7 @@ The following lists the possible values for errnoFunction Prototype:
         #include <semaphore.h>
    -    int sem_trywait ( sem_t *sem );
    +    int sem_trywait(sem_t *sem);
     

    @@ -2479,22 +2501,22 @@ returns without blocking.

    Input Parameters:

      -
    • sem. The semaphore descriptor +
    • sem. The semaphore descriptor

    -Returned Values: +Returned Value:

      -
    • 0 (OK) or -1 (ERROR) if unsuccessful +
    • 0 (OK) or -1 (ERROR) if unsuccessful
    -If sem_wait returns -1 (ERROR) then the cause of the failure +If sem_wait returns -1 (ERROR) then the cause of the failure will be indicated by the thread-specific
    errno. The following lists the possible values for errno:

      -
    • EINVAL: Indicates that the sem input parameter is +
    • EINVAL: Indicates that the sem input parameter is not valid. -
    • EAGAIN: Indicates that the semaphore was not acquired. +
    • EAGAIN: Indicates that the semaphore was not acquired.

    @@ -2510,13 +2532,13 @@ interface of the same name. Function Prototype:

         #include <semaphore.h>
    -    int sem_post ( sem_t *sem );
    +    int sem_post(sem_t *sem);
     

    Description: When a task has finished with a semaphore, it will call sem_post(). This function unlocks the semaphore referenced -by sem by performing the semaphore unlock operation. +by sem by performing the semaphore unlock operation.

    If the semaphore value resulting from this operation is positive, then no tasks were blocked waiting for the semaphore to become unlocked; @@ -2524,19 +2546,19 @@ The semaphore value is simply incremented.

    If the value of the semaphore resulting from this operation is zero, then on of the tasks blocked waiting for the semaphore will be allowed to -return successfully from its call to sem_wait(). +return successfully from its call to sem_wait().

    -NOTE: sem_post() may be called from an interrupt handler. +NOTE: sem_post() may be called from an interrupt handler.

    Input Parameters:

      -
    • sem. Semaphore descriptor +
    • sem. Semaphore descriptor

    -Returned Values: +Returned Value:

      -
    • 0 (OK) or -1 (ERROR) if unsuccessful. +
    • 0 (OK) or -1 (ERROR) if unsuccessful.

    @@ -2553,7 +2575,7 @@ interface of the same name. Function Prototype:

         #include <semaphore.h>
    -    int sem_getvalue ( sem_t *sem, int *sval );
    +    int sem_getvalue(sem_t *sem, int *sval);
     

    @@ -2570,14 +2592,14 @@ number of tasks waiting for the semaphore.

    Input Parameters:

      -
    • sem. Semaphore descriptor -
    • sval. Buffer by which the value is returned +
    • sem. Semaphore descriptor +
    • sval. Buffer by which the value is returned

    -Returned Values: +Returned Value:

      -
    • 0 (OK) or -1 (ERROR) if unsuccessful. +
    • 0 (OK) or -1 (ERROR) if unsuccessful.

    @@ -2618,7 +2640,7 @@ interface of the same name. Function Prototype:

         #include <wdog.h>
    -    WDOG_ID wd_create (void);
    +    WDOG_ID wd_create(void);
     

    @@ -2627,7 +2649,7 @@ by allocating the appropriate resources for the watchdog.

    Input Parameters: None.

    -Returned Values: +Returned Value:

    • Pointer to watchdog that may be used as a handle in subsequent NuttX calls (i.e., the watchdog ID), or NULL if insufficient resources @@ -2656,7 +2678,7 @@ initialization time). Function Prototype:
           #include <wdog.h>
      -    int wd_delete (WDOG_ID wdog);
      +    int wd_delete(WDOG_ID wdog);
       

      @@ -2666,12 +2688,12 @@ has been started.

      Input Parameters:

        -
      • wdog. The watchdog ID to delete. This is actually a +
      • wdog. The watchdog ID to delete. This is actually a pointer to a watchdog structure.

      -Returned Values: +Returned Value:

      • OK or ERROR
      @@ -2700,8 +2722,8 @@ before deallocating it (i.e., never returns ERROR). Function Prototype:
           #include <wdog.h>
      -    int wd_start( WDOG_ID wdog, int delay, wdentry_t wdentry,
      -                     intt argc, ....);
      +    int wd_start(WDOG_ID wdog, int delay, wdentry_t wdentry,
      +                 int argc, ....);
       

      @@ -2720,15 +2742,15 @@ wd_start() on a given watchdog ID has any effect.

      Input Parameters:

        -
      • wdog. Watchdog ID -
      • delay. Delay count in clock ticks -
      • wdentry. Function to call on timeout -
      • argc. The number of uint32_t parameters to pass to wdentry. -
      • .... uint32_t size parameters to pass to wdentry +
      • wdog. Watchdog ID +
      • delay. Delay count in clock ticks +
      • wdentry. Function to call on timeout +
      • argc. The number of uint32_t parameters to pass to wdentry. +
      • .... uint32_t size parameters to pass to wdentry

      -Returned Values: +Returned Value:

      • OK or ERROR
      @@ -2757,7 +2779,7 @@ number of parameters is determined by Function Prototype:
           #include <wdog.h>
      -    int wd_cancel (WDOG_ID wdog);
      +    int wd_cancel(WDOG_ID wdog);
       

      @@ -2767,11 +2789,11 @@ level.

      Input Parameters:

        -
      • wdog. ID of the watchdog to cancel. +
      • wdog. ID of the watchdog to cancel.

      -Returned Values: +Returned Value:

      • OK or ERROR
      @@ -2852,10 +2874,10 @@ VxWorks provides the following comparable interface:
    • parm.

    - Returned Values: + Returned Value:

    - If successful, the clock_settime() function will return zero (OK). + If successful, the clock_settime() function will return zero (OK). Otherwise, an non-zero error number will be returned to indicate the error:

      @@ -2880,10 +2902,10 @@ VxWorks provides the following comparable interface:
    • parm.

    - Returned Values: + Returned Value:

    - If successful, the clock_gettime() function will return zero (OK). + If successful, the clock_gettime() function will return zero (OK). Otherwise, an non-zero error number will be returned to indicate the error:

      @@ -2908,10 +2930,10 @@ VxWorks provides the following comparable interface:
    • parm.

    - Returned Values: + Returned Value:

    - If successful, the clock_getres() function will return zero (OK). + If successful, the clock_getres() function will return zero (OK). Otherwise, an non-zero error number will be returned to indicate the error:

      @@ -2936,10 +2958,10 @@ VxWorks provides the following comparable interface:
    • parm.

    - Returned Values: + Returned Value:

    - If successful, the mktime() function will return zero (OK). + If successful, the mktime() function will return zero (OK). Otherwise, an non-zero error number will be returned to indicate the error:

      @@ -2968,10 +2990,10 @@ VxWorks provides the following comparable interface:

    - Returned Values: + Returned Value:

    - If successful, the gmtime() function will return the pointer to a statically + If successful, the gmtime() function will return the pointer to a statically defined instance of struct tim. Otherwise, a NULL will be returned to indicate the error:

    @@ -3008,10 +3030,10 @@ VxWorks provides the following comparable interface: A user-provided buffer to receive the converted time structure.

    - Returned Values: + Returned Value:

    - If successful, the gmtime_r() function will return the pointer, result, + If successful, the gmtime_r() function will return the pointer, result, provided by the caller. Otherwise, a NULL will be returned to indicate the error:

    @@ -3055,7 +3077,7 @@ VxWorks provides the following comparable interface:

    Each implementation defines a set of clocks that can be used as timing bases - for per-thread timers. All implementations shall support a clock_id of + for per-thread timers. All implementations will support a clock_id of CLOCK_REALTIME.

    @@ -3069,7 +3091,7 @@ VxWorks provides the following comparable interface:

  • timerid. The pre-thread timer created by the call to timer_create().
  • - Returned Values: + Returned Value:

    If the call succeeds, timer_create() will return 0 (OK) and update the @@ -3119,11 +3141,11 @@ VxWorks provides the following comparable interface: The pre-thread timer, previously created by the call to timer_create(), to be deleted.

    - Returned Values: + Returned Value:

    - If successful, the timer_delete() function will return zero (OK). - Otherwise, the function will return a value of -1 (ERROR) and set + If successful, the timer_delete() function will return zero (OK). + Otherwise, the function will return a value of -1 (ERROR) and set errno to indicate the error:

      @@ -3197,11 +3219,11 @@ VxWorks provides the following comparable interface:
    • ovalue. A location in which to return the time remaining from the previous timer setting (ignored).

    - Returned Values: + Returned Value:

    - If the timer_gettime() succeeds, a value of 0 (OK) will be returned. - If an error occurs, the value -1 (ERROR) will be returned, and + If the timer_gettime() succeeds, a value of 0 (OK) will be returned. + If an error occurs, the value -1 (ERROR) will be returned, and errno set to indicate the error.

      @@ -3248,10 +3270,10 @@ VxWorks provides the following comparable interface: timer_create(), whose remaining count will be returned.

    - Returned Values: + Returned Value:

    - If successful, the timer_gettime() function will return zero (OK). + If successful, the timer_gettime() function will return zero (OK). Otherwise, an non-zero error number will be returned to indicate the error:

      @@ -3302,7 +3324,7 @@ VxWorks provides the following comparable interface: timer_create(), whose overrun count will be returned.

    - Returned Values: + Returned Value: If the timer_getoverrun() function succeeds, it will return the timer expiration overrun count as explained above. timer_getoverrun() will fail if:

    @@ -3348,7 +3370,7 @@ interface of the same name.
  • tzp. A reference to the timezone -- IGNORED.
  • - Returned Values: + Returned Value: See clock_gettime().

    @@ -3414,13 +3436,13 @@ by set such that all signals are excluded.

    Input Parameters:

      -
    • set. Signal set to initialize. +
    • set. Signal set to initialize.

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) if the signal set cannot be initialized. +
    • 0 (OK), or -1 (ERROR) if the signal set cannot be initialized.

    @@ -3444,13 +3466,13 @@ by set such that all signals are included.

    Input Parameters:

      -
    • set. Signal set to initialize +
    • set. Signal set to initialize

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) if the signal set cannot be initialized. +
    • 0 (OK), or -1 (ERROR) if the signal set cannot be initialized.

    @@ -3474,14 +3496,14 @@ signo to the signal set specified by set.

    Input Parameters:

      -
    • set. Signal set to add signal to -
    • signo. Signal to add +
    • set. Signal set to add signal to +
    • signo. Signal to add

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) if the signal number is invalid. +
    • 0 (OK), or -1 (ERROR) if the signal number is invalid.

    @@ -3505,14 +3527,14 @@ by signo from the signal set specified by set.

    Input Parameters:

      -
    • set. Signal set to delete the signal from -
    • signo. Signal to delete +
    • set. Signal set to delete the signal from +
    • signo. Signal to delete

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) if the signal number is invalid. +
    • 0 (OK), or -1 (ERROR) if the signal number is invalid.

    @@ -3536,16 +3558,16 @@ by signo is a member of the set specified by set.

    Input Parameters:

      -
    • set. Signal set to test -
    • signo. Signal to test for +
    • set. Signal set to test +
    • signo. Signal to test for

    -Returned Values: +Returned Value:

    • 1 (TRUE), if the specified signal is a member of the set,
    • 0 (OK or FALSE), if it is not, or -
    • -1 (ERROR) if the signal number is invalid. +
    • -1 (ERROR) if the signal number is invalid.

    @@ -3560,8 +3582,8 @@ interface of the same name. Function Prototype:

         #include <signal.h>
    -    int sigaction( int signo, const struct sigaction *act,
    -                   struct sigaction *oact );
    +    int sigaction(int signo, const struct sigaction *act,
    +                  struct sigaction *oact);
     

    @@ -3572,12 +3594,12 @@ signal. The structure sigaction, used to describe an action to be taken, is defined to include the following members:

      -
    • sa_u.sa_handler. A pointer to a signal-catching function. -
    • sa_u.sa_sigaction. An alternative form for the signal catching +
    • sa_u.sa_handler. A pointer to a signal-catching function. +
    • sa_u.sa_sigaction. An alternative form for the signal catching function. -
    • sa_mask. Additional set of signals to be blocked during +
    • sa_mask. Additional set of signals to be blocked during execution of the signal-catching function. -
    • sa_flags: Special flags to affect behavior of a signal. +
    • sa_flags: Special flags to affect behavior of a signal.

    If the argument act is not NULL, it points to a structure specifying the @@ -3603,15 +3625,15 @@ sigaction().

    Input Parameters:

      -
    • sig. Signal of interest -
    • act. Location of new handler -
    • oact. Location to store old handler +
    • sig. Signal of interest +
    • act. Location of new handler +
    • oact. Location to store old handler

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) if the signal number is invalid. +
    • 0 (OK), or -1 (ERROR) if the signal number is invalid.

    @@ -3650,25 +3672,25 @@ If sigprocmask() fails, the signal mask of the task is not changed.

    Input Parameters:

      -
    • how. How the signal mast will be changed: +
    • how. How the signal mast will be changed:
        -
      • SIG_BLOCK. The resulting set is the union of the -current set and the signal set pointed to by the set input parameter. -
      • SIG_UNBLOCK. The resulting set is the intersection +
      • SIG_BLOCK. The resulting set is the union of the +current set and the signal set pointed to by the set input parameter. +
      • SIG_UNBLOCK. The resulting set is the intersection of the current set and the complement of the signal set pointed -to by the set input parameter. -
      • SIG_SETMASK. The resulting set is the signal set -pointed to by the set input parameter. +to by the set input parameter. +
      • SIG_SETMASK. The resulting set is the signal set +pointed to by the set input parameter.
      -
    • set. Location of the new signal mask -
    • oset. Location to store the old signal mask +
    • set. Location of the new signal mask +
    • oset. Location to store the old signal mask

    -Returned Values: +Returned Value:

      -
    • 0 (OK), or -1 (ERROR) if how is invalid. +
    • 0 (OK), or -1 (ERROR) if how is invalid.

    @@ -3683,7 +3705,7 @@ interface of the same name. Function Prototype:

         #include <signal.h>
    -    int sigpending( sigset_t *set );
    +    int sigpending(sigset_t *set);
     

    @@ -3700,13 +3722,13 @@ is delivered more than once."

    Input Parameters:

      -
    • set. The location to return the pending signal set. +
    • set. The location to return the pending signal set.

    -Returned Values: +Returned Value:

      -
    • 0 (OK) or -1 (ERROR) +
    • 0 (OK) or -1 (ERROR)

    @@ -3721,7 +3743,7 @@ interface of the same name. Function Prototype:

         #include <signal.h>
    -    int sigsuspend( const sigset_t *set );
    +    int sigsuspend(const sigset_t *set);
     

    @@ -3739,14 +3761,14 @@ resources (a very bad idea).

    Input Parameters:

      -
    • set. The value of the signal mask to use while +
    • set. The value of the signal mask to use while suspended.

    -Returned Values: +Returned Value:

      -
    • -1 (ERROR) always +
    • -1 (ERROR) always

    @@ -3778,15 +3800,15 @@ with a NULL timeout parameter. (see below).

    Input Parameters:

      -
    • set. The set of pending signals to wait for. -
    • info. The returned signal values +
    • set. The set of pending signals to wait for. +
    • info. The returned signal values

    -Returned Values: +Returned Value:

    • Signal number that cause the wait to be terminated, otherwise --1 (ERROR) is returned. +-1 (ERROR) is returned.

    @@ -3801,8 +3823,8 @@ interface of the same name. Function Prototype:

         #include <signal.h>
    -    int sigtimedwait( const sigset_t *set, struct siginfo *info,
    -                      const struct timespec *timeout );
    +    int sigtimedwait(const sigset_t *set, struct siginfo *info,
    +                     const struct timespec *timeout);
     

    @@ -3821,26 +3843,26 @@ in the si_code member. The content of si_value is only meaningful if the signal was generated by sigqueue(). The following values for si_code are defined in signal.h:

      -
    • SI_USER. Signal sent from kill, raise, or abort -
    • SI_QUEUE. Signal sent from sigqueue -
    • SI_TIMER. Signal is result of timer expiration -
    • SI_ASYNCIO. Signal is the result of asynchronous IO completion -
    • SI_MESGQ. Signal generated by arrival of a message on an empty message queue. +
    • SI_USER. Signal sent from kill, raise, or abort +
    • SI_QUEUE. Signal sent from sigqueue +
    • SI_TIMER. Signal is result of timer expiration +
    • SI_ASYNCIO. Signal is the result of asynchronous IO completion +
    • SI_MESGQ. Signal generated by arrival of a message on an empty message queue.

    Input Parameters:

      -
    • set. The set of pending signals to wait for. -
    • info. The returned signal values -
    • timeout. The amount of time to wait +
    • set. The set of pending signals to wait for. +
    • info. The returned signal values +
    • timeout. The amount of time to wait

    -Returned Values: +Returned Value:

    • Signal number that cause the wait to be terminated, otherwise --1 (ERROR) is returned. +-1 (ERROR) is returned.

    @@ -3854,7 +3876,7 @@ Differences from the POSIX interface include:

  • No mechanism to return cause of ERROR. (It can be inferred from si_code in a non-standard way).
  • POSIX states that "If no signal is pending at the time of the -call, the calling task shall be suspended until one or more signals +call, the calling task will be suspended until one or more signals in set become pending or until it is interrupted by an unblocked, caught signal." The present implementation does not require that the unblocked signal be caught; the task will be resumed even if @@ -3884,17 +3906,17 @@ is delivered more than once."

    Input Parameters:

      -
    • tid. ID of the task to receive signal -
    • signo. Signal number -
    • value. Value to pass to task with signal +
    • tid. ID of the task to receive signal +
    • signo. Signal number +
    • value. Value to pass to task with signal

    -Returned Values: +Returned Value:

    • - On success (at least one signal was sent), zero (OK) is returned. - On error, -1 (ERROR) is returned, and errno is set appropriately. + On success (at least one signal was sent), zero (OK) is returned. + On error, -1 (ERROR) is returned, and errno is set appropriately.
      • EGAIN. The limit of signals which may be queued has been reached.
      • EINVAL. signo was invalid.
      • @@ -3944,17 +3966,17 @@ be sent.

        Input Parameters:

          -
        • pid. The id of the task to receive the signal. +
        • pid. The id of the task to receive the signal. The POSIX kill() specification encodes process group information as zero and negative pid values. Only positive, non-zero values of pid are supported by this implementation. ID of the task to receive signal -
        • signo. The signal number to send. +
        • signo. The signal number to send. If signo is zero, no signal is sent, but all error checking is performed.

        - Returned Values: + Returned Value:

        • OK or ERROR
        @@ -4064,9 +4086,6 @@ be sent.
      • pthread_attr_setscope. get and set the contentionscope attribute.
      • pthread_attr_setstack. get and set stack attributes.
      • pthread_attr_setstackaddr. get and set the stackaddr attribute.
      • -
      • pthread_barrier_destroy. destroy and initialize a barrier object.
      • -
      • pthread_barrier_init. destroy and initialize a barrier object.
      • -
      • pthread_barrier_wait. synchronize at a barrier.
      • pthread_cleanup_pop. establish cancellation handlers.
      • pthread_cleanup_push. establish cancellation handlers.
      • pthread_condattr_getclock. set the clock selection condition variable attribute.
      • @@ -4124,10 +4143,10 @@ for all of the individual attributes used by the implementation.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_attr_init() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_attr_init() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4156,10 +4175,10 @@ An attributes object can be deleted when it is no longer needed.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_attr_destroy() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_attr_destroy() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4187,10 +4206,10 @@ interface of the same name.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_attr_setschedpolicy() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_attr_setschedpolicy() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4218,10 +4237,10 @@ interface of the same name.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_attr_getschedpolicy() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_attr_getschedpolicy() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4237,9 +4256,9 @@ interface of the same name. Function Prototype:

        -   #include <pthread.h>
        +    #include <pthread.h>
             int pthread_attr_setschedparam(pthread_attr_t *attr,
        -				      const struct sched_param *param);
        +                                   const struct sched_param *param);
         

        Description: @@ -4250,10 +4269,10 @@ interface of the same name.

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_attr_getschedpolicy() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_attr_getschedpolicy() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4269,9 +4288,9 @@ interface of the same name. Function Prototype:

        -   #include <pthread.h>
        -     int pthread_attr_getschedparam(pthread_attr_t *attr,
        -				      struct sched_param *param);
        +    #include <pthread.h>
        +    int pthread_attr_getschedparam(pthread_attr_t *attr,
        +                                   struct sched_param *param);
         

        Description: @@ -4282,10 +4301,10 @@ interface of the same name.

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_attr_getschedparam() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_attr_getschedparam() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4303,7 +4322,7 @@ interface of the same name.
            #include <pthread.h>
             int pthread_attr_setinheritsched(pthread_attr_t *attr,
        -					int inheritsched);
        +                                     int inheritsched);
         

        Description: @@ -4314,10 +4333,10 @@ interface of the same name.

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_attr_setinheritsched() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_attr_setinheritsched() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4335,7 +4354,7 @@ interface of the same name.
            #include <pthread.h>
              int pthread_attr_getinheritsched(const pthread_attr_t *attr,
        -					int *inheritsched);
        +                                      int *inheritsched);
         

        Description: @@ -4346,10 +4365,10 @@ interface of the same name.

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_attr_getinheritsched() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_attr_getinheritsched() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4365,7 +4384,7 @@ interface of the same name. Function Prototype:

        -   #include <pthread.h>
        +    #include <pthread.h>
             int pthread_attr_setstacksize(pthread_attr_t *attr, long stacksize);
         

        @@ -4377,10 +4396,10 @@ interface of the same name.

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_attr_setstacksize() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_attr_setstacksize() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4397,7 +4416,7 @@ interface of the same name.

             #include <pthread.h>
        -   int pthread_attr_getstacksize(pthread_attr_t *attr, long *stackaddr);
        +    int pthread_attr_getstacksize(pthread_attr_t *attr, long *stackaddr);
         

        Description: @@ -4408,10 +4427,10 @@ interface of the same name.

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_attr_getstacksize() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_attr_getstacksize() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4429,8 +4448,8 @@ interface of the same name.
             #include <pthread.h>
             int pthread_create(pthread_t *thread, pthread_attr_t *attr,
        -			  pthread_startroutine_t startRoutine,
        -			  pthread_addr_t arg);
        +                       pthread_startroutine_t startRoutine,
        +                       pthread_addr_t arg);
         

        Description: @@ -4447,10 +4466,10 @@ specify details about the kind of thread being created.

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_create() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_create() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4480,10 +4499,10 @@ return value and completion status will not be requested.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_detach() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_detach() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4512,10 +4531,10 @@ A thread may terminate it's own execution.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_exit() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_exit() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4537,10 +4556,10 @@ interface of the same name.

        Description: -

        The pthread_cancel() function shall request that thread +

        The pthread_cancel() function will request that thread be canceled. The target thread's cancelability state determines when the cancellation takes effect. When the -cancellation is acted on, thread shall be terminated.

        +cancellation is acted on, thread will be terminated.

        When cancelability is disabled, all cancels are held pending in the target thread until the thread changes the cancelability. @@ -4555,17 +4574,17 @@ immediately (when enable), interrupting the thread with its processing.

        Input Parameters:

          -
        • thread. +
        • thread. Identifies the thread to be canceled.

        -Returned Values: +Returned Value:

        -If successful, the pthread_cancel() function will return zero (OK). +If successful, the pthread_cancel() function will return zero (OK). Otherwise, an error number will be returned to indicate the error:

          -
        • ESRCH. +
        • ESRCH. No thread could be found corresponding to that specified by the given thread ID.
        Assumptions/Limitations: @@ -4573,7 +4592,7 @@ No thread could be found corresponding to that specified by the given thread ID. POSIX Compatibility: Comparable to the POSIX interface of the same name. Except:

          -
        • The thread-specific data destructor functions shall be called for thread. +
        • The thread-specific data destructor functions will be called for thread. However, these destructors are not currently supported.
        • Cancellation types are not supported. The thread will be canceled at the time that pthread_cancel() is called or, if cancellation is disabled, at @@ -4592,7 +4611,7 @@ the time when cancellation is re-enabled.
        • Description: -

          The pthread_setcancelstate() function atomically +

          The pthread_setcancelstate() function atomically sets both the calling thread's cancelability state to the indicated state and returns the previous cancelability state at the location referenced by oldstate. @@ -4604,19 +4623,19 @@ cancellation state is set to PTHREAD_CANCEL_ENABLE.

          Input Parameters:

            -
          • state +
          • state New cancellation state. One of PTHREAD_CANCEL_ENABLE or PTHREAD_CANCEL_DISABLE.<.li> -
          • oldstate. +
          • oldstate. Location to return the previous cancellation state.

          -Returned Values: +Returned Value:

          -If successful, the pthread_setcancelstate() function will return -zero (OK). Otherwise, an error number will be returned to indicate the error: +If successful, the pthread_setcancelstate() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

            -
          • ESRCH. +
          • ESRCH. No thread could be found corresponding to that specified by the given thread ID.
          Assumptions/Limitations: @@ -4641,10 +4660,10 @@ interface of the same name.
        • To be provided.

        -Returned Values: +Returned Value:

        -If successful, the pthread_setcancelstate() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_setcancelstate() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

          @@ -4674,10 +4693,10 @@ the return value of the thread.
        • To be provided.

        -Returned Values: +Returned Value:

        -If successful, the pthread_join() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_join() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

          @@ -4707,10 +4726,10 @@ made available.
        • To be provided.

        -Returned Values: +Returned Value:

        -If successful, the pthread_yield() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_yield() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

          @@ -4739,10 +4758,10 @@ A thread may obtain a copy of its own thread handle.
        • To be provided.

        -Returned Values: +Returned Value:

        -If successful, the pthread_self() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_self() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

          @@ -4806,7 +4825,7 @@ interface of the same name.

        - Returned Values: + Returned Value: 0 (OK) if successful. Otherwise, the error code ESRCH if the value specified by thread does not refer to an existing thread. @@ -4871,11 +4890,11 @@ interface of the same name.

      - Returned Values: + Returned Value:

      - If successful, the pthread_setschedparam() function will return - zero (OK). Otherwise, an error number will be + If successful, the pthread_setschedparam() function will return + zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -4917,7 +4936,7 @@ interface of the same name.

             #include <pthread.h>
        -    int pthread_key_create( pthread_key_t *key, void (*destructor)(void*) )
        +    int pthread_key_create(pthread_key_t *key, void (*destructor)(void*))
         

        Description: @@ -4925,38 +4944,38 @@ interface of the same name. This function creates a thread-specific data key visible to all threads in the system. Although the same key value may be used by different threads, the values bound to -the key by pthread_setspecific() are maintained on a +the key by pthread_setspecific() are maintained on a per-thread basis and persist for the life of the calling thread.

        -Upon key creation, the value NULL will be associated with +Upon key creation, the value NULL will be associated with the new key in all active threads. Upon thread -creation, the value NULL will be associated with all +creation, the value NULL will be associated with all defined keys in the new thread.

        Input Parameters:

          -
        • key is a pointer to the key to create. -
        • destructor is an optional destructor() function that may +
        • key is a pointer to the key to create. +
        • destructor is an optional destructor() function that may be associated with each key that is invoked when a thread exits. However, this argument is ignored in the current implementation.

        -Returned Values: +Returned Value:

        -If successful, the pthread_key_create() function will -store the newly created key value at *key and return -zero (OK). Otherwise, an error number will be +If successful, the pthread_key_create() function will +store the newly created key value at *key and return +zero (OK). Otherwise, an error number will be returned to indicate the error:

          -
        • EAGAIN. The system lacked sufficient resources +
        • EAGAIN. The system lacked sufficient resources to create another thread-specific data key, or the system-imposed limit on the total number of keys -per task {PTHREAD_KEYS_MAX} has been exceeded -
        • ENONMEM Insufficient memory exists to create the key. +per task {PTHREAD_KEYS_MAX} has been exceeded +
        • ENONMEM Insufficient memory exists to create the key.
        Assumptions/Limitations:

        @@ -4972,39 +4991,39 @@ interface of the same name.

             #include <pthread.h>
        -    int pthread_setspecific( pthread_key_t key, void *value )
        +    int pthread_setspecific(pthread_key_t key, void *value)
         

        Description:

        -The pthread_setspecific() function associates a thread- +The pthread_setspecific() function associates a thread- specific value with a key obtained via a previous call -to pthread_key_create(). Different threads may bind +to pthread_key_create(). Different threads may bind different values to the same key. These values are typically pointers to blocks of dynamically allocated memory that have been reserved for use by the calling thread.

        -The effect of calling pthread_setspecific() with a key value -not obtained from pthread_key_create() or after a key has been -deleted with pthread_key_delete() is undefined. +The effect of calling pthread_setspecific() with a key value +not obtained from pthread_key_create() or after a key has been +deleted with pthread_key_delete() is undefined.

        Input Parameters:

          -
        • key. The data key to set the binding for. -
        • value. The value to bind to the key. +
        • key. The data key to set the binding for. +
        • value. The value to bind to the key.

        -Returned Values: +Returned Value:

        -If successful, pthread_setspecific() will return zero (OK). +If successful, pthread_setspecific() will return zero (OK). Otherwise, an error number will be returned:

          -
        • ENOMEM. Insufficient memory exists to associate the value +
        • ENOMEM. Insufficient memory exists to associate the value with the key. -
        • EINVAL. The key value is invalid. +
        • EINVAL. The key value is invalid.

        Assumptions/Limitations: @@ -5022,31 +5041,31 @@ destructor function.

             #include <pthread.h>
        -    void *pthread_getspecific( pthread_key_t key )
        +    void *pthread_getspecific(pthread_key_t key)
         

        Description:

        -The pthread_getspecific() function returns the value +The pthread_getspecific() function returns the value currently bound to the specified key on behalf of the calling thread.

        -The effect of calling pthread_getspecific() with a key value -not obtained from pthread_key_create() or after a key has been -deleted with pthread_key_delete() is undefined. +The effect of calling pthread_getspecific() with a key value +not obtained from pthread_key_create() or after a key has been +deleted with pthread_key_delete() is undefined.

        Input Parameters:

          -
        • key. The data key to get the binding for. +
        • key. The data key to get the binding for.

        -Returned Values: +Returned Value:

        -The function pthread_getspecific() returns the thread- +The function pthread_getspecific() returns the thread- specific data associated with the given key. If no thread specific data is associated with the key, then -the value NULL is returned. +the value NULL is returned.

        Assumptions/Limitations:

        @@ -5063,25 +5082,25 @@ destructor function.

             #include <pthread.h>
        -    int pthread_key_delete( pthread_key_t key )
        +    int pthread_key_delete(pthread_key_t key)
         

        Description:

        This POSIX function should delete a thread-specific data -key previously returned by pthread_key_create(). However, +key previously returned by pthread_key_create(). However, this function does nothing in the present implementation.

        Input Parameters:

          -
        • key. The key to delete +
        • key. The key to delete

        -Returned Values: +Returned Value:

          -
        • Always returns EINVAL. +
        • Always returns EINVAL.

        Assumptions/Limitations: @@ -5106,10 +5125,10 @@ interface of the same name.

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutexattr_init() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_mutexattr_init() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5137,10 +5156,10 @@ interface of the same name.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutexattr_destroy() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_mutexattr_destroy() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5158,7 +5177,7 @@ interface of the same name.
             #include <pthread.h>
             int pthread_mutexattr_getpshared(pthread_mutexattr_t *attr,
        -					int *pshared);
        +                                     int *pshared);
         

        Description: @@ -5169,10 +5188,10 @@ interface of the same name.

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutexattr_getpshared() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_mutexattr_getpshared() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5190,7 +5209,7 @@ interface of the same name.
             #include <pthread.h>
            int pthread_mutexattr_setpshared(pthread_mutexattr_t *attr,
        -					int pshared);
        +                                    int pshared);
         

        Description: @@ -5201,10 +5220,10 @@ interface of the same name.

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutexattr_setpshared() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_mutexattr_setpshared() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5237,10 +5256,10 @@ interface of the same name. for a description of possible mutex types that may be returned.

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutexattr_settype() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_mutexattr_settype() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5291,10 +5310,10 @@ returned to indicate the error:

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutexattr_settype() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_mutexattr_settype() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5311,7 +5330,7 @@ returned to indicate the error:
             #include <pthread.h>
             int pthread_mutex_init(pthread_mutex_t *mutex,
        -			      pthread_mutexattr_t *attr);
        +                           pthread_mutexattr_t *attr);
         

        Description: @@ -5322,10 +5341,10 @@ returned to indicate the error:

      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutex_init() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_mutex_init() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5353,10 +5372,10 @@ interface of the same name.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutex_destroy() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_mutex_destroy() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5419,9 +5438,9 @@ interface of the same name.
      • mutex. A reference to the mutex to be locked.

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutex_lock() function will return zero (OK). +If successful, the pthread_mutex_lock() function will return zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5446,7 +5465,7 @@ interface of the same name. The function pthread_mutex_trylock() is identical to pthread_mutex_lock() except that if the mutex object referenced by mutex is currently locked (by any thread, including the current thread), the call returns immediately - with the errno EBUSY. + with the errno EBUSY.

        If a signal is delivered to a thread waiting for a mutex, upon return from the signal handler the thread resumes waiting for the mutex as if it was @@ -5459,9 +5478,9 @@ interface of the same name.

      • mutex. A reference to the mutex to be locked.

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutex_trylock() function will return zero (OK). +If successful, the pthread_mutex_trylock() function will return zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5489,7 +5508,7 @@ interface of the same name. mutex's type attribute. If there are threads blocked on the mutex object referenced by mutex when pthread_mutex_unlock() is called, resulting in the mutex becoming available, the scheduling policy is used to determine - which thread shall acquire the mutex. (In the case of PTHREAD_MUTEX_RECURSIVE + which thread will acquire the mutex. (In the case of PTHREAD_MUTEX_RECURSIVE mutexes, the mutex becomes available when the count reaches zero and the calling thread no longer has any locks on this mutex).

        @@ -5504,10 +5523,10 @@ interface of the same name.
      • mutex.

      -Returned Values: +Returned Value:

      -If successful, the pthread_mutex_unlock() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_mutex_unlock() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5536,10 +5555,10 @@ interface of the same name.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_condattr_init() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_condattr_init() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5567,10 +5586,10 @@ interface of the same name.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_condattr_destroy() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_condattr_destroy() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5598,10 +5617,10 @@ interface of the same name.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_cond_init() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_cond_init() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5629,10 +5648,10 @@ interface of the same name.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_cond_destroy() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_cond_destroy() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5660,10 +5679,10 @@ interface of the same name.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_cond_broadcast() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_cond_broadcast() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5691,10 +5710,10 @@ interface of the same name.
      • To be provided.

      -Returned Values: +Returned Value:

      -If successful, the pthread_cond_signal() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_cond_signal() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5722,10 +5741,10 @@ interface of the same name.
      • To be provided.

      - Returned Values: + Returned Value:

      -If successful, the pthread_cond_wait() function will return -zero (OK). Otherwise, an error number will be +If successful, the pthread_cond_wait() function will return +zero (OK). Otherwise, an error number will be returned to indicate the error:

        @@ -5743,7 +5762,7 @@ interface of the same name.
             #include <pthread.h>
             int pthread_cond_timedwait(pthread_cond_t *cond, pthread_mutex_t *mutex,
        -				  const struct timespec *abstime);
        +                               const struct timespec *abstime);
         

        Description: @@ -5756,7 +5775,7 @@ interface of the same name.

      • To be provided.

      - Returned Values: + Returned Value:

      If successful, the pthread_cond_timedwait() function will return @@ -5796,7 +5815,7 @@ interface of the same name.

    - Returned Values: + Returned Value: 0 (OK) on success or EINVAL if attr is invalid.

    @@ -5829,7 +5848,7 @@ interface of the same name.

  • - Returned Values: 0 (OK) on success or EINVAL if attr is invalid. + Returned Value: 0 (OK) on success or EINVAL if attr is invalid.

    Assumptions/Limitations: @@ -5865,7 +5884,7 @@ interface of the same name.

  • pshared. The new value of the pshared attribute.
  • - Returned Values: 0 (OK) on success or EINVAL if either + Returned Value: 0 (OK) on success or EINVAL if either attr is invalid or pshared is not one of PTHREAD_PROCESS_SHARED or PTHREAD_PROCESS_PRIVATE.

    @@ -5898,7 +5917,7 @@ interface of the same name.
  • pshared. The location to stored the current value of the pshared attribute.
  • - Returned Values: 0 (OK) on success or EINVAL if + Returned Value: 0 (OK) on success or EINVAL if either attr or pshared is invalid.

    @@ -5950,7 +5969,7 @@ interface of the same name.

    - Returned Values:0 (OK) on success or on of the following error numbers: + Returned Value:0 (OK) on success or on of the following error numbers:

    • @@ -6003,7 +6022,7 @@ interface of the same name.
    • barrier. The barrier to be destroyed.

    - Returned Values: 0 (OK) on success or on of the following error numbers: + Returned Value: 0 (OK) on success or on of the following error numbers:

    • @@ -6072,7 +6091,7 @@ interface of the same name.
    • barrier. The barrier on which to wait.

    - Returned Values: 0 (OK) on success or EINVAL if the barrier is not valid. + Returned Value: 0 (OK) on success or EINVAL if the barrier is not valid.

    Assumptions/Limitations: @@ -6116,8 +6135,8 @@ interface of the same name.

    - Returned Values: - 0 (OK) on success or EINVAL if either once_control or init_routine are invalid. + Returned Value: + 0 (OK) on success or EINVAL if either once_control or init_routine are invalid.

    Assumptions/Limitations: @@ -6157,7 +6176,7 @@ interface of the same name.

    - Returned Values: + Returned Value:

    On success, the signal was sent and zero is returned. @@ -6232,11 +6251,11 @@ interface of the same name.

    - Returned Values: -

    -

    - 0 (OK) on success or EINVAL if how is invalid. + Returned Value:

    +
      + 0 (OK) on success or EINVAL if how is invalid. +

    Assumptions/Limitations:

    @@ -6314,7 +6333,7 @@ interface of the same name.

    - Returned Values: + Returned Value: The value of the variable (read-only) or NULL on failure.

    @@ -6341,11 +6360,11 @@ interface of the same name.
    • string - name=value string describing the environment setting to add/modify. + name=value string describing the environment setting to add/modify.

    - Returned Values: + Returned Value: Zero on success.

    @@ -6367,7 +6386,7 @@ interface of the same name. None

    - Returned Values: + Returned Value: Zero on success.

    @@ -6405,7 +6424,7 @@ interface of the same name.

    - Returned Values: + Returned Value: Zero on success.

    @@ -6432,7 +6451,7 @@ interface of the same name.

    - Returned Values: + Returned Value: Zero on success.

    @@ -6560,7 +6579,7 @@ interface of the same name.

       #include <poll.h>
    -  int     poll(struct pollfd *fds, nfds_t nfds, int timeout);
    +  int poll(struct pollfd *fds, nfds_t nfds, int timeout);
     

    Description: @@ -6607,7 +6626,7 @@ interface of the same name. timeout.

    - Returned Values: + Returned Value:

    On success, the number of structures that have nonzero revents fields. @@ -6629,11 +6648,11 @@ interface of the same name.

    Function Prototype:

    -
    -  #include <sys/select.h>
    -  int     select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
    -                 FAR fd_set *exceptfds, FAR struct timeval *timeout);
    -
    +
      +#include <sys/select.h>
      +int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
      +           FAR fd_set *exceptfds, FAR struct timeval *timeout);
      +

    Description: select() allows a program to monitor multiple file descriptors, waiting @@ -6660,7 +6679,7 @@ interface of the same name.

  • timeout. Return at this time if none of these events of interest occur.
  • - Returned Values: + Returned Value:

    • 0: Timer expired
    • @@ -6802,10 +6821,10 @@ void *memmove(void *dest, const void *src, size_t count);

      Function Prototype:

      -
      -  #include <unistd.h>
      -  int pipe(int filedes[2]);
      -
      +
        +#include <unistd.h>
        +int pipe(int filedes[2]);
        +

      Description:

        @@ -6824,7 +6843,7 @@ void *memmove(void *dest, const void *src, size_t count);

        - Returned Values: + Returned Value:

          0 is returned on success; otherwise, -1 is returned with errno set appropriately. @@ -6836,10 +6855,10 @@ void *memmove(void *dest, const void *src, size_t count);

          Function Prototype:

          -
          -  #include <sys/stat.h>
          -  int mkfifo(FAR const char *pathname, mode_t mode);
          -
          +
            +#include <sys/stat.h>
            +int mkfifo(FAR const char *pathname, mode_t mode);
            +

          Description:

            @@ -6871,7 +6890,7 @@ void *memmove(void *dest, const void *src, size_t count);

          - Returned Values: + Returned Value:

            0 is returned on success; otherwise, -1 is returned with errno set appropriately. @@ -6933,7 +6952,7 @@ struct fat_format_s

          - Returned Values: + Returned Value:

            Zero (OK) on success; @@ -7189,7 +7208,7 @@ FAR void *mmap(FAR void *start, size_t length, int prot, int flags, int fd, off_

          - Returned Values: + Returned Value:

            On success, mmap() returns a pointer to the mapped area. @@ -7246,10 +7265,10 @@ Those socket APIs are discussed in the following paragraphs.

            Function Prototype:

            -
            -  #include <sys/socket.h>
            -  int socket(int domain, int type, int protocol);
            -
            +
              +#include <sys/socket.h>
              +int socket(int domain, int type, int protocol);
              +

            Description: socket() creates an endpoint for communication and returns a descriptor. @@ -7264,7 +7283,7 @@ Those socket APIs are discussed in the following paragraphs.

          • protocol: (see sys/socket.h)

          - Returned Values: + Returned Value: 0 on success; -1 on error with errno set appropriately:

            @@ -7288,10 +7307,10 @@ Those socket APIs are discussed in the following paragraphs.

            Function Prototype:

            -
            -  #include <sys/socket.h>
            -  int bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen);
            -
            +
              +#include <sys/socket.h>
              +int bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen);
              +

            Description: bind() gives the socket sockfd the local address addr. @@ -7310,7 +7329,7 @@ Those socket APIs are discussed in the following paragraphs.

          • addrlen: Length of addr.

          - Returned Values: + Returned Value: 0 on success; -1 on error with errno set appropriately:

            @@ -7330,10 +7349,10 @@ Those socket APIs are discussed in the following paragraphs.

            Function Prototype:

            -
            -  #include <sys/socket.h>
            -  int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen);
            -
            +
              +#include <sys/socket.h>
              +int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen);
              +

            Description: connect() connects the socket referred to by the file descriptor @@ -7365,7 +7384,7 @@ Those socket APIs are discussed in the following paragraphs.

          • addrlen: Length of actual addr

          - Returned Values: + Returned Value: 0 on success; -1 on error with errno set appropriately:

        • EACCES or EPERM: @@ -7409,10 +7428,10 @@ Those socket APIs are discussed in the following paragraphs.

          Function Prototype:

          -
          -  #include <sys/socket.h>
          -  int listen(int sockfd, int backlog);
          -
          +
            +#include <sys/socket.h>
            +int listen(int sockfd, int backlog);
            +

          Description: To accept connections, a socket is first created with socket(), a @@ -7432,7 +7451,7 @@ Those socket APIs are discussed in the following paragraphs.

          the request may be ignored so that retries succeed.

        - Returned Values: + Returned Value: On success, zero is returned. On error, -1 is returned, and errno is set appropriately.

        @@ -7447,10 +7466,10 @@ Those socket APIs are discussed in the following paragraphs.

        Function Prototype:

        -
        -  #include <sys/socket.h>
        -  int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen);
        -
        +
          +#include <sys/socket.h>
          +int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen);
          +

        Description: The accept() function is used with connection-based socket types @@ -7488,7 +7507,7 @@ Those socket APIs are discussed in the following paragraphs.

      • addrlen: Input: allocated size of addr, Return: returned size of addr.

      - Returned Values: + Returned Value: Returns -1 on error. If it succeeds, it returns a non-negative integer that is a descriptor for the accepted socket.

      @@ -7525,10 +7544,10 @@ Those socket APIs are discussed in the following paragraphs.

      Function Prototype:

      -
      -  #include <sys/socket.h>
      -  ssize_t send(int sockfd, const void *buf, size_t len, int flags);
      -
      +
        +#include <sys/socket.h>
        +ssize_t send(int sockfd, const void *buf, size_t len, int flags);
        +

      Description: The send() call may be used only when the socket is in a connected state @@ -7549,7 +7568,7 @@ Those socket APIs are discussed in the following paragraphs.

    • flags: Send flags

    - Returned Values: + Returned Value: See sendto().

    @@ -7557,11 +7576,11 @@ Those socket APIs are discussed in the following paragraphs.

    Function Prototype:

    -
    -  #include <sys/socket.h>
    -  ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
    -                 const struct sockaddr *to, socklen_t tolen);
    -
    +
      +#include <sys/socket.h>
      + ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
      +               const struct sockaddr *to, socklen_t tolen);
      +

    Description: If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET) @@ -7582,7 +7601,7 @@ Those socket APIs are discussed in the following paragraphs.

  • tolen: The length of the address structure

    - Returned Values: + Returned Value: On success, returns the number of characters sent. On error, -1 is returned, and errno is set appropriately:

    @@ -7630,10 +7649,10 @@ Those socket APIs are discussed in the following paragraphs.

    Function Prototype:

    -
    -  #include <sys/socket.h>
    -  ssize_t recv(int sockfd, void *buf, size_t len, int flags);
    -
    +
      +#include <sys/socket.h>
      +ssize_t recv(int sockfd, void *buf, size_t len, int flags);
      +

    Description: The recv() call is identical to @@ -7652,7 +7671,7 @@ Those socket APIs are discussed in the following paragraphs.

  • flags: Receive flags
  • - Returned Values: + Returned Value: See recvfrom().

    @@ -7660,11 +7679,11 @@ Those socket APIs are discussed in the following paragraphs.

    Function Prototype:

    -
    -  #include <sys/socket.h>
    -  ssize_t recvfrom(int sockfd, void *buf, size_t len, int flags,
    -                   struct sockaddr *from, socklen_t *fromlen);
    -
    +
      +#include <sys/socket.h>
      +ssize_t recvfrom(int sockfd, void *buf, size_t len, int flags,
      +                 struct sockaddr *from, socklen_t *fromlen);
      +

    Description: recvfrom() receives messages from a socket, and may be used to receive @@ -7688,7 +7707,7 @@ Those socket APIs are discussed in the following paragraphs.

  • fromlen: The length of the address structure.
  • - Returned Values: + Returned Value: On success, returns the number of characters sent. If no data is available to be received and the peer has performed an orderly shutdown, recv() will return 0. Othwerwise, on errors, -1 is returned, and errno is set appropriately: @@ -7723,11 +7742,11 @@ Those socket APIs are discussed in the following paragraphs.

    Function Prototype:

    -
    -  #include <sys/socket.h>
    -  int setsockopt(int sockfd, int level, int option,
    -                 const void *value, socklen_t value_len);
    -
    +
      +#include <sys/socket.h>
      +int setsockopt(int sockfd, int level, int option,
      +               const void *value, socklen_t value_len);
      +

    Description: setsockopt() sets the option specified by the option argument, @@ -7753,7 +7772,7 @@ Those socket APIs are discussed in the following paragraphs.

  • value_len: The length of the argument value
  • - Returned Values: + Returned Value: On success, returns the number of characters sent. On error, -1 is returned, and errno is set appropriately:

    @@ -7783,11 +7802,11 @@ Those socket APIs are discussed in the following paragraphs.

    Function Prototype:

    -
    -  #include <sys/socket.h>
    -  int getsockopt(int sockfd, int level, int option,
    -                 void *value, socklen_t *value_len);
    -
    +
      +#include <sys/socket.h>
      +int getsockopt(int sockfd, int level, int option,
      +               void *value, socklen_t *value_len);
      +

    Description: getsockopt() retrieve those value for the option specified by the @@ -7816,7 +7835,7 @@ Those socket APIs are discussed in the following paragraphs.

  • value_len: The length of the argument value

    - Returned Values: + Returned Value: On success, returns the number of characters sent. On error, -1 is returned, and errno is set appropriately:

    @@ -7904,9 +7923,11 @@ OS resources. These hidden structures include:

    Function Prototype:

    -

        #include <errno.h>
    -    #define errno *get_errno_ptr()
    -    int *get_errno_ptr( void )
    +
      +#include <errno.h>
      +#define errno *get_errno_ptr()
      +int *get_errno_ptr(void);
      +

    Description: get_errno_ptr() returns a pointer to the thread-specific errno value. diff --git a/nuttx/sched/sched_getscheduler.c b/nuttx/sched/sched_getscheduler.c index 5771e86ff4..0d996ca271 100644 --- a/nuttx/sched/sched_getscheduler.c +++ b/nuttx/sched/sched_getscheduler.c @@ -129,3 +129,4 @@ int sched_getscheduler(pid_t pid) return SCHED_FIFO; } } + From 26cbab4570e466f88221e3f459aa3273386cd9ea Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 31 Oct 2012 14:36:00 +0000 Subject: [PATCH 049/206] Add apps/netutils/codecs and associated NSH commands from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5280 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 4 + apps/include/netutils/base64.h | 85 +++++ apps/include/netutils/md5.h | 104 ++++++ apps/include/netutils/urldecode.h | 74 ++++ apps/netutils/Kconfig | 1 + apps/netutils/Make.defs | 4 + apps/netutils/Makefile | 2 +- apps/netutils/codecs/Kconfig | 59 ++++ apps/netutils/codecs/Makefile | 91 +++++ apps/netutils/codecs/base64.c | 359 ++++++++++++++++++++ apps/netutils/codecs/md5.c | 402 ++++++++++++++++++++++ apps/netutils/codecs/urldecode.c | 429 ++++++++++++++++++++++++ apps/nshlib/Kconfig | 68 ++++ apps/nshlib/Makefile | 44 +-- apps/nshlib/README.txt | 42 ++- apps/nshlib/nsh.h | 24 ++ apps/nshlib/nsh_codeccmd.c | 538 ++++++++++++++++++++++++++++++ apps/nshlib/nsh_parse.c | 25 ++ 18 files changed, 2320 insertions(+), 35 deletions(-) create mode 100644 apps/include/netutils/base64.h create mode 100644 apps/include/netutils/md5.h create mode 100644 apps/include/netutils/urldecode.h create mode 100644 apps/netutils/codecs/Kconfig create mode 100644 apps/netutils/codecs/Makefile create mode 100644 apps/netutils/codecs/base64.c create mode 100644 apps/netutils/codecs/md5.c create mode 100644 apps/netutils/codecs/urldecode.c create mode 100644 apps/nshlib/nsh_codeccmd.c diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 5020eb1c7c..4d147d91d9 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -390,3 +390,7 @@ * apps/nshlib/nsh_netinit.c: Fix static IP DNS problem (Darcy Gong) * apps/netutils/resolv/resolv.c: DNS fixes from Darcy Gong. * COPYING: Licensing information added. + * apps/netutils/codec and include/netutils/urldecode.h, base64.h, and md5.h: + A port of the BASE46, MD5 and URL CODEC library from Darcy Gong. + * nslib/nsh_codeccmd.c: NSH commands to use the CODEC library. + Contributed by Darcy Gong. diff --git a/apps/include/netutils/base64.h b/apps/include/netutils/base64.h new file mode 100644 index 0000000000..e361a3a22d --- /dev/null +++ b/apps/include/netutils/base64.h @@ -0,0 +1,85 @@ +/**************************************************************************** + * apps/include/netutils/base64.h + * + * This file is part of the NuttX RTOS: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Darcy Gong + * + * Reference: + * + * Base64 encoding/decoding (RFC1341) + * Copyright (c) 2005, Jouni Malinen + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + * + * Alternatively, this software may be distributed under the terms of BSD + * license. + * + * See README and COPYING for more details. + * + * And is re-released under the NuttX modified BSD license: + * + * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 __APPS_INCLUDE_NETUTILS_BASE64_H +#define __APPS_INCLUDE_NETUTILS_BASE64_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef __cplusplus +extern "C" +{ +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef CONFIG_CODECS_BASE64 +unsigned char *base64_encode(const unsigned char *src, size_t len, + unsigned char *dst, size_t *out_len); +unsigned char *base64_decode(const unsigned char *src, size_t len, + unsigned char *dst, size_t *out_len); +unsigned char *base64w_encode(const unsigned char *src, size_t len, + unsigned char *dst, size_t *out_len); +unsigned char *base64w_decode(const unsigned char *src, size_t len, + unsigned char *dst, size_t *out_len); +#endif /* CONFIG_CODECS_BASE64 */ + +#ifdef __cplusplus +} +#endif + +#endif /* __APPS_INCLUDE_NETUTILS_BASE64_H */ diff --git a/apps/include/netutils/md5.h b/apps/include/netutils/md5.h new file mode 100644 index 0000000000..b982a0b366 --- /dev/null +++ b/apps/include/netutils/md5.h @@ -0,0 +1,104 @@ +/**************************************************************************** + * apps/include/netutils/md5.h + * + * This file is part of the NuttX RTOS: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Darcy Gong + * + * Reference: + * + * This code implements the MD5 message-digest algorithm. + * The algorithm is due to Ron Rivest. This code was + * written by Colin Plumb in 1993, no copyright is claimed. + * This code is in the public domain; do with it what you wish. + * + * Equivalent code is available from RSA Data Security, Inc. + * This code has been tested against that, and is equivalent, + * except that you don't need to include two pages of legalese + * with every copy. + * + * To compute the message digest of a chunk of bytes, declare an + * MD5Context structure, pass it to MD5Init, call MD5Update as + * needed on buffers full of bytes, and then call MD5Final, which + * will fill a supplied 16-byte array with the digest. + * + * See README and COPYING for more details. + * + * And is re-released under the NuttX modified BSD license: + * + * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 __APPS_INCLUDE_NETUTILS_MD5_H +#define __APPS_INCLUDE_NETUTILS_MD5_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef CONFIG_CODECS_HASH_MD5 + +#ifdef __cplusplus +extern "C" +{ +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +struct MD5Context +{ + uint32_t buf[4]; + uint32_t bits[2]; + uint8_t in[64]; +}; + +typedef struct MD5Context MD5_CTX; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +void MD5Init(struct MD5Context *context); +void MD5Update(struct MD5Context *context, unsigned char const *buf, + unsigned len); +void MD5Final(unsigned char digest[16], struct MD5Context *context); +void MD5Transform(uint32_t buf[4], uint32_t const in[16]); + +void md5_sum(const uint8_t *addr, const size_t len, uint8_t *mac); +char *md5_hash(const uint8_t *addr, const size_t len); + +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_CODECS_HASH_MD5 */ +#endif /* __APPS_INCLUDE_NETUTILS_MD5_H */ diff --git a/apps/include/netutils/urldecode.h b/apps/include/netutils/urldecode.h new file mode 100644 index 0000000000..136d33041a --- /dev/null +++ b/apps/include/netutils/urldecode.h @@ -0,0 +1,74 @@ +/**************************************************************************** + * apps/include/netutils/urldecode.h + * + * This file is part of the NuttX RTOS: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 __APPS_INCLUDE_NETUTILS_URLDECODE_H +#define __APPS_INCLUDE_NETUTILS_URLDECODE_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef __cplusplus +extern "C" +{ +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE_NEWMEMORY +char *url_encode(char *str); +char *url_decode(char *str); +#endif /* CONFIG_CODECS_URLCODE_NEWMEMORY */ + +#ifdef CONFIG_CODECS_URLCODE +char *urlencode(const char *src, const int src_len, char *dest, int *dest_len); +char *urldecode(const char *src, const int src_len, char *dest, int *dest_len); +#endif /* CONFIG_CODECS_URLCODE */ + +#ifdef CONFIG_CODECS_AVR_URLCODE +void urlrawdecode(char *urlbuf); +void urlrawencode(char *str,char *urlbuf); +#endif /* CONFIG_CODECS_AVR_URLCODE */ + +#ifdef __cplusplus +} +#endif + +#endif /* __APPS_INCLUDE_NETUTILS_URLDECODE_H */ + diff --git a/apps/netutils/Kconfig b/apps/netutils/Kconfig index d59afb28eb..42a6713a06 100644 --- a/apps/netutils/Kconfig +++ b/apps/netutils/Kconfig @@ -5,6 +5,7 @@ comment "Networking Utilities" +source "$APPSDIR/netutils/codecs/Kconfig" source "$APPSDIR/netutils/dhcpc/Kconfig" source "$APPSDIR/netutils/dhcpd/Kconfig" source "$APPSDIR/netutils/ftpc/Kconfig" diff --git a/apps/netutils/Make.defs b/apps/netutils/Make.defs index 9fb25b80f7..b603c9dd33 100644 --- a/apps/netutils/Make.defs +++ b/apps/netutils/Make.defs @@ -34,6 +34,10 @@ # ############################################################################ +ifeq ($(CONFIG_NETUTILS_CODECS),y) +CONFIGURED_APPS += netutils/codecs +endif + ifeq ($(CONFIG_NETUTILS_DHCPC),y) CONFIGURED_APPS += netutils/dhcpc endif diff --git a/apps/netutils/Makefile b/apps/netutils/Makefile index e60771d327..e03369e303 100644 --- a/apps/netutils/Makefile +++ b/apps/netutils/Makefile @@ -37,7 +37,7 @@ # Sub-directories -SUBDIRS = json +SUBDIRS = json codecs ifeq ($(CONFIG_NET),y) SUBDIRS += uiplib dhcpc dhcpd discover ftpc ftpd resolv smtp telnetd SUBDIRS += webclient webserver tftpc thttpd xmlrpc diff --git a/apps/netutils/codecs/Kconfig b/apps/netutils/codecs/Kconfig new file mode 100644 index 0000000000..5248f1d5db --- /dev/null +++ b/apps/netutils/codecs/Kconfig @@ -0,0 +1,59 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config NETUTILS_CODECS + bool "CODEC Library" + default n + ---help--- + Enables the netutils/code library: Base64 coding, URL coding, MD5. + +if NETUTILS_CODECS + +config CODECS_BASE64 + bool "Base 64 Support" + default n + ---help--- + Enables support for the following interfaces: base64_encode(), + base64_decode(), base64w_encode(), and base64w_decode(), + + Contributed NuttX by Darcy Gong. + +config CODECS_HASH_MD5 + bool "MD5 Support" + default n + ---help--- + Enables support for the following interfaces: MD5Init(), + MD5Update(), MD5Final(), MD5Transform(), md5_sum() and md5_hash() + + Contributed NuttX by Darcy Gong. + +config CODECS_URLCODE + bool "URL Decode Support" + default n + ---help--- + Enables support for the following interfaces: urlencode() and + urldecode() + + Contributed NuttX by Darcy Gong. + +config CODECS_URLCODE_NEWMEMORY + bool "URL Allocating Decode Support" + default n + ---help--- + Enables support for the following interfaces: url_encode() and + url_decode() + + Contributed NuttX by Darcy Gong. + +config CODECS_AVR_URLCODE + bool "URL Raw Decode Support" + default n + ---help--- + Enables support for the following interfaces: urlrawdecode() and + urlrawencode() + + Contributed NuttX by Darcy Gong. + +endif diff --git a/apps/netutils/codecs/Makefile b/apps/netutils/codecs/Makefile new file mode 100644 index 0000000000..d1b84d4603 --- /dev/null +++ b/apps/netutils/codecs/Makefile @@ -0,0 +1,91 @@ +############################################################################ +# apps/netutils/codecs/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +ASRCS = +CSRCS = urldecode.c base64.c md5.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 + +context: + +.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 Make.dep .depend + +-include Make.dep diff --git a/apps/netutils/codecs/base64.c b/apps/netutils/codecs/base64.c new file mode 100644 index 0000000000..c1656b3433 --- /dev/null +++ b/apps/netutils/codecs/base64.c @@ -0,0 +1,359 @@ +/**************************************************************************** + * apps/include/netutils/base64.h + * + * This file is part of the NuttX RTOS: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Darcy Gong + * + * Reference: + * + * Base64 encoding/decoding (RFC1341) + * Copyright (c) 2005, Jouni Malinen + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + * + * Alternatively, this software may be distributed under the terms of BSD + * license. + * + * See README and COPYING for more details. + * + * And is re-released under the NuttX modified BSD license: + * + * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 + +#ifdef CONFIG_CODECS_BASE64 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: base64_tab + ****************************************************************************/ + +static void base64_tab(unsigned char *tab, size_t len, bool websafe) +{ + static const char *_tab = + "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/"; + + memset(tab, 0, len); + if (len >= 64) + { + memcpy(tab, _tab, 64); + } + + if (websafe) + { + tab[62] = '-'; + tab[63] = '_'; + } +} + +/**************************************************************************** + * Name: _base64_encode + * + * Description: + * Base64 encode + * + * Caller is responsible for freeing the returned buffer. Returned buffer + * is nul terminated to make it easier to use as a C string. The nul + * terminator is not included in out_len. + * + * Input Parameters: + * src: Data to be encoded + * len: Length of the data to be encoded + * out_len: Pointer to output length variable, or NULL if not used + * + * Returned Value: + * Returns: Allocated buffer of out_len bytes of encoded data, + * or NULL on failure + * + ****************************************************************************/ + +static unsigned char *_base64_encode(const unsigned char *src, size_t len, + unsigned char *dst, size_t * out_len, + bool websafe) +{ + unsigned char *out; + unsigned char *pos; + const unsigned char *end; + const unsigned char *in; + size_t olen; +/*int line_len; */ + unsigned char base64_table[64]; + char ch = '='; + + if (websafe) + { + ch = '.'; + } + + base64_tab(base64_table, sizeof(base64_table), websafe); + olen = len * 4 / 3 + 4; /* 3-byte blocks to 4-byte */ + +#if 0 + olen += olen / 72; /* line feeds */ + olen++; /* nul termination */ + out = malloc(olen); + if (out == NULL) + { + return NULL; + } +#endif + + end = src + len; + in = src; + + if (dst) + { + pos = out = dst; + } + else + { + pos = out = malloc(olen); + if (out == NULL) + { + return NULL; + } + } + +/*line_len = 0; */ + while (end - in >= 3) + { + *pos++ = base64_table[in[0] >> 2]; + *pos++ = base64_table[((in[0] & 0x03) << 4) | (in[1] >> 4)]; + *pos++ = base64_table[((in[1] & 0x0f) << 2) | (in[2] >> 6)]; + *pos++ = base64_table[in[2] & 0x3f]; + in += 3; + /* line_len += 4; */ + } + + if (end - in) + { + *pos++ = base64_table[in[0] >> 2]; + if (end - in == 1) + { + *pos++ = base64_table[(in[0] & 0x03) << 4]; + *pos++ = ch; /* *pos++ = '='; */ + } + else + { + *pos++ = base64_table[((in[0] & 0x03) << 4) | (in[1] >> 4)]; + *pos++ = base64_table[(in[1] & 0x0f) << 2]; + } + *pos++ = ch; /* *pos++ = '='; */ + /* line_len += 4; */ + } + +#if 0 + if (line_len) + { + *pos++ = '\n'; + } +#endif + + *pos = '\0'; + if (out_len) + { + *out_len = pos - out; + } + +/*out[*out_len] = '\0'; */ + return out; +} + +/**************************************************************************** + * Name: _base64_decode + * + * Description: + * Base64 decode + * + * Caller is responsible for freeing the returned buffer. + * + * Input Parameters: + * src: Data to be decoded + * len: Length of the data to be decoded + * out_len: Pointer to output length variable + * + * Returned Value: + * Returns: Allocated buffer of out_len bytes of decoded data, + * or NULL on failure + * + ****************************************************************************/ + +static unsigned char *_base64_decode(const unsigned char *src, size_t len, + unsigned char *dst, size_t * out_len, + bool websafe) +{ + unsigned char dtable[256]; + unsigned char *out; + unsigned char *pos; + unsigned char in[4]; + unsigned char block[4]; + unsigned char tmp; + size_t count; + size_t i; + unsigned char base64_table[64]; + char ch = '='; + + if (websafe) + { + ch = '.'; + } + base64_tab(base64_table, sizeof(base64_table), websafe); + + memset(dtable, 0x80, 256); + for (i = 0; i < sizeof(base64_table); i++) + { + dtable[base64_table[i]] = i; + } + + dtable[(int)ch] = 0; /* dtable['='] = 0; */ + + count = 0; + for (i = 0; i < len; i++) + { + if (dtable[src[i]] != 0x80) + { + count++; + } + } + + if (count % 4) + { + return NULL; + } + + if (dst) + { + pos = out = dst; + } + else + { + pos = out = malloc(count); + if (out == NULL) + { + return NULL; + } + } + + count = 0; + for (i = 0; i < len; i++) + { + tmp = dtable[src[i]]; + if (tmp == 0x80) + { + continue; + } + + in[count] = src[i]; + block[count] = tmp; + count++; + if (count == 4) + { + *pos++ = (block[0] << 2) | (block[1] >> 4); + *pos++ = (block[1] << 4) | (block[2] >> 2); + *pos++ = (block[2] << 6) | block[3]; + count = 0; + } + } + + if (pos > out) + { + if (in[2] == ch) /* if (in[2] == '=') */ + { + pos -= 2; + } + else if (in[3] == ch) /* else if (in[3] == '=') */ + { + pos--; + } + } + + *out_len = pos - out; + return out; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: base64_encode + ****************************************************************************/ + +unsigned char *base64_encode(const unsigned char *src, size_t len, + unsigned char *dst, size_t * out_len) +{ + return _base64_encode(src, len, dst, out_len, false); +} + +/**************************************************************************** + * Name: base64_decode + ****************************************************************************/ + +unsigned char *base64_decode(const unsigned char *src, size_t len, + unsigned char *dst, size_t * out_len) +{ + return _base64_decode(src, len, dst, out_len, false); +} + +/**************************************************************************** + * Name: base64w_encode + ****************************************************************************/ + +unsigned char *base64w_encode(const unsigned char *src, size_t len, + unsigned char *dst, size_t * out_len) +{ + return _base64_encode(src, len, dst, out_len, true); +} + +/**************************************************************************** + * Name: base64w_decode + ****************************************************************************/ + +unsigned char *base64w_decode(const unsigned char *src, size_t len, + unsigned char *dst, size_t * out_len) +{ + return _base64_decode(src, len, dst, out_len, true); +} + +#endif /* CONFIG_CODECS_BASE64 */ diff --git a/apps/netutils/codecs/md5.c b/apps/netutils/codecs/md5.c new file mode 100644 index 0000000000..da25d14b15 --- /dev/null +++ b/apps/netutils/codecs/md5.c @@ -0,0 +1,402 @@ +/**************************************************************************** + * apps/include/netutils/base64.h + * + * This file is part of the NuttX RTOS: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Darcy Gong + * + * Reference: + * + * This code implements the MD5 message-digest algorithm. + * The algorithm is due to Ron Rivest. This code was + * written by Colin Plumb in 1993, no copyright is claimed. + * This code is in the public domain; do with it what you wish. + * + * Equivalent code is available from RSA Data Security, Inc. + * This code has been tested against that, and is equivalent, + * except that you don't need to include two pages of legalese + * with every copy. + * + * To compute the message digest of a chunk of bytes, declare an + * MD5Context structure, pass it to MD5Init, call MD5Update as + * needed on buffers full of bytes, and then call MD5Final, which + * will fill a supplied 16-byte array with the digest. + * + * See README and COPYING for more details. + * + * And is re-released under the NuttX modified BSD license: + * + * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 + +#ifdef CONFIG_CODECS_HASH_MD5 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* The four core functions - F1 is optimized somewhat */ + +/* #define F1(x, y, z) (x & y | ~x & z) */ +# define F1(x, y, z) (z ^ (x & (y ^ z))) +# define F2(x, y, z) F1(z, x, y) +# define F3(x, y, z) (x ^ y ^ z) +# define F4(x, y, z) (y ^ (x | ~z)) + +/* This is the central step in the MD5 algorithm. */ +# define MD5STEP(f, w, x, y, z, data, s) \ + ( w += f(x, y, z) + data, w = w<>(32-s), w += x ) + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: byteReverse + ****************************************************************************/ + +#ifndef CONFIG_ENDIAN_BIG +# define byteReverse(buf, len) +#else +static void byteReverse(unsigned char *buf, unsigned longs) +{ + uint32_t t; + do + { + t = ((uint32_t)buf[3] << 8) | + ((uint32_t)buf[2]) << 16) | + ((uint32_t)buf[1] << 8) | + (uint32_t)buf[0]; + + *(uint32_t*)buf = t; + buf += 4; + } + while (--longs); +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: MD5Init + * + * Description: + * Start MD5 accumulation. Set bit count to 0 and buffer to mysterious + * initialization constants. + * + ****************************************************************************/ + +void MD5Init(struct MD5Context *ctx) +{ + ctx->buf[0] = 0x67452301; + ctx->buf[1] = 0xefcdab89; + ctx->buf[2] = 0x98badcfe; + ctx->buf[3] = 0x10325476; + + ctx->bits[0] = 0; + ctx->bits[1] = 0; +} + +/**************************************************************************** + * Name: MD5Update + * + * Description: + * Update context to reflect the concatenation of another buffer full + * of bytes. + * + ****************************************************************************/ + +void MD5Update(struct MD5Context *ctx, unsigned char const *buf, unsigned len) +{ + uint32_t t; + + /* Update bitcount */ + + t = ctx->bits[0]; + if ((ctx->bits[0] = t + ((uint32_t) len << 3)) < t) + { + /* Carry from low to high */ + + ctx->bits[1]++; + } + + ctx->bits[1] += len >> 29; + + /* Bytes already in shsInfo->data */ + + t = (t >> 3) & 0x3f; + + /* Handle any leading odd-sized chunks */ + + if (t) + { + unsigned char *p = (unsigned char *)ctx->in + t; + + t = 64 - t; + if (len < t) + { + memcpy(p, buf, len); + return; + } + + memcpy(p, buf, t); + byteReverse(ctx->in, 16); + MD5Transform(ctx->buf, (uint32_t *) ctx->in); + buf += t; + len -= t; + } + + /* Process data in 64-byte chunks */ + + while (len >= 64) + { + memcpy(ctx->in, buf, 64); + byteReverse(ctx->in, 16); + MD5Transform(ctx->buf, (uint32_t *) ctx->in); + buf += 64; + len -= 64; + } + + /* Handle any remaining bytes of data. */ + + memcpy(ctx->in, buf, len); +} + +/**************************************************************************** + * Name: MD5Final + * + * Description: + * Final wrapup - pad to 64-byte boundary with the bit pattern + * 1 0* (64-bit count of bits processed, MSB-first) + * + ****************************************************************************/ + +void MD5Final(unsigned char digest[16], struct MD5Context *ctx) +{ + unsigned count; + unsigned char *p; + + /* Compute number of bytes mod 64 */ + + count = (ctx->bits[0] >> 3) & 0x3f; + + /* Set the first char of padding to 0x80. This is safe since there is + * always at least one byte free. + */ + + p = ctx->in + count; + *p++ = 0x80; + + /* Bytes of padding needed to make 64 bytes */ + + count = 64 - 1 - count; + + /* Pad out to 56 mod 64 */ + + if (count < 8) + { + /* Two lots of padding: Pad the first block to 64 bytes */ + + memset(p, 0, count); + byteReverse(ctx->in, 16); + MD5Transform(ctx->buf, (uint32_t *) ctx->in); + + /* Now fill the next block with 56 bytes */ + + memset(ctx->in, 0, 56); + } + else + { + /* Pad block to 56 bytes */ + + memset(p, 0, count - 8); + } + + byteReverse(ctx->in, 14); + + /* Append length in bits and transform */ + + ((uint32_t *)ctx->in)[14] = ctx->bits[0]; + ((uint32_t *)ctx->in)[15] = ctx->bits[1]; + + MD5Transform(ctx->buf, (uint32_t *) ctx->in); + byteReverse((unsigned char *)ctx->buf, 4); + memcpy(digest, ctx->buf, 16); + memset(ctx, 0, sizeof(ctx)); /* In case it's sensitive */ +} + +/**************************************************************************** + * Name: MD5Transform + * + * Description: + * The core of the MD5 algorithm, this alters an existing MD5 hash to + * reflect the addition of 16 longwords of new data. MD5Update blocks + * the data and converts bytes into longwords for this routine. + * + ****************************************************************************/ + +void MD5Transform(uint32_t buf[4], uint32_t const in[16]) +{ + register uint32_t a, b, c, d; + + a = buf[0]; + b = buf[1]; + c = buf[2]; + d = buf[3]; + + MD5STEP(F1, a, b, c, d, in[0] + 0xd76aa478, 7); + MD5STEP(F1, d, a, b, c, in[1] + 0xe8c7b756, 12); + MD5STEP(F1, c, d, a, b, in[2] + 0x242070db, 17); + MD5STEP(F1, b, c, d, a, in[3] + 0xc1bdceee, 22); + MD5STEP(F1, a, b, c, d, in[4] + 0xf57c0faf, 7); + MD5STEP(F1, d, a, b, c, in[5] + 0x4787c62a, 12); + MD5STEP(F1, c, d, a, b, in[6] + 0xa8304613, 17); + MD5STEP(F1, b, c, d, a, in[7] + 0xfd469501, 22); + MD5STEP(F1, a, b, c, d, in[8] + 0x698098d8, 7); + MD5STEP(F1, d, a, b, c, in[9] + 0x8b44f7af, 12); + MD5STEP(F1, c, d, a, b, in[10] + 0xffff5bb1, 17); + MD5STEP(F1, b, c, d, a, in[11] + 0x895cd7be, 22); + MD5STEP(F1, a, b, c, d, in[12] + 0x6b901122, 7); + MD5STEP(F1, d, a, b, c, in[13] + 0xfd987193, 12); + MD5STEP(F1, c, d, a, b, in[14] + 0xa679438e, 17); + MD5STEP(F1, b, c, d, a, in[15] + 0x49b40821, 22); + + MD5STEP(F2, a, b, c, d, in[1] + 0xf61e2562, 5); + MD5STEP(F2, d, a, b, c, in[6] + 0xc040b340, 9); + MD5STEP(F2, c, d, a, b, in[11] + 0x265e5a51, 14); + MD5STEP(F2, b, c, d, a, in[0] + 0xe9b6c7aa, 20); + MD5STEP(F2, a, b, c, d, in[5] + 0xd62f105d, 5); + MD5STEP(F2, d, a, b, c, in[10] + 0x02441453, 9); + MD5STEP(F2, c, d, a, b, in[15] + 0xd8a1e681, 14); + MD5STEP(F2, b, c, d, a, in[4] + 0xe7d3fbc8, 20); + MD5STEP(F2, a, b, c, d, in[9] + 0x21e1cde6, 5); + MD5STEP(F2, d, a, b, c, in[14] + 0xc33707d6, 9); + MD5STEP(F2, c, d, a, b, in[3] + 0xf4d50d87, 14); + MD5STEP(F2, b, c, d, a, in[8] + 0x455a14ed, 20); + MD5STEP(F2, a, b, c, d, in[13] + 0xa9e3e905, 5); + MD5STEP(F2, d, a, b, c, in[2] + 0xfcefa3f8, 9); + MD5STEP(F2, c, d, a, b, in[7] + 0x676f02d9, 14); + MD5STEP(F2, b, c, d, a, in[12] + 0x8d2a4c8a, 20); + + MD5STEP(F3, a, b, c, d, in[5] + 0xfffa3942, 4); + MD5STEP(F3, d, a, b, c, in[8] + 0x8771f681, 11); + MD5STEP(F3, c, d, a, b, in[11] + 0x6d9d6122, 16); + MD5STEP(F3, b, c, d, a, in[14] + 0xfde5380c, 23); + MD5STEP(F3, a, b, c, d, in[1] + 0xa4beea44, 4); + MD5STEP(F3, d, a, b, c, in[4] + 0x4bdecfa9, 11); + MD5STEP(F3, c, d, a, b, in[7] + 0xf6bb4b60, 16); + MD5STEP(F3, b, c, d, a, in[10] + 0xbebfbc70, 23); + MD5STEP(F3, a, b, c, d, in[13] + 0x289b7ec6, 4); + MD5STEP(F3, d, a, b, c, in[0] + 0xeaa127fa, 11); + MD5STEP(F3, c, d, a, b, in[3] + 0xd4ef3085, 16); + MD5STEP(F3, b, c, d, a, in[6] + 0x04881d05, 23); + MD5STEP(F3, a, b, c, d, in[9] + 0xd9d4d039, 4); + MD5STEP(F3, d, a, b, c, in[12] + 0xe6db99e5, 11); + MD5STEP(F3, c, d, a, b, in[15] + 0x1fa27cf8, 16); + MD5STEP(F3, b, c, d, a, in[2] + 0xc4ac5665, 23); + + MD5STEP(F4, a, b, c, d, in[0] + 0xf4292244, 6); + MD5STEP(F4, d, a, b, c, in[7] + 0x432aff97, 10); + MD5STEP(F4, c, d, a, b, in[14] + 0xab9423a7, 15); + MD5STEP(F4, b, c, d, a, in[5] + 0xfc93a039, 21); + MD5STEP(F4, a, b, c, d, in[12] + 0x655b59c3, 6); + MD5STEP(F4, d, a, b, c, in[3] + 0x8f0ccc92, 10); + MD5STEP(F4, c, d, a, b, in[10] + 0xffeff47d, 15); + MD5STEP(F4, b, c, d, a, in[1] + 0x85845dd1, 21); + MD5STEP(F4, a, b, c, d, in[8] + 0x6fa87e4f, 6); + MD5STEP(F4, d, a, b, c, in[15] + 0xfe2ce6e0, 10); + MD5STEP(F4, c, d, a, b, in[6] + 0xa3014314, 15); + MD5STEP(F4, b, c, d, a, in[13] + 0x4e0811a1, 21); + MD5STEP(F4, a, b, c, d, in[4] + 0xf7537e82, 6); + MD5STEP(F4, d, a, b, c, in[11] + 0xbd3af235, 10); + MD5STEP(F4, c, d, a, b, in[2] + 0x2ad7d2bb, 15); + MD5STEP(F4, b, c, d, a, in[9] + 0xeb86d391, 21); + + buf[0] += a; + buf[1] += b; + buf[2] += c; + buf[3] += d; +} + +/**************************************************************************** + * Name: md5_sum + * + * Description: + * MD5 hash for a data block + * + * Input Parameters: + * addr: Pointers to the data area + * len: Lengths of the data block + * mac: Buffer for the hash + * + ****************************************************************************/ + +void md5_sum(const uint8_t * addr, const size_t len, uint8_t * mac) +{ + MD5_CTX ctx; + + MD5Init(&ctx); + MD5Update(&ctx, addr, len); + MD5Final(mac, &ctx); +} + +/**************************************************************************** + * Name: md5_hash + ****************************************************************************/ + +char *md5_hash(const uint8_t * addr, const size_t len) +{ + uint8_t digest[16]; + char *hash; + int i; + + hash = malloc(33); + md5_sum(addr, len, digest); + for (i = 0; i < 16; i++) + { + vsprintf(&hash[i * 2], "%.2x", digest[i]); + } + + hash[32] = 0; + return hash; +} + +#endif /* CONFIG_CODECS_HASH_MD5 */ diff --git a/apps/netutils/codecs/urldecode.c b/apps/netutils/codecs/urldecode.c new file mode 100644 index 0000000000..9b3b609550 --- /dev/null +++ b/apps/netutils/codecs/urldecode.c @@ -0,0 +1,429 @@ +/**************************************************************************** + * apps/include/netutils/base64.h + * + * This file is part of the NuttX RTOS: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE +# define IS_HEX_CHAR(ch) \ + ((ch >= '0' && ch <= '9') || \ + (ch >= 'a' && ch <= 'f') || \ + (ch >= 'A' && ch <= 'F')) + +# define HEX_VALUE(ch, value) \ + if (ch >= '0' && ch <= '9') \ + { \ + value = ch - '0'; \ + } \ + else if (ch >= 'a' && ch <= 'f') \ + { \ + value = ch - 'a' + 10; \ + } \ + else \ + { \ + value = ch - 'A' + 10; \ + } +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: from_hex + * + * Description: + * Converts a hex character to its integer value, + * + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE_NEWMEMORY +static char from_hex(char ch) +{ + return isdigit(ch) ? ch - '0' : tolower(ch) - 'a' + 10; +} +#endif + +/**************************************************************************** + * Name: + * + * Description: + * Converts an integer value to its hex character, + * + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE_NEWMEMORY +static char to_hex(char code) +{ + static const char hex[] = "0123456789abcdef"; + return hex[code & 15]; +} +#endif + +/**************************************************************************** + * Name: int2h + * + * Description: + * Convert a single character to a 2 digit hex str a terminating '\0' is + * added + * + ****************************************************************************/ + +#ifdef CONFIG_CODECS_AVR_URLCODE +static void int2h(char c, char *hstr) +{ + hstr[1] = (c & 0xf) + '0'; + if ((c & 0xf) > 9) + { + hstr[1] = (c & 0xf) - 10 + 'a'; + } + + c = (c >> 4) & 0xf; + hstr[0] = c + '0'; + if (c > 9) + { + hstr[0] = c - 10 + 'a'; + } + + hstr[2] = '\0'; +} +#endif + +/**************************************************************************** + * Name: h2int + * + * Description: + * Convert a single hex digit character to its integer value. + * + ****************************************************************************/ + +#ifdef CONFIG_CODECS_AVR_URLCODE +static unsigned char h2int(char c) +{ + if (c >= '0' && c <= '9') + { + return ((unsigned char)c - '0'); + } + + if (c >= 'a' && c <= 'f') + { + return ((unsigned char)c - 'a' + 10); + } + + if (c >= 'A' && c <= 'F') + { + return ((unsigned char)c - 'A' + 10); + } + + return 0; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: + * + * Description: + * Returns a url-encoded version of str. + * + * IMPORTANT: be sure to free() the returned string after use. + * + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE_NEWMEMORY +char *url_encode(char *str) +{ + char *pstr = str; + char *buf = malloc(strlen(str) * 3 + 1); + char *pbuf = buf; + + while (*pstr) + { + if (isalnum(*pstr) || *pstr == '-' || *pstr == '_' || *pstr == '.' || *pstr == '~') + { + *pbuf++ = *pstr; + } + else if (*pstr == ' ') + { + *pbuf++ = '+'; + } + else + { + *pbuf++ = '%'; + *pbuf++ = to_hex(*pstr >> 4); + *pbuf++ = to_hex(*pstr & 15); + } + + pstr++; + } + + *pbuf = '\0'; + return buf; +} +#endif + +/**************************************************************************** + * Name: url_decode + * + * Description: + * Returns a url-decoded version of str. + * + * IMPORTANT: be sure to free() the returned string after use. + * + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE_NEWMEMORY +char *url_decode(char *str) +{ + char *pstr = str; + char *buf = malloc(strlen(str) + 1); + char *pbuf = buf; + + while (*pstr) + { + if (*pstr == '%') + { + if (pstr[1] && pstr[2]) + { + *pbuf++ = from_hex(pstr[1]) << 4 | from_hex(pstr[2]); + pstr += 2; + } + } + else if (*pstr == '+') + { + *pbuf++ = ' '; + } + else + { + *pbuf++ = *pstr; + } + + pstr++; + } + + *pbuf = '\0'; + return buf; +} +#endif + +/**************************************************************************** + * Name: urlencode + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE +char *urlencode(const char *src, const int src_len, char *dest, int *dest_len) +{ + static const unsigned char hex_chars[] = "0123456789ABCDEF"; + const unsigned char *pSrc; + const unsigned char *pEnd; + char *pDest; + + pDest = dest; + pEnd = (unsigned char *)src + src_len; + for (pSrc = (unsigned char *)src; pSrc < pEnd; pSrc++) + { + if ((*pSrc >= '0' && *pSrc <= '9') || + (*pSrc >= 'a' && *pSrc <= 'z') || + (*pSrc >= 'A' && *pSrc <= 'Z') || + (*pSrc == '_' || *pSrc == '-' || *pSrc == '.' || *pSrc == '~')) + { + *pDest++ = *pSrc; + } + else if (*pSrc == ' ') + { + *pDest++ = '+'; + } + else + { + *pDest++ = '%'; + *pDest++ = hex_chars[(*pSrc) >> 4]; + *pDest++ = hex_chars[(*pSrc) & 0x0F]; + } + } + + *pDest = '\0'; + *dest_len = pDest - dest; + return dest; +} +#endif + +/**************************************************************************** + * Name: urldecode + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE +char *urldecode(const char *src, const int src_len, char *dest, int *dest_len) +{ + const unsigned char *pSrc; + const unsigned char *pEnd; + char *pDest; + unsigned char cHigh; + unsigned char cLow; + int valHigh; + int valLow; + + pDest = dest; + pSrc = (unsigned char *)src; + pEnd = (unsigned char *)src + src_len; + while (pSrc < pEnd) + { + if (*pSrc == '%' && pSrc + 2 < pEnd) + { + cHigh = *(pSrc + 1); + cLow = *(pSrc + 2); + + if (IS_HEX_CHAR(cHigh) && IS_HEX_CHAR(cLow)) + { + HEX_VALUE(cHigh, valHigh) + HEX_VALUE(cLow, valLow) + *pDest++ = (valHigh << 4) | valLow; + pSrc += 3; + } + else + { + *pDest++ = *pSrc; + pSrc++; + } + } + else if (*pSrc == '+') + { + *pDest++ = ' '; + pSrc++; + } + else + { + *pDest++ = *pSrc; + pSrc++; + } + } + + *pDest = '\0'; + *dest_len = pDest - dest; + return dest; +} +#endif + +/**************************************************************************** + * Name: urlrawdecode + * + * Description: + * decode a url string e.g "hello%20joe" or "hello+joe" becomes "hello joe" + * + ****************************************************************************/ + +#ifdef CONFIG_CODECS_AVR_URLCODE +void urlrawdecode(char *urlbuf) +{ + char c; + char *dst; + dst = urlbuf; + while ((c = *urlbuf)) + { + if (c == '+') + { + c = ' '; + } + + if (c == '%') + { + urlbuf++; + c = *urlbuf; + urlbuf++; + c = (h2int(c) << 4) | h2int(*urlbuf); + } + + *dst = c; + dst++; + urlbuf++; + } + + *dst = '\0'; +} +#endif + +/**************************************************************************** + * Name: urlrawencode + * + * Description: + * There must be enoug space in urlbuf. In the worst case that is 3 times + * the length of str + * + ****************************************************************************/ + +#ifdef CONFIG_CODECS_AVR_URLCODE +void urlrawencode(char *str, char *urlbuf) +{ + char c; + while ((c = *str)) + { + if (c == ' ' || isalnum(c) || c == '_' || c == '-' || c == '.' || c == '~') + { + if (c == ' ') + { + c = '+'; + } + + *urlbuf = c; + str++; + urlbuf++; + continue; + } + + *urlbuf = '%'; + urlbuf++; + int2h(c, urlbuf); + urlbuf++; + urlbuf++; + str++; + } + + *urlbuf = '\0'; +} +#endif diff --git a/apps/nshlib/Kconfig b/apps/nshlib/Kconfig index e89a4cc3f9..7009e6a3d6 100644 --- a/apps/nshlib/Kconfig +++ b/apps/nshlib/Kconfig @@ -23,122 +23,190 @@ config NSH_BUILTIN_APPS (NAMEDAPP). menu "Disable Individual commands" + +config NSH_DISABLE_BASE64DEC + bool "Disable base64dec" + default n + depends on NETUTILS_CODECS && CODECS_BASE64 + +config NSH_DISABLE_BASE64ENC + bool "Disable base64enc" + default n + depends on NETUTILS_CODECS && CODECS_BASE64 + config NSH_DISABLE_CAT bool "Disable cat" default n + config NSH_DISABLE_CD bool "Disable cd" default n + config NSH_DISABLE_CP bool "Disable cp" default n + config NSH_DISABLE_DD bool "Disable dd" default n + config NSH_DISABLE_ECHO bool "Disable echo" default n + config NSH_DISABLE_EXEC bool "Disable exec" default n + config NSH_DISABLE_EXIT bool "Disable exit" default n + config NSH_DISABLE_FREE bool "Disable free" default n + config NSH_DISABLE_GET bool "Disable get" default n + config NSH_DISABLE_HELP bool "Disable help" default n + config NSH_DISABLE_IFCONFIG bool "Disable ifconfig" default n + config NSH_DISABLE_KILL bool "Disable kill" default n + config NSH_DISABLE_LOSETUP bool "Disable losetup" default n + config NSH_DISABLE_LS bool "Disable ls" default n + config NSH_DISABLE_MB bool "Disable mb" default n + +config NSH_DISABLE_MD5 + bool "Disable md5" + default n + depends on NETUTILS_CODECS && CODECS_HASH_MD5 + config NSH_DISABLE_MKDIR bool "Disable mkdir" default n + config NSH_DISABLE_MKFATFS bool "Disable mkfatfs" default n + config NSH_DISABLE_MKFIFO bool "Disable mkfifo" default n + config NSH_DISABLE_MKRD bool "Disable mkrd" default n + config NSH_DISABLE_MH bool "Disable mh" default n + config NSH_DISABLE_MOUNT bool "Disable mount" default n + config NSH_DISABLE_MW bool "Disable mw" default n + config NSH_DISABLE_NSFMOUNT bool "Disable nfsmount" default n + config NSH_DISABLE_PS bool "Disable ps" default n + config NSH_DISABLE_PING bool "Disable ping" default n + config NSH_DISABLE_PUT bool "Disable put" default n + config NSH_DISABLE_PWD bool "Disable pwd" default n + config NSH_DISABLE_RM bool "Disable rm" default n + config NSH_DISABLE_RMDIR bool "Disable rmdir" default n + config NSH_DISABLE_SET bool "Disable set" default n + config NSH_DISABLE_SH bool "Disable sh" default n + config NSH_DISABLE_SLEEP bool "Disable sleep" default n + config NSH_DISABLE_TEST bool "Disable test" default n + config NSH_DISABLE_UMOUNT bool "Disable umount" default n + config NSH_DISABLE_UNSET bool "Disable unset" default n + +config NSH_DISABLE_URLDECODE + bool "Disable urldecode" + default n + depends on NETUTILS_CODECS && CODECS_URLCODE + +config NSH_DISABLE_URLENCODE + bool "Disable urlencode" + default n + depends on NETUTILS_CODECS && CODECS_URLCODE + config NSH_DISABLE_USLEEP bool "Disable usleep" default n + config NSH_DISABLE_WGET bool "Disable wget" default n + config NSH_DISABLE_XD bool "Disable xd" default n + endmenu +config NSH_CODECS_BUFSIZE + int "File buffer size used by CODEC commands" + default 128 + config NSH_FILEIOSIZE int "NSH I/O buffer size" default 1024 diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile index f616374bfd..71f159b388 100644 --- a/apps/nshlib/Makefile +++ b/apps/nshlib/Makefile @@ -39,64 +39,68 @@ include $(APPDIR)/Make.defs # NSH Library -ASRCS = -CSRCS = nsh_init.c nsh_parse.c nsh_console.c nsh_fscmds.c nsh_ddcmd.c \ +ASRCS = +CSRCS = nsh_init.c nsh_parse.c nsh_console.c nsh_fscmds.c nsh_ddcmd.c \ nsh_proccmds.c nsh_mmcmds.c nsh_envcmds.c nsh_dbgcmds.c ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) -CSRCS += nsh_apps.c +CSRCS += nsh_apps.c endif ifeq ($(CONFIG_NSH_ROMFSETC),y) -CSRCS += nsh_romfsetc.c +CSRCS += nsh_romfsetc.c endif ifeq ($(CONFIG_NET),y) -CSRCS += nsh_netinit.c nsh_netcmds.c +CSRCS += nsh_netinit.c nsh_netcmds.c endif ifeq ($(CONFIG_RTC),y) -CSRCS += nsh_timcmds.c +CSRCS += nsh_timcmds.c endif ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y) -CSRCS += nsh_mntcmds.c +CSRCS += nsh_mntcmds.c endif ifeq ($(CONFIG_NSH_CONSOLE),y) -CSRCS += nsh_consolemain.c +CSRCS += nsh_consolemain.c endif ifeq ($(CONFIG_NSH_TELNET),y) -CSRCS += nsh_telnetd.c +CSRCS += nsh_telnetd.c endif ifneq ($(CONFIG_NSH_DISABLESCRIPT),y) -CSRCS += nsh_test.c +CSRCS += nsh_test.c endif ifeq ($(CONFIG_USBDEV),y) -CSRCS += nsh_usbdev.c +CSRCS += nsh_usbdev.c endif -AOBJS = $(ASRCS:.S=$(OBJEXT)) -COBJS = $(CSRCS:.c=$(OBJEXT)) +ifeq ($(CONFIG_NETUTILS_CODECS),y) +CSRCS += nsh_codeccmd.c +endif -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) ifeq ($(WINTOOL),y) - BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = "$(APPDIR)/libapps$(LIBEXT)" + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif -ROOTDEPPATH = --dep-path . -VPATH = +ROOTDEPPATH = --dep-path . +VPATH = # Build targets -all: .built +all: .built .PHONY: context .depend depend clean distclean $(AOBJS): %$(OBJEXT): %.S diff --git a/apps/nshlib/README.txt b/apps/nshlib/README.txt index 9f4a88e3e4..043db2ae9e 100644 --- a/apps/nshlib/README.txt +++ b/apps/nshlib/README.txt @@ -257,6 +257,10 @@ o cd [|-|~|..] 'home' directory is '/'. 'cd ..' sets the current working directory to the parent directory. +o base64dec [-w] [-f] + +o base64dec [-w] [-f] + o cp Copy of the contents of the file at to the location @@ -449,6 +453,8 @@ o ls [-lRs] -l Show size and mode information along with the filenames in the listing. +o md5 [-f] + o mb [=][ ] o mh [=][ ] o mw [=][ ] @@ -781,6 +787,10 @@ o unset nsh> + o urldecode [-f] + + o urlencode [-f] + o usleep Pause execution (sleep) of microseconds. @@ -826,6 +836,8 @@ Command Dependencies on Configuration Settings Command Depends on Configuration ---------- -------------------------- [ !CONFIG_NSH_DISABLESCRIPT + base64dec CONFIG_NETUTILS_CODECS && CONFIG_CODECS_BASE64 + base64enc CONFIG_NETUTILS_CODECS && CONFIG_CODECS_BASE64 cat CONFIG_NFILE_DESCRIPTORS > 0 cd !CONFIG_DISABLE_ENVIRON && CONFIG_NFILE_DESCRIPTORS > 0 cp CONFIG_NFILE_DESCRIPTORS > 0 @@ -841,6 +853,7 @@ Command Dependencies on Configuration Settings kill !CONFIG_DISABLE_SIGNALS losetup !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 ls CONFIG_NFILE_DESCRIPTORS > 0 + md5 CONFIG_NETUTILS_CODECS && CONFIG_CODECS_HASH_MD5 mb,mh,mw --- mkdir !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_FS_WRITABLE (see note 4) mkfatfs !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_FS_FAT @@ -880,20 +893,21 @@ In addition, each NSH command can be individually disabled via one of the follow settings. All of these settings make the configuration of NSH potentially complex but also allow it to squeeze into very small memory footprints. - CONFIG_NSH_DISABLE_CAT, CONFIG_NSH_DISABLE_CD, CONFIG_NSH_DISABLE_CP, - CONFIG_NSH_DISABLE_DD, CONFIG_NSH_DISABLE_DF, CONFIG_NSH_DISABLE_ECHO, - CONFIG_NSH_DISABLE_EXEC, CONFIG_NSH_DISABLE_EXIT, CONFIG_NSH_DISABLE_FREE, - CONFIG_NSH_DISABLE_GET, CONFIG_NSH_DISABLE_HELP, CONFIG_NSH_DISABLE_IFCONFIG, - CONFIG_NSH_DISABLE_KILL, CONFIG_NSH_DISABLE_LOSETUP, CONFIG_NSH_DISABLE_LS, - CONFIG_NSH_DISABLE_MB, CONFIG_NSH_DISABLE_MKDIR, CONFIG_NSH_DISABLE_MKFATFS, - CONFIG_NSH_DISABLE_MKFIFO, CONFIG_NSH_DISABLE_MKRD, CONFIG_NSH_DISABLE_MH, - CONFIG_NSH_DISABLE_MOUNT, CONFIG_NSH_DISABLE_MW, CONFIG_NSH_DISABLE_MV, - CONFIG_NSH_DISABLE_NFSMOUNT, CONFIG_NSH_DISABLE_PS, CONFIG_NSH_DISABLE_PING, - CONFIG_NSH_DISABLE_PUT, CONFIG_NSH_DISABLE_PWD, CONFIG_NSH_DISABLE_RM, - CONFIG_NSH_DISABLE_RMDIR, CONFIG_NSH_DISABLE_SET, CONFIG_NSH_DISABLE_SH, - CONFIG_NSH_DISABLE_SLEEP, CONFIG_NSH_DISABLE_TEST, CONFIG_NSH_DISABLE_UMOUNT, - CONFIG_NSH_DISABLE_UNSET, CONFIG_NSH_DISABLE_USLEEP, CONFIG_NSH_DISABLE_WGET, - CONFIG_NSH_DISABLE_XD + CONFIG_NSH_DISABLE_BASE64DEC, CONFIG_NSH_DISABLE_BASE64ENC, CONFIG_NSH_DISABLE_CAT, + CONFIG_NSH_DISABLE_CD, CONFIG_NSH_DISABLE_CP, CONFIG_NSH_DISABLE_DD, + CONFIG_NSH_DISABLE_DF, CONFIG_NSH_DISABLE_ECHO, CONFIG_NSH_DISABLE_EXEC, + CONFIG_NSH_DISABLE_EXIT, CONFIG_NSH_DISABLE_FREE, CONFIG_NSH_DISABLE_GET, + CONFIG_NSH_DISABLE_HELP, CONFIG_NSH_DISABLE_IFCONFIG, CONFIG_NSH_DISABLE_KILL, + CONFIG_NSH_DISABLE_LOSETUP, CONFIG_NSH_DISABLE_LS, CONFIG_NSH_DISABLE_MD5 + CONFIG_NSH_DISABLE_MB, CONFIG_NSH_DISABLE_MKDIR, CONFIG_NSH_DISABLE_MKFATFS, + CONFIG_NSH_DISABLE_MKFIFO, CONFIG_NSH_DISABLE_MKRD, CONFIG_NSH_DISABLE_MH, + CONFIG_NSH_DISABLE_MOUNT, CONFIG_NSH_DISABLE_MW, CONFIG_NSH_DISABLE_MV, + CONFIG_NSH_DISABLE_NFSMOUNT, CONFIG_NSH_DISABLE_PS, CONFIG_NSH_DISABLE_PING, + CONFIG_NSH_DISABLE_PUT, CONFIG_NSH_DISABLE_PWD, CONFIG_NSH_DISABLE_RM, + CONFIG_NSH_DISABLE_RMDIR, CONFIG_NSH_DISABLE_SET, CONFIG_NSH_DISABLE_SH, + CONFIG_NSH_DISABLE_SLEEP, CONFIG_NSH_DISABLE_TEST, CONFIG_NSH_DISABLE_UMOUNT, + CONFIG_NSH_DISABLE_UNSET, CONFIG_NSH_DISABLE_URLDECODE, CONFIG_NSH_DISABLE_URLENCODE, + CONFIG_NSH_DISABLE_USLEEP, CONFIG_NSH_DISABLE_WGET, CONFIG_NSH_DISABLE_XD Verbose help output can be suppressed by defining CONFIG_NSH_HELP_TERSE. In that case, the help command is still available but will be slightly smaller. diff --git a/apps/nshlib/nsh.h b/apps/nshlib/nsh.h index f85df29dd6..9f36b1d1f0 100644 --- a/apps/nshlib/nsh.h +++ b/apps/nshlib/nsh.h @@ -650,4 +650,28 @@ void nsh_usbtrace(void); # endif #endif /* CONFIG_DISABLE_SIGNALS */ +#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_BASE64) +# ifndef CONFIG_NSH_DISABLE_BASE64DEC + int cmd_base64decode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); +# endif +# ifndef CONFIG_NSH_DISABLE_BASE64ENC + int cmd_base64encode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); +# endif +#endif + +#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_HASH_MD5) +# ifndef CONFIG_NSH_DISABLE_MD5 + int cmd_md5(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); +# endif +#endif + +#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_URLCODE) +# ifndef CONFIG_NSH_DISABLE_URLDECODE + int cmd_urlencode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); +# endif +# ifndef CONFIG_NSH_DISABLE_URLENCODE + int cmd_urldecode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); +# endif +#endif + #endif /* __APPS_NSHLIB_NSH_H */ diff --git a/apps/nshlib/nsh_codeccmd.c b/apps/nshlib/nsh_codeccmd.c new file mode 100644 index 0000000000..8c1f5adbdf --- /dev/null +++ b/apps/nshlib/nsh_codeccmd.c @@ -0,0 +1,538 @@ +/**************************************************************************** + * apps/nshlib/nsh_apps.c + * + * This file is part of NuttX, contributed by Darcy Gong + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Darcy Gong 2012-10-30 + * + * 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 +#ifdef CONFIG_NETUTILS_CODECS + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined(CONFIG_NSH_DISABLE_URLENCODE) && defined(CONFIG_NSH_DISABLE_URLDECODE) +# undef CONFIG_CODECS_URLCODE +#endif + +#ifdef CONFIG_CODECS_URLCODE +#include +#endif + +#if defined(CONFIG_NSH_DISABLE_BASE64ENC) && defined(CONFIG_NSH_DISABLE_BASE64ENC) +# undef CONFIG_CODECS_BASE64 +#endif + +#ifdef CONFIG_CODECS_BASE64 +#include +#endif + +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) +#include +#endif + +#include "nsh.h" +#include "nsh_console.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef CONFIG_NSH_CODECS_BUFSIZE +# define CONFIG_NSH_CODECS_BUFSIZE 128 +#endif + +#define CODEC_MODE_URLENCODE 1 +#define CODEC_MODE_URLDECODE 2 +#define CODEC_MODE_BASE64ENC 3 +#define CODEC_MODE_BASE64DEC 4 +#define CODEC_MODE_HASH_MD5 5 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +typedef void (*codec_callback_t)(FAR char *src_buff, int src_buff_len, + FAR char *dst_buff, FAR int *dst_buff_len, + int mode); + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: urlencode_cb + ****************************************************************************/ + +#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLENCODE) +static void urlencode_cb(FAR char *src_buff, int src_buff_len, + FAR char *dst_buff, FAR int *dst_buff_len, int mode) +{ + urlencode(src_buff,src_buff_len,dst_buff,dst_buff_len); +} +#endif + +/**************************************************************************** + * Name: urldecode_cb + ****************************************************************************/ + +#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) +static void urldecode_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, + FAR int *dst_buff_len, int mode) +{ + urldecode(src_buff,src_buff_len,dst_buff,dst_buff_len); +} +#endif + +/**************************************************************************** + * Name: b64enc_cb + ****************************************************************************/ + +#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) +static void b64enc_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, + FAR int *dst_buff_len, int mode) +{ + if (mode == 0) + { + //dst_buff = + base64_encode((unsigned char *)src_buff, src_buff_len, + (unsigned char *)dst_buff, (size_t *)dst_buff_len); + } + else + { + //dst_buff = + base64w_encode((unsigned char *)src_buff, src_buff_len, + (unsigned char *)dst_buff, (size_t *)dst_buff_len); + } +} +#endif + +/**************************************************************************** + * Name: b64dec_cb + ****************************************************************************/ + +#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64DEC) +static void b64dec_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, + FAR int *dst_buff_len, int mode) +{ + if (mode == 0) + { + //dst_buff = + base64_decode((unsigned char *)src_buff, src_buff_len, + (unsigned char *)dst_buff, (size_t *)dst_buff_len); + } + else + { + //dst_buff = + base64w_decode((unsigned char *)src_buff, src_buff_len, + (unsigned char *)dst_buff,(size_t *)dst_buff_len); + } +} +#endif + +/**************************************************************************** + * Name: md5_cb + ****************************************************************************/ + +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) +static void md5_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, + FAR int *dst_buff_len, int mode) +{ + MD5Update((MD5_CTX *)dst_buff, (unsigned char *)src_buff, src_buff_len); +} +#endif + +/**************************************************************************** + * Name: calc_codec_buffsize + ****************************************************************************/ + +static int calc_codec_buffsize(int src_buffsize, uint8_t mode) +{ + switch (mode) + { + case CODEC_MODE_URLENCODE: + return src_buffsize*3+1; + case CODEC_MODE_URLDECODE: + return src_buffsize+1; + case CODEC_MODE_BASE64ENC: + return ((src_buffsize + 2)/ 3 * 4)+1; + case CODEC_MODE_BASE64DEC: + return (src_buffsize / 4 * 3 + 2)+1; + case CODEC_MODE_HASH_MD5: + return 32+1; + default: + return src_buffsize+1; + } +} + +/**************************************************************************** + * Name: cmd_codecs_proc + ****************************************************************************/ + +static int cmd_codecs_proc(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv, + uint8_t mode, codec_callback_t func) +{ +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) + static const unsigned char hex_chars[] = "0123456789abcdef"; + MD5_CTX ctx; + unsigned char mac[16]; + char *pSrc; + char *pDest; +#endif + + char *localfile = NULL; + char *src_buffer = NULL; + char *buffer = NULL; + char *fullpath = NULL; + const char *fmt; + char *s_data; + bool badarg = false; + bool is_file = false; + bool is_websafe=false; + int option; + int fd = -1; + int buff_len = 0; + int src_buff_len = 0; + int i = 0; + int ret = OK; + + /* Get the command options */ + + while ((option = getopt(argc, argv, ":fw")) != ERROR) + { + switch (option) + { + case 'f': + is_file = true; + break; + +#ifdef CONFIG_CODECS_BASE64 + case 'w': + is_websafe = true; + + if (!(mode == CODEC_MODE_BASE64ENC || mode == CODEC_MODE_BASE64DEC)) + { + badarg = true; + } + break; +#endif + case ':': + nsh_output(vtbl, g_fmtargrequired, argv[0]); + badarg = true; + break; + + case '?': + default: + nsh_output(vtbl, g_fmtarginvalid, argv[0]); + badarg = true; + break; + } + } + + /* If a bad argument was encountered, then return without processing the command */ + + if (badarg) + { + return ERROR; + } + + /* There should be exactly on parameter left on the command-line */ + + if (optind == argc-1) + { + s_data = argv[optind]; + } + else if (optind >= argc) + { + fmt = g_fmttoomanyargs; + goto errout; + } + else + { + fmt = g_fmtargrequired; + goto errout; + } + +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) + if (mode == CODEC_MODE_HASH_MD5) + { + MD5Init(&ctx); + } +#endif + + if (is_file) + { + /* Get the local file name */ + + localfile = s_data; + + /* Get the full path to the local file */ + + fullpath = nsh_getfullpath(vtbl, localfile); + + /* Open the local file for writing */ + + fd = open(fullpath, O_RDONLY|O_TRUNC, 0644); + if (fd < 0) + { + nsh_output(vtbl, g_fmtcmdfailed, argv[0], "open", NSH_ERRNO); + ret = ERROR; + goto exit; + } + + src_buffer = malloc(CONFIG_NSH_CODECS_BUFSIZE+2); +#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) + if (mode == CODEC_MODE_BASE64ENC) + { + src_buff_len = CONFIG_NSH_CODECS_BUFSIZE / 3 * 3; + } + else +#endif + { + src_buff_len = CONFIG_NSH_CODECS_BUFSIZE; + } + + buff_len = calc_codec_buffsize(src_buff_len+2, mode); + buffer = malloc(buff_len); + while(true) + { + memset(src_buffer, 0, src_buff_len+2); + ret=read(fd, src_buffer, src_buff_len); + if (ret < 0) + { + nsh_output(vtbl, g_fmtcmdfailed, argv[0], "read", NSH_ERRNO); + ret = ERROR; + goto exit; + } + else if(ret==0) + { + break; + } + +#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) + if (mode == CODEC_MODE_URLDECODE) + { + if (src_buffer[src_buff_len-1]=='%') + { + ret += read(fd,&src_buffer[src_buff_len],2); + } + else if (src_buffer[src_buff_len-2]=='%') + { + ret += read(fd,&src_buffer[src_buff_len],1); + } + } +#endif + memset(buffer, 0, buff_len); + if (func) + { +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) + if (mode == CODEC_MODE_HASH_MD5) + { + func(src_buffer, ret, (char *)&ctx, &buff_len,0); + } + else +#endif + { + func(src_buffer, ret, buffer, &buff_len,(is_websafe)?1:0); + nsh_output(vtbl, "%s", buffer); + } + } + + buff_len = calc_codec_buffsize(src_buff_len+2, mode); + } + +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) + if (mode == CODEC_MODE_HASH_MD5) + { + MD5Final(mac, &ctx); + pSrc = (char *)&mac; + pDest = buffer; + for(i=0;i<16;i++,pSrc++) + { + *pDest++ = hex_chars[(*pSrc) >> 4]; + *pDest++ = hex_chars[(*pSrc) & 0x0f]; + } + + *pDest='\0'; + nsh_output(vtbl, "%s\n", buffer); + } +#endif + ret = OK; + goto exit; + } + else + { + src_buffer = s_data; + src_buff_len = strlen(s_data); + buff_len = calc_codec_buffsize(src_buff_len, mode); + buffer = malloc(buff_len); + buffer[0]=0; + if (!buffer) + { + fmt = g_fmtcmdoutofmemory; + goto errout; + } + + memset(buffer, 0, buff_len); + if (func) + { +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) + if (mode == CODEC_MODE_HASH_MD5) + { + func(src_buffer, src_buff_len, (char *)&ctx, &buff_len, 0); + MD5Final(mac, &ctx); + pSrc = (char *)&mac; + pDest = buffer; + for(i=0;i<16;i++,pSrc++) + { + *pDest++ = hex_chars[(*pSrc) >> 4]; + *pDest++ = hex_chars[(*pSrc) & 0x0f]; + } + + *pDest='\0'; + } + else +#endif + { + func(src_buffer, src_buff_len, buffer, &buff_len,(is_websafe)?1:0); + } + } + + nsh_output(vtbl, "%s\n",buffer); + src_buffer = NULL; + goto exit; + } + +exit: + if (fd >= 0) + { + close(fd); + } + + if (fullpath) + { + free(fullpath); + } + + if (src_buffer) + { + free(src_buffer); + } + + if (buffer) + { + free(buffer); + } + + return ret; + +errout: + nsh_output(vtbl, fmt, argv[0]); + ret = ERROR; + goto exit; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cmd_urlencode + ****************************************************************************/ + +#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLENCODE) +int cmd_urlencode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_URLENCODE, urlencode_cb); +} +#endif + +/**************************************************************************** + * Name: cmd_urldecode + ****************************************************************************/ + +#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) +int cmd_urldecode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_URLDECODE, urldecode_cb); +} +#endif + +/**************************************************************************** + * Name: cmd_base64encode + ****************************************************************************/ + +#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) +int cmd_base64encode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_BASE64ENC, b64enc_cb); +} +#endif + +/**************************************************************************** + * Name: cmd_base64decode + ****************************************************************************/ + +#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64DEC) +int cmd_base64decode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_BASE64DEC, b64dec_cb); +} +#endif + +/**************************************************************************** + * Name: cmd_md5 + ****************************************************************************/ + +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) +int cmd_md5(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + return cmd_codecs_proc(vtbl,argc,argv,CODEC_MODE_HASH_MD5,md5_cb); +} +#endif + +#endif /* CONFIG_NETUTILS_CODECS */ diff --git a/apps/nshlib/nsh_parse.c b/apps/nshlib/nsh_parse.c index df2f7c3e39..f9642809fc 100644 --- a/apps/nshlib/nsh_parse.c +++ b/apps/nshlib/nsh_parse.c @@ -153,6 +153,15 @@ static const struct cmdmap_s g_cmdmap[] = { "?", cmd_help, 1, 1, NULL }, #endif +#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_BASE64) +# ifndef CONFIG_NSH_DISABLE_BASE64DEC + { "base64dec", cmd_base64decode, 2, 4, "[-w] [-f] " }, +# endif +# ifndef CONFIG_NSH_DISABLE_BASE64ENC + { "base64enc", cmd_base64encode, 2, 4, "[-w] [-f] " }, +# endif +#endif + #if CONFIG_NFILE_DESCRIPTORS > 0 # ifndef CONFIG_NSH_DISABLE_CAT { "cat", cmd_cat, 2, NSH_MAX_ARGUMENTS, " [ [ ...]]" }, @@ -246,6 +255,12 @@ static const struct cmdmap_s g_cmdmap[] = { "mb", cmd_mb, 2, 3, "[=][ ]" }, #endif +#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_HASH_MD5) +# ifndef CONFIG_NSH_DISABLE_MD5 + { "md5", cmd_md5, 2, 3, "[-f] " }, +# endif +#endif + #if !defined(CONFIG_DISABLE_MOUNTPOINT) && CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_FS_WRITABLE) # ifndef CONFIG_NSH_DISABLE_MKDIR { "mkdir", cmd_mkdir, 2, 2, "" }, @@ -363,6 +378,15 @@ static const struct cmdmap_s g_cmdmap[] = # endif #endif +#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_URLCODE) +# ifndef CONFIG_NSH_DISABLE_URLDECODE + { "urldecode", cmd_urldecode, 2, 3, "[-f] " }, +# endif +# ifndef CONFIG_NSH_DISABLE_URLENCODE + { "urlencode", cmd_urlencode, 2, 3, "[-f] " }, +# endif +#endif + #ifndef CONFIG_DISABLE_SIGNALS # ifndef CONFIG_NSH_DISABLE_USLEEP { "usleep", cmd_usleep, 2, 2, "" }, @@ -378,6 +402,7 @@ static const struct cmdmap_s g_cmdmap[] = #ifndef CONFIG_NSH_DISABLE_XD { "xd", cmd_xd, 3, 3, " " }, #endif + { NULL, NULL, 1, 1, NULL } }; From 33a3edbaf731fd409bfd6e9aa3ad46a194a2f9a4 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 31 Oct 2012 16:04:45 +0000 Subject: [PATCH 050/206] Add apps/examples/wgetjson from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5281 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 3 +- apps/examples/Kconfig | 1 + apps/examples/Make.defs | 4 + apps/examples/Makefile | 4 +- apps/examples/README.txt | 9 + apps/examples/wgetjson/Kconfig | 23 ++ apps/examples/wgetjson/Makefile | 105 ++++++ .../wgetjson/webserver/wgetjson/json_cmd.php | 13 + apps/examples/wgetjson/wgetjson_main.c | 305 ++++++++++++++++++ apps/netutils/codecs/md5.c | 4 +- apps/netutils/json/cJSON.c | 10 +- 11 files changed, 472 insertions(+), 9 deletions(-) create mode 100644 apps/examples/wgetjson/Kconfig create mode 100644 apps/examples/wgetjson/Makefile create mode 100644 apps/examples/wgetjson/webserver/wgetjson/json_cmd.php create mode 100644 apps/examples/wgetjson/wgetjson_main.c diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 4d147d91d9..db56d66819 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -392,5 +392,6 @@ * COPYING: Licensing information added. * apps/netutils/codec and include/netutils/urldecode.h, base64.h, and md5.h: A port of the BASE46, MD5 and URL CODEC library from Darcy Gong. - * nslib/nsh_codeccmd.c: NSH commands to use the CODEC library. + * nsnlib/nsh_codeccmd.c: NSH commands to use the CODEC library. Contributed by Darcy Gong. + * apps/examples/wgetjson: Test example contributed by Darcy Gong diff --git a/apps/examples/Kconfig b/apps/examples/Kconfig index f851ad8bda..7f0c8e3658 100644 --- a/apps/examples/Kconfig +++ b/apps/examples/Kconfig @@ -54,5 +54,6 @@ source "$APPSDIR/examples/usbstorage/Kconfig" source "$APPSDIR/examples/usbterm/Kconfig" source "$APPSDIR/examples/watchdog/Kconfig" source "$APPSDIR/examples/wget/Kconfig" +source "$APPSDIR/examples/wgetjson/Kconfig" source "$APPSDIR/examples/wlan/Kconfig" source "$APPSDIR/examples/xmlrpc/Kconfig" diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index ad5653c82e..67c1685fe7 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -234,6 +234,10 @@ ifeq ($(CONFIG_EXAMPLES_WGET),y) CONFIGURED_APPS += examples/wget endif +ifeq ($(CONFIG_EXAMPLES_WGETJSON),y) +CONFIGURED_APPS += examples/wgetjson +endif + ifeq ($(CONFIG_EXAMPLES_WLAN),y) CONFIGURED_APPS += examples/wlan endif diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 0ebc300e4a..d8a2c96646 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -42,7 +42,7 @@ SUBDIRS += helloxx hidkbd igmp json lcdrw mm modbus mount nettest nsh null nx SUBDIRS += nxconsole nxffs nxflat nxhello nximage nxlines nxtext ostest SUBDIRS += pashello pipe poll pwm qencoder rgmp romfs serloop telnetd SUBDIRS += thttpd tiff touchscreen udp uip usbserial sendmail usbstorage -SUBDIRS += usbterm watchdog wget wlan +SUBDIRS += usbterm watchdog wget wgetjson wlan # Sub-directories that might need context setup. Directories may need # context setup for a variety of reasons, but the most common is because @@ -58,7 +58,7 @@ CNTXTDIRS = pwm ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) CNTXTDIRS += adc can cdcacm composite dhcpd discover ftpd json modbus -CNTXTDIRS += nettest qencoder telnetd watchdog +CNTXTDIRS += nettest qencoder telnetd watchdog wgetjson endif ifeq ($(CONFIG_EXAMPLES_HELLO_BUILTIN),y) diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 907467bb17..f254ce154f 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -1747,7 +1747,16 @@ examples/wget CONFIGURED_APPS += resolv CONFIGURED_APPS += webclient +examples/wget +^^^^^^^^^^^^^ + + Uses wget to get a JSON encoded file, then decodes the file. + + CONFIG_EXAMPLES_WDGETJSON_MAXSIZE - Max. JSON Buffer Size + CONFIG_EXAMPLES_EXAMPLES_WGETJSON_URL - wget URL + examples/xmlrpc +^^^^^^^^^^^^^^^ This example exercises the "Embeddable Lightweight XML-RPC Server" which is discussed at: diff --git a/apps/examples/wgetjson/Kconfig b/apps/examples/wgetjson/Kconfig new file mode 100644 index 0000000000..2e3b4b3eb7 --- /dev/null +++ b/apps/examples/wgetjson/Kconfig @@ -0,0 +1,23 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config EXAMPLES_WGETJSON + bool "wget JSON Example" + default n + depends on NETUTILS_JSON + ---help--- + Enable the wget JSON example + +if EXAMPLES_WGETJSON + +config EXAMPLES_WGETJSON_MAXSIZE + int "Max. JSON Buffer Size" + default 10240 + +config EXAMPLES_WGETJSON_URL + string "wget URL" + default "http://10.0.0.1/wgetjson/json_cmd.php" + +endif diff --git a/apps/examples/wgetjson/Makefile b/apps/examples/wgetjson/Makefile new file mode 100644 index 0000000000..e8c3e50650 --- /dev/null +++ b/apps/examples/wgetjson/Makefile @@ -0,0 +1,105 @@ +############################################################################ +# apps/examples/wgetjson/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +# Hello, World! Example + +ASRCS = +CSRCS = wgetjson_main.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 . + +# Buttons built-in application info + +APPNAME = wgetjson +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +# Common build + +VPATH = + +all: .built +.PHONY: context clean depend 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 + +.context: +ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) + $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) + @touch $@ +endif + +context: .context + +.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 Make.dep .depend + +-include Make.dep diff --git a/apps/examples/wgetjson/webserver/wgetjson/json_cmd.php b/apps/examples/wgetjson/webserver/wgetjson/json_cmd.php new file mode 100644 index 0000000000..2b66ff18f3 --- /dev/null +++ b/apps/examples/wgetjson/webserver/wgetjson/json_cmd.php @@ -0,0 +1,13 @@ + \ No newline at end of file diff --git a/apps/examples/wgetjson/wgetjson_main.c b/apps/examples/wgetjson/wgetjson_main.c new file mode 100644 index 0000000000..7f3096797a --- /dev/null +++ b/apps/examples/wgetjson/wgetjson_main.c @@ -0,0 +1,305 @@ +/**************************************************************************** + * examples/wgetjson/wgetjson_main.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: 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 +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#ifndef CONFIG_EXAMPLES_WGETJSON_MAXSIZE +# define CONFIG_EXAMPLES_WGETJSON_MAXSIZE 1024*10 +#endif + +#ifndef CONFIG_EXAMPLES_EXAMPLES_WGETJSON_URL +# define CONFIG_EXAMPLES_EXAMPLES_WGETJSON_URL "http://10.0.0.1/wgetjson/json_cmd.php" +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static char *g_json_buff = NULL; +static int g_json_bufflen = 0; +static bool g_has_json = false; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: wgetjson_callback + ****************************************************************************/ + +static void wgetjson_callback(FAR char **buffer, int offset, int datend, + FAR int *buflen, FAR void *arg) +{ + int len = datend - offset,org=len; + + if (len <= 0) + { + return; + } + + if (!g_json_buff) + { + g_json_buff = malloc(len + 1); + memcpy(g_json_buff, &((*buffer)[offset]), len); + g_json_buff[len] = 0; + g_json_bufflen = len; + } + else + { + if (g_json_bufflen >= CONFIG_EXAMPLES_WGETJSON_MAXSIZE) + { + g_json_bufflen += org; + return; + } + + if (g_json_bufflen+len > CONFIG_EXAMPLES_WGETJSON_MAXSIZE) + { + len = CONFIG_EXAMPLES_WGETJSON_MAXSIZE - g_json_bufflen; + } + + g_json_buff = realloc(g_json_buff, g_json_bufflen + len + 1); + memcpy(&g_json_buff[g_json_bufflen-1], &((*buffer)[offset]), len); + g_json_buff[g_json_bufflen + len] = 0; + g_json_bufflen += org; + } +} + +/**************************************************************************** + * Name: wgetjson_json_release + ****************************************************************************/ + +static void wgetjson_json_release(void) +{ + if (g_json_buff) + { + free(g_json_buff); + g_json_buff = NULL; + } + + g_json_bufflen = 0; +} + +/**************************************************************************** + * Name: wgetjson_doit + ****************************************************************************/ + +#if 0 /* Not used */ +static void wgetjson_doit(char *text) +{ + char *out; + cJSON *json; + + json = cJSON_Parse(text); + if (!json) + { + printf("Error before: [%s]\n",cJSON_GetErrorPtr()); + } + else + { + out = cJSON_Print(json); + cJSON_Delete(json); + printf("%s\n", out); + free(out); + } +} +#endif + +/**************************************************************************** + * Name: wgetjson_json_item_callback + ****************************************************************************/ + +static int wgetjson_json_item_callback(const char *name,int type,cJSON *item) +{ + if (strlen(name) > 8 && !memcmp(name, "/(null)", 7)) + { + name += 8; + g_has_json = true; + } + + if (!strcmp(name, "name")) + { + printf("name:\t\t\t%s \n", item->valuestring); + // todo something.... + } + else if (strcmp(name, "format/type")==0) + { + printf("format/type:\t\t%s \n", item->valuestring); + // todo something.... + } + else if (!strcmp(name, "format/width")) + { + printf("format/width:\t\t%d \n", item->valueint); + // todo something.... + } + else if (!strcmp(name, "format/height")) + { + printf("format/height:\t\t%d \n", item->valueint); + // todo something.... + } + else if (!strcmp(name, "format/interlace")) + { + printf("format/interlace:\t%s \n", (item->valueint) ? "true" : "false"); + // todo something.... + } + else if (!strcmp(name, "format/frame rate")) + { + printf("format/frame rate:\t%d \n", item->valueint); + // todo something.... + } + + return 1; +} + +/**************************************************************************** + * Name: wgetjson_json_item_scan + ****************************************************************************/ + +static void wgetjson_json_item_scan(cJSON *item, const char *prefix) +{ + char *newprefix; + int dorecurse; + + while (item) + { + newprefix = malloc(strlen(prefix) + strlen(item->string) + 2); + sprintf(newprefix, "%s/%s", prefix, item->string); + + dorecurse = wgetjson_json_item_callback(newprefix, item->type, item); + if (item->child && dorecurse) + { + wgetjson_json_item_scan(item->child, newprefix); + } + + item = item->next; + free(newprefix); + } +} + +/**************************************************************************** + * Name: wgetjson_json_parse + ****************************************************************************/ + +static int wgetjson_json_parse(char *text) +{ + cJSON *json; + char *path = ""; + + json=cJSON_Parse(text); + if (!json) + { + printf("Error before: [%s]\n", cJSON_GetErrorPtr()); + return ERROR; + } + else + { + wgetjson_json_item_scan(json, path); + cJSON_Delete(json); + return OK; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: wgetjson_main + ****************************************************************************/ + +int wgetjson_main(int argc, char *argv[]) +{ + char *buffer = NULL; + char *url = CONFIG_EXAMPLES_EXAMPLES_WGETJSON_URL; + int ret; + + buffer = malloc(512); + wgetjson_json_release(); + + printf("URL: %s\n", url); + + ret = wget(url, buffer, 512, wgetjson_callback, NULL); + if (ret < 0) + { + printf("get json size: %d\n",g_json_bufflen); + } + else + { + g_has_json = false; + if (wgetjson_json_parse(g_json_buff) == OK && g_has_json) + { + printf("Parse OK\n"); + } + else + { + printf("Parse error\n"); + } + + g_has_json = false; + } + + wgetjson_json_release(); + free(buffer); + return 0; +} diff --git a/apps/netutils/codecs/md5.c b/apps/netutils/codecs/md5.c index da25d14b15..bf0394b9d5 100644 --- a/apps/netutils/codecs/md5.c +++ b/apps/netutils/codecs/md5.c @@ -60,6 +60,8 @@ #include +#include +#include #include #include @@ -392,7 +394,7 @@ char *md5_hash(const uint8_t * addr, const size_t len) md5_sum(addr, len, digest); for (i = 0; i < 16; i++) { - vsprintf(&hash[i * 2], "%.2x", digest[i]); + sprintf(&hash[i * 2], "%.2x", digest[i]); } hash[32] = 0; diff --git a/apps/netutils/json/cJSON.c b/apps/netutils/json/cJSON.c index 85091c9487..e5120ec429 100644 --- a/apps/netutils/json/cJSON.c +++ b/apps/netutils/json/cJSON.c @@ -1382,7 +1382,7 @@ void cJSON_ReplaceItemInObject(cJSON *object, const char *string, cJSON *newitem /* Create basic types: */ -cJSON *cJSON_CreateNull() +cJSON *cJSON_CreateNull(void) { cJSON *item = cJSON_New_Item(); if (item) @@ -1393,7 +1393,7 @@ cJSON *cJSON_CreateNull() return item; } -cJSON *cJSON_CreateTrue() +cJSON *cJSON_CreateTrue(void) { cJSON *item = cJSON_New_Item(); if (item) @@ -1404,7 +1404,7 @@ cJSON *cJSON_CreateTrue() return item; } -cJSON *cJSON_CreateFalse() +cJSON *cJSON_CreateFalse(void) { cJSON *item = cJSON_New_Item(); if (item) @@ -1451,7 +1451,7 @@ cJSON *cJSON_CreateString(const char *string) return item; } -cJSON *cJSON_CreateArray() +cJSON *cJSON_CreateArray(void) { cJSON *item = cJSON_New_Item(); if (item) @@ -1462,7 +1462,7 @@ cJSON *cJSON_CreateArray() return item; } -cJSON *cJSON_CreateObject() +cJSON *cJSON_CreateObject(void) { cJSON *item = cJSON_New_Item(); if (item) From a74dd084927e6e7d5f44fcb54216098143cf38e1 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 31 Oct 2012 17:53:28 +0000 Subject: [PATCH 051/206] Documentation update git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5282 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/wgetjson/Kconfig | 2 +- apps/examples/wgetjson/wgetjson_main.c | 2 +- apps/nshlib/README.txt | 10 +- nuttx/Documentation/NuttShell.html | 299 ++++++++++++++++++------- 4 files changed, 230 insertions(+), 83 deletions(-) diff --git a/apps/examples/wgetjson/Kconfig b/apps/examples/wgetjson/Kconfig index 2e3b4b3eb7..f7f4f236cf 100644 --- a/apps/examples/wgetjson/Kconfig +++ b/apps/examples/wgetjson/Kconfig @@ -14,7 +14,7 @@ if EXAMPLES_WGETJSON config EXAMPLES_WGETJSON_MAXSIZE int "Max. JSON Buffer Size" - default 10240 + default 1024 config EXAMPLES_WGETJSON_URL string "wget URL" diff --git a/apps/examples/wgetjson/wgetjson_main.c b/apps/examples/wgetjson/wgetjson_main.c index 7f3096797a..a137af438c 100644 --- a/apps/examples/wgetjson/wgetjson_main.c +++ b/apps/examples/wgetjson/wgetjson_main.c @@ -58,7 +58,7 @@ ****************************************************************************/ #ifndef CONFIG_EXAMPLES_WGETJSON_MAXSIZE -# define CONFIG_EXAMPLES_WGETJSON_MAXSIZE 1024*10 +# define CONFIG_EXAMPLES_WGETJSON_MAXSIZE 1024 #endif #ifndef CONFIG_EXAMPLES_EXAMPLES_WGETJSON_URL diff --git a/apps/nshlib/README.txt b/apps/nshlib/README.txt index 043db2ae9e..9f371678ee 100644 --- a/apps/nshlib/README.txt +++ b/apps/nshlib/README.txt @@ -235,6 +235,10 @@ o test integer -gt integer | integer -le integer | integer -lt integer | integer -ne integer +o base64dec [-w] [-f] + +o base64dec [-w] [-f] + o cat [ [ ...]] This command copies and concatentates all of the files at @@ -257,10 +261,6 @@ o cd [|-|~|..] 'home' directory is '/'. 'cd ..' sets the current working directory to the parent directory. -o base64dec [-w] [-f] - -o base64dec [-w] [-f] - o cp Copy of the contents of the file at to the location @@ -874,6 +874,8 @@ Command Dependencies on Configuration Settings test !CONFIG_NSH_DISABLESCRIPT umount !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_FS_READABLE unset !CONFIG_DISABLE_ENVIRON + urldecode CONFIG_NETUTILS_CODECS && CONFIG_CODECS_URLCODE + urlencode CONFIG_NETUTILS_CODECS && CONFIG_CODECS_URLCODE usleep !CONFIG_DISABLE_SIGNALS get CONFIG_NET && CONFIG_NET_TCP && CONFIG_NFILE_DESCRIPTORS > 0 xd --- diff --git a/nuttx/Documentation/NuttShell.html b/nuttx/Documentation/NuttShell.html index 78a5651074..f8ef41fb96 100644 --- a/nuttx/Documentation/NuttShell.html +++ b/nuttx/Documentation/NuttShell.html @@ -8,7 +8,7 @@

    NuttShell (NSH)

    -

    Last Updated: October 20, 2012

    +

    Last Updated: October 31, 2012

    @@ -89,229 +89,259 @@
    - 2.2 Concatenate Files (cat) + 2.2 Base64 Decode (base64dec)
    - 2.3 Change Current Working Directory (cd) + 2.3 Base64 Encode (base64enc)
    - 2.4 Copy Files (cp) + 2.4 Concatenate Files (cat)
    - 2.5 Show or set the date and time (date) + 2.5 Change Current Working Directory (cd)
    - 2.6 Copy and Convert Files (dd) + 2.6 Copy Files (cp)
    - 2.7 Show volume status (df) + 2.7 Show or set the date and time (date)
    - 2.8 Echo Strings and Variables (echo) + 2.8 Copy and Convert Files (dd)
    - 2.9 Execute User Code (exec) + 2.9 Show volume status (df)
    - 2.10 Exit NSH (exit) + 2.10 Echo Strings and Variables (echo)
    - 2.11 Show Memory Manager Status (free) + 2.11 Execute User Code (exec)
    - 2.12 Get File Via TFTP (get) + 2.12 Exit NSH (exit)
    - 2.13 Show Usage Command Usage (help) + 2.13 Show Memory Manager Status (free)
    - 2.14 Show Network Configuration (ifconfig) + 2.14 Get File Via TFTP (get)
    - 2.15 Send a signal to a task (kill) + 2.15 Show Usage Command Usage (help)
    - 2.16 Setup/teardown the Loop Device (losetup) + 2.16 Show Network Configuration (ifconfig)
    - 2.17 List Directory Contents (ls) + 2.17 Send a signal to a task (kill)
    - 2.18 Access Memory (mb, mh, and mw) + 2.18 Setup/teardown the Loop Device (losetup)
    - 2.19 Show Current Tasks and Threads (ps) + 2.19 List Directory Contents (ls)
    - 2.20 Create a Directory (mkdir) + 2.20 Calculate MD5 (md5)
    - 2.21 Create a FAT Filesystem (mkfatfs) + 2.21 Access Memory (mb, mh, and mw)
    - 2.22 Create a FIFO (mkfifo) + 2.22 Show Current Tasks and Threads (ps)
    - 2.23 Create a RAMDISK (mkrd) + 2.23 Create a Directory (mkdir)
    - 2.24 Mount a File System (mount) + 2.24 Create a FAT Filesystem (mkfatfs)
    - 2.25 Rename a File (mv) + 2.25 Create a FIFO (mkfifo)
    - 2.26 Mount an NFS file system (nfsmount) + 2.26 Create a RAMDISK (mkrd)
    - 2.27 Check Network Peer (ping) + 2.27 Mount a File System (mount)
    - 2.28 Send File Via TFTP (put) + 2.28 Rename a File (mv)
    - 2.29 Show Current Working Directory (pwd) + 2.29 Mount an NFS file system (nfsmount)
    - 2.30 Remove a File (rm) + 2.30 Check Network Peer (ping)
    - 2.31 Remove a Directory (rmdir) + 2.31 Send File Via TFTP (put)
    - 2.32 Set an Environment Variable (set) + 2.32 Show Current Working Directory (pwd)
    - 2.33 Execute an NSH Script (sh) + 2.33 Remove a File (rm)
    - 2.34 Wait for Seconds (sleep) + 2.34 Remove a Directory (rmdir)
    - 2.35 Unmount a File System (umount) + 2.35 Set an Environment Variable (set)
    - 2.36 Unset an Environment Variable (unset) + 2.36 Execute an NSH Script (sh)
    - 2.37 Wait for Microseconds (usleep) + 2.37 Wait for Seconds (sleep)
    - 2.38 Get File Via HTTP (wget) + 2.38 Unmount a File System (umount)
    - 2.39 Hexadecimal Dump (xd) + 2.39 Unset an Environment Variable (unset) + + + +
    + + 2.40 URL Decode (urldecode) + + + +
    + + 2.41 URL Encode (urlencode) + + + +
    + + 2.42 Wait for Microseconds (usleep) + + + +
    + + 2.43 Get File Via HTTP (wget) + + + +
    + + 2.44 Hexadecimal Dump (xd) @@ -750,7 +780,41 @@ test <expression> + +
    -

    2.2 Concatenate Files (cat)

    +

    2.2 Base64 Decode (base64dec)

    +
    + +

    Command Syntax:

    +
      +base64dec [-w] [-f] <string or filepath>
      +
    +

    + Synopsis. + To be provided. +

    + + + + + +
    +

    2.3 Base64 Encode (base64enc)

    +
    + +

    Command Syntax:

    +
      +base64enc [-w] [-f] <string or filepath>
      +
    +

    + Synopsis. + To be provided. +

    + + + +
    +

    2.4 Concatenate Files (cat)

    @@ -768,7 +832,7 @@ cat <path> [<path> [<path> -

    2.3 Change Current Working Directory (cd)

    +

    2.5 Change Current Working Directory (cd)

    @@ -810,7 +874,7 @@ cd [<dir-path>|-|~|..]
    -

    2.4 Copy Files (cp)

    +

    2.6 Copy Files (cp)

    @@ -828,7 +892,7 @@ cp <source-path> <dest-path>
    -

    2.5 Show or set the date and time (date)

    +

    2.7 Show or set the date and time (date)

    @@ -855,7 +919,7 @@ data -s "Sep 1 11:30:00 2011"
    -

    2.6 Copy and Convert Files (dd)

    +

    2.8 Copy and Convert Files (dd)

    @@ -913,7 +977,7 @@ nsh> dd if=/dev/ram0 of=/dev/null
    -

    2.7 Show Volument Status (df)

    +

    2.9 Show Volument Status (df)

    @@ -941,7 +1005,7 @@ nsh>
    -

    2.8 Echo Strings and Variables (echo)

    +

    2.10 Echo Strings and Variables (echo)

    @@ -959,7 +1023,7 @@ echo [<string|$name> [<string|$name>...]]
    -

    2.9 Execute User Code (exec)

    +

    2.11 Execute User Code (exec)

    @@ -978,7 +1042,7 @@ exec <hex-address>
    -

    2.10 Exit NSH (exit)

    +

    2.12 Exit NSH (exit)

    @@ -997,7 +1061,7 @@ exit
    -

    2.11 Show Memory Manager Status (free)

    +

    2.13 Show Memory Manager Status (free)

    @@ -1039,7 +1103,7 @@ nsh>
    -

    2.12 Get File Via TFTP (get)

    +

    2.14 Get File Via TFTP (get)

    @@ -1074,7 +1138,7 @@ get [-b|-n] [-f <local-path>] -h <ip-address> <remote-path>
    -

    2.13 Show Usage Command Usage (help)

    +

    2.15 Show Usage Command Usage (help)

    @@ -1106,7 +1170,7 @@ help [-v] [<cmd>]
    -

    2.14 Show Network Configuration (ifconfig)

    +

    2.16 Show Network Configuration (ifconfig)

    @@ -1157,7 +1221,7 @@ ifconfig nic_name ip_address
    -

    2.15 Send a signal to a task (kill)

    +

    2.17 Send a signal to a task (kill)

    @@ -1198,7 +1262,7 @@ nsh>
    -

    2.16 Setup/teardown the Loop Device (losetup)

    +

    2.18 Setup/teardown the Loop Device (losetup)

    @@ -1251,7 +1315,7 @@ losetup d <dev-path>
    -

    2.17 List Directory Contents (ls)

    +

    2.19 List Directory Contents (ls)

    @@ -1288,7 +1352,24 @@ ls [-lRs] <dir-path> + +
    -

    2.18 Access Memory (mb, mh, and mw)

    +

    2.20 Calculate MD5 (md5)

    +
    + +

    Command Syntax:

    +
      +md5 [-f] <string or filepath>
      +
    +

    + Synopsis. + To be provided. +

    + + + +
    +

    2.21 Access Memory (mb, mh, and mw)

    @@ -1342,7 +1423,7 @@ nsh>
    -

    2.19 Show Current Tasks and Threads (ps)

    +

    2.22 Show Current Tasks and Threads (ps)

    @@ -1368,7 +1449,7 @@ nsh>
    -

    2.20 Create a Directory (mkdir)

    +

    2.23 Create a Directory (mkdir)

    @@ -1403,7 +1484,7 @@ nsh>
    -

    2.21 Create a FAT Filesystem (mkfatfs)

    +

    2.24 Create a FAT Filesystem (mkfatfs)

    @@ -1423,7 +1504,7 @@ mkfatfs <path>
    -

    2.22 Create a FIFO (mkfifo)

    +

    2.25 Create a FIFO (mkfifo)

    @@ -1461,7 +1542,7 @@ nsh>
    -

    2.23 Create a RAMDISK (mkrd)

    +

    2.26 Create a RAMDISK (mkrd)

    @@ -1512,7 +1593,7 @@ nsh>
    -

    2.24 Mount a File System (mount)

    +

    2.27 Mount a File System (mount)

    @@ -1591,7 +1672,7 @@ nsh> mount
    -

    2.25 Rename a File (mv)

    +

    2.28 Rename a File (mv)

    @@ -1609,7 +1690,7 @@ mv <old-path> <new-path>
    -

    2.26 Mount an NFS file system (nfsmount)

    +

    2.29 Mount an NFS file system (nfsmount)

    @@ -1628,7 +1709,7 @@ nfsmount <server-address> <mount-point> <remote-path>
    -

    2.27 Check Network Peer (ping)

    +

    2.30 Check Network Peer (ping)

    @@ -1661,7 +1742,7 @@ nsh>
    -

    2.28 Send File Via TFTP (put)

    +

    2.31 Send File Via TFTP (put)

    @@ -1696,7 +1777,7 @@ put [-b|-n] [-f <remote-path>] -h <ip-address> <local-path>
    -

    2.29 Show Current Working Directory (pwd)

    +

    2.32 Show Current Working Directory (pwd)

    @@ -1726,7 +1807,7 @@ nsh>
    -

    2.30 Remove a File (rm)

    +

    2.33 Remove a File (rm)

    @@ -1760,7 +1841,7 @@ nsh>
    -

    2.31 Remove a Directory (rmdir)

    +

    2.34 Remove a Directory (rmdir)

    @@ -1795,7 +1876,7 @@ nsh>
    -

    2.32 Set an Environment Variable (set)

    +

    2.35 Set an Environment Variable (set)

    @@ -1821,7 +1902,7 @@ nsh>
    -

    2.33 Execute an NSH Script (sh)

    +

    2.36 Execute an NSH Script (sh)

    @@ -1839,7 +1920,7 @@ sh <script-path>
    -

    2.34 Wait for Seconds (sleep)

    +

    2.37 Wait for Seconds (sleep)

    @@ -1856,7 +1937,7 @@ sleep <sec>
    -

    2.35 Unmount a File System (umount)

    +

    2.38 Unmount a File System (umount)

    @@ -1886,7 +1967,7 @@ nsh>
    -

    2.36 Unset an Environment Variable (unset)

    +

    2.39 Unset an Environment Variable (unset)

    @@ -1912,7 +1993,41 @@ nsh> + +
    -

    2.37 Wait for Microseconds (usleep)

    +

    2.40 URL Decode (urldecode)

    +
    + +

    Command Syntax:

    +
      +urldecode [-f] <string or filepath>
      +
    +

    + Synopsis. + To be provided. +

    + + + + + +
    +

    2.41 URL Encode (urlencode)

    +
    + +

    Command Syntax:

    +
      +urlencode [-f] <string or filepath>
      +
    +

    + Synopsis. + To be provided. +

    + + + +
    +

    2.42 Wait for Microseconds (usleep)

    @@ -1929,7 +2044,7 @@ usleep <usec>
    - 2.37 Get File Via HTTP (wget) + 2.43 Get File Via HTTP (wget)
    @@ -1956,7 +2071,7 @@ wget [-o <local-path>] <url>
    -

    2.38 Hexadecimal dump (xd)

    +

    2.44 Hexadecimal dump (xd)

    @@ -2024,6 +2139,16 @@ nsh> !CONFIG_NSH_DISABLESCRIPT CONFIG_NSH_DISABLE_TEST + + base64dec + CONFIG_NETUTILS_CODECS && CONFIG_CODECS_BASE64 + CONFIG_NSH_DISABLE_BASE64DEC + + + base64enc + CONFIG_NETUTILS_CODECS && CONFIG_CODECS_BASE64 + CONFIG_NSH_DISABLE_BASE64ENC + cat CONFIG_NFILE_DESCRIPTORS > 0 @@ -2105,6 +2230,11 @@ nsh> CONFIG_NFILE_DESCRIPTORS > 0 CONFIG_NSH_DISABLE_LS + + md5 + CONFIG_NETUTILS_CODECS && CONFIG_CODECS_HASH_MD5 + CONFIG_NSH_DISABLE_MD5 + mb,mh,mw
    @@ -2212,6 +2342,16 @@ nsh> !CONFIG_DISABLE_ENVIRON CONFIG_NSH_DISABLE_UNSET + + urldecode + !CONFIG_NETUTILS_CODECS && CONFIG_CODECS_URLCODE + CONFIG_NSH_DISABLE_URLDECODE + + + urlencode + !CONFIG_NETUTILS_CODECS && CONFIG_CODECS_URLCODE + CONFIG_NSH_DISABLE_URLENCODE + usleep !CONFIG_DISABLE_SIGNALS @@ -3517,6 +3657,8 @@ mount -t vfat /dev/ram1 /tmp
  • binfs
  • Built-In applications
  • Built-in variables
  • +
  • base64dec
  • +
  • base64enc
  • cat
  • cd
  • Command summaries
  • @@ -3597,6 +3739,7 @@ mount -t vfat /dev/ram1 /tmp
  • losetup
  • ls
  • mb
  • +
  • md5
  • mh
  • mw
  • mkdir
  • @@ -3652,6 +3795,8 @@ mount -t vfat /dev/ram1 /tmp
  • unset
  • up_cxxinitialize()
  • up_nsh.c
  • +
  • urldecode
  • +
  • urlencode
  • usleep
  • waitpid()
  • wget
  • From 66aae459f14ce34b1735c17d13ba56fe8f885fb1 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 31 Oct 2012 19:13:18 +0000 Subject: [PATCH 052/206] Add misc/uClibc++ and build hooks in nuttx/ git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5283 42af7a65-404d-4744-a932-0658087f49c3 --- misc/uClibc++/include/cxx/Makefile | 13 + misc/uClibc++/include/cxx/algorithm | 1695 +++++++++++++++++ misc/uClibc++/include/cxx/associative_base | 640 +++++++ misc/uClibc++/include/cxx/basic_definitions | 66 + misc/uClibc++/include/cxx/bitset | 423 ++++ misc/uClibc++/include/cxx/cfloat | 30 + misc/uClibc++/include/cxx/char_traits | 215 +++ misc/uClibc++/include/cxx/clocale | 30 + misc/uClibc++/include/cxx/complex | 327 ++++ misc/uClibc++/include/cxx/csetjmp | 44 + misc/uClibc++/include/cxx/cwchar | 86 + misc/uClibc++/include/cxx/cwctype | 106 ++ misc/uClibc++/include/cxx/deque | 884 +++++++++ misc/uClibc++/include/cxx/exception | 120 ++ misc/uClibc++/include/cxx/fstream | 676 +++++++ misc/uClibc++/include/cxx/func_exception | 41 + misc/uClibc++/include/cxx/functional | 439 +++++ misc/uClibc++/include/cxx/iomanip | 170 ++ misc/uClibc++/include/cxx/ios | 500 +++++ misc/uClibc++/include/cxx/iosfwd | 114 ++ misc/uClibc++/include/cxx/iostream | 101 + misc/uClibc++/include/cxx/istream | 599 ++++++ misc/uClibc++/include/cxx/istream_helpers | 374 ++++ misc/uClibc++/include/cxx/iterator | 229 +++ misc/uClibc++/include/cxx/iterator_base | 305 +++ misc/uClibc++/include/cxx/limits | 663 +++++++ misc/uClibc++/include/cxx/list | 926 +++++++++ misc/uClibc++/include/cxx/locale | 83 + misc/uClibc++/include/cxx/map | 264 +++ misc/uClibc++/include/cxx/memory | 196 ++ misc/uClibc++/include/cxx/new | 64 + misc/uClibc++/include/cxx/numeric | 161 ++ misc/uClibc++/include/cxx/ostream | 510 +++++ misc/uClibc++/include/cxx/ostream_helpers | 491 +++++ misc/uClibc++/include/cxx/queue | 126 ++ misc/uClibc++/include/cxx/set | 406 ++++ misc/uClibc++/include/cxx/sstream | 384 ++++ misc/uClibc++/include/cxx/stack | 84 + misc/uClibc++/include/cxx/stdexcept | 117 ++ misc/uClibc++/include/cxx/streambuf | 329 ++++ misc/uClibc++/include/cxx/string | 1042 ++++++++++ misc/uClibc++/include/cxx/string_iostream | 146 ++ misc/uClibc++/include/cxx/support | 165 ++ .../include/cxx/system_configuration.h | 48 + misc/uClibc++/include/cxx/type_traits | 92 + misc/uClibc++/include/cxx/typeinfo | 156 ++ misc/uClibc++/include/cxx/unwind-cxx.h | 213 +++ misc/uClibc++/include/cxx/utility | 88 + misc/uClibc++/include/cxx/valarray | 1042 ++++++++++ misc/uClibc++/include/cxx/vector | 517 +++++ misc/uClibc++/include/features.h | 451 +++++ misc/uClibc++/install.sh | 312 +++ misc/uClibc++/libxx/uClib++/Make.defs | 52 + misc/uClibc++/libxx/uClib++/algorithm.cxx | 30 + .../libxx/uClib++/associative_base.cxx | 26 + misc/uClibc++/libxx/uClib++/bitset.cxx | 26 + misc/uClibc++/libxx/uClib++/char_traits.cxx | 69 + misc/uClibc++/libxx/uClib++/complex.cxx | 28 + misc/uClibc++/libxx/uClib++/del_op.cxx | 26 + misc/uClibc++/libxx/uClib++/del_opnt.cxx | 28 + misc/uClibc++/libxx/uClib++/del_opv.cxx | 26 + misc/uClibc++/libxx/uClib++/del_opvnt.cxx | 28 + misc/uClibc++/libxx/uClib++/deque.cxx | 42 + misc/uClibc++/libxx/uClib++/eh_alloc.cxx | 61 + misc/uClibc++/libxx/uClib++/eh_globals.cxx | 42 + misc/uClibc++/libxx/uClib++/exception.cxx | 52 + misc/uClibc++/libxx/uClib++/fstream.cxx | 174 ++ .../uClibc++/libxx/uClib++/func_exception.cxx | 87 + misc/uClibc++/libxx/uClib++/iomanip.cxx | 29 + misc/uClibc++/libxx/uClib++/ios.cxx | 189 ++ misc/uClibc++/libxx/uClib++/iostream.cxx | 38 + misc/uClibc++/libxx/uClib++/istream.cxx | 75 + misc/uClibc++/libxx/uClib++/iterator.cxx | 28 + misc/uClibc++/libxx/uClib++/limits.cxx | 25 + misc/uClibc++/libxx/uClib++/list.cxx | 29 + misc/uClibc++/libxx/uClib++/locale.cxx | 29 + misc/uClibc++/libxx/uClib++/map.cxx | 33 + misc/uClibc++/libxx/uClib++/new_handler.cxx | 31 + misc/uClibc++/libxx/uClib++/new_op.cxx | 35 + misc/uClibc++/libxx/uClib++/new_opnt.cxx | 28 + misc/uClibc++/libxx/uClib++/new_opv.cxx | 35 + misc/uClibc++/libxx/uClib++/new_opvnt.cxx | 28 + misc/uClibc++/libxx/uClib++/numeric.cxx | 27 + misc/uClibc++/libxx/uClib++/ostream.cxx | 65 + misc/uClibc++/libxx/uClib++/queue.cxx | 27 + misc/uClibc++/libxx/uClib++/set.cxx | 33 + misc/uClibc++/libxx/uClib++/sstream.cxx | 59 + misc/uClibc++/libxx/uClib++/stack.cxx | 27 + misc/uClibc++/libxx/uClib++/stdexcept.cxx | 63 + misc/uClibc++/libxx/uClib++/streambuf.cxx | 49 + misc/uClibc++/libxx/uClib++/string.cxx | 112 ++ misc/uClibc++/libxx/uClib++/support.cxx | 53 + misc/uClibc++/libxx/uClib++/typeinfo.cxx | 34 + misc/uClibc++/libxx/uClib++/utility.cxx | 30 + misc/uClibc++/libxx/uClib++/valarray.cxx | 29 + misc/uClibc++/libxx/uClib++/vector.cxx | 83 + nuttx/libxx/Makefile | 41 +- 97 files changed, 19452 insertions(+), 12 deletions(-) create mode 100644 misc/uClibc++/include/cxx/Makefile create mode 100644 misc/uClibc++/include/cxx/algorithm create mode 100644 misc/uClibc++/include/cxx/associative_base create mode 100644 misc/uClibc++/include/cxx/basic_definitions create mode 100644 misc/uClibc++/include/cxx/bitset create mode 100644 misc/uClibc++/include/cxx/cfloat create mode 100644 misc/uClibc++/include/cxx/char_traits create mode 100644 misc/uClibc++/include/cxx/clocale create mode 100644 misc/uClibc++/include/cxx/complex create mode 100644 misc/uClibc++/include/cxx/csetjmp create mode 100644 misc/uClibc++/include/cxx/cwchar create mode 100644 misc/uClibc++/include/cxx/cwctype create mode 100644 misc/uClibc++/include/cxx/deque create mode 100644 misc/uClibc++/include/cxx/exception create mode 100644 misc/uClibc++/include/cxx/fstream create mode 100644 misc/uClibc++/include/cxx/func_exception create mode 100644 misc/uClibc++/include/cxx/functional create mode 100644 misc/uClibc++/include/cxx/iomanip create mode 100644 misc/uClibc++/include/cxx/ios create mode 100644 misc/uClibc++/include/cxx/iosfwd create mode 100644 misc/uClibc++/include/cxx/iostream create mode 100644 misc/uClibc++/include/cxx/istream create mode 100644 misc/uClibc++/include/cxx/istream_helpers create mode 100644 misc/uClibc++/include/cxx/iterator create mode 100644 misc/uClibc++/include/cxx/iterator_base create mode 100644 misc/uClibc++/include/cxx/limits create mode 100644 misc/uClibc++/include/cxx/list create mode 100644 misc/uClibc++/include/cxx/locale create mode 100644 misc/uClibc++/include/cxx/map create mode 100644 misc/uClibc++/include/cxx/memory create mode 100644 misc/uClibc++/include/cxx/new create mode 100644 misc/uClibc++/include/cxx/numeric create mode 100644 misc/uClibc++/include/cxx/ostream create mode 100644 misc/uClibc++/include/cxx/ostream_helpers create mode 100644 misc/uClibc++/include/cxx/queue create mode 100644 misc/uClibc++/include/cxx/set create mode 100644 misc/uClibc++/include/cxx/sstream create mode 100644 misc/uClibc++/include/cxx/stack create mode 100644 misc/uClibc++/include/cxx/stdexcept create mode 100644 misc/uClibc++/include/cxx/streambuf create mode 100644 misc/uClibc++/include/cxx/string create mode 100644 misc/uClibc++/include/cxx/string_iostream create mode 100644 misc/uClibc++/include/cxx/support create mode 100644 misc/uClibc++/include/cxx/system_configuration.h create mode 100644 misc/uClibc++/include/cxx/type_traits create mode 100644 misc/uClibc++/include/cxx/typeinfo create mode 100644 misc/uClibc++/include/cxx/unwind-cxx.h create mode 100644 misc/uClibc++/include/cxx/utility create mode 100644 misc/uClibc++/include/cxx/valarray create mode 100644 misc/uClibc++/include/cxx/vector create mode 100644 misc/uClibc++/include/features.h create mode 100755 misc/uClibc++/install.sh create mode 100644 misc/uClibc++/libxx/uClib++/Make.defs create mode 100644 misc/uClibc++/libxx/uClib++/algorithm.cxx create mode 100644 misc/uClibc++/libxx/uClib++/associative_base.cxx create mode 100644 misc/uClibc++/libxx/uClib++/bitset.cxx create mode 100644 misc/uClibc++/libxx/uClib++/char_traits.cxx create mode 100644 misc/uClibc++/libxx/uClib++/complex.cxx create mode 100644 misc/uClibc++/libxx/uClib++/del_op.cxx create mode 100644 misc/uClibc++/libxx/uClib++/del_opnt.cxx create mode 100644 misc/uClibc++/libxx/uClib++/del_opv.cxx create mode 100644 misc/uClibc++/libxx/uClib++/del_opvnt.cxx create mode 100644 misc/uClibc++/libxx/uClib++/deque.cxx create mode 100644 misc/uClibc++/libxx/uClib++/eh_alloc.cxx create mode 100644 misc/uClibc++/libxx/uClib++/eh_globals.cxx create mode 100644 misc/uClibc++/libxx/uClib++/exception.cxx create mode 100644 misc/uClibc++/libxx/uClib++/fstream.cxx create mode 100644 misc/uClibc++/libxx/uClib++/func_exception.cxx create mode 100644 misc/uClibc++/libxx/uClib++/iomanip.cxx create mode 100644 misc/uClibc++/libxx/uClib++/ios.cxx create mode 100644 misc/uClibc++/libxx/uClib++/iostream.cxx create mode 100644 misc/uClibc++/libxx/uClib++/istream.cxx create mode 100644 misc/uClibc++/libxx/uClib++/iterator.cxx create mode 100644 misc/uClibc++/libxx/uClib++/limits.cxx create mode 100644 misc/uClibc++/libxx/uClib++/list.cxx create mode 100644 misc/uClibc++/libxx/uClib++/locale.cxx create mode 100644 misc/uClibc++/libxx/uClib++/map.cxx create mode 100644 misc/uClibc++/libxx/uClib++/new_handler.cxx create mode 100644 misc/uClibc++/libxx/uClib++/new_op.cxx create mode 100644 misc/uClibc++/libxx/uClib++/new_opnt.cxx create mode 100644 misc/uClibc++/libxx/uClib++/new_opv.cxx create mode 100644 misc/uClibc++/libxx/uClib++/new_opvnt.cxx create mode 100644 misc/uClibc++/libxx/uClib++/numeric.cxx create mode 100644 misc/uClibc++/libxx/uClib++/ostream.cxx create mode 100644 misc/uClibc++/libxx/uClib++/queue.cxx create mode 100644 misc/uClibc++/libxx/uClib++/set.cxx create mode 100644 misc/uClibc++/libxx/uClib++/sstream.cxx create mode 100644 misc/uClibc++/libxx/uClib++/stack.cxx create mode 100644 misc/uClibc++/libxx/uClib++/stdexcept.cxx create mode 100644 misc/uClibc++/libxx/uClib++/streambuf.cxx create mode 100644 misc/uClibc++/libxx/uClib++/string.cxx create mode 100644 misc/uClibc++/libxx/uClib++/support.cxx create mode 100644 misc/uClibc++/libxx/uClib++/typeinfo.cxx create mode 100644 misc/uClibc++/libxx/uClib++/utility.cxx create mode 100644 misc/uClibc++/libxx/uClib++/valarray.cxx create mode 100644 misc/uClibc++/libxx/uClib++/vector.cxx diff --git a/misc/uClibc++/include/cxx/Makefile b/misc/uClibc++/include/cxx/Makefile new file mode 100644 index 0000000000..b5c2694da8 --- /dev/null +++ b/misc/uClibc++/include/cxx/Makefile @@ -0,0 +1,13 @@ +TOPDIR=../ +include $(TOPDIR)Rules.mak + +all: + +clean: + +distclean: + +HEADERS = $(filter-out .svn CVS Makefile,$(wildcard *)) +install: + $(INSTALL) -d $(PREFIX)$(UCLIBCXX_RUNTIME_INCLUDEDIR) + $(INSTALL) -m 644 $(HEADERS) $(PREFIX)$(UCLIBCXX_RUNTIME_INCLUDEDIR) diff --git a/misc/uClibc++/include/cxx/algorithm b/misc/uClibc++/include/cxx/algorithm new file mode 100644 index 0000000000..5e8f139c06 --- /dev/null +++ b/misc/uClibc++/include/cxx/algorithm @@ -0,0 +1,1695 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include + +#ifndef __STD_HEADER_ALGORITHM +#define __STD_HEADER_ALGORITHM 1 + +//Elliminate any previously defined macro +#undef min +#undef max + +#pragma GCC visibility push(default) + +namespace std{ + + // subclause _lib.alg.nonmodifying_, non-modifying sequence operations: + template _UCXXEXPORT + Function for_each(InputIterator first, InputIterator last, Function f) + { + while(first !=last){ + f(*first); + ++first; + } + return f; + } + + + template _UCXXEXPORT + InputIterator find(InputIterator first, InputIterator last, const T& value) + { + while(first !=last && *first != value){ + ++first; + } + return first; + } + + template _UCXXEXPORT + InputIterator find_if(InputIterator first, InputIterator last, Predicate pred) + { + while(first !=last && !pred(*first)){ + ++first; + } + return first; + } + + template _UCXXEXPORT ForwardIterator1 + find_end(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2) + { + ForwardIterator1 retval = last1; + while(first1 !=last1){ + ForwardIterator1 temp1(first1); + ForwardIterator2 temp2(first2); + while(temp2!=last2 && temp1!= last1){ + if(*temp1 != *temp2){ + break; //Exit while loop + } + ++temp1; + ++temp2; + if(temp2 == last2){ //Have successfully checked the whole sequence + retval = first1; + } + } + } + return retval; + } + + template _UCXXEXPORT + ForwardIterator1 + find_end(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2, + BinaryPredicate pred) + { + ForwardIterator1 retval = last1; + while(first1 !=last1){ + ForwardIterator1 temp1(first1); + ForwardIterator2 temp2(first2); + while(temp2!=last2 && temp1!= last1){ + if( ! pred(*temp1, *temp2)){ + break; //Exit while loop + } + ++temp1; + ++temp2; + if(temp2 == last2){ //Have successfully checked the whole sequence + retval = first1; + } + } + } + return retval; + } + + template _UCXXEXPORT + ForwardIterator1 + find_first_of(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2) + { + while(first1 != last1){ + ForwardIterator2 temp2(first2); + while(temp2 != last2 ){ + if(*temp2 == first1){ + return first1; + } + ++temp2; + } + + } + return last1; + } + + template _UCXXEXPORT + ForwardIterator1 + find_first_of(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2, + BinaryPredicate pred) + { + while(first1 != last1){ + ForwardIterator2 temp2(first2); + while(temp2 != last2 ){ + if(*temp2 == first1){ + return first1; + } + ++temp2; + } + + } + return last1; + } + + template _UCXXEXPORT ForwardIterator + adjacent_find(ForwardIterator first, ForwardIterator last) + { + ForwardIterator temp; + while(first != last){ + temp = first; + ++temp; + if(*temp == *first){ + return first; + } + ++first; + } + return first; + } + + template _UCXXEXPORT + ForwardIterator + adjacent_find(ForwardIterator first, ForwardIterator last, BinaryPredicate pred) + { + ForwardIterator temp; + while(first != last){ + temp = first; + ++temp; + if( pred(*temp, *first)){ + return first; + } + ++first; + } + return first; + } + + template _UCXXEXPORT + typename iterator_traits::difference_type + count(InputIterator first, InputIterator last, const T& value) + { + typename iterator_traits::difference_type i = 0; + while(first!=last){ + if(*first == value){ + ++i; + } + ++first; + } + return i; + } + + template _UCXXEXPORT + typename iterator_traits::difference_type + count_if(InputIterator first, InputIterator last, Predicate pred) + { + typename iterator_traits::difference_type i = 0; + while(first!=last){ + if( pred(*first) ){ + ++i; + } + ++first; + } + return i; + } + + template _UCXXEXPORT + pair + mismatch(InputIterator1 first1, InputIterator1 last1, InputIterator2 first2) + { + while(first1 != last1){ + if(*first1 != *first2){ + break; + } + ++first1; + ++first2; + } + + pair retval; + retval.first = first1; + retval.second = first2; + return retval; + } + + template _UCXXEXPORT + pair + mismatch(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, BinaryPredicate pred) + { + while(first1 != last1){ + if( !pred(*first1, *first2) ){ + break; + } + ++first1; + ++first2; + } + + pair retval; + retval.first = first1; + retval.second = first2; + return retval; + } + + template _UCXXEXPORT + bool + equal(InputIterator1 first1, InputIterator1 last1, InputIterator2 first2) + { + while(first1 !=last1){ + if(*first1 != *first2){ + return false; + } + ++first1; + ++first2; + } + return true; + } + + template _UCXXEXPORT + bool + equal(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, BinaryPredicate pred) + { + while(first1 !=last1){ + if( !pred(*first1, *first2) ){ + return false; + } + ++first1; + ++first2; + } + return true; + } + + template _UCXXEXPORT + ForwardIterator1 search(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2) + { + equal_to::value_type> c; + return search(first1, last1, first2, last2, c); + } + + + template _UCXXEXPORT + ForwardIterator1 + search(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2, + BinaryPredicate pred) + { + while(first1 != last1){ + ForwardIterator1 temp1(first1); + ForwardIterator2 temp2(first2); + while(temp2 != last2 && temp1 != last1){ + if( !pred(*temp2, *temp1) ){ + break; + } + ++temp1; + ++temp2; + if(temp2 == last2){ + return first1; + } + } + ++first1; + } + return last1; + } + + + template _UCXXEXPORT + ForwardIterator + search_n(ForwardIterator first, ForwardIterator last, Size count, const T& value) + { + while( first != last ){ + if(*first == value){ + ForwardIterator temp(first); + Size i = 1; + ++first; //Avoid doing the same comparison over again + while(i < count && *temp == value){ + ++first; + ++i; + } + if(i == count){ + return first; + } + } + ++first; + } + return first; + } + + + template _UCXXEXPORT + ForwardIterator + search_n(ForwardIterator first, ForwardIterator last, + Size count, const T& value, BinaryPredicate pred) + { + while( first != last ){ + if( pred(*first, value) ){ + ForwardIterator temp(first); + Size i = 1; + ++first; //Avoid doing the same comparison over again + while(i < count && pred(*temp, value) ){ + ++first; + ++i; + } + if(i == count){ + return first; + } + } + ++first; + } + return first; + + } + + // subclause _lib.alg.modifying.operations_, modifying sequence operations: + + template _UCXXEXPORT + OutputIterator + copy(InputIterator first, InputIterator last, OutputIterator result) + { + while(first != last){ + *result = *first; + ++first; + ++result; + } + return result; + } + + template _UCXXEXPORT + BidirectionalIterator2 + copy_backward(BidirectionalIterator1 first, BidirectionalIterator1 last, + BidirectionalIterator2 result) + { + while(first !=last ){ + --result; + --last; + *result = *last; + } + return result; + } + + template _UCXXEXPORT void swap(T& a, T& b){ + T temp(a); + a = b; + b = temp; + } + + template _UCXXEXPORT + ForwardIterator2 + swap_ranges(ForwardIterator1 first1, ForwardIterator1 last1, ForwardIterator2 first2) + { + while(first1 != last1){ + iter_swap(first1, first2); + ++first1; + ++first2; + } + return first2; + } + + + template _UCXXEXPORT + void + iter_swap(ForwardIterator1 a, ForwardIterator2 b) + { + typename iterator_traits::value_type temp(*a); + *a = *b; + *b = temp; + } + + + template _UCXXEXPORT + OutputIterator + transform(InputIterator first, InputIterator last, + OutputIterator result, UnaryOperation op) + { + while(first != last){ + *result = op(*first); + ++first; + ++result; + } + return result; + } + + + template _UCXXEXPORT + OutputIterator transform(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, OutputIterator result, + BinaryOperation binary_op) + { + while(first1 != last1){ + *result = binary_op(*first1, *first2); + ++first1; + ++first2; + ++result; + } + return result; + } + + + template _UCXXEXPORT + void + replace(ForwardIterator first, ForwardIterator last, + const T& old_value, const T& new_value) + { + while(first != last){ + if(*first == old_value){ + *first = new_value; + } + ++first; + } + } + + template _UCXXEXPORT + void + replace_if(ForwardIterator first, ForwardIterator last, + Predicate pred, const T& new_value) + { + while(first != last){ + if( pred(*first) ){ + *first = new_value; + } + ++first; + } + } + + + template _UCXXEXPORT + OutputIterator + replace_copy(InputIterator first, InputIterator last, + OutputIterator result, const T& old_value, const T& new_value) + { + while(first != last){ + if(*first == old_value){ + *result = new_value; + }else{ + *result = *first; + } + ++first; + ++result; + } + return result; + } + + template _UCXXEXPORT + OutputIterator + replace_copy_if(Iterator first, Iterator last, + OutputIterator result, Predicate pred, const T& new_value) + { + while(first != last){ + if( pred(*first) ){ + *result = new_value; + }else{ + *result = *first; + } + ++first; + ++result; + } + return result; + } + + template _UCXXEXPORT + void + fill(ForwardIterator first, ForwardIterator last, const T& value) + { + while(first != last){ + *first = value; + ++first; + } + } + + template _UCXXEXPORT + void + fill_n(OutputIterator first, Size n, const T& value) + { + while(n != 0){ + *first = value; + --n; + ++first; + } + } + + template _UCXXEXPORT + void + generate(ForwardIterator first, ForwardIterator last, Generator gen) + { + while(first != last){ + *first = gen(); + ++first; + } + } + + template _UCXXEXPORT + void + generate_n(OutputIterator first, Size n, Generator gen) + { + while(n !=0){ + *first = gen(); + --n; + ++first; + } + } + + template _UCXXEXPORT + ForwardIterator + remove(ForwardIterator first, ForwardIterator last, const T& value) + { + ForwardIterator temp(first); + while(temp !=last){ + if(*temp == value){ + + }else{ + *first = *temp; + ++first; + } + ++temp; + } + return first; + } + + template _UCXXEXPORT + ForwardIterator + remove_if(ForwardIterator first, ForwardIterator last, Predicate pred) + { + ForwardIterator temp(first); + while(temp !=last){ + if( pred(*temp) ){ + + }else{ + *first = *temp; + ++first; + } + ++temp; + } + return first; + } + + + template _UCXXEXPORT + OutputIterator + remove_copy(InputIterator first, InputIterator last, + OutputIterator result, const T& value) + { + while(first !=last){ + if(*first != value){ + *result = *first; + ++result; + } + ++first; + } + return result; + } + + template _UCXXEXPORT + OutputIterator + remove_copy_if(InputIterator first, InputIterator last, + OutputIterator result, Predicate pred) + { + while(first !=last){ + if( !pred(*first) ){ + *result = *first; + ++result; + } + ++first; + } + return result; + } + + template _UCXXEXPORT + ForwardIterator + unique(ForwardIterator first, ForwardIterator last) + { + ForwardIterator new_val(first); + ForwardIterator old_val(first); + + while(new_val !=last){ + if(*new_val == *old_val && new_val != old_val){ + + }else{ + *first = *new_val; + old_val = new_val; + ++first; + } + ++new_val; + } + return first; + } + + template _UCXXEXPORT + ForwardIterator + unique(ForwardIterator first, ForwardIterator last, BinaryPredicate pred) + { + ForwardIterator new_val(first); + ForwardIterator old_val(first); + + while(new_val !=last){ + if( pred(*new_val, *old_val) && new_val != old_val){ + + }else{ + *first = *new_val; + old_val = new_val; + ++first; + } + ++new_val; + } + return first; + } + + template _UCXXEXPORT + OutputIterator + unique_copy(InputIterator first, InputIterator last, OutputIterator result) + { + InputIterator temp(first); + while(first !=last ){ + if(*first == *temp && first != temp){ + + }else{ + *result = *first; + temp = first; + ++result; + } + ++first; + } + return result; + } + + template _UCXXEXPORT + OutputIterator + unique_copy(InputIterator first, InputIterator last, + OutputIterator result, BinaryPredicate pred) + { + InputIterator temp(first); + while(first !=last ){ + if( pred(*first, *temp) && first != temp){ + + }else{ + *result = *first; + temp = first; + ++result; + } + ++first; + } + return result; + } + + template _UCXXEXPORT + void + reverse(BidirectionalIterator first, BidirectionalIterator last) + { + --last; //Don't work with one past the end element + while(first < last){ + iter_swap(first, last); + ++first; + --last; + } + } + + template _UCXXEXPORT + OutputIterator + reverse_copy(BidirectionalIterator first, BidirectionalIterator last, + OutputIterator result) + { + while(last > first){ + --last; + *result = *last; + ++result; + } + return result; + } + + template _UCXXEXPORT + void + rotate(ForwardIterator first, ForwardIterator middle, ForwardIterator last) + { + if ((first == middle) || (last == middle)){ + return; + } + + ForwardIterator first2 = middle; + + do { + swap(*first, *first2); + first++; + first2++; + if(first == middle){ + middle = first2; + } + } while(first2 != last); + + first2 = middle; + + while (first2 != last) { + swap(*first, *first2); + first++; + first2++; + if (first == middle){ + middle = first2; + }else if (first2 == last){ + first2 = middle; + } + } + } + + template _UCXXEXPORT + OutputIterator + rotate_copy(ForwardIterator first, ForwardIterator middle, + ForwardIterator last, OutputIterator result) + { + ForwardIterator temp(middle); + while(temp !=last){ + *result = *temp; + ++temp; + ++result; + } + while(first != middle){ + *result = *first; + ++first; + ++result; + } + return result; + } + + + template _UCXXEXPORT + void + random_shuffle(RandomAccessIterator first, RandomAccessIterator last) + { + --last; + while(first != last){ + iter_swap(first, (first + (rand() % (last - first) ) ) ); + ++first; + } + } + + template _UCXXEXPORT + void + random_shuffle(RandomAccessIterator first, RandomAccessIterator last, + RandomNumberGenerator& rand) + { + --last; + while(first != last){ + iter_swap(first, (first + (rand(last - first) ) ) ); + ++first; + } + } + + // _lib.alg.partitions_, partitions: + template _UCXXEXPORT BidirectionalIterator + partition(BidirectionalIterator first, BidirectionalIterator last, Predicate pred) + { + return stable_partition(first, last, pred); + } + + template _UCXXEXPORT BidirectionalIterator + stable_partition(BidirectionalIterator first, BidirectionalIterator last, Predicate pred) + { + //first now points to the first non-desired element + while( first != last && pred(*first) ){ + ++first; + } + + BidirectionalIterator tempb; + BidirectionalIterator tempe = first; + + while( tempe != last ){ + //Find the next desired element + while( !pred(*tempe) ){ + ++tempe; + + //See if we should exit + if(tempe == last){ + return first; + } + } + + //Rotate the element back to the begining + tempb = tempe; + while(tempb != first){ + iter_swap(tempb, tempb-1 ); + --tempb; + } + //First now has a desired element + ++first; + } + + return first; + } + + template _UCXXEXPORT + void sort(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + sort(first, last, c ); + } + + template _UCXXEXPORT + void sort(RandomAccessIterator first, RandomAccessIterator last, Compare comp) + { + stable_sort(first, last, comp); + } + + template _UCXXEXPORT + void stable_sort(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + stable_sort(first, last, c); + } + + template _UCXXEXPORT + void stable_sort(RandomAccessIterator first, RandomAccessIterator last, Compare comp) + { + //FIXME - bubble sort + RandomAccessIterator temp; + --last; + while(last - first > 0){ + temp = last; + while(temp != first){ + if( comp( *temp, *(temp-1) ) ){ + iter_swap( temp-1, temp); + } + --temp; + } + ++first; + } + } + + template _UCXXEXPORT + void partial_sort(RandomAccessIterator first, RandomAccessIterator middle, RandomAccessIterator last) + { + less::value_type> c; + partial_sort(first, middle, last, c); + } + template _UCXXEXPORT + void partial_sort(RandomAccessIterator first, RandomAccessIterator middle, + RandomAccessIterator last, Compare comp) + { + //Fixme - partial bubble sort + RandomAccessIterator temp; + --last; + while(first < middle){ + temp = last; + while(temp != first){ + if( comp(*temp, *(temp -1 ) ) ) { + iter_swap( temp-1, temp); + } + --temp; + } + ++first; + } + } + template _UCXXEXPORT + RandomAccessIterator + partial_sort_copy(InputIterator first, InputIterator last, + RandomAccessIterator result_first, RandomAccessIterator result_last) + { + less::value_type> c; + return partial_sort_copy(first, last, result_first, result_last, c); + } + template _UCXXEXPORT + RandomAccessIterator + partial_sort_copy(InputIterator first, InputIterator last, + RandomAccessIterator result_first, RandomAccessIterator result_last, Compare comp) + { + size_t output_size = last-first; + size_t temp_size = result_last - result_first; + if(temp_size < output_size){ + output_size = temp_size; + } + + RandomAccessIterator middle = result_first + output_size; + RandomAccessIterator temp = result_first; + + while(temp != middle){ + *temp = *first; + ++temp; + ++first; + } + sort(result_first, middle, comp); + + while( first != last){ + if( comp( *first, *(middle-1) ) ){ + *(middle-1) = *first; + sort(result_first, middle, comp); + } + ++first; + } + + return middle; + } + template _UCXXEXPORT + void nth_element(RandomAccessIterator first, RandomAccessIterator nth, RandomAccessIterator last) + { + less::value_type> c; + nth_element(first, nth, last, c); + } + template _UCXXEXPORT + void nth_element(RandomAccessIterator first, RandomAccessIterator nth, + RandomAccessIterator last, Compare comp) + { + partial_sort(first, nth, last, comp); + } + + template _UCXXEXPORT + ForwardIterator lower_bound(ForwardIterator first, ForwardIterator last, + const T& value) + { + less::value_type> c; + return lower_bound(first, last, value, c); + } + + template _UCXXEXPORT + ForwardIterator lower_bound(ForwardIterator first, ForwardIterator last, + const T& value, Compare comp) + { + if(first == last){ + return last; + } + //If below or equal to the first element + if( comp(*first, value) == false){ + return first; + } + ForwardIterator middle; + + //If greater than the top element + middle = first; + advance(middle, distance(first, last) - 1); + if( comp(*middle, value) ){ + return last; + } + + //Now begin the actual search for the begining + while( distance(first, last) > 1 ){ + //Find middle + middle = first; + advance(middle, (distance(first, last)/2) ); + if( !comp(*middle, value) ){ + last = middle; + }else{ + first = middle; + } + } + + if( !comp(*first, value) ){ + return first; + } + return last; + } + + template _UCXXEXPORT + ForwardIterator upper_bound(ForwardIterator first, ForwardIterator last, + const T& value) + { + less::value_type> c; + return upper_bound(first, last, value, c); + } + + + template _UCXXEXPORT + ForwardIterator upper_bound(ForwardIterator first, ForwardIterator last, + const T& value, Compare comp) + { + if(first == last){ + return last; + } + //If below the first element + if( comp(value, *first) == true){ + return first; + } + + ForwardIterator middle; + + //If greater than the top element + middle = first; + advance(middle, distance(first, last) - 1); + if( comp(*middle, value) ){ + return last; + } + + //Now begin the actual search for the end + while( distance(first, last) > 1 ){ + //Find middle + middle = first; + advance(middle, (distance(first, last)/2) ); + if( comp(value, *middle) ){ + last = middle; + }else{ + first = middle; + } + } + + if( comp(value, *first) ){ + return first; + } + return last; + } + + + template _UCXXEXPORT + pair + equal_range(ForwardIterator first, ForwardIterator last, const T& value) + { + less::value_type> c; + return equal_range(first, last, value, c); + } + + template _UCXXEXPORT + pair + equal_range(ForwardIterator first, ForwardIterator last, const T& value, Compare comp) + { + pair retval; + retval.first = lower_bound(first, last, value, comp); + //Reuse retval.first in order to (possibly) save a few comparisons + retval.second = upper_bound(retval.first, last, value, comp); + return retval; + + } + + template _UCXXEXPORT + bool binary_search(ForwardIterator first, ForwardIterator last, + const T& value) + { + less::value_type> c; + return binary_search(first, last, value, c); + } + + template _UCXXEXPORT + bool binary_search(ForwardIterator first, ForwardIterator last, + const T& value, Compare comp) + { + if( distance(first, last) == 0){ + return false; + } + + ForwardIterator middle; + + while( distance(first, last) > 1 ){ + //Set middle between first and last + middle = first; + advance(middle, distance(first, last)/2 ); + + if( comp(*middle, value ) == true){ + first = middle; + }else{ + last = middle; + } + } + + if( !comp(*first, value) && !comp(value, *first) ){ + return true; + } + if( !comp(*last, value) && !comp(value, *last) ){ + return true; + } + + return false; + } + + // _lib.alg.merge_, merge: + template _UCXXEXPORT + OutputIterator + merge(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result) + { + less::value_type> c; + return merge(first1, last1, first2, last2, result, c); + } + template _UCXXEXPORT + OutputIterator + merge(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) + { + while( first1 != last1 && first2 != last2){ + //If in this order so first1 elements which are equal come first + if( comp(*first2, *first1) ){ + *result = *first2; + ++first2; + }else{ + *result = *first1; + ++first1; + } + ++result; + } + //Clean up remaining elements + while(first1 != last1){ + *result = *first1; + ++first1; + ++result; + } + while(first2 != last2){ + *result = *first2; + ++first2; + ++result; + } + return result; + } + template _UCXXEXPORT + void inplace_merge(BidirectionalIterator first, + BidirectionalIterator middle, BidirectionalIterator last) + { + less::value_type> c; + inplace_merge(first, middle, last, c); + } + template _UCXXEXPORT + void inplace_merge(BidirectionalIterator first, + BidirectionalIterator middle, BidirectionalIterator last, Compare comp) + { + //FIXME - using a bubble exchange method + while(first != middle && middle !=last){ + if( comp(*middle, *first) ){ + BidirectionalIterator temp(middle); + while( temp != first){ + iter_swap(temp, temp-1); + --temp; + } + ++middle; + } + ++first; + } + } + + // _lib.alg.set.operations_, set operations: + template _UCXXEXPORT + bool includes(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2) + { + less::value_type> c; + return includes(first1, last1, first2, last2, c ); + } + + template _UCXXEXPORT + bool includes(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, Compare comp) + { + while(first2 != last2){ + //Advance the large set until no longer smaller than the element we are looking for + while( comp(*first1, *first2) ){ + ++first1; + //If we are at the end of the list, we don't have the desired element + if(first1 == last1){ + return false; + } + } + //If we are past the element we want, it isn't here + if( comp(*first2, *first1) ){ + return false; + } + ++first2; //Move to next element + } + return true; + } + + template _UCXXEXPORT + OutputIterator set_union(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result) + { + less::value_type> c; + return set_union(first1, last1, first2, last2, result, c); + } + + template _UCXXEXPORT + OutputIterator set_union(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) + { + while( first1 != last1 && first2 != last2){ + if( comp(*first2, *first1) ){ + *result = *first2; + + //Elliminate duplicates + InputIterator2 temp = first2; + while( first1 != last1 && !comp( *temp, *first1) ){ + ++first1; + } + while( first2 != last2 && !comp( *temp, *first2) ){ + ++first2; + } + }else{ + *result = *first1; + //Elliminate duplicates + InputIterator1 temp = first1; + while( first1 != last1 && !comp( *temp, *first1) ){ + ++first1; + } + while( first2 != last2 && !comp( *temp, *first2) ){ + ++first2; + } + } + ++result; + } + + //Clean up remaining elements + while(first1 != last1){ + *result = *first1; + ++result; + InputIterator1 temp = first1; + while( first1 != last1 && !comp( *temp, *first1) ){ + ++first1; + } + } + + while(first2 != last2){ + *result = *first2; + ++result; + InputIterator2 temp = first2; + while( first2 != last2 && !comp( *temp, *first2) ){ + ++first2; + } + } + return result; + } + + template _UCXXEXPORT + OutputIterator set_intersection(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result) + { + less::value_type> c; + return set_intersection(first1, last1, first2, last2, result, c); + } + template _UCXXEXPORT + OutputIterator set_intersection(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) + { + while( first1 != last1 && first2 != last2){ + if( comp(*first2, *first1) ){ + ++first2; + }else if( comp(*first1, *first2) ) { + ++first1; + }else{ + *result = *first1; + ++result; + InputIterator1 temp = first1; + while( first1 != last1 && !comp( *temp, *first1) ){ + ++first1; + } + ++first2; + } + } + return result; + } + template _UCXXEXPORT + OutputIterator set_difference(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result) + { + less::value_type> c; + return set_difference(first1, last1, first2, last2, result, c); + } + template _UCXXEXPORT + OutputIterator set_difference(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) + { + while( first1 != last1 && first2 != last2){ + if( comp(*first1, *first2) ){ + *result = *first1; + ++result; + + //Elliminate duplicates + InputIterator1 temp = first1; + while( first1 != last1 && !comp( *temp, *first1) ){ + ++first1; + } + }else if( comp(*first2, *first1) ){ + + //Elliminate duplicates + InputIterator2 temp = first2; + while( first2 != last2 && !comp( *temp, *first2) ){ + ++first2; + } + + }else{ //They are identical - skip + //Elliminate duplicates + InputIterator1 temp = first1; + while( first1 != last1 && !comp( *temp, *first1) ){ + ++first1; + } + while( first2 != last2 && !comp( *temp, *first2) ){ + ++first2; + } + } + } + + //Clean up remaining elements + while(first1 != last1){ + *result = *first1; + ++result; + InputIterator1 temp = first1; + while( first1 != last1 && !comp( *temp, *first1) ){ + ++first1; + } + } + + return result; + } + template _UCXXEXPORT + OutputIterator set_symmetric_difference(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result) + { + less::value_type> c; + return set_symmetric_difference(first1, last1, first2, last2, result, c); + } + template _UCXXEXPORT + OutputIterator set_symmetric_difference(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) + { + while( first1 != last1 && first2 != last2){ + if( comp(*first1, *first2) ){ + *result = *first1; + ++result; + + //Elliminate duplicates + InputIterator1 temp = first1; + while( first1 != last1 && !comp( *temp, *first1) ){ + ++first1; + } + }else if( comp(*first2, *first1) ){ + *result = *first2; + ++result; + + //Elliminate duplicates + InputIterator2 temp = first2; + while( first2 != last2 && !comp( *temp, *first2) ){ + ++first2; + } + + }else{ //They are identical - skip + //Elliminate duplicates + InputIterator1 temp = first1; + while( first1 != last1 && !comp( *temp, *first1) ){ + ++first1; + } + while( first2 != last2 && !comp( *temp, *first2) ){ + ++first2; + } + } + } + + //Clean up remaining elements + while(first1 != last1){ + *result = *first1; + ++result; + InputIterator1 temp = first1; + while( first1 != last1 && !comp( *temp, *first1) ){ + ++first1; + } + } + + while(first2 != last2){ + *result = *first2; + ++result; + InputIterator2 temp = first2; + while( first2 != last2 && !comp( *temp, *first2) ){ + ++first2; + } + } + + return result; + } + + // _lib.alg.heap.operations_, heap operations: + + template _UCXXEXPORT + void push_heap(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + push_heap(first, last, c); + } + + template _UCXXEXPORT + void push_heap(RandomAccessIterator first, RandomAccessIterator last, Compare comp) + { + // *(last - 1) is the last element + RandomAccessIterator begin, middle, end; + begin = first; + end = last - 2; + if(last - first < 2){ //Empty heap + return; + } + if ( comp(*(last-1), *end) ){ //Belongs past the end - already in place + return; + } + while(end - begin > 1){ + middle = begin + ((end - begin)/2); + if( comp(*middle, *(last-1) ) ){ + end = middle; + }else{ + begin = middle; + } + } + + if( comp(*begin, *(last-1)) ){ + middle = begin; + }else{ + middle = end; + } + + //Now all we do is swap the elements up to the begining + --last; + + while(last > middle){ + iter_swap(last, last-1); + --last; + } + } + + template _UCXXEXPORT + void pop_heap(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + pop_heap(first, last, c); + } + template _UCXXEXPORT + void pop_heap(RandomAccessIterator first, RandomAccessIterator last, Compare) + { + --last; + while(first < last){ + iter_swap( first, first+1); + ++first; + } + } + + template _UCXXEXPORT + void make_heap(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + make_heap(first, last, c); + } + template _UCXXEXPORT + void make_heap(RandomAccessIterator first, RandomAccessIterator last, Compare comp) + { + sort( reverse_iterator(last), reverse_iterator(first), comp); + } + template _UCXXEXPORT + void sort_heap(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + sort_heap(first, last, c); + } + template _UCXXEXPORT + void sort_heap(RandomAccessIterator first, RandomAccessIterator last, Compare comp) + { + sort( first, last, comp); + } + + + // _lib.alg.min.max_, minimum and maximum: + template _UCXXEXPORT + const T& min(const T& a, const T& b) + { + if(b < a){ + return b; + } + return a; + } + + template _UCXXEXPORT + const T& min(const T& a, const T& b, Compare comp) + { + if( comp(b, a) == true){ + return b; + } + return a; + } + + template _UCXXEXPORT + const T& max(const T& a, const T& b) + { + if( a < b){ + return b; + } + return a; + } + + template _UCXXEXPORT + const T& max(const T& a, const T& b, Compare comp) + { + if( comp(a, b) ){ + return b; + } + return a; + } + + template _UCXXEXPORT + ForwardIterator min_element(ForwardIterator first, ForwardIterator last) + { + less::value_type> c; + return min_element(first, last, c); + } + + template _UCXXEXPORT + ForwardIterator min_element(ForwardIterator first, ForwardIterator last, Compare comp) + { + ForwardIterator retval = first; + ++first; + while(first != last){ + if( comp( *first, *retval) ){ + retval = first; + } + ++first; + } + return retval; + } + + template _UCXXEXPORT + ForwardIterator max_element(ForwardIterator first, ForwardIterator last) + { + less::value_type> c; + return max_element(first, last, c); + } + + template _UCXXEXPORT + ForwardIterator max_element(ForwardIterator first, ForwardIterator last, Compare comp) + { + ForwardIterator retval = first; + ++first; + while(first != last){ + if( comp( *retval, *first ) ){ + retval = first; + } + ++first; + } + return retval; + } + + template _UCXXEXPORT + bool lexicographical_compare(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2) + { + less::value_type> c; + return lexicographical_compare(first1, last1, first2, last2, c); + } + + template _UCXXEXPORT + bool lexicographical_compare(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, Compare comp) + { + while(first1 != last1 && first2 != last2){ + if( comp(*first1, *first2) ){ + return true; + } + if( comp(*first2, *first1) ){ + return false; + } + ++first1; + ++first2; + } + return first1==last1 && first2 != last2; + } + + // _lib.alg.permutation.generators_, permutations + template _UCXXEXPORT + bool next_permutation(BidirectionalIterator first, BidirectionalIterator last) + { + less::value_type> c; + return next_permutation(first, last, c); + } + + template _UCXXEXPORT + bool next_permutation(BidirectionalIterator first, BidirectionalIterator last, Compare comp) + { + if(first == last){ + return false; // No data + } + BidirectionalIterator i = last; + --i; + if(i == first){ + return false; //Only one element + } + BidirectionalIterator ii = i; + --ii; + //If the last two items are in order, swap them and call it done + if( comp(*ii, *i) ){ + iter_swap(ii, i); + return true; + } + + + //This part of the algorithm copied from G++ header files ver. 3.4.2 + i = last; + --i; + for(;;){ + ii = i; + --i; + if ( comp(*i, *ii) ){ + BidirectionalIterator j = last; + --j; + while ( !comp(*i, *j)){ + --j; + } + iter_swap(i, j); + reverse(ii, last); + return true; + } + if (i == first){ + reverse(first, last); + return false; + } + } + + + } + + template _UCXXEXPORT + bool prev_permutation(BidirectionalIterator first, BidirectionalIterator last) + { + less::value_type> c; + return prev_permutation(first, last, c); + } + + template _UCXXEXPORT + bool prev_permutation(BidirectionalIterator first, BidirectionalIterator last, Compare comp) + { + if(first == last){ + return false; // No data + } + BidirectionalIterator i = last; + --i; + if(i == first){ + return false; //Only one element + } + BidirectionalIterator ii = i; + --ii; + //If the last two items are in reverse order, swap them and call it done + if( comp(*i, *ii) ){ + iter_swap(ii, i); + return true; + } + + //Copied from GNU GCC header files version 3.4.2 + i = last; + --i; + + for(;;){ + ii = i; + --i; + if ( comp(*ii, *i)){ + BidirectionalIterator j = last; + --j; + while ( !comp(*j, *i)){ + --j; + } + iter_swap(i, j); + reverse(ii, last); + return true; + } + if (i == first){ + reverse(first, last); + return false; + } + } + + } + +} + +#pragma GCC visibility pop + +#endif + + + diff --git a/misc/uClibc++/include/cxx/associative_base b/misc/uClibc++/include/cxx/associative_base new file mode 100644 index 0000000000..27ae0ef9f8 --- /dev/null +++ b/misc/uClibc++/include/cxx/associative_base @@ -0,0 +1,640 @@ +/* Copyright (C) 2007 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + + + +#include +#include +#include +#include +#include + + +#ifndef __STD_HEADER_ASSOCIATIVE_BASE +#define __STD_HEADER_ASSOCIATIVE_BASE + +#pragma GCC visibility push(default) + +namespace std{ + + +/* + * The basic premise here is that most of the code used by map, multimap, set and + * multiset is really common. There are a number of interface additions, and + * considerations about how to address multiple entries with the same key. + * The goal is that the tree/storage code should be here, and managing + * single or multiple counts will be left to subclasses. + * Yes, inheritence for the purpose of code sharing is usually a bad idea. + * However, since our goal is to reduce the total amount of code written + * and the overall binary size, this seems to be the best approach possible. + */ + +template, class Allocator = allocator > class __base_associative; +template class _associative_iter; +template class _associative_citer; + +template, class Allocator = allocator > class __single_associative; +template, class Allocator = allocator > class __multi_associative; + +template class _UCXXEXPORT __base_associative{ + +protected: + +public: + typedef Key key_type; + typedef ValueType value_type; + typedef Compare key_compare; + typedef Allocator allocator_type; + typedef typename Allocator::reference reference; + typedef typename Allocator::const_reference const_reference; + typedef typename Allocator::size_type size_type; + typedef typename Allocator::difference_type difference_type; + typedef typename Allocator::pointer pointer; + typedef typename Allocator::const_pointer const_pointer; + typedef __base_associative associative_type; + + typedef _associative_iter iterator; + typedef _associative_citer const_iterator; + typedef typename std::reverse_iterator reverse_iterator; + typedef typename std::reverse_iterator const_reverse_iterator; + + + explicit __base_associative(const Compare& comp, const Allocator& A, const key_type (*v_to_k)(const value_type)) + : c(comp), value_to_key(v_to_k) { } +protected: + __base_associative(const associative_type& x) + : c(x.c), backing(x.backing), value_to_key(x.value_to_key) { } + +public: + ~__base_associative(){ + } + + bool empty() const{ + return backing.empty(); + } + size_type size() const{ + return backing.size(); + } + size_type max_size() const{ + return backing.max_size(); + } + + iterator begin(){ + return iterator(backing.begin()); + } + + const_iterator begin() const{ + return const_iterator(backing.begin()); + } + + iterator end() { + return iterator(backing.end()); + } + + const_iterator end() const{ + return const_iterator(backing.end()); + } + + reverse_iterator rbegin(){ + return reverse_iterator(end()); + } + + const_reverse_iterator rbegin() const{ + return const_reverse_iterator(end()); + } + + reverse_iterator rend(){ + return reverse_iterator(begin()); + } + + const_reverse_iterator rend() const{ + return const_reverse_iterator(begin()); + } + + + iterator lower_bound(const key_type &x); + const_iterator lower_bound(const key_type &x) const; + iterator upper_bound(const key_type &x); + const_iterator upper_bound(const key_type &x) const; + + pair equal_range(const key_type& x){ + pair retval; + retval.first = lower_bound(x); + retval.second = retval.first; + while(retval.second != end() && !c(x, value_to_key(*retval.second))){ + ++retval.second; + } + return retval; + } + pair equal_range(const key_type& x) const{ + pair retval; + retval.first = lower_bound(x); + retval.second = retval.first; + while(retval.second != end() && !c(x, value_to_key(*retval.second))){ + ++retval.second; + } + return retval; + } + + iterator find(const key_type& x){ + iterator retval = lower_bound(x); + if(retval == end()){ + return retval; + } + if(c(x, value_to_key(*retval))){ + return end(); + } + return retval; + } + const_iterator find(const key_type& x) const{ + const_iterator retval = lower_bound(x); + if(retval == end()){ + return retval; + } + if(c(x, value_to_key(*retval))){ + return end(); + } + return retval; + } + size_type count(const key_type& x) const{ + size_type retval(0); + const_iterator first = lower_bound(x); + while(first != end() && !c(x, value_to_key(*first))){ + ++retval; + ++first; + } + return retval; + } + + void clear(){ + backing.clear(); + } + + void erase(iterator pos){ + backing.erase(pos.base_iterator()); + } + size_type erase(const key_type& x){ + size_type count(0); + iterator start = lower_bound(x); + iterator end = upper_bound(x); + while(start != end){ + start = backing.erase(start.base_iterator()); + ++count; + } + return count; + } + void erase(iterator first, iterator last){ + while(first != last){ + backing.erase(first.base_iterator()); + ++first; + } + } + + key_compare key_comp() const{ + return c; + } + + __base_associative &operator=(const __base_associative & x){ + c = x.c; + backing = x.backing; + value_to_key = x.value_to_key; + return *this; + } + bool operator==(const __base_associative & x){ + return x.backing == backing; + } + bool operator!=(const __base_associative & x){ + return !(x.backing == backing); + } + +protected: + void swap(__base_associative & x); + + Compare c; + std::list backing; + + const key_type (*value_to_key)(const value_type); + +}; + + +/* + * Tree iterators for the base associative class + */ + +template class _associative_citer + : public std::iterator< + bidirectional_iterator_tag, + ValueType, + typename Allocator::difference_type, + ValueType*, + ValueType& + > +{ +protected: + typedef std::list listtype; + + typename listtype::const_iterator base_iter; + friend class _associative_iter; +public: + _associative_citer() { } + _associative_citer(const _associative_citer & m) + : base_iter(m.base_iter) { } + _associative_citer(const typename listtype::const_iterator & m) + : base_iter(m) { } + ~_associative_citer() { } + ValueType operator*() const{ + return *base_iter; + } + const ValueType * operator->() const{ + return &(*base_iter); + } + _associative_citer & operator=(const _associative_citer & m){ + base_iter = m.base_iter; + return *this; + } + bool operator==(const _associative_citer & m) const{ + return m.base_iter == base_iter; + } + bool operator!=(const _associative_citer & m) const{ + return m.base_iter != base_iter; + } + _associative_citer & operator++(){ + ++base_iter; + return *this; + } + _associative_citer operator++(int){ + //The following approach ensures that we only need to + //provide code for ++ in one place (above) + _associative_citer temp(base_iter); + ++base_iter; + return temp; + } + _associative_citer & operator--(){ + --base_iter; + return *this; + } + _associative_citer operator--(int){ + //The following approach ensures that we only need to + //provide code for -- in one place (above) + _associative_citer temp(base_iter); + --base_iter; + return temp; + } + + //This is an implementation-defined function designed to make internals work correctly + typename listtype::const_iterator base_iterator(){ + return base_iter; + } +}; + + +template class _associative_iter + : public std::iterator< + bidirectional_iterator_tag, + ValueType, + typename Allocator::difference_type, + ValueType*, + ValueType& + > +{ +protected: + typedef std::list listtype; + + typename listtype::iterator base_iter; + typedef _associative_citer __associative_citer; + +public: + _associative_iter() { } + _associative_iter(const _associative_iter & m) + : base_iter(m.base_iter) { } + _associative_iter(const typename listtype::iterator & m) + : base_iter(m) { } + ~_associative_iter() { } + const ValueType & operator*() const{ + return *base_iter; + } + ValueType & operator*(){ + return *base_iter; + } + ValueType * operator->(){ + return &(*base_iter); + } + const ValueType * operator->() const{ + return &(*base_iter); + } + _associative_iter & operator=(const _associative_iter & m){ + base_iter = m.base_iter; + return *this; + } + bool operator==(const _associative_iter & m) const{ + return m.base_iter == base_iter; + } + bool operator==(const __associative_citer & m) const{ + return m.base_iter == base_iter; + } + bool operator!=(const _associative_iter & m) const{ + return m.base_iter != base_iter; + } + bool operator!=(const __associative_citer & m) const{ + return m.base_iter != base_iter; + } + _associative_iter & operator++(){ + ++base_iter; + return *this; + } + _associative_iter operator++(int){ + //The following approach ensures that we only need to + //provide code for ++ in one place (above) + _associative_iter temp(base_iter); + ++base_iter; + return temp; + } + _associative_iter & operator--(){ + --base_iter; + return *this; + } + _associative_iter operator--(int){ + //The following approach ensures that we only need to + //provide code for -- in one place (above) + _associative_iter temp(base_iter); + --base_iter; + return temp; + } + operator __associative_citer() const{ + return __associative_citer(base_iter); + } + typename listtype::iterator base_iterator(){ + return base_iter; + } + const typename listtype::iterator base_iterator() const{ + return base_iter; + } + +}; + + + // The lower_bound code is really crappy linear search. However, it is a dead + // simple implementation (easy to audit). It can also be easily replaced. + + + template + typename __base_associative::iterator + __base_associative::lower_bound(const key_type &x) + { + iterator retval = begin(); + while(retval != end() && c(value_to_key(*retval), x)){ + ++retval; + } + return retval; + } + + template + typename __base_associative::const_iterator + __base_associative::lower_bound(const key_type &x) const + { + const_iterator retval = begin(); + while(retval != end() && c(value_to_key(*retval), x)){ + ++retval; + } + return retval; + } + + // Upper bound search is linear from the point of lower_bound. This is likely the best solution + // in all but the most pathological of cases. + + template + typename __base_associative::iterator + __base_associative::upper_bound(const key_type &x) + { + iterator retval = lower_bound(x); + while(retval != end() && !c(x, value_to_key(*retval))){ + ++retval; + } + return retval; + } + + template + typename __base_associative::const_iterator + __base_associative::upper_bound(const key_type &x) const + { + const_iterator retval = begin(); + while(retval != end() && !c(x, value_to_key(*retval))){ + ++retval; + } + return retval; + } + + + template + void __base_associative::swap(__base_associative& m) + { + Compare n = c; + c = m.c; + m.c = n; + + m.backing.swap(backing); + } + + +template class _UCXXEXPORT __single_associative : + public __base_associative +{ +protected: + typedef __base_associative base; + using base::backing; + + using base::c; + +public: + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; + + using base::begin; + using base::end; + using base::rbegin; + using base::rend; + + using base::empty; + using base::size; + using base::max_size; + + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; + + using base::operator=; + using base::operator==; + using base::operator!=; + + explicit __single_associative(const Compare& comp, const Allocator& A, const key_type (*v_to_k)(const value_type)) + : base(comp, A, v_to_k) { } + + template __single_associative( + InputIterator first, + InputIterator last, + const Compare& comp, + const Allocator& A, + const key_type (*v_to_k)(const value_type) + ) : base(comp, A, v_to_k) { + insert(first, last); + } + + pair insert(const value_type& x){ + pair retval; + iterator location = lower_bound(this->value_to_key(x)); + retval.second = true; + //Empty list or need to insert at end + if(end() == location){ + backing.push_back(x); + retval.first = --(end()); + return retval; + } + //Something in the list + if(c(this->value_to_key(x), this->value_to_key(*location))){ + location = backing.insert(location.base_iterator(), x); + retval.first = location; + }else{ + retval.second = false; + retval.first = location; + } + return retval; + } + + iterator insert(iterator position, const value_type& x){ + // FIXME - this is cheating and probably should be more efficient since we are + // now log(n) to find for inserts + return insert(x).first; + } + + template void insert(InputIterator first, InputIterator last){ + while(first != last){ + insert(*first); + ++first; + } + } + +}; + + +template class _UCXXEXPORT __multi_associative : + public __base_associative +{ +protected: + typedef __base_associative base; + using base::backing; + + using base::c; + +public: + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; + + using base::begin; + using base::end; + using base::rbegin; + using base::rend; + + using base::empty; + using base::size; + using base::max_size; + + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; + + using base::operator=; + using base::operator==; + + + explicit __multi_associative(const Compare& comp, const Allocator& A, const key_type (*v_to_k)(const value_type)) + : base(comp, A, v_to_k) { } + + template __multi_associative( + InputIterator first, + InputIterator last, + const Compare& comp, + const Allocator& A, + const key_type (*v_to_k)(const value_type) + ) : base(comp, A, v_to_k) { + insert(first, last); + } + + iterator insert(const value_type& x){ + iterator location = lower_bound(this->value_to_key(x)); + + if(location == begin()){ + backing.push_front(x); + location = begin(); + }else{ + location = backing.insert(location.base_iterator(), x); + } + return location; + } + + iterator insert(iterator position, const value_type& x){ + // FIXME - this is cheating and probably should be more efficient since we are + // now log(n) to find for inserts + return insert(x); + } + + template void insert(InputIterator first, InputIterator last){ + while(first != last){ + insert(*first); + ++first; + } + } +}; + + + + +} + +#pragma GCC visibility pop + +#endif //__STD_HEADER_ASSOCIATIVE_BASE + diff --git a/misc/uClibc++/include/cxx/basic_definitions b/misc/uClibc++/include/cxx/basic_definitions new file mode 100644 index 0000000000..e0392b8ea7 --- /dev/null +++ b/misc/uClibc++/include/cxx/basic_definitions @@ -0,0 +1,66 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#ifndef __BASIC_DEFINITIONS +#define __BASIC_DEFINITIONS 1 + +#include + +#pragma GCC visibility push(default) + +//The following is used to support GCC symbol visibility patch + +#ifdef GCC_HASCLASSVISIBILITY + #define _UCXXEXPORT __attribute__ ((visibility("default"))) + #define _UCXXLOCAL __attribute__ ((visibility("hidden"))) +#else + #define _UCXXEXPORT + #define _UCXXLOCAL + +#endif + +#ifdef __GCC__ +#define __UCLIBCXX_NORETURN __attribute__ ((__noreturn__)) +#else +#define __UCLIBCXX_NORETURN +#endif + +#ifdef __UCLIBCXX_HAS_TLS__ + #define __UCLIBCXX_TLS __thread +#else + #define __UCLIBCXX_TLS +#endif + + + +//Testing purposes +#define __STRING_MAX_UNITS 65535 + +namespace std{ + typedef signed long int streamsize; +} + +#pragma GCC visibility pop + +#endif + + +#ifdef __DODEBUG__ + #define UCLIBCXX_DEBUG 1 +#else + #define UCLIBCXX_DEBUG 0 +#endif diff --git a/misc/uClibc++/include/cxx/bitset b/misc/uClibc++/include/cxx/bitset new file mode 100644 index 0000000000..50d540469a --- /dev/null +++ b/misc/uClibc++/include/cxx/bitset @@ -0,0 +1,423 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include +#include +#include + +#ifndef __STD_BITSET_HEADER +#define __STD_BITSET_HEADER 1 + +#pragma GCC visibility push(default) + +namespace std{ + template class bitset; + + + template bitset operator&(const bitset&, const bitset&); + template bitset operator|(const bitset&, const bitset&); + template bitset operator^(const bitset&, const bitset&); + template basic_istream& + operator>>(basic_istream& is, bitset& x); + + template basic_ostream& + operator<<(basic_ostream& os, const bitset& x); + + //Actual Code + + + template class _UCXXEXPORT bitset { + private: + //Number of characters allocated to hold the bits + static const size_t WORD_SIZE = CHAR_BIT; //Use int maybe? + static const size_t num_bytes = (N + WORD_SIZE - 1) / WORD_SIZE; + + //From the bit number, figure out which byte we are working with + size_t byte_num(size_t bit_num) const{ + if(WORD_SIZE == 8){ + return (bit_num >> 3); + } + if(WORD_SIZE == 16){ + return (bit_num >> 4); + } + if(WORD_SIZE == 32){ + return (bit_num >> 5); + } + if(WORD_SIZE == 64){ + return (bit_num >> 6); + } + return bit_num / WORD_SIZE; + } + //From the bit number, figure out which bit inside the byte we need + size_t bit_num(const size_t bit_num) const{ + return bit_num % WORD_SIZE; + } + + + //Point to the actual data + char data[num_bytes]; + public: + + class _UCXXEXPORT reference { + friend class bitset; + reference() : bit_num(0), parent(0) { } + size_t bit_num; + bitset * parent; + public: + ~reference() { } + reference& operator=(bool x){ // for b[i] = x; + parent->set(bit_num, x); + return *this; + } + reference& operator=(const reference& x){ // for b[i] = b[j]; + parent->set(bit_num, x); + return *this; + } + bool operator~() const{ // flips the bit + return !parent->test(bit_num); + } + operator bool() const{ // for x = b[i]; + return parent->test(bit_num); + } + reference& flip(){ // for b[i].flip(); + parent->flip(bit_num); + return *this; + } + }; + + bitset(){ + reset(); + } + bitset(unsigned long val){ + reset(); + size_t count = sizeof(val) * CHAR_BIT; + if(count > N){ + count = N; + } + for(size_t i = 0; i < count; ++i){ + set(i, ((val >> i) & 1)); + } + } + + bitset(const bitset & val){ + for(size_t i = 0; i < num_bytes; ++i){ + data[i] = val.data[i]; + } + } + + template _UCXXEXPORT + explicit bitset( + const basic_string& str, + typename basic_string::size_type pos = 0, + typename basic_string::size_type n = + basic_string::npos + + ){ + reset(); + if(n > str.length()){ + n = str.length(); + } + size_t width = n; + if (width + pos > str.length()){ + width = str.length() - pos; + } + + for(size_t i = 0; i < width; ++i){ + switch(str[pos + width - i - 1]){ + case '0': + break; + case '1': + set(i); + break; + default: + __throw_invalid_argument(); + } + } + } + + bitset& operator&=(const bitset& rhs){ + for(size_t i =0; i < num_bytes; ++i){ + data[i] &= rhs.data[i]; + } + return *this; + } + + bitset& operator|=(const bitset& rhs){ + for(size_t i =0; i < num_bytes; ++i){ + data[i] |= rhs.data[i]; + } + return *this; + } + bitset& operator^=(const bitset& rhs){ + for(size_t i=0; i < num_bytes; ++i){ + data[i] ^= rhs.data[i]; + } + return *this; + } + + bitset& operator<<=(size_t pos){ + for(size_t i = N-1; i >=pos; --i){ + set(i, test(i - pos)); + } + for(size_t i = 0; i < pos; ++i){ + reset(i); + } + return *this; + } + + bitset& operator>>=(size_t pos){ + for(size_t i = 0; i < (N - pos); ++i){ + set(i, test(i + pos)); + } + for(size_t i = pos; i > 0; --i){ + reset(N - i); + } + return *this; + } + + bitset& set(){ + size_t i; + for(i = 0; i < N ; ++i){ + data[byte_num(i)] |= (1<& set(size_t pos, int val = true){ + if(val == true){ + data[byte_num(pos)] |= (1<& reset(){ + for(size_t i = 0; i < num_bytes; ++i){ + data[i] = 0; + } + return *this; + } + bitset& reset(size_t pos){ + data[byte_num(pos)] &= ~(1< operator~() const{ + bitset retval(*this); + retval.flip(); + return retval; + } + + bitset& flip(){ + for(size_t i = 0; i < num_bytes; ++i){ + data[i] = ~data[i]; + } + return *this; + } + bitset& flip(size_t pos){ + char temp = data[byte_num(pos)] & (1 << bit_num(pos)); + if(temp == 0){ //Bit was 0 + data[byte_num(pos)] |= (1 << bit_num(pos)); + }else{ //Bit was 1 + data[byte_num(pos)] &= ~(1< sizeof(unsigned long) * CHAR_BIT){ + __throw_overflow_error(); + } + unsigned long retval = 0; + size_t count = N; + for(size_t i = count; i > 0; --i){ + if(test(i)){ + retval +=1; + } + retval<<=1; + } + if(test(0)){ + retval +=1; + } + return retval; + } + + template + basic_string to_string() const + { + basic_string retval; + retval.reserve(N); + for(size_t i = N ; i > 0; --i){ + if(test(i-1) == true){ + retval.append("1"); + }else{ + retval.append("0"); + } + } + return retval; + } + + + size_t count() const{ + size_t retval = 0; + for(size_t i =0; i < N; ++i){ + if(test(i)){ + ++retval; + } + } + return retval; + } + size_t size() const{ + return N; + } + + bitset& operator=(const bitset & rhs){ + if(&rhs == this){ + return *this; + } + for(size_t i = 0; i <= byte_num(N); ++i){ + data[i] = rhs.data[i]; + } + return *this; + } + + + bool operator==(const bitset& rhs) const{ + for(size_t i =0; i< N; ++i){ + if(test(i) != rhs.test(i)){ + return false; + } + } + return true; + } + + bool operator!=(const bitset& rhs) const{ + for(size_t i =0; i< N; ++i){ + if(test(i) != rhs.test(i)){ + return true; + } + } + return false; + } + + bool test(size_t pos) const{ + return (data[byte_num(pos)] & (1< operator<<(size_t pos) const{ + bitset retval(*this); + retval<<=pos; + return retval; + } + bitset operator>>(size_t pos) const{ + bitset retval(*this); + retval>>=pos; + return retval; + } + }; + + //Non-member functions + + + template _UCXXEXPORT bitset operator&(const bitset& lhs, const bitset& rhs){ + bitset retval(lhs); + retval &= rhs; + return retval; + } + + template _UCXXEXPORT bitset operator|(const bitset& lhs, const bitset& rhs){ + bitset retval(lhs); + retval |= rhs; + return retval; + } + + template _UCXXEXPORT bitset operator^(const bitset& lhs, const bitset& rhs){ + bitset retval(lhs); + retval ^= rhs; + return retval; + } + + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, bitset& x) + { + string s; + charT c; + for(size_t i = 0; i < N; ++i){ + is.get(c); + if(!is.good()){ + break; + } + if(c != '1' && c !='0'){ + is.putback(c); + break; + } + s+=c; + } + bitset temp(s); + x = temp; + + return is; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const bitset& x) + { + for(size_t i = N ; i > 0; --i){ + if(x.test(i-1) == true){ + os << "1"; + }else{ + os << "0"; + } + } + return os; + } + + + + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/cfloat b/misc/uClibc++/include/cxx/cfloat new file mode 100644 index 0000000000..d2ab703f52 --- /dev/null +++ b/misc/uClibc++/include/cxx/cfloat @@ -0,0 +1,30 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +#ifndef __STD_HEADER_CFLOAT +#define __STD_HEADER_CFLOAT 1 + + +#include + + +#endif + diff --git a/misc/uClibc++/include/cxx/char_traits b/misc/uClibc++/include/cxx/char_traits new file mode 100644 index 0000000000..0f01d2e5d4 --- /dev/null +++ b/misc/uClibc++/include/cxx/char_traits @@ -0,0 +1,215 @@ +//*************************************************************************** +// include/cxx/cerrno +// +// 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. +// +//*************************************************************************** +//#ifndef __INCLUDE_CXX_CHAR1_TRAITS +//#define __INCLUDE_CXX_CHAR1_TRAITS +#include +#include +#include +#include + +#ifdef __UCLIBCXX_HAS_WCHAR__ +#include +#include +#endif + +#ifndef __HEADER_CHAR_TRAITS +#define __HEADER_CHAR_TRAITS 1 + +namespace std{ + /* Inlining all wrapped function calls to shrink the amount of code generated*/ + //Typedefs to use for stuff + typedef signed int char_traits_off_type; + + //Generic char_traits + template struct _UCXXEXPORT char_traits { }; + + //Specialize for char + template<> struct _UCXXEXPORT char_traits { + typedef char char_type; + typedef short int int_type; + typedef char_traits_off_type off_type; + typedef char_traits_off_type pos_type; + typedef char state_type; + + inline static void assign(char_type & c, const char_type & d) { c = d; } + + static bool eq(const char_type& c1, const char_type& c2); + + static char_type to_char_type(const int_type & i); + + inline static int_type to_int_type(const char_type & c){ + return (short int)(unsigned char)c; + } + + inline static bool eq_int_type(const int_type & a, const int_type & b){ + if(a==b){ + return true; + } + return false; + } + + + inline static bool lt(const char_type& c1, const char_type& c2){ + if(strncmp(&c1, &c2, 1) < 0){ + return true; + } + return false; + } + + inline static char_type* move(char_type* s1, const char_type* s2, size_t n){ + return (char*) memmove(s1, s2, n); + } + + inline static char_type* copy(char_type* s1, const char_type* s2, size_t n){ + for(unsigned long int i=0; i< n; ++i){ + assign(s1[i], s2[i]); + } + return s1 + n; + } + + inline static char_type* assign(char_type* s, size_t n, char_type a){ + return (char *)memset(s, a, n); + } + + inline static int compare(const char_type* s1, const char_type* s2, size_t n){ + return strncmp(s1, s2, n); + } + + inline static size_t length(const char_type* s){ + return wstrlen(s); + } + + static const char_type* find(const char_type* s, int n, const char_type& a); + + inline static char_type eos() { return 0; } + inline static int_type eof() { return -1; } + inline static int_type not_eof(const int_type & i) { + if(i == -1){ + return 0; + } else { + return i; + } + } + static state_type get_state(pos_type p){ + p = p; + state_type a; + return a; + } + }; + + +#ifdef __UCLIBCXX_HAS_WCHAR__ + template<> struct _UCXXEXPORT char_traits { + typedef wchar_t char_type; + typedef wint_t int_type; + typedef char_traits_off_type off_type; + typedef char_traits_off_type pos_type; + typedef mbstate_t state_type; + + static void assign(char_type & c, const char_type & d){ c=d; } + + static char_type to_char_type(const int_type & i){ + return i; + } + + static int_type to_int_type(const char_type & c){ + return c; + } + + inline static bool eq_int_type(const int_type & a, const int_type & b){ + if(a==b){ + return true; + } + return false; + } + + inline static bool eq(const char_type& c1, const char_type& c2){ + if(wcsncmp(&c1, &c2, 1) == 0){ + return true; + } + return false; + } + + inline static bool lt(const char_type& c1, const char_type& c2){ + if(wcsncmp(&c1, &c2, 1) < 0){ + return true; + } + return false; + } + + inline static char_type* move(char_type* s1, const char_type* s2, size_t n){ + return (char_type*) memmove(s1, s2, n * sizeof(char_type)); + } + + inline static char_type* copy(char_type* s1, const char_type* s2, size_t n){ + for(unsigned long int i=0; i< n; ++i){ + assign(s1[i], s2[i]); + } + return s1 + n; + } + + inline static char_type* assign(char_type* s, size_t n, char_type a){ + return (char_type *)memset(s, a, n); /*FIXME*/ + } + + inline static int compare(const char_type* s1, const char_type* s2, size_t n){ + return wcsncmp(s1, s2, n); + } + + inline static size_t length(const char_type* s){ + return wcslen(s); + } + + static const char_type* find(const char_type* s, int n, const char_type& a); + + inline static char_type eos() { return 0; } + inline static int_type eof() { return WEOF; } + inline static int_type not_eof(const int_type & i) { + if(i == WEOF){ + return (int_type)0; + } else { + return i; + } + } + static state_type get_state(pos_type){ + state_type a; + return a; + } + }; +#endif + +} + +#endif diff --git a/misc/uClibc++/include/cxx/clocale b/misc/uClibc++/include/cxx/clocale new file mode 100644 index 0000000000..4f3cd6943d --- /dev/null +++ b/misc/uClibc++/include/cxx/clocale @@ -0,0 +1,30 @@ +/* Copyright (C) 2005 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#ifndef __STD_HEADER_CLOCALE +#define __STD_HEADER_CLOCALE 1 + +#include + +namespace std { + using ::lconv; + using ::setlocale; + using ::localeconv; +} + +#endif // __STD_HEADER_CLOCALE diff --git a/misc/uClibc++/include/cxx/complex b/misc/uClibc++/include/cxx/complex new file mode 100644 index 0000000000..2c3c82b961 --- /dev/null +++ b/misc/uClibc++/include/cxx/complex @@ -0,0 +1,327 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include + +#ifndef __STD_HEADER_COMPLEX +#define __STD_HEADER_COMPLEX 1 + + +namespace std { +// class complex; +// class complex; +// class complex; + + template class _UCXXEXPORT complex{ + public: + typedef T value_type; + + complex(const T& re = T(), const T& im = T()) : r(re), i(im) { } + complex(const complex& c): r(c.r), i(c.i){ } + template complex(const complex& c): r(c.r), i(c.i){ } + + inline T real() const{ + return r; + } + inline T imag() const{ + return i; + } + + complex& operator= (const T& v){ + r = v; + i = 0; + return *this; + } + complex& operator+=(const T& v){ + r +=v; + return *this; + } + complex& operator-=(const T& v){ + r -=v; + return *this; + } + complex& operator*=(const T& v){ + r*=v; + i*=v; + return *this; + } + complex& operator/=(const T& v){ + r/=v; + i/=v; + return *this; + } + complex& operator=(const complex& v){ + if(&v != this){ + r = v.r; + i = v.i; + } + return *this; + } + template complex& operator= (const complex& v){ + r = v.r; + i = v.i; + return *this; + } + template complex& operator+=(const complex& v){ + r+=v.r; + i+=v.i; + return *this; + } + template complex& operator-=(const complex& v){ + r-=v.r; + i-=v.i; + return *this; + } + template complex& operator*=(const complex& v){ + T tempr = r*v.r - i*v.i; + T tempi = r*v.i + i*v.r; + r = tempr; + i = tempi; + return *this; + } + template complex& operator/=(const complex& v){ + T tempr = (r*v.r + i*v.i) / (v.r*v.r + v.i*v.i); + T tempi = (i*v.r - r*v.i) / (v.r*v.r + v.i*v.i); + r = tempr; + i = tempi; + return *this; + } + private: + T r; + T i; + }; + + template _UCXXEXPORT complex operator+(const complex& ls, const complex& rs){ + complex retval(ls); + retval += rs; + return retval; + } + template _UCXXEXPORT complex operator+(const complex& ls, const T& rs){ + complex retval(ls); + ls += rs; + return retval; + } + template _UCXXEXPORT inline complex operator+(const T& ls, const complex& rs){ + return rs + ls; + } + template _UCXXEXPORT complex operator-(const complex& ls, const complex& rs){ + complex retval(ls); + retval -= rs; + return retval; + } + template _UCXXEXPORT complex operator-(const complex& ls, const T& rs){ + complex retval(ls); + retval -= rs; + return retval; + } + template _UCXXEXPORT complex operator-(const T& ls, const complex& rs){ + complex retval(ls); + retval -= rs; + return retval; + } + template _UCXXEXPORT complex operator*(const complex& ls, const complex& rs){ + complex retval(ls); + retval *= rs; + return retval; + } + template _UCXXEXPORT complex operator*(const complex& ls, const T& rs){ + complex retval(ls); + retval *= rs; + return retval; + } + template _UCXXEXPORT complex operator*(const T& ls, const complex& rs){ + complex retval(ls); + retval *=rs; + return retval; + } + template _UCXXEXPORT complex operator/(const complex& ls, const complex& rs){ + complex retval(ls); + retval/=rs; + return retval; + } + template _UCXXEXPORT complex operator/(const complex& ls, const T& rs){ + complex retval(ls); + retval/=rs; + return retval; + } + template _UCXXEXPORT complex operator/(const T& ls, const complex& rs){ + complex retval(ls); + retval/=rs; + return retval; + } + template _UCXXEXPORT complex operator+(const complex& v){ + return v; + } + template _UCXXEXPORT complex operator-(const complex& v){ + return complex (-v.real(), -v.imag()); + } + template _UCXXEXPORT bool operator==(const complex& ls, const complex& rs){ + if( ls.real() == rs.real() && ls.imag() == rs.image()){ + return true; + } + return false; + } + template _UCXXEXPORT bool operator==(const complex& ls, const T& rs){ + if(ls.real() == rs && ls.imag() == T()){ + return true; + } + return false; + } + template _UCXXEXPORT bool operator==(const T& ls, const complex& rs){ + if(ls == rs.real() && rs.imag() == T()){ + return true; + } + return false; + } + template _UCXXEXPORT bool operator!=(const complex& ls, const complex& rs){ + if(ls == rs){ + return false; + } + return true; + } + template _UCXXEXPORT bool operator!=(const complex& ls, const T& rs){ + if(ls == rs){ + return false; + } + return true; + } + template _UCXXEXPORT bool operator!=(const T& ls, const complex& rs){ + if(ls == rs){ + return false; + } + return true; + } + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, complex& v) + { + T tempr; + T tempi; + is >> tempr; + is.get(); + is >> tempi; + v = complex(tempr, tempi); + return is; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const complex&v) + { + os << v.real() << ", " << v.imag(); + return os; + } + + template _UCXXEXPORT T real(const complex& v){ + return v.real(); + } + + template _UCXXEXPORT T imag(const complex& v){ + return v.imag(); + } + + template _UCXXEXPORT T norm(const complex& v){ + return (v.real() * v.real() + v.imag() * v.imag()); + } + + template _UCXXEXPORT complex conj(const complex& v){ + return complex(v.real(), -v.imag()); + } + +#ifdef __UCLIBCXX_SUPPORT_MATH__ //Can we link with libm? + + template _UCXXEXPORT T abs(const complex& v){ + return sqrt(v.real() * v.real() + v.imag() * v.imag()); + } + + template _UCXXEXPORT T arg(const complex& v){ + return atan2(v.imag(), v.real()); + } + + template _UCXXEXPORT complex polar(const T& rho, const T& theta){ + return complex(rho * cos(theta), rho * sin(theta)); + } + + template _UCXXEXPORT complex cos (const complex& v){ + return complex(cos(v.real()) * cosh(v.imag()), -sin(v.real()) * sinh(v.imag())); + } + + template _UCXXEXPORT complex cosh (const complex& v){ + return complex(cosh(v.real()) * cos(v.imag()), sinh(v.real()) * sin(v.imag())); + } + + template _UCXXEXPORT complex exp (const complex& v){ + return polar(exp(v.real()), v.imag()); + } + + template _UCXXEXPORT complex log (const complex& v){ + return complex(log(abs(v)), arg(v)); + } + + template _UCXXEXPORT complex log10(const complex& v){ + return (log(v) / log(T(10.0))); + } + + template _UCXXEXPORT complex pow(const complex& v, int p){ + T rho = pow(abs(v), p); + T theta = arg(v); + return complex(rho * cos(p * theta), rho * sin(p * theta) ); + } + + template _UCXXEXPORT complex pow(const complex& v, const T& p){ + return polar( pow(abs(v),p), arg(v)*p ); + } + + template _UCXXEXPORT complex pow(const complex& v, const complex& p){ + if(v == T()){ + //We are using "0" as the value + return T(); + } + return exp(p * log(v)); + } + + template _UCXXEXPORT complex pow(const T& v, const complex& p){ + if(v == T()){ + return T(); + } + return polar(pow(v,p.real()), y.imag() * log(x) ); + } + + template _UCXXEXPORT complex sin (const complex& v){ + return complex(sin(v.real()) * cosh(v.imag()), cosh(v.real()) * sin(v.imag())); + } + + template _UCXXEXPORT complex sinh (const complex& v){ + return complext(sinh(v.real()) * cos(v.imag()), cosh(v.real()) * sin(v.imag()) ); + } + + template _UCXXEXPORT complex sqrt (const complex&); + template _UCXXEXPORT complex tan (const complex& v){ + return sin(v) / cos(v); + } + + template _UCXXEXPORT complex tanh (const complex& v){ + return sinh(v) / cosh(v); + } + +#endif + +} + +#endif + diff --git a/misc/uClibc++/include/cxx/csetjmp b/misc/uClibc++/include/cxx/csetjmp new file mode 100644 index 0000000000..a11f932e86 --- /dev/null +++ b/misc/uClibc++/include/cxx/csetjmp @@ -0,0 +1,44 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +#ifndef __STD_HEADER_CSETJMP +#define __STD_HEADER_CSETJMP 1 + + +//From GCC Header files +#undef longjmp + +// Adhere to section 17.4.1.2 clause 5 of ISO 14882:1998 +#ifndef setjmp +#define setjmp(env) setjmp (env) +#endif + +//Mine again + + +namespace std{ + using ::longjmp; + using ::jmp_buf; +} + + +#endif + diff --git a/misc/uClibc++/include/cxx/cwchar b/misc/uClibc++/include/cxx/cwchar new file mode 100644 index 0000000000..03fae09d15 --- /dev/null +++ b/misc/uClibc++/include/cxx/cwchar @@ -0,0 +1,86 @@ +/* Copyright (C) 2006 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation version 2.1 + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include + +#ifndef __HEADER_CWCHAR +#define __HEADER_CWCHAR 1 + + +namespace std{ + using ::mbstate_t; + using ::wint_t; + + using ::btowc; + using ::fgetwc; + using ::fgetws; + using ::fputwc; + using ::fputws; + using ::fwide; + using ::fwprintf; + using ::fwscanf; + using ::getwc; + using ::getwchar; + using ::mbrlen; + using ::mbrtowc; + using ::mbsinit; + using ::mbsrtowcs; + using ::putwc; + using ::putwchar; + using ::swprintf; + using ::swscanf; + using ::ungetwc; + using ::vfwprintf; + using ::vswprintf; + using ::vwprintf; + using ::wcrtomb; + using ::wcscat; + using ::wcschr; + using ::wcscmp; + using ::wcscoll; + using ::wcscpy; + using ::wcscspn; + using ::wcsftime; + using ::wcslen; + using ::wcsncat; + using ::wcsncmp; + using ::wcsncpy; + using ::wcspbrk; + using ::wcsrchr; + using ::wcsrtombs; + using ::wcsspn; + using ::wcsstr; + using ::wcstod; + using ::wcstok; + using ::wcstol; + using ::wcstoul; + using ::wcsxfrm; + using ::wctob; + using ::wmemchr; + using ::wmemcmp; + using ::wmemcpy; + using ::wmemmove; + using ::wmemset; + using ::wprintf; + using ::wscanf; +} + + + +#endif + diff --git a/misc/uClibc++/include/cxx/cwctype b/misc/uClibc++/include/cxx/cwctype new file mode 100644 index 0000000000..5e4b60538b --- /dev/null +++ b/misc/uClibc++/include/cxx/cwctype @@ -0,0 +1,106 @@ +// -*- C++ -*- forwarding header. + +// Copyright (C) 1997, 1998, 1999, 2000, 2001, 2002 +// Free Software Foundation, Inc. +// +// This file is part of the GNU ISO C++ Library. This library is free +// software; you can redistribute it and/or modify it under the +// terms of the GNU General Public License as published by the +// Free Software Foundation; either version 2, or (at your option) +// any later version. + +// This library is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. + +// You should have received a copy of the GNU General Public License along +// with this library; see the file COPYING. If not, write to the Free +// Software Foundation, 59 Temple Place - Suite 330, Boston, MA 02111-1307, +// USA. + +// As a special exception, you may use this file as part of a free software +// library without restriction. Specifically, if other files instantiate +// templates or use macros or inline functions from this file, or you compile +// this file and link it with other files to produce an executable, this +// file does not by itself cause the resulting executable to be covered by +// the GNU General Public License. This exception does not however +// invalidate any other reasons why the executable file might be covered by +// the GNU General Public License. + +// +// ISO C++ 14882: +// + +/** @file cwctype + * This is a Standard C++ Library file. You should @c #include this file + * in your programs, rather than any of the "*.h" implementation files. + * + * This is the C++ version of the Standard C Library header @c wctype.h, + * and its contents are (mostly) the same as that header, but are all + * contained in the namespace @c std. + */ + +#ifndef _CPP_CWCTYPE +#define _CPP_CWCTYPE 1 + +#pragma GCC system_header + +//#include + +#ifdef __UCLIBCXX_HAS_WCHAR__ +#include +#endif + +// Get rid of those macros defined in in lieu of real functions. +#undef iswalnum +#undef iswalpha +#undef iswblank +#undef iswcntrl +#undef iswdigit +#undef iswgraph +#undef iswlower +#undef iswprint +#undef iswprint +#undef iswpunct +#undef iswspace +#undef iswupper +#undef iswxdigit +#undef iswctype +#undef towlower +#undef towupper +#undef towctrans +#undef wctrans +#undef wctype + +#if __UCLIBCXX_HAS_WCHAR__ +namespace std +{ + using ::wint_t; // cwchar + + using ::wctype_t; + using ::wctrans_t; + + using ::iswalnum; + using ::iswalpha; + using ::iswblank; + using ::iswcntrl; + using ::iswdigit; + using ::iswgraph; + using ::iswlower; + using ::iswprint; + using ::iswprint; + using ::iswpunct; + using ::iswspace; + using ::iswupper; + using ::iswxdigit; + using ::iswctype; + using ::towlower; + using ::towupper; + using ::towctrans; + using ::wctrans; + using ::wctype; +} +#endif //__ULIBCXX_HAS_WCHAR__ + +#endif diff --git a/misc/uClibc++/include/cxx/deque b/misc/uClibc++/include/cxx/deque new file mode 100644 index 0000000000..ff07ab51c9 --- /dev/null +++ b/misc/uClibc++/include/cxx/deque @@ -0,0 +1,884 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + + +#include +#include +#include + +#pragma GCC visibility push(default) + +#ifndef __STD_HEADER_DEQUE +#define __STD_HEADER_DEQUE + + +namespace std{ + template > class deque; + template bool operator==(const deque& x, const deque& y); + template bool operator< (const deque& x, const deque& y); + template bool operator!=(const deque& x, const deque& y); + template bool operator> (const deque& x, const deque& y); + template bool operator>=(const deque& x, const deque& y); + template bool operator<=(const deque& x, const deque& y); + template void swap(deque& x, deque& y); + + template class _UCXXEXPORT deque { + public: + friend bool operator==<>(const deque& x, const deque& y); + friend class deque_iter; + friend class deque_citer; + class deque_iter; + class deque_citer; + + typedef typename Allocator::reference reference; + typedef typename Allocator::const_reference const_reference; + typedef deque_iter iterator; + typedef deque_citer const_iterator; + typedef typename Allocator::size_type size_type; + typedef typename Allocator::difference_type difference_type; + typedef T value_type; + typedef Allocator allocator_type; + typedef typename Allocator::pointer pointer; + typedef typename Allocator::const_pointer const_pointer; + typedef std::reverse_iterator reverse_iterator; + typedef std::reverse_iterator const_reverse_iterator; + + explicit deque(const Allocator& al = Allocator()); + explicit deque(size_type n, const T& value = T(), const Allocator& al = Allocator()); + template deque(InputIterator first, InputIterator last, const Allocator& = Allocator()); + deque(const deque& x); + ~deque(); + + deque& operator=(const deque& x); + template void assign(InputIterator first, InputIterator last); + template void assign(Size n, const U& u = U()); + allocator_type get_allocator() const; + + iterator begin(); + const_iterator begin() const; + iterator end(); + const_iterator end() const; + reverse_iterator rbegin(); + const_reverse_iterator rbegin() const; + reverse_iterator rend(); + const_reverse_iterator rend() const; + + size_type size() const; + size_type max_size() const; + void resize(size_type sz, T c = T()); + bool empty() const; + + reference operator[](size_type n); + const_reference operator[](size_type n) const; + reference at(size_type n); + const_reference at(size_type n) const; + reference front(); + const_reference front() const; + reference back(); + const_reference back() const; + + void push_front(const T& x); + void push_back(const T& x); + iterator insert(iterator position, const T& x = T()); + void insert(iterator position, size_type n, const T& x); + template void insert (iterator position, InputIterator first, InputIterator last); + void pop_front(); + void pop_back(); + + iterator erase(iterator position); + iterator erase(iterator first, iterator last); + void swap(deque&); + void clear(); + + protected: + void reserve(size_type n); + inline size_type array_element(size_type deque_element) const{ + if(deque_element < (data_size - first_element)){ + return first_element + deque_element; + } + return deque_element - (data_size - first_element); + } + inline size_type first_subtract(size_type sub_size) const{ + if(sub_size > first_element){ + return (data_size - first_element) - sub_size; + } + return first_element - sub_size; + } + + T * data; + size_type data_size; //Physical size of array + size_type elements; //Elements in array + size_type first_element; //Element number of array 0..n + size_type last_element; //Element number of array 0..n + Allocator a; + + }; + + + template class _UCXXEXPORT deque::deque_iter + : public std::iterator< + random_access_iterator_tag, + T, + typename Allocator::difference_type, + typename Allocator::pointer, + typename Allocator::reference + > + { + friend class deque; + protected: + deque * container; + typename Allocator::size_type element; + + public: + deque_iter() : container(0), element(0) { } + deque_iter(const deque_iter & d) : container (d.container), element(d.element) { } + deque_iter(deque * c, typename Allocator::size_type e) + : container(c), element(e) + { + return; + } + ~deque_iter() { } + deque_iter & operator=(const deque_iter & d){ + container = d.container; + element = d.element; + return *this; + } + T & operator*(){ + return container->data[container->array_element(element)]; + } + T * operator->(){ + return container->data + container->array_element(element); + } + const T & operator*() const{ + return container->data[container->array_element(element)]; + } + const T * operator->() const{ + return container->data + container->array_element(element); + } + bool operator==(const deque_iter & d) const{ + if(container == d.container && element == d.element){ + return true; + } + return false; + } + bool operator==(const deque_citer & d) const{ + if(container == d.container && element == d.element){ + return true; + } + return false; + } + bool operator!=(const deque_iter & d) const{ + if(container != d.container || element != d.element){ + return true; + } + return false; + } + bool operator!=(const deque_citer & d) const{ + if(container != d.container || element != d.element){ + return true; + } + return false; + } + bool operator<(const deque_iter & d) const{ + if(element < d.element){ + return true; + } + return false; + } + bool operator<(const deque_citer & d) const{ + if(element < d.element){ + return true; + } + return false; + } + bool operator<=(const deque_iter & d) const{ + if(element <= d.element){ + return true; + } + return false; + } + bool operator<=(const deque_citer & d) const{ + if(element <= d.element){ + return true; + } + return false; + } + bool operator>(const deque_iter & d) const{ + if(element > d.element){ + return true; + } + return false; + } + bool operator>(const deque_citer & d) const{ + if(element > d.element){ + return true; + } + return false; + } + bool operator>=(const deque_iter & d) const{ + if(element >= d.element){ + return true; + } + return false; + } + bool operator>=(const deque_citer & d) const{ + if(element >= d.element){ + return true; + } + return false; + } + deque_iter & operator++(){ + ++element; + return *this; + } + deque_iter operator++(int){ + deque_iter temp(container, element); + ++element; + return temp; + } + deque_iter operator+(typename Allocator::size_type n){ + deque_iter temp(container, element + n); + return temp; + } + deque_iter & operator+=(typename Allocator::size_type n){ + element += n; + return *this; + } + deque_iter & operator--(){ + --element; + return *this; + } + deque_iter operator--(int){ + deque_iter temp(container, element); + --element; + return temp; + } + deque_iter operator-(typename Allocator::size_type n){ + deque_iter temp(container, element - n); + return temp; + } + deque_iter & operator-=(typename Allocator::size_type n){ + element -= n; + return *this; + } + typename Allocator::size_type operator-(const deque_iter & d){ + return element - d.element; + } + + }; + + template class _UCXXEXPORT deque::deque_citer + : public std::iterator< + random_access_iterator_tag, + T, + typename Allocator::difference_type, + typename Allocator::const_pointer, + typename Allocator::const_reference + > + { + friend class deque; + protected: + const deque * container; + typename Allocator::size_type element; + + public: + deque_citer() : container(0), element(0) { } + deque_citer(const deque_citer & d) : container (d.container), element(d.element) { } + deque_citer(const deque_iter & d) : container (d.container), element(d.element) { } + deque_citer(const deque * c, typename Allocator::size_type e) + : container(c), element(e) + { + return; + } + ~deque_citer() { } + deque_citer & operator=(const deque_iter & d){ + container = d.container; + element = d.element; + return *this; + } + const T & operator*() const{ + return container->data[container->array_element(element)]; + } + const T * operator->() const{ + return container->data + container->array_element(element); + } + bool operator==(const deque_citer & d) const{ + if(container == d.container && element == d.element){ + return true; + } + return false; + } + bool operator==(const deque_iter & d) const{ + if(container == d.container && element == d.element){ + return true; + } + return false; + } + bool operator!=(const deque_citer & d) const{ + if(container != d.container || element != d.element){ + return true; + } + return false; + } + bool operator!=(const deque_iter & d) const{ + if(container != d.container || element != d.element){ + return true; + } + return false; + } + bool operator<(const deque_citer & d) const{ + if(element < d.element){ + return true; + } + return false; + } + bool operator<(const deque_iter & d) const{ + if(element < d.element){ + return true; + } + return false; + } + bool operator<=(const deque_citer & d) const{ + if(element <= d.element){ + return true; + } + return false; + } + bool operator<=(const deque_iter & d) const{ + if(element <= d.element){ + return true; + } + return false; + } + bool operator>(const deque_citer & d) const{ + if(element > d.element){ + return true; + } + return false; + } + bool operator>(const deque_iter & d) const{ + if(element > d.element){ + return true; + } + return false; + } + bool operator>=(const deque_citer & d){ + if(element >= d.element){ + return true; + } + return false; + } + bool operator>=(const deque_iter & d){ + if(element >= d.element){ + return true; + } + return false; + } + deque_citer & operator++(){ + ++element; + return *this; + } + deque_citer operator++(int){ + deque_citer temp(container, element); + ++element; + return temp; + } + deque_citer operator+(typename Allocator::size_type n){ + deque_citer temp(container, element + n); + return temp; + } + deque_citer & operator+=(typename Allocator::size_type n){ + element += n; + return *this; + } + deque_citer & operator--(){ + --element; + return *this; + } + deque_citer operator--(int){ + deque_citer temp(container, element); + --element; + return temp; + } + deque_citer operator-(typename Allocator::size_type n){ + deque_citer temp(container, element - n); + return temp; + } + deque_citer & operator-=(typename Allocator::size_type n){ + element -= n; + return *this; + } + typename Allocator::size_type operator-(const deque_citer & d){ + return element - d.element; + } + + }; + + template deque::deque(const Allocator& al) + : data(0), + data_size(0), elements(0), first_element(0), last_element(0), a(al) + { + data_size = __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + first_element = data_size /2; + last_element = first_element; + } + + + template deque::deque( + size_type n, const T& value, const Allocator& al) + : data(0), + elements(n), first_element(0), last_element(0), a(al) + { + data_size = elements + __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + first_element = (data_size - elements) / 2; + last_element = first_element; + + for(n=first_element ; n < last_element; ++n ){ + a.construct(data+n, value); + } + } + + + template template + deque::deque(InputIterator first, InputIterator last, const Allocator& al) + : data(0), + data_size(0), elements(0), first_element(0), last_element(0), a(al) + { + data_size = __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + first_element = data_size / 4; //Note sure how big, but let's add a little space... + last_element = first_element; + while(first != last){ + push_back(*first); + ++first; + } + } + + + template deque::deque(const deque& x) + : data(0), + elements(0), first_element(0), last_element(0), a(x.a) + { + data_size = x.elements + __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + first_element = (data_size - x.elements) / 2; + last_element = first_element; + for(size_type i=0; i < x.elements; ++i){ + push_back(x[i]); + } + } + + + template deque::~deque(){ + clear(); + a.deallocate(data, data_size); + } + + template deque& deque:: + operator=(const deque& x) + { + if(&x == this){ + return *this; + } + resize(x.elements); + for(size_t i = 0; i < elements; ++i){ + data[array_element(i)] = x[i]; + } + return *this; + } + + + template template void + deque::assign(InputIterator first, InputIterator last) + { + clear(); + while(first !=last){ + push_back(*first); + ++first; + } + } + + + template template void + deque::assign(Size n, const U& u) + { + if(&u == this){ + return; + } + clear(); + for(size_type i = 0; i < n; ++i){ + push_back(u); + } + } + + + template typename deque::allocator_type + deque::get_allocator() const + { + return a; + } + + template typename + deque::iterator deque::begin() + { + return deque_iter(this, 0); + } + + + template typename deque::const_iterator + deque::begin() const + { + return deque_citer(this, 0); + } + + template typename + deque::iterator deque::end() + { + return deque_iter(this, elements); + } + + template typename + deque::const_iterator deque::end() const + { + return deque_citer(this, elements); + } + + template typename + deque::reverse_iterator deque::rbegin() + { + return reverse_iterator(end()); + } + + template typename + deque::const_reverse_iterator deque::rbegin() const + { + return const_reverse_iterator(end()); + } + + template typename + deque::reverse_iterator deque::rend() + { + return reverse_iterator(begin()); + } + + template typename + deque::const_reverse_iterator deque::rend() const + { + return const_reverse_iterator(begin()); + } + + template typename + deque::size_type deque::size() const + { + return elements; + } + + template typename + deque::size_type deque::max_size() const + { + return ((size_type)(-1)) / sizeof(T); + } + + template void deque::resize(size_type sz, T c){ + reserve(sz); + while(sz > size()){ + push_back(c); + } + while(sz < size()){ + pop_back(); + } + } + + template bool deque::empty() const{ + return (elements == 0); + } + + template typename + deque::reference deque::operator[](size_type n) + { + return data[array_element(n)]; + } + + template typename + deque::const_reference deque::operator[](size_type n) const + { + return data[array_element(n)]; + } + + template typename + deque::reference deque::at(size_type n) + { + if(n > elements){ + __throw_out_of_range("Out of deque range"); + } + return data[array_element(n)]; + } + + template typename + deque::const_reference deque::at(size_type n) const + { + if(n > elements){ + __throw_out_of_range("Out of deque range"); + } + return data[array_element(n)]; + } + + template typename + deque::reference deque::front() + { + return data[first_element]; + } + + template typename + deque::const_reference deque::front() const + { + return data[first_element]; + } + + template typename + deque::reference deque::back() + { + return data[array_element(elements-1)]; + } + + template typename + deque::const_reference deque::back() const + { + return data[array_element(elements-1)]; + } + + template void deque::push_front(const T& x){ + reserve(elements + 1); + first_element = first_subtract(1); + a.construct(data + first_element, x); + ++elements; + } + + template void deque::push_back(const T& x){ + reserve(elements + 1); + a.construct(data + last_element, x); + ++elements; + last_element = array_element(elements); + } + + template typename + deque::iterator deque::insert(iterator position, const T& x) + { + reserve(elements+1); + if(position.element > (elements/2)){ + //Push all elements back 1 + push_back(x); + for(size_type i = elements-1; i > position.element; --i){ + at(i) = at(i-1); + } + }else{ + //Push all elements forward 1 + push_front(x); + for(size_type i = 0; i < position.element; ++i){ + at(i) = at(i+1); + } + } + at(position.element) = x; + return deque_iter(this, position.element); + } + + template void deque:: + insert(typename deque::iterator position, size_type n, const T& x) + { + reserve(elements + n); + for(size_t i =0; i < n; ++i){ + position = insert(position, x); + } + } + + template template + void deque::insert (iterator position, InputIterator first, InputIterator last) + { + while(first != last){ + position = insert(position, *first); + ++first; + } + } + + template void deque::pop_front(){ + if(elements == 0){ + __throw_out_of_range("deque pop_front"); + } + a.destroy(data + first_element); + first_element = array_element(1); + --elements; + } + + template void deque::pop_back(){ + last_element = array_element(elements - 1); + a.destroy(data + last_element); + --elements; + } + + template typename + deque::iterator deque::erase(typename deque::iterator position) + { + if(position.element > (elements /2)){ + for(size_type i = position.element; i < elements - 1; ++i){ + at(i) = at(i+1); + } + pop_back(); + }else{ + for(size_type i = position.element; i > 0; --i){ + at(i) = at(i-1); + } + pop_front(); + } + return deque_iter(this, position.element); + } + + template typename deque::iterator + deque:: + erase(typename deque::iterator first, typename deque::iterator last) + { + //Shift backwards + size_type num_move = last.element - first.element; + if( first.element > (elements - last.element) ){ + for(size_type i = last.element; i < elements ; ++i){ + at(i-num_move) = at(i); + } + for(size_type i = 0; i < num_move ; ++i){ + pop_back(); + } + }else{ + for(size_type i = 0; i < first.element ; ++i){ + at(last.element - i - 1) = at(first.element - i - 1); + } + for(size_type i = 0; i < num_move ; ++i){ + pop_front(); + } + } + return deque_iter(this, first.element); + } + + template void deque::swap(deque& x) + { + T * temp_data; + typename deque::size_type temp_size; + + //Swap data pointers + temp_data = x.data; + x.data = data; + data = temp_data; + + //Swap array sizes + temp_size = x.data_size; + x.data_size = data_size; + data_size = temp_size; + + //Swap num array elements + temp_size = x.elements; + x.elements = elements; + elements = temp_size; + + //Swap first_pointer + temp_size = x.first_element; + x.first_element = first_element; + first_element = temp_size; + + //Swap last_pointer + temp_size = x.last_element; + x.last_element = last_element; + last_element = temp_size; + } + + template void deque::clear() + { + while(elements > 0 ){ + pop_back(); + } + } + + + template void deque::reserve(typename deque::size_type n) + { + if(data_size >= n){ + return; + } + + size_type size_temp; + size_type first_temp; + T * data_temp; + size_temp = n + __UCLIBCXX_STL_BUFFER_SIZE__; //Reserve extra 'cause we can + data_temp = a.allocate(size_temp); + + first_temp = (size_temp - elements) / 2; + for(size_type i = 0; i < elements; ++i){ + a.construct(data_temp + first_temp + i, data[array_element(i)]); + a.destroy(data + array_element(i)); + } + + //Now shuffle pointers + a.deallocate(data, data_size); + data = data_temp; + data_size = size_temp; + first_element = first_temp; + last_element = first_element + elements; + } + + + template _UCXXEXPORT + bool + operator==(const deque& x, const deque& y) + { + if(x.elements != y.elements){ + return false; + } + for(typename deque::size_type i = 0; i < x.elements; ++i){ + if(x[i] < y[i] || y[i] < x[i]){ + return false; + } + } + return true; + } + + template bool operator< (const deque& x, const deque& y); + template _UCXXEXPORT + bool + operator!=(const deque& x, const deque& y) + { + if(x == y){ + return false; + } + return true; + } + template bool operator> (const deque& x, const deque& y); + template bool operator>=(const deque& x, const deque& y); + template bool operator<=(const deque& x, const deque& y); + template _UCXXEXPORT void swap(deque& x, deque& y){ + x.swap(y); + } + + + +} + +#pragma GCC visibility pop + +#endif + + + + diff --git a/misc/uClibc++/include/cxx/exception b/misc/uClibc++/include/cxx/exception new file mode 100644 index 0000000000..bdf393e6cc --- /dev/null +++ b/misc/uClibc++/include/cxx/exception @@ -0,0 +1,120 @@ +// Exception Handling support header for -*- C++ -*- + +// Copyright (C) 1995, 1996, 1997, 1998, 2000, 2001, 2002 +// Free Software Foundation +// +// This file is part of GNU CC. +// +// GNU CC is free software; you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation; either version 2, or (at your option) +// any later version. +// +// GNU CC is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with GNU CC; see the file COPYING. If not, write to +// the Free Software Foundation, 59 Temple Place - Suite 330, +// Boston, MA 02111-1307, USA. + +// As a special exception, you may use this file as part of a free software +// library without restriction. Specifically, if other files instantiate +// templates or use macros or inline functions from this file, or you compile +// this file and link it with other files to produce an executable, this +// file does not by itself cause the resulting executable to be covered by +// the GNU General Public License. This exception does not however +// invalidate any other reasons why the executable file might be covered by +// the GNU General Public License. + +/** @file exception + * This header defines several types and functions relating to the + * handling of exceptions in a C++ program. + */ + +#ifndef __EXCEPTION__ +#define __EXCEPTION__ + +#include + +extern "C++" { + +namespace std +{ + /** + * @brief Base class for all library exceptions. + * + * This is the base class for all exceptions thrown by the standard + * library, and by certain language expressions. You are free to derive + * your own %exception classes, or use a different hierarchy, or to + * throw non-class data (e.g., fundamental types). + */ + class exception + { + public: + exception() throw() { } + virtual ~exception() throw(); + /** Returns a C-style character string describing the general cause + * of the current error. */ + virtual const char* what() const throw(); + }; + + /** If an %exception is thrown which is not listed in a function's + * %exception specification, one of these may be thrown. */ + class bad_exception : public exception + { + public: + bad_exception() throw() { } + // This declaration is not useless: + // http://gcc.gnu.org/onlinedocs/gcc-3.0.2/gcc_6.html#SEC118 + virtual ~bad_exception() throw(); + }; + + /// If you write a replacement %terminate handler, it must be of this type. + typedef void (*terminate_handler) (); + /// If you write a replacement %unexpected handler, it must be of this type. + typedef void (*unexpected_handler) (); + + /// Takes a new handler function as an argument, returns the old function. + terminate_handler set_terminate(terminate_handler) throw(); + /** The runtime will call this function if %exception handling must be + * abandoned for any reason. */ + void terminate() __UCLIBCXX_NORETURN; + + /// Takes a new handler function as an argument, returns the old function. + unexpected_handler set_unexpected(unexpected_handler) throw(); + /** The runtime will call this function if an %exception is thrown which + * violates the function's %exception specification. */ + void unexpected() __UCLIBCXX_NORETURN; + + /** [18.6.4]/1: "Returns true after completing evaluation of a + * throw-expression until either completing initialization of the + * exception-declaration in the matching handler or entering @c unexpected() + * due to the throw; or after entering @c terminate() for any reason + * other than an explicit call to @c terminate(). [Note: This includes + * stack unwinding [15.2]. end note]" + * + * 2: "When @c uncaught_exception() is true, throwing an %exception can + * result in a call of @c terminate() (15.5.1)." + */ + bool uncaught_exception() throw(); +} // namespace std + +namespace __gnu_cxx +{ + /** A replacement for the standard terminate_handler which prints more + information about the terminating exception (if any) on stderr. Call + @code + std::set_terminate (__gnu_cxx::__verbose_terminate_handler) + @endcode + to use. For more info, see + http://gcc.gnu.org/onlinedocs/libstdc++/19_diagnostics/howto.html#4 + */ + void __verbose_terminate_handler (); +} // namespace __gnu_cxx + +} // extern "C++" + +#endif diff --git a/misc/uClibc++/include/cxx/fstream b/misc/uClibc++/include/cxx/fstream new file mode 100644 index 0000000000..b8dd602c2d --- /dev/null +++ b/misc/uClibc++/include/cxx/fstream @@ -0,0 +1,676 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#ifndef __STD_HEADER_FSTREAM +#define __STD_HEADER_FSTREAM 1 + + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#ifdef __UCLIBCXX_HAS_WCHAR__ +#include +#include +#endif //__UCLIBCXX_HAS_WCHAR__ + +#pragma GCC visibility push(default) + +namespace std{ + + template class basic_filebuf; + + typedef basic_filebuf filebuf; +#ifdef __UCLIBCXX_HAS_WCHAR__ + typedef basic_filebuf wfilebuf; +#endif + + + template class _UCXXEXPORT basic_filebuf + : public basic_streambuf + { +#ifdef __UCLIBCXX_SUPPORT_CDIR__ + friend ios_base::Init::Init(); //Needed for cout/cin stuff +#endif + public: + // Types (inherited from basic_streambuf: + typedef typename basic_streambuf::char_type char_type; + typedef typename basic_streambuf::int_type int_type; + typedef typename basic_streambuf::pos_type pos_type; + typedef typename basic_streambuf::off_type off_type; + typedef traits traits_type; + + //Constructors/destructor: + + _UCXXEXPORT basic_filebuf() : basic_streambuf(), fp(0), pbuffer(0), gbuffer(0) + { + append=false; + pbuffer = new char_type[__UCLIBCXX_IOSTREAM_BUFSIZE__]; + gbuffer = new char_type[__UCLIBCXX_IOSTREAM_BUFSIZE__]; + + this->setp(pbuffer, pbuffer + __UCLIBCXX_IOSTREAM_BUFSIZE__); + //Position get buffer so that there is no data available + this->setg(gbuffer, gbuffer + __UCLIBCXX_IOSTREAM_BUFSIZE__, + gbuffer + __UCLIBCXX_IOSTREAM_BUFSIZE__); + } + + + _UCXXEXPORT virtual ~basic_filebuf(){ + sync(); + close(); + delete [] pbuffer; + delete [] gbuffer; + pbuffer = 0; + gbuffer = 0; + } + + + //Members: + + _UCXXEXPORT bool is_open() const{ + if(fp == 0){ + return false; + } + return true; + } + + _UCXXEXPORT basic_filebuf* open(const char* s, ios_base::openmode mode){ + bool move_end = (mode & ios_base::ate) != 0; + if(is_open() !=false){ //Must call close() first + return 0; + } + basic_streambuf::openedFor = mode; + mode = mode & ~ios_base::ate; + + if(mode == ios_base::out || mode == (ios_base::out | ios_base::trunc)){ + fp = fopen(s, "w" ); + }else if((mode & ios_base::app) && ! (mode & ios_base::trunc)){ + if(mode & ios_base::binary){ + if(mode & ios_base::in){ + fp = fopen(s, "a+b"); + }else{ + fp = fopen(s, "ab"); + } + }else{ + if(mode & ios_base::in){ + fp = fopen(s, "a+"); + }else{ + fp = fopen(s, "a"); + } + } + }else if(mode == ios_base::in){ + fp = fopen(s, "r"); + }else if(mode == (ios_base::in | ios_base::out)){ + fp = fopen(s, "r+"); + }else if(mode == (ios_base::in | ios_base::out | ios_base::trunc)){ + fp = fopen(s, "w+"); + }else if(mode == (ios_base::binary | ios_base::out)){ + fp = fopen(s, "wb"); + }else if(mode == (ios_base::in | ios_base::binary)){ + fp = fopen(s, "rb"); + }else if(mode == (ios_base::in | ios_base::binary | ios_base::out)){ + fp = fopen(s, "r+b"); + }else if(mode==(ios_base::binary | ios_base::out | ios_base::trunc)){ + fp = fopen(s, "w+b"); + }else if(mode == (ios_base::in | ios_base::binary | ios_base::out | ios_base::trunc)){ + fp = fopen(s, "w+b"); + } + + if(fp == 0){ + return 0; + } + if(ferror(fp)){ + fclose(fp); + fp=0; + return 0; + } + int retval = 0; + + //Check to make sure the stream is good + if(move_end == true){ + retval = fseek(fp, 0, SEEK_END); + }else{ + retval = fseek(fp, 0, SEEK_SET); + } + if(retval!=0){ //Seek error + fclose(fp); + fp=0; + return 0; + } + + basic_streambuf::mgnext = basic_streambuf::mgend; + + return this; + } + _UCXXEXPORT basic_filebuf* close(){ + if(fp != 0 && fp != stdin && fp != stdout && fp !=stderr ){ + overflow(); + sync(); + int retval = fclose(fp); + if(retval !=0){ //Error of some sort + return 0; + } + fp=0; + } + return this; + } + protected: + _UCXXEXPORT basic_filebuf(const basic_filebuf &){ } + _UCXXEXPORT basic_filebuf & operator=(const basic_filebuf &){ return *this; } + + //Overridden virtual functions: + + virtual _UCXXEXPORT int showmanyc(){ + return basic_streambuf::egptr() - basic_streambuf::gptr(); + } + virtual _UCXXEXPORT int_type underflow(){ + /* Some variables used internally: + Buffer pointers: + charT * mgbeg; + charT * mgnext; + charT * mgend; + + eback() returns mgbeg + gptr() returns mgnext + egptr() returns mgend + + gbump(int n) mgnext+=n + + */ + + if(!is_open()){ + return traits::eof(); + } + + if(basic_streambuf::eback() == 0){ + //No buffer, so... + charT c; + int retval; + retval = fread(&c, sizeof(charT), 1, fp); + + if(retval == 0 || feof(fp) || ferror(fp) ){ + return traits::eof(); + } + return traits::to_int_type(c); + } + + if(basic_streambuf::eback() == basic_streambuf::gptr()){ //Buffer is full + return traits::to_int_type(*basic_streambuf::gptr()); + } + //Shift entire buffer back to the begining + size_t offset = basic_streambuf::gptr() - basic_streambuf::eback(); + size_t amountData = basic_streambuf::egptr() - basic_streambuf::gptr(); + + for(charT * i = basic_streambuf::gptr(); i < basic_streambuf::egptr(); ++i){ + *(i-offset) = *i; + } + + size_t retval = 0; + //Save operating flags from file descriptor + int fcntl_flags = fcntl(fileno(fp), F_GETFL); + retval = 0; + + //Set to non_blocking mode + fcntl(fileno(fp), F_SETFL, fcntl_flags | O_NONBLOCK); + + //Fill rest of buffer + retval = fread(basic_streambuf::egptr() - + basic_streambuf::gptr() + basic_streambuf::eback(), + sizeof(charT), + offset, + fp + ); + + //Clear problems where we didn't read in enough characters + if(EAGAIN == errno){ + clearerr(fp); + } + + //Restore file descriptor clase + fcntl(fileno(fp), F_SETFL, fcntl_flags); + + //Now we are going to make sure that we read in at least one character. The hard way. + if(retval == 0){ + fcntl_flags = fcntl(fileno(fp), F_GETFL); + //Set to blocking mode + fcntl(fileno(fp), F_SETFL, fcntl_flags & ~O_NONBLOCK); + + retval = fread(basic_streambuf::egptr() - + basic_streambuf::gptr() + basic_streambuf::eback(), + sizeof(charT), + 1, + fp + ); + + //Restore file descriptor clase + fcntl(fileno(fp), F_SETFL, fcntl_flags); + + } + + if(retval !=offset){ //Slide buffer forward again + for(size_t i = 0; i < amountData + retval; ++i){ + *(basic_streambuf::egptr() - i - 1) = + *(basic_streambuf::eback() + amountData + retval - i - 1); + } + } + + basic_streambuf::mgnext -= retval; + + if( (retval <= 0 && feof(fp)) || ferror(fp) ){ + return traits::eof(); + } + + return traits::to_int_type(*basic_streambuf::gptr()); + } + virtual _UCXXEXPORT int_type uflow(){ + bool dobump = (basic_streambuf::gptr() != 0); + int_type retval = underflow(); + if(dobump){ + basic_streambuf::gbump(1); + } + return retval; + } + virtual _UCXXEXPORT int_type pbackfail(int_type c = traits::eof()){ + if(is_open() == false || + basic_streambuf::gptr() == basic_streambuf::eback()) + { + return traits::eof(); + } + if(traits::eq_int_type(c,traits::eof()) == false){ + if(traits::eq(traits::to_char_type(c), basic_streambuf::gptr()[-1]) == true){ + basic_streambuf::gbump(-1); + }else{ + basic_streambuf::gbump(-1); + basic_streambuf::gptr()[0] = c; + } + return c; + }else{ + basic_streambuf::gbump(-1); + return traits::not_eof(c); + } + } + + virtual _UCXXEXPORT int_type overflow(int_type c = traits::eof()){ + if(is_open() == false){ + //Can't do much + return traits::eof(); + } + if(basic_streambuf::pbase() == 0){ //Unbuffered - elliminate dupe code below + if(fputc(c, fp) == EOF){ + return traits::eof(); + } + return c; + } + if(basic_streambuf::pbase() == 0 && traits::eq_int_type(c,traits::eof()) ){ + //Nothing to flush + return traits::not_eof(c); + } + size_t r = basic_streambuf::pptr() - basic_streambuf::pbase(); + + if( r == 0 && traits::eq_int_type(c,traits::eof()) ){ + return traits::not_eof(c); + }else if (r == 0 ){ + if(fputc(c, fp) == EOF){ + return traits::eof(); + } + return c; + } + + size_t totalChars = r; + + char_type *buffer = 0; + if(traits::eq_int_type(c,traits::eof())){ + buffer = new char_type[r]; + }else{ + buffer = new char_type[r+1]; + buffer[r] = c; + totalChars++; + } + + traits::copy(buffer, basic_streambuf::pbase(), r); +// memcpy(buffer, basic_streambuf::pbase(), r); + + size_t retval = fwrite(buffer, sizeof(charT), totalChars, fp); + if(retval !=totalChars){ + if(retval == 0){ + delete [] buffer; + return traits::eof(); + } + basic_streambuf::pbump(-retval); + fprintf(stderr, "***** Did not write the full buffer out. Should be: %d, actually: %d\n", + totalChars, retval); + }else{ + basic_streambuf::pbump(-r); + } + + delete [] buffer; + return traits::not_eof(c); + } + + virtual _UCXXEXPORT basic_streambuf* setbuf(char_type* s, streamsize n){ + if(s == 0 && n == 0){ //Unbuffered + if(pbuffer !=0){ + delete [] pbuffer; + } + if(gbuffer !=0){ + delete [] gbuffer; + } + pbuffer = 0; + gbuffer = 0; + }else if(basic_streambuf::gptr() !=0 && + basic_streambuf::gptr()==basic_streambuf::egptr()) + { + delete [] pbuffer; + pbuffer = s; + } + return this; + } + virtual _UCXXEXPORT pos_type seekoff(off_type off, ios_base::seekdir way, + ios_base::openmode = ios_base::in | ios_base::out) + { + if(is_open() == false){ + return -1; + } + int whence = SEEK_SET; // if(way == basic_ios::beg) + off_type position = off; + + if(way == basic_ios::cur){ + whence = SEEK_CUR; + position -= (basic_streambuf::egptr() - basic_streambuf::gptr()); + }else if(way == basic_ios::end){ + whence = SEEK_END; + } + + sync(); + + int retval = fseek( + fp, + sizeof(charT)*(position), + whence + ); + + //Invalidate read buffer + basic_streambuf::gbump( + basic_streambuf::egptr() - basic_streambuf::gptr() + ); + + if(-1 != retval){ + retval = ftell(fp); + } + + return retval; + } + virtual _UCXXEXPORT pos_type seekpos(pos_type sp, ios_base::openmode = ios_base::in | ios_base::out){ + if(is_open() == false){ + return -1; + } + sync(); + + int retval = fseek(fp,sizeof(charT)* sp, SEEK_SET); + + //Invalidate read buffer + basic_streambuf::gbump(basic_streambuf::egptr() - basic_streambuf::gptr()); + if(retval > -1){ + return sp; + } + return -1; + } + virtual _UCXXEXPORT int sync(){ + if(pbuffer !=0){ + if(overflow() == traits::eof()){ + return -1; + } + } + if(0 != fp && 0 != fflush(fp)){ + return -1; + } + return 0; + } + virtual _UCXXEXPORT void imbue(const locale&){ + return; + } + + + virtual _UCXXEXPORT streamsize xsputn(const char_type* s, streamsize n){ + if(is_open() == false){ + return 0; + } + //Check to see if buffered + + //Check to see if we can buffer the data + streamsize buffer_avail = basic_streambuf::epptr() - basic_streambuf::pptr(); + + if(n > buffer_avail){ //Flush buffer and write directly + overflow(); //Flush the buffer + return fwrite(s, sizeof(charT), n, fp); + } + + //Add to buffer to be written later + + traits::copy(basic_streambuf::pptr(), s, n); + basic_streambuf::pbump(n); + + return n; + } + + FILE * fp; + char_type * pbuffer; + char_type * gbuffer; + bool append; + }; + + +#ifdef __UCLIBCXX_HAS_WCHAR__ + +template <> _UCXXEXPORT basic_filebuf >::int_type + basic_filebuf >::overflow(int_type c); + +template <> _UCXXEXPORT basic_filebuf >::int_type + basic_filebuf >::underflow(); + +#endif //__UCLIBCXX_HAS_WCHAR__ + + + +#ifdef __UCLIBCXX_EXPAND_FSTREAM_CHAR__ +#ifndef __UCLIBCXX_COMPILE_FSTREAM__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT filebuf::basic_filebuf(); + template <> _UCXXEXPORT filebuf::~basic_filebuf(); + +#endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT filebuf::int_type filebuf::pbackfail(filebuf::int_type c); + template <> _UCXXEXPORT filebuf * filebuf::open(const char* s, ios_base::openmode mode); + template <> _UCXXEXPORT filebuf * filebuf::close(); + template <> _UCXXEXPORT filebuf::int_type filebuf::overflow(filebuf::int_type c); + template <> _UCXXEXPORT filebuf::int_type filebuf::underflow (); + + template <> _UCXXEXPORT basic_streambuf > * filebuf::setbuf(char * s, streamsize n); + template <> _UCXXEXPORT streamsize filebuf::xsputn(const char* s, streamsize n); + +#endif +#endif + + + template class _UCXXEXPORT basic_ifstream + : public basic_istream + { + public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + _UCXXEXPORT basic_ifstream(): basic_ios(&sb), basic_istream(&sb){ + //Passing the address of sb + } + explicit _UCXXEXPORT basic_ifstream(const char* s, ios_base::openmode mode = ios_base::in) + : basic_ios(&sb), basic_istream(&sb) + { + if(sb.open(s, mode) == 0){ + basic_ios::setstate(ios_base::failbit); + } + } + + virtual _UCXXEXPORT ~basic_ifstream(){ + + } + + _UCXXEXPORT basic_filebuf* rdbuf() const{ + return (basic_filebuf*)&sb; + } + _UCXXEXPORT bool is_open() const{ + return sb.is_open(); + } + _UCXXEXPORT void open(const char* s, ios_base::openmode mode = ios_base::in){ + if(sb.open(s, mode) == 0){ + basic_ios::setstate(ios_base::failbit); + } + } + _UCXXEXPORT void close(){ + sb.close(); + } + private: + basic_filebuf sb; + }; + + + template class _UCXXEXPORT basic_ofstream + : public basic_ostream + { + public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + _UCXXEXPORT basic_ofstream() : basic_ios(&sb), basic_ostream(&sb){ + + } + + virtual _UCXXEXPORT ~basic_ofstream(); + + explicit _UCXXEXPORT basic_ofstream(const char* s, ios_base::openmode mode = ios_base::out | ios_base::trunc) : + basic_ios(&sb), basic_ostream(&sb) + { + if(sb.open(s, mode | ios_base::out ) == 0){ + basic_ios::setstate(ios_base::failbit); + } + } + + _UCXXEXPORT basic_filebuf* rdbuf() const{ + return (basic_filebuf*)&sb; + } + + _UCXXEXPORT bool is_open() const{ + return sb.is_open(); + } + _UCXXEXPORT void open(const char* s, ios_base::openmode mode = ios_base::out | ios_base::trunc){ + if(sb.open(s, mode) == 0){ + basic_ios::setstate(ios_base::failbit); + } + } + _UCXXEXPORT void close(){ + sb.close(); + } + private: + basic_filebuf sb; + }; + + template _UCXXEXPORT basic_ofstream::~basic_ofstream(){ + basic_ostream::flush(); + } + + + template class _UCXXEXPORT basic_fstream + : public basic_iostream + { + public: + typedef charT char_type; + typedef typename traits::int_type ins_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + _UCXXEXPORT basic_fstream(): basic_ios(&sb), basic_iostream(&sb){ } + + explicit _UCXXEXPORT basic_fstream(const char* s, ios_base::openmode mode = ios_base::in|ios_base::out): + basic_ios(&sb), basic_iostream(&sb) + { + if(sb.open(s, mode) == 0){ + basic_ios::setstate(ios_base::failbit); + } + } + + _UCXXEXPORT basic_filebuf* rdbuf() const{ + return (basic_filebuf*)&sb; + } + _UCXXEXPORT bool is_open() const{ + return sb.is_open(); + } + _UCXXEXPORT void open(const char* s, ios_base::openmode mode = ios_base::in|ios_base::out){ + if(sb.open(s, mode) == 0){ + basic_ios::setstate(ios_base::failbit); + } + } + _UCXXEXPORT void close(){ + sb.close(); + } + private: + basic_filebuf sb; + }; + + + +#ifdef __UCLIBCXX_EXPAND_FSTREAM_CHAR__ +#ifndef __UCLIBCXX_COMPILE_FSTREAM__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT basic_ofstream >::basic_ofstream(); + template <> _UCXXEXPORT basic_ofstream >::basic_ofstream(const char* s, ios_base::openmode mode); + template <> _UCXXEXPORT basic_ofstream >::~basic_ofstream(); + + template <> _UCXXEXPORT basic_ifstream >::basic_ifstream(); + template <> _UCXXEXPORT basic_ifstream >::basic_ifstream(const char* s, ios_base::openmode mode); + template <> _UCXXEXPORT basic_ifstream >::~basic_ifstream(); + +#endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + +#endif +#endif + + + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/func_exception b/misc/uClibc++/include/cxx/func_exception new file mode 100644 index 0000000000..1b7bdd8c50 --- /dev/null +++ b/misc/uClibc++/include/cxx/func_exception @@ -0,0 +1,41 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include + + +#ifndef HEADER_IMPLEMENTATION_FUNC_EXCEPTION +#define HEADER_IMPLEMENTATION_FUNC_EXCEPTION + +#pragma GCC visibility push(default) + +namespace std{ + + _UCXXEXPORT void __throw_bad_alloc(); + _UCXXEXPORT void __throw_out_of_range(const char * message = 0); + _UCXXEXPORT void __throw_overflow_error(const char * message = 0); + _UCXXEXPORT void __throw_length_error(const char * message = 0); + _UCXXEXPORT void __throw_invalid_argument(const char * message = 0); +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/functional b/misc/uClibc++/include/cxx/functional new file mode 100644 index 0000000000..b7932e2cf9 --- /dev/null +++ b/misc/uClibc++/include/cxx/functional @@ -0,0 +1,439 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + + +#ifndef __STD_HEADER_FUNCTIONAL +#define __STD_HEADER_FUNCTIONAL 1 + +#include + +#pragma GCC visibility push(default) + +namespace std{ + + template struct unary_function; + template struct binary_function; + + template struct plus; + template struct minus; + template struct multiplies; + template struct divides; + template struct modulus; + template struct negate; + + template struct equal_to; + template struct not_equal_to; + template struct greater; + template struct less; + template struct greater_equal; + template struct less_equal; + + template struct logical_and; + template struct logical_or; + template struct logical_not; + + template struct unary_negate; + template unary_negate not1(const Predicate&); + template struct binary_negate; + template binary_negate not2(const Predicate&); + + + template class binder1st; + template binder1st bind1st(const Operation&, const T&); + template class binder2nd; + template binder2nd bind2nd(const Operation&, const T&); + + template class pointer_to_unary_function; + template pointer_to_unary_function ptr_fun(Result (*)(Arg)); + template class pointer_to_binary_function; + template + pointer_to_binary_function ptr_fun(Result (*)(Arg1,Arg2)); + + template class mem_fun_t; + template class mem_fun1_t; + template class const_mem_fun_t; + template class const_mem_fun1_t; + template mem_fun_t mem_fun(S (T::*f)()); + template mem_fun1_t mem_fun(S (T::*f)(A)); + template class mem_fun_ref_t; + template class mem_fun1_ref_t; + template mem_fun_ref_t mem_fun_ref(S (T::*f)()); + template mem_fun1_ref_t mem_fun1_ref(S (T::*f)(A)); + + //Implementation + + template struct _UCXXEXPORT unary_function{ + typedef Arg argument_type; + typedef Result result_type; + }; + + + template struct _UCXXEXPORT binary_function{ + typedef Arg1 first_argument_type; + typedef Arg2 second_argument_type; + typedef Result result_type; + }; + + template struct _UCXXEXPORT plus : binary_function{ + T operator()(const T& x, const T& y) const{ + return x + y; + } + }; + + template struct _UCXXEXPORT minus : binary_function{ + T operator()(const T& x, const T& y) const{ + return x - y; + } + }; + + template struct _UCXXEXPORT multiplies : binary_function{ + T operator()(const T& x, const T& y) const{ + return x * y; + } + }; + + template struct _UCXXEXPORT divides : binary_function{ + T operator()(const T& x, const T& y) const{ + return x / y; + } + }; + + template struct _UCXXEXPORT modulus : binary_function{ + T operator()(const T& x, const T& y) const{ + return x % y; + } + }; + + template struct _UCXXEXPORT negate : unary_function{ + T operator()(const T& x) const{ + return -x; + } + }; + + template struct _UCXXEXPORT equal_to : binary_function{ + bool operator()(const T& x, const T& y) const{ + return (x == y); + } + }; + + template struct _UCXXEXPORT not_equal_to : binary_function{ + bool operator()(const T& x, const T& y) const{ + return (x != y); + } + }; + + template struct _UCXXEXPORT greater : binary_function{ + bool operator()(const T& x, const T& y) const{ + return (x > y); + } + }; + + template struct _UCXXEXPORT less : binary_function{ + bool operator()(const T& x, const T& y) const{ + return (x < y); + } + }; + + template struct _UCXXEXPORT greater_equal : binary_function{ + bool operator()(const T& x, const T& y) const{ + return (x >= y); + } + }; + + template struct _UCXXEXPORT less_equal : binary_function{ + bool operator()(const T& x, const T& y) const{ + return (x <= y); + } + }; + + template struct _UCXXEXPORT logical_and : binary_function { + bool operator()(const T& x, const T& y) const{ + return (x && y); + } + }; + + template struct _UCXXEXPORT logical_or : binary_function { + bool operator()(const T& x, const T& y) const{ + return (x || y); + } + }; + + template struct _UCXXEXPORT logical_not : unary_function { + bool operator()(const T& x) const{ + return !x; + } + }; + + template class _UCXXEXPORT unary_negate + : public unary_function + { + public: + explicit unary_negate(const Predicate& pred) : p(pred) { } + bool operator()(const typename Predicate::argument_type& x) const{ + return !p(x); + } + private: + Predicate p; + }; + + + template _UCXXEXPORT unary_negate not1(const Predicate& pred){ + return unary_negate(pred); + } + + + template class _UCXXEXPORT binary_negate : public + binary_function + { + public: + explicit binary_negate(const Predicate& pred) : p(pred) { } + bool operator()(const typename Predicate::first_argument_type& x, + const typename Predicate::second_argument_type& y) const + { + return !p(x, y); + } + private: + Predicate p; + }; + + + template _UCXXEXPORT binary_negate not2(const Predicate& pred){ + return binary_negate(pred); + } + + + template class _UCXXEXPORT binder1st + : public unary_function + { + protected: + Operation op; + typename Operation::first_argument_type value; + public: + binder1st(const Operation& x, const typename Operation::first_argument_type& y) : op(x), value(y){ } + typename Operation::result_type operator()(const typename Operation::second_argument_type& x) const{ + return op(value,x); + } + }; + + + template _UCXXEXPORT binder1st bind1st(const Operation& op, const T& x){ + return binder1st(op, typename Operation::first_argument_type(x)); + } + + + template class _UCXXEXPORT binder2nd + : public unary_function + { + protected: + Operation op; + typename Operation::second_argument_type value; + public: + binder2nd(const Operation& x, const typename Operation::second_argument_type& y) : op(x), value(y) { } + typename Operation::result_type operator()(const typename Operation::first_argument_type& x) const{ + return op(x,value); + } + }; + + + template _UCXXEXPORT + binder2nd bind2nd(const Operation& op, const T& x) + { + return binder2nd(op, typename Operation::second_argument_type(x)); + } + + + template class _UCXXEXPORT + pointer_to_unary_function : public unary_function + { + protected: + Result (*func)(Arg); + public: + explicit pointer_to_unary_function(Result (*f)(Arg)) : func(f) { } + Result operator()(Arg x) const{ + return func(x); + } + }; + + + template _UCXXEXPORT pointer_to_unary_function ptr_fun(Result (*f)(Arg)){ + return pointer_to_unary_function(f); + } + + + template class _UCXXEXPORT + pointer_to_binary_function : public binary_function + { + protected: + Result (*func)(Arg1, Arg2); + public: + explicit pointer_to_binary_function(Result (*f)(Arg1, Arg2)) : func(f) { } + Result operator()(Arg1 x, Arg2 y) const{ + return func(x, y); + } + }; + + template _UCXXEXPORT + pointer_to_binary_function ptr_fun(Result (*f)(Arg1, Arg2)) + { + return pointer_to_binary_function(f); + } + + + template class _UCXXEXPORT mem_fun_t + : public unary_function + { + public: + explicit mem_fun_t(S (T::*p)()) : m(p) { } + S operator()(T* p) const { return (p->*m)(); } + private: + S (T::*m)(); + }; + + + template class _UCXXEXPORT mem_fun1_t + : public binary_function + { + public: + explicit mem_fun1_t(S (T::*p)(A)) : m(p) { } + S operator()(T* p, A x) const { return (p->*m)(x); } + private: + S (T::*m)(A); + }; + + + template class _UCXXEXPORT const_mem_fun_t + : public unary_function + { + public: + explicit const_mem_fun_t(S (T::*p)() const) : m(p) { } + S operator()(const T* p) const { return (p->*m)(); } + private: + S (T::*m)() const; + }; + + + template class _UCXXEXPORT const_mem_fun1_t + : public binary_function + { + public: + explicit const_mem_fun1_t(S (T::*p)(A) const) : m(p) { } + S operator()(const T* p, A x) const { return (p->*m)(x); } + private: + S (T::*m)(A) const; + }; + + + template _UCXXEXPORT mem_fun_t mem_fun(S (T::*f)()){ + return mem_fun_t(f); + } + + template _UCXXEXPORT const_mem_fun_t mem_fun(S (T::*f)() const){ + return const_mem_fun_t(f); + } + + template _UCXXEXPORT mem_fun1_t mem_fun(S (T::*f)(A)){ + return mem_fun1_t(f); + } + + template _UCXXEXPORT const_mem_fun1_t mem_fun(S (T::*f)(A) const){ + return const_mem_fun1_t(f); + } + + template class _UCXXEXPORT mem_fun_ref_t + : public unary_function + { + public: + explicit mem_fun_ref_t(S (T::*p)()) : mf(p) { } + S operator()(T& p) { return (p.*mf)(); } + private: + S (T::*mf)(); + }; + + template class _UCXXEXPORT mem_fun1_ref_t + : public binary_function + { + public: + explicit mem_fun1_ref_t(S (T::*p)(A)) : mf(p) { } + S operator()(T& p, A x) { return (p.*mf)(x); } + private: + S (T::*mf)(A); + }; + + template _UCXXEXPORT mem_fun_ref_t mem_fun_ref(S (T::*f)()){ + return mem_fun_ref_t(f); + } + + template _UCXXEXPORT mem_fun1_ref_t mem_fun1_ref(S (T::*f)(A)){ + return mem_fun1_ref_t(f); + } + + +} + + +//These are SGI extensions which are checked for by some conformance checks. They +// are *NOT* part of the C++ standard, however + +template class _UCXXEXPORT unary_compose : + public std::unary_function +{ +protected: + Op1 mf1; + Op2 mf2; +public: + unary_compose(const Op1& x, const Op2& y) : mf1(x), mf2(y) { } + typename Op1::result_type operator()(const typename Op2::argument_type& x) const { + return mf1(mf2(x)); + } +}; + +template _UCXXEXPORT +inline unary_compose +compose1(const Op1& fn1, const Op2& fn2){ + return unary_compose(fn1, fn2); +} + +template class _UCXXEXPORT binary_compose : + public std::unary_function +{ +protected: + Op1 mf1; + Op2 mf2; + Op3 mf3; +public: + binary_compose(const Op1 & x, const Op2 & y, const Op3 & z) + : mf1(x), mf2(y), mf3(z){ } + typename Op1::result_type operator()(const typename Op2::argument_type & x) const { + return mf1(mf2(x), mf3(x)); + } +}; + +template inline _UCXXEXPORT binary_compose +compose2(const Op1 & fn1, const Op2 & fn2, const Op3 & fn3){ + return binary_compose(fn1, fn2, fn3); +} + +#pragma GCC visibility pop + +#endif + + + diff --git a/misc/uClibc++/include/cxx/iomanip b/misc/uClibc++/include/cxx/iomanip new file mode 100644 index 0000000000..14a82607c1 --- /dev/null +++ b/misc/uClibc++/include/cxx/iomanip @@ -0,0 +1,170 @@ +/* Copyright (C) 2005 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include + +#ifndef __STD_IOMANIP +#define __STD_IOMANIP 1 + +#pragma GCC visibility push(default) + +namespace std{ + +// These are the helper classes which we are going to be using to +// hold the required data + +class _UCXXEXPORT __resetiosflags{ +public: + ios_base::fmtflags m; + _UCXXEXPORT __resetiosflags(ios_base::fmtflags mask) : m(mask){ } +}; + +class _UCXXEXPORT __setiosflags{ +public: + ios_base::fmtflags m; + _UCXXEXPORT __setiosflags(ios_base::fmtflags mask) : m(mask){ } +}; + +class _UCXXEXPORT __setbase{ +public: + int base; + _UCXXEXPORT __setbase(int b) : base(b){ } +}; + +class _UCXXEXPORT __setfill{ +public: + int character; + _UCXXEXPORT __setfill(int c): character(c){ } +}; + +class _UCXXEXPORT __setprecision{ +public: + int digits; + _UCXXEXPORT __setprecision(int n): digits(n) { } +}; + +class _UCXXEXPORT __setw{ +public: + int width; + _UCXXEXPORT __setw(int n): width(n) { } +}; + + +//Actual manipulator functions + +inline __resetiosflags resetiosflags(ios_base::fmtflags mask){ + return __resetiosflags(mask); +} + +inline __setiosflags setiosflags(ios_base::fmtflags mask){ + return __setiosflags(mask); +} + +inline __setbase setbase(int b){ + return __setbase(b); +} + +inline __setfill setfill(int c){ + return __setfill(c); +} + +inline __setprecision setprecision(int n){ + return __setprecision(n); +} + +inline __setw setw(int n){ + return __setw(n); +} + + +//How to handle interaction with [i|o]stream classes + +template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const __resetiosflags s) +{ + os.setf(ios_base::fmtflags(0),s.m); + return os; +} + +template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, const __resetiosflags s) +{ + is.setf(ios_base::fmtflags(0),s.m); + return is; +} + +template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const __setiosflags s) +{ + os.setf(s.m); + return os; +} + +template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const __setbase s) +{ + ios_base::fmtflags f(0); + switch(s.base){ + case 8: + f = ios_base::oct; + break; + case 10: + f = ios_base::dec; + break; + case 16: + f = ios_base::hex; + break; + default: + break; + + } + os.setf(f, ios_base::basefield); + return os; +} + +template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const __setfill s) +{ + os.fill(s.character); + return os; +} + +template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const __setprecision s) +{ + os.precision(s.digits); + return os; +} + +template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const __setw s) +{ + os.width(s.width); + return os; +} + + + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/ios b/misc/uClibc++/include/cxx/ios new file mode 100644 index 0000000000..63dc4edbc8 --- /dev/null +++ b/misc/uClibc++/include/cxx/ios @@ -0,0 +1,500 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include + +#ifndef __HEADER_STD_IOS +#define __HEADER_STD_IOS 1 + +#pragma GCC visibility push(default) + +namespace std{ + typedef signed long int streamoff; + + template class fpos; + + class _UCXXEXPORT ios_base { + public: + class failure; +#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ + class failure : public exception { + public: + explicit failure(const std::string&) { } + explicit failure() { } + virtual const char* what() const throw() { + return "std::ios_base failure exception"; + } + }; +#endif +#ifdef __UCLIBCXX_SUPPORT_CDIR__ + class _UCXXLOCAL Init{ + public: + _UCXXEXPORT Init(); + _UCXXEXPORT ~Init(); + private: + static int init_cnt; + }; +#endif + + public: + + typedef unsigned short int fmtflags; + + static const fmtflags skipws = 0x0001; + + static const fmtflags left = 0x0002; + static const fmtflags right = 0x0004; + static const fmtflags internal = 0x0008; + + static const fmtflags boolalpha = 0x0010; + + static const fmtflags dec = 0x0020; + static const fmtflags oct = 0x0040; + static const fmtflags hex = 0x0080; + + static const fmtflags scientific = 0x0100; + static const fmtflags fixed = 0x0200; + + static const fmtflags showbase = 0x0400; + static const fmtflags showpoint = 0x0800; + static const fmtflags showpos = 0x1000; + static const fmtflags uppercase = 0x2000; + + static const fmtflags adjustfield = left | right | internal; + static const fmtflags basefield = dec | oct | hex; + static const fmtflags floatfield = fixed | scientific; + + static const fmtflags unitbuf = 0x4000; + + typedef unsigned char iostate; + static const iostate goodbit = 0x00; + static const iostate badbit = 0x01; + static const iostate eofbit = 0x02; + static const iostate failbit = 0x04; + + typedef unsigned char openmode; + static const openmode app = 0x01; + static const openmode ate = 0x02; + static const openmode binary = 0x04; + static const openmode in = 0x08; + static const openmode out = 0x10; + static const openmode trunc = 0x20; + + typedef unsigned char seekdir; + static const seekdir beg = 0x01; + static const seekdir cur = 0x02; + static const seekdir end = 0x04; + + _UCXXEXPORT fmtflags flags() const{ + return mformat; + } + _UCXXEXPORT fmtflags flags(fmtflags fmtfl); + + fmtflags setf(fmtflags fmtfl); + fmtflags setf(fmtflags fmtfl, fmtflags mask ); + + _UCXXEXPORT void unsetf(fmtflags mask){ + mformat&= ~mask; + } + + _UCXXEXPORT streamsize precision() const{ + return mprecision; + } + + _UCXXEXPORT streamsize precision(streamsize prec); + + _UCXXEXPORT streamsize width() const{ + return mwidth; + } + + _UCXXEXPORT streamsize width(streamsize wide); + + _UCXXEXPORT locale imbue(const locale& loc); + + _UCXXEXPORT locale getloc() const{ + return mLocale; + } + +// FIXME - These need to be implemented +// static int xalloc(); +// long& iword(int index); +// void*& pword(int index); + + _UCXXEXPORT ~ios_base() { } + + enum event { erase_event, imbue_event, copyfmt_event }; + + typedef void (*event_callback)(event, ios_base&, int index); +// void register_callback(event_call_back fn, int index); + + //We are going to wrap stdio so we don't need implementation of the following: + inline static bool sync_with_stdio(bool = true) { return true; } + + protected: + _UCXXEXPORT ios_base() : mLocale(), mformat(dec | skipws ), mstate(goodbit), + mmode(), mdir(), mprecision(6), mwidth(0) +#ifdef __UCLIBCXX_SUPPORT_CDIR__ + ,mInit() +#endif + { + + } + locale mLocale; + fmtflags mformat; + iostate mstate; + openmode mmode; + seekdir mdir; + streamsize mprecision; + streamsize mwidth; +#ifdef __UCLIBCXX_SUPPORT_CDIR__ + Init mInit; +#endif + }; + + + //ios_base manipulators + + + inline ios_base& boolalpha (ios_base& str){ + str.setf(ios_base::boolalpha); + return str; + } + inline ios_base& noboolalpha(ios_base& str){ + str.unsetf(ios_base::boolalpha); + return str; + } + inline ios_base& showbase (ios_base& str){ + str.setf(ios_base::showbase); + return str; + } + inline ios_base& noshowbase (ios_base& str){ + str.unsetf(ios_base::showbase); + return str; + } + inline ios_base& showpoint (ios_base& str){ + str.setf(ios_base::showpoint); + return str; + } + inline ios_base& noshowpoint(ios_base& str){ + str.unsetf(ios_base::showpoint); + return str; + } + inline ios_base& showpos (ios_base& str){ + str.setf(ios_base::showpos); + return str; + } + inline ios_base& noshowpos (ios_base& str){ + str.unsetf(ios_base::showpos); + return str; + } + inline ios_base& skipws (ios_base& str){ + str.setf(ios_base::skipws); + return str; + } + inline ios_base& noskipws (ios_base& str){ + str.unsetf(ios_base::skipws); + return str; + } + inline ios_base& uppercase (ios_base& str){ + str.setf(ios_base::uppercase); + return str; + } + inline ios_base& nouppercase(ios_base& str){ + str.unsetf(ios_base::uppercase); + return str; + } + + inline ios_base& unitbuf (ios_base& str){ + str.setf(ios_base::unitbuf); + return str; + } + inline ios_base& nounitbuf (ios_base& str){ + str.unsetf(ios_base::unitbuf); + return str; + } + inline ios_base& internal (ios_base& str){ + str.setf(ios_base::internal, ios_base::adjustfield); + return str; + } + inline ios_base& left (ios_base& str){ + str.setf(ios_base::left, ios_base::adjustfield); + return str; + } + inline ios_base& right (ios_base& str){ + str.setf(ios_base::right, ios_base::adjustfield); + return str; + } + + inline ios_base& dec (ios_base& str){ + str.setf(ios_base::dec, ios_base::basefield); + return str; + } + inline ios_base& hex (ios_base& str){ + str.setf(ios_base::hex, ios_base::basefield); + return str; + } + inline ios_base& oct (ios_base& str){ + str.setf(ios_base::oct, ios_base::basefield); + return str; + } + + inline ios_base& fixed (ios_base& str){ + str.setf(ios_base::fixed, ios_base::floatfield); + return str; + } + inline ios_base& scientific (ios_base& str){ + str.setf(ios_base::scientific, ios_base::floatfield); + return str; + } + + + //basic_ios class definition + + + template class _UCXXEXPORT basic_ios + : public ios_base + { + public: + // Types: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef traits traits_type; + + _UCXXEXPORT operator void*() const{ + if(fail() ){ + return 0; + } + return (void *)(1); //Must return a non-NULL pointer (though it can be *any* pointer) + } + + _UCXXEXPORT bool operator!() const{ + return fail(); + } + _UCXXEXPORT iostate rdstate() const{ + return mstate; + } + _UCXXEXPORT void clear(iostate state = goodbit){ + if(rdbuf()!=0){ + mstate = state; + }else{ + mstate = state|ios_base::badbit; + } + } + _UCXXEXPORT void setstate(iostate state) { + clear(rdstate() | state); +#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ + if(rdstate() & throw_mask){ + throw failure(); + } +#endif + } + + _UCXXEXPORT bool good() const{ + return (rdstate() == 0); + } + _UCXXEXPORT bool eof() const{ + if(rdstate() & eofbit){ + return true; + } + return false; + } + _UCXXEXPORT bool fail() const{ + if( mstate & (failbit | badbit) ){ + return true; + } + return false; + } + + _UCXXEXPORT bool bad() const{ + if(mstate & badbit){ + return true; + } + return false; + } + + _UCXXEXPORT iostate exceptions() const{ + return throw_mask; + } + _UCXXEXPORT void exceptions(iostate except){ + throw_mask = except; + } + + explicit _UCXXEXPORT basic_ios(basic_streambuf* sb) : fill_char(' '), mtied(0), mstreambuf(0){ + init(sb); + } + + basic_ios() : mtied(0), mstreambuf(0){ } + + virtual _UCXXEXPORT ~basic_ios(){ + } + + _UCXXEXPORT basic_ostream* tie() const{ + return mtied; + } + _UCXXEXPORT basic_ostream* tie(basic_ostream* tiestr){ + basic_ostream* retval= mtied; + mtied = tiestr; + return retval; + } + _UCXXEXPORT basic_streambuf* rdbuf() const{ + return mstreambuf; + } + _UCXXEXPORT basic_streambuf* rdbuf(basic_streambuf* sb){ + basic_streambuf* retval = mstreambuf; + mstreambuf = sb; + return retval; + } + _UCXXEXPORT basic_ios& copyfmt(const basic_ios& rhs); + _UCXXEXPORT char_type fill() const{ + return fill_char; + } + _UCXXEXPORT char_type fill(char_type ch){ + char_type temp = fill_char; + fill_char = ch; + return temp; + } + + _UCXXEXPORT locale imbue(const locale& loc){ + return ios_base::imbue(loc); + } + _UCXXEXPORT char narrow(char_type c, char dfault) const; + _UCXXEXPORT char_type widen(char c) const; + + protected: + char_type fill_char; + basic_ostream* mtied; + basic_streambuf* mstreambuf; + iostate throw_mask; + _UCXXEXPORT basic_ios(const basic_ios &){ } + _UCXXEXPORT basic_ios & operator=(const basic_ios &){ return *this; } + _UCXXEXPORT void init(basic_streambuf* sb){ + ios_base::mformat = skipws|dec; + mstreambuf = sb; + mstate = goodbit; + throw_mask = goodbit; + } + }; + +#ifdef __UCLIBCXX_EXPAND_IOS_CHAR__ +#ifndef __UCLIBCXX_COMPILE_IOS__ + + template <> _UCXXEXPORT void basic_ios >::clear(iostate state); + template <> _UCXXEXPORT void basic_ios >::setstate(iostate state); + +#endif +#endif + + + template + inline char basic_ios::narrow(char_type c, char dfault) const + { + return dfault; + } + + template <> + inline char basic_ios >::narrow(char_type c, char) const + { + return c; + } + +#ifdef __UCLIBCXX_HAS_WCHAR__ + + template <> + inline char basic_ios >::narrow(char_type c, char dfault) const + { + char retval = wctob (c); + if(retval == EOF){ + retval = dfault; + } + return retval; + } + +#endif //__UCLIBCXX_HAS_WCHAR__ + + template + inline typename basic_ios::char_type + basic_ios::widen(char c) const + { + return c; + } + + template <> + inline basic_ios >::char_type + basic_ios >::widen(char c) const + { + return c; + } + +#ifdef __UCLIBCXX_HAS_WCHAR__ + + template <> + inline basic_ios >::char_type + basic_ios >::widen(char c) const + { + return btowc(c); + } + +#endif //__UCLIBCXX_HAS_WCHAR__ + + + template class _UCXXEXPORT fpos{ + public: + _UCXXEXPORT fpos(stateT s){ + st = s; + } + _UCXXEXPORT stateT state() const{ + return st; + } + _UCXXEXPORT void state(stateT s){ + st = s; + } + _UCXXEXPORT bool operator==(const fpos &rhs){ + return st == rhs.st; + } + _UCXXEXPORT bool operator!=(const fpos &rhs){ + return st != rhs.st; + } + _UCXXEXPORT fpos & operator+(const streamoff & o){ + st += o; + return *this; + } + _UCXXEXPORT fpos & operator-(const streamoff & o){ + st -= o; + return *this; + } + _UCXXEXPORT streamoff operator-(const fpos & rhs){ + return st - rhs.st; + } + + private: + stateT st; + }; + + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/iosfwd b/misc/uClibc++/include/cxx/iosfwd new file mode 100644 index 0000000000..2c14725e32 --- /dev/null +++ b/misc/uClibc++/include/cxx/iosfwd @@ -0,0 +1,114 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + + +#ifndef __HEADER_STD_IOSFWD +#define __HEADER_STD_IOSFWD 1 + +#pragma GCC visibility push(default) + +namespace std { + class ios_base; + template<> class char_traits; + +#ifdef __UCLIBCXX_HAS_WCHAR__ + template<> class char_traits; +#endif + + template > class basic_ios; + + template > class basic_streambuf; + template > class basic_istream; + template > class basic_ostream; + template > class basic_iostream; + + template , + class Allocator = allocator > class basic_stringbuf; + + template , + class Allocator = allocator > class basic_istringstream; + + template , + class Allocator = allocator > class basic_ostringstream; + + template , + class Allocator = allocator > class basic_stringstream; + + template > class basic_filebuf; + + template > class basic_ifstream; + + template > class basic_ofstream; + + template > class basic_fstream; + + template > class basic_istreambuf_iterator; + + template > class basic_ostreambuf_iterator; + + typedef basic_ios ios; +#ifdef __UCLIBCXX_HAS_WCHAR__ + typedef basic_ios wios; +#endif + + typedef basic_streambuf streambuf; + typedef basic_istream istream; + typedef basic_ostream ostream; + typedef basic_iostream iostream; + + typedef basic_stringbuf stringbuf; + typedef basic_istringstream istringstream; + typedef basic_ostringstream ostringstream; + typedef basic_stringstream stringstream; + + typedef basic_filebuf filebuf; + typedef basic_ifstream ifstream; + typedef basic_ofstream ofstream; + typedef basic_fstream fstream; +#ifdef __UCLIBCXX_HAS_WCHAR__ + typedef basic_streambuf wstreambuf; + typedef basic_istream wistream; + typedef basic_ostream wostream; + typedef basic_iostream wiostream; + + typedef basic_stringbuf wstringbuf; + typedef basic_istringstream wistringstream; + typedef basic_ostringstream wostringstream; + typedef basic_stringstream wstringstream; + + typedef basic_filebuf wfilebuf; + typedef basic_ifstream wifstream; + typedef basic_ofstream wofstream; + typedef basic_fstream wfstream; +#endif + + template class fpos; + typedef fpos::state_type> streampos; +#ifdef __UCLIBCXX_HAS_WCHAR__ + typedef fpos::state_type> wstreampos; +#endif +} + +#pragma GCC visibility pop + +#endif diff --git a/misc/uClibc++/include/cxx/iostream b/misc/uClibc++/include/cxx/iostream new file mode 100644 index 0000000000..f93987f3bb --- /dev/null +++ b/misc/uClibc++/include/cxx/iostream @@ -0,0 +1,101 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +#ifndef __HEADER_STD_IOSTREAM +#define __HEADER_STD_IOSTREAM 1 + +#include +#include +#include +#include +#include +#include + +#pragma GCC visibility push(default) + +namespace std{ +#ifdef __UCLIBCXX_SUPPORT_CIN__ + extern istream cin; +#endif +#ifdef __UCLIBCXX_SUPPORT_COUT__ + extern ostream cout; +#endif +#ifdef __UCLIBCXX_SUPPORT_CERR__ + extern ostream cerr; +#endif +#ifdef __UCLIBCXX_SUPPORT_CLOG__ + extern ostream clog; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCIN__ + extern wistream wcin; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCOUT__ + extern wostream wcout; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCERR__ + extern wostream wcerr; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCLOG__ + extern wostream wclog; +#endif + + + template class _UCXXEXPORT basic_iostream : + public basic_istream, public basic_ostream + { + public: + // constructor/destructor + explicit _UCXXEXPORT basic_iostream(basic_streambuf* sb); + virtual _UCXXEXPORT ~basic_iostream(); //Below + }; + + template _UCXXEXPORT + basic_iostream:: basic_iostream(basic_streambuf* sb) + : basic_ios(sb), basic_istream(sb), basic_ostream(sb) + { + return; + } + + + template _UCXXEXPORT basic_iostream::~basic_iostream(){ + return; + } + + +#ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ +#ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ +#ifndef __UCLIBCXX_COMPILE_IOSTREAM__ + + template <> _UCXXEXPORT basic_iostream >:: + basic_iostream(basic_streambuf >* sb); + template <> _UCXXEXPORT basic_iostream >::~basic_iostream(); + +#endif +#endif +#endif + + + +} + +#pragma GCC visibility pop + +#endif diff --git a/misc/uClibc++/include/cxx/istream b/misc/uClibc++/include/cxx/istream new file mode 100644 index 0000000000..d67f48f577 --- /dev/null +++ b/misc/uClibc++/include/cxx/istream @@ -0,0 +1,599 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc C++ Library. This library is free + software; you can redistribute it and/or modify it under the + terms of the GNU General Public License as published by the + Free Software Foundation; either version 2, or (at your option) + any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License along + with this library; see the file COPYING. If not, write to the Free + Software Foundation, 59 Temple Place - Suite 330, Boston, MA 02111-1307, + USA. +*/ + +#include +#include +#include +#include +#include + +#ifndef __STD_HEADER_ISTREAM +#define __STD_HEADER_ISTREAM 1 + +#pragma GCC visibility push(default) + +namespace std{ + + typedef basic_istream istream; + +#ifdef __UCLIBCXX_HAS_WCHAR__ + typedef basic_istream wistream; +#endif + + template basic_istream& ws(basic_istream& is); + + template class _UCXXEXPORT basic_istream : + virtual public basic_ios + { + public: + + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef basic_streambuf streambuf_type; + typedef traits traits_type; + + explicit basic_istream(basic_streambuf* sb) + : basic_ios(sb), count_last_ufmt_input(0) + { + basic_ios::init(sb); + } + virtual ~basic_istream() { } + + class sentry; + + basic_istream& operator>>(basic_istream& (*pf)(basic_istream&)); + basic_istream& operator>>(basic_ios& (*pf)(basic_ios&)); + basic_istream& operator>>(ios_base& (*pf)(ios_base&)); + basic_istream& operator>>(bool& n); + basic_istream& operator>>(short& n); + basic_istream& operator>>(unsigned short& n); + basic_istream& operator>>(int& n); + basic_istream& operator>>(unsigned int& n); + basic_istream& operator>>(long& n); + basic_istream& operator>>(unsigned long& n); + basic_istream& operator>>(void*& p); + basic_istream& operator>>(basic_streambuf* sb); + +#ifdef __UCLIBCXX_HAS_FLOATS__ + basic_istream& operator>>(float& f); + basic_istream& operator>>(double& f); + basic_istream& operator>>(long double& f); +#endif + + _UCXXEXPORT streamsize gcount() const{ + return count_last_ufmt_input; + } + + _UCXXEXPORT int_type get(); //below + _UCXXEXPORT basic_istream& get(char_type& c); //Below + + _UCXXEXPORT basic_istream& get(char_type* s, streamsize n){ + return get(s, n, basic_ios::widen('\n')); + } + + _UCXXEXPORT basic_istream& get(char_type* s, streamsize n, char_type delim){ + sentry(*this, true); + streamsize i = 0; + int_type c; + for(i=0;i::mstreambuf->sgetc(); + basic_ios::mstreambuf->sbumpc(); + if(c == traits::eof() ){ + if(i==0){ + basic_ios::setstate(ios_base::failbit); + }else{ + basic_ios::setstate(ios_base::eofbit); + } + break; + } + if(c == delim){ + if(i==0){ + basic_ios::setstate(ios_base::failbit); + } + basic_ios::mstreambuf->sputbackc(c); + break; + } + s[i] = c; + } + s[i] = traits::eos(); + count_last_ufmt_input = i; + return *this; + } + + _UCXXEXPORT basic_istream& get(basic_streambuf& sb){ + return get(sb, basic_ios::widen('\n')); + } + + _UCXXEXPORT basic_istream& get(basic_streambuf& sb, char_type delim){ + sentry(*this, true); + streamsize i = 0; + int_type c; + while(1){ //We will exit internally based upon error conditions + c = basic_ios::mstreambuf->sgetc(); + if(c == traits::eof()){ + if(i==0){ + basic_ios::setstate(ios_base::failbit); + }else{ + basic_ios::setstate(ios_base::eofbit); + } + count_last_ufmt_input = i; + return *this; + } + if(c == delim){ + if(i==0){ + basic_ios::setstate(ios_base::failbit); + } + count_last_ufmt_input = i; + return *this; + } + if(sb.sputc(c) != c){ //Error doing output + count_last_ufmt_input = i; + return *this; + } + ++i; + basic_ios::mstreambuf->sbumpc(); + } + } + + _UCXXEXPORT basic_istream& getline(char_type* s, streamsize n){ + return getline(s, n, basic_ios::widen('\n')); + } + + _UCXXEXPORT basic_istream& getline(char_type* s, streamsize n, char_type delim){ + sentry(*this, true); + streamsize i = 0; + int_type c; + for(i=0;i::mstreambuf->sgetc(); + if(c == traits::eof() ){ + if( basic_ios::eof() ){ + basic_ios::setstate(ios_base::failbit); + }else{ + basic_ios::setstate(ios_base::eofbit); + } + count_last_ufmt_input = i; + s[i] = traits::eos(); + return *this; + } + if(basic_ios::mstreambuf->sbumpc()==traits::eof() ){ + basic_ios::setstate(ios_base::eofbit); + } + if(c == delim){ + count_last_ufmt_input = i+1; + s[i] = traits::eos(); + return *this; + } + s[i] = c; + } + s[n-1] = traits::eos(); + return *this; + } + + _UCXXEXPORT basic_istream& ignore (streamsize n = 1, int_type delim = traits::eof()){ + sentry(*this, true); + streamsize i; + int_type c; + for(i=0;i::mstreambuf->sgetc(); + if(c == traits::eof()){ + basic_ios::setstate(ios_base::eofbit); + return *this; + } + basic_ios::mstreambuf->sbumpc(); + if(c == delim){ + return *this; + } + } + return *this; + } + + _UCXXEXPORT int_type peek(){ + if(basic_ios::good() == false){ + return traits::eof(); + }else{ + int_type c = basic_ios::mstreambuf->sgetc(); + if(c == traits::eof()){ + basic_ios::setstate(ios_base::eofbit); + } + return basic_ios::mstreambuf->sgetc(); + } + } + + _UCXXEXPORT basic_istream& read (char_type* s, streamsize n){ + sentry(*this, true); + streamsize i; + int_type c; + for(i=0;i::mstreambuf->sgetc(); + + if(c == traits::eof()){ + basic_ios::setstate(ios_base::failbit); + basic_ios::setstate(ios_base::eofbit); + count_last_ufmt_input = i; + return *this; + } + basic_ios::mstreambuf->sbumpc(); + s[i] = c; + } + count_last_ufmt_input = n; + return *this; + } + + _UCXXEXPORT streamsize readsome(char_type* s, streamsize n){ + sentry(*this, true); + if(!basic_ios::good()){ + count_last_ufmt_input = 0; + basic_ios::setstate(ios_base::failbit); + return 0; + } + + if( basic_ios::mstreambuf->in_avail() == -1){ + count_last_ufmt_input=0; + basic_ios::setstate(ios_base::eofbit); + return 0; + } + + if(n > basic_ios::mstreambuf->in_avail() ){ + n = basic_ios::mstreambuf->in_avail(); + } + + streamsize i; + int_type c; + + for(i=0;i::mstreambuf->sgetc(); + basic_ios::mstreambuf->sbumpc(); + s[i] = c; + } + count_last_ufmt_input = n; + return n; + } + + _UCXXEXPORT basic_istream& putback(char_type c){ + sentry(*this, true); + if(!basic_ios::good()){ + basic_ios::setstate(ios_base::failbit); + return *this; + } + if(basic_ios::mstreambuf == 0){ + basic_ios::setstate(ios_base::badbit); + return *this; + } + if(basic_ios::mstreambuf->sputbackc(c) == traits::eof()){ + basic_ios::setstate(ios_base::badbit); + return *this; + } + return *this; + } + + _UCXXEXPORT basic_istream& unget(){ + sentry(*this, true); + if(!basic_ios::good()){ + basic_ios::setstate(ios_base::failbit); + return *this; + } + if(basic_ios::mstreambuf == 0){ + basic_ios::setstate(ios_base::failbit); + return *this; + } + if(basic_ios::mstreambuf->sungetc() == traits::eof()){ + basic_ios::setstate(ios_base::failbit); + } + return *this; + } + + _UCXXEXPORT int sync(){ + sentry(*this, true); + if(basic_ios::mstreambuf == 0){ + return -1; + } + if(basic_ios::mstreambuf->pubsync() == -1){ + basic_ios::setstate(ios_base::badbit); + return traits::eof(); + } + return 0; + } + + _UCXXEXPORT pos_type tellg(){ + if(basic_ios::fail() !=false){ + return pos_type(-1); + } + return basic_ios::mstreambuf->pubseekoff(0, ios_base::cur, ios_base::in); + } + + _UCXXEXPORT basic_istream& seekg(pos_type pos){ + if(basic_ios::fail() !=true){ + basic_ios::mstreambuf->pubseekpos(pos); + } + return *this; + } + + _UCXXEXPORT basic_istream& seekg(off_type off, ios_base::seekdir dir){ + if(basic_ios::fail() !=true){ + basic_ios::mstreambuf->pubseekoff(off, dir); + } + return *this; + } + + protected: + _UCXXEXPORT basic_istream(const basic_istream &): basic_ios() { } + _UCXXEXPORT basic_istream & operator=(const basic_istream &){ return *this; } + streamsize count_last_ufmt_input; + + }; + + template > class _UCXXEXPORT basic_istream::sentry { + bool ok; + public: + explicit _UCXXEXPORT sentry(basic_istream& os, bool noskipws = false){ + if(os.good() !=0){ //Prepare for output + } + + //Flush any tied buffer + if(os.tie() != 0){ + os.tie()->flush(); + } + if(!noskipws){ + __skipws(os); + } + + ok = true; + } + _UCXXEXPORT ~sentry() { } + _UCXXEXPORT operator bool() { + return ok; + } + }; + + //Template implementations of basic_istream functions which may be partially specialized + //For code reduction + + template + _UCXXEXPORT typename basic_istream::int_type basic_istream::get(){ + sentry(*this, true); + int_type retval = basic_ios::mstreambuf->sgetc(); + if(retval == traits::eof()){ + count_last_ufmt_input = 0; + basic_ios::setstate(ios_base::eofbit); + }else{ + count_last_ufmt_input = 1; + basic_ios::mstreambuf->sbumpc(); + } + return retval; + } + + template + _UCXXEXPORT basic_istream& basic_istream::get(char_type& c){ + sentry(*this, true); + int_type retval = basic_ios::mstreambuf->sgetc(); + if(retval == traits::eof()){ + count_last_ufmt_input = 0; + basic_ios::setstate(ios_base::eofbit); + basic_ios::setstate(ios_base::failbit); + }else{ + count_last_ufmt_input = 1; + c = traits::to_char_type(retval); + basic_ios::mstreambuf->sbumpc(); + } + return *this; + } + + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(bool& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(short& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(unsigned short& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& basic_istream::operator>>(int& n){ + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& basic_istream::operator>>(unsigned int& n){ + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& basic_istream::operator>>(long int& n){ + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(unsigned long int& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + +#ifdef __UCLIBCXX_HAS_FLOATS__ + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(float& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(double& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(long double& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } +#endif + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(void *& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, charT& c) + { + typename basic_istream::sentry s(is); + is.get(c); + return is; + } + + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, unsigned char& c) + { + typename basic_istream::sentry s(is); + char b; + is.get(b); + c = b; + return is; + } + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, signed char& c) + { + typename basic_istream::sentry s(is); + is.get(c); + return is; + } + + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, charT* c) + { + typename basic_istream::sentry s(is); + int n = is.width(); + if(n == 0){ + n = __STRING_MAX_UNITS; + } + is.get(c, n); + return is; + + } + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, unsigned char* c) + { + typename basic_istream::sentry s(is); + int n = is.width(); + if(n == 0){ + n = __STRING_MAX_UNITS; + } + is.get(c, n); + return is; + } + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, signed char* c) + { + typename basic_istream::sentry s(is); + int n = is.width(); + if(n == 0){ + n = __STRING_MAX_UNITS; + } + is.get(c, n); + return is; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(basic_istream& (*pf)(basic_istream&)) + { + sentry(*this); + pf(*this); + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(basic_ios& (*pf)(basic_ios&)) + { + sentry(*this); + pf(*this); + return *this; + } + + template _UCXXEXPORT basic_istream& + ws(basic_istream& is) + { + __skipws(is); + return is; + } + + +#ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ +#ifndef __UCLIBCXX_COMPILE_ISTREAM__ + + + template <> _UCXXEXPORT istream & basic_istream >::get(char & c); + template <> _UCXXEXPORT istream::int_type basic_istream >::get(); + + template <> _UCXXEXPORT istream & istream::operator>>(bool &n); + template <> _UCXXEXPORT istream & istream::operator>>(short &n); + template <> _UCXXEXPORT istream & istream::operator>>(unsigned short &n); + template <> _UCXXEXPORT istream & istream::operator>>(int &n); + template <> _UCXXEXPORT istream & istream::operator>>(unsigned int &n); + template <> _UCXXEXPORT istream & istream::operator>>(long unsigned &n); + template <> _UCXXEXPORT istream & istream::operator>>(long int &n); + template <> _UCXXEXPORT istream & istream::operator>>(void *& p); + +#ifdef __UCLIBCXX_HAS_FLOATS__ + template <> _UCXXEXPORT istream & istream::operator>>(float &f); + template <> _UCXXEXPORT istream & istream::operator>>(double &f); + template <> _UCXXEXPORT istream & istream::operator>>(long double &f); +#endif + + template <> _UCXXEXPORT istream & operator>>(istream & is, char & c); + + template <> _UCXXEXPORT void __skipws(basic_istream >& is); + +#endif +#endif + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/istream_helpers b/misc/uClibc++/include/cxx/istream_helpers new file mode 100644 index 0000000000..0bdca7d218 --- /dev/null +++ b/misc/uClibc++/include/cxx/istream_helpers @@ -0,0 +1,374 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#include + +#ifndef __STD_HEADER_ISTREAM_HELPERS +#define __STD_HEADER_ISTREAM_HELPERS 1 + +#pragma GCC visibility push(default) + +namespace std{ + + + /* We are making the following template class for serveral reasons. Firstly, + * we want to keep the main istream code neat and tidy. Secondly, we want it + * to be easy to do partial specialization of the istream code so that it can + * be expanded and put into the library. This will allow us to make application + * code smaller at the expense of increased library size. This is a fair + * trade-off when there are multiple applications being compiled. Also, this + * feature will be used optionally via configuration options. It will also + * allow us to keep the code bases in sync, dramatically simplifying the + * maintenance required. We specialized for char because wchar and others + * require different scanf functions + */ + + template _UCXXEXPORT + basic_string _readToken(basic_istream& stream) + { + basic_string temp; + typename traits::int_type c; + while(true){ + c = stream.rdbuf()->sgetc(); + if(c != traits::eof() && isspace(c) == false){ + stream.rdbuf()->sbumpc(); + temp.append(1, traits::to_char_type(c)); + }else{ + break; + } + } + if (temp.size() == 0) + stream.setstate(ios_base::eofbit|ios_base::failbit); + + return temp; + } + + template _UCXXEXPORT + basic_string _readTokenDecimal(basic_istream& stream) + { + basic_string temp; + typename traits::int_type c; + while(true){ + c = stream.rdbuf()->sgetc(); + if(c != traits::eof() && isspace(c) == false && ( + isdigit(c) || + c == '.' || + c == ',' || + ((c == '-' || c == '+') && temp.size() == 0) ) + ){ + stream.rdbuf()->sbumpc(); + temp.append(1, traits::to_char_type(c)); + }else{ + break; + } + } + if (temp.size() == 0) + stream.setstate(ios_base::eofbit|ios_base::failbit); + + return temp; + } + +#ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ + + template <> _UCXXEXPORT string _readToken >(istream & stream); + +#endif + + + template class _UCXXEXPORT __istream_readin{ + public: + static void readin(basic_istream& stream, dataType & var); + }; + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, bool & var) + { + /* 22.4.2.1.2.4 */ + basic_string temp; + temp = _readToken( stream); + if (stream.flags() & ios_base::boolalpha) { + if (temp == "true") // truename() + var = true; + else { + var = false; + if (temp != "false") // falsename() + stream.setstate(ios_base::failbit); + } + } else { + long int i = 0; + int ret; + if (stream.flags() & ios_base::dec) { + ret = sscanf(temp.c_str(), "%ld", &i ); + } else { + if (stream.flags() & ios_base::oct) { + ret = sscanf(temp.c_str(), "%lo", (unsigned long int *)(&i)); + } else if (stream.flags() & ios_base::hex) { + if (stream.flags() & ios_base::uppercase) { + ret = sscanf(temp.c_str(), "%lX", (unsigned long int *)(&i)); + } else { + ret = sscanf(temp.c_str(), "%lx", (unsigned long int *)(&i)); + } + } else { + ret = sscanf(temp.c_str(), "%li", &i); + } + } + if (ret != 1 || i >> 1) + stream.setstate(ios_base::failbit); + var = ret == 1 && bool(i); + } + } + }; + + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, short & var) + { + basic_string temp; + + if(stream.flags() & ios_base::dec){ + temp = _readTokenDecimal( stream); + sscanf(temp.c_str(), "%hd", &var ); + }else{ + temp = _readToken( stream); + if( stream.flags() & ios_base::oct){ + sscanf(temp.c_str(), "%ho", (unsigned short int *)(&var) ); + }else if(stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::uppercase){ + sscanf(temp.c_str(), "%hX", (unsigned short int *)(&var) ); + }else{ + sscanf(temp.c_str(), "%hx", (unsigned short int *)(&var) ); + } + }else{ + sscanf(temp.c_str(), "%hi", &var); + } + } + } + }; + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, unsigned short & var) + { + basic_string temp; + + if(stream.flags() & ios_base::dec){ + temp = _readTokenDecimal( stream); + sscanf(temp.c_str(), "%hu", &var ); + }else{ + temp = _readToken( stream); + if( stream.flags() & ios_base::oct){ + sscanf(temp.c_str(), "%ho", &var); + }else if(stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::uppercase){ + sscanf(temp.c_str(), "%hX", &var ); + }else{ + sscanf(temp.c_str(), "%hx", &var); + } + }else{ + sscanf(temp.c_str(), "%hi", (signed short int*)(&var) ); + } + } + } + }; + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, int & var) + { + basic_string temp; + + if(stream.flags() & ios_base::dec){ + temp = _readTokenDecimal( stream); + sscanf(temp.c_str(), "%d", &var ); + }else{ + temp = _readToken( stream); + if( stream.flags() & ios_base::oct){ + sscanf(temp.c_str(), "%o", (unsigned int *)(&var) ); + }else if(stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::uppercase){ + sscanf(temp.c_str(), "%X", (unsigned int *)(&var) ); + }else{ + sscanf(temp.c_str(), "%x", (unsigned int *)(&var) ); + } + }else{ + sscanf(temp.c_str(), "%i", &var); + } + } + } + }; + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, unsigned int & var) + { + basic_string temp; + + if(stream.flags() & ios_base::dec){ + temp = _readTokenDecimal( stream); + sscanf(temp.c_str(), "%u", &var ); + }else{ + temp = _readToken( stream); + if( stream.flags() & ios_base::oct){ + sscanf(temp.c_str(), "%o", (unsigned int *)(&var) ); + }else if(stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::uppercase){ + sscanf(temp.c_str(), "%X", (unsigned int *)(&var) ); + }else{ + sscanf(temp.c_str(), "%x", (unsigned int *)(&var) ); + } + }else{ + sscanf(temp.c_str(), "%i", (int *)(&var) ); + } + } + + } + }; + + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, long int & var) + { + basic_string temp; + + if(stream.flags() & ios_base::dec){ + temp = _readTokenDecimal( stream); + sscanf(temp.c_str(), "%ld", &var ); + }else{ + temp = _readToken( stream); + if( stream.flags() & ios_base::oct){ + sscanf(temp.c_str(), "%lo", (unsigned long int *)(&var) ); + }else if(stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::uppercase){ + sscanf(temp.c_str(), "%lX", (unsigned long int *)(&var) ); + }else{ + sscanf(temp.c_str(), "%lx", (unsigned long int *)(&var) ); + } + }else{ + sscanf(temp.c_str(), "%li", (long int *)(&var) ); + } + } + + } + }; + + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, unsigned long int & var) + { + basic_string temp; + + if(stream.flags() & ios_base::dec){ + temp = _readTokenDecimal( stream); + sscanf(temp.c_str(), "%lu", &var ); + }else{ + temp = _readToken( stream); + if( stream.flags() & ios_base::oct){ + sscanf(temp.c_str(), "%lo", &var ); + }else if(stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::uppercase){ + sscanf(temp.c_str(), "%lX", &var ); + }else{ + sscanf(temp.c_str(), "%lx", &var); + } + }else{ + sscanf(temp.c_str(), "%li", (long int *)(&var) ); + } + } + } + }; + + +#ifdef __UCLIBCXX_HAS_FLOATS__ + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, float & var) + { + basic_string temp; + temp = _readTokenDecimal( stream); + + sscanf(temp.c_str(), "%g", &var); + } + }; + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, double & var) + { + basic_string temp; + temp = _readTokenDecimal( stream); + sscanf(temp.c_str(), "%lg", &var); + } + }; + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, long double & var) + { + basic_string temp; + temp = _readTokenDecimal( stream); + sscanf(temp.c_str(), "%Lg", &var); + } + }; + +#endif // ifdef __UCLIBCXX_HAS_FLOATS__ + + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, void* & var) + { + basic_string temp; + temp = _readToken( stream); + sscanf(temp.c_str(), "%p", &var); + } + }; + + + template void __skipws(basic_istream& is){ + const typename basic_istream::int_type eof = traits::eof(); + typename basic_istream::int_type c; + //While the next character normally read doesn't equal eof + //and that character is a space, advance to the next read position + //Thus itterating through all whitespace until we get to the meaty stuff + while ( + !traits::eq_int_type((c = is.rdbuf()->sgetc()), eof) + && isspace(c) + ) { + is.rdbuf()->sbumpc(); + } + if(traits::eq_int_type(c, eof)){ + is.setstate(ios_base::eofbit); + } + } +} + +#pragma GCC visibility pop + +#endif + + + diff --git a/misc/uClibc++/include/cxx/iterator b/misc/uClibc++/include/cxx/iterator new file mode 100644 index 0000000000..b3d81b2074 --- /dev/null +++ b/misc/uClibc++/include/cxx/iterator @@ -0,0 +1,229 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include +#include + + + +#ifndef __STD_HEADER_ITERATOR +#define __STD_HEADER_ITERATOR 1 + +#pragma GCC visibility push(default) + +namespace std{ + + // subclause _lib.stream.iterators_, stream iterators: + template , class Distance = ptrdiff_t> class istream_iterator; + template bool + operator==(const istream_iterator& x, const istream_iterator& y); + template bool + operator!=(const istream_iterator& x, const istream_iterator& y); + template > class ostream_iterator; + template > class istreambuf_iterator; + template bool + operator==(const istreambuf_iterator& a, const istreambuf_iterator& b); + template bool + operator!=(const istreambuf_iterator& a, const istreambuf_iterator& b); + template > class ostreambuf_iterator; + + + template < class T, class charT, class traits, class Distance > class _UCXXEXPORT istream_iterator + : public iterator + { + public: + typedef charT char_type; + typedef traits traits_type; + typedef basic_istream istream_type; + istream_iterator() : in_stream(0), value(0) {} + istream_iterator(istream_type& s) : in_stream(&s), value() { + *in_stream >> value; + } + istream_iterator(const istream_iterator& x) + : in_stream(x.in_stream), value(x.value) + { } + ~istream_iterator() { } + const T& operator*() const{ + return value; + } + const T* operator->() const{ + return &value; + } + istream_iterator& operator++() { + *in_stream >> value; + return *this; + } + istream_iterator operator++(int){ + istream_iterator tmp = *this; + *in_stream >> value; + return (tmp); + } + bool m_equal(const istream_iterator& x) const{ + return (in_stream == x.in_stream); + } + private: + basic_istream* in_stream; + T value; + }; + + template _UCXXEXPORT + bool operator==(const istream_iterator& x, + const istream_iterator& y) + { + return x.m_equal(y); + } + + template _UCXXEXPORT + bool operator!=(const istream_iterator& x, + const istream_iterator& y) + { + return !(x == y); + } + + template class _UCXXEXPORT ostream_iterator + : public iterator + { + public: + typedef charT char_type; + typedef traits traits_type; + typedef basic_ostream ostream_type; + + ostream_iterator(ostream_type& s) : out_stream(&s), delim(0) { } + ostream_iterator(ostream_type& s, const charT* delimiter) : out_stream(&s), delim(delimiter) { } + ostream_iterator(const ostream_iterator& x) : out_stream(x.out_stream), delim(x.delim) { } + ~ostream_iterator() { } + ostream_iterator& operator=(const T& value){ + *out_stream << value; + if(delim != 0){ + *out_stream << delim; + } + return (*this); + } + ostream_iterator& operator*(){ return *this; } + ostream_iterator& operator++() { return *this; } + ostream_iterator operator++(int) { return *this; } + private: + basic_ostream* out_stream; + const char* delim; + }; + + template class _UCXXEXPORT istreambuf_iterator : + public iterator + { + public: + typedef charT char_type; + typedef traits traits_type; + typedef typename traits::int_type int_type; + typedef basic_streambuf streambuf_type; + typedef basic_istream istream_type; + + class _UCXXEXPORT proxy{ + charT val; + basic_streambuf * buf; + + proxy(charT v, basic_streambuf * b) : val(v), buf(b) { } + public: + charT operator*() { return val; } + }; + + istreambuf_iterator() throw() : sbuf(0) { } + istreambuf_iterator(istream_type& s) throw() : sbuf(s.rdbuf()) { } + istreambuf_iterator(streambuf_type* s) throw() : sbuf(s) { } + istreambuf_iterator(const proxy& p) throw() : sbuf(&p.buf) { } + + charT operator*() const{ + return sbuf->sgetc(); + } + istreambuf_iterator& operator++(){ + sbuf->sbumpc(); + return *this; + } + proxy operator++(int){ + istreambuf_iterator tmp = *this; + sbuf->sbumpc(); + return(tmp); + } + + bool equal(const istreambuf_iterator& b) const{ + return sbuf == b.sbuf || is_eof() && b.is_eof(); + } + private: + streambuf_type* sbuf; + inline bool is_eof() const{ + return sbuf == 0 || sbuf->sgetc() == traits_type::eof(); + } + }; + + template _UCXXEXPORT bool + operator==(const istreambuf_iterator& a, + const istreambuf_iterator& b) + { + return a.equal(b); + } + + template bool _UCXXEXPORT + operator!=(const istreambuf_iterator& a, + const istreambuf_iterator& b) + { + return !a.equal(b); + } + + template class _UCXXEXPORT ostreambuf_iterator + : iterator + { + public: + typedef charT char_type; + typedef traits traits_type; + typedef basic_streambuf streambuf_type; + typedef basic_ostream ostream_type; + public: + ostreambuf_iterator(ostream_type& s) throw() : sbuf(s.rdbuf()), f(false) { } + ostreambuf_iterator(streambuf_type* s) throw() : sbuf(s), f(false) { } + ostreambuf_iterator& operator=(charT c){ + if(failed() == false){ + if(sbuf->sputc(c) == traits::eof()){ + f = true; + } + } + return *this; + } + ostreambuf_iterator& operator*(){ + return *this; + } + ostreambuf_iterator& operator++() { return *this; } + ostreambuf_iterator operator++(int) { return *this; } + bool failed() const throw(){ + return f; + } + + private: + streambuf_type* sbuf; + bool f; + }; + +} + +#pragma GCC visibility pop + +#endif + + diff --git a/misc/uClibc++/include/cxx/iterator_base b/misc/uClibc++/include/cxx/iterator_base new file mode 100644 index 0000000000..1cae589661 --- /dev/null +++ b/misc/uClibc++/include/cxx/iterator_base @@ -0,0 +1,305 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +#ifndef __STD_HEADER_ITERATOR_BASE +#define __STD_HEADER_ITERATOR_BASE 1 + +#pragma GCC visibility push(default) + +namespace std{ + template struct iterator_traits; + template struct iterator_traits; + + template struct iterator; + + struct _UCXXEXPORT input_iterator_tag {}; + struct _UCXXEXPORT output_iterator_tag {}; + struct _UCXXEXPORT forward_iterator_tag: public input_iterator_tag {}; + struct _UCXXEXPORT bidirectional_iterator_tag: public forward_iterator_tag {}; + struct _UCXXEXPORT random_access_iterator_tag: public bidirectional_iterator_tag {}; + + template _UCXXEXPORT void advance(InputIterator& i, Distance n){ + while(n > 0){ + --n; + ++i; + } + } + + template _UCXXEXPORT typename iterator_traits::difference_type + distance(InputIterator first, InputIterator last) + { + typename iterator_traits::difference_type d = 0; + while(first++ !=last){ + d++; + } + return d; + } + + // subclause _lib.predef.iterators_, predefined iterators: + template class reverse_iterator; + template bool operator==(const reverse_iterator& x, const reverse_iterator& y); + template bool operator<(const reverse_iterator& x, const reverse_iterator& y); + template bool operator!=(const reverse_iterator& x, const reverse_iterator& y); + template bool operator>(const reverse_iterator& x, const reverse_iterator& y); + template bool operator>=(const reverse_iterator& x, const reverse_iterator& y); + template bool operator<=(const reverse_iterator& x, const reverse_iterator& y); + template typename reverse_iterator::difference_type + operator-( const reverse_iterator& x, const reverse_iterator& y); + template reverse_iterator + operator+( typename reverse_iterator::difference_type n, const reverse_iterator& x); + template class back_insert_iterator; + template back_insert_iterator back_inserter(Container& x); + template class front_insert_iterator; + template front_insert_iterator front_inserter(Container& x); + template class insert_iterator; + template + insert_iterator inserter(Container& x, Iterator i); + + //Actual Template definitions + + template struct _UCXXEXPORT iterator_traits { + typedef typename Iterator::difference_type difference_type; + typedef typename Iterator::value_type value_type; + typedef typename Iterator::pointer pointer; + typedef typename Iterator::reference reference; + typedef typename Iterator::iterator_category iterator_category; + }; + + //Pointer specialization - required by standard + template struct _UCXXEXPORT iterator_traits { + typedef ptrdiff_t difference_type; + typedef T value_type; + typedef T* pointer; + typedef T& reference; + typedef random_access_iterator_tag iterator_category; + }; + + //Specialization recomended by standard +/* template struct _UCXXEXPORT iterator_traits { + typedef long difference_type; + typedef T value_type; + typedef T __far* pointer; + typedef T __far& reference; + typedef random_access_iterator_tag iterator_category; + };*/ + +/* template _UCXXEXPORT void + reverse(BidirectionalIterator first, BidirectionalIterator last) + { + typename iterator_traits::difference_type n = distance(first, last); + --n; + while(n > 0){ + typename iterator_traits::value_type tmp = *first; + *first++ = * --last; + *last = tmp; + n -= 2; + } + };*/ + + + template + struct _UCXXEXPORT iterator + { + typedef T value_type; + typedef Distance difference_type; + typedef Pointer pointer; + typedef Reference reference; + typedef Category iterator_category; + }; + + + template class _UCXXEXPORT reverse_iterator + : public iterator::iterator_category, + typename iterator_traits::value_type, typename iterator_traits::difference_type, + typename iterator_traits::pointer, typename iterator_traits::reference> + { + protected: + Iterator current; + friend bool operator== (const reverse_iterator& x, const reverse_iterator& y); + friend bool operator< (const reverse_iterator& x, const reverse_iterator& y); + + public: + typedef Iterator iterator_type; + + reverse_iterator() : current(){}; + explicit reverse_iterator(Iterator x) : current(x) { } + template reverse_iterator(const reverse_iterator &x) : current(x.base()){} + + Iterator base() const { return current; } // explicit + + typename iterator_traits::reference operator*() const { Iterator tmp = current; return *--tmp; } + typename iterator_traits::pointer operator->() const { return &(operator*()); } + typename iterator_traits::reference operator[](typename iterator_traits::difference_type n) const{ + return current[-n-1]; + } + + reverse_iterator& operator++(){ --current; return *this; } + reverse_iterator operator++(int) {reverse_iterator tmp = *this; --current; return tmp; } + reverse_iterator& operator--() { ++ current; return *this; } + reverse_iterator operator--(int) {reverse_iterator tmp = *this; ++current; return tmp; } + + reverse_iterator operator+ (typename iterator_traits::difference_type n) const{ + reverse_iterator retval( *this ); + retval+=n; + return retval; + } + reverse_iterator& operator+=(typename iterator_traits::difference_type n){ + current -= n; + return *this; + } + reverse_iterator operator- (typename iterator_traits::difference_type n) const{ + reverse_iterator retval( *this ); + retval-=n; + return retval; + } + reverse_iterator& operator-=(typename iterator_traits::difference_type n){ + current += n; + return *this; + } + }; + + + template _UCXXEXPORT bool + operator==(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() == y.base(); + } + template _UCXXEXPORT bool + operator<(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() < y.base(); + } + template _UCXXEXPORT bool + operator!=(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() != y.base(); + } + template _UCXXEXPORT bool + operator>(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() > y.base(); + } + template _UCXXEXPORT bool + operator>=(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() >= y.base(); + } + template _UCXXEXPORT bool + operator<=(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() <= y.base(); + } + template _UCXXEXPORT typename reverse_iterator::difference_type + operator-( const reverse_iterator& x, const reverse_iterator& y) + { + return y.base() - x.base(); + } + template _UCXXEXPORT reverse_iterator + operator+(typename reverse_iterator::difference_type n, const reverse_iterator& x) + { + return reverse_iterator (x.base() - n); + } + + template class _UCXXEXPORT back_insert_iterator : + public iterator + { + protected: + Container& container; + public: + typedef Container container_type; + explicit back_insert_iterator(Container& x):container(x) {}; + back_insert_iterator& operator=(const typename Container::value_type& value){ + container.push_back(value); + return *this; + } + back_insert_iterator& operator*(){ + return *this; + } + back_insert_iterator& operator++(){ + return *this; + } + back_insert_iterator operator++(int){ + return *this; + } + }; + + template _UCXXEXPORT back_insert_iterator + back_inserter(Container& x) + { + return back_insert_iterator(x); + } + + template class _UCXXEXPORT front_insert_iterator + : public iterator + { + protected: + Container& container; + public: + typedef Container container_type; + explicit front_insert_iterator(Container& x): container(x) {} + front_insert_iterator& operator=(const typename Container::value_type& value){ + container.push_front(value); + return *this; + } + + front_insert_iterator& operator*() { return *this; } + front_insert_iterator& operator++() { return *this; } + front_insert_iterator operator++(int) { return *this; } + }; + + template _UCXXEXPORT front_insert_iterator + front_inserter(Container& x) + { + return front_insert_iterator(x); + } + + template class _UCXXEXPORT insert_iterator + : public iterator + { + protected: + Container& container; + typename Container::iterator iter; + public: + typedef Container container_type; + insert_iterator(Container& x, typename Container::iterator i) : container(x), iter(i) {} + insert_iterator& operator=(const typename Container::value_type& value){ + iter = container.insert(iter, value); + ++iter; + return *this; + } + insert_iterator& operator*() { return *this; } + insert_iterator& operator++() { return *this; } + insert_iterator operator++(int) { return *this; } + }; + + template _UCXXEXPORT insert_iterator + inserter(Container& x, Iterator i) + { + return insert_iterator(x,typename Container::iterator(i)); + } + +} + +#pragma GCC visibility pop + +#endif + + diff --git a/misc/uClibc++/include/cxx/limits b/misc/uClibc++/include/cxx/limits new file mode 100644 index 0000000000..e275eb5ec0 --- /dev/null +++ b/misc/uClibc++/include/cxx/limits @@ -0,0 +1,663 @@ +/* Copyright (C) 2006 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +#ifndef __STD_HEADER_LIMITS +#define __STD_HEADER_LIMITS 1 + +#warning limits header is nowhere complete or accurate + +#pragma GCC visibility push(default) + +namespace std{ + +enum float_round_style{ + round_indeterminate =-1, + round_toward_zero = 0, + round_to_nearest = 1, + round_toward_infinity = 2, + round_toward_neg_infinity = 3 +}; + +template struct __bits_to_base_10{ + static const int size = -1; +}; +template <> struct __bits_to_base_10<7>{ + static const int size = 2; +}; +template <> struct __bits_to_base_10<8>{ + static const int size = 2; +}; +template <> struct __bits_to_base_10<9>{ + static const int size = 2; +}; +template <> struct __bits_to_base_10<10>{ + static const int size = 3; +}; +template <> struct __bits_to_base_10<15>{ + static const int size = 4; +}; +template <> struct __bits_to_base_10<16>{ + static const int size = 4; +}; +template <> struct __bits_to_base_10<17>{ + static const int size = 5; +}; +template <> struct __bits_to_base_10<18>{ + static const int size = 5; +}; +template <> struct __bits_to_base_10<31>{ + static const int size = 9; +}; +template <> struct __bits_to_base_10<32>{ + static const int size = 9; +}; +template <> struct __bits_to_base_10<35>{ + static const int size = 10; +}; +template <> struct __bits_to_base_10<36>{ + static const int size = 10; +}; +template <> struct __bits_to_base_10<63>{ + static const int size = 18; +}; +template <> struct __bits_to_base_10<64>{ + static const int size = 19; +}; +template <> struct __bits_to_base_10<71>{ + static const int size = 21; +}; +template <> struct __bits_to_base_10<72>{ + static const int size = 21; +}; +template <> struct __bits_to_base_10<79>{ + static const int size = 23; +}; +template <> struct __bits_to_base_10<80>{ + static const int size = 24; +}; +template <> struct __bits_to_base_10<127>{ + static const int size = 38; +}; +template <> struct __bits_to_base_10<128>{ + static const int size = 38; +}; + + + + + + +template class numeric_limits { +public: + // General -- meaningful for all specializations. + + static const bool is_specialized = false; + static T min(); + static T max(); + static const int radix; + static const int digits; + static const int digits10; + static const bool is_signed; + static const bool is_integer; + static const bool is_exact; + static const bool traps; + static const bool is_modulo; + static const bool is_bounded; + + // Floating point specific. + + static T epsilon(); + static T round_error(); + static const int min_exponent10; + static const int max_exponent10; + static const int min_exponent; + + static const int max_exponent; + static const bool has_infinity; + static const bool has_quiet_NaN; + static const bool has_signaling_NaN; + static const bool is_iec559; + static const bool has_denorm; + static const bool tinyness_before; + static const float_round_style round_style; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef bool T; + // General -- meaningful for all specializations. + static const bool is_specialized = true; + static T min(){ + return false; + } + static T max(){ + return true; + } + static const int radix = 2; + static const int digits = 1; + static const int digits10 = 0; + static const bool is_signed = false; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = false; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + static T round_error(){ + return 0; + } + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef unsigned char T; + // General -- meaningful for all specializations. + static const bool is_specialized = true; + static T min(){ + return 0; + } + static T max(){ + return UCHAR_MAX; + } + static const int radix = 2; + static const int digits = CHAR_BIT; + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = false; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + static T round_error(){ + return 0; + } + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef signed char T; + // General -- meaningful for all specializations. + static const bool is_specialized = true; + static T min(){ + return SCHAR_MIN; + } + static T max(){ + return SCHAR_MAX; + } + static const int radix = 2; + static const int digits = CHAR_BIT - 1; + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = true; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + static T round_error(){ + return 0; + } + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef char T; + // General -- meaningful for all specializations. + static const bool is_specialized = true; + static T min(){ + return CHAR_MIN; + } + static T max(){ + return CHAR_MAX; + } + static const int radix = 2; + static const int digits = (CHAR_MIN != 0) ? CHAR_BIT - 1 : CHAR_BIT; + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = (CHAR_MIN != 0); + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + static T round_error(){ + return 0; + } + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef unsigned short T; + // General -- meaningful for all specializations. + static const bool is_specialized = true; + static T min(){ + return 0; + } + static T max(){ + return USHRT_MAX; + } + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = false; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + static T round_error(){ + return 0; + } + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef signed short T; + // General -- meaningful for all specializations. + static const bool is_specialized = true; + static T min(){ + return SHRT_MIN; + } + static T max(){ + return SHRT_MAX; + } + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = true; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + static T round_error(){ + return 0; + } + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef unsigned int T; + // General -- meaningful for all specializations. + static const bool is_specialized = true; + static T min(){ + return 0; + } + static T max(){ + return UINT_MAX; + } + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = false; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + static T round_error(){ + return 0; + } + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef signed int T; + // General -- meaningful for all specializations. + static const bool is_specialized = true; + static T min(){ + return INT_MIN; + } + static T max(){ + return INT_MAX; + } + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = true; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + static T round_error(){ + return 0; + } + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef unsigned long int T; + // General -- meaningful for all specializations. + static const bool is_specialized = true; + static T min(){ + return 0; + } + static T max(){ + return ULONG_MAX; + } + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = false; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + static T round_error(){ + return 0; + } + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef signed long int T; + // General -- meaningful for all specializations. + static const bool is_specialized = true; + static T min(){ + return LONG_MIN; + } + static T max(){ + return LONG_MAX; + } + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = true; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + static T round_error(){ + return 0; + } + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); +}; + +template <> class numeric_limits { +public: + typedef double numeric_type; + + static const bool is_specialized = true; + static numeric_type min () { return __DBL_MIN__; } + static numeric_type max () { return __DBL_MAX__; } + static const int radix = __FLT_RADIX__; + static const int digits = __DBL_MANT_DIG__; + static const int digits10 = __DBL_DIG__; + static const bool is_signed = true; + static const bool is_integer = false; + static const bool is_exact = false; + static const bool traps = false; // this is a guess + static const bool is_modulo = false; + static const bool is_bounded = true; + + // Floating point specific. + + static numeric_type epsilon () { return __DBL_EPSILON__; } + static numeric_type round_error () { return 0.5; } + static const int min_exponent10 = -1; //How do I properly get this? + static const int max_exponent10 = -1; //How do I properly get this? + static const int min_exponent = -1; //How do I properly get this? + static const int max_exponent = -1; //How do I properly get this? + static const bool has_infinity = false; //I don't know, so until I can find out, I'm saying no + static const bool has_quiet_NaN = false; //I don't know, so until I can find out, I'm saying no + static const bool has_signaling_NaN = false; //I don't know, so until I can find out, I'm saying no + static const bool has_denorm = false; //I don't know, so until I can find out, I'm saying no + + static const bool is_iec559 = false; //I don't know, so until I can find out, I'm saying no + static const bool tinyness_before = false; // more questions + static const float_round_style round_style = round_to_nearest; // more questions + static numeric_type denorm_min () { return -1; } //How do I properly get this? + static numeric_type infinity () { return -1; } //How do I properly get this? + static numeric_type quiet_NaN () { return -1; } //How do I properly get this? + static numeric_type signaling_NaN () { return -1; } //How do I properly get this? +}; + + + + + +} + +#pragma GCC visibility pop + +#endif diff --git a/misc/uClibc++/include/cxx/list b/misc/uClibc++/include/cxx/list new file mode 100644 index 0000000000..de8edadd63 --- /dev/null +++ b/misc/uClibc++/include/cxx/list @@ -0,0 +1,926 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#ifndef __STD_HEADER_LIST +#define __STD_HEADER_LIST 1 + +#pragma GCC visibility push(default) + +namespace std{ + + template > class _UCXXEXPORT list { + public: + typedef typename Allocator::reference reference; + typedef typename Allocator::const_reference const_reference; + typedef typename Allocator::size_type size_type; + typedef typename Allocator::difference_type difference_type; + typedef T value_type; + typedef Allocator allocator_type; + typedef typename Allocator::pointer pointer; + typedef typename Allocator::const_pointer const_pointer; + + protected: + class node; + class iter_list; + + node * list_start; + node * list_end; + size_type elements; + Allocator a; + + public: + + typedef iter_list iterator; + typedef iter_list const_iterator; + typedef std::reverse_iterator reverse_iterator; + typedef std::reverse_iterator const_reverse_iterator; + + explicit list(const Allocator& = Allocator()); + explicit list(size_type n, const T& value = T(), const Allocator& = Allocator()); + template list(InputIterator first, InputIterator last, + const Allocator& al= Allocator()); + list(const list& x); + ~list(); + + list& operator=(const list& x){ + if(&x == this){ + return *this; + } + clear(); + iterator i = x.begin(); + while(i != x.end()){ + push_back(*i); + ++i; + } + return *this; + } + + template void assign(InputIterator first, InputIterator last); + template void assign(Size n, const U& u = U()); + allocator_type get_allocator() const; + + iterator begin(); + const_iterator begin() const; + iterator end(); + const_iterator end() const; + reverse_iterator rbegin(); + const_reverse_iterator rbegin() const; + reverse_iterator rend(); + const_reverse_iterator rend() const; + + bool empty() const; + size_type size() const; + size_type max_size() const; + void resize(size_type sz, T c = T()); + + reference front(); + const_reference front() const; + reference back(); + const_reference back() const; + + void push_front(const T& x); + void pop_front(); + void push_back(const T& x); + void pop_back(); + iterator insert(iterator position, const T& x = T()); + void insert(iterator position, size_type n, const T& x); + template void insert(iterator position, InputIterator first, InputIterator last); + iterator erase(iterator position); + iterator erase(iterator position, iterator last); + void swap(list&); + void clear(); + + void splice(iterator position, list& x); + void splice(iterator position, list& x, iterator i); + void splice(iterator position, list& x, iterator first, iterator last); + void remove(const T& value); + template void remove_if(Predicate pred); + void unique(); + template void unique(BinaryPredicate binary_pred); + void merge(list& x); + template void merge(list& x, Compare comp); + void sort(); + template void sort(Compare comp); + void reverse(); + protected: + void swap_nodes(node * x, node * y); + }; + + + //Implementations of List + + //List node + template class _UCXXEXPORT list::node{ + public: + node * previous; + node * next; + T * val; + + node(): previous(0), next(0), val(0){ } + node(const T & t ): previous(0), next(0), val(0) { + val = new T(t); + //FIXME use allocator somehow but only call constructor once + } + node(const T & t, node * p, node * n): previous(p), next(n), val(0) { + val = new T(t); + } + ~node(){ } + }; + + //List iterator + template class _UCXXEXPORT list::iter_list + : public std::iterator< + bidirectional_iterator_tag, + T, + typename Allocator::difference_type, + typename Allocator::pointer, + typename Allocator::reference + > + { + private: + node * current; + public: + iter_list():current(0) { } + iter_list( typename list::node * n): current(n) { } + iter_list(const list::iter_list & l): current(l.current) { } + ~iter_list(){ } + + iter_list & operator=(const list::iter_list & right ){ + current = right.current; + return *this; + } + + T & operator*(){ + return *(current->val); + } + T * operator->(){ + return current->val; + } + const T & operator*() const{ + return *current->val; + } + const T * operator->() const{ + return current->val; + } + + bool operator==(const list::iter_list & right) const { + return (current == right.current); + } + + bool operator!=(const list::iter_list & right) const { + return (current != right.current); + } + + iter_list & operator++(){ + current = current->next; + return *this; + } + + iter_list operator++(int){ + iter_list temp(current); + current = current->next; + return temp; + } + iter_list & operator--(){ + current = current->previous; + return *this; + } + + iter_list operator--(int){ + iter_list temp(current); + current = current->previous; + return temp; + } + node * link_struct(){ + return current; + } + iter_list & operator+=(unsigned int n){ + for(unsigned int i = 0; i < n; ++i){ + current = current->next; + } + return *this; + } + iter_list & operator-=(unsigned int n){ + for(unsigned int i = 0; i < n; ++i){ + current = current->previous; + } + return *this; + } + }; + + + template list::list(const Allocator& al) + :list_start(0), list_end(0), elements(0), a(al) + { + //End node + list_start = new node(); + list_end = list_start; + return; + } + + template list::list + (typename Allocator::size_type n, const T& value, const Allocator& al) + :list_start(0), list_end(0), elements(0), a(al) + { + //End node + list_start = new node(); + list_end = list_start; + + for(typename Allocator::size_type i = 0; i < n ; ++i){ + push_back(value); + } + } + + template template + list::list + (InputIterator first, InputIterator last, const Allocator& al) + : list_start(0), list_end(0), elements(0), a(al) + { + list_start = new node(); + list_end = list_start; + while(first != last){ + push_back(*first); + ++first; + } + } + + template list::list(const list& x) + : list_start(0), list_end(0), elements(0), a(x.a) + { + list_start = new node(); + list_end = list_start; + + iterator i = x.begin(); + while(i != x.end()){ + push_back( *i); + ++i; + } + } + + template list::~list(){ + while(elements > 0){ + pop_front(); + } + delete list_start->val; +#if UCLIBCXX_DEBUG + list_start->val = 0; +#endif + delete list_start; +#if UCLIBCXX_DEBUG + list_start = 0; + list_end = 0; +#endif + } + + + template void list::swap_nodes(node * x, node * y){ + T * v = x->val; + x->val = y->val; + y->val = v; + } + + template typename list::iterator + list::begin() + { + return iterator(list_start); + } + + + template typename list::const_iterator + list::begin() const + { + return const_iterator(list_start); + } + + + template typename list::iterator + list::end() + { + return iterator(list_end); + } + + template typename list::const_iterator + list::end() const + { + return const_iterator(list_end); + } + + template typename list::reverse_iterator + list::rbegin() + { + return reverse_iterator(end()); + } + + template typename list::const_reverse_iterator + list::rbegin() const + { + return const_reverse_iterator(end()); + } + + template typename list::reverse_iterator + list::rend() + { + return reverse_iterator(begin()); + } + + template typename list::const_reverse_iterator + list::rend() const + { + return const_reverse_iterator(begin()); + } + + template bool list::empty() const{ + return (elements == 0); + } + template typename list::size_type list::size() const{ + return elements; + } + template typename list::size_type list::max_size() const{ + return ((size_type)(-1)) / (sizeof(T) + sizeof(node)); + } + template void list::resize(typename Allocator::size_type sz, T c){ +// if(sz > elements){ + for(typename Allocator::size_type i = elements; i < sz; ++i){ + push_back(c); + } +// } +// if(sz < elements){ + for(typename Allocator::size_type i = elements; i > sz; --i){ + pop_back(); + } +// } + } + + template typename list::reference list::front(){ + return *(list_start->val); + } + template typename list::const_reference list::front() const{ + return *(list_start->val); + } + template typename list::reference list::back(){ + return *(list_end->previous->val); + } + template typename list::const_reference list::back() const{ + return *(list_end->previous->val); + } + + + template void list::push_front(const T& x){ + node * temp = new node(x); + list_start->previous = temp; + temp->previous = 0; + temp->next = list_start; + list_start = temp; + ++elements; + } + + template void list::pop_front(){ + if(elements > 0){ + list_start = list_start->next; + delete list_start->previous->val; +#if UCLIBCXX_DEBUG + list_start->previous->val = 0; + list_start->previous->next = 0; + list_start->previous->previous = 0; +#endif + delete list_start->previous; + list_start->previous = 0; + --elements; + } + } + + template void list::push_back(const T& x){ + if(elements == 0){ + //The list is completely empty + list_start = new node(x); + list_end->previous = list_start; + list_start->previous = 0; + list_start->next = list_end; + elements = 1; + }else{ + node * temp = new node(x); + temp->previous = list_end->previous; + temp->next = list_end; + list_end->previous->next = temp; + list_end->previous = temp; + ++elements; + } + } + + template void list::pop_back(){ + if(elements > 0){ + node * temp = list_end->previous; + if(temp == list_start){ + list_end->previous = 0; + list_start = list_end; + }else{ + temp->previous->next = temp->next; + list_end->previous = temp->previous; + } + delete temp->val; +#if UCLIBCXX_DEBUG + temp->val = 0; + temp->next = 0; + temp->previous = 0; +#endif + delete temp; +#if UCLIBCXX_DEBUG + temp = 0; +#endif + --elements; + } + } + + + template typename list::iterator + list::insert(iterator position, const T& x) + { + node * temp = new node(x); + + temp->previous = position.link_struct()->previous; + temp->next = position.link_struct(); + + if(temp->previous == 0){ + list_start = temp; + }else{ + position.link_struct()->previous->next = temp; + } + + position.link_struct()->previous = temp; + + ++elements; + --position; + return position; + } + + template void list::insert(iterator position, size_type n, const T& x){ + for(typename list::size_type i = 0; i < n; ++i){ + position = insert(position, x); + } + } + + template template void + list::insert(iterator position, InputIterator first, InputIterator last) + { + while(first !=last){ + insert(position, *first); + ++first; + } + } + template typename list::iterator + list::erase(iterator position) + { + if(position != end() ){ + node * temp = position.link_struct(); + if(temp == list_start){ + ++position; + temp->next->previous = 0; + list_start = temp->next; + }else{ + --position; + temp->next->previous = temp->previous; + temp->previous->next = temp->next; + ++position; + } + delete temp->val; +#if UCLIBCXX_DEBUG + temp->next = 0; + temp->previous = 0; + temp->val = 0; +#endif + delete temp; +#if UCLIBCXX_DEBUG + temp = 0; +#endif + --elements; + } + return position; + } + template typename list::iterator + list::erase(iterator position, iterator last) + { + iterator temp = position; + while(position !=last){ + position = erase(position); + } + return position; + } + template void list::swap(list& l){ + node * temp; + size_type tempel; + + temp = list_start; + list_start = l.list_start; + l.list_start = temp; + + temp = list_end; + list_end = l.list_end; + l.list_end = temp; + + tempel = elements; + elements = l.elements; + l.elements = tempel; + } + template void list::clear(){ + while(elements > 0){ + pop_front(); + } + } + + template + void list::splice(iterator position, list& x) + { + + //Can't add non-existant elements + if(x.elements == 0){ + return; + } + + elements += x.elements; + x.elements = 0; + + + //Chaining to the begining + if(position == begin()){ + x.list_end->previous->next = list_start; + list_start->previous = x.list_end->previous; + + list_start = x.list_start; + + x.list_start = x.list_end; + x.list_end->previous = 0; + + return; + } + + //Link everything we need + x.list_start->previous = position.link_struct()->previous; + position.link_struct()->previous->next = x.list_start; + + position.link_struct()->previous = x.list_end->previous; + x.list_end->previous->next = position.link_struct(); + + //Clean up the other list + + x.list_start = x.list_end; + x.list_end->previous=0; + + } + + template + void list::splice(iterator position, list& x, iterator i) + { + //Invalid conditions + if( x.elements == 0 || i == position || position.link_struct() == i.link_struct()->next ){ + return; + } + + //Do we need to adjust the begining pointer? + if(i == x.begin()){ + x.list_start = x.list_start->next; + x.list_start->previous = 0; + } + + + //Insert at begining special case + if(position == begin()){ + + i.link_struct()->previous->next = i.link_struct()->next; + i.link_struct()->next->previous = i.link_struct()->previous; + + i.link_struct()->previous = 0; + i.link_struct()->next = position.link_struct(); + position.link_struct()->previous = i.link_struct(); + + list_start = i.link_struct(); + + --x.elements; + ++elements; + return; + } + + if( i.link_struct()->previous != 0){ + i.link_struct()->previous->next = i.link_struct()->next; + i.link_struct()->next->previous = i.link_struct()->previous; + }else{ + i.link_struct()->next->previous = 0; + x.list_start = i.link_struct()->next; + } + + i.link_struct()->previous = position.link_struct()->previous; + position.link_struct()->previous->next = i.link_struct(); + + i.link_struct()->next = position.link_struct(); + position.link_struct()->previous = i.link_struct(); + + --x.elements; + ++elements; + } + + template + void list::splice(iterator position, list& x, + iterator first, iterator last) + { + if(x.elements == 0){ + return; + } + + iterator temp; + while(first != last){ + temp = first; + ++first; + splice(position, x, temp); + } + } + + + template void list::remove(const T& value){ + iterator temp = begin(); + while( temp != end() ){ + if(*temp == value){ + temp = erase(temp); + }else{ + ++temp; + } + } + } + + + template template void list::remove_if(Predicate pred){ + iterator temp = begin(); + while( temp != end() ){ + if( pred(*temp) ){ + temp = erase(temp); + }else{ + ++temp; + } + } + } + + + template void list::unique(){ + equal_to::value_type> p; + unique(p); + } + + template template + void list::unique(BinaryPredicate binary_pred) + { + iterator temp1 = begin(); + iterator temp2; + ++temp1; + while( temp1 != end() ){ + temp2 = temp1; + --temp2; + if( binary_pred(*temp1, *temp2) ){ + erase(temp1); + temp1 = temp2; + } + ++temp1; + } + } + + template void list::merge(list& x){ + less::iterator>::value_type> c; + merge(x, c); + } + + template template + void list::merge(list& x, Compare comp) + { + iterator source = x.begin(); + iterator temp; + iterator dest = begin(); + + while(source != x.end()){ + while( dest != end() && comp (*dest, *source) ){ + ++dest; + } + ++elements; + --x.elements; + + temp = source; + ++temp; + + if(dest == begin()){ + dest.link_struct()->previous = source.link_struct(); + source.link_struct()->next = dest.link_struct(); + source.link_struct()->previous = 0; + list_start = source.link_struct(); + }else{ + source.link_struct()->previous = dest.link_struct()->previous; + dest.link_struct()->previous->next = source.link_struct(); + source.link_struct()->next = dest.link_struct(); + dest.link_struct()->previous = source.link_struct(); + } + source = temp; + } + + //Fix up x; + x.list_start = x.list_end; + x.list_start->previous = 0; + } + + template void list::sort(){ + less::iterator>::value_type> c; + sort(c); + } + + template template + void list::sort(Compare comp) + { + typename list::iterator i, j, k; + + //FIXME - bubble sort + + if(elements == 0){ + return; + } + + i = end(); + --i; + while(i != begin()){ + j = begin(); + k = j; + ++k; + while(j != i){ + if( comp(*k, *j) ){ + swap_nodes(k.link_struct(), j.link_struct()); + } + ++j; + ++k; + } + --i; + } + } + + + template void list::reverse(){ + if(elements == 0){ + return; + } + + node * current; + node * following; + node * temp; + + //Need to move the list_end element to the begining + + temp = list_end; + list_end = temp->previous; + list_end->next = 0; + + list_start->previous = temp; + temp->previous = 0; + temp->next = list_start; + list_start = temp; + + current = list_start; + + while( current != list_end ){ + following = current->next; + + //Swap the values pointed to/at with the current node + temp = current->next; + current->next = current->previous; + current->previous = temp; + + current = following; + } + + //Swap pointers on the end node + temp = list_end->next; + list_end->next = list_end->previous; + list_end->previous = temp; + + + //Swap the fixed pointers + temp = list_start; + list_start = list_end; + list_end = temp; + + } + + template + bool operator==(const list& x, const list& y){ + if(x.size() != y.size()){ + return false; + } + typename list::const_iterator i = x.begin(); + typename list::const_iterator j = y.begin(); + + while(i != x.end()){ + if( *i != *j){ + return false; + } + ++i; + ++j; + } + return true; + } + + template + bool operator< (const list& x, const list& y){ + typename list::const_iterator i = x.begin(); + typename list::const_iterator j = y.begin(); + while(i != x.end() && j != y.end()){ + if( *i < *j){ + return true; + } + if(*j < *i){ + return false; + } + ++i; + ++j; + } + return (i == x.end() && j != y.end()); + } + + template + bool operator!=(const list& x, const list& y){ + return !(x == y); + } + + template + bool operator> (const list& x, const list& y){ + typename list::const_iterator i = x.begin(); + typename list::const_iterator j = y.begin(); + while(i != x.end() && j != y.end()){ + if( *i > *j){ + return true; + } + if( *j > *i){ + return false; + } + ++i; + ++j; + } + return (i != x.end() && j == y.end()); + } + + template + bool operator>=(const list& x, const list& y){ + typename list::const_iterator i = x.begin(); + typename list::const_iterator j = y.begin(); + while(i != x.end() && j != y.end()){ + if( *i >= *j){ + return true; + } + if(*j >= *i){ + return false; + } + ++i; + ++j; + } + return (i != x.end() && j == y.end()); + } + + template + bool operator<=(const list& x, const list& y){ + typename list::const_iterator i = x.begin(); + typename list::const_iterator j = y.begin(); + while(i != x.end() && j != y.end()){ + if( *i <= *j){ + return true; + } + if(*j <= *i){ + return false; + } + ++i; + ++j; + } + return (i == x.end()); + } + + template + void swap(list& x, list& y){ + x.swap(y); + } + +} + +#pragma GCC visibility pop + +#endif + + diff --git a/misc/uClibc++/include/cxx/locale b/misc/uClibc++/include/cxx/locale new file mode 100644 index 0000000000..96e6bc948f --- /dev/null +++ b/misc/uClibc++/include/cxx/locale @@ -0,0 +1,83 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#ifndef __HEADER_STD_LOCALE +#define __HEADER_STD_LOCALE 1 + +#pragma GCC visibility push(default) + +namespace std{ + class _UCXXEXPORT locale { + public: + // types: + class facet; + class id; + typedef unsigned char category; + + static const category + none = 0, + collate = 0x01, ctype = 0x02, + monetary = 0x04, numeric = 0x08, + time = 0x10, messages = 0x20, + all = collate | ctype | monetary | numeric | time | messages; + + // construct/copy/destroy: + locale() throw(){ + return; + } + locale(const locale& other) throw(){ + (void)other; + return; + } + locale(const char *) throw(){ + return; + } + ~locale() throw(){ + return; + } + + const locale& operator=(const locale&) throw(){ + return *this; + } + std::string name() const { return "C"; } + }; + + class _UCXXEXPORT locale::facet { + friend class locale; + explicit facet(size_t = 0){ + return; + } + virtual ~facet(){ + return; + } + }; + + class _UCXXEXPORT locale::id { + id(){ } + }; + +} + +#pragma GCC visibility pop + +#endif diff --git a/misc/uClibc++/include/cxx/map b/misc/uClibc++/include/cxx/map new file mode 100644 index 0000000000..038191af7c --- /dev/null +++ b/misc/uClibc++/include/cxx/map @@ -0,0 +1,264 @@ +/* Copyright (C) 2004-2007 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + + + +#include +#include +#include +#include + + +#ifndef __STD_HEADER_MAP +#define __STD_HEADER_MAP + +#pragma GCC visibility push(default) + +namespace std{ + + +template, class Allocator = allocator > class map; +template, class Allocator = allocator > class multimap; + + + //Compare the keys of the two items +/* template class _UCXXEXPORT + __base_map::value_compare : public binary_function< + typename map::value_type, + typename map::value_type, + bool> + { + friend class __base_map; + protected: + Compare comp; + value_compare(Compare c) : comp(c) { } + ~value_compare() { } + public: + bool operator()(const value_type& x, const value_type& y) const { + return comp(x.first, y.first); + } + }; +*/ + +// value_compare value_comp() const; + + + +/* This is the implementation for the map container. As noted above, it deviates + * from ISO spec by deriving from a base class in order to reduce code redundancy. + * More code could be reduced by convirting to virtual functions (thus allowing + * much of the erase and insert code to be duplicated), but that would deviate from + * the specifications too much to be worth the risk. + */ + + + +//Implementation of map + + +template class _UCXXEXPORT map + : public __single_associative, Compare, Allocator> +{ + //Default value of allocator does not meet C++ standard specs, but it works for this library + //Deal with it + +public: + + typedef __single_associative, Compare, Allocator> base; + typedef T mapped_type; + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; + + static const key_type v_t_k(const value_type v){ + return v.first; + } + +// using base::value_compare; + + explicit map(const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(comp, al, v_t_k) { } + + template map(InputIterator first, InputIterator last, + const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(first, last, comp, al, v_t_k) { } + + map(const map& x) : base(x) { } + ~map() { } + + using base::operator=; + using base::operator==; + using base::operator!=; + + using base::insert; + using base::erase; + + using base::begin; + using base::end; + using base::rbegin; + using base::rend; + + using base::empty; + using base::size; + using base::max_size; + + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; + using base::swap; + + reference operator[](const key_type& k){ + iterator i = lower_bound(k); + if (i == end() || base::c(k, i->first)) { + i = insert(make_pair(k, T())).first; + } + return i->second; + } + +protected: + using base::backing; +}; + + +//Implementation of multimap + + +template class _UCXXEXPORT multimap + : public __multi_associative, Compare, Allocator> + +{ + //Default value of allocator does not meet C++ standard specs, but it works for this library + //Deal with it +public: + + typedef __multi_associative, Compare, Allocator> base; + typedef T mapped_type; + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; + + static const key_type v_t_k(const value_type v){ + return v.first; + } + + explicit multimap(const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(comp, al, v_t_k) { } + + template multimap(InputIterator first, InputIterator last, + const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(first, last, comp, al, v_t_k) { } + + + multimap(const multimap& x) : base(x) { } + ~multimap() { } + + using base::operator=; + using base::operator==; + using base::operator!=; + + using base::insert; + using base::erase; + + using base::begin; + using base::end; + using base::rbegin; + using base::rend; + + using base::empty; + using base::size; + using base::max_size; + + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; + using base::swap; + +protected: + + using base::c; + +}; + + +/* Non-member functions. These are at the end because they are not associated with any + particular class. These will be implemented as I figure out exactly what all of + them are supposed to do, and I have time. + */ + + template _UCXXEXPORT bool operator< + (const map& x, const map& y); + template _UCXXEXPORT bool operator!= + (const map& x, const map& y); + template _UCXXEXPORT bool operator> + (const map& x, const map& y); + template _UCXXEXPORT bool operator>= + (const map& x, const map& y); + template _UCXXEXPORT bool operator<= + (const map& x, const map& y); + template _UCXXEXPORT void swap + (map& x, map& y); + + + template _UCXXEXPORT bool operator== + (const multimap& x, const multimap& y); + template _UCXXEXPORT bool operator< + (const multimap& x, const multimap& y); + template _UCXXEXPORT bool operator!= + (const multimap& x, const multimap& y); + template _UCXXEXPORT bool operator> + (const multimap& x, const multimap& y); + template _UCXXEXPORT bool operator>= + (const multimap& x, const multimap& y); + template _UCXXEXPORT bool operator<= + (const multimap& x, const multimap& y); + template _UCXXEXPORT void swap + (multimap& x, multimap& y); + +} + +#pragma GCC visibility pop + +#endif + + diff --git a/misc/uClibc++/include/cxx/memory b/misc/uClibc++/include/cxx/memory new file mode 100644 index 0000000000..2a7ce8c152 --- /dev/null +++ b/misc/uClibc++/include/cxx/memory @@ -0,0 +1,196 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include +#include +#include + +#ifndef HEADER_STD_MEMORY +#define HEADER_STD_MEMORY 1 + +#pragma GCC visibility push(default) + +namespace std{ + +template class allocator; + // Specialize for void: + +template <> class _UCXXEXPORT allocator { +public: + typedef void* pointer; + typedef const void* const_pointer; + typedef void value_type; + template struct rebind { typedef allocator other; }; +}; + +template class _UCXXEXPORT allocator{ +public: + typedef T value_type; + typedef size_t size_type; + typedef ptrdiff_t difference_type; + + typedef T* pointer; + typedef const T* const_pointer; + + typedef T& reference; + typedef const T& const_reference; + + pointer address(reference r) const { return &r; } + const_pointer address(const_reference r) const { return &r; } + + allocator() throw(){} + template allocator(const allocator& ) throw(); + ~allocator() throw(){} + + //Space for n Ts + pointer allocate(size_type n, typename allocator::const_pointer = 0){ + return (T*)(::operator new( n * sizeof(T) )); + } + void deallocate(pointer p, size_type){ + ::operator delete(p); + } + + //Use placement new to engage the constructor + void construct(pointer p, const T& val) { new((void*)p) T(val); } + void destroy(pointer p){ ((T*)p)->~T(); } //Call destructor + + size_type max_size() const throw(); + template struct rebind { typedef allocator other; }; + +}; + +template class _UCXXEXPORT raw_storage_iterator + : public iterator +{ + Out p; + +public: + explicit raw_storage_iterator(Out pp) : p (pp) { } + raw_storage_iterator & operator*() { return *this; } + raw_storage_iterator & operator=(const T& val) { + T* pp = &*p; + new(pp) T(val); + return *this; + } + + raw_storage_iterator & operator++() { ++p; return *this; } + raw_storage_iterator operator++(int) { + raw_storage_iterator t = *this; + ++p; + return t; + } +}; + +template _UCXXEXPORT pair get_temporary_buffer(ptrdiff_t n){ + pair retval; + retval.first = static_cast(malloc(n * sizeof(T))); + if(retval.first == 0){ + retval.second = 0; + }else{ + retval.second = n; + } + return retval; +} + +template _UCXXEXPORT void return_temporary_buffer(T* p){ + free(p); +} + + +template class _UCXXEXPORT auto_ptr{ + +private: + T * object; + template struct auto_ptr_ref{ + Y * p; + }; + +public: + + typedef T element_type; + + explicit auto_ptr(T* p =0) throw() : object(p){ } + auto_ptr(auto_ptr& p) throw() : object(p.release()){ } + auto_ptr(auto_ptr_ref r) throw() : object(r.p){ + r.p = 0; + } + template auto_ptr(auto_ptr& p) throw() : object(p.release()){ } + auto_ptr& operator=(auto_ptr& p) throw(){ + if(&p == this){ + return *this; + } + delete object; + object = p.release(); + return *this; + } + template auto_ptr& operator=(auto_ptr& p) throw(){ + if(&p == this){ + return *this; + } + delete object; + object = p.release(); + return *this; + } + ~auto_ptr(){ + delete object; + } + + T& operator*() const throw(){ + return *object; + } + T* operator->() const throw(){ + return object; + } + T* get() const throw(){ + return object; + } + T* release() throw(){ + T * temp(object); + object = 0; + return temp; + } + void reset(T * p=0) throw(){ + if(p != object){ + delete object; + object = p; + } + } + template operator auto_ptr_ref() throw(){ + auto_ptr_ref retval; + retval.p = object; + object = 0; + return retval; + } + template operator auto_ptr() throw(){ + auto_ptr retval(object); + object = 0; + return retval; + } + +}; + +} //namespace std + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/new b/misc/uClibc++/include/cxx/new new file mode 100644 index 0000000000..665e783952 --- /dev/null +++ b/misc/uClibc++/include/cxx/new @@ -0,0 +1,64 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#ifndef __STD_NEW_OPERATOR +#define __STD_NEW_OPERATOR 1 + +#pragma GCC visibility push(default) + +namespace std{ + class _UCXXEXPORT bad_alloc : public exception {}; + + struct _UCXXEXPORT nothrow_t {}; + extern const nothrow_t nothrow; + + typedef void (*new_handler)(); + _UCXXEXPORT new_handler set_new_handler(new_handler new_p) throw(); +} + + +_UCXXEXPORT void* operator new(std::size_t numBytes) throw(std::bad_alloc); +_UCXXEXPORT void operator delete(void* ptr) throw(); + +_UCXXEXPORT void* operator new[](std::size_t numBytes) throw(std::bad_alloc); +_UCXXEXPORT void operator delete[](void * ptr) throw(); + +#ifndef NO_NOTHROW +_UCXXEXPORT void* operator new(std::size_t numBytes, const std::nothrow_t& ) throw(); +_UCXXEXPORT void operator delete(void* ptr, const std::nothrow_t& ) throw(); + +_UCXXEXPORT void* operator new[](std::size_t numBytes, const std::nothrow_t& ) throw(); +_UCXXEXPORT void operator delete[](void* ptr, const std::nothrow_t& ) throw(); +#endif + + /* Placement operators */ +inline void* operator new(std::size_t, void* ptr) throw() {return ptr; } +inline void operator delete(void* , void *) throw() { } + +inline void* operator new[](std::size_t, void *p) throw() { return p; } +inline void operator delete[](void* , void *) throw() {} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/numeric b/misc/uClibc++/include/cxx/numeric new file mode 100644 index 0000000000..25d1b27468 --- /dev/null +++ b/misc/uClibc++/include/cxx/numeric @@ -0,0 +1,161 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include + +#ifndef __STD_NUMERIC_HEADER +#define __STD_NUMERIC_HEADER 1 + +#pragma GCC visibility push(default) + +namespace std{ + template _UCXXEXPORT + T accumulate(InputIterator first, InputIterator last, T init) + { + while(first != last){ + init = init + *first; + ++first; + } + return init; + } + + template _UCXXEXPORT + T accumulate(InputIterator first, InputIterator last, T init, BinaryOperation binary_op) + { + while(first != last){ + init = binary_op(init, *first); + ++first; + } + return init; + } + + + template _UCXXEXPORT + T inner_product(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, T init) + { + while(first1 != last1){ + init = init + *first1 * *first2; + ++first1; + ++first2; + } + return init; + } + + template _UCXXEXPORT + T inner_product(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, T init, + BinaryOperation1 binary_op1, + BinaryOperation2 binary_op2) + { + while(first1 != last1){ + init = binary_op1(init, binary_op2(*first1, *first2)); + ++first1; + ++first2; + } + return init; + } + + template _UCXXEXPORT + OutputIterator partial_sum(InputIterator first, InputIterator last, + OutputIterator result) + { + OutputIterator temp(result); + *result = *first; + ++first; + ++result; + + while(first != last){ + *result = *first + *temp; + temp = result; + ++first; + ++result; + } + return result; + } + + + template _UCXXEXPORT + OutputIterator partial_sum(InputIterator first, InputIterator last, + OutputIterator result, BinaryOperation binary_op) + { + OutputIterator temp(result); + *result = *first; + ++first; + ++result; + + while(first != last){ + *result = binary_op(*first, *temp); + temp = result; + ++first; + ++result; + } + return result; + } + + + template _UCXXEXPORT + OutputIterator + adjacent_difference(InputIterator first, InputIterator last, + OutputIterator result) + { + OutputIterator temp(first); + *result = *first; + ++first; + ++result; + + while(first != last){ + *result = *first - *temp; + temp = first; + ++first; + ++result; + } + + return result; + } + + + template _UCXXEXPORT + OutputIterator + adjacent_difference(InputIterator first, InputIterator last, + OutputIterator result, BinaryOperation binary_op) + { + OutputIterator temp(first); + *result = *first; + ++first; + ++result; + + while(first != last){ + *result = binary_op(*first, *temp); + temp = first; + ++first; + ++result; + } + + return result; + } + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/ostream b/misc/uClibc++/include/cxx/ostream new file mode 100644 index 0000000000..55bace3a0e --- /dev/null +++ b/misc/uClibc++/include/cxx/ostream @@ -0,0 +1,510 @@ +/* Copyright (C) 2004-2008 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +#ifndef STD_HEADER_OSTREAM +#define STD_HEADER_OSTREAM 1 + +#include +#include +#include +#include +#include + +#pragma GCC visibility push(default) + +namespace std { + template class basic_ostream; + typedef basic_ostream ostream; + +#ifdef __UCLIBCXX_HAS_WCHAR__ + typedef basic_ostream wostream; +#endif + + template basic_ostream& endl(basic_ostream& os); + template basic_ostream& ends(basic_ostream& os); + template basic_ostream& flush(basic_ostream& os); + + template class _UCXXEXPORT basic_ostream + : virtual public basic_ios + { + public: + + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef traits traits_type; + + + _UCXXEXPORT basic_ostream(basic_streambuf* sb) + : basic_ios(sb) + { + basic_ios::init(sb); + } + virtual _UCXXEXPORT ~basic_ostream(); + + class sentry; + + _UCXXEXPORT basic_ostream& operator<<(basic_ostream& (*pf)(basic_ostream&)){ + return pf(*this); + } + _UCXXEXPORT basic_ostream& operator<<(basic_ios& (*pf)(basic_ios&)){ + pf(*this); + return *this; + } + _UCXXEXPORT basic_ostream& operator<<(ios_base& (*pf)(ios_base&)){ + pf(*this); + return *this; + } + basic_ostream& operator<<(bool n); + basic_ostream& operator<<(short n); + basic_ostream& operator<<(unsigned short n); + basic_ostream& operator<<(int n); + basic_ostream& operator<<(unsigned int n); + basic_ostream& operator<<(long n); + basic_ostream& operator<<(unsigned long n); + basic_ostream& operator<<(float f); + basic_ostream& operator<<(double f); + basic_ostream& operator<<(long double f); + basic_ostream& operator<<(void* p); + basic_ostream& operator<<(basic_streambuf* sb); + + _UCXXEXPORT basic_ostream& put(char_type c){ + if(basic_ostream::traits_type::eq_int_type( + basic_ios::mstreambuf->sputc(c), + basic_ostream::traits_type::eof())) + { + basic_ios::setstate(ios_base::eofbit); + } + return *this; + } + _UCXXEXPORT basic_ostream& write(const char_type* s, streamsize n){ + if(basic_ostream::traits_type::eq_int_type( + basic_ios::mstreambuf->sputn(s, n), + basic_ostream::traits_type::eof()) + ){ + basic_ios::setstate(ios_base::eofbit); + } + return *this; + } + _UCXXEXPORT basic_ostream& flush(){ + if(basic_ios::mstreambuf->pubsync() == -1){ + basic_ios::setstate(ios_base::badbit); + } + return *this; + } + _UCXXEXPORT pos_type tellp(){ + if(basic_ios::fail() != false){ + return pos_type(-1); + } + return basic_ios::rdbuf()->pubseekoff(0, ios_base::cur, ios_base::out); + } + _UCXXEXPORT basic_ostream& seekp(pos_type pos){ + if( basic_ios::fail() != true ){ + basic_ios::rdbuf()->pubseekpos(pos); + } + return *this; + } + _UCXXEXPORT basic_ostream& seekp(off_type off, ios_base::seekdir dir){ + if( basic_ios::fail() != true){ + basic_ios::rdbuf()->pubseekoff(off, dir); + } + return *this; + } + + _UCXXEXPORT void printout(const char_type* s, streamsize n){ +//david + streamsize extra = ios::width() - n; + if ((ios::flags()&ios::adjustfield) == ios::right){ + while (extra > 0) { + --extra; + put(ios::fill()); + } + } + write(s, n); + if ((ios::flags()&ios::adjustfield) == ios::left) { + while (extra > 0) { + --extra; + put(ios::fill()); + } + } + // Width value only applies for the next output operation. Reset to zero. + ios::width(0); + } + + protected: + basic_ostream(const basic_ostream &){ } + basic_ostream & operator=(const basic_ostream &){ return *this; } + }; + + //Implementations of template functions. To allow for partial specialization + + template _UCXXEXPORT basic_ostream::~basic_ostream(){ } + + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(bool n){ + sentry s(*this); + if( basic_ios::flags() & ios_base::boolalpha){ + if(n){ + printout("true", 4); + }else{ + printout("false", 5); + } + }else{ + if(n){ + printout("1", 1); + }else{ + printout("0", 1); + } + } + if(basic_ios::flags() & ios_base::unitbuf){ + flush(); + } + return *this; + } + + template _UCXXEXPORT basic_ostream& + basic_ostream::operator<<(unsigned short n){ + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } + + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(short n){ + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } + + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(int n){ + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } + + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(unsigned int n){ + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } + + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(long n){ + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } + + template _UCXXEXPORT basic_ostream& + basic_ostream::operator<<(unsigned long n) + { + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } + + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(float f){ + sentry s(*this); + __ostream_printout::printout(*this, f); + return *this; + } + + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(double f){ + sentry s(*this); + __ostream_printout::printout(*this, f); + return *this; + } + + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(long double f){ + sentry s(*this); + __ostream_printout::printout(*this, f); + return *this; + } + + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(void* p){ + sentry s(*this); + char buffer[20]; + printout(buffer, snprintf(buffer, 20, "%p", p) ); + if(basic_ios::flags() & ios_base::unitbuf){ + flush(); + } + return *this; + } + + template _UCXXEXPORT basic_ostream& + basic_ostream::operator<<(basic_streambuf* sb) + { + sentry s(*this); + if(sb == 0){ + basic_ios::setstate(ios_base::badbit); + return *this; + } + + typename traits::int_type c; + + while(basic_ios::good() && (c = sb->sbumpc()) != traits::eof() ){ + put(c); + } + + if(basic_ios::flags() & ios_base::unitbuf){ + flush(); + } + return *this; + } + + /*Template Specializations*/ + +#ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ +#ifndef __UCLIBCXX_COMPILE_OSTREAM__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT ostream::~basic_ostream(); + +#endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT ostream & ostream::flush(); + + template <> _UCXXEXPORT ostream & ostream::operator<<(bool n); + template <> _UCXXEXPORT ostream & ostream::operator<<(short int n); + template <> _UCXXEXPORT ostream & ostream::operator<<(unsigned short int n); + template <> _UCXXEXPORT ostream & ostream::operator<<(int n); + template <> _UCXXEXPORT ostream & ostream::operator<<(unsigned int n); + template <> _UCXXEXPORT ostream & ostream::operator<<(long n); + template <> _UCXXEXPORT ostream & ostream::operator<<(unsigned long n); + template <> _UCXXEXPORT ostream & ostream::operator<<(float f); + template <> _UCXXEXPORT ostream & ostream::operator<<(double f); + template <> _UCXXEXPORT ostream & ostream::operator<<(long double f); + template <> _UCXXEXPORT ostream & ostream::operator<<(void* p); + template <> _UCXXEXPORT ostream & ostream::operator<<(basic_streambuf >* sb); +#endif +#endif + + template > + class _UCXXEXPORT basic_ostream::sentry + { + bool ok; + public: + explicit _UCXXEXPORT sentry(basic_ostream& os): ok(true){ +//david + if(os.good() !=0){ //Prepare for output + } + //Flush any tied buffer + if(os.tie() !=0 ){ + os.tie()->flush(); + } + } + _UCXXEXPORT ~sentry() { } + _UCXXEXPORT operator bool() { + return ok; + } + }; + + +#ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ +#ifndef __UCLIBCXX_COMPILE_OSTREAM__ +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT ostream::sentry::sentry(ostream & os); + template <> _UCXXEXPORT ostream::sentry::~sentry(); + +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ +#endif +#endif + + + //Non - class functions + + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, charT c) + { + typename basic_ostream::sentry s(out); + out.put(c); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, char c) + { + typename basic_ostream::sentry s(out); + out.put(c); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, char c) + { + typename basic_ostream::sentry s(out); + out.put(c); + return out; + } + + // signed and unsigned + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, signed char c) + { + typename basic_ostream::sentry s(out); + out.put(c); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, unsigned char c) + { + typename basic_ostream::sentry s(out); + out.put(c); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const charT* c) + { + typename basic_ostream::sentry s(out); + out.printout(c, traits::length(c) ); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const char* c) + { + typename basic_ostream::sentry s(out); + out.printout(c, char_traits::length(c) ); + return out; + } +//david + // partial specializations + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const char* c) + { +//add by david + /* printf("hello\n"); + int i; + for(i=0;i::sentry s(out); + out.printout(c, traits::length(c)); + return out; + } + +#ifdef __UCLIBCXX_HAS_WCHAR__ + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const char* c) + { + typename basic_ostream::sentry s(out); + size_t numChars = char_traits::length(c); + wchar_t * temp = new wchar_t[numChars]; + + for(size_t i=0; i < numChars; ++i){ + temp[i] = out.widen(c[i]); + } + + out.printout(temp, numChars); + return out; + } +#endif + + // signed and unsigned + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const signed char* c) + { + typename basic_ostream::sentry s(out); + out.printout(reinterpret_cast(c), traits::length( reinterpret_cast(c))); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const unsigned char* c) + { + typename basic_ostream::sentry s(out); + out.printout(reinterpret_cast(c), traits::length( reinterpret_cast(c))); + return out; + } + + template _UCXXEXPORT basic_ostream& + endl(basic_ostream& os) + { + typename basic_ostream::sentry s(os); + os.put('\n'); + os.flush(); + return os; + } + + template _UCXXEXPORT basic_ostream& + ends(basic_ostream& os) + { + typename basic_ostream::sentry s(os); + os.put(traits::eos()); + return os; + } + + template _UCXXEXPORT basic_ostream& flush(basic_ostream& os){ + typename basic_ostream::sentry s(os); + os.flush(); + return os; + } + + +#ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ +#ifndef __UCLIBCXX_COMPILE_OSTREAM__ + template <> _UCXXEXPORT ostream & endl(ostream & os); + template <> _UCXXEXPORT ostream & flush(ostream & os); + template <> _UCXXEXPORT ostream & operator<<(ostream & out, char c); + template <> _UCXXEXPORT ostream & operator<<(ostream & out, const char* c); + template <> _UCXXEXPORT ostream & operator<<(ostream & out, unsigned char c); + template <> _UCXXEXPORT ostream & operator<<(ostream & out, unsigned const char* c); + +#endif +#endif + + +#ifndef __STRICT_ANSI__ + +//Support for output of long long data types + +template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, signed long long int i) +{ + typename basic_ostream::sentry s(os); + __ostream_printout::printout(os, i); + return os; +} + + +template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, unsigned long long int i) +{ + typename basic_ostream::sentry s(os); + __ostream_printout::printout(os, i); + return os; +} + + +#endif //__STRICT_ANSI__ + + + + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/ostream_helpers b/misc/uClibc++/include/cxx/ostream_helpers new file mode 100644 index 0000000000..6c3f9fc69c --- /dev/null +++ b/misc/uClibc++/include/cxx/ostream_helpers @@ -0,0 +1,491 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include +#include +#include + +#ifndef __STD_HEADER_OSTREAM_HELPERS +#define __STD_HEADER_OSTREAM_HELPERS 1 + +#pragma GCC visibility push(default) + +namespace std{ + + /* We are making the following template class for serveral reasons. Firstly, + * we want to keep the main ostream code neat and tidy. Secondly, we want it + * to be easy to do partial specialization of the ostream code so that it can + * be expanded and put into the library. This will allow us to make application + * code smaller at the expense of increased library size. This is a fair + * trade-off when there are multiple applications being compiled. Also, this + * feature will be used optionally via configuration options. It will also + * allow us to keep the code bases in sync, dramatically simplifying the + * maintenance required. We specialized for char because wchar and others + * require different scanf functions + */ + + + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const dataType n); + }; + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const signed long int n) + { + char buffer[20]; + const char * c_ld = "%ld"; + const char * c_lo = "%lo"; + const char * c_lX = "%lX"; + const char * c_lx = "%lx"; + const char * c_hashlo = "%#lo"; + const char * c_hashlX = "%#lX"; + const char * c_hashlx = "%#lx"; + + const char * formatString=0; + + if( stream.flags() & ios_base::dec){ + formatString = c_ld; + }else if( stream.flags() & ios_base::oct){ + if( stream.flags() & ios_base::showbase){ + formatString = c_hashlo; + }else{ + formatString = c_lo; + } + }else if (stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::showbase){ + if(stream.flags() & ios_base::uppercase){ + formatString = c_hashlX; + }else{ + formatString = c_hashlx; + } + }else{ + if(stream.flags() & ios_base::uppercase){ + formatString = c_lX; + }else{ + formatString = c_lx; + } + } + } + + stream.printout(buffer, snprintf(buffer, 20, formatString, n) ); + + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + + } + }; + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const unsigned long int n) + { + char buffer[20]; + const char * c_lo = "%lo"; + const char * c_lu = "%lu"; + const char * c_lX = "%lX"; + const char * c_lx = "%lx"; + const char * c_hashlo = "%#lo"; + const char * c_hashlX = "%#lX"; + const char * c_hashlx = "%#lx"; + const char * formatString=0; + + if( stream.flags() & ios_base::dec){ + formatString = c_lu; + }else if( stream.flags() & ios_base::oct){ + if( stream.flags() & ios_base::showbase){ + formatString = c_hashlo; + }else{ + formatString = c_lo; + } + }else if (stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::showbase){ + if(stream.flags() & ios_base::uppercase){ + formatString = c_hashlX; + }else{ + formatString = c_hashlx; + } + }else{ + if(stream.flags() & ios_base::uppercase){ + formatString = c_lX; + }else{ + formatString = c_lx; + } + } + } + + stream.printout(buffer, snprintf(buffer, 20, formatString, n)); + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + } + }; + +#ifndef __STRICT_ANSI__ + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const signed long long int n) + { + char buffer[28]; + const char * lld = "%lld"; + const char * llo = "%llo"; + const char * llX = "%llX"; + const char * llx = "%llx"; + const char * hashllo = "%#llo"; + const char * hashllX = "%#llX"; + const char * hashllx = "%#llx"; + const char * formatString=0; + + if( stream.flags() & ios_base::dec){ + formatString = lld; + }else if( stream.flags() & ios_base::oct){ + if( stream.flags() & ios_base::showbase){ + formatString = hashllo; + }else{ + formatString = llo; + } + }else if (stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::showbase){ + if(stream.flags() & ios_base::uppercase){ + formatString = hashllX; + }else{ + formatString = hashllx; + } + }else{ + if(stream.flags() & ios_base::uppercase){ + formatString = llX; + }else{ + formatString = llx; + } + } + } + + stream.printout(buffer, snprintf(buffer, 27, formatString, n) ); + + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + } + }; + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const unsigned long long int n) + { + char buffer[28]; + const char * llo = "%llo"; + const char * llu = "%llu"; + const char * llX = "%llX"; + const char * llx = "%llx"; + const char * hashllo = "%#llo"; + const char * hashllX = "%#llX"; + const char * hashllx = "%#llx"; + const char * formatString=0; + + if( stream.flags() & ios_base::dec){ + formatString = llu; + }else if( stream.flags() & ios_base::oct){ + if( stream.flags() & ios_base::showbase){ + formatString = hashllo; + }else{ + formatString = llo; + } + }else if (stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::showbase){ + if(stream.flags() & ios_base::uppercase){ + formatString = hashllX; + }else{ + formatString = hashllx; + } + }else{ + if(stream.flags() & ios_base::uppercase){ + formatString = llX; + }else{ + formatString = llx; + } + } + } + + stream.printout(buffer, snprintf(buffer, 27, formatString, n) ); + + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + } + }; + + +#endif //__STRICT_ANSI__ + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const double f) + { + char buffer[32]; + int length; + if(stream.flags() & ios_base::scientific){ + if(stream.flags() & ios_base::uppercase){ + length = snprintf(buffer, 32, "%*.*E", static_cast(stream.width()),static_cast(stream.precision()), f); + }else{ + length = snprintf(buffer, 32, "%*.*e", static_cast(stream.width()),static_cast(stream.precision()), f); + } + } else if(stream.flags() & ios_base::fixed){ + length = snprintf(buffer, 32, "%*.*f",static_cast(stream.width()),static_cast(stream.precision()), f); + } else { + length = snprintf(buffer, 32, "%*.*g",static_cast(stream.width()),static_cast(stream.precision()), f); + } + stream.printout(buffer, length); + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + } + }; + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const long double f) + { + char buffer[32]; + int length; + if(stream.flags() & ios_base::scientific){ + if(stream.flags() & ios_base::uppercase){ + length = snprintf(buffer, 32, "%*.*LE", static_cast(stream.width()), static_cast(stream.precision()), f); + }else{ + length = snprintf(buffer, 32, "%*.*Le", static_cast(stream.width()), static_cast(stream.precision()), f); + } + } else if(stream.flags() & ios_base::fixed){ + length = snprintf(buffer, 32, "%*.*Lf", static_cast(stream.width()), static_cast(stream.precision()), f); + } else { + length = snprintf(buffer, 32, "%*.*Lg", static_cast(stream.width()), static_cast(stream.precision()), f); + } + stream.printout(buffer, length); + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + + } + }; + +#ifdef __UCLIBCXX_HAS_WCHAR__ + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const signed long int n) + { + wchar_t buffer[20]; + if( stream.flags() & ios_base::dec){ + stream.printout(buffer, swprintf(buffer, 20, L"%ld", n)); + }else if( stream.flags() & ios_base::oct){ + if( stream.flags() & ios_base::showbase){ + stream.printout(buffer, swprintf(buffer, 20, L"%#lo", n)); + }else{ + stream.printout(buffer, swprintf(buffer, 20, L"%lo", n) ); + } + }else if (stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::showbase){ + if(stream.flags() & ios_base::uppercase){ + stream.printout(buffer, swprintf(buffer, 20, L"%#lX", n) ); + }else{ + stream.printout(buffer, swprintf(buffer, 20, L"%#lx", n) ); + } + }else{ + if(stream.flags() & ios_base::uppercase){ + stream.printout(buffer, swprintf(buffer, 20, L"%lX", n) ); + }else{ + stream.printout(buffer, swprintf(buffer, 20, L"%lx", n) ); + } + } + } + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + } + }; + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const unsigned long int n) + { + wchar_t buffer[20]; + if( stream.flags() & ios_base::dec){ + stream.printout(buffer, swprintf(buffer, 20, L"%lu", n)); + }else if( stream.flags() & ios_base::oct){ + if( stream.flags() & ios_base::showbase){ + stream.printout(buffer, swprintf(buffer, 20, L"%#lo", n)); + }else{ + stream.printout(buffer, swprintf(buffer, 20, L"%lo", n) ); + } + }else if (stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::showbase){ + if(stream.flags() & ios_base::uppercase){ + stream.printout(buffer, swprintf(buffer, 20, L"%#lX", n) ); + }else{ + stream.printout(buffer, swprintf(buffer, 20, L"%#lx", n) ); + } + }else{ + if(stream.flags() & ios_base::uppercase){ + stream.printout(buffer, swprintf(buffer, 20, L"%lX", n) ); + }else{ + stream.printout(buffer, swprintf(buffer, 20, L"%lx", n) ); + } + } + } + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + } + }; + +#ifndef __STRICT_ANSI__ + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const signed long long int n) + { + wchar_t buffer[28]; + if( stream.flags() & ios_base::dec){ + stream.printout(buffer, swprintf(buffer, 27, L"%lld", n)); + }else if( stream.flags() & ios_base::oct){ + if( stream.flags() & ios_base::showbase){ + stream.printout(buffer, swprintf(buffer, 27, L"%#llo", n)); + }else{ + stream.printout(buffer, swprintf(buffer, 27, L"%llo", n) ); + } + }else if (stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::showbase){ + if(stream.flags() & ios_base::uppercase){ + stream.printout(buffer, swprintf(buffer, 27, L"%#llX", n) ); + }else{ + stream.printout(buffer, swprintf(buffer, 27, L"%#llx", n) ); + } + }else{ + if(stream.flags() & ios_base::uppercase){ + stream.printout(buffer, swprintf(buffer, 27, L"%llX", n) ); + }else{ + stream.printout(buffer, swprintf(buffer, 27, L"%llx", n) ); + } + } + } + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + } + }; + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const unsigned long long int n) + { + wchar_t buffer[28]; + if( stream.flags() & ios_base::dec){ + stream.printout(buffer, swprintf(buffer, 27, L"%llu", n)); + }else if( stream.flags() & ios_base::oct){ + if( stream.flags() & ios_base::showbase){ + stream.printout(buffer, swprintf(buffer, 27, L"%#llo", n)); + }else{ + stream.printout(buffer, swprintf(buffer, 27, L"%llo", n) ); + } + }else if (stream.flags() & ios_base::hex){ + if(stream.flags() & ios_base::showbase){ + if(stream.flags() & ios_base::uppercase){ + stream.printout(buffer, swprintf(buffer, 27, L"%#llX", n) ); + }else{ + stream.printout(buffer, swprintf(buffer, 27, L"%#llx", n) ); + } + }else{ + if(stream.flags() & ios_base::uppercase){ + stream.printout(buffer, swprintf(buffer, 27, L"%llX", n) ); + }else{ + stream.printout(buffer, swprintf(buffer, 27, L"%llx", n) ); + } + } + } + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + } + }; + + +#endif //__STRICT_ANSI__ + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const double f) + { + wchar_t buffer[32]; + wchar_t format_string[32]; + if(stream.flags() & ios_base::scientific){ + if(stream.flags() & ios_base::uppercase){ + swprintf(format_string, 32, L"%%%u.%uE", static_cast(stream.width()), static_cast(stream.precision())); + }else{ + swprintf(format_string, 32, L"%%%u.%ue", static_cast(stream.width()), static_cast(stream.precision())); + } + } else if(stream.flags() & ios_base::fixed){ + swprintf(format_string, 32, L"%%%u.%uf", static_cast(stream.width()), static_cast(stream.precision())); + } else { + swprintf(format_string, 32, L"%%%u.%ug", static_cast(stream.width()), static_cast(stream.precision())); + } + stream.printout(buffer, swprintf(buffer, 32, format_string, f) ); + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + } + }; + + template class _UCXXEXPORT __ostream_printout{ + public: + static void printout(basic_ostream& stream, const long double f) + { + wchar_t buffer[32]; + wchar_t format_string[32]; + if(stream.flags() & ios_base::scientific){ + if(stream.flags() & ios_base::uppercase){ + swprintf(format_string, 32, L"%%%u.%uLE", static_cast(stream.width()), static_cast(stream.precision())); + }else{ + swprintf(format_string, 32, L"%%%u.%uLe", static_cast(stream.width()), static_cast(stream.precision())); + } + } else if(stream.flags() & ios_base::fixed){ + swprintf(format_string, 32, L"%%%u.%uLf", static_cast(stream.width()), static_cast(stream.precision())); + } else { + swprintf(format_string, 32, L"%%%u.%uLg", static_cast(stream.width()), static_cast(stream.precision())); + } + stream.printout(buffer, swprintf(buffer, 32, format_string, f) ); + if(stream.flags() & ios_base::unitbuf){ + stream.flush(); + } + } + }; + +#endif //__UCLIBCXX_HAS_WCHAR__ + +} + +#pragma GCC visibility pop + +#endif + + + diff --git a/misc/uClibc++/include/cxx/queue b/misc/uClibc++/include/cxx/queue new file mode 100644 index 0000000000..b817b1dfe7 --- /dev/null +++ b/misc/uClibc++/include/cxx/queue @@ -0,0 +1,126 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include + +#ifndef __HEADER_STD_QUEUE +#define __HEADER_STD_QUEUE 1 + +#pragma GCC visibility push(default) + +namespace std{ + + template > class _UCXXEXPORT queue{ + protected: + Container c; + public: + typedef typename Container::value_type value_type; + typedef typename Container::size_type size_type; + typedef Container container_type; + + explicit queue(const Container& a = Container()) : c(a) { } + + bool empty() const { return c.empty(); } + size_type size() const { return c.size(); } + value_type& front() { return c.front(); } + const value_type& front() const { return c.front(); } + value_type& back() { return c.back(); } + const value_type& back() const { return c.back(); } + void push(const value_type& x) { c.push_back(x); } + void pop() { c.pop_front(); } + }; + + + template _UCXXEXPORT bool + operator==(const queue& x, const queue& y) + { + return (x.c == y.c); + } + template _UCXXEXPORT bool + operator< (const queue& x, const queue& y) + { + return (x.c < y.c); + } + template _UCXXEXPORT bool + operator!=(const queue& x, const queue& y) + { + return (x.c != y.c); + } + template _UCXXEXPORT bool + operator> (const queue& x, const queue& y) + { + return (x.c > y.c); + } + template _UCXXEXPORT bool + operator>=(const queue& x, const queue& y) + { + return (x.c >= y.c); + } + template _UCXXEXPORT bool + operator<=(const queue& x, const queue& y) + { + return (x.c <= y.c); + } + + + template , + class Compare = less + > class _UCXXEXPORT priority_queue { + protected: + Container c; + Compare comp; + public: + typedef typename Container::value_type value_type; + typedef typename Container::size_type size_type; + typedef Container container_type; + + explicit priority_queue(const Compare& x = Compare(), const Container& a = Container()) + : c(a), comp(x) { make_heap(c.begin(), c.end(), comp) ; } + template priority_queue(InputIterator first, + InputIterator last, + const Compare& x = Compare(), + const Container& y= Container()) + : c(y), comp(c) + { + c.insert(c.end(), first, last); + make_heap(c.begin(), c.end(), comp); + } + + bool empty() const { return c.empty(); } + size_type size() const { return c.size(); } + const value_type& top() const { return c.front(); } + void push(const value_type& x){ + c.push_back(x); + push_heap(c.begin(), c.end(), comp); + } + void pop(){ + pop_heap(c.begin(), c.end(), comp); + c.pop_back(); + } + }; + +} + +#pragma GCC visibility pop + +#endif + + diff --git a/misc/uClibc++/include/cxx/set b/misc/uClibc++/include/cxx/set new file mode 100644 index 0000000000..f376e47008 --- /dev/null +++ b/misc/uClibc++/include/cxx/set @@ -0,0 +1,406 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + + + +#include +#include +#include +#include +#include +#include + +#ifndef __STD_HEADER_SET +#define __STD_HEADER_SET + +#pragma GCC visibility push(default) + +namespace std{ + + +template, class Allocator = allocator > class set; +template, class Allocator = allocator > class multiset; + + +/* This is the implementation for the set container. As noted above, it deviates + * from ISO spec by deriving from a base class in order to reduce code redundancy. + * More code could be reduced by convirting to virtual functions (thus allowing + * much of the erase and insert code to be duplicated), but that would deviate from + * the specifications too much to be worth the risk. + */ + + +//Implementation of set + + +template class _UCXXEXPORT set + : public __single_associative +{ + //Default value of allocator does not meet C++ standard specs, but it works for this library + //Deal with it +public: + + typedef __single_associative base; + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; + +// using base::value_compare; + + static const key_type v_t_k(const value_type v){ + return v; + } + + explicit set(const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(comp, al, v_t_k) { } + + template set(InputIterator first, InputIterator last, + const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(first, last, comp, al, v_t_k) { } + + set(const set& x) : base(x) { } + ~set() { } + + using base::operator=; + using base::operator==; + using base::operator!=; + + using base::insert; + using base::erase; + + using base::begin; + using base::end; + using base::rbegin; + using base::rend; + + using base::empty; + using base::size; + using base::max_size; + + + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; + +protected: + +}; + + +//Implementation of multiset + + +template class _UCXXEXPORT multiset + : public __multi_associative +{ + //Default value of allocator does not meet C++ standard specs, but it works for this library + //Deal with it +public: + + typedef __multi_associative base; + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; + + static const key_type v_t_k(const value_type v){ + return v; + } + + explicit multiset(const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(comp, al, v_t_k) { } + + template multiset(InputIterator first, InputIterator last, + const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(first, last, comp, al, v_t_k) { } + + + multiset(const multiset& x) : base(x) { } + ~multiset() { } + + using base::operator=; + using base::operator==; + using base::operator!=; + + using base::insert; + using base::erase; + + using base::begin; + using base::end; + using base::rbegin; + using base::rend; + + using base::empty; + using base::size; + using base::max_size; + + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; + + +protected: + +}; + + +/* Non-member functions. These are at the end because they are not associated with any + particular class. These will be implemented as I figure out exactly what all of + them are supposed to do, and I have time. + */ + + template _UCXXEXPORT bool operator< + (const set& x, const set& y) + { + typename set::const_iterator first1 = x.begin(); + typename set::const_iterator first2 = y.begin(); + typename set::const_iterator last1 = x.end(); + typename set::const_iterator last2 = y.end(); + + while(first1 != last1 && first2 != last2){ + if( *first1 < *first2 ){ + return true; + } + if( *first2 < *first1 ){ + return false; + } + ++first1; + ++first2; + } + return first1==last1 && first2 != last2; + } + + template _UCXXEXPORT bool operator> + (const set& x, const set& y) + { + typename set::const_iterator first1 = x.begin(); + typename set::const_iterator first2 = y.begin(); + typename set::const_iterator last1 = x.end(); + typename set::const_iterator last2 = y.end(); + + while(first1 != last1 && first2 != last2){ + if( *first1 > *first2 ){ + return true; + } + if( *first2 > *first1 ){ + return false; + } + ++first1; + ++first2; + } + return first1!=last1 && first2 == last2; + } + + template _UCXXEXPORT bool operator>= + (const set& x, const set& y) + { + typename set::const_iterator first1 = x.begin(); + typename set::const_iterator first2 = y.begin(); + typename set::const_iterator last1 = x.end(); + typename set::const_iterator last2 = y.end(); + + while(first1 != last1 && first2 != last2){ + if( *first1 > *first2 ){ + return true; + } + if( *first2 > *first1 ){ + return false; + } + ++first1; + ++first2; + } + return first1!=last1; + } + + template _UCXXEXPORT bool operator<= + (const set& x, const set& y) + { + typename set::const_iterator first1 = x.begin(); + typename set::const_iterator first2 = y.begin(); + typename set::const_iterator last1 = x.end(); + typename set::const_iterator last2 = y.end(); + + while(first1 != last1 && first2 != last2){ + if( *first1 < *first2 ){ + return true; + } + if( *first2 < *first1 ){ + return false; + } + ++first1; + ++first2; + } + return first2!=last2; + } + template _UCXXEXPORT void swap + (set& x, set& y) + { + x.swap(y); + } + + + template _UCXXEXPORT bool operator== + (const multiset& x, const multiset& y) + { + if(x.data == y.data){ + return true; + } + return false; + } + + template _UCXXEXPORT bool operator< + (const multiset& x, const multiset& y) + { + typename multiset::const_iterator first1 = x.begin(); + typename multiset::const_iterator first2 = y.begin(); + typename multiset::const_iterator last1 = x.end(); + typename multiset::const_iterator last2 = y.end(); + + while(first1 != last1 && first2 != last2){ + if( *first1 < *first2 ){ + return true; + } + if( *first2 < *first1 ){ + return false; + } + ++first1; + ++first2; + } + return first1==last1 && first2 != last2; + } + + template _UCXXEXPORT bool operator!= + (const multiset& x, const multiset& y) + { + typename multiset::const_iterator first1 = x.begin(); + typename multiset::const_iterator first2 = y.begin(); + typename multiset::const_iterator last1 = x.end(); + typename multiset::const_iterator last2 = y.end(); + + while(first1 != last1 && first2 != last2){ + if( *first1 != *first2 ){ + return true; + } + ++first1; + ++first2; + } + return first1!=last1 || first2 != last2; + } + + template _UCXXEXPORT bool operator> + (const multiset& x, const multiset& y) + { + typename multiset::const_iterator first1 = x.begin(); + typename multiset::const_iterator first2 = y.begin(); + typename multiset::const_iterator last1 = x.end(); + typename multiset::const_iterator last2 = y.end(); + + while(first1 != last1 && first2 != last2){ + if( *first1 > *first2 ){ + return true; + } + if( *first2 > *first1 ){ + return false; + } + ++first1; + ++first2; + } + return first1!=last1 && first2 == last2; + } + + template _UCXXEXPORT bool operator>= + (const multiset& x, const multiset& y) + { + typename multiset::const_iterator first1 = x.begin(); + typename multiset::const_iterator first2 = y.begin(); + typename multiset::const_iterator last1 = x.end(); + typename multiset::const_iterator last2 = y.end(); + + while(first1 != last1 && first2 != last2){ + if( *first1 > *first2 ){ + return true; + } + if( *first2 > *first1 ){ + return false; + } + ++first1; + ++first2; + } + return first1!=last1; + } + + template _UCXXEXPORT bool operator<= + (const multiset& x, const multiset& y) + { + typename multiset::const_iterator first1 = x.begin(); + typename multiset::const_iterator first2 = y.begin(); + typename multiset::const_iterator last1 = x.end(); + typename multiset::const_iterator last2 = y.end(); + + while(first1 != last1 && first2 != last2){ + if( *first1 < *first2 ){ + return true; + } + if( *first2 < *first1 ){ + return false; + } + ++first1; + ++first2; + } + return first2!=last2; + } + + template _UCXXEXPORT void swap + (multiset& x, multiset& y) + { + x.swap(y); + } + + + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/sstream b/misc/uClibc++/include/cxx/sstream new file mode 100644 index 0000000000..296985374c --- /dev/null +++ b/misc/uClibc++/include/cxx/sstream @@ -0,0 +1,384 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +#ifndef HEADER_STD_SSTREAM +#define HEADER_STD_SSTREAM 1 + +#include +#include +#include +#include +#include +#include + +#pragma GCC visibility push(default) + +namespace std{ + + template + class _UCXXEXPORT basic_stringbuf : public basic_streambuf + { + public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef typename Allocator::size_type size_type; + + explicit _UCXXEXPORT basic_stringbuf(ios_base::openmode which = ios_base::in | ios_base::out) + : data(), ielement(0), oelement(0) + { + basic_streambuf::openedFor = which; + } + + explicit _UCXXEXPORT basic_stringbuf(const basic_string& str, + ios_base::openmode which = ios_base::in | ios_base::out) + : data(str), ielement(0), oelement(0) + { + if(which & ios_base::ate){ + oelement = data.length(); + } + basic_streambuf::openedFor = which; + } + + virtual _UCXXEXPORT ~basic_stringbuf() { } + + _UCXXEXPORT basic_string str() const{ + return data; + } + + _UCXXEXPORT void str(const basic_string& s){ + data = s; + ielement = 0; + if(basic_streambuf::openedFor & ios_base::ate){ + oelement = data.length(); + }else{ + oelement = 0; + } + } + + protected: + virtual _UCXXEXPORT int sync(){ + return 0; + } + virtual _UCXXEXPORT int_type underflow(){ + if(ielement >= data.length()){ + return traits::eof(); + } + return traits::to_int_type(data[ielement]); + } + + virtual _UCXXEXPORT int_type uflow(){ + int_type retval = underflow(); + if(retval != traits::eof()){ + ++ielement; + } + return retval; + } + + virtual _UCXXEXPORT int_type pbackfail(int_type c = traits::eof()){ + //Error possibilities + if(ielement == 0){ + return traits::eof(); + } + if(ielement > data.length()){ + ielement = data.length(); + return traits::eof(); + } + //eof passed in + if(traits::eq_int_type(c,traits::eof())==true){ + --ielement; + return traits::not_eof(c); + } + if(traits::eq(traits::to_char_type(c),data[ielement-1]) == true){ + --ielement; + return c; + } + if(basic_streambuf::openedFor & ios_base::out){ + --ielement; + data[ielement] = c; + return c; + } + return traits::eof(); + } + + virtual _UCXXEXPORT int showmanyc(){ + return data.length() - ielement; + } + virtual _UCXXEXPORT streamsize xsgetn(char_type* c, streamsize n){ + streamsize i = 0; + while(ielement < data.length() && i < n ){ + c[i] = data[ielement]; + ++i; + ++ielement; + } + return i; + } + + virtual _UCXXEXPORT int_type overflow (int_type c = traits::eof()){ + //Nothing to do + if(traits::eq_int_type(c,traits::eof())){ + return traits::not_eof(c); + } + + //Actually add character, if possible + if(basic_streambuf::openedFor & ios_base::out){ + if(oelement >= data.length()){ + data.push_back(c); + }else{ + data[oelement] = c; + } + ++oelement; + return c; + } + //Not possible + return traits::eof(); + } + + virtual _UCXXEXPORT basic_streambuf* setbuf(charT*, streamsize){ + //This function does nothing + return this; + } + + virtual _UCXXEXPORT streamsize xsputn(const char_type* s, streamsize n){ + data.replace(oelement, n, s, n); + oelement += n; + return n; + } + + virtual _UCXXEXPORT pos_type seekoff(off_type off, ios_base::seekdir way, + ios_base::openmode which = ios_base::in | ios_base::out) + { + //Test for invalid option + if( (which & ios_base::in) && (which & ios_base::out) && (way == ios_base::cur)){ + return -1; + } + + //Calculate new location + size_type newpos = 0; + + if(way == ios_base::beg){ + newpos = off; + }else if(way == ios_base::cur){ + if(which & ios_base::out){ + newpos = data.length() + off; + } + if(which & ios_base::in){ + newpos = ielement + off; + } + + }else{ + newpos = data.length() + off; + } + + //Test for error conditions + if(newpos > data.length()){ + return -1; + } + + //Shuffle pointers + + if(which & ios_base::in){ + ielement = newpos; + } + if(which & ios_base::out){ + data.resize(newpos); + if(ielement > data.length()){ + ielement = data.length(); + } + } + + return newpos; + } + + virtual _UCXXEXPORT pos_type seekpos(pos_type sp, + ios_base::openmode which = ios_base::in | ios_base::out) + { + return seekoff(sp, ios_base::beg, which); + } + + basic_string data; + size_type ielement; + size_type oelement; + }; + + + template class _UCXXEXPORT basic_istringstream + : public basic_istream + { + public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + + explicit _UCXXEXPORT basic_istringstream(ios_base::openmode m = ios_base::in) + : basic_ios(&sb), basic_istream(&sb), sb(m) + { + } + explicit _UCXXEXPORT basic_istringstream( const basic_string& str, + ios_base::openmode which = ios_base::in) + : basic_ios(&sb), basic_istream(&sb), sb(str, which) + { + } + virtual _UCXXEXPORT ~basic_istringstream() { } + _UCXXEXPORT basic_stringbuf* rdbuf() const{ + return &sb; + } + _UCXXEXPORT basic_string str() const{ + return sb.str(); + } + _UCXXEXPORT void str(const basic_string& s){ + sb.str(s); + basic_istream::clear(); + } + private: + basic_stringbuf sb; + }; + + + template class _UCXXEXPORT basic_ostringstream + : public basic_ostream + { + public: + + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + explicit _UCXXEXPORT basic_ostringstream(ios_base::openmode m = ios_base::out) + : basic_ios(&sb), basic_ostream(&sb), sb(m) + { + } + explicit _UCXXEXPORT basic_ostringstream(const basic_string& str, + ios_base::openmode which = ios_base::out) + : basic_ios(&sb), basic_ostream(&sb), sb(str, which) + { + } + virtual _UCXXEXPORT ~basic_ostringstream() { } + + _UCXXEXPORT basic_stringbuf* rdbuf() const{ + return &sb; + } + _UCXXEXPORT basic_string str() const{ + return sb.str(); + } + _UCXXEXPORT void str(const basic_string& s){ + sb.str(s); + basic_ostream::clear(); + } + private: + basic_stringbuf sb; + }; + + + template class _UCXXEXPORT basic_stringstream + : public basic_iostream + { + public: + + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + explicit _UCXXEXPORT basic_stringstream(ios_base::openmode which = ios_base::out|ios_base::in) + : basic_ios(&sb), basic_iostream(&sb), sb(which) + { + } + + explicit _UCXXEXPORT basic_stringstream(const basic_string& str, + ios_base::openmode which = ios_base::out|ios_base::in) + : basic_ios(&sb), basic_iostream(&sb), sb(str, which) + { + } + virtual _UCXXEXPORT ~basic_stringstream(){ } + + _UCXXEXPORT basic_stringbuf* rdbuf(){ + return &sb; + } + _UCXXEXPORT basic_string str() const{ + return sb.str(); + } + _UCXXEXPORT void str(const basic_string& s){ + sb.str(s); + basic_iostream::clear(); + } + private: + basic_stringbuf sb; + }; + +#ifdef __UCLIBCXX_EXPAND_SSTREAM_CHAR__ +#ifndef __UCLIBCXX_COMPILE_SSTREAM__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT basic_stringbuf, allocator >:: + basic_stringbuf(ios_base::openmode which); + template <> _UCXXEXPORT basic_stringbuf, allocator >::~basic_stringbuf(); + +#endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT basic_string, allocator > + basic_stringbuf, allocator >::str() const; + + template <> _UCXXEXPORT basic_stringbuf, allocator >::int_type + basic_stringbuf, allocator >:: + pbackfail(basic_stringbuf, allocator >::int_type c); + + template <> _UCXXEXPORT basic_stringbuf, allocator >::pos_type + basic_stringbuf, allocator >:: + seekoff (basic_stringbuf, allocator >::off_type off, + ios_base::seekdir way, + ios_base::openmode which + ); + + template <> _UCXXEXPORT basic_stringbuf, allocator >::int_type + basic_stringbuf, allocator >:: + overflow (basic_stringbuf, allocator >::int_type c); + + template <> _UCXXEXPORT basic_stringbuf, allocator >::int_type + basic_stringbuf, allocator >::underflow (); + + template <> _UCXXEXPORT streamsize basic_stringbuf, allocator >:: + xsputn(const char* s, streamsize n); + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT basic_stringstream, allocator >:: + basic_stringstream(ios_base::openmode which); + template <> _UCXXEXPORT basic_stringstream, allocator >::~basic_stringstream(); + template <> _UCXXEXPORT basic_istringstream, allocator >::~basic_istringstream(); + template <> _UCXXEXPORT basic_ostringstream, allocator >::~basic_ostringstream(); + +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + +#endif +#endif + +#pragma GCC visibility pop + +} + + +#endif diff --git a/misc/uClibc++/include/cxx/stack b/misc/uClibc++/include/cxx/stack new file mode 100644 index 0000000000..d4861b3a42 --- /dev/null +++ b/misc/uClibc++/include/cxx/stack @@ -0,0 +1,84 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include + +#ifndef __HEADER_STD_STACK +#define __HEADER_STD_STACK 1 + +#pragma GCC visibility push(default) + +namespace std{ + + template > class _UCXXEXPORT stack{ + protected: + Container c; + + public: + typedef typename Container::value_type value_type; + typedef typename Container::size_type size_type; + typedef Container container_type; + + explicit stack(const Container& a = Container()) : c(a) { }; + bool empty() const { return c.empty(); } + size_type size() const { return c.size(); } + value_type& top() { return c.back(); } + const value_type& top() const { return c.back(); } + void push(const value_type& x) { c.push_back(x); } + void pop() { c.pop_back(); } + + bool operator==(const stack &x) const{ + return x.c == c; + } + + }; + + + template _UCXXEXPORT bool + operator< (const stack& x, const stack& y) + { + return (x.c < y.c); + } + template _UCXXEXPORT bool + operator!=(const stack& x, const stack& y) + { + return (x.c != y.c); + } + template _UCXXEXPORT bool + operator> (const stack& x, const stack& y) + { + return (x.c > y.c); + } + template _UCXXEXPORT bool + operator>=(const stack& x, const stack& y) + { + return (x.c >= y.c); + } + template _UCXXEXPORT bool + operator<=(const stack& x, const stack& y) + { + return (x.c <= y.c); + } + +} + +#pragma GCC visibility pop + +#endif + + diff --git a/misc/uClibc++/include/cxx/stdexcept b/misc/uClibc++/include/cxx/stdexcept new file mode 100644 index 0000000000..7557f24c49 --- /dev/null +++ b/misc/uClibc++/include/cxx/stdexcept @@ -0,0 +1,117 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#ifndef HEADER_STD_EXCEPTIONS +#define HEADER_STD_EXCEPTIONS 1 + +//Don't include support if not needed +#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ + +#pragma GCC visibility push(default) + +namespace std{ + +//typedef basic_string string; + +class _UCXXEXPORT logic_error : public exception { +protected: + string mstring; +public: + logic_error() throw(); + logic_error(const string& what_arg); + + virtual ~logic_error() throw() {} + virtual const char * what() const throw(); + +}; + +class _UCXXEXPORT domain_error : public logic_error { +public: + domain_error() : logic_error() {} + domain_error(const string& what_arg) : logic_error(what_arg) {} + virtual ~domain_error() throw() {} +}; + +class _UCXXEXPORT invalid_argument : public logic_error { +public: + invalid_argument() : logic_error(){} + invalid_argument(const string& what_arg) : logic_error(what_arg){} + virtual ~invalid_argument() throw() {} +}; + +class _UCXXEXPORT length_error : public logic_error { +public: + length_error() : logic_error(){} + length_error(const string& what_arg) : logic_error(what_arg){} + virtual ~length_error() throw() {} +}; + +class _UCXXEXPORT out_of_range : public logic_error{ +public: + out_of_range(); + out_of_range(const string & what_arg); + virtual ~out_of_range() throw() {} + +}; + +class _UCXXEXPORT runtime_error : public exception{ +protected: + string mstring; +public: + runtime_error(); + runtime_error(const string& what_arg); + + virtual ~runtime_error() throw() {} + virtual const char * what() const throw(); +}; + +class _UCXXEXPORT range_error : public runtime_error{ +public: + range_error() : runtime_error(){} + range_error(const string& what_arg) : runtime_error(what_arg) {} + virtual ~range_error() throw(){ } +}; + + +class _UCXXEXPORT overflow_error : public runtime_error{ +public: + overflow_error() : runtime_error(){} + overflow_error(const string& what_arg) : runtime_error(what_arg) {} + virtual ~overflow_error() throw(){} +}; + +class _UCXXEXPORT underflow_error : public runtime_error{ +public: + underflow_error() : runtime_error(){} + underflow_error(const string& what_arg) : runtime_error(what_arg) {} + virtual ~underflow_error() throw(){} +}; + + + +} + +#pragma GCC visibility pop + +#endif +#endif diff --git a/misc/uClibc++/include/cxx/streambuf b/misc/uClibc++/include/cxx/streambuf new file mode 100644 index 0000000000..0daa388f06 --- /dev/null +++ b/misc/uClibc++/include/cxx/streambuf @@ -0,0 +1,329 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include + +#ifndef HEADER_STD_STREAMBUF +#define HEADER_STD_STREAMBUF 1 + +#include + +#pragma GCC visibility push(default) + +namespace std{ + + template class _UCXXEXPORT basic_streambuf{ + public: +#ifdef __UCLIBCXX_SUPPORT_CDIR__ + friend ios_base::Init::Init(); +#endif + // Types: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef traits traits_type; + + virtual ~basic_streambuf(); + + locale pubimbue(const locale &loc); + + locale getloc() const{ + return myLocale; + } + + basic_streambuf* pubsetbuf(char_type* s, streamsize n){ + return setbuf(s,n); + } + pos_type pubseekoff(off_type off, + typename ios_base::seekdir way, + ios_base::openmode which = ios_base::in | + ios_base::out + ) + { + return seekoff(off,way,which); + } + pos_type pubseekpos(pos_type sp, ios_base::openmode which = ios_base::in | ios_base::out){ + return seekpos(sp,which); + } + int pubsync(){ + return sync(); + } + + streamsize in_avail(); + + int_type snextc(); + + int_type sbumpc(); + + int_type sgetc(); + + streamsize sgetn(char_type* s, streamsize n){ + return xsgetn(s,n); + } + + int_type sputbackc(char_type c); + + int_type sungetc(); + + int_type sputc(char_type c); + + streamsize sputn(const char_type* s, streamsize n){ + if(openedFor & ios_base::app){ + seekoff(0, ios_base::end, ios_base::out); + } + return xsputn(s, n); + } + + protected: + locale myLocale; + //Pointers for the "get" buffers + charT * mgbeg; + charT * mgnext; + charT * mgend; + + //Pointers for the "put" buffers + charT * mpbeg; + charT * mpnext; + charT * mpend; + + //In the event of null buffers Lets us know what the buffer is opened for + ios_base::openmode openedFor; + + basic_streambuf(); + + basic_streambuf(const basic_streambuf > &) + : myLocale(), + mgbeg(0), mgnext(0), mgend(0), mpbeg(0), mpnext(0), mpend(0), + openedFor(0) + { } + basic_streambuf > & operator=(const basic_streambuf > &){ + return *this; + } + + char_type* eback() const{ + return mgbeg; + } + char_type* gptr() const{ + return mgnext; + } + char_type* egptr() const{ + return mgend; + } + void gbump(int n){ + mgnext+=n; + } + void setg(char_type* gbeg, char_type* gnext, char_type* gend){ + mgbeg = gbeg; + mgnext = gnext; + mgend = gend; + } + + char_type* pbase() const{ + return mpbeg; + } + char_type* pptr() const{ + return mpnext; + } + char_type* epptr() const{ + return mpend; + } + void pbump(int n){ + mpnext+=n; + } + void setp(char_type* pbeg, char_type* pend){ + mpbeg = pbeg; + mpnext = pbeg; + mpend = pend; + } + + virtual void imbue(const locale &loc){ + myLocale = loc; + } + + //Virtual functions which we will not implement + + virtual basic_streambuf* setbuf(char_type* , streamsize){ + return 0; + } + virtual pos_type seekoff(off_type , ios_base::seekdir, + ios_base::openmode = ios_base::in | ios_base::out) + { + return 0; + } + virtual pos_type seekpos(pos_type , ios_base::openmode = ios_base::in | ios_base::out){ + return 0; + } + virtual int sync(){ + return 0; + } + + virtual int showmanyc(){ + return 0; + } + virtual streamsize xsgetn(char_type* , streamsize ){ + return 0; + } + virtual int_type underflow(){ + return traits_type::eof(); + } + virtual int_type uflow(){ + int_type ret = underflow(); + if (!traits_type::eq_int_type(ret, traits_type::eof())) + gbump(1); + return ret; + } + + virtual int_type pbackfail(int_type c = traits::eof()){ + return c; + } + virtual streamsize xsputn(const char_type* c, streamsize n){ + //This function is designed to be replaced by subclasses + for(streamsize i = 0; i< n; ++i){ + if(sputc(c[i]) == traits::eof()){ + return i; + } + } + return n; + } + virtual int_type overflow (int_type c = traits::eof()){ + return c; + } + }; + + typedef basic_streambuf streambuf; +#ifdef __UCLIBCXX_HAS_WCHAR__ + typedef basic_streambuf wstreambuf; +#endif + + +//Definitions put below to allow for easy expansion of code + + template basic_streambuf::~basic_streambuf(){ } + + template locale basic_streambuf::pubimbue(const locale &loc){ + locale temp = myLocale; + myLocale = loc; + return temp; + } + + template streamsize basic_streambuf::in_avail(){ + if(mgend !=0 && mgnext !=0){ + return mgend - mgnext; + } + return showmanyc(); + } + + template typename basic_streambuf::int_type basic_streambuf::sbumpc(){ + if(mgbeg == 0 || mgnext == mgend){ + return uflow(); + } + int_type retval = T::to_int_type(*gptr()); + gbump(1); + return retval; + } + + template typename basic_streambuf::int_type basic_streambuf::snextc(){ + if(sbumpc() == T::eof() ){ + return T::eof() ; + } + return sgetc(); + } + + template typename basic_streambuf::int_type basic_streambuf::sgetc(){ + if(mgbeg == 0 || mgnext == mgend){ + return underflow(); + } + return T::to_int_type(*gptr()); + } + + template typename basic_streambuf::int_type basic_streambuf::sputbackc(char_type c){ + if(mgbeg == 0 || mgnext == mgbeg || !T::eq(c, gptr()[-1] )){ + return pbackfail(T::to_int_type(c)); + } + gbump(-1); + return T::to_int_type(*gptr()); + } + + template typename basic_streambuf::int_type basic_streambuf::sungetc(){ + if(mgbeg == 0 || mgnext == mgbeg){ + return ios_base::failbit; + } + gbump(-1); + return T::to_int_type(*gptr()); + } + + template typename basic_streambuf::int_type basic_streambuf::sputc(char_type c){ + if(openedFor & ios_base::app){ + seekoff(0, ios_base::end, ios_base::out); + } + if(mpnext < mpend){ + *mpnext = c; + ++mpnext; + }else{ + return overflow( T::to_int_type(c) ); + } + return T::to_int_type(c); + } + + template basic_streambuf::basic_streambuf() + : myLocale(), + mgbeg(0), mgnext(0), mgend(0), mpbeg(0), mpnext(0), mpend(0), + openedFor(0) + { } + + + + + + +#ifdef __UCLIBCXX_EXPAND_STREAMBUF_CHAR__ +#ifndef __UCLIBCXX_COMPILE_STREAMBUF__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT streambuf::basic_streambuf(); + template <> _UCXXEXPORT streambuf::~basic_streambuf(); + +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT locale streambuf::pubimbue(const locale &loc); + template <> _UCXXEXPORT streamsize streambuf::in_avail(); + template <> _UCXXEXPORT streambuf::int_type streambuf::sbumpc(); + template <> _UCXXEXPORT streambuf::int_type streambuf::snextc(); + template <> _UCXXEXPORT streambuf::int_type streambuf::sgetc(); + template <> _UCXXEXPORT streambuf::int_type streambuf::sputbackc(char_type c); + template <> _UCXXEXPORT streambuf::int_type streambuf::sungetc(); + template <> _UCXXEXPORT streambuf::int_type streambuf::sputc(char_type c); + +#endif +#endif + + + + + +} + +#pragma GCC visibility pop + +#endif diff --git a/misc/uClibc++/include/cxx/string b/misc/uClibc++/include/cxx/string new file mode 100644 index 0000000000..7826ce77c1 --- /dev/null +++ b/misc/uClibc++/include/cxx/string @@ -0,0 +1,1042 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include +#include +#include + + +#ifdef __UCLIBCXX_HAS_WCHAR__ +#include +#include +#endif + +#ifndef __HEADER_STD_STRING +#define __HEADER_STD_STRING 1 + +#pragma GCC visibility push(default) + +namespace std{ + + //Basic basic_string + + template, class A = allocator > class basic_string; + + typedef basic_string string; + #ifdef __UCLIBCXX_HAS_WCHAR__ + typedef basic_string wstring; + #endif + + + +//template, class A = allocator > class _UCXXEXPORT basic_string +template class basic_string + : public std::vector +{ +public: + typedef Tr traits_type; + typedef typename Tr::char_type value_type; + typedef A allocator_type; + typedef typename A::size_type size_type; + typedef typename A::difference_type difference_type; + + typedef typename A::reference reference; + typedef typename A::const_reference const_reference; + typedef typename A::pointer pointer; + typedef typename A::const_pointer const_pointer; + + typedef typename vector::iterator iterator; + typedef typename vector::const_iterator const_iterator; + + typedef typename vector::reverse_iterator reverse_iterator; + typedef typename vector::const_reverse_iterator const_reverse_iterator; + + static const size_type npos = (size_type)-1; + + explicit _UCXXEXPORT basic_string(const A& al = A()) : vector(al){ return; } + + _UCXXEXPORT basic_string(const basic_string& str, size_type pos = 0, size_type n = npos, const A& al = A()); //Below + + _UCXXEXPORT basic_string(const Ch* s, size_type n, const A& al = A()) + : vector(al) + { + if(n == npos){ + __throw_out_of_range(); + } + if(s > 0){ + resize(n); + Tr::copy(vector::data, s, vector::elements); + } + } + + _UCXXEXPORT basic_string(const Ch* s, const A& al = A()); //Below + + _UCXXEXPORT basic_string(size_type n, Ch c, const A& al = A()) + : vector(n, c, al) + { + } + + template _UCXXEXPORT basic_string(InputIterator begin, InputIterator end, const A& a = A()) + :vector(begin, end) + { + + } + + _UCXXEXPORT ~basic_string() { + return; + } + + _UCXXEXPORT basic_string& operator=(const basic_string& str); //Below + + _UCXXEXPORT basic_string& operator=(const Ch* s){ + vector::clear(); + if(s!=0){ + size_type len = Tr::length(s); + resize(len); + Tr::copy( vector::data, s, len); + } + return *this; + } + + _UCXXEXPORT basic_string& operator=(Ch c){ + vector::clear(); + vector::push_back(c); + return *this; + } + + inline _UCXXEXPORT size_type length() const { return vector::size(); } + + void _UCXXEXPORT resize(size_type n, Ch c = Ch()){ + vector::resize(n, c); + } + + _UCXXEXPORT basic_string& operator+=(const basic_string& str){ + return append(str); + } + + _UCXXEXPORT basic_string& operator+=(const Ch * s){ + return append(s); + } + + _UCXXEXPORT basic_string& operator+=(Ch c){ + vector::push_back(c); + return *this; + } + + _UCXXEXPORT basic_string& append(const basic_string& str){ + size_t temp = vector::elements; + resize(vector::elements + str.elements); + Tr::copy( vector::data + temp, str.vector::data, str.elements); + + return *this; + } + + _UCXXEXPORT basic_string& append(const basic_string& str, size_type pos, size_type n){ + if(pos > str.size()){ + __throw_out_of_range(); + } + + size_type rlen = str.elements - pos; + if(rlen > n){ + rlen = n; + } + if(vector::elements > npos - rlen){ + __throw_length_error(); + } + size_t temp = vector::elements; + resize(vector::elements + rlen); + Tr::copy( vector::data + temp, str.vector::data + pos, rlen); + return *this; + } + + _UCXXEXPORT basic_string& append(const Ch* s, size_type n){ + size_t temp = vector::elements; + resize(vector::elements + n); + Tr::copy( vector::data + temp, s, n); + return *this; + } + + _UCXXEXPORT basic_string& append(const Ch* s){ + size_type strLen = Tr::length(s); + size_t temp = vector::elements; + resize(vector::elements + strLen); + Tr::copy( vector::data + temp, s, strLen); + return *this; + } + + _UCXXEXPORT basic_string& append(size_type n, Ch c){ + vector::resize(vector::elements + n, c); + return *this; + } + + _UCXXEXPORT basic_string& assign(const basic_string& str){ + operator=(str); + return *this; + } + + _UCXXEXPORT basic_string& assign(const basic_string& str, size_type pos, size_type n){ + if(pos > str.elements){ + __throw_out_of_range(); + } + size_type r = str.elements - pos; + if(r > n){ + r = n; + } + resize(r); + Tr::copy(vector::data, str.vector::data + pos, r); + return *this; + } + + _UCXXEXPORT basic_string& assign(const Ch* s, size_type n){ + resize(n); + Tr::copy(vector::data, s, n); + return *this; + } + + _UCXXEXPORT basic_string& assign(const Ch* s){ + size_type len = Tr::length(s); + return assign(s, len); + } + + _UCXXEXPORT basic_string& assign(size_type n, Ch c){ + vector::clear(); + vector::resize(n, Ch() ); + return *this; + } + + template _UCXXEXPORT basic_string& assign(InputIterator first, InputIterator last){ + vector::resize(0, Ch()); + while (first != last){ + append(*first); + ++first; + } + return *this; + } + + _UCXXEXPORT basic_string& insert(size_type pos1, const basic_string& str, size_type pos2=0, size_type n=npos){ + if(pos1 > vector::elements || pos2 > str.elements){ + __throw_out_of_range(); + } + size_type r = str.elements - pos2; + if( r > n){ + r = n; + } + if(vector::elements > npos - r){ + __throw_length_error(); + } + size_type temp = vector::elements; + resize(vector::elements + r); + Tr::move(vector::data + pos1 + r, vector::data + pos1, temp - pos1); + Tr::copy(vector::data + pos1, str.vector::data + pos2, r); + return *this; + } + + _UCXXEXPORT basic_string& insert(size_type pos, const Ch* s, size_type n){ + if(pos > vector::elements){ + __throw_out_of_range(); + } + if(vector::elements > npos - n){ + __throw_length_error(); + } + size_type temp = vector::elements; + resize(vector::elements + n); + Tr::move(vector::data + pos + n, vector::data + pos, temp - pos); + Tr::copy(vector::data + pos, s, n); + return *this; + } + + inline _UCXXEXPORT basic_string& insert(size_type pos, const Ch* s){ + size_type len = Tr::length(s); + return insert(pos, s, len); + } + + _UCXXEXPORT basic_string& insert(size_type pos, size_type n, Ch c){ + if(pos > vector::elements){ + __throw_out_of_range(); + } + if(vector::elements > npos - n){ + __throw_length_error(); + } + size_type temp = vector::elements; + resize(vector::elements + n); + Tr::move(vector::data + pos + n, vector::data + pos, temp - pos); + Tr::assign(vector::data + pos, n, c); + return *this; + } + + using vector::insert; +// void insert(iterator p, size_type n, charT c); +// template void insert(iterator p, InputIterator first, InputIterator last); + + _UCXXEXPORT basic_string& erase(size_type pos = 0, size_type n = npos){ + size_type xlen = vector::elements - pos; + + if(xlen > n){ + xlen = n; + } + size_type temp = vector::elements; + + Tr::move(vector::data + pos, vector::data + pos + xlen, temp - pos - xlen); + resize(temp - xlen); + return *this; + } + + _UCXXEXPORT iterator erase(iterator position){ + if(position == vector::end()){ + return position; + } + + ++position; + + iterator temp = position; + + while(position != vector::end()){ + *(position-1) = *position; + ++position; + } + vector::pop_back(); + return temp; + } + + _UCXXEXPORT iterator erase(iterator first, iterator last){ + size_t count = last - first; + + iterator temp = last; + + while(last != vector::end()){ + *(last - count) = *last; + ++last; + } + + resize( vector::elements-count); + + return temp; + } + + _UCXXEXPORT basic_string& + replace(size_type pos1, size_type n1, const basic_string& str, size_type pos2=0, size_type n2=npos) + { + if(pos1 > vector::elements){ + __throw_out_of_range(); + } + size_type xlen = vector::elements - pos1; + if(xlen > n1){ + xlen = n1; + } + size_type rlen = str.elements - pos2; + if(rlen > n2){ + rlen = n2; + } + if((vector::elements - xlen) >= (npos - rlen)){ + __throw_length_error(); + } + + size_t temp = vector::elements; + + if(rlen > xlen){ //Only if making larger + resize(temp - xlen + rlen); + } + + //Final length = vector::elements - xlen + rlen + //Initial block is of size pos1 + //Block 2 is of size len + + Tr::move(vector::data + pos1 + rlen, vector::data + pos1 + xlen, temp - pos1 - xlen); + Tr::copy(vector::data + pos1, str.vector::data + pos2, rlen); + resize(temp - xlen + rlen); + return *this; + } + + _UCXXEXPORT basic_string& replace(size_type pos, size_type n1, const Ch* s, size_type n2){ + return replace(pos,n1,basic_string(s,n2)); + + } + + inline _UCXXEXPORT basic_string& replace(size_type pos, size_type n1, const Ch* s){ + return replace(pos,n1,basic_string(s)); + } + + _UCXXEXPORT basic_string& replace(size_type pos, size_type n1, size_type n2, Ch c){ + return replace(pos,n1,basic_string(n2,c)); + } +// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, const basic_string& str); +// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, const Ch* s, size_type n); +// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, const Ch* s); +// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, size_type n, Ch c); +/* template _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, + InputIterator j1, InputIterator j2);*/ + + size_type _UCXXEXPORT copy(Ch* s, size_type n, size_type pos = 0) const{ + if(pos > vector::elements){ + __throw_out_of_range(); + } + size_type r = vector::elements - pos; + if(r > n){ + r = n; + } + Tr::copy(s, vector::data + pos, r); + return r; + } + + _UCXXEXPORT void swap(basic_string& s){ + //Data pointers + + vector::swap(s); + } + + _UCXXEXPORT const Ch* c_str() const{ + const_cast *>(this)->reserve(vector::elements+1); + vector::data[vector::elements] = 0; //Add 0 at the end + return vector::data; + } + + _UCXXEXPORT const Ch* data() const{ + return vector::data; + } + _UCXXEXPORT allocator_type get_allocator() const{ + return vector::a; + } + + _UCXXEXPORT size_type find (const basic_string& str, size_type pos = 0) const; //Below + + _UCXXEXPORT size_type find (const Ch* s, size_type pos, size_type n) const{ + return find(basic_string(s,n), pos); + } + _UCXXEXPORT size_type find (const Ch* s, size_type pos = 0) const{ + return find(basic_string(s), pos); + } + _UCXXEXPORT size_type find (Ch c, size_type pos = 0) const{ + for(size_type i = pos; i < length(); ++i){ + if(this->operator[](i) == c){ + return i; + } + } + return npos; + } + _UCXXEXPORT size_type rfind(const basic_string& str, size_type pos = npos) const{ + if(pos >= length()){ + pos = length(); + } + for(size_type i = pos; i > 0; --i){ + if(str == substr(i-1, str.length())){ + return i-1; + } + } + return npos; + } + _UCXXEXPORT size_type rfind(const Ch* s, size_type pos, size_type n) const{ + return rfind(basic_string(s,n),pos); + } + _UCXXEXPORT size_type rfind(const Ch* s, size_type pos = npos) const{ + return rfind(basic_string(s),pos); + } + _UCXXEXPORT size_type rfind(Ch c, size_type pos = npos) const{ + return rfind(basic_string(1,c),pos); + } + + _UCXXEXPORT size_type find_first_of(const basic_string& str, size_type pos = 0) const{ + for(size_type i = pos; i < length(); ++i){ + for(size_type j = 0; j < str.length() ; ++j){ + if( Tr::eq(str[j], this->operator[](i)) ){ + return i; + } + } + } + return npos; + } + + _UCXXEXPORT size_type find_first_of(const Ch* s, size_type pos, size_type n) const{ + return find_first_of(basic_string(s,n),pos); + } + _UCXXEXPORT size_type find_first_of(const Ch* s, size_type pos = 0) const{ + return find_first_of(basic_string(s),pos); + } + _UCXXEXPORT size_type find_first_of(Ch c, size_type pos = 0) const{ + for(size_type i = pos; i< length(); ++i){ + if( Tr::eq(this->operator[](i), c) ){ + return i; + } + } + return npos; + } + + _UCXXEXPORT size_type find_last_of (const basic_string& str, size_type pos = npos) const{ + if(pos > length()){ + pos = length(); + } + for(size_type i = pos; i >0 ; --i){ + for(size_type j = 0 ; j < str.length(); ++j){ + if( Tr::eq(this->operator[](i-1), str[j]) ){ + return i-1; + } + } + } + return npos; + } + _UCXXEXPORT size_type find_last_of (const Ch* s, size_type pos, size_type n) const{ + return find_last_of(basic_string(s,n),pos); + } + _UCXXEXPORT size_type find_last_of (const Ch* s, size_type pos = npos) const{ + return find_last_of(basic_string(s),pos); + } + _UCXXEXPORT size_type find_last_of (Ch c, size_type pos = npos) const{ + if(pos > length()){ + pos = length(); + } + for(size_type i = pos; i >0 ; --i){ + if( Tr::eq(this->operator[](i-1), c) ){ + return i-1; + } + } + return npos; + } + + _UCXXEXPORT size_type find_first_not_of(const basic_string& str, size_type pos = 0) const{ + bool foundCharacter; + for(size_type i = pos; i < length(); ++i){ + foundCharacter = false; + for(size_type j = 0; j < str.length() ; ++j){ + if( Tr::eq(str[j], this->operator[](i)) ){ + foundCharacter = true; + } + } + if(foundCharacter == false){ + return i; + } + } + return npos; + } + + _UCXXEXPORT size_type find_first_not_of(const Ch* s, size_type pos, size_type n) const{ + return find_first_not_of(basic_string(s,n),pos); + } + _UCXXEXPORT size_type find_first_not_of(const Ch* s, size_type pos = 0) const{ + return find_first_not_of(basic_string(s),pos); + } + _UCXXEXPORT size_type find_first_not_of(Ch c, size_type pos = 0) const{ + for(size_type i = pos; i < length() ; ++i){ + if(this->operator[](i) != c){ + return i; + } + } + return npos; + } + _UCXXEXPORT size_type find_last_not_of (const basic_string& str, size_type pos = npos) const{ + size_type xpos(length() - 1); + if(xpos > pos){ + xpos = pos; + } + + while(xpos != npos && npos != str.find_first_of(this->at(xpos))){ + --xpos; + } + + return xpos; + } + + _UCXXEXPORT size_type find_last_not_of (const Ch* s, size_type pos, size_type n) const{ + return find_last_not_of(basic_string(s,n),pos); + } + _UCXXEXPORT size_type find_last_not_of (const Ch* s, size_type pos = npos) const{ + return find_last_not_of(basic_string(s),pos); + } + _UCXXEXPORT size_type find_last_not_of (Ch c, size_type pos = npos) const{ + size_type xpos(length() - 1); + if(xpos > pos){ + xpos = pos; + } + while(xpos != npos && Tr::eq(this->at(xpos), c)){ + --xpos; + } + return xpos; + + } + + _UCXXEXPORT basic_string substr(size_type pos = 0, size_type n = npos) const; + + _UCXXEXPORT int compare(const basic_string& str) const{ + size_type rlen = vector::elements; + if(rlen > str.elements){ + rlen = str.elements; + } + int retval = Tr::compare(vector::data, str.vector::data, rlen); + if(retval == 0){ + if(vector::elements < str.elements){ + retval = -1; + } + if(vector::elements > str.elements){ + retval = 1; + } + } + return retval; + } + + _UCXXEXPORT int compare(size_type pos1, size_type n1, const basic_string& str, + size_type pos2=0, size_type n2=npos) const{ + size_type len1 = vector::elements - pos1; + if(len1 > n1){ + len1 = n1; + } + size_type len2 = str.vector::elements - pos2; + if(len2 > n2){ + len2 = n2; + } + size_type rlen = len1; + if(rlen > len2){ + rlen = len2; + } + int retval = Tr::compare(vector::data + pos1, str.vector::data + pos2, rlen); + if(retval == 0){ + if(len1 < len2){ + retval = -1; + } + if(len1 > len2){ + retval = 1; + } + } + return retval; + } + + _UCXXEXPORT int compare(const Ch* s) const{ + size_type slen = Tr::length(s); + size_type rlen = slen; + if(rlen > vector::elements){ + rlen=vector::elements; + } + int retval = Tr::compare(vector::data, s, rlen); + if(retval==0){ + if(vector::elements < slen){ + retval = -1; + } + if(vector::elements > slen){ + retval = 1; + } + } + return retval; + } + + _UCXXEXPORT int compare(size_type pos1, size_type n1, const Ch* s, size_type n2 = npos) const{ + size_type len1 = vector::elements - pos1; + if(len1 > n1){ + len1 = n1; + } + size_type slen = Tr::length(s); + size_type len2 = slen; + if(len2 > n2){ + len2 = n2; + } + size_type rlen = len1; + if(rlen > len2){ + rlen = len2; + } + int retval = Tr::compare(vector::data + pos1, s, rlen); + if(retval == 0){ + if(len1 < len2){ + retval = -1; + } + if(len1 > len2){ + retval = 1; + } + } + return retval; + } + +}; + + +//Functions + +template _UCXXEXPORT basic_string::basic_string(const Ch* s, const A& al) + : vector(al) +{ + if(s!=0){ + size_type temp = Tr::length(s); + append(s, temp); + } +} + +template _UCXXEXPORT basic_string:: + basic_string(const basic_string& str, size_type pos, size_type n, const A& al) + : vector(al) +{ + if(pos>str.size()){ + __throw_out_of_range(); + } + size_type rlen = str.size() - pos; + if( rlen > n){ + rlen = n; + } + resize(rlen); + Tr::copy(vector::data, str.vector::data + pos, vector::elements); +} + +template _UCXXEXPORT basic_string& + basic_string::operator=(const basic_string & str) +{ + if(&str == this){ //Check if we are doing a=a + return *this; + } + vector::clear(); + resize(str.elements); + Tr::copy( vector::data, str.vector::data, str.elements); + return *this; +} + + +template _UCXXEXPORT typename basic_string::size_type + basic_string::find (const basic_string& str, size_type pos) const +{ + if(str.length() > length()){ + return npos; + } + size_type max_string_start = 1 + length() - str.length(); + for(size_type i = pos; i < max_string_start; ++i){ + if(str == substr(i, str.length())){ + return i; + } + } + return npos; +} + + +template + _UCXXEXPORT basic_string basic_string::substr(size_type pos, size_type n) const +{ + if(pos > vector::elements){ + __throw_out_of_range(); + } + size_type rlen = vector::elements - pos; + if(rlen > n){ + rlen = n; + } + return basic_string(vector::data + pos,rlen); +} + + + + +#ifdef __UCLIBCXX_EXPAND_STRING_CHAR__ +#ifndef __UCLIBCXX_COMPILE_STRING__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT string::basic_string(const allocator &); + template <> _UCXXEXPORT string::basic_string(size_type n, char c, const allocator & ); + template <> _UCXXEXPORT string::basic_string(const char* s, const allocator& al); + template <> _UCXXEXPORT string::basic_string(const basic_string& str, size_type pos, size_type n, const allocator& al); + template <> _UCXXEXPORT string::~basic_string(); + +#endif + + template <> _UCXXEXPORT string & string::append(const char * s, size_type n); + + + template <> _UCXXEXPORT string::size_type string::find(const string & str, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find(const char* s, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find (char c, size_type pos) const; + + template <> _UCXXEXPORT string::size_type string::rfind(const string & str, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::rfind(char c, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::rfind(const char* s, size_type pos) const; + + template <> _UCXXEXPORT string::size_type string::find_first_of(const string &, size_type) const; + template <> _UCXXEXPORT string::size_type string::find_first_of(const char *, size_type pos, size_type n) const; + template <> _UCXXEXPORT string::size_type string::find_first_of(const char*, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find_first_of(char c, size_type pos) const; + + template <> _UCXXEXPORT string::size_type string::find_last_of (const string & , size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos, size_type n) const; + template <> _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find_last_of (char c, size_type pos) const; + + template <> _UCXXEXPORT string::size_type string::find_first_not_of(const string &, size_type) const; + template <> _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type, size_type) const; + template <> _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type) const; + template <> _UCXXEXPORT string::size_type string::find_first_not_of(char c, size_type) const; + + template <> _UCXXEXPORT int string::compare(const string & str) const; + template <> _UCXXEXPORT int string::compare( + size_type pos1, size_type n1, const string & str, size_type pos2, size_type n2) const; + + template <> _UCXXEXPORT string string::substr(size_type pos, size_type n) const; + + template <> _UCXXEXPORT string & string::operator=(const string & str); + template <> _UCXXEXPORT string & string::operator=(const char * s); + +#endif +#endif + + + + +//typedef basic_string string; + +template _UCXXEXPORT basic_string + operator+(const basic_string& lhs, const basic_string& rhs) +{ + basic_string temp(lhs); + temp.append(rhs); + return temp; +} + +template _UCXXEXPORT basic_string + operator+(const charT* lhs, const basic_string& rhs) +{ + basic_string temp(lhs); + temp.append(rhs); + return temp; +} + + +template _UCXXEXPORT basic_string + operator+(charT lhs, const basic_string& rhs) +{ + basic_string temp(1, lhs); + temp.append(rhs); + return temp; +} + +template _UCXXEXPORT basic_string + operator+(const basic_string& lhs, const charT* rhs) +{ + basic_string temp(lhs); + temp.append(rhs); + return temp; +} + +template _UCXXEXPORT basic_string + operator+(const basic_string& lhs, charT rhs) +{ + basic_string temp(lhs); + temp+=rhs; + return temp; +} + +template _UCXXEXPORT bool + operator==(const basic_string& lhs, const basic_string& rhs) +{ + if(lhs.compare(rhs) == 0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator==(const charT* lhs, const basic_string& rhs) +{ + if(rhs.compare(lhs) == 0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator==(const basic_string& lhs, const charT* rhs) +{ + if(lhs.compare(rhs)==0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator!=(const basic_string& lhs, const basic_string& rhs) +{ + if(lhs.compare(rhs) !=0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator!=(const charT* lhs, const basic_string& rhs) +{ + basic_string temp(lhs); + return (temp != rhs); +} + +template _UCXXEXPORT bool + operator!=(const basic_string& lhs, const charT* rhs) +{ + basic_string temp(rhs); + return (lhs != temp); +} + +template _UCXXEXPORT bool + operator< (const basic_string& lhs, const basic_string& rhs) +{ + if(lhs.compare(rhs) < 0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator< (const basic_string& lhs, const charT* rhs) +{ + basic_string temp(rhs); + if(lhs.compare(rhs) < 0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator< (const charT* lhs, const basic_string& rhs) +{ + basic_string temp(lhs); + if(temp.compare(rhs) < 0){ + return true; + } + return false; +} + + +template _UCXXEXPORT bool + operator> (const basic_string& lhs, const basic_string& rhs) +{ + if(lhs.compare(rhs) > 0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator> (const basic_string& lhs, const charT* rhs) +{ + basic_string temp(rhs); + if(lhs.compare(rhs) > 0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator> (const charT* lhs, const basic_string& rhs) +{ + basic_string temp(lhs); + if(temp.compare(rhs) > 0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator<=(const basic_string& lhs, const basic_string& rhs) +{ + if(lhs.compare(rhs) <=0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator<=(const basic_string& lhs, const charT* rhs) +{ + basic_string temp(rhs); + if(lhs.compare(temp) <=0 ){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator<=(const charT* lhs, const basic_string& rhs) +{ + basic_string temp(lhs); + if(temp.compare(rhs) <= 0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator>=(const basic_string& lhs, const basic_string& rhs) +{ + if(lhs.compare(rhs) >=0){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator>=(const basic_string& lhs, const charT* rhs) +{ + basic_string temp(rhs); + if(lhs.compare(temp) >=0 ){ + return true; + } + return false; +} + +template _UCXXEXPORT bool + operator>=(const charT* lhs, const basic_string& rhs) +{ + basic_string temp(lhs); + if(temp.compare(rhs) >=0 ){ + return true; + } + return false; +} + +template _UCXXEXPORT void + swap(basic_string& lhs, basic_string& rhs) +{ + lhs.swap(rhs); +} + +/*template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const basic_string& str) +{ + return os.write(str.data(), str.length()); +}*/ + +#ifdef __UCLIBCXX_EXPAND_STRING_CHAR__ +#ifndef __UCLIBCXX_COMPILE_STRING__ + +//Operators we can avoid duplication of + +template <> _UCXXEXPORT bool operator==(const string & lhs, const string & rhs); +template <> _UCXXEXPORT bool operator==(const char * lhs, const string & rhs); +template <> _UCXXEXPORT bool operator==(const string & lhs, const char * rhs); + +template <> _UCXXEXPORT bool operator!=(const string & lhs, const string & rhs); +template <> _UCXXEXPORT bool operator!=(const char * lhs, const string & rhs); +template <> _UCXXEXPORT bool operator!=(const string & lhs, const char * rhs); + +template <> _UCXXEXPORT string operator+(const string & lhs, const char* rhs); +template <> _UCXXEXPORT string operator+(const char* lhs, const string & rhs); +template <> _UCXXEXPORT string operator+(const string & lhs, const string & rhs); + +template <> _UCXXEXPORT bool operator> (const string & lhs, const string & rhs); +template <> _UCXXEXPORT bool operator< (const string & lhs, const string & rhs); + + +#endif +#endif + + +} + +#pragma GCC visibility pop + +#endif diff --git a/misc/uClibc++/include/cxx/string_iostream b/misc/uClibc++/include/cxx/string_iostream new file mode 100644 index 0000000000..4ef3b600c5 --- /dev/null +++ b/misc/uClibc++/include/cxx/string_iostream @@ -0,0 +1,146 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#ifdef __UCLIBCXX_HAS_WCHAR__ +#include +#include +#endif + +#ifndef __HEADER_STD_STRING_IOSTREAM +#define __HEADER_STD_STRING_IOSTREAM 1 + +#pragma GCC visibility push(default) + +namespace std{ + + + +template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const basic_string& str) +{ + return os.write(str.data(), str.length()); +} + +template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, basic_string& str) +{ + + typename basic_istream::sentry s(is); + if(s == false){ + return is; + } + + str.clear(); + + typename basic_istream::int_type c; + typename Allocator::size_type n = is.width(); + bool exitnow = false; + if(n == 0){ + n = str.max_size(); + } + +// //Clear out preliminary spaces first +// c = is.get(); +// while(isspace(c)){ +// c = is.get(); +// } +// +// is.putback(c); + + do{ + c = is.get(); + if(c == traits::eof() || isspace(c) || n == 0){ + is.putback(c); + exitnow = true; + }else{ + str.append(1, traits::to_char_type(c) ); + --n; + } + }while(exitnow == false); + return is; +} + +template _UCXXEXPORT basic_istream& + getline(basic_istream& is, basic_string& str, charT delim) +{ + typename basic_istream::sentry s(is); + if(s == false){ + return is; + } + + str.erase(); + + streamsize i = 0; + typename basic_istream::int_type c_i; + charT c; + unsigned int n = str.max_size(); + for(i=0;i _UCXXEXPORT basic_istream& + getline(basic_istream& is, basic_string& str) +{ + return getline(is, str, '\n'); +} + + +#ifdef __UCLIBCXX_EXPAND_STRING_CHAR__ +#ifndef __UCLIBCXX_COMPILE_STRING__ + + +#ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ +template<> _UCXXEXPORT basic_istream >& operator>>( + basic_istream >& is, + basic_string, allocator >& str); +#endif + + +#ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ +template<> _UCXXEXPORT basic_ostream >& + operator<<(basic_ostream >& os, + const basic_string, std::allocator >& str); + +#endif + + +#endif +#endif + + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/support b/misc/uClibc++/include/cxx/support new file mode 100644 index 0000000000..9279987ad9 --- /dev/null +++ b/misc/uClibc++/include/cxx/support @@ -0,0 +1,165 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#ifndef HEADER_ULC_SUPPORT +#define HEADER_ULC_SUPPORT 1 + +using namespace std; + +//From C++ ABI spec +typedef enum { + _URC_NO_REASON = 0, + _URC_FOREIGN_EXCEPTION_CAUGHT = 1, + _URC_FATAL_PHASE2_ERROR = 2, + _URC_FATAL_PHASE1_ERROR = 3, + _URC_NORMAL_STOP = 4, + _URC_END_OF_STACK = 5, + _URC_HANDLER_FOUND = 6, + _URC_INSTALL_CONTEXT = 7, + _URC_CONTINUE_UNWIND = 8 +} _Unwind_Reason_Code; + + +typedef void (*_Unwind_Exception_Cleanup_Fn) + (_Unwind_Reason_Code reason, struct _Unwind_Exception *exc); + +//The following definitions were grabbed from the gcc implementation +typedef unsigned _Unwind_Ptr __attribute__((__mode__(__pointer__))); +typedef unsigned _Unwind_Word __attribute__((__mode__(__word__))); +typedef signed _Unwind_Sword __attribute__((__mode__(__word__))); +typedef unsigned _Unwind_Exception_Class __attribute__((__mode__(__DI__))); +typedef void (*_Unwind_Exception_Cleanup_Fn) (_Unwind_Reason_Code, struct _Unwind_Exception *); + +typedef int _Unwind_Action; +static const _Unwind_Action _UA_SEARCH_PHASE = 1; +static const _Unwind_Action _UA_CLEANUP_PHASE = 2; +static const _Unwind_Action _UA_HANDLER_FRAME = 4; +static const _Unwind_Action _UA_FORCE_UNWIND = 8; + +const _Unwind_Exception_Class __uclibcxx_exception_class = (((((((( + _Unwind_Exception_Class) 'u' << 8 | (_Unwind_Exception_Class) 'l') << 8 + | (_Unwind_Exception_Class) 'i') << 8 | (_Unwind_Exception_Class) 'b') << 8 + | (_Unwind_Exception_Class) 'C')<< 8 | (_Unwind_Exception_Class) '+') << 8 + | (_Unwind_Exception_Class) '+') << 8 | (_Unwind_Exception_Class) '\0'); + + +#define _UA_SEARCH_PHASE 1 +#define _UA_CLEANUP_PHASE 2 +#define _UA_HANDLER_FRAME 4 +#define _UA_FORCE_UNWIND 8 +#define _UA_END_OF_STACK 16 + +struct _Unwind_Exception{ + _Unwind_Exception_Class exception_class; //Type of exception, eg ulibC++\0 + _Unwind_Exception_Cleanup_Fn exception_cleanup; //Destructor if from diff runtime + _Unwind_Word private_1; //Don't touch at all! + _Unwind_Word private_2; //Don't touch at all! +} __attribute__((__aligned__)); + + +//The following structure is system-dependent and defined by the compiler +//Thus it's definition was copied from the gcc 3.4.0 header files +struct _Unwind_Context; +//{ +// void *reg[DWARF_FRAME_REGISTERS+1]; +// void *cfa; +// void *ra; +// void *lsda; +// struct dwarf_eh_bases bases; +// _Unwind_Word args_size; +//}; + + + +_Unwind_Reason_Code _Unwind_RaiseException ( struct _Unwind_Exception *exception_object ); + +//_Unwind_ForcedUnwind + +typedef _Unwind_Reason_Code (*_Unwind_Stop_Fn) + (int version, _Unwind_Action actions, _Unwind_Exception_Class exceptionClass, + struct _Unwind_Exception *exceptionObject, + struct _Unwind_Context *context, void *stop_parameter ); + +_Unwind_Reason_Code _Unwind_ForcedUnwind ( + struct _Unwind_Exception *exception_object, _Unwind_Stop_Fn stop, + void *stop_parameter ); + +void _Unwind_Resume (struct _Unwind_Exception *exception_object); +void _Unwind_DeleteException (struct _Unwind_Exception *exception_object); + +_Unwind_Word _Unwind_GetGR (struct _Unwind_Context *context, int index); +void _Unwind_SetGR (struct _Unwind_Context *context, int index, _Unwind_Word); + +_Unwind_Ptr _Unwind_GetIP (struct _Unwind_Context *context); +void _Unwind_SetIP (struct _Unwind_Context *context, _Unwind_Ptr new_value); + +_Unwind_Ptr _Unwind_GetLanguageSpecificData (struct _Unwind_Context *context); +_Unwind_Ptr _Unwind_GetRegionStart (struct _Unwind_Context *context); + +_Unwind_Reason_Code (*__personality_routine) + (int version, //Should be 1 + _Unwind_Action actions, //Actions the routine will perform (bitmask) + _Unwind_Exception_Class exceptionClass, //Type of exception - vendor is high 4 bytes + struct _Unwind_Exception *exceptionObject, //Points to exception header + struct _Unwind_Context *context); //Unwinder state information + + +/*The following part is the Level II ABI which is required for compatability*/ +//This might be the only stuff that *I* need to implement + +struct __cxa_exception { + std::type_info *exceptionType; //Type of thrown exception + void (*exceptionDestructor) (void *); //Pointer to the destructor + unexpected_handler unexpectedHandler; //Unexpected handler to use + terminate_handler terminateHandler; //Terminate handle to use + __cxa_exception *nextException; //per thread linked list + + int handlerCount; //How many handlers have caught this + int handlerSwitchValue; + const char *actionRecord; + const char *languageSpecificData; + void *catchTemp; + void *adjustedPtr; + + _Unwind_Exception unwindHeader; +}; + +struct __cxa_eh_globals { + __cxa_exception *caughtExceptions; + unsigned int uncaughtExceptions; +}; + +extern "C" __cxa_eh_globals *__cxa_get_globals(void); //Return ptr to the eh_globals object for current thread +extern "C" __cxa_eh_globals *__cxa_get_globals_fast(void); //Same as above, assumes that above called at least once + +extern "C" void *__cxa_allocate_exception(size_t thrown_size); //Allocate space for exception plus header +extern "C" void __cxa_free_exception(void *thrown_exception); //Free space allocated from the above + +extern "C" void __cxa_throw (void *thrown_exception, //This is the actual throw call +// std::type_info *tinfo, //Type of object + void * tinfo, //Type of object + void (*dest) (void *) ); //Pointer to destructor destroy object + + +#endif + diff --git a/misc/uClibc++/include/cxx/system_configuration.h b/misc/uClibc++/include/cxx/system_configuration.h new file mode 100644 index 0000000000..4db8e8bd85 --- /dev/null +++ b/misc/uClibc++/include/cxx/system_configuration.h @@ -0,0 +1,48 @@ +/* + * Automatically generated C config: don't edit + */ +/* + * Version Number + */ +#define __UCLIBCXX_MAJOR__ 0 +#define __UCLIBCXX_MINOR__ 2 +#define __UCLIBCXX_SUBLEVEL__ 4 + +/* + * Target Features and Options + */ +#define __UCLIBCXX_HAS_FLOATS__ 1 +#define __UCLIBCXX_HAS_LONG_DOUBLE__ 1 +#define __UCLIBCXX_HAS_TLS__ 1 +#define __WARNINGS__ "-Wall" +#define __BUILD_EXTRA_LIBRARIES__ "" +#define __HAVE_DOT_CONFIG__ 1 + +/* + * String and I/O Stream Support + */ +#undef __UCLIBCXX_HAS_WCHAR__ +#define __UCLIBCXX_IOSTREAM_BUFSIZE__ 32 +#define __UCLIBCXX_HAS_LFS__ 1 +#define __UCLIBCXX_SUPPORT_CDIR__ 1 +#define __UCLIBCXX_SUPPORT_CIN__ 1 +#define __UCLIBCXX_SUPPORT_COUT__ 1 +#define __UCLIBCXX_SUPPORT_CERR__ 1 +#undef __UCLIBCXX_SUPPORT_CLOG__ + +/* + * STL and Code Expansion + */ +#define __UCLIBCXX_STL_BUFFER_SIZE__ 32 +#define __UCLIBCXX_CODE_EXPANSION__ 1 +#define __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ 1 +#define __UCLIBCXX_EXPAND_STRING_CHAR__ 1 +#define __UCLIBCXX_EXPAND_VECTOR_BASIC__ 1 +#define __UCLIBCXX_EXPAND_IOS_CHAR__ 1 +#define __UCLIBCXX_EXPAND_STREAMBUF_CHAR__ 1 +#define __UCLIBCXX_EXPAND_ISTREAM_CHAR__ 1 +#define __UCLIBCXX_EXPAND_OSTREAM_CHAR__ 1 +#define __UCLIBCXX_EXPAND_FSTREAM_CHAR__ 1 +#define __UCLIBCXX_EXPAND_SSTREAM_CHAR__ 1 + + diff --git a/misc/uClibc++/include/cxx/type_traits b/misc/uClibc++/include/cxx/type_traits new file mode 100644 index 0000000000..fa1de40cee --- /dev/null +++ b/misc/uClibc++/include/cxx/type_traits @@ -0,0 +1,92 @@ +/* Copyright (C) 2005 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include +#include + +#ifndef __HEADER_TYPE_TRAITS +#define __HEADER_TYPE_TRAITS 1 + +#pragma GCC visibility push(default) + +namespace std{ + + struct _UCXXEXPORT __true_type{}; + struct _UCXXEXPORT __false_type{}; + + template class _UCXXEXPORT __is_integer{ + public: + typedef __false_type value; + }; + + template <> class _UCXXEXPORT __is_integer { + public: + typedef __true_type value; + }; + + template <> class _UCXXEXPORT __is_integer { + public: + typedef __true_type value; + }; + + template <> class _UCXXEXPORT __is_integer { + public: + typedef __true_type value; + }; + + template <> class _UCXXEXPORT __is_integer { + public: + typedef __true_type value; + }; + + template <> class _UCXXEXPORT __is_integer { + public: + typedef __true_type value; + }; + + template <> class _UCXXEXPORT __is_integer { + public: + typedef __true_type value; + }; + + template <> class _UCXXEXPORT __is_integer { + public: + typedef __true_type value; + }; + + template <> class _UCXXEXPORT __is_integer { + public: + typedef __true_type value; + }; + + template <> class _UCXXEXPORT __is_integer { + public: + typedef __true_type value; + }; + + + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/cxx/typeinfo b/misc/uClibc++/include/cxx/typeinfo new file mode 100644 index 0000000000..88a2639b89 --- /dev/null +++ b/misc/uClibc++/include/cxx/typeinfo @@ -0,0 +1,156 @@ +// RTTI support for -*- C++ -*- +// Copyright (C) 1994, 1995, 1996, 1997, 1998, 2000, 2001, 2002 +// Free Software Foundation +// +// This file is part of GNU CC. +// +// GNU CC is free software; you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation; either version 2, or (at your option) +// any later version. +// +// GNU CC is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with GNU CC; see the file COPYING. If not, write to +// the Free Software Foundation, 59 Temple Place - Suite 330, +// Boston, MA 02111-1307, USA. + +// As a special exception, you may use this file as part of a free software +// library without restriction. Specifically, if other files instantiate +// templates or use macros or inline functions from this file, or you compile +// this file and link it with other files to produce an executable, this +// file does not by itself cause the resulting executable to be covered by +// the GNU General Public License. This exception does not however +// invalidate any other reasons why the executable file might be covered by +// the GNU General Public License. + +/** @file typeinfo + * This header provides RTTI support. + */ + +#ifndef __TYPEINFO__ +#define __TYPEINFO__ + +#include + +extern "C++" { + +namespace __cxxabiv1 +{ + class __class_type_info; +} // namespace __cxxabiv1 + +#if !__GXX_WEAK__ + // If weak symbols are not supported, typeinfo names are not merged. + #define __GXX_MERGED_TYPEINFO_NAMES 0 +#else + // On platforms that support weak symbols, typeinfo names are merged. + #define __GXX_MERGED_TYPEINFO_NAMES 1 +#endif + +namespace std +{ + /** + * @brief Part of RTTI. + * + * The @c type_info class describes type information generated by + * an implementation. + */ + class type_info + { + public: + /** Destructor. Being the first non-inline virtual function, this + * controls in which translation unit the vtable is emitted. The + * compiler makes use of that information to know where to emit + * the runtime-mandated type_info structures in the new-abi. */ + virtual ~type_info(); + + private: + /// Assigning type_info is not supported. Made private. + type_info& operator=(const type_info&); + type_info(const type_info&); + + protected: + const char *__name; + + protected: + explicit type_info(const char *__n): __name(__n) { } + + public: + // the public interface + /** Returns an @e implementation-defined byte string; this is not + * portable between compilers! */ + const char* name() const + { return __name; } + +#if !__GXX_MERGED_TYPEINFO_NAMES + bool before(const type_info& __arg) const; + // In old abi, or when weak symbols are not supported, there can + // be multiple instances of a type_info object for one + // type. Uniqueness must use the _name value, not object address. + bool operator==(const type_info& __arg) const; +#else + /** Returns true if @c *this precedes @c __arg in the implementation's + * collation order. */ + // In new abi we can rely on type_info's NTBS being unique, + // and therefore address comparisons are sufficient. + bool before(const type_info& __arg) const + { return __name < __arg.__name; } + bool operator==(const type_info& __arg) const + { return __name == __arg.__name; } +#endif + bool operator!=(const type_info& __arg) const + { return !operator==(__arg); } + + // the internal interface + public: + // return true if this is a pointer type of some kind + virtual bool __is_pointer_p() const; + // return true if this is a function type + virtual bool __is_function_p() const; + + // Try and catch a thrown type. Store an adjusted pointer to the + // caught type in THR_OBJ. If THR_TYPE is not a pointer type, then + // THR_OBJ points to the thrown object. If THR_TYPE is a pointer + // type, then THR_OBJ is the pointer itself. OUTER indicates the + // number of outer pointers, and whether they were const + // qualified. + virtual bool __do_catch(const type_info *__thr_type, void **__thr_obj, + unsigned __outer) const; + + // internally used during catch matching + virtual bool __do_upcast(const __cxxabiv1::__class_type_info *__target, + void **__obj_ptr) const; + }; + + /** + * @brief Thrown during incorrect typecasting. + * + * If you attempt an invalid @c dynamic_cast expression, an instance of + * this class (or something derived from this class) is thrown. */ + class bad_cast : public exception + { + public: + bad_cast() throw() { } + // This declaration is not useless: + // http://gcc.gnu.org/onlinedocs/gcc-3.0.2/gcc_6.html#SEC118 + virtual ~bad_cast() throw(); + }; + + /** If you use a NULL pointer in a @c typeid expression, this is thrown. */ + class bad_typeid : public exception + { + public: + bad_typeid () throw() { } + // This declaration is not useless: + // http://gcc.gnu.org/onlinedocs/gcc-3.0.2/gcc_6.html#SEC118 + virtual ~bad_typeid() throw(); + }; +} // namespace std + +} // extern "C++" +#endif diff --git a/misc/uClibc++/include/cxx/unwind-cxx.h b/misc/uClibc++/include/cxx/unwind-cxx.h new file mode 100644 index 0000000000..4a8961a978 --- /dev/null +++ b/misc/uClibc++/include/cxx/unwind-cxx.h @@ -0,0 +1,213 @@ +// -*- C++ -*- Exception handling and frame unwind runtime interface routines. +// Copyright (C) 2001 Free Software Foundation, Inc. +// +// This file is part of GCC. +// +// GCC is free software; you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation; either version 2, or (at your option) +// any later version. +// +// GCC is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with GCC; see the file COPYING. If not, write to +// the Free Software Foundation, 59 Temple Place - Suite 330, +// Boston, MA 02111-1307, USA. + +// As a special exception, you may use this file as part of a free software +// library without restriction. Specifically, if other files instantiate +// templates or use macros or inline functions from this file, or you compile +// this file and link it with other files to produce an executable, this +// file does not by itself cause the resulting executable to be covered by +// the GNU General Public License. This exception does not however +// invalidate any other reasons why the executable file might be covered by +// the GNU General Public License. + +// This is derived from the C++ ABI for IA-64. Where we diverge +// for cross-architecture compatibility are noted with "@@@". + +#ifndef _UNWIND_CXX_H +#define _UNWIND_CXX_H 1 + +// Level 2: C++ ABI + +#include +#include +#include +#include "unwind.h" + +#pragma GCC visibility push(default) + +namespace __cxxabiv1 +{ + +// A primary C++ exception object consists of a header, which is a wrapper +// around an unwind object header with additional C++ specific information, +// followed by the exception object itself. + +struct __cxa_exception +{ + // Manage the exception object itself. + std::type_info *exceptionType; + void (*exceptionDestructor)(void *); + + // The C++ standard has entertaining rules wrt calling set_terminate + // and set_unexpected in the middle of the exception cleanup process. + std::unexpected_handler unexpectedHandler; + std::terminate_handler terminateHandler; + + // The caught exception stack threads through here. + __cxa_exception *nextException; + + // How many nested handlers have caught this exception. A negated + // value is a signal that this object has been rethrown. + int handlerCount; + + // Cache parsed handler data from the personality routine Phase 1 + // for Phase 2 and __cxa_call_unexpected. + int handlerSwitchValue; + const unsigned char *actionRecord; + const unsigned char *languageSpecificData; + _Unwind_Ptr catchTemp; + void *adjustedPtr; + + // The generic exception header. Must be last. + _Unwind_Exception unwindHeader; +}; + + +// A dependent C++ exception object consists of a header, which is a wrapper +// around an unwind object header with additional C++ specific information, +// followed by the exception object itself. +struct __cxa_dependent_exception +{ + // The primary exception + void *primaryException; + + // The C++ standard has entertaining rules wrt calling set_terminate + // and set_unexpected in the middle of the exception cleanup process. + std::unexpected_handler unexpectedHandler; + std::terminate_handler terminateHandler; + + // The caught exception stack threads through here. + __cxa_exception *nextException; + + // How many nested handlers have caught this exception. A negated + // value is a signal that this object has been rethrown. + int handlerCount; + + // Cache parsed handler data from the personality routine Phase 1 + // for Phase 2 and __cxa_call_unexpected. + int handlerSwitchValue; + const unsigned char *actionRecord; + const unsigned char *languageSpecificData; + _Unwind_Ptr catchTemp; + void *adjustedPtr; + + // The generic exception header. Must be last. + _Unwind_Exception unwindHeader; +}; + + +// Each thread in a C++ program has access to a __cxa_eh_globals object. +struct __cxa_eh_globals +{ + __cxa_exception *caughtExceptions; + unsigned int uncaughtExceptions; +}; + + +// The __cxa_eh_globals for the current thread can be obtained by using +// either of the following functions. The "fast" version assumes at least +// one prior call of __cxa_get_globals has been made from the current +// thread, so no initialization is necessary. +extern "C" __cxa_eh_globals *__cxa_get_globals () throw(); +extern "C" __cxa_eh_globals *__cxa_get_globals_fast () throw(); + +// Allocate memory for the primary exception plus the thrown object. +extern "C" void *__cxa_allocate_exception(std::size_t thrown_size) throw(); +// Allocate memory for dependent exception. +extern "C" __cxa_dependent_exception *__cxa_allocate_dependent_exception() throw(); + +// Free the space allocated for the primary exception. +extern "C" void __cxa_free_exception(void *thrown_exception) throw(); +// Free the space allocated for the dependent exception. +extern "C" void __cxa_free_dependent_exception(__cxa_dependent_exception *dependent_exception) throw(); + +// Throw the exception. +extern "C" void __cxa_throw (void *thrown_exception, + std::type_info *tinfo, + void (*dest) (void *)) + __attribute__((noreturn)); + +// Used to implement exception handlers. +extern "C" void *__cxa_begin_catch (void *) throw(); +extern "C" void __cxa_end_catch (); +extern "C" void __cxa_rethrow () __attribute__((noreturn)); + +// These facilitate code generation for recurring situations. +extern "C" void __cxa_bad_cast (); +extern "C" void __cxa_bad_typeid (); + +// @@@ These are not directly specified by the IA-64 C++ ABI. + +// Handles re-checking the exception specification if unexpectedHandler +// throws, and if bad_exception needs to be thrown. Called from the +// compiler. +extern "C" void __cxa_call_unexpected (void *) __attribute__((noreturn)); + +// Invokes given handler, dying appropriately if the user handler was +// so inconsiderate as to return. +extern void __terminate(std::terminate_handler) __attribute__((noreturn)); +extern void __unexpected(std::unexpected_handler) __attribute__((noreturn)); + +// The current installed user handlers. +extern std::terminate_handler __terminate_handler; +extern std::unexpected_handler __unexpected_handler; + +// These are explicitly GNU C++ specific. + +// This is the exception class we report -- "GNUCC++\0". +const _Unwind_Exception_Class __gxx_exception_class += ((((((((_Unwind_Exception_Class) 'G' + << 8 | (_Unwind_Exception_Class) 'N') + << 8 | (_Unwind_Exception_Class) 'U') + << 8 | (_Unwind_Exception_Class) 'C') + << 8 | (_Unwind_Exception_Class) 'C') + << 8 | (_Unwind_Exception_Class) '+') + << 8 | (_Unwind_Exception_Class) '+') + << 8 | (_Unwind_Exception_Class) '\0'); + +// GNU C++ personality routine, Version 0. +extern "C" _Unwind_Reason_Code __gxx_personality_v0 + (int, _Unwind_Action, _Unwind_Exception_Class, + struct _Unwind_Exception *, struct _Unwind_Context *); + +// GNU C++ sjlj personality routine, Version 0. +extern "C" _Unwind_Reason_Code __gxx_personality_sj0 + (int, _Unwind_Action, _Unwind_Exception_Class, + struct _Unwind_Exception *, struct _Unwind_Context *); + +// Acquire the C++ exception header from the C++ object. +static inline __cxa_exception * +__get_exception_header_from_obj (void *ptr) +{ + return reinterpret_cast<__cxa_exception *>(ptr) - 1; +} + +// Acquire the C++ exception header from the generic exception header. +static inline __cxa_exception * +__get_exception_header_from_ue (_Unwind_Exception *exc) +{ + return reinterpret_cast<__cxa_exception *>(exc + 1) - 1; +} + +} /* namespace __cxxabiv1 */ + +#pragma GCC visibility pop + +#endif // _UNWIND_CXX_H diff --git a/misc/uClibc++/include/cxx/utility b/misc/uClibc++/include/cxx/utility new file mode 100644 index 0000000000..b654679248 --- /dev/null +++ b/misc/uClibc++/include/cxx/utility @@ -0,0 +1,88 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + + +#include + + +#ifndef __STD_HEADER_UTILITY +#define __STD_HEADER_UTILITY 1 + +#pragma GCC visibility push(default) + +namespace std{ + + namespace rel_ops { + template inline bool operator!=(const T& x, const T& y){ + return !(x == y); + } + + template inline bool operator> (const T& x, const T& y){ + return ( y < x); + } + + template inline bool operator<=(const T& x, const T& y){ + return !( y < x ); + } + + template inline bool operator>=(const T& x, const T& y){ + return !(x < y); + } + } + + template struct _UCXXEXPORT pair { + typedef T1 first_type; + typedef T2 second_type; + + T1 first; + T2 second; + pair() : first(), second() { } + pair(const T1& x, const T2& y) : first(x), second(y) { } + template pair(const pair &p) : first(p.first), second(p.second) { } + }; + + template bool operator==(const pair& x, const pair& y){ + using namespace rel_ops; + return (x.first == y.first && x.second==y.second); + } + template bool operator< (const pair& x, const pair& y){ + return x.first < y.first || (!(y.first < x.first) && x.second < y.second); + } + template bool operator!=(const pair& x, const pair& y){ + return !(x == y); + } + template bool operator> (const pair& x, const pair& y){ + return y < x; + } + template bool operator>=(const pair& x, const pair& y){ + return !(x < y); + } + template bool operator<=(const pair& x, const pair& y){ + return !(y < x); + } + template pair make_pair(const T1& x, const T2& y){ + return pair(x, y); + } + + +} + +#pragma GCC visibility pop + +#endif //__STD_HEADER_UTILITY diff --git a/misc/uClibc++/include/cxx/valarray b/misc/uClibc++/include/cxx/valarray new file mode 100644 index 0000000000..09d929c49e --- /dev/null +++ b/misc/uClibc++/include/cxx/valarray @@ -0,0 +1,1042 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +#ifndef __HEADER_STD_VALARRAY +#define __HEADER_STD_VALARRAY 1 + +#include +#include + +#pragma GCC visibility push(default) + +namespace std{ + + template class valarray; + class slice; + template class slice_array; + class gslice; + template class gslice_array; + template class mask_array; + template class indirect_array; + + //Actual class definitions + + + class _UCXXEXPORT slice { + protected: + size_t sta; + size_t siz; + size_t str; + + public: + slice() : sta(0), siz(0), str(0){ } + slice(size_t a, size_t b, size_t c) : sta(a), siz(b), str(c) { } + slice(const slice& s) : sta(s.sta), siz(s.siz), str(s.str) { } + ~slice() { } + size_t start() const{ + return sta; + } + size_t size() const{ + return siz; + } + size_t stride() const{ + return str; + } + }; + + + + template class _UCXXEXPORT valarray { + friend class slice_array; + protected: + T * data; + size_t length; + + public: + typedef T value_type; + + valarray() : data(0), length(0) { } + + explicit valarray(size_t t) : data(0), length(t){ + data = new T[length]; + } + + valarray(const T& v, size_t t) : data(0), length(t){ + data = new T[length]; + for(size_t i = 0; i < length; ++i){ + data[i] = v; + } + } + valarray(const T* p, size_t t) : data(0), length(t) { + data = new T[length]; + for(size_t i = 0; i < length; ++i){ + data[i] = p[i]; + } + } + valarray(const valarray& v) : data(0), length(v.length){ + data = new T[length]; + for(size_t i = 0; i < length; ++i){ + data[i] = v.data[i]; + } + } + valarray(const slice_array & sa) : data(0), length(sa.s.size()){ + data = new T[length]; + for(unsigned int i = 0; i < length; ++i){ + data[i] = sa.array->data[sa.s.start() + i * sa.s.stride()]; + } + } + valarray(const gslice_array&); + valarray(const mask_array&); + valarray(const indirect_array&); + ~valarray(){ + delete [] data; + data = 0; + length = 0; + } + + valarray& operator=(const valarray& v){ + if (length != v.length) { // DR 630 + delete [] data; + length = v.length; + data = new T[length]; + } + for (size_t i = 0; i < length; ++i) { + data[i] = v.data[i]; + } + return *this; + } + valarray& operator=(const T& t){ + for(size_t i = 0; i < length; ++i){ + data[i] = t; + } + return *this; + } + valarray& operator=(const slice_array& sa){ + for(size_t i =0; i < length; ++i){ + data[i] = sa.data[sa.s.start() + i * sa.s.stride()]; + } + return *this; + } + valarray& operator=(const gslice_array&); + valarray& operator=(const mask_array&); + valarray& operator=(const indirect_array&); + + const T& operator[](size_t t) const{ + return data[t]; + } + T& operator[](size_t t){ + return data[t]; + } + + valarray operator[](slice s) const{ + valarray retval(s.size()); + for(unsigned int i = 0; i< s.size(); ++i){ + retval.data[i] = data[s.start() + i * s.stride()]; + } + return retval; + } + + slice_array operator[](slice sl){ + slice_array retval; + retval.s = sl; + retval.array = this; + return retval; + } + + valarray operator[](const gslice&) const; + gslice_array operator[](const gslice&); + valarray operator[](const valarray&) const; + mask_array operator[](const valarray&); + valarray operator[](const valarray&) const; + indirect_array operator[](const valarray&); + + valarray operator+() const{ + valarray retval(length); + for(size_t i = 0; i< length ; ++i){ + retval.data[i] = +data[i]; + } + return retval; + } + valarray operator-() const{ + valarray retval(length); + for(size_t i = 0; i< length; ++i){ + retval.data[i] = -data[i]; + } + return retval; + } + valarray operator~() const{ + valarray retval(length); + for(size_t i = 0; i< length ; ++i){ + retval.data[i] = ~data[i]; + } + return retval; + } + valarray operator!() const{ + valarray retval(length); + for (size_t i = 0; i < length ; ++i){ + retval[i] = !data[i]; + } + return retval; + } + valarray& operator*= (const T& t){ + for(size_t i=0;i& operator/= (const T& t){ + for(size_t i=0;i& operator%= (const T& t){ + for(size_t i=0;i& operator+= (const T& t){ + for(size_t i=0;i& operator-= (const T& t){ + for(size_t i=0;i& operator^= (const T& t){ + for(size_t i=0;i& operator&= (const T& t){ + for(size_t i=0;i& operator|= (const T& t){ + for(size_t i=0;i& operator<<=(const T& t){ + for(size_t i=0;i& operator>>=(const T& t){ + for(size_t i=0;i>= t; + } + return *this; + } + valarray& operator*= (const valarray& a){ + for(size_t i=0;i& operator/= (const valarray& a){ + for(size_t i=0;i& operator%= (const valarray& a){ + for(size_t i=0;i& operator+= (const valarray& a){ + for(size_t i=0;i& operator-= (const valarray& a){ + for(size_t i=0;i& operator^= (const valarray& a){ + for(size_t i=0;i& operator|= (const valarray& a){ + for(size_t i=0;i& operator&= (const valarray& a){ + for(size_t i=0;i& operator<<=(const valarray& a){ + for(size_t i=0;i& operator>>=(const valarray& a){ + for(size_t i=0;i>= a.data[i]; + } + return *this; + } +#if 0 + void swap(valarray& other) noexcept { + std::swap(length, other.length); + std::swap(data, other.data); + } +#endif + size_t size() const{ + return length; + } + + T sum() const{ + T retval(data[0]); + for(size_t i = 1; i< length; ++i){ + retval += data[i]; + } + return retval; + } + + T min() const{ + T retval(data[0]); + for(size_t i = 1; i< length; ++i){ + if(data[i] < retval){ + retval = data[i]; + } + } + return retval; + } + + T max() const{ + T retval(data[0]); + for(size_t i = 1; i< length; ++i){ + if(retval < data[i]){ + retval = data[i]; + } + } + return retval; + } + + valarray shift (int n) const{ + valarray retval(length); + if (n < 0) { + if (-size_t(n) > length) + n = -int(length); + } else { + if (size_t(n) > length) + n = int(length); + } + for (size_t i = 0; i < length ; ++i) { + if ((n + i) < length) + retval.data[i] = data[n + i]; + } + return retval; + } + valarray cshift(int n) const{ + valarray retval(length); + if (length == 0) + return retval; + if (n < 0) { + if (-size_t(n) > length) + n = -int(-size_t(n) % length); + n = length + n; + } else { + if (size_t(n) > length) + n = int(size_t(n) % length); + } + for (size_t i = 0; i < length ; ++i){ + retval.data[i] = data[(n + i) % length]; + } + return retval; + } + valarray apply(T func(T) ) const{ + valarray retval(length); + for(size_t i = 0; i< length; ++i){ + retval.data[i] = func(data[i]); + } + return retval; + } + valarray apply(T func(const T&)) const{ + valarray retval(length); + for(size_t i = 0; i< length; ++i){ + retval.data[i] = func(data[i]); + } + return retval; + } + void resize(size_t sz, T c = T()){ + delete [] data; + data = 0; + if(sz > 0){ + data = new T[sz]; + for(size_t i = 0; i < sz; ++i){ + data[i] = c; + } + } + length = sz; + } + }; + + + + template class _UCXXEXPORT slice_array { + friend class valarray; + public: + typedef T value_type; + + void operator= (const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] = v[i]; + } + } + void operator= (const T & v){ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] = v; + } + } + void fill(const T & v){ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] = v; + } + } + void operator*= (const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] *= v[i]; + } + } + void operator/= (const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] /= v[i]; + } + } + void operator%= (const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] %= v[i]; + } + } + void operator+= (const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] += v[i]; + } + } + void operator-= (const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] -= v[i]; + } + } + void operator^= (const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] ^= v[i]; + } + } + void operator&= (const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] &= v[i]; + } + } + void operator|= (const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] |= v[i]; + } + } + void operator<<=(const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] <<= v[i]; + } + } + void operator>>=(const valarray& v) const{ + for(unsigned int i = 0; i < s.size(); ++i){ + array->data[s.start() + i * s.stride()] >>= v[i]; + } + } + ~slice_array(){ + array = 0; + } + + private: + slice_array() : array(0){ } + + public: + slice_array(const slice_array& sa) : array(sa.array), s(sa.s){ } + slice_array& operator=(const slice_array& sa){ + array = sa.array; + s = sa.s; + return *this; + } + + private: + valarray * array; + slice s; + }; + + + class _UCXXEXPORT gslice { + private: + size_t sta; + valarray siz; + valarray str; + + public: + gslice() : sta(0), siz(), str() { } // DR 543 + gslice(size_t s, const valarray& l, const valarray& d) + : sta(s), siz(l), str(d) { } + + size_t start() const{ + return sta; + } + valarray size() const{ + return siz; + } + valarray stride() const{ + return str; + } + }; + + template class gslice_array { + private: + friend class valarray; + + public: + ~gslice_array(); + + void operator=(const valarray& array) const; + void operator*=(const valarray& array) const; + void operator/=(const valarray& array) const; + void operator%=(const valarray& array) const; + void operator+=(const valarray& array) const; + void operator-=(const valarray& array) const; + void operator^=(const valarray& array) const; + void operator&=(const valarray& array) const; + void operator|=(const valarray& array) const; + void operator<<=(const valarray& array) const; + void operator>>=(const valarray& array) const; + + void operator=(const T&); + + private: + gslice_array(); + gslice_array(const gslice_array&); + gslice_array& operator= (const gslice_array& array); + }; + + + + template valarray operator* (const valarray& lhs, const valarray& rhs){ + valarray retval(lhs); + retval *= rhs; + return retval; + } + + template valarray operator* (const valarray& lhs, const T& rhs){ + valarray retval(lhs); + retval *= rhs; + return retval; + } + template valarray operator* (const T& lhs, const valarray& rhs){ + valarray retval(rhs); + retval *= lhs; + return retval; + } + template valarray operator/ (const valarray& lhs, const valarray& rhs){ + valarray retval(lhs); + retval /= rhs; + return retval; + } + template valarray operator/ (const valarray& lhs, const T& rhs){ + valarray retval(lhs); + retval /= rhs; + return retval; + } + template valarray operator/ (const T& lhs, const valarray& rhs){ + valarray retval(lhs, rhs.size()); + retval /= rhs; + return retval; + } + template valarray operator% (const valarray& lhs, const valarray& rhs){ + valarray retval(lhs); + retval %= rhs; + return retval; + } + template valarray operator% (const valarray& lhs, const T& rhs){ + valarray retval(lhs); + retval %= rhs; + return retval; + } + template valarray operator% (const T& lhs, const valarray& rhs){ + valarray retval(lhs, rhs.size()); + retval %= rhs; + return retval; + } + template valarray operator+ (const valarray& lhs, const valarray& rhs){ + valarray retval(lhs); + retval += rhs; + return retval; + } + template valarray operator+ (const valarray& lhs, const T& rhs){ + valarray retval(lhs); + retval += rhs; + return retval; + } + template valarray operator+ (const T& lhs, const valarray& rhs){ + valarray retval(lhs, rhs.size()); + retval += rhs; + return retval; + } + template valarray operator- (const valarray& lhs, const valarray& rhs){ + valarray retval(lhs); + retval -= rhs; + return retval; + } + template valarray operator- (const valarray& lhs, const T& rhs){ + valarray retval(lhs); + retval -= rhs; + return retval; + } + template valarray operator- (const T& lhs, const valarray& rhs){ + valarray retval(lhs, rhs.size()); + retval -= rhs; + return retval; + } + template valarray operator^ (const valarray& lhs, const valarray& rhs){ + valarray retval(lhs); + retval ^= rhs; + return retval; + } + template valarray operator^ (const valarray& lhs, const T& rhs){ + valarray retval(lhs); + retval ^= rhs; + return retval; + } + template valarray operator^ (const T& lhs, const valarray& rhs){ + valarray retval(lhs, rhs.size()); + retval ^= rhs; + return retval; + } + template valarray operator& (const valarray& lhs, const valarray& rhs){ + valarray retval(lhs); + retval &= rhs; + return retval; + } + template valarray operator& (const valarray& lhs, const T& rhs){ + valarray retval(lhs); + retval &= rhs; + return retval; + } + template valarray operator& (const T& lhs, const valarray& rhs){ + valarray retval(lhs, rhs.size()); + retval &= rhs; + return retval; + } + template valarray operator| (const valarray& lhs, const valarray& rhs){ + valarray retval(lhs); + retval |= rhs; + return retval; + } + template valarray operator| (const valarray& lhs, const T& rhs){ + valarray retval(lhs); + retval |= rhs; + return retval; + } + template valarray operator| (const T& lhs, const valarray& rhs){ + valarray retval(lhs, rhs.size()); + retval |= rhs; + return retval; + } + template valarray operator<<(const valarray& lhs, const valarray& rhs){ + valarray retval(lhs); + retval <<= rhs; + return retval; + } + template valarray operator<<(const valarray& lhs, const T& rhs){ + valarray retval(lhs); + retval <<= rhs; + return retval; + } + template valarray operator<<(const T& lhs, const valarray& rhs){ + valarray retval(lhs, rhs.size()); + retval <<= rhs; + return retval; + } + template valarray operator>>(const valarray& lhs, const valarray& rhs){ + valarray retval(lhs); + retval >>= rhs; + return retval; + } + template valarray operator>>(const valarray& lhs, const T& rhs){ + valarray retval(lhs); + retval >>= rhs; + return retval; + } + template valarray operator>>(const T& lhs, const valarray& rhs){ + valarray retval(lhs, rhs.size()); + retval >>= rhs; + return retval; + } + + template valarray operator&&(const valarray& lhs, const valarray& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = lhs[i] && rhs[i]; + } + return retval; + } + template valarray operator&&(const valarray& lhs, const T& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i valarray operator&&(const T& lhs, const valarray& rhs){ + valarray retval(rhs.size()); + for(size_t i = 0; i valarray operator||(const valarray&lhs, const valarray& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i valarray operator||(const valarray& lhs, const T& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i valarray operator||(const T& lhs, const valarray& rhs){ + valarray retval(rhs.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = lhs || rhs[i]; + } + return retval; + } + + template valarray operator==(const valarray& lhs, const valarray& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i valarray operator==(const valarray& lhs, const T& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = lhs[i] == rhs; + } + return retval; + } + template valarray operator==(const T& lhs, const valarray& rhs){ + valarray retval(rhs.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = lhs == rhs[i]; + } + return retval; + } + template valarray operator!=(const valarray& lhs, const valarray& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i valarray operator!=(const valarray& lhs, const T& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i valarray operator!=(const T& lhs, const valarray& rhs){ + valarray retval(rhs.size()); + for(size_t i = 0; i valarray operator< (const valarray& lhs, const valarray& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i valarray operator< (const valarray& lhs, const T& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i valarray operator< (const T& lhs, const valarray& rhs){ + valarray retval(rhs.size()); + for(size_t i = 0; i valarray operator> (const valarray& lhs, const valarray& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i rhs[i]; + } + return retval; + } + template valarray operator> (const valarray& lhs, const T& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i rhs; + } + return retval; + } + template valarray operator> (const T& lhs, const valarray& rhs){ + valarray retval(rhs.size()); + for(size_t i = 0; i rhs[i]; + } + return retval; + } + template valarray operator<=(const valarray& lhs, const valarray& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i valarray operator<=(const valarray& lhs, const T& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i valarray operator<=(const T& lhs, const valarray& rhs){ + valarray retval(rhs.size()); + for(size_t i = 0; i valarray operator>=(const valarray& lhs, const valarray& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i = rhs[i]; + } + return retval; + } + template valarray operator>=(const valarray& lhs, const T& rhs){ + valarray retval(lhs.size()); + for(size_t i = 0; i = rhs; + } + return retval; + } + template valarray operator>=(const T& lhs, const valarray& rhs){ + valarray retval(rhs.size()); + for(size_t i = 0; i = rhs[i]; + } + return retval; + } + template T min(const valarray& x){ + T retval(x[0]); + for(size_t i = 1; i < x.size(); ++i){ + if(x[i] < retval){ + retval = x[i]; + } + } + } + template T max(const valarray& x){ + T retval(x[0]); + for(size_t i = 1; i < x.size(); ++i){ + if(x[i] > retval){ + retval = x[i]; + } + } + } + + template valarray abs (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = abs(x[i]); + } + return retval; + } + template valarray acos (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = acos(x[i]); + } + return retval; + } + template valarray asin (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = asin(x[i]); + } + return retval; + } + template valarray atan (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = atan(x[i]); + } + return retval; + } + template valarray atan2(const valarray& y, const valarray& x){ + valarray retval(y.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = atan2(y[i], x[i]); + } + return retval; + } + template valarray atan2(const valarray& y, const T& x){ + valarray retval(y.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = atan2(y[i], x); + } + return retval; + } + template valarray atan2(const T& y, const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = atan2(y, x[i]); + } + return retval; + } + template valarray cos (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = cos(x[i]); + } + return retval; + } + template valarray cosh (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = cosh(x[i]); + } + return retval; + } + template valarray exp (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = exp(x[i]); + } + return retval; + } + template valarray log (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = log(x[i]); + } + return retval; + } + template valarray log10(const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = log10(x[i]); + } + return retval; + } + template valarray pow (const valarray& x, const valarray& y){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = pow(x[i], y[i]); + } + return retval; + } + template valarray pow (const valarray& x, const T& y){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = pow(x[i], y); + } + return retval; + } + template valarray pow (const T& x, const valarray& y){ + valarray retval(y.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = pow(x, y[i]); + } + return retval; + } + template valarray sin (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = sin(x[i]); + } + return retval; + } + template valarray sinh (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = sinh(x[i]); + } + return retval; + } + template valarray sqrt (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = sqrt(x[i]); + } + return retval; + } + template valarray tan (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = tan(x[i]); + } + return retval; + } + template valarray tanh (const valarray& x){ + valarray retval(x.size()); + for(size_t i = 0; i < retval.size(); ++i){ + retval[i] = tanh(x[i]); + } + return retval; + } +} + +#pragma GCC visibility pop + +#endif diff --git a/misc/uClibc++/include/cxx/vector b/misc/uClibc++/include/cxx/vector new file mode 100644 index 0000000000..8310bc14e3 --- /dev/null +++ b/misc/uClibc++/include/cxx/vector @@ -0,0 +1,517 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + +#include +#include +#include +#include +#include +#include + + +#ifndef __STD_HEADER_VECTOR +#define __STD_HEADER_VECTOR + +#pragma GCC visibility push(default) + +namespace std{ + + template > class vector; + template bool operator==(const vector& x, const vector& y); + template bool operator< (const vector& x, const vector& y); + template bool operator!=(const vector& x, const vector& y); + template bool operator> (const vector& x, const vector& y); + template bool operator>=(const vector& x, const vector& y); + template bool operator<=(const vector& x, const vector& y); + template void swap(vector& x, vector& y); + + template class _UCXXEXPORT vector { + public: + + typedef typename Allocator::reference reference; + typedef typename Allocator::const_reference const_reference; + typedef typename Allocator::size_type size_type; + typedef typename Allocator::difference_type difference_type; + typedef typename Allocator::pointer pointer; + typedef typename Allocator::const_pointer const_pointer; + + typedef T* iterator; + typedef const T* const_iterator; + typedef T value_type; + typedef Allocator allocator_type; + typedef std::reverse_iterator reverse_iterator; + typedef std::reverse_iterator const_reverse_iterator; + + explicit _UCXXEXPORT vector(const Allocator& al= Allocator()): data(0), //defaultValue(T()), + data_size(__UCLIBCXX_STL_BUFFER_SIZE__), elements(0), a(al) + { + data = a.allocate(data_size); + } + + explicit _UCXXEXPORT vector(size_type n, const T& value = T(), const Allocator& al= Allocator()) : + data(0), data_size(0), elements(0), a(al) + { + data_size = n + __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + + resize(n, value); + } + + template _UCXXEXPORT + vector(InputIterator first, InputIterator last, const Allocator& al = Allocator()): + data(0), data_size(__UCLIBCXX_STL_BUFFER_SIZE__), elements(0), a(al) + { + data = a.allocate(data_size); + assign(first, last); + } + + _UCXXEXPORT vector(const vector& x){ + a = x.a; + + elements = x.elements; + data_size = elements + __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + + for(size_type i = 0; i < elements; i++){ + a.construct(data+i, x.data[i]); + } + } + + _UCXXEXPORT ~vector(); //Below + + _UCXXEXPORT vector& operator=(const vector& x){ + if(&x == this){ + return *this; + } + + reserve(x.elements); //Make sure that we have enough actual memory + + + //Copy as many elements as possible + + size_t minElements = elements; + if(minElements > x.elements){ + minElements = x.elements; + } + for(size_t i = 0; i < minElements; ++i){ + data[i] = x.data[i]; + } + + //If we need to add new elements + if(elements < x.elements){ + for(size_t i = elements; i< x.elements; ++i){ + a.construct(data+i, x.data[i]); + ++elements; + } + } + + if(elements > x.elements){ + downsize(x.elements); + } + + return *this; + } + + template _UCXXEXPORT void assign(InputIterator first, InputIterator last){ + clear(); + insert(begin(), first, last); + } + + template _UCXXEXPORT void assign(Size n, const U& u = U()){ + clear(); + resize(n, u); + } + + inline allocator_type get_allocator() const{ + return a; + } + + inline iterator begin(){ + return data; + } + + inline const_iterator begin() const{ + return data; + } + + inline iterator end(){ + return (data + elements); + } + + inline const_iterator end() const{ + return (data + elements); + } + + inline reverse_iterator rbegin(){ + return reverse_iterator(end()); + } + + inline const_reverse_iterator rbegin() const{ + return const_reverse_iterator(end()); + } + + inline reverse_iterator rend(){ + return reverse_iterator(begin()); + } + + inline const_reverse_iterator rend() const{ + return const_reverse_iterator(begin()); + } + + inline size_type size() const{ + return elements; + } + + _UCXXEXPORT size_type max_size() const{ + return ((size_type)(-1)) / sizeof(T); + } + + void downsize(size_type sz); + void resize(size_type sz, const T & c = T()); + + inline size_type capacity() const{ + return data_size; + } + + inline bool empty() const{ + return (size() == 0); + } + + void reserve(size_type n); + + inline reference operator[](size_type n){ + return data[n]; + } + + inline const_reference operator[](size_type n) const{ + return data[n]; + } + + _UCXXEXPORT const_reference at(size_type n) const{ + if(n >= elements){ + __throw_out_of_range("Invalid subscript"); + } + return data[n]; + } + + _UCXXEXPORT reference at(size_type n){ + if(n >= elements){ + __throw_out_of_range("Invalid subscript"); + } + return data[n]; + } + + inline reference front(){ + return data[0]; + } + + inline const_reference front() const{ + return data[0]; + } + + inline reference back(){ + return data[ size() - 1]; + } + + inline const_reference back() const{ + return data[ size() - 1 ]; + } + + inline void push_back(const T& x){ + resize( size() + 1, x); + } + + inline void pop_back(){ + downsize(size() - 1); + } + + _UCXXEXPORT iterator insert(iterator position, const T& x = T()){ + size_type index = position - data; + resize(size() + 1, x); + for(size_type i = elements - 1; i > index; --i){ + data[i] = data[i-1]; + } + data[index] = x; + return (data + index); + } + + _UCXXEXPORT void _insert_fill(iterator position, size_type n, const T & x){ + size_type index = position - data; + resize(size() + n, x); + + for(size_type i = elements -1; (i > (index+n-1)); --i){ + data[i] = data[i-n]; + } + for(size_type i = 0; i < n; i++){ + data[i + index] = x; + } + } + + template _UCXXEXPORT + void _insert_from_iterator(iterator position, InputIterator first, InputIterator last) + { + T temp; + while(first !=last){ + temp = *first; + position = insert(position, temp); + ++position; + ++first; + } + } + + template + inline void _dispatch_insert(iterator position, InputIterator first, InputIterator last, __true_type) + { + _insert_fill(position, first, last); + } + + template + inline void _dispatch_insert(iterator position, InputIterator first, InputIterator last, __false_type) + { + _insert_from_iterator(position, first, last); + } + + inline void insert(iterator position, size_type n, const T& x ){ + _insert_fill(position, n, x); + } + + template inline void insert(iterator position, InputIterator first, InputIterator last){ + typedef typename __is_integer::value __some_type; + _dispatch_insert(position, first, last, __some_type()); + } + + _UCXXEXPORT iterator erase(iterator position){ + size_type index = position - data; + for(size_type i = index; i < (elements - 1); ++i){ + data[i] = data[i+1]; + } + downsize(size() - 1); + return (data + index); + } + + _UCXXEXPORT iterator erase(iterator first, iterator last){ + size_type index = first - data; + size_type width = last - first; + for(size_type i = index; i < (elements - width) ;++i){ + data[i] = data[i+width]; + } + downsize(size() - width); + return (data + index); + } + + _UCXXEXPORT void swap(vector& v){ + if(this == &v){ //Avoid dv.swap(v) + return; + } + T* ptr; + size_type temp; + + //Swap pointers first + ptr = data; + data = v.data; + v.data = ptr; + + //Swap element counts + temp = elements; + elements = v.elements; + v.elements = temp; + + //Swap data size + temp = data_size; + data_size = v.data_size; + v.data_size = temp; + } + + _UCXXEXPORT void clear(){ + downsize(0); + } + + protected: + T* data; + size_type data_size; + size_type elements; + Allocator a; + }; + + + + //Here go template instantiations + + template _UCXXEXPORT vector::~vector(){ + for(size_t i = 0; i < elements; ++i){ + a.destroy(data + i); + } + a.deallocate(data, data_size); + } + + + template _UCXXEXPORT void vector::reserve(size_type n){ + if(n > data_size){ //We never shrink... + T * temp_ptr = data; + size_type temp_size = data_size; + + data_size = n; + data = a.allocate(data_size); + + for(size_type i = 0; i _UCXXEXPORT void vector::resize(size_type sz, const T & c){ + if(sz > elements){ //Need to actually call constructor + if(sz > data_size){ + reserve(sz + __UCLIBCXX_STL_BUFFER_SIZE__); + } + + for(size_type i = elements; i _UCXXEXPORT void vector::downsize(size_type sz){ + if(sz < elements){ //Actually are downsizing + for(size_t i = sz; i< elements; ++i){ + a.destroy(data+i); + } + elements = sz; + } + } + + +#ifndef __UCLIBCXX_COMPILE_VECTOR__ +#ifdef __UCLIBCXX_EXPAND_VECTOR_BASIC__ + + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + template<> _UCXXEXPORT vector >::vector(const allocator& al); + template<> _UCXXEXPORT vector >::vector(size_type n, const char & value, const allocator & al); + + template<> _UCXXEXPORT vector >::~vector(); + template<> _UCXXEXPORT vector >::~vector(); + +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + + template<> _UCXXEXPORT void vector >::resize(size_type sz, const char & c); + template<> _UCXXEXPORT void + vector >::resize(size_type sz, const unsigned char & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const short & c); + template<> _UCXXEXPORT void + vector >::resize(size_type sz, const unsigned short int & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const int & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const unsigned int & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const long int & c); + template<> _UCXXEXPORT void + vector >::resize(size_type sz, const unsigned long int & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const float & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const double & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const bool & c); + +#elif defined __UCLIBCXX_EXPAND_STRING_CHAR__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template<> _UCXXEXPORT vector >::vector(const allocator& al); + template<> _UCXXEXPORT vector >::vector(size_type n, const char & value, const allocator & al); + template<> _UCXXEXPORT vector >::~vector(); + +#endif + + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const char & c); + +#endif +#endif + + + + template _UCXXEXPORT bool + operator==(const vector& x, const vector& y) + { + if(x.size() !=y.size() ){ + return false; + } + for(size_t i = 0; i < x.size(); ++i){ + if(x[i] != y[i]){ + return false; + } + } + return true; + } + + template _UCXXEXPORT bool + operator< (const vector& x, const vector& y) + { + less::iterator >::value_type> c; + return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); + } + template _UCXXEXPORT bool + operator!=(const vector& x, const vector& y) + { + return !(x == y); + } + template _UCXXEXPORT bool + operator> (const vector& x, const vector& y) + { + greater::iterator >::value_type> c; + return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); + } + template _UCXXEXPORT bool + operator>=(const vector& x, const vector& y) + { + greater_equal::iterator >::value_type> c; + return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); + } + template _UCXXEXPORT bool + operator<=(const vector& x, const vector& y) + { + less_equal::iterator >::value_type> c; + return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); + } + + template _UCXXEXPORT void swap(vector& x, vector& y){ + x.swap(y); + } + +} + +#pragma GCC visibility pop + +#endif + diff --git a/misc/uClibc++/include/features.h b/misc/uClibc++/include/features.h new file mode 100644 index 0000000000..41e83a93ff --- /dev/null +++ b/misc/uClibc++/include/features.h @@ -0,0 +1,451 @@ +/* Copyright (C) 1991-1993,1995-2006,2007,2009 Free Software Foundation, Inc. + This file is part of the GNU C Library. + + The GNU C Library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + The GNU C Library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with the GNU C Library; if not, write to the Free + Software Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA + 02111-1307 USA. */ + +#ifndef _FEATURES_H +#define _FEATURES_H 1 + +/* These are defined by the user (or the compiler) + to specify the desired environment: + + __STRICT_ANSI__ ISO Standard C. + _ISOC99_SOURCE Extensions to ISO C89 from ISO C99. + _POSIX_SOURCE IEEE Std 1003.1. + _POSIX_C_SOURCE If ==1, like _POSIX_SOURCE; if >=2 add IEEE Std 1003.2; + if >=199309L, add IEEE Std 1003.1b-1993; + if >=199506L, add IEEE Std 1003.1c-1995; + if >=200112L, all of IEEE 1003.1-2004 + if >=200809L, all of IEEE 1003.1-2008 + _XOPEN_SOURCE Includes POSIX and XPG things. Set to 500 if + Single Unix conformance is wanted, to 600 for the + sixth revision, to 700 for the seventh revision. + _XOPEN_SOURCE_EXTENDED XPG things and X/Open Unix extensions. + _LARGEFILE_SOURCE Some more functions for correct standard I/O. + _LARGEFILE64_SOURCE Additional functionality from LFS for large files. + _FILE_OFFSET_BITS=N Select default filesystem interface. + _BSD_SOURCE ISO C, POSIX, and 4.3BSD things. + _SVID_SOURCE ISO C, POSIX, and SVID things. + _ATFILE_SOURCE Additional *at interfaces. + _GNU_SOURCE All of the above, plus GNU extensions. + _REENTRANT Select additionally reentrant object. + _THREAD_SAFE Same as _REENTRANT, often used by other systems. + _FORTIFY_SOURCE If set to numeric value > 0 additional security + measures are defined, according to level. + + The `-ansi' switch to the GNU C compiler defines __STRICT_ANSI__. + If none of these are defined, the default is to have _SVID_SOURCE, + _BSD_SOURCE, and _POSIX_SOURCE set to one and _POSIX_C_SOURCE set to + 200112L. If more than one of these are defined, they accumulate. + For example __STRICT_ANSI__, _POSIX_SOURCE and _POSIX_C_SOURCE + together give you ISO C, 1003.1, and 1003.2, but nothing else. + + These are defined by this file and are used by the + header files to decide what to declare or define: + + __USE_ISOC99 Define ISO C99 things. + __USE_ISOC95 Define ISO C90 AMD1 (C95) things. + __USE_POSIX Define IEEE Std 1003.1 things. + __USE_POSIX2 Define IEEE Std 1003.2 things. + __USE_POSIX199309 Define IEEE Std 1003.1, and .1b things. + __USE_POSIX199506 Define IEEE Std 1003.1, .1b, .1c and .1i things. + __USE_XOPEN Define XPG things. + __USE_XOPEN_EXTENDED Define X/Open Unix things. + __USE_UNIX98 Define Single Unix V2 things. + __USE_XOPEN2K Define XPG6 things. + __USE_XOPEN2K8 Define XPG7 things. + __USE_LARGEFILE Define correct standard I/O things. + __USE_LARGEFILE64 Define LFS things with separate names. + __USE_FILE_OFFSET64 Define 64bit interface as default. + __USE_BSD Define 4.3BSD things. + __USE_SVID Define SVID things. + __USE_MISC Define things common to BSD and System V Unix. + __USE_ATFILE Define *at interfaces and AT_* constants for them. + __USE_GNU Define GNU extensions. + __USE_REENTRANT Define reentrant/thread-safe *_r functions. + __USE_FORTIFY_LEVEL Additional security measures used, according to level. + __FAVOR_BSD Favor 4.3BSD things in cases of conflict. + + The macros `__GNU_LIBRARY__', `__GLIBC__', and `__GLIBC_MINOR__' are + defined by this file unconditionally. `__GNU_LIBRARY__' is provided + only for compatibility. All new code should use the other symbols + to test for features. + + All macros listed above as possibly being defined by this file are + explicitly undefined if they are not explicitly defined. + Feature-test macros that are not defined by the user or compiler + but are implied by the other feature-test macros defined (or by the + lack of any definitions) are defined by the file. */ + + +/* Undefine everything, so we get a clean slate. */ +#undef __USE_ISOC99 +#undef __USE_ISOC95 +#undef __USE_POSIX +#undef __USE_POSIX2 +#undef __USE_POSIX199309 +#undef __USE_POSIX199506 +#undef __USE_XOPEN +#undef __USE_XOPEN_EXTENDED +#undef __USE_UNIX98 +#undef __USE_XOPEN2K +#undef __USE_XOPEN2K8 +#undef __USE_LARGEFILE +#undef __USE_LARGEFILE64 +#undef __USE_FILE_OFFSET64 +#undef __USE_BSD +#undef __USE_SVID +#undef __USE_MISC +#undef __USE_ATFILE +#undef __USE_GNU +#undef __USE_REENTRANT +#undef __USE_FORTIFY_LEVEL +#undef __FAVOR_BSD +#undef __KERNEL_STRICT_NAMES + +/* Suppress kernel-name space pollution unless user expressedly asks + for it. */ +#ifndef _LOOSE_KERNEL_NAMES +# define __KERNEL_STRICT_NAMES +#endif + +/* Always use ISO C things. */ +#define __USE_ANSI 1 + +/* Convenience macros to test the versions of glibc and gcc. + Use them like this: + #if __GNUC_PREREQ (2,8) + ... code requiring gcc 2.8 or later ... + #endif + Note - they won't work for gcc1 or glibc1, since the _MINOR macros + were not defined then. */ +#if defined __GNUC__ && defined __GNUC_MINOR__ +# define __GNUC_PREREQ(maj, min) \ + ((__GNUC__ << 16) + __GNUC_MINOR__ >= ((maj) << 16) + (min)) +#else +# define __GNUC_PREREQ(maj, min) 0 +#endif + + +/* If _BSD_SOURCE was defined by the user, favor BSD over POSIX. */ +#if defined _BSD_SOURCE && \ + !(defined _POSIX_SOURCE || defined _POSIX_C_SOURCE || \ + defined _XOPEN_SOURCE || defined _XOPEN_SOURCE_EXTENDED || \ + defined _GNU_SOURCE || defined _SVID_SOURCE) +# define __FAVOR_BSD 1 +#endif + +/* If _GNU_SOURCE was defined by the user, turn on all the other features. */ +#ifdef _GNU_SOURCE +# undef _ISOC99_SOURCE +# define _ISOC99_SOURCE 1 +# undef _POSIX_SOURCE +# define _POSIX_SOURCE 1 +# undef _POSIX_C_SOURCE +# define _POSIX_C_SOURCE 200809L +# undef _XOPEN_SOURCE +# define _XOPEN_SOURCE 700 +# undef _XOPEN_SOURCE_EXTENDED +# define _XOPEN_SOURCE_EXTENDED 1 +# undef _LARGEFILE64_SOURCE +# define _LARGEFILE64_SOURCE 1 +# undef _BSD_SOURCE +# define _BSD_SOURCE 1 +# undef _SVID_SOURCE +# define _SVID_SOURCE 1 +# undef _ATFILE_SOURCE +# define _ATFILE_SOURCE 1 +#endif + +/* This macro indicates that the installed library is uClibc. Use + * __UCLIBC_MAJOR__ and __UCLIBC_MINOR__ to test for the features in + * specific releases. */ +#define __UCLIBC__ 1 + +#ifdef __UCLIBC__ +/* Load up the current set of uClibc supported features along + * with the current uClibc major and minor version numbers. + * For uClibc release 0.9.26, these numbers would be: + * #define __UCLIBC_MAJOR__ 0 + * #define __UCLIBC_MINOR__ 9 + * #define __UCLIBC_SUBLEVEL__ 26 + */ +# define __need_uClibc_config_h +# include +# undef __need_uClibc_config_h + +/* For uClibc, always optimize for size -- this should disable + * a lot of expensive inlining... + * TODO: this is wrong! __OPTIMIZE_SIZE__ is an indicator of + * gcc -Os compile. We should not mess with compiler inlines. + * We should instead disable __USE_EXTERN_INLINES unconditionally, + * or maybe actually audit and test uclibc to work correctly + * with __USE_EXTERN_INLINES on. + */ +# define __OPTIMIZE_SIZE__ 1 + +/* disable unsupported features */ +# undef __LDBL_COMPAT + +# ifndef __UCLIBC_HAS_FORTIFY__ +# undef _FORTIFY_SOURCE +# endif + +# ifndef __UCLIBC_HAS_THREADS__ +# if defined _REENTRANT || defined _THREAD_SAFE +# warning requested reentrant code, but thread support was disabled +# undef _REENTRANT +# undef _THREAD_SAFE +# endif +# endif + +# ifndef __UCLIBC_HAS_LFS__ +# undef _LARGEFILE64_SOURCE +/* NOTE: This is probably incorrect on a 64-bit arch... */ +# if defined _FILE_OFFSET_BITS && _FILE_OFFSET_BITS == 64 +# error It appears you have defined _FILE_OFFSET_BITS=64. Unfortunately, \ +uClibc was built without large file support enabled. +# endif +# elif defined __BCC__ +# error BCC does not support LFS, please disable it +# endif +#endif /* __UCLIBC__ */ + +/* If nothing (other than _GNU_SOURCE) is defined, + define _BSD_SOURCE and _SVID_SOURCE. */ +#if (!defined __STRICT_ANSI__ && !defined _ISOC99_SOURCE && \ + !defined _POSIX_SOURCE && !defined _POSIX_C_SOURCE && \ + !defined _XOPEN_SOURCE && !defined _XOPEN_SOURCE_EXTENDED && \ + !defined _BSD_SOURCE && !defined _SVID_SOURCE) +# define _BSD_SOURCE 1 +# define _SVID_SOURCE 1 +#endif + +/* This is to enable the ISO C99 extension. Also recognize the old macro + which was used prior to the standard acceptance. This macro will + eventually go away and the features enabled by default once the ISO C99 + standard is widely adopted. */ +#if (defined _ISOC99_SOURCE || defined _ISOC9X_SOURCE \ + || (defined __STDC_VERSION__ && __STDC_VERSION__ >= 199901L)) +# define __USE_ISOC99 1 +#endif + +/* This is to enable the ISO C90 Amendment 1:1995 extension. */ +#if (defined _ISOC99_SOURCE || defined _ISOC9X_SOURCE \ + || (defined __STDC_VERSION__ && __STDC_VERSION__ >= 199409L)) +# define __USE_ISOC95 1 +#endif + +/* If none of the ANSI/POSIX macros are defined, use POSIX.1 and POSIX.2 + (and IEEE Std 1003.1b-1993 unless _XOPEN_SOURCE is defined). */ +#if ((!defined __STRICT_ANSI__ || (_XOPEN_SOURCE - 0) >= 500) && \ + !defined _POSIX_SOURCE && !defined _POSIX_C_SOURCE) +# define _POSIX_SOURCE 1 +# if defined _XOPEN_SOURCE && (_XOPEN_SOURCE - 0) < 500 +# define _POSIX_C_SOURCE 2 +# elif defined _XOPEN_SOURCE && (_XOPEN_SOURCE - 0) < 600 +# define _POSIX_C_SOURCE 199506L +# elif defined _XOPEN_SOURCE && (_XOPEN_SOURCE - 0) < 700 +# define _POSIX_C_SOURCE 200112L +# else +# define _POSIX_C_SOURCE 200809L +# endif +# define __USE_POSIX_IMPLICITLY 1 +#endif + +#if defined _POSIX_SOURCE || _POSIX_C_SOURCE >= 1 || defined _XOPEN_SOURCE +# define __USE_POSIX 1 +#endif + +#if defined _POSIX_C_SOURCE && _POSIX_C_SOURCE >= 2 || defined _XOPEN_SOURCE +# define __USE_POSIX2 1 +#endif + +#if (_POSIX_C_SOURCE - 0) >= 199309L +# define __USE_POSIX199309 1 +#endif + +#if (_POSIX_C_SOURCE - 0) >= 199506L +# define __USE_POSIX199506 1 +#endif + +#if (_POSIX_C_SOURCE - 0) >= 200112L +# define __USE_XOPEN2K 1 +# undef __USE_ISOC99 +# define __USE_ISOC99 1 +#endif + +#if (_POSIX_C_SOURCE - 0) >= 200809L +# define __USE_XOPEN2K8 1 +# undef _ATFILE_SOURCE +# define _ATFILE_SOURCE 1 +#endif + +#ifdef _XOPEN_SOURCE +# define __USE_XOPEN 1 +# if (_XOPEN_SOURCE - 0) >= 500 +# define __USE_XOPEN_EXTENDED 1 +# define __USE_UNIX98 1 +# undef _LARGEFILE_SOURCE +# define _LARGEFILE_SOURCE 1 +# if (_XOPEN_SOURCE - 0) >= 600 +# if (_XOPEN_SOURCE - 0) >= 700 +# define __USE_XOPEN2K8 1 +# endif +# define __USE_XOPEN2K 1 +# undef __USE_ISOC99 +# define __USE_ISOC99 1 +# endif +# else +# ifdef _XOPEN_SOURCE_EXTENDED +# define __USE_XOPEN_EXTENDED 1 +# endif +# endif +#endif + +#ifdef _LARGEFILE_SOURCE +# define __USE_LARGEFILE 1 +#endif + +#ifdef _LARGEFILE64_SOURCE +# define __USE_LARGEFILE64 1 +#endif + +#if defined _FILE_OFFSET_BITS && _FILE_OFFSET_BITS == 64 +# define __USE_FILE_OFFSET64 1 +#endif + +#if defined _BSD_SOURCE || defined _SVID_SOURCE +# define __USE_MISC 1 +#endif + +#ifdef _BSD_SOURCE +# define __USE_BSD 1 +#endif + +#ifdef _SVID_SOURCE +# define __USE_SVID 1 +#endif + +#ifdef _ATFILE_SOURCE +# define __USE_ATFILE 1 +#endif + +#ifdef _GNU_SOURCE +# define __USE_GNU 1 +#endif + +#if defined _REENTRANT || defined _THREAD_SAFE +# define __USE_REENTRANT 1 +#endif + +#if defined _FORTIFY_SOURCE && _FORTIFY_SOURCE > 0 \ + && __GNUC_PREREQ (4, 1) && defined __OPTIMIZE__ && __OPTIMIZE__ > 0 +# if _FORTIFY_SOURCE > 1 +# define __USE_FORTIFY_LEVEL 2 +# else +# define __USE_FORTIFY_LEVEL 1 +# endif +#else +# define __USE_FORTIFY_LEVEL 0 +#endif + +/* We do support the IEC 559 math functionality, real and complex. */ +#ifdef __UCLIBC_HAS_FLOATS__ +#define __STDC_IEC_559__ 1 +#define __STDC_IEC_559_COMPLEX__ 1 +#endif + +#ifdef __UCLIBC_HAS_WCHAR__ +/* wchar_t uses ISO 10646-1 (2nd ed., published 2000-09-15) / Unicode 3.1. */ +#define __STDC_ISO_10646__ 200009L +#endif + +/* There is an unwholesomely huge amount of code out there that depends on the + * presence of GNU libc header files. We have GNU libc header files. So here + * we commit a horrible sin. At this point, we _lie_ and claim to be GNU libc + * to make things like /usr/include/linux/socket.h and lots of apps work as + * their developers intended. This is IMHO, pardonable, since these defines + * are not really intended to check for the presence of a particular library, + * but rather are used to define an _interface_. */ +#if !defined __FORCE_NOGLIBC && (!defined _LIBC || defined __FORCE_GLIBC) +/* This macro indicates that the installed library is the GNU C Library. + For historic reasons the value now is 6 and this will stay from now + on. The use of this variable is deprecated. */ +/* uClibc WARNING: leave these aligned to the left, don't put a space after '#', else + * broken apps could fail the check. */ +#undef __GNU_LIBRARY__ +#define __GNU_LIBRARY__ 6 + +/* Major and minor version number of the GNU C library package. Use + these macros to test for features in specific releases. */ +/* Don't do it, if you want to keep uClibc happy. */ +#define __GLIBC__ 2 +#define __GLIBC_MINOR__ 2 +#endif + +#define __GLIBC_PREREQ(maj, min) \ + ((__GLIBC__ << 16) + __GLIBC_MINOR__ >= ((maj) << 16) + (min)) + +#ifndef __UCLIBC__ +/* Decide whether a compiler supports the long long datatypes. */ +#if defined __GNUC__ \ + || (defined __PGI && defined __i386__ ) \ + || (defined __INTEL_COMPILER && (defined __i386__ || defined __ia64__)) \ + || (defined __STDC_VERSION__ && __STDC_VERSION__ >= 199901L) +# define __GLIBC_HAVE_LONG_LONG 1 +#endif +#endif + +/* This is here only because every header file already includes this one. */ +#ifndef __ASSEMBLER__ +# ifndef _SYS_CDEFS_H +# include +# endif + +/* If we don't have __REDIRECT, prototypes will be missing if + __USE_FILE_OFFSET64 but not __USE_LARGEFILE[64]. */ +# if defined __USE_FILE_OFFSET64 && !defined __REDIRECT +# define __USE_LARGEFILE 1 +# ifdef __UCLIBC_HAS_LFS__ +# define __USE_LARGEFILE64 1 +# endif +# endif + +#endif /* !ASSEMBLER */ + +/* Decide whether we can, and are willing to define extern inline + * functions in headers, even if this results in a slightly bigger + * code for user programs built against uclibc. + * Enabled only in -O2 compiles, not -Os. + * uclibc itself is usually built without __USE_EXTERN_INLINES, + * remove "&& !defined __OPTIMIZE_SIZE__" part to do otherwise. + */ +#if __GNUC_PREREQ (2, 7) && defined __OPTIMIZE__ \ + && !defined __OPTIMIZE_SIZE__ && !defined __NO_INLINE__ \ + && (defined __extern_inline || defined __GNUC_GNU_INLINE__ || defined __GNUC_STDC_INLINE__) +# define __USE_EXTERN_INLINES 1 +#endif + +#ifdef _LIBC +# ifdef __UCLIBC_HAS_LFS__ +# undef _FILE_OFFSET_BITS +# undef __USE_FILE_OFFSET64 +# endif +# include +#endif + +#endif /* features.h */ diff --git a/misc/uClibc++/install.sh b/misc/uClibc++/install.sh new file mode 100755 index 0000000000..9f612bc41f --- /dev/null +++ b/misc/uClibc++/install.sh @@ -0,0 +1,312 @@ +#!/bin/bash + +usage="USAGE: $0 " + +lgpl="\n +GNU LESSER GENERAL PUBLIC LICENSE\n +\n +Version 3, 29 June 2007\n +\n +Copyright © 2007 Free Software Foundation, Inc. \n +\n +Everyone is permitted to copy and distribute verbatim copies of this \n +license document, but changing it is not allowed.\n +\n +This version of the GNU Lesser General Public License incorporates the\n +terms and conditions of version 3 of the GNU General Public License,\n +supplemented by the additional permissions listed below.\n +\n +0. Additional Definitions.\n +\n +As used herein, “this License” refers to version 3 of the GNU Lesser\n +General Public License, and the “GNU GPL” refers to version 3 of the\n +GNU General Public License.\n +\n +“The Library” refers to a covered work governed by this License, other\n +than an Application or a Combined Work as defined below.\n +\n +An “Application” is any work that makes use of an interface provided\n +by the Library, but which is not otherwise based on the Library. Defining\n +a subclass of a class defined by the Library is deemed a mode of using an\n +interface provided by the Library.\n +\n +A “Combined Work” is a work produced by combining or linking an\n +Application with the Library. The particular version of the Library with\n +which the Combined Work was made is also called the “Linked Version”.\n +\n +The “Minimal Corresponding Source” for a Combined Work means the\n +Corresponding Source for the Combined Work, excluding any source code\n +for portions of the Combined Work that, considered in isolation, are based\n +on the Application, and not on the Linked Version.\n +\n +The “Corresponding Application Code” for a Combined Work means the object\n +code and/or source code for the Application, including any data and utility\n +programs needed for reproducing the Combined Work from the Application,\n +but excluding the System Libraries of the Combined Work.\n +\n +1. Exception to Section 3 of the GNU GPL.\n +\n +You may convey a covered work under sections 3 and 4 of this License\n +without being bound by section 3 of the GNU GPL.\n +\n +2. Conveying Modified Versions.\n +\n +If you modify a copy of the Library, and, in your modifications, a\n +facility refers to a function or data to be supplied by an Application\n +that uses the facility (other than as an argument passed when the facility\n +is invoked), then you may convey a copy of the modified version:\n +\n + a) under this License, provided that you make a good faith effort to\n + ensure that, in the event an Application does not supply the function\n + or data, the facility still operates, and performs whatever part of\n + its purpose remains meaningful, or\n + b) under the GNU GPL, with none of the additional permissions of this\n + License applicable to that copy.\n +\n +3. Object Code Incorporating Material from Library Header Files.\n +\n +The object code form of an Application may incorporate material from a\n +header file that is part of the Library. You may convey such object code\n +under terms of your choice, provided that, if the incorporated material is\n +not limited to numerical parameters, data structure layouts and accessors, or\n +small macros, inline functions and templates (ten or fewer lines in length),\n +you do both of the following:\n +\n + a) Give prominent notice with each copy of the object code that the\n + Library is used in it and that the Library and its use are covered\n + by this License.\n + b) Accompany the object code with a copy of the GNU GPL and this license\n + document.\n +\n +4. Combined Works.\n +\n +You may convey a Combined Work under terms of your choice that, taken\n +together, effectively do not restrict modification of the portions of the\n +Library contained in the Combined Work and reverse engineering for debugging\n +such modifications, if you also do each of the following:\n +\n + a) Give prominent notice with each copy of the Combined Work that the\n + Library is used in it and that the Library and its use are covered by\n + this License.\n + b) Accompany the Combined Work with a copy of the GNU GPL and this\n + license document.\n + c) For a Combined Work that displays copyright notices during execution,\n + include the copyright notice for the Library among these notices,\n + as well as a reference directing the user to the copies of the\n + GNU GPL and this license document.\n + d) Do one of the following:\n +\n + 0) Convey the Minimal Corresponding Source under the terms of\n + this License, and the Corresponding Application Code in a form\n + suitable for, and under terms that permit, the user to recombine\n + or relink the Application with a modified version of the Linked\n + Version to produce a modified Combined Work, in the manner\n + specified by section 6 of the GNU GPL for conveying Corresponding\n + Source.\n + 1) Use a suitable shared library mechanism for linking with the Library.\n + A suitable mechanism is one that (a) uses at run time a copy of\n + the Library already present on the user's computer system, and\n + (b) will operate properly with a modified version of the Library\n + that is interface-compatible with the Linked Version.\n +\n + e) Provide Installation Information, but only if you would otherwise\n + be required to provide such information under section 6 of the\n + GNU GPL, and only to the extent that such information is necessary\n + to install and execute a modified version of the Combined Work\n + produced by recombining or relinking the Application with a\n + modified version of the Linked Version. (If you use option 4d0, the\n + Installation Information must accompany the Minimal Corresponding\n + Source and Corresponding Application Code. If you use option 4d1,\n + you must provide the Installation Information in the manner\n + specified by section 6 of the GNU GPL for conveying Corresponding\n + Source.)\n +\n +5. Combined Libraries.\n +\n +You may place library facilities that are a work based on the Library\n +side by side in a single library together with other library facilities\n +that are not Applications and are not covered by this License, and convey\n +such a combined library under terms of your choice, if you do both of the\n +following:\n +\n + a) Accompany the combined library with a copy of the same work based\n + on the Library, uncombined with any other library facilities,\n + conveyed under the terms of this License.\n + b) Give prominent notice with the combined library that part of it\n + is a work based on the Library, and explaining where to find the\n + accompanying uncombined form of the same work.\n +\n +6. Revised Versions of the GNU Lesser General Public License.\n +\n +The Free Software Foundation may publish revised and/or new versions of\n +the GNU Lesser General Public License from time to time. Such new\n +versions will be similar in spirit to the present version, but may\n +differ in detail to address new problems or concerns.\n +\n +Each version is given a distinguishing version number. If the Library\n +as you received it specifies that a certain numbered version of the\n +GNU Lesser General Public License “or any later version” applies to\n +it, you have the option of following the terms and conditions either\n +of that published version or of any later version published by the Free\n +Software Foundation. If the Library as you received it does not specify\n +a version number of the GNU Lesser General Public License, you may\n +choose any version of the GNU Lesser General Public License ever\n +published by the Free Software Foundation.\n +\n +If the Library as you received it specifies that a proxy can decide\n +whether future versions of the GNU Lesser General Public License shall\n +apply, that proxy's public statement of acceptance of any version is\n +permanent authorization for you to choose that version for the Library.\n" + +# readans prompt default + +function readans () { + echo -n "$1 ($2): " + IFS='@' read ans || exit 1 + [ -z "$ans" ] && ans=$2 +} + +# readyn prompt default + +function readyn () { + while :; do + readans "$1 [Y/N]" $2 + case "$ans" in + [yY] | [yY]es ) + ans=y + break ;; + [nN] | [nN]o ) + ans=n + break ;; + * ) + echo "Please answer Y or N" + ;; + esac + done +} + +# Get the single, required command line argument + +nuttx_path=$1 +if [ -z "${nuttx_path}" ]; then + echo "ERROR: Missing path to the NuttX directory" + echo $usage + exit 1 +fi + +# Lots of sanity checking so that we do not do anything too stupid + +if [ ! -d libxx ]; then + echo "ERROR: Directory libxx does not exist in this directory" + echo " Please CD into the misc/uClibc++ directory and try again" + echo $usage + exit 1 +fi + +if [ ! -d include ]; then + echo "ERROR: Directory include does not exist in this directory" + echo " Please CD into the misc/uClibc++ directory and try again" + echo $usage + exit 1 +fi + +if [ ! -d "${nuttx_path}" ]; then + echo "ERROR: Directory ${nuttx_path} does not exist" + echo $usage + exit 1 +fi + +if [ ! -f "${nuttx_path}/Makefile" ]; then + echo "ERROR: Not Makefile in directory ${nuttx_path}" + echo $usage + exit 1 +fi + +libxx_srcdir=${nuttx_path}/libxx + +if [ ! -d "${libxx_srcdir}" ]; then + echo "ERROR: Directory ${libxx_srcdir} does not exist" + echo $usage + exit 1 +fi + +if [ ! -f "${libxx_srcdir}/Makefile" ]; then + echo "ERROR: No Makefile in directory ${libxx_srcdir}" + echo $usage + exit 1 +fi + +uclibc_srcdir=${libxx_srcdir}/uClibc++ + +if [ -d "${uclibc_srcdir}" ]; then + echo "ERROR: Directory ${uclibc_srcdir} already exists" + echo " Please remove the ${uclibc_srcdir} directory and try again" + echo $usage + exit 1 +fi + +nuttx_incdir=${nuttx_path}/include + +if [ ! -d "${nuttx_incdir}" ]; then + echo "ERROR: Directory ${nuttx_incdir} does not exist" + echo $usage + exit 1 +fi + +nuttxcxx_incdir=${nuttx_incdir}/cxx + +if [ ! -d "${nuttxcxx_incdir}" ]; then + echo "ERROR: Directory ${nuttxcxx_incdir} does not exist" + echo $usage + exit 1 +fi + +# Licensing + +echo "You are about to install the uClibc++ library into the NuttX source" +echo "tree. NuttX is licensed under a modified BSD License; uClibc is" +echo "licensed under the GNU LGPL Version 3 license. When you install" +echo "uClibc++ into the NuttX source tree, you must then comply with uClibc's" +echo "stricter GNU LGPL Version 3 license." +echo "" + +readyn "Continue" "N" +echo "" + +if [ "X${ans}" != "Xy" -a "X${ans}" != "XY" ]; then + echo "Good bye" + exit 0 +fi + +echo "You must read and agree to the following license" +echo "" + +readyn "Continue" "N" +echo "" + +if [ "X${ans}" != "Xy" -a "X${ans}" != "XY" ]; then + echo "Good bye" + exit 0 +fi + +echo -e ${lgpl} | more +echo "" + +readyn "I agree to the termso the GNU LGPL Version 3 license" "N" +echo "" + +if [ "X${ans}" != "Xy" -a "X${ans}" != "XY" ]; then + echo "Good bye" + exit 0 +fi + +echo "Installing uClibc++ in the NuttX source tree" + +cp -a ./libxx/* ${libxx_srcdir}/. || + { echo "Copy from ./libxx/* to ${libxx_srcdir}/. failed"; exit 1; } + +cp -a ./include/* ${nuttx_incdir}/. || + { echo "Copy from ./include/* ${nuttx_incdir}/. failed"; exit 1; } + +echo "Installation suceeded" +echo "" diff --git a/misc/uClibc++/libxx/uClib++/Make.defs b/misc/uClibc++/libxx/uClib++/Make.defs new file mode 100644 index 0000000000..38ae24a93e --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/Make.defs @@ -0,0 +1,52 @@ +############################################################################ +# misc/uClibc++/libxx/uClibc++/Makefile +# +# 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. +# +########################################################################### + +# Add the uClibc++ sources + +CXXSRCS += algorithm.cxx associative_base.cxx bitset.cxx char_traits.cxx +CXXSRCS += complex.cxx del_op.cxx del_opnt.cxx del_opv.cxx del_opvnt.cxx +CXXSRCS += deque.cxx eh_alloc.cxx eh_globals.cxx exception.cxx +CXXSRCS += stream.cxx func_exception.cxx iomanip.cxx ios.cxx +CXXSRCS += iostream.cxx istream.cxx iterator.cxx limits.cxx list.cxx +CXXSRCS += locale.cxx map.cxx new_handler.cxx new_op.cxx new_opnt.cxx +CXXSRCS += new_opv.cxx new_opvnt.cxx numeric.cxx ostream.cxx queue.cxx +CXXSRCS += set.cxx sstream.cxx stack.cxx stdexcept.cxx streambuf.cxx +CXXSRCS += string.cxx support.cxx typeinfo.cxx utility.cxx valarray.cxx +CXXSRCS += vector.cxx + +# Add the path to the uClibc++ subdirectory + +DEPPATH += --dep-path . +VPATH += uClibc++ diff --git a/misc/uClibc++/libxx/uClib++/algorithm.cxx b/misc/uClibc++/libxx/uClib++/algorithm.cxx new file mode 100644 index 0000000000..e21b14e3f4 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/algorithm.cxx @@ -0,0 +1,30 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + + +#include + + +namespace std{ + + + +} + + diff --git a/misc/uClibc++/libxx/uClib++/associative_base.cxx b/misc/uClibc++/libxx/uClib++/associative_base.cxx new file mode 100644 index 0000000000..cc2d20e549 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/associative_base.cxx @@ -0,0 +1,26 @@ +/* Copyright (C) 2007 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + +#include + +namespace std{ + + + +} diff --git a/misc/uClibc++/libxx/uClib++/bitset.cxx b/misc/uClibc++/libxx/uClib++/bitset.cxx new file mode 100644 index 0000000000..f1ece31f9f --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/bitset.cxx @@ -0,0 +1,26 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + +#include + +namespace std{ + + + +} diff --git a/misc/uClibc++/libxx/uClib++/char_traits.cxx b/misc/uClibc++/libxx/uClib++/char_traits.cxx new file mode 100644 index 0000000000..2a91bd97f2 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/char_traits.cxx @@ -0,0 +1,69 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + +#define __UCLIBCXX_COMPILE_CHAR_TRAITS__ 1 + + +#include +#include + +namespace std{ + +_UCXXEXPORT const char_traits::char_type* char_traits::find(const char_type* s, int n, const char_type& a){ + for(int i=0; i < n; i++){ + if(eq(s[i], a)){ + return (s+i); + } + } + return 0; +} + +_UCXXEXPORT bool char_traits::eq(const char_type& c1, const char_type& c2){ + if(strncmp(&c1, &c2, 1) == 0){ + return true; + } + return false; +} + +_UCXXEXPORT char_traits::char_type char_traits::to_char_type(const int_type & i){ + if(i > 0 && i <= 255){ + return (char)(unsigned char)i; + } + + //Out of range + return 0; +} + + + +#ifdef __UCLIBCXX_HAS_WCHAR__ + +_UCXXEXPORT const char_traits::char_type* char_traits::find(const char_type* s, int n, const char_type& a){ + for(int i=0; i < n; i++){ + if(eq(s[i], a)){ + return (s+i); + } + } + return 0; +} + +#endif + +} diff --git a/misc/uClibc++/libxx/uClib++/complex.cxx b/misc/uClibc++/libxx/uClib++/complex.cxx new file mode 100644 index 0000000000..6b895a888a --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/complex.cxx @@ -0,0 +1,28 @@ +/* Copyright (C) 2005 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + + +namespace std{ + + + template class _UCXXEXPORT complex; + + +} diff --git a/misc/uClibc++/libxx/uClib++/del_op.cxx b/misc/uClibc++/libxx/uClib++/del_op.cxx new file mode 100644 index 0000000000..f5a36957df --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/del_op.cxx @@ -0,0 +1,26 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +_UCXXEXPORT void operator delete(void* ptr) throw(){ + free(ptr); +} diff --git a/misc/uClibc++/libxx/uClib++/del_opnt.cxx b/misc/uClibc++/libxx/uClib++/del_opnt.cxx new file mode 100644 index 0000000000..96cb03baac --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/del_opnt.cxx @@ -0,0 +1,28 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#ifndef NO_NOTHROW +_UCXXEXPORT void operator delete(void* ptr, const std::nothrow_t& ) throw() { + free(ptr); +} +#endif diff --git a/misc/uClibc++/libxx/uClib++/del_opv.cxx b/misc/uClibc++/libxx/uClib++/del_opv.cxx new file mode 100644 index 0000000000..028e86f36b --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/del_opv.cxx @@ -0,0 +1,26 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +_UCXXEXPORT void operator delete[](void * ptr) throw(){ + free(ptr); +} diff --git a/misc/uClibc++/libxx/uClib++/del_opvnt.cxx b/misc/uClibc++/libxx/uClib++/del_opvnt.cxx new file mode 100644 index 0000000000..f2a2a361c3 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/del_opvnt.cxx @@ -0,0 +1,28 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#ifndef NO_NOTHROW +_UCXXEXPORT void operator delete[](void* ptr, const std::nothrow_t& ) throw(){ + free(ptr); +} +#endif diff --git a/misc/uClibc++/libxx/uClib++/deque.cxx b/misc/uClibc++/libxx/uClib++/deque.cxx new file mode 100644 index 0000000000..c5155808bb --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/deque.cxx @@ -0,0 +1,42 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + +#include + + +namespace std{ + + + + + + + + + + + + + + +} + + + + diff --git a/misc/uClibc++/libxx/uClib++/eh_alloc.cxx b/misc/uClibc++/libxx/uClib++/eh_alloc.cxx new file mode 100644 index 0000000000..5098196d85 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/eh_alloc.cxx @@ -0,0 +1,61 @@ +/* Copyright (C) 2006 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation, version 2.1 + of the License. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +//This is a system-specific header which does all of the error-handling management +#include + +namespace __cxxabiv1{ + +extern "C" void * __cxa_allocate_exception(std::size_t thrown_size) throw(){ + void *retval; + //The sizeof crap is required by Itanium ABI because we need to provide space for + //accounting information which is implementaion (gcc) specified + retval = malloc (thrown_size + sizeof(__cxa_exception)); + if (0 == retval){ + std::terminate(); + } + memset (retval, 0, sizeof(__cxa_exception)); + return (void *)((unsigned char *)retval + sizeof(__cxa_exception)); +} + +extern "C" void __cxa_free_exception(void *vptr) throw(){ + free( (char *)(vptr) - sizeof(__cxa_exception) ); +} + + +extern "C" __cxa_dependent_exception * __cxa_allocate_dependent_exception() throw(){ + __cxa_dependent_exception *retval; + //The sizeof crap is required by Itanium ABI because we need to provide space for + //accounting information which is implementaion (gcc) specified + retval = static_cast<__cxa_dependent_exception*>(malloc (sizeof(__cxa_dependent_exception))); + if (0 == retval){ + std::terminate(); + } + memset (retval, 0, sizeof(__cxa_dependent_exception)); + return retval; +} + +extern "C" void __cxa_free_dependent_exception(__cxa_dependent_exception *vptr) throw(){ + free( (char *)(vptr) ); +} +} diff --git a/misc/uClibc++/libxx/uClib++/eh_globals.cxx b/misc/uClibc++/libxx/uClib++/eh_globals.cxx new file mode 100644 index 0000000000..38d4583e6a --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/eh_globals.cxx @@ -0,0 +1,42 @@ +/* Copyright (C) 2006 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation, version 2.1 + of the License. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +//This is a system-specific header which does all of the error-handling management +#include + +//The following functionality is derived from reading of the GNU libstdc++ code and making it...simple + + +namespace __cxxabiv1{ + +static __UCLIBCXX_TLS __cxa_eh_globals eh_globals; + +extern "C" __cxa_eh_globals* __cxa_get_globals() throw(){ + return &eh_globals; +} + +extern "C" __cxa_eh_globals* __cxa_get_globals_fast() throw(){ + return &eh_globals; +} + +} diff --git a/misc/uClibc++/libxx/uClib++/exception.cxx b/misc/uClibc++/libxx/uClib++/exception.cxx new file mode 100644 index 0000000000..82021ddb63 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/exception.cxx @@ -0,0 +1,52 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + +#include + +//We can't do this yet because gcc is too stupid to be able to handle +//different implementations of exception class. + +#undef __UCLIBCXX_EXCEPTION_SUPPORT__ + +#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ + +namespace std{ + _UCXXEXPORT static char * __std_exception_what_value = "exception"; + + //We are providing our own versions to be sneaky + + + _UCXXEXPORT exception::~exception() throw(){ + //Empty function + } + + _UCXXEXPORT const char* exception::what() const throw(){ + return __std_exception_what_value; + } + + _UCXXEXPORT bad_exception::~bad_exception() throw(){ + + } + + +} + + +#endif diff --git a/misc/uClibc++/libxx/uClib++/fstream.cxx b/misc/uClibc++/libxx/uClib++/fstream.cxx new file mode 100644 index 0000000000..535fe9a524 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/fstream.cxx @@ -0,0 +1,174 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#define __UCLIBCXX_COMPILE_FSTREAM__ 1 + +#include + +namespace std{ + +#ifdef __UCLIBCXX_EXPAND_FSTREAM_CHAR__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT filebuf::basic_filebuf(); + template _UCXXEXPORT filebuf::~basic_filebuf(); + +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT filebuf::int_type filebuf::pbackfail(filebuf::int_type c); + template _UCXXEXPORT filebuf * filebuf::open(const char* s, ios_base::openmode mode); + template _UCXXEXPORT filebuf * filebuf::close(); + template _UCXXEXPORT filebuf::int_type filebuf::overflow(filebuf::int_type); + template _UCXXEXPORT filebuf::int_type filebuf::underflow (); + template _UCXXEXPORT streamsize filebuf::xsputn(const char* s, streamsize n); + + template _UCXXEXPORT basic_streambuf >* + filebuf::setbuf(char * s, streamsize n); + + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT basic_ofstream >::basic_ofstream(); + template _UCXXEXPORT basic_ofstream >::basic_ofstream(const char* s, ios_base::openmode mode); + template _UCXXEXPORT basic_ofstream >::~basic_ofstream(); + + template _UCXXEXPORT basic_ifstream >::basic_ifstream(); + template _UCXXEXPORT basic_ifstream >::basic_ifstream(const char* s, ios_base::openmode mode); + template _UCXXEXPORT basic_ifstream >::~basic_ifstream(); + +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + +#endif + + + +#ifdef __UCLIBCXX_HAS_WCHAR__ + +template <> _UCXXEXPORT basic_filebuf >::int_type + basic_filebuf >::overflow(int_type c) +{ + typedef basic_streambuf > wstreambuf; + typedef char_traits wtraits; + + if(is_open() == false){ + //Can't do much + return wtraits::eof(); + } + + mbstate_t ps = { 0 }; + char out_array[8]; + size_t out_size; + + + if( wstreambuf::pbase() != 0 ){ + + //Write all possible character from the existing array first + size_t chars_written = 0; + while(wstreambuf::pbase() && (wstreambuf::pbase() + chars_written !=wstreambuf::pptr()) ){ + out_size = wcrtomb(out_array, wstreambuf::pbase()[chars_written], &ps); + if(out_size == (size_t)(-1) || fwrite(out_array, out_size, 1, fp) == 0){ + break; + } + ++chars_written; + } + + if( wstreambuf::pbase() + chars_written == wstreambuf::pptr() ){ + wstreambuf::pbump(-chars_written); + }else{ + //Shuffle data back into order + size_t chars_left = wstreambuf::pptr() - wstreambuf::pbase() - chars_written; + for(size_t i = 0; i < chars_left; ++i){ + wstreambuf::pbase()[i] = (wstreambuf::pptr() - chars_written)[i]; + } + return wtraits::eof(); + } + } + + if( !wtraits::eq_int_type(c, wtraits::eof()) ){ + out_size = wcrtomb(out_array, c, &ps); + if(out_size == (size_t)(-1) || fwrite(out_array, out_size, 1, fp) == 0){ + return wtraits::eof(); + } + return c; + } + + return wtraits::not_eof(c); +} + + +template <> _UCXXEXPORT basic_filebuf >::int_type + basic_filebuf >::underflow() +{ + /*Some variables used internally: + Buffer pointers: + + charT * mgbeg; + charT * mgnext; + charT * mgend; + + eback() returns mgbeg + gptr() returns mgnext + egptr() returns mgend + + gbump(int n) mgnext+=n + */ + + typedef char_traits traits; + typedef basic_streambuf wstreambuf; + + + if(wstreambuf::eback() == wstreambuf::gptr() && 0 != wstreambuf::eback()){ //Buffer is full + return traits::to_int_type(*wstreambuf::gptr()); + } + + size_t in_size; + + wchar_t c = 0; + wint_t wi = 0; + in_size = 0; + + wi = fgetwc(fp); + if(WEOF == wi){ + fprintf(stderr, "WEOF returned by fgetwc\n"); + return traits::eof(); + } + + c = traits::to_char_type(wi); + + if(wstreambuf::eback() == 0){ + return traits::to_int_type(c); + } + + for(wchar_t * i = wstreambuf::gptr(); i < wstreambuf::egptr(); ++i){ + *(i-1) = *i; + } + + *(wstreambuf::egptr()-1) = c; + + wstreambuf::mgnext -= 1; + + return traits::to_int_type(*wstreambuf::gptr()); +} + +#endif // __UCLIBCXX_HAS_WCHAR__ + + +} diff --git a/misc/uClibc++/libxx/uClib++/func_exception.cxx b/misc/uClibc++/libxx/uClib++/func_exception.cxx new file mode 100644 index 0000000000..fab095f3de --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/func_exception.cxx @@ -0,0 +1,87 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include + +namespace std{ + +#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ + +_UCXXEXPORT void __throw_bad_alloc(){ + throw bad_alloc(); +} + +_UCXXEXPORT void __throw_out_of_range( const char * message){ + if(message == 0){ + throw out_of_range(); + } + throw out_of_range(message); +} + +_UCXXEXPORT void __throw_overflow_error( const char * message){ + if(message == 0){ + throw overflow_error(); + } + throw overflow_error(message); +} + +_UCXXEXPORT void __throw_length_error(const char * message){ + if(message == 0){ + throw length_error(); + } + throw length_error(message); +} + +_UCXXEXPORT void __throw_invalid_argument(const char * message){ + if(message == 0){ + throw invalid_argument(); + } + throw invalid_argument(message); +} + +#else + +_UCXXEXPORT void __throw_bad_alloc(){ + abort(); +} + +_UCXXEXPORT void __throw_out_of_range( const char * ){ + abort(); +} + +_UCXXEXPORT void __throw_overflow_error( const char * ){ + abort(); +} + +_UCXXEXPORT void __throw_length_error(const char * ){ + abort(); +} + +_UCXXEXPORT void __throw_invalid_argument(const char *){ + abort(); +} + +#endif + + + +} diff --git a/misc/uClibc++/libxx/uClib++/iomanip.cxx b/misc/uClibc++/libxx/uClib++/iomanip.cxx new file mode 100644 index 0000000000..c5e60ccea1 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/iomanip.cxx @@ -0,0 +1,29 @@ +/* Copyright (C) 2005 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +namespace std{ + + + + +} + + diff --git a/misc/uClibc++/libxx/uClib++/ios.cxx b/misc/uClibc++/libxx/uClib++/ios.cxx new file mode 100644 index 0000000000..3b85d5be2c --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/ios.cxx @@ -0,0 +1,189 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#define __UCLIBCXX_COMPILE_IOS__ 1 + +#include +#include +#include +#include +#include + +namespace std{ + + +#ifdef __UCLIBCXX_SUPPORT_CDIR__ + _UCXXLOCAL int ios_base::Init::init_cnt = 0; //Needed to ensure the static value is created + +//Create buffers first +#ifdef __UCLIBCXX_SUPPORT_COUT__ + _UCXXEXPORT filebuf _cout_filebuf; +#endif +#ifdef __UCLIBCXX_SUPPORT_CIN__ + _UCXXEXPORT filebuf _cin_filebuf; +#endif +#ifdef __UCLIBCXX_SUPPORT_CERR__ + _UCXXEXPORT filebuf _cerr_filebuf; +#endif +#ifdef __UCLIBCXX_SUPPORT_CLOG__ + _UCXXEXPORT filebuf _clog_filebuf; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCOUT__ + _UCXXEXPORT wfilebuf _wcout_filebuf; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCIN__ + _UCXXEXPORT wfilebuf _wcin_filebuf; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCERR__ + _UCXXEXPORT wfilebuf _wcerr_filebuf; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCLOG__ + _UCXXEXPORT wfilebuf _wclog_filebuf; +#endif + +//Then create streams +#ifdef __UCLIBCXX_SUPPORT_COUT__ + _UCXXEXPORT ostream cout(&_cout_filebuf); +#endif +#ifdef __UCLIBCXX_SUPPORT_CIN__ + _UCXXEXPORT istream cin(&_cin_filebuf); +#endif +#ifdef __UCLIBCXX_SUPPORT_CERR__ + _UCXXEXPORT ostream cerr(&_cerr_filebuf); +#endif +#ifdef __UCLIBCXX_SUPPORT_CLOG__ + _UCXXEXPORT ostream clog(&_clog_filebuf); +#endif +#ifdef __UCLIBCXX_SUPPORT_WCOUT__ + _UCXXEXPORT wostream wcout(&_wcout_filebuf); +#endif +#ifdef __UCLIBCXX_SUPPORT_WCIN__ + _UCXXEXPORT wistream wcin(&_wcin_filebuf); +#endif +#ifdef __UCLIBCXX_SUPPORT_WCERR__ + _UCXXEXPORT wostream wcerr(&_wcerr_filebuf); +#endif +#ifdef __UCLIBCXX_SUPPORT_WCLOG__ + _UCXXEXPORT wostream wclog(&_wclog_filebuf); +#endif + + + _UCXXEXPORT ios_base::Init::Init(){ + if(init_cnt == 0){ //Need to construct cout et al +#ifdef __UCLIBCXX_SUPPORT_COUT__ + _cout_filebuf.fp = stdout; + _cout_filebuf.openedFor = ios_base::out; +#endif +#ifdef __UCLIBCXX_SUPPORT_CERR__ + _cerr_filebuf.fp = stderr; + _cerr_filebuf.openedFor = ios_base::out; + cerr.mformat |= ios_base::unitbuf; +#endif +#ifdef __UCLIBCXX_SUPPORT_CLOG__ + _clog_filebuf.fp = stderr; + _clog_filebuf.openedFor = ios_base::out; +#endif +#ifdef __UCLIBCXX_SUPPORT_CIN__ + _cin_filebuf.fp = stdin; + _cin_filebuf.openedFor = ios_base::in; + +#ifdef __UCLIBCXX_SUPPORT_COUT__ + cin.tie(&cout); +#endif + +#endif +#ifdef __UCLIBCXX_SUPPORT_WCOUT__ + _wcout_filebuf.fp = stdout; + _wcout_filebuf.openedFor = ios_base::out; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCERR__ + _wcerr_filebuf.fp = stderr; + _wcerr_filebuf.openedFor = ios_base::out; + wcerr.mformat |= ios_base::unitbuf; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCLOG__ + _wclog_filebuf.fp = stderr; + _wclog_filebuf.openedFor = ios_base::out; +#endif +#ifdef __UCLIBCXX_SUPPORT_WCIN__ + _wcin_filebuf.fp = stdin; + _wcin_filebuf.openedFor = ios_base::in; + +#ifdef __UCLIBCXX_SUPPORT_WCOUT__ + wcin.tie(&wcout); +#endif + +#endif + } + init_cnt++; + } + + _UCXXEXPORT ios_base::Init::~Init(){ + --init_cnt; + if(init_cnt==0){ + + } + } +#endif + + +#ifdef __UCLIBCXX_EXPAND_IOS_CHAR__ + + template _UCXXEXPORT void basic_ios >::clear(iostate state); + template _UCXXEXPORT void basic_ios >::setstate(iostate state); + +#endif + + + _UCXXEXPORT ios_base::fmtflags ios_base::flags(fmtflags fmtfl){ + fmtflags temp = mformat; + mformat = fmtfl; + return temp; + } + + _UCXXEXPORT ios_base::fmtflags ios_base::setf(fmtflags fmtfl){ + return flags(flags() | fmtfl); + } + + _UCXXEXPORT ios_base::fmtflags ios_base::setf(fmtflags fmtfl, fmtflags mask ){ + return flags( (flags()& ~mask) | (fmtfl & mask)); + } + + _UCXXEXPORT streamsize ios_base::precision(streamsize prec){ + streamsize temp = mprecision; + mprecision = prec; + return temp; + } + + _UCXXEXPORT streamsize ios_base::width(streamsize wide){ + streamsize temp = mwidth; + mwidth = wide; + return temp; + } + + _UCXXEXPORT locale ios_base::imbue(const locale& loc){ + locale retval = mLocale; + mLocale = loc; + return retval; + } + +} + + + diff --git a/misc/uClibc++/libxx/uClib++/iostream.cxx b/misc/uClibc++/libxx/uClib++/iostream.cxx new file mode 100644 index 0000000000..7a190a2bf6 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/iostream.cxx @@ -0,0 +1,38 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#define __UCLIBCXX_COMPILE_IOSTREAM__ 1 + +#include + +namespace std{ + +#ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ +#ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ + + template _UCXXEXPORT basic_iostream >:: + basic_iostream(basic_streambuf >* sb); + template _UCXXEXPORT basic_iostream >::~basic_iostream(); + +#endif +#endif + +} + + diff --git a/misc/uClibc++/libxx/uClib++/istream.cxx b/misc/uClibc++/libxx/uClib++/istream.cxx new file mode 100644 index 0000000000..9e9613973f --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/istream.cxx @@ -0,0 +1,75 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + +#define __UCLIBCXX_COMPILE_ISTREAM__ 1 + +#include + + +namespace std{ + +#ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ + + template <> _UCXXEXPORT string _readToken >(istream & stream) + { + string temp; + char_traits::int_type c; + while(true){ + c = stream.rdbuf()->sgetc(); + if(c != char_traits::eof() && isspace(c) == false){ + stream.rdbuf()->sbumpc(); + temp.append(1, char_traits::to_char_type(c)); + }else{ + break; + } + } + if (temp.size() == 0) + stream.setstate(ios_base::eofbit|ios_base::failbit); + + return temp; + } + + template _UCXXEXPORT istream::int_type istream::get(); + template _UCXXEXPORT istream & istream::get(char &c); + + template _UCXXEXPORT istream & istream::operator>>(bool &n); + template _UCXXEXPORT istream & istream::operator>>(short &n); + template _UCXXEXPORT istream & istream::operator>>(unsigned short &n); + template _UCXXEXPORT istream & istream::operator>>(int &n); + template _UCXXEXPORT istream & istream::operator>>(unsigned int &n); + template _UCXXEXPORT istream & istream::operator>>(long unsigned &n); + template _UCXXEXPORT istream & istream::operator>>(long int &n); + template _UCXXEXPORT istream & istream::operator>>(void *& p); + template _UCXXEXPORT istream & operator>>(istream & is, char & c); + + +#ifdef __UCLIBCXX_HAS_FLOATS__ + template _UCXXEXPORT istream & istream::operator>>(float &f); + template _UCXXEXPORT istream & istream::operator>>(double &f); + template _UCXXEXPORT istream & istream::operator>>(long double &f); +#endif + + template _UCXXEXPORT void __skipws(basic_istream >& is); + +#endif + + +} + diff --git a/misc/uClibc++/libxx/uClib++/iterator.cxx b/misc/uClibc++/libxx/uClib++/iterator.cxx new file mode 100644 index 0000000000..2e21517a2f --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/iterator.cxx @@ -0,0 +1,28 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +namespace std{ + + + +} + + diff --git a/misc/uClibc++/libxx/uClib++/limits.cxx b/misc/uClibc++/libxx/uClib++/limits.cxx new file mode 100644 index 0000000000..0fd42d577e --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/limits.cxx @@ -0,0 +1,25 @@ +/* Copyright (C) 2006 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + +#include + +namespace std{ + + +} diff --git a/misc/uClibc++/libxx/uClib++/list.cxx b/misc/uClibc++/libxx/uClib++/list.cxx new file mode 100644 index 0000000000..cfc44e0797 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/list.cxx @@ -0,0 +1,29 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +namespace std{ + + + + +} + + diff --git a/misc/uClibc++/libxx/uClib++/locale.cxx b/misc/uClibc++/libxx/uClib++/locale.cxx new file mode 100644 index 0000000000..bc41792df1 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/locale.cxx @@ -0,0 +1,29 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include +#include +#include + +namespace std{ + +} + diff --git a/misc/uClibc++/libxx/uClib++/map.cxx b/misc/uClibc++/libxx/uClib++/map.cxx new file mode 100644 index 0000000000..06e56a0bbd --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/map.cxx @@ -0,0 +1,33 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + +#include + +namespace std{ + + + + + + + + + + +} diff --git a/misc/uClibc++/libxx/uClib++/new_handler.cxx b/misc/uClibc++/libxx/uClib++/new_handler.cxx new file mode 100644 index 0000000000..1d85ee3fad --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/new_handler.cxx @@ -0,0 +1,31 @@ +/* Copyright (C) 2005 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +const std::nothrow_t std::nothrow = { }; + +//Name selected to be compatable with g++ code +std::new_handler __new_handler; + +_UCXXEXPORT std::new_handler std::set_new_handler(std::new_handler new_p) throw(){ + std::new_handler retval = __new_handler; + __new_handler = new_p; + return retval; +} diff --git a/misc/uClibc++/libxx/uClib++/new_op.cxx b/misc/uClibc++/libxx/uClib++/new_op.cxx new file mode 100644 index 0000000000..764eb835cb --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/new_op.cxx @@ -0,0 +1,35 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +_UCXXEXPORT void* operator new(std::size_t numBytes) throw(std::bad_alloc){ + //C++ stardard 5.3.4.8 requires that a valid pointer be returned for + //a call to new(0). Thus: + if(numBytes == 0){ + numBytes = 1; + } + void * p = malloc(numBytes); + if(p == 0){ + std::__throw_bad_alloc(); + } + return p; +} diff --git a/misc/uClibc++/libxx/uClib++/new_opnt.cxx b/misc/uClibc++/libxx/uClib++/new_opnt.cxx new file mode 100644 index 0000000000..cffce610b0 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/new_opnt.cxx @@ -0,0 +1,28 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#ifndef NO_NOTHROW +_UCXXEXPORT void* operator new(std::size_t numBytes, const std::nothrow_t& ) throw(){ + return malloc(numBytes); +} +#endif diff --git a/misc/uClibc++/libxx/uClib++/new_opv.cxx b/misc/uClibc++/libxx/uClib++/new_opv.cxx new file mode 100644 index 0000000000..ef416e07b7 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/new_opv.cxx @@ -0,0 +1,35 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +_UCXXEXPORT void* operator new[](std::size_t numBytes) throw(std::bad_alloc){ + //C++ stardard 5.3.4.8 requires that a valid pointer be returned for + //a call to new(0). Thus: + if(numBytes == 0){ + numBytes = 1; + } + void * p = malloc(numBytes); + if(p == 0){ + std::__throw_bad_alloc(); + } + return p; +} diff --git a/misc/uClibc++/libxx/uClib++/new_opvnt.cxx b/misc/uClibc++/libxx/uClib++/new_opvnt.cxx new file mode 100644 index 0000000000..3ea592afb2 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/new_opvnt.cxx @@ -0,0 +1,28 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include +#include + +#ifndef NO_NOTHROW +_UCXXEXPORT void* operator new[](std::size_t numBytes, const std::nothrow_t& ) throw(){ + return malloc(numBytes); +} +#endif diff --git a/misc/uClibc++/libxx/uClib++/numeric.cxx b/misc/uClibc++/libxx/uClib++/numeric.cxx new file mode 100644 index 0000000000..eb93f2eb7c --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/numeric.cxx @@ -0,0 +1,27 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +namespace std{ + + +} + + diff --git a/misc/uClibc++/libxx/uClib++/ostream.cxx b/misc/uClibc++/libxx/uClib++/ostream.cxx new file mode 100644 index 0000000000..0973871b05 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/ostream.cxx @@ -0,0 +1,65 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#define __UCLIBCXX_COMPILE_OSTREAM__ 1 + +#include + +namespace std{ + + +#ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + template _UCXXEXPORT ostream::~basic_ostream(); +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT ostream & ostream::flush(); + + template _UCXXEXPORT ostream & ostream::operator<<(bool n); + template _UCXXEXPORT ostream & ostream::operator<<(short int n); + template _UCXXEXPORT ostream & ostream::operator<<(unsigned short int n); + template _UCXXEXPORT ostream & ostream::operator<<(int n); + template _UCXXEXPORT ostream & ostream::operator<<(unsigned int n); + template _UCXXEXPORT ostream & ostream::operator<<(long n); + template _UCXXEXPORT ostream & ostream::operator<<(unsigned long n); + template _UCXXEXPORT ostream & ostream::operator<<(float f); + template _UCXXEXPORT ostream & ostream::operator<<(double f); + template _UCXXEXPORT ostream & ostream::operator<<(long double f); + template _UCXXEXPORT ostream & ostream::operator<<(void* p); + template _UCXXEXPORT ostream & ostream::operator<<(basic_streambuf >* sb); + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT ostream::sentry::sentry(ostream & os); + template _UCXXEXPORT ostream::sentry::~sentry(); + +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT ostream & endl(ostream & os); + template _UCXXEXPORT ostream & flush(ostream & os); + template _UCXXEXPORT ostream & operator<<(ostream & out, char c); + template _UCXXEXPORT ostream & operator<<(ostream & out, const char* c); + template _UCXXEXPORT ostream & operator<<(ostream & out, unsigned char c); + template _UCXXEXPORT ostream & operator<<(ostream & out, const unsigned char* c); + +#endif + + +} diff --git a/misc/uClibc++/libxx/uClib++/queue.cxx b/misc/uClibc++/libxx/uClib++/queue.cxx new file mode 100644 index 0000000000..356efeb139 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/queue.cxx @@ -0,0 +1,27 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + + +namespace std{ + + + + +} diff --git a/misc/uClibc++/libxx/uClib++/set.cxx b/misc/uClibc++/libxx/uClib++/set.cxx new file mode 100644 index 0000000000..61ec56a717 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/set.cxx @@ -0,0 +1,33 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + +#include + +namespace std{ + + + + + + + + + + +} diff --git a/misc/uClibc++/libxx/uClib++/sstream.cxx b/misc/uClibc++/libxx/uClib++/sstream.cxx new file mode 100644 index 0000000000..e712b67640 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/sstream.cxx @@ -0,0 +1,59 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#define __UCLIBCXX_COMPILE_SSTREAM__ 1 + +#include + +namespace std{ + +#ifdef __UCLIBCXX_EXPAND_SSTREAM_CHAR__ + + typedef char_traits tr_ch; + typedef basic_stringbuf > char_stringbuf; + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT char_stringbuf::basic_stringbuf(ios_base::openmode which); + template _UCXXEXPORT char_stringbuf::~basic_stringbuf(); + +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT basic_string, allocator > char_stringbuf::str() const; + template _UCXXEXPORT char_stringbuf::int_type char_stringbuf::pbackfail(char_stringbuf::int_type c); + template _UCXXEXPORT char_stringbuf::int_type char_stringbuf::overflow(char_stringbuf::int_type c); + template _UCXXEXPORT char_stringbuf::pos_type + char_stringbuf::seekoff(char_stringbuf::off_type, ios_base::seekdir, ios_base::openmode); + template _UCXXEXPORT char_stringbuf::int_type char_stringbuf::underflow (); + template _UCXXEXPORT streamsize char_stringbuf::xsputn(const char* s, streamsize n); + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT basic_stringstream >::basic_stringstream(ios_base::openmode which); + template _UCXXEXPORT basic_istringstream >::~basic_istringstream(); + template _UCXXEXPORT basic_ostringstream >::~basic_ostringstream(); + template _UCXXEXPORT basic_stringstream >::~basic_stringstream(); + +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + +#endif + +} + + diff --git a/misc/uClibc++/libxx/uClib++/stack.cxx b/misc/uClibc++/libxx/uClib++/stack.cxx new file mode 100644 index 0000000000..53a21bba51 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/stack.cxx @@ -0,0 +1,27 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + + +namespace std{ + + + + +} diff --git a/misc/uClibc++/libxx/uClib++/stdexcept.cxx b/misc/uClibc++/libxx/uClib++/stdexcept.cxx new file mode 100644 index 0000000000..90dccc7a49 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/stdexcept.cxx @@ -0,0 +1,63 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include +#include + +#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ + +namespace std{ + + _UCXXEXPORT logic_error::logic_error() throw() : mstring(){ + + } + + _UCXXEXPORT logic_error::logic_error(const string& what_arg) : mstring(what_arg){ + + } + + _UCXXEXPORT const char * logic_error::what() const throw(){ + return mstring.c_str(); + } + + + _UCXXEXPORT out_of_range::out_of_range() : logic_error(){ + + } + + _UCXXEXPORT out_of_range::out_of_range(const string & what_arg) : logic_error(what_arg) { + + } + + _UCXXEXPORT runtime_error::runtime_error() : mstring(){ + + } + + _UCXXEXPORT runtime_error::runtime_error(const string& what_arg) : mstring(what_arg){ + + } + + _UCXXEXPORT const char * runtime_error::what() const throw(){ + return mstring.c_str(); + } + +} + +#endif + diff --git a/misc/uClibc++/libxx/uClib++/streambuf.cxx b/misc/uClibc++/libxx/uClib++/streambuf.cxx new file mode 100644 index 0000000000..5417324595 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/streambuf.cxx @@ -0,0 +1,49 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#define __UCLIBCXX_COMPILE_STREAMBUF__ 1 + +#include + +namespace std{ + +#ifdef __UCLIBCXX_EXPAND_STREAMBUF_CHAR__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT streambuf::basic_streambuf(); + template _UCXXEXPORT streambuf::~basic_streambuf(); + +#endif + + template _UCXXEXPORT locale streambuf::pubimbue(const locale &loc); + template _UCXXEXPORT streamsize streambuf::in_avail(); + template _UCXXEXPORT streambuf::int_type streambuf::sbumpc(); + template _UCXXEXPORT streambuf::int_type streambuf::snextc(); + template _UCXXEXPORT streambuf::int_type streambuf::sgetc(); + template _UCXXEXPORT streambuf::int_type streambuf::sputbackc(char_type c); + template _UCXXEXPORT streambuf::int_type streambuf::sungetc(); + template _UCXXEXPORT streambuf::int_type streambuf::sputc(char_type c); + +#endif + + +} + + diff --git a/misc/uClibc++/libxx/uClib++/string.cxx b/misc/uClibc++/libxx/uClib++/string.cxx new file mode 100644 index 0000000000..1edf69b5d9 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/string.cxx @@ -0,0 +1,112 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#define __UCLIBCXX_COMPILE_STRING__ 1 + +#include +#include +#include +#include +#include +#include + +namespace std{ + +#ifdef __UCLIBCXX_EXPAND_STRING_CHAR__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT string::basic_string(const allocator &); + template _UCXXEXPORT string::basic_string(size_type n, char c, const allocator & ); + template _UCXXEXPORT string::basic_string(const char* s, const allocator& al); + template _UCXXEXPORT string::basic_string(const basic_string& str, size_type pos, size_type n, const allocator& al); + template _UCXXEXPORT string::~basic_string(); + +#endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT string & string::append(const char * s, size_type n); + + template _UCXXEXPORT string::size_type string::find(const string & str, size_type pos) const; + template _UCXXEXPORT string::size_type string::find(const char* s, size_type pos) const; + template _UCXXEXPORT string::size_type string::find (char c, size_type pos) const; + template _UCXXEXPORT string::size_type string::rfind(const string & str, size_type pos) const; + template _UCXXEXPORT string::size_type string::rfind(char c, size_type pos) const; + template _UCXXEXPORT string::size_type string::rfind(const char* s, size_type pos) const; + + template _UCXXEXPORT string::size_type string::find_first_of(const string &, size_type) const; + template _UCXXEXPORT string::size_type string::find_first_of(const char *, size_type pos, size_type n) const; + template _UCXXEXPORT string::size_type string::find_first_of(const char*, size_type pos) const; + template _UCXXEXPORT string::size_type string::find_first_of(char c, size_type pos) const; + + template _UCXXEXPORT string::size_type string::find_last_of (const string & , size_type pos) const; + template _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos, size_type n) const; + template _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos) const; + template _UCXXEXPORT string::size_type string::find_last_of (char c, size_type pos) const; + + template _UCXXEXPORT string::size_type string::find_first_not_of(const string &, size_type) const; + template _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type, size_type) const; + template _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type) const; + template _UCXXEXPORT string::size_type string::find_first_not_of(char c, size_type) const; + + template _UCXXEXPORT int string::compare(const string & str) const; +// template _UCXXEXPORT int string::compare(size_type pos1, size_type n1, const string & str) const; + template _UCXXEXPORT int string::compare( + size_type pos1, size_type n1, const string & str, size_type pos2, size_type n2) const; + + template _UCXXEXPORT string string::substr(size_type pos, size_type n) const; + + template _UCXXEXPORT string & string::operator=(const string & str); + template _UCXXEXPORT string & string::operator=(const char * s); + + template _UCXXEXPORT bool operator==(const string & lhs, const string & rhs); + template _UCXXEXPORT bool operator==(const char * lhs, const string & rhs); + template _UCXXEXPORT bool operator==(const string & lhs, const char * rhs); + + template _UCXXEXPORT bool operator!=(const string & lhs, const string & rhs); + template _UCXXEXPORT bool operator!=(const char * lhs, const string & rhs); + template _UCXXEXPORT bool operator!=(const string & lhs, const char * rhs); + + template _UCXXEXPORT string operator+(const string & lhs, const char* rhs); + template _UCXXEXPORT string operator+(const char* lhs, const string & rhs); + template _UCXXEXPORT string operator+(const string & lhs, const string & rhs); + + template _UCXXEXPORT bool operator> (const string & lhs, const string & rhs); + template _UCXXEXPORT bool operator< (const string & lhs, const string & rhs); + + +//Functions dependent upon OSTREAM +#ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ + +template _UCXXEXPORT ostream & operator<<(ostream & os, const string & str); + +#endif + + +//Functions dependent upon ISTREAM +#ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ + +template _UCXXEXPORT istream & operator>>(istream & is, string & str); + + +#endif + + +#endif + +} diff --git a/misc/uClibc++/libxx/uClib++/support.cxx b/misc/uClibc++/libxx/uClib++/support.cxx new file mode 100644 index 0000000000..875459442e --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/support.cxx @@ -0,0 +1,53 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +extern "C" void *__cxa_allocate_exception(size_t thrown_size){ + void * retval; + +// The amount of data needed is the size of the object *PLUS* +// the size of the header. The header is of struct __cxa_exception +// The address needs to be adjusted because the pointer we return +// should not point to the start of the memory, but to the point +// where the object being thrown actually starts +// + retval = malloc(thrown_size + sizeof(__cxa_exception)); + +// Check to see that we actuall allocated memory + if(retval == 0){ + std::terminate(); + } + + //Need to do a typecast to char* otherwize we are doing math with + //a void* which makes the compiler cranky (Like me) + return ((char *)retval + sizeof(__cxa_exception)); +} + +extern "C" void __cxa_free_exception(void *thrown_exception){ + + + +} + +extern "C" void __cxa_throw (void *thrown_exception, void *info,void (*dest) (void *) ){ + + +} + diff --git a/misc/uClibc++/libxx/uClib++/typeinfo.cxx b/misc/uClibc++/libxx/uClib++/typeinfo.cxx new file mode 100644 index 0000000000..b8ea301977 --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/typeinfo.cxx @@ -0,0 +1,34 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +namespace std{ + + _UCXXEXPORT bad_cast::~bad_cast() throw(){ + + } + + _UCXXEXPORT bad_typeid::~bad_typeid() throw(){ + + } + +} + + diff --git a/misc/uClibc++/libxx/uClib++/utility.cxx b/misc/uClibc++/libxx/uClib++/utility.cxx new file mode 100644 index 0000000000..b2f8995d7f --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/utility.cxx @@ -0,0 +1,30 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +*/ + + +#include + + +namespace std{ + + + +} + + diff --git a/misc/uClibc++/libxx/uClib++/valarray.cxx b/misc/uClibc++/libxx/uClib++/valarray.cxx new file mode 100644 index 0000000000..e4bd504cfa --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/valarray.cxx @@ -0,0 +1,29 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include + +namespace std{ + + + + +} + + diff --git a/misc/uClibc++/libxx/uClib++/vector.cxx b/misc/uClibc++/libxx/uClib++/vector.cxx new file mode 100644 index 0000000000..5ee0de188e --- /dev/null +++ b/misc/uClibc++/libxx/uClib++/vector.cxx @@ -0,0 +1,83 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + + This file is part of the uClibc++ Library. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#define __UCLIBCXX_COMPILE_VECTOR__ 1 + + +#include + +namespace std{ + + +#ifdef __UCLIBCXX_EXPAND_VECTOR_BASIC__ + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT vector >::vector(const allocator& al); + template _UCXXEXPORT vector >::vector(size_type n, const char & value, const allocator & al); + + template _UCXXEXPORT vector >::~vector(); + template _UCXXEXPORT vector >::~vector(); + +#endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::reserve(size_type n); + + template _UCXXEXPORT void vector >::resize(size_type sz, const char & c); + template _UCXXEXPORT void vector >::resize(size_type sz, const unsigned char & c); + template _UCXXEXPORT void vector >::resize(size_type sz, const short & c); + template _UCXXEXPORT void vector > + ::resize(size_type sz, const unsigned short int & c); + template _UCXXEXPORT void vector >::resize(size_type sz, const int & c); + template _UCXXEXPORT void vector >::resize(size_type sz, const unsigned int & c); + template _UCXXEXPORT void vector >::resize(size_type sz, const long int & c); + template _UCXXEXPORT void vector >:: + resize(size_type sz, const unsigned long int & c); + template _UCXXEXPORT void vector >::resize(size_type sz, const float & c); + template _UCXXEXPORT void vector >::resize(size_type sz, const double & c); + template _UCXXEXPORT void vector >::resize(size_type sz, const bool & c); + +#elif defined __UCLIBCXX_EXPAND_STRING_CHAR__ + + +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + template _UCXXEXPORT vector >::vector(const allocator& al); + template _UCXXEXPORT vector >::vector(size_type n, const char & value, const allocator & al); + template _UCXXEXPORT vector >::~vector(); +#endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template _UCXXEXPORT void vector >::reserve(size_type n); + template _UCXXEXPORT void vector >::resize(size_type sz, const char & c); + +#endif + + + + +} diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile index 4122931ac9..67f8531d71 100644 --- a/nuttx/libxx/Makefile +++ b/nuttx/libxx/Makefile @@ -35,20 +35,37 @@ -include $(TOPDIR)/Make.defs -ASRCS = -AOBJS = $(ASRCS:.S=$(OBJEXT)) -CSRCS = -COBJS = $(CSRCS:.c=$(OBJEXT)) -CXXSRCS = libxx_cxapurevirtual.cxx libxx_delete.cxx libxx_deletea.cxx \ - libxx_eabi_atexit.cxx libxx_new.cxx libxx_newa.cxx -CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) +# Sources -SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) -OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) +ASRCS = +CSRCS = +CXXSRCS = libxx_cxapurevirtual.cxx libxx_delete.cxx libxx_deletea.cxx +CXXSRCS += libxx_eabi_atexit.cxx libxx_new.cxx libxx_newa.cxx -BIN = liblibxx$(LIBEXT) +# Paths -all: $(BIN) +DEPPATH = --dep-path . +VPATH = . + +# Include the uClibc++ Make.defs file (if it is present). If is present, +# the uClibc++/Make.defs file will add its files to the source file list, +# add its DEPPATH info, and will add the appropriate paths to the VPATH +# variable + +-include/uClibc++/Make.defs + +# Object Files + +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) +CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) +OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) + +BIN = liblibxx$(LIBEXT) + +all: $(BIN) $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -65,7 +82,7 @@ $(BIN): $(OBJS) done ; ) .depend: Makefile $(SRCS) - @$(MKDEP) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(DEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend From 05a1bb2abf4cf172bb6ddc6851566835f9c00208 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 31 Oct 2012 20:13:28 +0000 Subject: [PATCH 053/206] Add apps/examples/cxxtest from Qiang Yu git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5284 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 2 + apps/examples/Kconfig | 1 + apps/examples/Make.defs | 4 + apps/examples/Makefile | 16 +- apps/examples/README.txt | 19 +++ apps/examples/cxxtest/Kconfig | 14 ++ apps/examples/cxxtest/Makefile | 122 ++++++++++++++ apps/examples/cxxtest/cxxtext_main.cxx | 219 +++++++++++++++++++++++++ misc/uClibc++/README.txt | 85 ++++++++++ misc/uClibc++/install.sh | 4 +- 10 files changed, 476 insertions(+), 10 deletions(-) create mode 100644 apps/examples/cxxtest/Kconfig create mode 100644 apps/examples/cxxtest/Makefile create mode 100644 apps/examples/cxxtest/cxxtext_main.cxx create mode 100755 misc/uClibc++/README.txt diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index db56d66819..0b8b3cde74 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -395,3 +395,5 @@ * nsnlib/nsh_codeccmd.c: NSH commands to use the CODEC library. Contributed by Darcy Gong. * apps/examples/wgetjson: Test example contributed by Darcy Gong + * apps/examples/cxxtest: A test for the uClibc++ library provided by + Qiang Yu and the RGMP team. diff --git a/apps/examples/Kconfig b/apps/examples/Kconfig index 7f0c8e3658..f7a923b944 100644 --- a/apps/examples/Kconfig +++ b/apps/examples/Kconfig @@ -8,6 +8,7 @@ source "$APPSDIR/examples/buttons/Kconfig" source "$APPSDIR/examples/can/Kconfig" source "$APPSDIR/examples/cdcacm/Kconfig" source "$APPSDIR/examples/composite/Kconfig" +source "$APPSDIR/examples/cxxtest/Kconfig" source "$APPSDIR/examples/dhcpd/Kconfig" source "$APPSDIR/examples/elf/Kconfig" source "$APPSDIR/examples/ftpc/Kconfig" diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index 67c1685fe7..52949ae915 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -54,6 +54,10 @@ ifeq ($(CONFIG_EXAMPLES_COMPOSITE),y) CONFIGURED_APPS += examples/composite endif +ifeq ($(CONFIG_EXAMPLES_CXXTEST,y) +CONFIGURED_APPS += examples/cxxtest +endif + ifeq ($(CONFIG_EXAMPLES_DHCPD),y) CONFIGURED_APPS += examples/dhcpd endif diff --git a/apps/examples/Makefile b/apps/examples/Makefile index d8a2c96646..0eaffbc15e 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -37,12 +37,12 @@ # Sub-directories -SUBDIRS = adc buttons can cdcacm composite dhcpd discover elf ftpc ftpd hello -SUBDIRS += helloxx hidkbd igmp json lcdrw mm modbus mount nettest nsh null nx -SUBDIRS += nxconsole nxffs nxflat nxhello nximage nxlines nxtext ostest -SUBDIRS += pashello pipe poll pwm qencoder rgmp romfs serloop telnetd -SUBDIRS += thttpd tiff touchscreen udp uip usbserial sendmail usbstorage -SUBDIRS += usbterm watchdog wget wgetjson wlan +SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf ftpc +SUBDIRS += ftpd hello helloxx hidkbd igmp json lcdrw mm modbus mount +SUBDIRS += nettest nsh null nx nxconsole nxffs nxflat nxhello nximage +SUBDIRS += nxlines nxtext ostest pashello pipe poll pwm qencoder rgmp +SUBDIRS += romfs serloop telnetd thttpd tiff touchscreen udp uip usbserial +SUBDIRS += sendmail usbstorage usbterm watchdog wget wgetjson wlan # Sub-directories that might need context setup. Directories may need # context setup for a variety of reasons, but the most common is because @@ -57,8 +57,8 @@ SUBDIRS += usbterm watchdog wget wgetjson wlan CNTXTDIRS = pwm ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) -CNTXTDIRS += adc can cdcacm composite dhcpd discover ftpd json modbus -CNTXTDIRS += nettest qencoder telnetd watchdog wgetjson +CNTXTDIRS += adc can cdcacm composite cxxtestdhcpd discover ftpd json +CNTXTDIRS += modbus nettest qencoder telnetd watchdog wgetjson endif ifeq ($(CONFIG_EXAMPLES_HELLO_BUILTIN),y) diff --git a/apps/examples/README.txt b/apps/examples/README.txt index f254ce154f..bfd61b73e8 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -239,6 +239,25 @@ examples/composite CONFIG_EXAMPLES_COMPOSITE_TRACEINTERRUPTS Show interrupt-related events. +examples/cxxtest +^^^^^^^^^^^^^^^^ + + This is a test of the C++ standard library. At present a port of the uClibc++ + C++ library is available. Due to licensinging issues, the uClibc++ C++ library + is not included in the NuttX source tree by default, but must be installed + (see misc/uClibc++/README.txt for installation). + + The only NuttX setting that is required is: + + CONFIG_HAVE_CXX=y + + The uClibc++ test includes simple test of: + + - iostreams, + - STL, + - RTTI, and + - Exceptions + examples/dhcpd ^^^^^^^^^^^^^^ diff --git a/apps/examples/cxxtest/Kconfig b/apps/examples/cxxtest/Kconfig new file mode 100644 index 0000000000..e8aa3d8f1e --- /dev/null +++ b/apps/examples/cxxtest/Kconfig @@ -0,0 +1,14 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config EXAMPLES_CXXTEST + bool "C++ test program" + default n + depends on HAVE_CXX + ---help--- + Enable the C++ test program + +if EXAMPLES_CXXTEST +endif diff --git a/apps/examples/cxxtest/Makefile b/apps/examples/cxxtest/Makefile new file mode 100644 index 0000000000..803bffa73c --- /dev/null +++ b/apps/examples/cxxtest/Makefile @@ -0,0 +1,122 @@ +############################################################################ +# apps/examples/cxxtest/Makefile +# +# Copyright (C) 2009-2011 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 +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +# CXX test program + +ASRCS = +CSRCS = +CXXSRCS = cxxtest_main.cxx + +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) +CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) +OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) + +ifeq ($(WINTOOL),y) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" +else + BIN = "$(APPDIR)/libapps$(LIBEXT)" +endif + +ROOTDEPPATH = --dep-path . + +# cxxtest built-in application info + +APPNAME = cxxtest +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 4096 + +# Common build + +VPATH = + +all: .built +.PHONY: clean depend disclean chkcxx + +chkcxx: +ifneq ($(CONFIG_HAVE_CXX),y) + @echo "" + @echo "In order to use this example, you toolchain must support must" + @echo "" + @echo " (1) Explicitly select CONFIG_HAVE_CXX to build in C++ support" + @echo " (2) Define CXX, CXXFLAGS, and COMPILEXX in the Make.defs file" + @echo " of the configuration that you are using." + @echo "" + @exit 1 +endif + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +$(CXXOBJS): %$(OBJEXT): %.cxx + $(call COMPILEXX, $<, $@) + +.built: chkcxx $(OBJS) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) + @touch .built + +.context: +ifeq ($(CONFIG_EXAMPLES_HELLOXX_BUILTIN),y) + $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) + @touch $@ +endif + +context: .context + +.depend: Makefile $(SRCS) + @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + @touch $@ + +depend: .depend + +clean: + @rm -f *.o *~ .*.swp .built + $(call CLEAN) + +distclean: clean + @rm -f Make.dep .depend + +-include Make.dep diff --git a/apps/examples/cxxtest/cxxtext_main.cxx b/apps/examples/cxxtest/cxxtext_main.cxx new file mode 100644 index 0000000000..0d181d0e4b --- /dev/null +++ b/apps/examples/cxxtest/cxxtext_main.cxx @@ -0,0 +1,219 @@ +//*************************************************************************** +// examples/cxxtest/main.cxx +// +// Copyright (C) 2012 Gregory Nutt. All rights reserved. +// Author: Qiang Yu, http://rgmp.sourceforge.net/wiki/index.php/Main_Page +// +// 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 + +using namespace std; + +//*************************************************************************** +// Definitions +//*************************************************************************** + +//*************************************************************************** +// Private Classes +//*************************************************************************** + +class Base +{ +public: + virtual void printBase(void) {}; +}; + +class Extend : public Base +{ +public: + void printExtend(void) + { + cout << "extend" << endl; + } +}; + +//*************************************************************************** +// Private Data +//*************************************************************************** + +//*************************************************************************** +// Public Functions +//*************************************************************************** + +//*************************************************************************** +// Name: test_iostream +//***************************************************************************/ + +static void test_iostream(void) +{ + int a; + string s; + + cout << "test iostream===========================" << endl; + cout << "Hello, this is only a test" << endl; + cout << "Print an int: " << 190 << endl; + cout << "Print a char: " << 'd' << endl; + +/* + cout << "Please type in an int:" << endl; + cin >> a; + cout << "You type in: " << a << endl; + cout << "Please type in a string:" << endl; + cin >> s; + cout << "You type in: " << s << endl; +*/ +} + +//*************************************************************************** +// Name: test_stl +//***************************************************************************/ + +static void test_stl(void) +{ + cout << "test vector=============================" << endl; + + vector v1; + assert(v1.empty()); + + v1.push_back(1); + assert(!v1.empty()); + + v1.push_back(2); + v1.push_back(3); + v1.push_back(4); + assert(v1.size() == 4); + + v1.pop_back(); + assert(v1.size() == 3); + + cout << "v1=" << v1[0] << ' ' << v1[1] << ' ' << v1[2] << endl; + assert(v1[2] == 3); + + vector v2 = v1; + assert(v2 == v1); + + string words[4] = {"Hello", "World", "Good", "Luck"}; + vector v3(words, words + 4); + vector::iterator it; + for (it = v3.begin(); it != v3.end(); it++) + { + cout << *it << ' '; + } + + cout << endl; + assert(v3[1] == "World"); + + cout << "test map================================" << endl; + + map m1; + m1[12] = "Hello"; + m1[24] = "World"; + assert(m1.size() == 2); + assert(m1[24] == "World"); +} + +//*************************************************************************** +// Name: test_rtti +//***************************************************************************/ + +static void test_rtti(void) +{ + cout << "test rtti===============================" << endl; + Base *a = new Base(); + Base *b = new Extend(); + assert(a); + assert(b); + + Extend *t = dynamic_cast(a); + assert(t == NULL); + + t = dynamic_cast(b); + assert(t); + t->printExtend(); + + delete a; + delete b; +} + +//*************************************************************************** +// Name: test_exception +//***************************************************************************/ + +static void test_exception(void) +{ + cout << "test exception==========================" << endl; + try + { + throw runtime_error("runtime error"); + } + + catch (runtime_error &e) + { + cout << "Catch exception: " << e.what() << endl; + } +} + +//*************************************************************************** +// Public Functions +//*************************************************************************** + +//*************************************************************************** +// Name: cxxtest_main +//***************************************************************************/ + +int cxxtest_main(int argc, char *argv[]) +{ + // If C++ initialization for static constructors is supported, then do + // that first + +#ifdef CONFIG_HAVE_CXXINITIALIZE + up_cxxinitialize(); +#endif + + test_iostream(); + test_stl(); + test_rtti(); + test_exception(); + + return 0; +} diff --git a/misc/uClibc++/README.txt b/misc/uClibc++/README.txt new file mode 100755 index 0000000000..d11efa6506 --- /dev/null +++ b/misc/uClibc++/README.txt @@ -0,0 +1,85 @@ +misc/uClib++ README +^^^^^^^^^^^^^^^^^^^ + +This directory contains a version of the uClibc++ C++ library. This code +originates from http://cxx.uclibc.org/ and has been adapted for NuttX by the +RGMP team (http://rgmp.sourceforge.net/wiki/index.php/Main_Page). + +uClibc++ resides in the misc/ directory rather than in the main NuttX source +tree due to licensing issues: NuttX is licensed under the permissiv + modified BSD License; uClibc, on the other hand, islicensed under the + stricter GNU LGPL Version 3 license. + +Installation of uClibc++ +^^^^^^^^^^^^^^^^^^^^^^^^ + +If you wish to use uClibc++ with NuttX, you will be required to comply with +the licensing requires of the GNU LGPL Version 3 license. A simple +installation script is provided at misc/uClibc++/install.sh that can be used +to install the uClibc++ components into the NuttX source tree. + +The install script takes only a single arguement: The path to the nuttx +directory. If your directory structure is the same as the SVN structure +(with misc/ and nuttx/ at the same level), then uClibc++ can be installed +using this command executed from the misc/uClibc++ directory: + + ./install.sh ../../nuttx + +If you run the install.sh like this, then it will (1) make sure you +understand that you have tainted the NuttX BSD license with LGPLv3, and (2) +copy the uClibc++ sources files into nuttx/libxx/uClibc++, include/, and +include/cxx. + +Building NuttX with uClibc++ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +After installing uClibc++ in this way, no additional steps should be +required to build NuttX with the uClibc++ library incorporated: + + $ cd ../../nuttx + $ . ./setenv.sh + $ make + +Here is how it works: + +There is a new file called Make.defs in misc/uClibc/libxx/uClibc++. After +installation, it will reside at nuttx/libxx/uClibc++. The +nuttx/libxx/Makefile will (conditionally) include this Make.defs file: + +-include uClibc++/Make.defs + +This Make.defs file, if present, will add the uClibc++ source files to the +build, add the uClibc++ subdirectory to the dependency list, and add the +uClibc++ subdirectory to the VPATH. That should, in principle, be all it +takes. + +Dependencies +^^^^^^^^^^^^ + +In order to build libxx (and hence libxx/uClibc++), CONFIG_HAVE_CXX must be +defined in your NuttX configuration file. + +The C++ runtime support is provided by GCC libgcc_eh.a and libsupc++.a +libraries. + +RGMP +^^^^ + +The target platform is RGMP X86, it is also updated for TLS support which is +needed by these two libraries. So application can also use TLS on RGMP NuttX +port. + +Command to compile and install RGMP: + + $ make + $ make install + $ /usr/rgmp/setup + $ exit + +Command to compile and run NUTTX: + + $ cd nuttx/tools + $ ./configure rgmp/x86/cxxtest + $ cd .. + $ make + $ rgmp_run diff --git a/misc/uClibc++/install.sh b/misc/uClibc++/install.sh index 9f612bc41f..001a71bfeb 100755 --- a/misc/uClibc++/install.sh +++ b/misc/uClibc++/install.sh @@ -264,8 +264,8 @@ fi # Licensing echo "You are about to install the uClibc++ library into the NuttX source" -echo "tree. NuttX is licensed under a modified BSD License; uClibc is" -echo "licensed under the GNU LGPL Version 3 license. When you install" +echo "tree. NuttX is licensed under the permissive, modified BSD License; uClibc" +echo "is licensed under the GNU LGPL Version 3 license. When you install" echo "uClibc++ into the NuttX source tree, you must then comply with uClibc's" echo "stricter GNU LGPL Version 3 license." echo "" From 25136e9a50d400c71e92ce281eddad0494f29fb2 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 31 Oct 2012 22:06:31 +0000 Subject: [PATCH 054/206] Convert configs/sim/ostest to use mconf tool; Add configs/sim/cxxtest git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5285 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/Make.defs | 2 +- .../{cxxtext_main.cxx => cxxtest_main.cxx} | 12 +- misc/uClibc++/install.sh | 14 +- nuttx/ChangeLog | 3 + nuttx/configs/sim/README.txt | 57 +- nuttx/configs/sim/cxxtest/Make.defs | 111 ++++ nuttx/configs/sim/cxxtest/defconfig | 434 +++++++++++++ .../{ostest/appconfig => cxxtest/setenv.sh} | 18 +- nuttx/configs/sim/ostest/Make.defs | 2 +- nuttx/configs/sim/ostest/defconfig | 577 ++++++++++++------ nuttx/configs/sim/ostest/setenv.sh | 2 +- nuttx/libxx/Makefile | 2 +- 12 files changed, 1023 insertions(+), 211 deletions(-) rename apps/examples/cxxtest/{cxxtext_main.cxx => cxxtest_main.cxx} (99%) create mode 100644 nuttx/configs/sim/cxxtest/Make.defs create mode 100644 nuttx/configs/sim/cxxtest/defconfig rename nuttx/configs/sim/{ostest/appconfig => cxxtest/setenv.sh} (80%) mode change 100644 => 100755 diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index 52949ae915..8d36aaa409 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -54,7 +54,7 @@ ifeq ($(CONFIG_EXAMPLES_COMPOSITE),y) CONFIGURED_APPS += examples/composite endif -ifeq ($(CONFIG_EXAMPLES_CXXTEST,y) +ifeq ($(CONFIG_EXAMPLES_CXXTEST),y) CONFIGURED_APPS += examples/cxxtest endif diff --git a/apps/examples/cxxtest/cxxtext_main.cxx b/apps/examples/cxxtest/cxxtest_main.cxx similarity index 99% rename from apps/examples/cxxtest/cxxtext_main.cxx rename to apps/examples/cxxtest/cxxtest_main.cxx index 0d181d0e4b..c0d4bfbd1f 100644 --- a/apps/examples/cxxtest/cxxtext_main.cxx +++ b/apps/examples/cxxtest/cxxtest_main.cxx @@ -86,22 +86,22 @@ public: static void test_iostream(void) { - int a; - string s; - cout << "test iostream===========================" << endl; cout << "Hello, this is only a test" << endl; cout << "Print an int: " << 190 << endl; - cout << "Print a char: " << 'd' << endl; + cout << "Print a char: " << 'd' << endl; + +#if 0 + int a; + string s; -/* cout << "Please type in an int:" << endl; cin >> a; cout << "You type in: " << a << endl; cout << "Please type in a string:" << endl; cin >> s; cout << "You type in: " << s << endl; -*/ +#endif } //*************************************************************************** diff --git a/misc/uClibc++/install.sh b/misc/uClibc++/install.sh index 001a71bfeb..3a2bb66f2f 100755 --- a/misc/uClibc++/install.sh +++ b/misc/uClibc++/install.sh @@ -302,11 +302,17 @@ fi echo "Installing uClibc++ in the NuttX source tree" -cp -a ./libxx/* ${libxx_srcdir}/. || - { echo "Copy from ./libxx/* to ${libxx_srcdir}/. failed"; exit 1; } +filelist=`find libxx -type f | fgrep -v '.svn'` -cp -a ./include/* ${nuttx_incdir}/. || - { echo "Copy from ./include/* ${nuttx_incdir}/. failed"; exit 1; } +for file in $filelist; do + install -D $file ${nuttx_path}/${file} +done + +filelist=`find include -type f | fgrep -v '.svn'` + +for file in $filelist; do + install -D $file ${nuttx_path}/${file} +done echo "Installation suceeded" echo "" diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index df9e345fe2..d4d840243b 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3538,4 +3538,7 @@ * binfmt/libelf: The ELF loader is working correctly with C++ static constructors and destructors and all. * Documentation/NuttXBinfmt.html: Add documentionof the binary loader. + * configs/sim/ostest: Converted to use the mconfig configuration tool. + * configs/sim/cxxtest: New test that will be used to verify the uClibc++ + port (eventually). diff --git a/nuttx/configs/sim/README.txt b/nuttx/configs/sim/README.txt index ee262e49a5..5583b23122 100644 --- a/nuttx/configs/sim/README.txt +++ b/nuttx/configs/sim/README.txt @@ -188,11 +188,33 @@ X11. See the discussion "Stack Size Issues" above. Configurations ^^^^^^^^^^^^^^ +cxxtest + + Description + ----------- + The C++ statndard libary test at apps/examples/cxxtest configuration. This + test is used to verify the uClibc++ port to NuttX. This configuration may + be selected as follows: + + cd /tools + ./configure.sh sim/cxxtest + + NOTES + ----- + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + mount Description ----------- - Configures to use examples/mount. This configuration may be + Configures to use apps/examples/mount. This configuration may be selected as follows: cd /tools @@ -202,7 +224,7 @@ nettest Description ----------- - Configures to use examples/nettest. This configuration + Configures to use apps/examples/nettest. This configuration enables networking using the network TAP device. It may be selected via: @@ -228,7 +250,7 @@ nsh Description ----------- - Configures to use the NuttShell at examples/nsh. This configuration + Configures to use the NuttShell at apps/examples/nsh. This configuration may be selected as follows: cd /tools @@ -238,7 +260,7 @@ nsh2 Description ----------- - This is another example that configures to use the NuttShell at examples/nsh. + This is another example that configures to use the NuttShell at apps/examples/nsh. Unlike nsh, this version uses NSH built-in functions. The nx, nxhello, and nxlines examples are included as built-in functions. @@ -260,7 +282,7 @@ nx Description ----------- - Configures to use examples/nx. This configuration may be + Configures to use apps/examples/nx. This configuration may be selected as follows: cd /tools @@ -297,7 +319,7 @@ nx11 Description ----------- - Configures to use examples/nx. This configuration is similar + Configures to use apps/examples/nx. This configuration is similar to the nx configuration except that it adds support for an X11- based framebuffer driver. Of course, this configuration can only be used in environments that support X11! (And it may not even @@ -379,10 +401,10 @@ nx11 CONFG_NX_MULTIUSER=y CONFIG_DISABLE_MQUEUE=n - examples/nxconsole - ------------------ - This configuration is also set up to use the examples/nxconsole - test instead of examples/nx. To enable this configuration, + apps/examples/nxconsole + ----------------------- + This configuration is also set up to use the apps/examples/nxconsole + test instead of apps/examples/nx. To enable this configuration, First, select Multi-User mode as described above. Then add the following definitions to the defconfig file: @@ -464,17 +486,28 @@ ostest Description ----------- - The "standard" NuttX examples/ostest configuration. This + The "standard" NuttX apps/examples/ostest configuration. This configuration may be selected as follows: cd /tools ./configure.sh sim/ostest + NOTES + ----- + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + pashello Description ----------- - Configures to use examples/pashello. This configuration may + Configures to use apps/examples/pashello. This configuration may by selected as follows: cd /tools diff --git a/nuttx/configs/sim/cxxtest/Make.defs b/nuttx/configs/sim/cxxtest/Make.defs new file mode 100644 index 0000000000..6e8de79d57 --- /dev/null +++ b/nuttx/configs/sim/cxxtest/Make.defs @@ -0,0 +1,111 @@ +############################################################################ +# configs/sim/cxxtest/Make.defs +# +# 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk + +HOSTOS = ${shell uname -o 2>/dev/null || echo "Other"} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = -O2 +endif + +ARCHCPUFLAGS = -fno-builtin +ARCHCPUFLAGSXX = -fno-builtin +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +ARCHDEFINES = +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include +ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx +ARCHSCRIPT = + +ifeq ($(CONFIG_SIM_M32),y) + ARCHCPUFLAGS += -m32 + ARCHCPUFLAGSXX += -m32 +endif + +CROSSDEV = +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 + +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXFLAGS = $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGSXX) $(ARCHINCLUDESXX) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +OBJEXT = .o +LIBEXT = .a + +ifeq ($(HOSTOS),Cygwin) + EXEEXT = .exe +else + EXEEXT = +endif + +LDLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(LD) +CCLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(CC) +LDFLAGS = $(ARCHSCRIPT) # For backward compatibility, same as CCLINKFLAGS + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDLINKFLAGS += -g + CCLINKFLAGS += -g + LDFLAGS += -g +endif + +ifeq ($(CONFIG_SIM_M32),y) + LDLINKFLAGS += -melf_i386 + CCLINKFLAGS += -m32 + LDFLAGS += -m32 +endif + + +MKDEP = $(TOPDIR)/tools/mkdeps.sh + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/sim/cxxtest/defconfig b/nuttx/configs/sim/cxxtest/defconfig new file mode 100644 index 0000000000..8e1fd8c57d --- /dev/null +++ b/nuttx/configs/sim/cxxtest/defconfig @@ -0,0 +1,434 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +# CONFIG_RAW_BINARY is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG=y +CONFIG_DEBUG_VERBOSE=y +# CONFIG_DEBUG_ENABLE is not set + +# +# Subsystem Debug Options +# +# CONFIG_DEBUG_MM is not set +# CONFIG_DEBUG_SCHED 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_ANALOG is not set +# CONFIG_DEBUG_DMA is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +# CONFIG_ARCH_ARM is not set +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +CONFIG_ARCH_SIM=y +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="sim" +CONFIG_BOARD_LOOPSPERMSEC=100 + +# +# Simulation Configuration Options +# +# CONFIG_SIM_M32 is not set +# CONFIG_SIM_WALLTIME is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +# CONFIG_ARCH_STACKDUMP is not set + +# +# Board Settings +# +CONFIG_DRAM_START=0x00000000 +CONFIG_DRAM_SIZE=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_SIM=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="sim" + +# +# Common Board Options +# + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=0 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=32 +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2007 +CONFIG_START_MONTH=2 +CONFIG_START_DAY=27 +CONFIG_DEV_CONSOLE=y +# CONFIG_DEV_LOWCONSOLE is not set +CONFIG_MUTEX_TYPES=y +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_WAITPID is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="cxxtest_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set +CONFIG_DISABLE_POLL=y + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=64 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=16 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=32 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=4 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_PREALLOC_TIMERS=8 + +# +# Stack and heap information +# +# CONFIG_CUSTOM_STACK is not set +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=8192 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +# CONFIG_SPI is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +# CONFIG_STANDARD_SERIAL is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_FS_FAT is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# +CONFIG_STDIO_BUFFER_SIZE=1024 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set +CONFIG_HAVE_CXX=y +# CONFIG_HAVE_CXXINITIALIZE is not set +# CONFIG_CXX_NEWLONG is not set + +# +# Application Configuration +# + +# +# Named Applications +# +# CONFIG_NAMEDAPP is not set + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +CONFIG_EXAMPLES_CXXTEST=y +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_NETTEST is not set +# CONFIG_EXAMPLES_NSH is not set +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WLAN is not set + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +# CONFIG_NSH_LIBRARY is not set + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +# CONFIG_SYSTEM_READLINE is not set + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# 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/sim/ostest/appconfig b/nuttx/configs/sim/cxxtest/setenv.sh old mode 100644 new mode 100755 similarity index 80% rename from nuttx/configs/sim/ostest/appconfig rename to nuttx/configs/sim/cxxtest/setenv.sh index 0827435048..c35ba6501f --- a/nuttx/configs/sim/ostest/appconfig +++ b/nuttx/configs/sim/cxxtest/setenv.sh @@ -1,7 +1,7 @@ -############################################################################ -# configs/sim/ostest/appconfig +#!/bin/bash +# configs/sim/cxxtext/setenv.sh # -# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Copyright (C) 2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -31,9 +31,15 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # -############################################################################ -# Path to example in apps/examples containing the user_start entry point +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi -CONFIGURED_APPS += examples/ostest +if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi +#export NUTTX_BIN= +#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/sim/ostest/Make.defs b/nuttx/configs/sim/ostest/Make.defs index 0851bcc776..201ff7a94f 100644 --- a/nuttx/configs/sim/ostest/Make.defs +++ b/nuttx/configs/sim/ostest/Make.defs @@ -1,5 +1,5 @@ ############################################################################ -# configs/sim/Make.defs +# configs/sim/ostest/Make.defs # # Copyright (C) 2007-2008, 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt diff --git a/nuttx/configs/sim/ostest/defconfig b/nuttx/configs/sim/ostest/defconfig index a2fbd9f050..708c82a79d 100644 --- a/nuttx/configs/sim/ostest/defconfig +++ b/nuttx/configs/sim/ostest/defconfig @@ -1,124 +1,153 @@ -############################################################################ -# configs/sim/ostest/defconfig # -# Copyright (C) 2007-2010 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration # -# 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. -# -############################################################################ -# -# Architecture selection -# -CONFIG_ARCH="sim" -CONFIG_ARCH_SIM=y -CONFIG_ARCH_BOARD="sim" -CONFIG_ARCH_BOARD_SIM=y +CONFIG_NUTTX_NEWCONFIG=y # -# General OS setup +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +# CONFIG_RAW_BINARY is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options # -CONFIG_USER_ENTRYPOINT="ostest_main" CONFIG_DEBUG=y CONFIG_DEBUG_VERBOSE=y -CONFIG_DEBUG_SYMBOLS=n -CONFIG_MM_REGIONS=1 -CONFIG_ARCH_LOWPUTC=y +# CONFIG_DEBUG_ENABLE is not set + +# +# Subsystem Debug Options +# +# CONFIG_DEBUG_MM is not set +# CONFIG_DEBUG_SCHED 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_ANALOG is not set +# CONFIG_DEBUG_DMA is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +# CONFIG_ARCH_ARM is not set +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +CONFIG_ARCH_SIM=y +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="sim" +CONFIG_BOARD_LOOPSPERMSEC=100 + +# +# Simulation Configuration Options +# +# CONFIG_SIM_M32 is not set +# CONFIG_SIM_WALLTIME is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +# CONFIG_ARCH_STACKDUMP is not set + +# +# Board Settings +# +CONFIG_DRAM_START=0x00000000 +CONFIG_DRAM_SIZE=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_SIM=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="sim" + +# +# Common Board Options +# + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 CONFIG_RR_INTERVAL=0 -CONFIG_SCHED_INSTRUMENTATION=n +# CONFIG_SCHED_INSTRUMENTATION is not set CONFIG_TASK_NAME_SIZE=32 +# CONFIG_JULIAN_TIME is not set CONFIG_START_YEAR=2007 CONFIG_START_MONTH=2 CONFIG_START_DAY=27 -CONFIG_JULIAN_TIME=n CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=n +# CONFIG_DEV_LOWCONSOLE is not set CONFIG_MUTEX_TYPES=y -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=n +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set CONFIG_SDCLONE_DISABLE=y - -# -# The following can be used to disable categories of -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=n -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=n -CONFIG_DISABLE_MOUNTPOINT=n -CONFIG_DISABLE_ENVIRON=n +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_WAITPID is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="ostest_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set CONFIG_DISABLE_POLL=y -# -# Misc libc settings -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve sysem performance -# -CONFIG_ARCH_MEMCPY=n -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n - -## -# General build options -# -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=n -CONFIG_RAW_BINARY=n - # # Sizes of configurable things (0 disables) # @@ -128,91 +157,281 @@ CONFIG_NPTHREAD_KEYS=4 CONFIG_NFILE_DESCRIPTORS=32 CONFIG_NFILE_STREAMS=16 CONFIG_NAME_MAX=32 -CONFIG_STDIO_BUFFER_SIZE=1024 -CONFIG_NUNGET_CHARS=2 CONFIG_PREALLOC_MQ_MSGS=32 CONFIG_MQ_MAXMSGSIZE=32 CONFIG_MAX_WDOGPARMS=4 CONFIG_PREALLOC_WDOGS=32 CONFIG_PREALLOC_TIMERS=8 -# -# FAT filesystem configuration -# -CONFIG_FS_FAT=y -CONFIG_FS_ROMFS=n - -# -# TCP/IP and UDP support via uIP -# -CONFIG_NET=n -CONFIG_NET_IPv6=n -CONFIG_NSOCKET_DESCRIPTORS=0 -CONFIG_NET_SOCKOPTS=y -CONFIG_NET_BUFSIZE=420 -CONFIG_NET_TCP=n -CONFIG_NET_TCP_CONNS=40 -CONFIG_NET_MAX_LISTENPORTS=40 -CONFIG_NET_UDP=n -CONFIG_NET_UDP_CHECKSUMS=y -#CONFIG_NET_UDP_CONNS=10 -CONFIG_NET_ICMP=n -CONFIG_NET_ICMP_PING=n -#CONFIG_NET_PINGADDRCONF=0 -CONFIG_NET_STATISTICS=y -#CONFIG_NET_RECEIVE_WINDOW= -#CONFIG_NET_ARPTAB_SIZE=8 -CONFIG_NET_BROADCAST=n - -# -# UIP Network Utilities -# -CONFIG_NET_DHCP_LIGHT=n -CONFIG_NET_RESOLV_ENTRIES=4 - -# -# Settings for examples/uip -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_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 -CONFIG_EXAMPLES_OSTEST_LOOPS=100 -CONFIG_EXAMPLES_OSTEST_STACKSIZE=8192 - -# -# Settings for apps/nshlib -CONFIG_NSH_CONSOLE=y -CONFIG_NSH_TELNET=n -CONFIG_NSH_IOBUFFER_SIZE=512 -CONFIG_NSH_CMD_SIZE=40 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=n -CONFIG_NSH_IPADDR=0x0a000002 -CONFIG_NSH_DRIPADDR=0x0a000001 -CONFIG_NSH_NETMASK=0xffffff00 - # # Stack and heap information # -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n +# CONFIG_CUSTOM_STACK is not set CONFIG_IDLETHREAD_STACKSIZE=4096 CONFIG_USERMAIN_STACKSIZE=4096 CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +# CONFIG_SPI is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +# CONFIG_STANDARD_SERIAL is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_FS_FAT is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# +CONFIG_STDIO_BUFFER_SIZE=1024 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set +# CONFIG_HAVE_CXX is not set +# CONFIG_HAVE_CXXINITIALIZE is not set +# CONFIG_CXX_NEWLONG is not set + +# +# Application Configuration +# + +# +# Named Applications +# +# CONFIG_NAMEDAPP is not set + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_NETTEST is not set +# CONFIG_EXAMPLES_NSH is not set +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +CONFIG_EXAMPLES_OSTEST=y +# CONFIG_EXAMPLES_OSTEST_BUILTIN is not set +CONFIG_EXAMPLES_OSTEST_LOOPS=100 +CONFIG_EXAMPLES_OSTEST_STACKSIZE=8192 +CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=8 +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WLAN is not set + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +# CONFIG_NSH_LIBRARY is not set + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +# CONFIG_SYSTEM_READLINE is not set + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# 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/sim/ostest/setenv.sh b/nuttx/configs/sim/ostest/setenv.sh index 273e418ee1..f13d73ee42 100755 --- a/nuttx/configs/sim/ostest/setenv.sh +++ b/nuttx/configs/sim/ostest/setenv.sh @@ -1,5 +1,5 @@ #!/bin/bash -# sim/setenv.sh +# configs/sim/ostest/setenv.sh # # Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. # Author: Gregory Nutt diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile index 67f8531d71..922c8d825c 100644 --- a/nuttx/libxx/Makefile +++ b/nuttx/libxx/Makefile @@ -52,7 +52,7 @@ VPATH = . # add its DEPPATH info, and will add the appropriate paths to the VPATH # variable --include/uClibc++/Make.defs +-include uClibc++/Make.defs # Object Files From 683e54b85fbd8641998c422eca33227755181f0f Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 31 Oct 2012 22:36:47 +0000 Subject: [PATCH 055/206] Fix DRAM size in STM32f4discovery defconfig files git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5286 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/sim/README.txt | 9 +++++++-- nuttx/configs/stm32f4discovery/elf/defconfig | 2 +- nuttx/configs/stm32f4discovery/nsh/defconfig | 2 +- nuttx/configs/stm32f4discovery/nxlines/defconfig | 2 +- nuttx/configs/stm32f4discovery/ostest/defconfig | 2 +- nuttx/configs/stm32f4discovery/pm/defconfig | 2 +- 6 files changed, 12 insertions(+), 7 deletions(-) diff --git a/nuttx/configs/sim/README.txt b/nuttx/configs/sim/README.txt index 5583b23122..bc8173fcf5 100644 --- a/nuttx/configs/sim/README.txt +++ b/nuttx/configs/sim/README.txt @@ -192,7 +192,7 @@ cxxtest Description ----------- - The C++ statndard libary test at apps/examples/cxxtest configuration. This + The C++ standard libary test at apps/examples/cxxtest configuration. This test is used to verify the uClibc++ port to NuttX. This configuration may be selected as follows: @@ -201,7 +201,12 @@ cxxtest NOTES ----- - 1. This configuration uses the mconf-based configuration tool. To + 1. Before you can use this example, you must first install the uClibc++ + C++ library. This is located outside of the NuttX source tree at + misc/uClibc++ in SVN. See the README.txt file for instructions on + how to install uClibc++ + + 2. This configuration uses the mconf-based configuration tool. To change this configuration using that tool, you should: a. Build and install the mconf tool. See nuttx/README.txt and diff --git a/nuttx/configs/stm32f4discovery/elf/defconfig b/nuttx/configs/stm32f4discovery/elf/defconfig index 67f5bf365a..e4702507c3 100644 --- a/nuttx/configs/stm32f4discovery/elf/defconfig +++ b/nuttx/configs/stm32f4discovery/elf/defconfig @@ -197,7 +197,7 @@ CONFIG_ARCH_STACKDUMP=y # Board Settings # CONFIG_DRAM_START=0x20000000 -CONFIG_DRAM_SIZE=196608 +CONFIG_DRAM_SIZE=114688 CONFIG_ARCH_HAVE_INTERRUPTSTACK=y CONFIG_ARCH_INTERRUPTSTACK=0 diff --git a/nuttx/configs/stm32f4discovery/nsh/defconfig b/nuttx/configs/stm32f4discovery/nsh/defconfig index 4461c08ce2..df802fee39 100644 --- a/nuttx/configs/stm32f4discovery/nsh/defconfig +++ b/nuttx/configs/stm32f4discovery/nsh/defconfig @@ -43,7 +43,7 @@ CONFIG_ARCH_CHIP_STM32F407VG=y CONFIG_ARCH_BOARD="stm32f4discovery" CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y CONFIG_BOARD_LOOPSPERMSEC=16717 -CONFIG_DRAM_SIZE=196608 +CONFIG_DRAM_SIZE=114688 CONFIG_DRAM_START=0x20000000 CONFIG_ARCH_IRQPRIO=y CONFIG_ARCH_FPU=n diff --git a/nuttx/configs/stm32f4discovery/nxlines/defconfig b/nuttx/configs/stm32f4discovery/nxlines/defconfig index 737b015b1f..34f6f636d9 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/defconfig +++ b/nuttx/configs/stm32f4discovery/nxlines/defconfig @@ -43,7 +43,7 @@ CONFIG_ARCH_CHIP_STM32F407VG=y CONFIG_ARCH_BOARD="stm32f4discovery" CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y CONFIG_BOARD_LOOPSPERMSEC=16717 -CONFIG_DRAM_SIZE=196608 +CONFIG_DRAM_SIZE=114688 CONFIG_DRAM_START=0x20000000 CONFIG_ARCH_IRQPRIO=y CONFIG_ARCH_FPU=n diff --git a/nuttx/configs/stm32f4discovery/ostest/defconfig b/nuttx/configs/stm32f4discovery/ostest/defconfig index ccd9c648aa..29d6b30eba 100644 --- a/nuttx/configs/stm32f4discovery/ostest/defconfig +++ b/nuttx/configs/stm32f4discovery/ostest/defconfig @@ -196,7 +196,7 @@ CONFIG_ARCH_STACKDUMP=y # Board Settings # CONFIG_DRAM_START=0x20000000 -CONFIG_DRAM_SIZE=196608 +CONFIG_DRAM_SIZE=114688 CONFIG_ARCH_HAVE_INTERRUPTSTACK=y CONFIG_ARCH_INTERRUPTSTACK=0 diff --git a/nuttx/configs/stm32f4discovery/pm/defconfig b/nuttx/configs/stm32f4discovery/pm/defconfig index 6785ec46ed..0a463d9bd6 100644 --- a/nuttx/configs/stm32f4discovery/pm/defconfig +++ b/nuttx/configs/stm32f4discovery/pm/defconfig @@ -43,7 +43,7 @@ CONFIG_ARCH_CHIP_STM32F407VG=y CONFIG_ARCH_BOARD="stm32f4discovery" CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y CONFIG_BOARD_LOOPSPERMSEC=16717 -CONFIG_DRAM_SIZE=196608 +CONFIG_DRAM_SIZE=114688 CONFIG_DRAM_START=0x20000000 CONFIG_ARCH_IRQPRIO=y CONFIG_ARCH_FPU=n From e60d4488b3f03a07d55bd164615ec8acf732aa0e Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 1 Nov 2012 12:19:20 +0000 Subject: [PATCH 056/206] Put uClibc++ header files in a different directory from NuttX header files git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5287 42af7a65-404d-4744-a932-0658087f49c3 --- misc/uClibc++/README.txt | 17 ++++++++++++++++- .../uClibc++/include/{cxx => uClibc++}/Makefile | 0 .../include/{cxx => uClibc++}/algorithm | 0 .../include/{cxx => uClibc++}/associative_base | 0 .../include/{cxx => uClibc++}/basic_definitions | 0 misc/uClibc++/include/{cxx => uClibc++}/bitset | 0 misc/uClibc++/include/{cxx => uClibc++}/cfloat | 0 .../include/{cxx => uClibc++}/char_traits | 0 misc/uClibc++/include/{cxx => uClibc++}/clocale | 0 misc/uClibc++/include/{cxx => uClibc++}/complex | 0 misc/uClibc++/include/{cxx => uClibc++}/csetjmp | 0 misc/uClibc++/include/{cxx => uClibc++}/cwchar | 0 misc/uClibc++/include/{cxx => uClibc++}/cwctype | 0 misc/uClibc++/include/{cxx => uClibc++}/deque | 0 .../include/{cxx => uClibc++}/exception | 0 misc/uClibc++/include/{cxx => uClibc++}/fstream | 0 .../include/{cxx => uClibc++}/func_exception | 0 .../include/{cxx => uClibc++}/functional | 0 misc/uClibc++/include/{cxx => uClibc++}/iomanip | 0 misc/uClibc++/include/{cxx => uClibc++}/ios | 0 misc/uClibc++/include/{cxx => uClibc++}/iosfwd | 0 .../uClibc++/include/{cxx => uClibc++}/iostream | 0 misc/uClibc++/include/{cxx => uClibc++}/istream | 0 .../include/{cxx => uClibc++}/istream_helpers | 0 .../uClibc++/include/{cxx => uClibc++}/iterator | 0 .../include/{cxx => uClibc++}/iterator_base | 0 misc/uClibc++/include/{cxx => uClibc++}/limits | 0 misc/uClibc++/include/{cxx => uClibc++}/list | 0 misc/uClibc++/include/{cxx => uClibc++}/locale | 0 misc/uClibc++/include/{cxx => uClibc++}/map | 0 misc/uClibc++/include/{cxx => uClibc++}/memory | 0 misc/uClibc++/include/{cxx => uClibc++}/new | 0 misc/uClibc++/include/{cxx => uClibc++}/numeric | 0 misc/uClibc++/include/{cxx => uClibc++}/ostream | 0 .../include/{cxx => uClibc++}/ostream_helpers | 0 misc/uClibc++/include/{cxx => uClibc++}/queue | 0 misc/uClibc++/include/{cxx => uClibc++}/set | 0 misc/uClibc++/include/{cxx => uClibc++}/sstream | 0 misc/uClibc++/include/{cxx => uClibc++}/stack | 0 .../include/{cxx => uClibc++}/stdexcept | 0 .../include/{cxx => uClibc++}/streambuf | 0 misc/uClibc++/include/{cxx => uClibc++}/string | 0 .../include/{cxx => uClibc++}/string_iostream | 0 misc/uClibc++/include/{cxx => uClibc++}/support | 0 .../{cxx => uClibc++}/system_configuration.h | 0 .../include/{cxx => uClibc++}/type_traits | 0 .../uClibc++/include/{cxx => uClibc++}/typeinfo | 0 .../include/{cxx => uClibc++}/unwind-cxx.h | 0 misc/uClibc++/include/{cxx => uClibc++}/utility | 0 .../uClibc++/include/{cxx => uClibc++}/valarray | 0 misc/uClibc++/include/{cxx => uClibc++}/vector | 0 nuttx/Documentation/NuttX.html | 8 ++++++++ nuttx/configs/sim/cxxtest/Make.defs | 3 +-- 53 files changed, 25 insertions(+), 3 deletions(-) rename misc/uClibc++/include/{cxx => uClibc++}/Makefile (100%) rename misc/uClibc++/include/{cxx => uClibc++}/algorithm (100%) rename misc/uClibc++/include/{cxx => uClibc++}/associative_base (100%) rename misc/uClibc++/include/{cxx => uClibc++}/basic_definitions (100%) rename misc/uClibc++/include/{cxx => uClibc++}/bitset (100%) rename misc/uClibc++/include/{cxx => uClibc++}/cfloat (100%) rename misc/uClibc++/include/{cxx => uClibc++}/char_traits (100%) rename misc/uClibc++/include/{cxx => uClibc++}/clocale (100%) rename misc/uClibc++/include/{cxx => uClibc++}/complex (100%) rename misc/uClibc++/include/{cxx => uClibc++}/csetjmp (100%) rename misc/uClibc++/include/{cxx => uClibc++}/cwchar (100%) rename misc/uClibc++/include/{cxx => uClibc++}/cwctype (100%) rename misc/uClibc++/include/{cxx => uClibc++}/deque (100%) rename misc/uClibc++/include/{cxx => uClibc++}/exception (100%) rename misc/uClibc++/include/{cxx => uClibc++}/fstream (100%) rename misc/uClibc++/include/{cxx => uClibc++}/func_exception (100%) rename misc/uClibc++/include/{cxx => uClibc++}/functional (100%) rename misc/uClibc++/include/{cxx => uClibc++}/iomanip (100%) rename misc/uClibc++/include/{cxx => uClibc++}/ios (100%) rename misc/uClibc++/include/{cxx => uClibc++}/iosfwd (100%) rename misc/uClibc++/include/{cxx => uClibc++}/iostream (100%) rename misc/uClibc++/include/{cxx => uClibc++}/istream (100%) rename misc/uClibc++/include/{cxx => uClibc++}/istream_helpers (100%) rename misc/uClibc++/include/{cxx => uClibc++}/iterator (100%) rename misc/uClibc++/include/{cxx => uClibc++}/iterator_base (100%) rename misc/uClibc++/include/{cxx => uClibc++}/limits (100%) rename misc/uClibc++/include/{cxx => uClibc++}/list (100%) rename misc/uClibc++/include/{cxx => uClibc++}/locale (100%) rename misc/uClibc++/include/{cxx => uClibc++}/map (100%) rename misc/uClibc++/include/{cxx => uClibc++}/memory (100%) rename misc/uClibc++/include/{cxx => uClibc++}/new (100%) rename misc/uClibc++/include/{cxx => uClibc++}/numeric (100%) rename misc/uClibc++/include/{cxx => uClibc++}/ostream (100%) rename misc/uClibc++/include/{cxx => uClibc++}/ostream_helpers (100%) rename misc/uClibc++/include/{cxx => uClibc++}/queue (100%) rename misc/uClibc++/include/{cxx => uClibc++}/set (100%) rename misc/uClibc++/include/{cxx => uClibc++}/sstream (100%) rename misc/uClibc++/include/{cxx => uClibc++}/stack (100%) rename misc/uClibc++/include/{cxx => uClibc++}/stdexcept (100%) rename misc/uClibc++/include/{cxx => uClibc++}/streambuf (100%) rename misc/uClibc++/include/{cxx => uClibc++}/string (100%) rename misc/uClibc++/include/{cxx => uClibc++}/string_iostream (100%) rename misc/uClibc++/include/{cxx => uClibc++}/support (100%) rename misc/uClibc++/include/{cxx => uClibc++}/system_configuration.h (100%) rename misc/uClibc++/include/{cxx => uClibc++}/type_traits (100%) rename misc/uClibc++/include/{cxx => uClibc++}/typeinfo (100%) rename misc/uClibc++/include/{cxx => uClibc++}/unwind-cxx.h (100%) rename misc/uClibc++/include/{cxx => uClibc++}/utility (100%) rename misc/uClibc++/include/{cxx => uClibc++}/valarray (100%) rename misc/uClibc++/include/{cxx => uClibc++}/vector (100%) diff --git a/misc/uClibc++/README.txt b/misc/uClibc++/README.txt index d11efa6506..83b4c13f9c 100755 --- a/misc/uClibc++/README.txt +++ b/misc/uClibc++/README.txt @@ -28,7 +28,22 @@ using this command executed from the misc/uClibc++ directory: If you run the install.sh like this, then it will (1) make sure you understand that you have tainted the NuttX BSD license with LGPLv3, and (2) copy the uClibc++ sources files into nuttx/libxx/uClibc++, include/, and -include/cxx. +include/uClibc++. + +Make.defs File Changes +^^^^^^^^^^^^^^^^^^^^^^ + +The new files that appear in nuttx/include/uClibc++ must be include-able +as system header files. So you will need to add 'isystem $(TOPDIR)/include/uClibc++' +to the ARCHINCLUDESXX definition in the NuttX Make.defs file, perhap like: + + -ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + +ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx -isystem $(TOPDIR)/include/uClibc++ + +And, of course, you no long need to suppress exceptions or run-time typing: + + -ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions -fno-rtti + +ARCHCPUFLAGSXX = -fno-builtin Building NuttX with uClibc++ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/misc/uClibc++/include/cxx/Makefile b/misc/uClibc++/include/uClibc++/Makefile similarity index 100% rename from misc/uClibc++/include/cxx/Makefile rename to misc/uClibc++/include/uClibc++/Makefile diff --git a/misc/uClibc++/include/cxx/algorithm b/misc/uClibc++/include/uClibc++/algorithm similarity index 100% rename from misc/uClibc++/include/cxx/algorithm rename to misc/uClibc++/include/uClibc++/algorithm diff --git a/misc/uClibc++/include/cxx/associative_base b/misc/uClibc++/include/uClibc++/associative_base similarity index 100% rename from misc/uClibc++/include/cxx/associative_base rename to misc/uClibc++/include/uClibc++/associative_base diff --git a/misc/uClibc++/include/cxx/basic_definitions b/misc/uClibc++/include/uClibc++/basic_definitions similarity index 100% rename from misc/uClibc++/include/cxx/basic_definitions rename to misc/uClibc++/include/uClibc++/basic_definitions diff --git a/misc/uClibc++/include/cxx/bitset b/misc/uClibc++/include/uClibc++/bitset similarity index 100% rename from misc/uClibc++/include/cxx/bitset rename to misc/uClibc++/include/uClibc++/bitset diff --git a/misc/uClibc++/include/cxx/cfloat b/misc/uClibc++/include/uClibc++/cfloat similarity index 100% rename from misc/uClibc++/include/cxx/cfloat rename to misc/uClibc++/include/uClibc++/cfloat diff --git a/misc/uClibc++/include/cxx/char_traits b/misc/uClibc++/include/uClibc++/char_traits similarity index 100% rename from misc/uClibc++/include/cxx/char_traits rename to misc/uClibc++/include/uClibc++/char_traits diff --git a/misc/uClibc++/include/cxx/clocale b/misc/uClibc++/include/uClibc++/clocale similarity index 100% rename from misc/uClibc++/include/cxx/clocale rename to misc/uClibc++/include/uClibc++/clocale diff --git a/misc/uClibc++/include/cxx/complex b/misc/uClibc++/include/uClibc++/complex similarity index 100% rename from misc/uClibc++/include/cxx/complex rename to misc/uClibc++/include/uClibc++/complex diff --git a/misc/uClibc++/include/cxx/csetjmp b/misc/uClibc++/include/uClibc++/csetjmp similarity index 100% rename from misc/uClibc++/include/cxx/csetjmp rename to misc/uClibc++/include/uClibc++/csetjmp diff --git a/misc/uClibc++/include/cxx/cwchar b/misc/uClibc++/include/uClibc++/cwchar similarity index 100% rename from misc/uClibc++/include/cxx/cwchar rename to misc/uClibc++/include/uClibc++/cwchar diff --git a/misc/uClibc++/include/cxx/cwctype b/misc/uClibc++/include/uClibc++/cwctype similarity index 100% rename from misc/uClibc++/include/cxx/cwctype rename to misc/uClibc++/include/uClibc++/cwctype diff --git a/misc/uClibc++/include/cxx/deque b/misc/uClibc++/include/uClibc++/deque similarity index 100% rename from misc/uClibc++/include/cxx/deque rename to misc/uClibc++/include/uClibc++/deque diff --git a/misc/uClibc++/include/cxx/exception b/misc/uClibc++/include/uClibc++/exception similarity index 100% rename from misc/uClibc++/include/cxx/exception rename to misc/uClibc++/include/uClibc++/exception diff --git a/misc/uClibc++/include/cxx/fstream b/misc/uClibc++/include/uClibc++/fstream similarity index 100% rename from misc/uClibc++/include/cxx/fstream rename to misc/uClibc++/include/uClibc++/fstream diff --git a/misc/uClibc++/include/cxx/func_exception b/misc/uClibc++/include/uClibc++/func_exception similarity index 100% rename from misc/uClibc++/include/cxx/func_exception rename to misc/uClibc++/include/uClibc++/func_exception diff --git a/misc/uClibc++/include/cxx/functional b/misc/uClibc++/include/uClibc++/functional similarity index 100% rename from misc/uClibc++/include/cxx/functional rename to misc/uClibc++/include/uClibc++/functional diff --git a/misc/uClibc++/include/cxx/iomanip b/misc/uClibc++/include/uClibc++/iomanip similarity index 100% rename from misc/uClibc++/include/cxx/iomanip rename to misc/uClibc++/include/uClibc++/iomanip diff --git a/misc/uClibc++/include/cxx/ios b/misc/uClibc++/include/uClibc++/ios similarity index 100% rename from misc/uClibc++/include/cxx/ios rename to misc/uClibc++/include/uClibc++/ios diff --git a/misc/uClibc++/include/cxx/iosfwd b/misc/uClibc++/include/uClibc++/iosfwd similarity index 100% rename from misc/uClibc++/include/cxx/iosfwd rename to misc/uClibc++/include/uClibc++/iosfwd diff --git a/misc/uClibc++/include/cxx/iostream b/misc/uClibc++/include/uClibc++/iostream similarity index 100% rename from misc/uClibc++/include/cxx/iostream rename to misc/uClibc++/include/uClibc++/iostream diff --git a/misc/uClibc++/include/cxx/istream b/misc/uClibc++/include/uClibc++/istream similarity index 100% rename from misc/uClibc++/include/cxx/istream rename to misc/uClibc++/include/uClibc++/istream diff --git a/misc/uClibc++/include/cxx/istream_helpers b/misc/uClibc++/include/uClibc++/istream_helpers similarity index 100% rename from misc/uClibc++/include/cxx/istream_helpers rename to misc/uClibc++/include/uClibc++/istream_helpers diff --git a/misc/uClibc++/include/cxx/iterator b/misc/uClibc++/include/uClibc++/iterator similarity index 100% rename from misc/uClibc++/include/cxx/iterator rename to misc/uClibc++/include/uClibc++/iterator diff --git a/misc/uClibc++/include/cxx/iterator_base b/misc/uClibc++/include/uClibc++/iterator_base similarity index 100% rename from misc/uClibc++/include/cxx/iterator_base rename to misc/uClibc++/include/uClibc++/iterator_base diff --git a/misc/uClibc++/include/cxx/limits b/misc/uClibc++/include/uClibc++/limits similarity index 100% rename from misc/uClibc++/include/cxx/limits rename to misc/uClibc++/include/uClibc++/limits diff --git a/misc/uClibc++/include/cxx/list b/misc/uClibc++/include/uClibc++/list similarity index 100% rename from misc/uClibc++/include/cxx/list rename to misc/uClibc++/include/uClibc++/list diff --git a/misc/uClibc++/include/cxx/locale b/misc/uClibc++/include/uClibc++/locale similarity index 100% rename from misc/uClibc++/include/cxx/locale rename to misc/uClibc++/include/uClibc++/locale diff --git a/misc/uClibc++/include/cxx/map b/misc/uClibc++/include/uClibc++/map similarity index 100% rename from misc/uClibc++/include/cxx/map rename to misc/uClibc++/include/uClibc++/map diff --git a/misc/uClibc++/include/cxx/memory b/misc/uClibc++/include/uClibc++/memory similarity index 100% rename from misc/uClibc++/include/cxx/memory rename to misc/uClibc++/include/uClibc++/memory diff --git a/misc/uClibc++/include/cxx/new b/misc/uClibc++/include/uClibc++/new similarity index 100% rename from misc/uClibc++/include/cxx/new rename to misc/uClibc++/include/uClibc++/new diff --git a/misc/uClibc++/include/cxx/numeric b/misc/uClibc++/include/uClibc++/numeric similarity index 100% rename from misc/uClibc++/include/cxx/numeric rename to misc/uClibc++/include/uClibc++/numeric diff --git a/misc/uClibc++/include/cxx/ostream b/misc/uClibc++/include/uClibc++/ostream similarity index 100% rename from misc/uClibc++/include/cxx/ostream rename to misc/uClibc++/include/uClibc++/ostream diff --git a/misc/uClibc++/include/cxx/ostream_helpers b/misc/uClibc++/include/uClibc++/ostream_helpers similarity index 100% rename from misc/uClibc++/include/cxx/ostream_helpers rename to misc/uClibc++/include/uClibc++/ostream_helpers diff --git a/misc/uClibc++/include/cxx/queue b/misc/uClibc++/include/uClibc++/queue similarity index 100% rename from misc/uClibc++/include/cxx/queue rename to misc/uClibc++/include/uClibc++/queue diff --git a/misc/uClibc++/include/cxx/set b/misc/uClibc++/include/uClibc++/set similarity index 100% rename from misc/uClibc++/include/cxx/set rename to misc/uClibc++/include/uClibc++/set diff --git a/misc/uClibc++/include/cxx/sstream b/misc/uClibc++/include/uClibc++/sstream similarity index 100% rename from misc/uClibc++/include/cxx/sstream rename to misc/uClibc++/include/uClibc++/sstream diff --git a/misc/uClibc++/include/cxx/stack b/misc/uClibc++/include/uClibc++/stack similarity index 100% rename from misc/uClibc++/include/cxx/stack rename to misc/uClibc++/include/uClibc++/stack diff --git a/misc/uClibc++/include/cxx/stdexcept b/misc/uClibc++/include/uClibc++/stdexcept similarity index 100% rename from misc/uClibc++/include/cxx/stdexcept rename to misc/uClibc++/include/uClibc++/stdexcept diff --git a/misc/uClibc++/include/cxx/streambuf b/misc/uClibc++/include/uClibc++/streambuf similarity index 100% rename from misc/uClibc++/include/cxx/streambuf rename to misc/uClibc++/include/uClibc++/streambuf diff --git a/misc/uClibc++/include/cxx/string b/misc/uClibc++/include/uClibc++/string similarity index 100% rename from misc/uClibc++/include/cxx/string rename to misc/uClibc++/include/uClibc++/string diff --git a/misc/uClibc++/include/cxx/string_iostream b/misc/uClibc++/include/uClibc++/string_iostream similarity index 100% rename from misc/uClibc++/include/cxx/string_iostream rename to misc/uClibc++/include/uClibc++/string_iostream diff --git a/misc/uClibc++/include/cxx/support b/misc/uClibc++/include/uClibc++/support similarity index 100% rename from misc/uClibc++/include/cxx/support rename to misc/uClibc++/include/uClibc++/support diff --git a/misc/uClibc++/include/cxx/system_configuration.h b/misc/uClibc++/include/uClibc++/system_configuration.h similarity index 100% rename from misc/uClibc++/include/cxx/system_configuration.h rename to misc/uClibc++/include/uClibc++/system_configuration.h diff --git a/misc/uClibc++/include/cxx/type_traits b/misc/uClibc++/include/uClibc++/type_traits similarity index 100% rename from misc/uClibc++/include/cxx/type_traits rename to misc/uClibc++/include/uClibc++/type_traits diff --git a/misc/uClibc++/include/cxx/typeinfo b/misc/uClibc++/include/uClibc++/typeinfo similarity index 100% rename from misc/uClibc++/include/cxx/typeinfo rename to misc/uClibc++/include/uClibc++/typeinfo diff --git a/misc/uClibc++/include/cxx/unwind-cxx.h b/misc/uClibc++/include/uClibc++/unwind-cxx.h similarity index 100% rename from misc/uClibc++/include/cxx/unwind-cxx.h rename to misc/uClibc++/include/uClibc++/unwind-cxx.h diff --git a/misc/uClibc++/include/cxx/utility b/misc/uClibc++/include/uClibc++/utility similarity index 100% rename from misc/uClibc++/include/cxx/utility rename to misc/uClibc++/include/uClibc++/utility diff --git a/misc/uClibc++/include/cxx/valarray b/misc/uClibc++/include/uClibc++/valarray similarity index 100% rename from misc/uClibc++/include/cxx/valarray rename to misc/uClibc++/include/uClibc++/valarray diff --git a/misc/uClibc++/include/cxx/vector b/misc/uClibc++/include/uClibc++/vector similarity index 100% rename from misc/uClibc++/include/cxx/vector rename to misc/uClibc++/include/uClibc++/vector diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index 0c98d4ad2e..be23be91d2 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -556,6 +556,14 @@

    + +
    + +

    +

  • Add-on uClibc++ C++ Library is available (LGPL).
  • +

    + + diff --git a/nuttx/configs/sim/cxxtest/Make.defs b/nuttx/configs/sim/cxxtest/Make.defs index 6e8de79d57..eac92e9282 100644 --- a/nuttx/configs/sim/cxxtest/Make.defs +++ b/nuttx/configs/sim/cxxtest/Make.defs @@ -51,7 +51,7 @@ ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow ARCHWARNINGSXX = -Wall -Wshadow ARCHDEFINES = ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx +ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx -isystem $(TOPDIR)/include/uClibc++ ARCHSCRIPT = ifeq ($(CONFIG_SIM_M32),y) @@ -101,7 +101,6 @@ ifeq ($(CONFIG_SIM_M32),y) LDFLAGS += -m32 endif - MKDEP = $(TOPDIR)/tools/mkdeps.sh HOSTCC = gcc From 76e6bb67a158a34e29a8c35785138583568e03b1 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 1 Nov 2012 12:43:56 +0000 Subject: [PATCH 057/206] Correct name of another uClibc++ directory git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5288 42af7a65-404d-4744-a932-0658087f49c3 --- misc/uClibc++/install.sh | 2 +- .../libxx/{uClib++ => uClibc++}/Make.defs | 0 .../libxx/{uClib++ => uClibc++}/algorithm.cxx | 0 .../associative_base.cxx | 0 .../libxx/{uClib++ => uClibc++}/bitset.cxx | 0 .../{uClib++ => uClibc++}/char_traits.cxx | 0 .../libxx/{uClib++ => uClibc++}/complex.cxx | 0 .../libxx/{uClib++ => uClibc++}/del_op.cxx | 0 .../libxx/{uClib++ => uClibc++}/del_opnt.cxx | 0 .../libxx/{uClib++ => uClibc++}/del_opv.cxx | 0 .../libxx/{uClib++ => uClibc++}/del_opvnt.cxx | 0 .../libxx/{uClib++ => uClibc++}/deque.cxx | 0 .../libxx/{uClib++ => uClibc++}/eh_alloc.cxx | 0 .../{uClib++ => uClibc++}/eh_globals.cxx | 0 .../libxx/{uClib++ => uClibc++}/exception.cxx | 0 .../libxx/{uClib++ => uClibc++}/fstream.cxx | 0 .../{uClib++ => uClibc++}/func_exception.cxx | 0 .../libxx/{uClib++ => uClibc++}/iomanip.cxx | 0 .../libxx/{uClib++ => uClibc++}/ios.cxx | 0 .../libxx/{uClib++ => uClibc++}/iostream.cxx | 0 .../libxx/{uClib++ => uClibc++}/istream.cxx | 0 .../libxx/{uClib++ => uClibc++}/iterator.cxx | 0 .../libxx/{uClib++ => uClibc++}/limits.cxx | 0 .../libxx/{uClib++ => uClibc++}/list.cxx | 0 .../libxx/{uClib++ => uClibc++}/locale.cxx | 0 .../libxx/{uClib++ => uClibc++}/map.cxx | 0 .../{uClib++ => uClibc++}/new_handler.cxx | 0 .../libxx/{uClib++ => uClibc++}/new_op.cxx | 0 .../libxx/{uClib++ => uClibc++}/new_opnt.cxx | 0 .../libxx/{uClib++ => uClibc++}/new_opv.cxx | 0 .../libxx/{uClib++ => uClibc++}/new_opvnt.cxx | 0 .../libxx/{uClib++ => uClibc++}/numeric.cxx | 0 .../libxx/{uClib++ => uClibc++}/ostream.cxx | 0 .../libxx/{uClib++ => uClibc++}/queue.cxx | 0 .../libxx/{uClib++ => uClibc++}/set.cxx | 0 .../libxx/{uClib++ => uClibc++}/sstream.cxx | 0 .../libxx/{uClib++ => uClibc++}/stack.cxx | 0 .../libxx/{uClib++ => uClibc++}/stdexcept.cxx | 0 .../libxx/{uClib++ => uClibc++}/streambuf.cxx | 0 .../libxx/{uClib++ => uClibc++}/string.cxx | 0 .../libxx/{uClib++ => uClibc++}/support.cxx | 0 .../libxx/{uClib++ => uClibc++}/typeinfo.cxx | 0 .../libxx/{uClib++ => uClibc++}/utility.cxx | 0 .../libxx/{uClib++ => uClibc++}/valarray.cxx | 0 .../libxx/{uClib++ => uClibc++}/vector.cxx | 0 misc/uClibc++/uninstall.sh | 94 +++++++++++++++++++ nuttx/configs/sim/cxxtest/defconfig | 4 +- 47 files changed, 97 insertions(+), 3 deletions(-) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/Make.defs (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/algorithm.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/associative_base.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/bitset.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/char_traits.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/complex.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/del_op.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/del_opnt.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/del_opv.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/del_opvnt.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/deque.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/eh_alloc.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/eh_globals.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/exception.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/fstream.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/func_exception.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/iomanip.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/ios.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/iostream.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/istream.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/iterator.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/limits.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/list.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/locale.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/map.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/new_handler.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/new_op.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/new_opnt.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/new_opv.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/new_opvnt.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/numeric.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/ostream.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/queue.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/set.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/sstream.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/stack.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/stdexcept.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/streambuf.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/string.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/support.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/typeinfo.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/utility.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/valarray.cxx (100%) rename misc/uClibc++/libxx/{uClib++ => uClibc++}/vector.cxx (100%) create mode 100755 misc/uClibc++/uninstall.sh diff --git a/misc/uClibc++/install.sh b/misc/uClibc++/install.sh index 3a2bb66f2f..065738e1a0 100755 --- a/misc/uClibc++/install.sh +++ b/misc/uClibc++/install.sh @@ -217,7 +217,7 @@ if [ ! -d "${nuttx_path}" ]; then fi if [ ! -f "${nuttx_path}/Makefile" ]; then - echo "ERROR: Not Makefile in directory ${nuttx_path}" + echo "ERROR: No Makefile in directory ${nuttx_path}" echo $usage exit 1 fi diff --git a/misc/uClibc++/libxx/uClib++/Make.defs b/misc/uClibc++/libxx/uClibc++/Make.defs similarity index 100% rename from misc/uClibc++/libxx/uClib++/Make.defs rename to misc/uClibc++/libxx/uClibc++/Make.defs diff --git a/misc/uClibc++/libxx/uClib++/algorithm.cxx b/misc/uClibc++/libxx/uClibc++/algorithm.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/algorithm.cxx rename to misc/uClibc++/libxx/uClibc++/algorithm.cxx diff --git a/misc/uClibc++/libxx/uClib++/associative_base.cxx b/misc/uClibc++/libxx/uClibc++/associative_base.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/associative_base.cxx rename to misc/uClibc++/libxx/uClibc++/associative_base.cxx diff --git a/misc/uClibc++/libxx/uClib++/bitset.cxx b/misc/uClibc++/libxx/uClibc++/bitset.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/bitset.cxx rename to misc/uClibc++/libxx/uClibc++/bitset.cxx diff --git a/misc/uClibc++/libxx/uClib++/char_traits.cxx b/misc/uClibc++/libxx/uClibc++/char_traits.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/char_traits.cxx rename to misc/uClibc++/libxx/uClibc++/char_traits.cxx diff --git a/misc/uClibc++/libxx/uClib++/complex.cxx b/misc/uClibc++/libxx/uClibc++/complex.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/complex.cxx rename to misc/uClibc++/libxx/uClibc++/complex.cxx diff --git a/misc/uClibc++/libxx/uClib++/del_op.cxx b/misc/uClibc++/libxx/uClibc++/del_op.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/del_op.cxx rename to misc/uClibc++/libxx/uClibc++/del_op.cxx diff --git a/misc/uClibc++/libxx/uClib++/del_opnt.cxx b/misc/uClibc++/libxx/uClibc++/del_opnt.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/del_opnt.cxx rename to misc/uClibc++/libxx/uClibc++/del_opnt.cxx diff --git a/misc/uClibc++/libxx/uClib++/del_opv.cxx b/misc/uClibc++/libxx/uClibc++/del_opv.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/del_opv.cxx rename to misc/uClibc++/libxx/uClibc++/del_opv.cxx diff --git a/misc/uClibc++/libxx/uClib++/del_opvnt.cxx b/misc/uClibc++/libxx/uClibc++/del_opvnt.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/del_opvnt.cxx rename to misc/uClibc++/libxx/uClibc++/del_opvnt.cxx diff --git a/misc/uClibc++/libxx/uClib++/deque.cxx b/misc/uClibc++/libxx/uClibc++/deque.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/deque.cxx rename to misc/uClibc++/libxx/uClibc++/deque.cxx diff --git a/misc/uClibc++/libxx/uClib++/eh_alloc.cxx b/misc/uClibc++/libxx/uClibc++/eh_alloc.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/eh_alloc.cxx rename to misc/uClibc++/libxx/uClibc++/eh_alloc.cxx diff --git a/misc/uClibc++/libxx/uClib++/eh_globals.cxx b/misc/uClibc++/libxx/uClibc++/eh_globals.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/eh_globals.cxx rename to misc/uClibc++/libxx/uClibc++/eh_globals.cxx diff --git a/misc/uClibc++/libxx/uClib++/exception.cxx b/misc/uClibc++/libxx/uClibc++/exception.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/exception.cxx rename to misc/uClibc++/libxx/uClibc++/exception.cxx diff --git a/misc/uClibc++/libxx/uClib++/fstream.cxx b/misc/uClibc++/libxx/uClibc++/fstream.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/fstream.cxx rename to misc/uClibc++/libxx/uClibc++/fstream.cxx diff --git a/misc/uClibc++/libxx/uClib++/func_exception.cxx b/misc/uClibc++/libxx/uClibc++/func_exception.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/func_exception.cxx rename to misc/uClibc++/libxx/uClibc++/func_exception.cxx diff --git a/misc/uClibc++/libxx/uClib++/iomanip.cxx b/misc/uClibc++/libxx/uClibc++/iomanip.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/iomanip.cxx rename to misc/uClibc++/libxx/uClibc++/iomanip.cxx diff --git a/misc/uClibc++/libxx/uClib++/ios.cxx b/misc/uClibc++/libxx/uClibc++/ios.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/ios.cxx rename to misc/uClibc++/libxx/uClibc++/ios.cxx diff --git a/misc/uClibc++/libxx/uClib++/iostream.cxx b/misc/uClibc++/libxx/uClibc++/iostream.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/iostream.cxx rename to misc/uClibc++/libxx/uClibc++/iostream.cxx diff --git a/misc/uClibc++/libxx/uClib++/istream.cxx b/misc/uClibc++/libxx/uClibc++/istream.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/istream.cxx rename to misc/uClibc++/libxx/uClibc++/istream.cxx diff --git a/misc/uClibc++/libxx/uClib++/iterator.cxx b/misc/uClibc++/libxx/uClibc++/iterator.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/iterator.cxx rename to misc/uClibc++/libxx/uClibc++/iterator.cxx diff --git a/misc/uClibc++/libxx/uClib++/limits.cxx b/misc/uClibc++/libxx/uClibc++/limits.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/limits.cxx rename to misc/uClibc++/libxx/uClibc++/limits.cxx diff --git a/misc/uClibc++/libxx/uClib++/list.cxx b/misc/uClibc++/libxx/uClibc++/list.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/list.cxx rename to misc/uClibc++/libxx/uClibc++/list.cxx diff --git a/misc/uClibc++/libxx/uClib++/locale.cxx b/misc/uClibc++/libxx/uClibc++/locale.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/locale.cxx rename to misc/uClibc++/libxx/uClibc++/locale.cxx diff --git a/misc/uClibc++/libxx/uClib++/map.cxx b/misc/uClibc++/libxx/uClibc++/map.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/map.cxx rename to misc/uClibc++/libxx/uClibc++/map.cxx diff --git a/misc/uClibc++/libxx/uClib++/new_handler.cxx b/misc/uClibc++/libxx/uClibc++/new_handler.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/new_handler.cxx rename to misc/uClibc++/libxx/uClibc++/new_handler.cxx diff --git a/misc/uClibc++/libxx/uClib++/new_op.cxx b/misc/uClibc++/libxx/uClibc++/new_op.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/new_op.cxx rename to misc/uClibc++/libxx/uClibc++/new_op.cxx diff --git a/misc/uClibc++/libxx/uClib++/new_opnt.cxx b/misc/uClibc++/libxx/uClibc++/new_opnt.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/new_opnt.cxx rename to misc/uClibc++/libxx/uClibc++/new_opnt.cxx diff --git a/misc/uClibc++/libxx/uClib++/new_opv.cxx b/misc/uClibc++/libxx/uClibc++/new_opv.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/new_opv.cxx rename to misc/uClibc++/libxx/uClibc++/new_opv.cxx diff --git a/misc/uClibc++/libxx/uClib++/new_opvnt.cxx b/misc/uClibc++/libxx/uClibc++/new_opvnt.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/new_opvnt.cxx rename to misc/uClibc++/libxx/uClibc++/new_opvnt.cxx diff --git a/misc/uClibc++/libxx/uClib++/numeric.cxx b/misc/uClibc++/libxx/uClibc++/numeric.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/numeric.cxx rename to misc/uClibc++/libxx/uClibc++/numeric.cxx diff --git a/misc/uClibc++/libxx/uClib++/ostream.cxx b/misc/uClibc++/libxx/uClibc++/ostream.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/ostream.cxx rename to misc/uClibc++/libxx/uClibc++/ostream.cxx diff --git a/misc/uClibc++/libxx/uClib++/queue.cxx b/misc/uClibc++/libxx/uClibc++/queue.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/queue.cxx rename to misc/uClibc++/libxx/uClibc++/queue.cxx diff --git a/misc/uClibc++/libxx/uClib++/set.cxx b/misc/uClibc++/libxx/uClibc++/set.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/set.cxx rename to misc/uClibc++/libxx/uClibc++/set.cxx diff --git a/misc/uClibc++/libxx/uClib++/sstream.cxx b/misc/uClibc++/libxx/uClibc++/sstream.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/sstream.cxx rename to misc/uClibc++/libxx/uClibc++/sstream.cxx diff --git a/misc/uClibc++/libxx/uClib++/stack.cxx b/misc/uClibc++/libxx/uClibc++/stack.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/stack.cxx rename to misc/uClibc++/libxx/uClibc++/stack.cxx diff --git a/misc/uClibc++/libxx/uClib++/stdexcept.cxx b/misc/uClibc++/libxx/uClibc++/stdexcept.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/stdexcept.cxx rename to misc/uClibc++/libxx/uClibc++/stdexcept.cxx diff --git a/misc/uClibc++/libxx/uClib++/streambuf.cxx b/misc/uClibc++/libxx/uClibc++/streambuf.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/streambuf.cxx rename to misc/uClibc++/libxx/uClibc++/streambuf.cxx diff --git a/misc/uClibc++/libxx/uClib++/string.cxx b/misc/uClibc++/libxx/uClibc++/string.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/string.cxx rename to misc/uClibc++/libxx/uClibc++/string.cxx diff --git a/misc/uClibc++/libxx/uClib++/support.cxx b/misc/uClibc++/libxx/uClibc++/support.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/support.cxx rename to misc/uClibc++/libxx/uClibc++/support.cxx diff --git a/misc/uClibc++/libxx/uClib++/typeinfo.cxx b/misc/uClibc++/libxx/uClibc++/typeinfo.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/typeinfo.cxx rename to misc/uClibc++/libxx/uClibc++/typeinfo.cxx diff --git a/misc/uClibc++/libxx/uClib++/utility.cxx b/misc/uClibc++/libxx/uClibc++/utility.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/utility.cxx rename to misc/uClibc++/libxx/uClibc++/utility.cxx diff --git a/misc/uClibc++/libxx/uClib++/valarray.cxx b/misc/uClibc++/libxx/uClibc++/valarray.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/valarray.cxx rename to misc/uClibc++/libxx/uClibc++/valarray.cxx diff --git a/misc/uClibc++/libxx/uClib++/vector.cxx b/misc/uClibc++/libxx/uClibc++/vector.cxx similarity index 100% rename from misc/uClibc++/libxx/uClib++/vector.cxx rename to misc/uClibc++/libxx/uClibc++/vector.cxx diff --git a/misc/uClibc++/uninstall.sh b/misc/uClibc++/uninstall.sh new file mode 100755 index 0000000000..ae73444498 --- /dev/null +++ b/misc/uClibc++/uninstall.sh @@ -0,0 +1,94 @@ +#!/bin/bash + +usage="USAGE: $0 " +special="include/features.h" + +# Get the single, required command line argument + +nuttx_path=$1 +if [ -z "${nuttx_path}" ]; then + echo "ERROR: Missing path to the NuttX directory" + echo $usage + exit 1 +fi + +# Lots of sanity checking so that we do not do anything too stupid + +if [ ! -d libxx ]; then + echo "ERROR: Directory libxx does not exist in this directory" + echo " Please CD into the misc/uClibc++ directory and try again" + echo $usage + exit 1 +fi + +if [ ! -d include ]; then + echo "ERROR: Directory include does not exist in this directory" + echo " Please CD into the misc/uClibc++ directory and try again" + echo $usage + exit 1 +fi + +if [ ! -d "${nuttx_path}" ]; then + echo "ERROR: Directory ${nuttx_path} does not exist" + echo $usage + exit 1 +fi + +if [ ! -f "${nuttx_path}/Makefile" ]; then + echo "ERROR: No Makefile in directory ${nuttx_path}" + echo $usage + exit 1 +fi + +libxx_srcdir=${nuttx_path}/libxx + +if [ ! -d "${libxx_srcdir}" ]; then + echo "ERROR: Directory ${libxx_srcdir} does not exist" + echo $usage + exit 1 +fi + +if [ ! -f "${libxx_srcdir}/Makefile" ]; then + echo "ERROR: No Makefile in directory ${libxx_srcdir}" + echo $usage + exit 1 +fi + +uclibc_srcdir=${libxx_srcdir}/uClibc++ + +if [ ! -d "${uclibc_srcdir}" ]; then + echo "ERROR: Directory ${uclibc_srcdir} already exists" + echo " uClibc++ is not installed" + exit 0 +fi + +nuttx_incdir=${nuttx_path}/include + +if [ ! -d "${nuttx_incdir}" ]; then + echo "ERROR: Directory ${nuttx_incdir} does not exist" + echo $usage + exit 1 +fi + +uclibc_incdir=${nuttx_incdir}/uClibc++ + +if [ ! -d "${uclibc_incdir}" ]; then + echo "ERROR: Directory ${uclibc_incdir} does not exist" + echo " uClibc++ is only partially installed" +fi + +echo "Removing uClibc++ in the NuttX source tree" + +rm -rf ${uclibc_incdir} || \ + { echo "ERROR: 'rm -rf ${uclibc_incdir}' failed"; exit 1; } + +rm -rf ${uclibc_srcdir} || \ + { echo "ERROR: 'rm -rf ${libxx_srcdir}' failed"; exit 1; } + +for file in $special; do + rm -f ${nuttx_path}/${special} || \ + { echo "ERROR: ' rm -f ${nuttx_path}/${special}' failed"; exit 1; } +done + +echo "Successfully uninstalled" +echo "" diff --git a/nuttx/configs/sim/cxxtest/defconfig b/nuttx/configs/sim/cxxtest/defconfig index 8e1fd8c57d..5797c8d4c8 100644 --- a/nuttx/configs/sim/cxxtest/defconfig +++ b/nuttx/configs/sim/cxxtest/defconfig @@ -28,7 +28,7 @@ CONFIG_NUTTX_NEWCONFIG=y # # CONFIG_ARCH_STDBOOL_H is not set # CONFIG_ARCH_MATH_H is not set -# CONFIG_ARCH_FLOAT_H is not set +CONFIG_ARCH_FLOAT_H=y # CONFIG_ARCH_STDARG_H is not set # @@ -262,7 +262,7 @@ CONFIG_STDIO_BUFFER_SIZE=1024 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" -# CONFIG_LIBM is not set +CONFIG_LIBM=y # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set From 3ceeb8f9f0486bcebcdb8b6c008f8cfde5920354 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 1 Nov 2012 13:45:30 +0000 Subject: [PATCH 058/206] Fix uClibc++ wstrlen bug git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5289 42af7a65-404d-4744-a932-0658087f49c3 --- misc/uClibc++/README.txt | 224 ++++++++++++--------- misc/uClibc++/include/uClibc++/char_traits | 2 +- misc/uClibc++/libxx/uClibc++/Make.defs | 4 +- nuttx/TODO | 10 +- 4 files changed, 128 insertions(+), 112 deletions(-) diff --git a/misc/uClibc++/README.txt b/misc/uClibc++/README.txt index 83b4c13f9c..6fedcb67fa 100755 --- a/misc/uClibc++/README.txt +++ b/misc/uClibc++/README.txt @@ -1,100 +1,124 @@ -misc/uClib++ README -^^^^^^^^^^^^^^^^^^^ - -This directory contains a version of the uClibc++ C++ library. This code -originates from http://cxx.uclibc.org/ and has been adapted for NuttX by the -RGMP team (http://rgmp.sourceforge.net/wiki/index.php/Main_Page). - -uClibc++ resides in the misc/ directory rather than in the main NuttX source -tree due to licensing issues: NuttX is licensed under the permissiv - modified BSD License; uClibc, on the other hand, islicensed under the - stricter GNU LGPL Version 3 license. - -Installation of uClibc++ -^^^^^^^^^^^^^^^^^^^^^^^^ - -If you wish to use uClibc++ with NuttX, you will be required to comply with -the licensing requires of the GNU LGPL Version 3 license. A simple -installation script is provided at misc/uClibc++/install.sh that can be used -to install the uClibc++ components into the NuttX source tree. - -The install script takes only a single arguement: The path to the nuttx -directory. If your directory structure is the same as the SVN structure -(with misc/ and nuttx/ at the same level), then uClibc++ can be installed -using this command executed from the misc/uClibc++ directory: - - ./install.sh ../../nuttx - -If you run the install.sh like this, then it will (1) make sure you -understand that you have tainted the NuttX BSD license with LGPLv3, and (2) -copy the uClibc++ sources files into nuttx/libxx/uClibc++, include/, and -include/uClibc++. - -Make.defs File Changes -^^^^^^^^^^^^^^^^^^^^^^ - -The new files that appear in nuttx/include/uClibc++ must be include-able -as system header files. So you will need to add 'isystem $(TOPDIR)/include/uClibc++' -to the ARCHINCLUDESXX definition in the NuttX Make.defs file, perhap like: - - -ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx - +ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx -isystem $(TOPDIR)/include/uClibc++ - -And, of course, you no long need to suppress exceptions or run-time typing: - - -ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions -fno-rtti - +ARCHCPUFLAGSXX = -fno-builtin - -Building NuttX with uClibc++ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -After installing uClibc++ in this way, no additional steps should be -required to build NuttX with the uClibc++ library incorporated: - - $ cd ../../nuttx - $ . ./setenv.sh - $ make - -Here is how it works: - -There is a new file called Make.defs in misc/uClibc/libxx/uClibc++. After -installation, it will reside at nuttx/libxx/uClibc++. The -nuttx/libxx/Makefile will (conditionally) include this Make.defs file: - --include uClibc++/Make.defs - -This Make.defs file, if present, will add the uClibc++ source files to the -build, add the uClibc++ subdirectory to the dependency list, and add the -uClibc++ subdirectory to the VPATH. That should, in principle, be all it -takes. - -Dependencies -^^^^^^^^^^^^ - -In order to build libxx (and hence libxx/uClibc++), CONFIG_HAVE_CXX must be -defined in your NuttX configuration file. - -The C++ runtime support is provided by GCC libgcc_eh.a and libsupc++.a -libraries. - -RGMP -^^^^ - -The target platform is RGMP X86, it is also updated for TLS support which is -needed by these two libraries. So application can also use TLS on RGMP NuttX -port. - -Command to compile and install RGMP: - - $ make - $ make install - $ /usr/rgmp/setup - $ exit - -Command to compile and run NUTTX: - - $ cd nuttx/tools - $ ./configure rgmp/x86/cxxtest - $ cd .. - $ make - $ rgmp_run +misc/uClib++ README +^^^^^^^^^^^^^^^^^^^ + +This directory contains a version of the uClibc++ C++ library. This code +originates from http://cxx.uclibc.org/ and has been adapted for NuttX by the +RGMP team (http://rgmp.sourceforge.net/wiki/index.php/Main_Page). + +uClibc++ resides in the misc/ directory rather than in the main NuttX source +tree due to licensing issues: NuttX is licensed under the permissiv + modified BSD License; uClibc, on the other hand, islicensed under the + stricter GNU LGPL Version 3 license. + +Installation of uClibc++ +^^^^^^^^^^^^^^^^^^^^^^^^ + +If you wish to use uClibc++ with NuttX, you will be required to comply with +the licensing requires of the GNU LGPL Version 3 license. A simple +installation script is provided at misc/uClibc++/install.sh that can be used +to install the uClibc++ components into the NuttX source tree. + +The install script takes only a single arguement: The path to the nuttx +directory. If your directory structure is the same as the SVN structure +(with misc/ and nuttx/ at the same level), then uClibc++ can be installed +using this command executed from the misc/uClibc++ directory: + + ./install.sh ../../nuttx + +If you run the install.sh like this, then it will (1) make sure you +understand that you have tainted the NuttX BSD license with LGPLv3, and (2) +copy the uClibc++ sources files into nuttx/libxx/uClibc++, include/, and +include/uClibc++. + +Dependencies +^^^^^^^^^^^^ + +1. The C++ runtime support is provided by GCC libgcc_eh.a and libsupc++.a + libraries. +2. NuttX C++ support +3. Math library +4. TLS support is currenly provided only under RGMP + +NuttX Configuration File Changes +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +In order to build libxx (and hence libxx/uClibc++), C++ support must be +enabled. The following must be defined in your NuttX configuration file. + + CONFIG_HAVE_CXX=y + +There are many ways to provide math library support (see nuttx/README.txt). +If you choose to use the NuttX math library, that is enabled as follows: + + + CONFIG_LIBM=y + +The math libraries depend on the float.h header file that is normally +provided by your tooltchain. A dummy (and probably wrong) fload.h file +can be installed by setting: + + CONFIG_ARCH_FLOAT_H=y + +Make.defs File Changes +^^^^^^^^^^^^^^^^^^^^^^ + +The new files that appear in nuttx/include/uClibc++ must be include-able +as system header files. So you will need to add 'isystem $(TOPDIR)/include/uClibc++' +to the ARCHINCLUDESXX definition in the NuttX Make.defs file, perhap like: + + -ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + +ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx -isystem $(TOPDIR)/include/uClibc++ + +And, of course, you no long need to suppress exceptions or run-time typing: + + -ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions -fno-rtti + +ARCHCPUFLAGSXX = -fno-builtin + + +I create the nuttx/configs/rgmp/x86/cxxtest/Make.def, add the two libs to EXTRA_LIBS to be linked +to NUTTX. The code. + +Building NuttX with uClibc++ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +After installing uClibc++ in this way, no additional steps should be +required to build NuttX with the uClibc++ library incorporated: + + $ cd ../../nuttx + $ . ./setenv.sh + $ make + +Here is how it works: + +There is a new file called Make.defs in misc/uClibc/libxx/uClibc++. After +installation, it will reside at nuttx/libxx/uClibc++. The +nuttx/libxx/Makefile will (conditionally) include this Make.defs file: + +-include uClibc++/Make.defs + +This Make.defs file, if present, will add the uClibc++ source files to the +build, add the uClibc++ subdirectory to the dependency list, and add the +uClibc++ subdirectory to the VPATH. That should, in principle, be all it +takes. + +RGMP +^^^^ + +The target platform is RGMP X86, it is also updated for TLS support which is +needed by these two libraries. So application can also use TLS on RGMP NuttX +port. + +Command to compile and install RGMP: + + $ make + $ make install + $ /usr/rgmp/setup + $ exit + +Command to compile and run NUTTX: + + $ cd nuttx/tools + $ ./configure rgmp/x86/cxxtest + $ cd .. + $ make + $ rgmp_run diff --git a/misc/uClibc++/include/uClibc++/char_traits b/misc/uClibc++/include/uClibc++/char_traits index 0f01d2e5d4..d09de41b6d 100644 --- a/misc/uClibc++/include/uClibc++/char_traits +++ b/misc/uClibc++/include/uClibc++/char_traits @@ -108,7 +108,7 @@ namespace std{ } inline static size_t length(const char_type* s){ - return wstrlen(s); + return strlen(s); } static const char_type* find(const char_type* s, int n, const char_type& a); diff --git a/misc/uClibc++/libxx/uClibc++/Make.defs b/misc/uClibc++/libxx/uClibc++/Make.defs index 38ae24a93e..9f1b2f51f4 100644 --- a/misc/uClibc++/libxx/uClibc++/Make.defs +++ b/misc/uClibc++/libxx/uClibc++/Make.defs @@ -38,7 +38,7 @@ CXXSRCS += algorithm.cxx associative_base.cxx bitset.cxx char_traits.cxx CXXSRCS += complex.cxx del_op.cxx del_opnt.cxx del_opv.cxx del_opvnt.cxx CXXSRCS += deque.cxx eh_alloc.cxx eh_globals.cxx exception.cxx -CXXSRCS += stream.cxx func_exception.cxx iomanip.cxx ios.cxx +CXXSRCS += fstream.cxx func_exception.cxx iomanip.cxx ios.cxx CXXSRCS += iostream.cxx istream.cxx iterator.cxx limits.cxx list.cxx CXXSRCS += locale.cxx map.cxx new_handler.cxx new_op.cxx new_opnt.cxx CXXSRCS += new_opv.cxx new_opvnt.cxx numeric.cxx ostream.cxx queue.cxx @@ -48,5 +48,5 @@ CXXSRCS += vector.cxx # Add the path to the uClibc++ subdirectory -DEPPATH += --dep-path . +DEPPATH += --dep-path uClibc++ VPATH += uClibc++ diff --git a/nuttx/TODO b/nuttx/TODO index c87137f642..e98aced905 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -32,7 +32,7 @@ nuttx/ (0) ARM/LPC43x (arch/arm/src/lpc43xx/) (3) ARM/STR71x (arch/arm/src/str71x/) (3) ARM/LM3S6918 (arch/arm/src/lm3s/) - (7) ARM/STM32 (arch/arm/src/stm32/) + (6) ARM/STM32 (arch/arm/src/stm32/) (3) AVR (arch/avr) (0) Intel x86 (arch/x86) (4) 8051 / MCS51 (arch/8051/) @@ -1417,14 +1417,6 @@ o ARM/STM32 (arch/arm/src/stm32/) Status: Open Priority: Low (I am not even sure if this is a problem yet). - Status: UNFINISHED STM32 F4 OTG FS HOST DRIVER - Description: A quick-n-dirty leverage of the the LPC17xx host driver was put into - the STM32 source to support development of the STM32 F4 OTG FS host - driver. It is non-functional and still waiting for STM32 F4 logic - to be added. Don't use it! - Status: Open - Priority: Low (unless you need a host driver). - o AVR (arch/avr) ^^^^^^^^^^^^^^ From a5b189950ec66b46f019fa3f3de54576f30e04d9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 1 Nov 2012 15:00:26 +0000 Subject: [PATCH 059/206] Add support for ferror(), feof(), and clearerr() git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5290 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 +- nuttx/include/nuttx/fs/fs.h | 15 ++++-- nuttx/include/stdio.h | 7 ++- nuttx/lib/stdio/Make.defs | 34 ++++++++----- nuttx/lib/stdio/lib_clearerr.c | 69 ++++++++++++++++++++++++++ nuttx/lib/stdio/lib_feof.c | 77 +++++++++++++++++++++++++++++ nuttx/lib/stdio/lib_ferror.c | 90 ++++++++++++++++++++++++++++++++++ nuttx/lib/stdio/lib_libfread.c | 31 ++++++++++-- 8 files changed, 307 insertions(+), 21 deletions(-) create mode 100644 nuttx/lib/stdio/lib_clearerr.c create mode 100644 nuttx/lib/stdio/lib_feof.c create mode 100644 nuttx/lib/stdio/lib_ferror.c diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index d4d840243b..e14cac1e2a 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3541,4 +3541,7 @@ * configs/sim/ostest: Converted to use the mconfig configuration tool. * configs/sim/cxxtest: New test that will be used to verify the uClibc++ port (eventually). - + * include/nuttx/fs/fs.h, lib/stdio/lib_libfread.c, lib_ferror.c, + lib_feof.c, and lib_clearerr.c: Add support for ferror(), feof(), + and clearerror(). ferror() support is bogus at the moment (it + is equivalent to !feof()); the others should be good. diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h index 81f81622f6..aab4ae4be8 100644 --- a/nuttx/include/nuttx/fs/fs.h +++ b/nuttx/include/nuttx/fs/fs.h @@ -51,6 +51,10 @@ /**************************************************************************** * Definitions ****************************************************************************/ +/* Stream flags for the fs_flags field of in struct file_struct */ + +#define __FS_FLAG_EOF (1 << 0) /* EOF detected by a read operation */ +#define __FS_FLAG_ERROR (1 << 1) /* Error detected by any operation */ /**************************************************************************** * Type Definitions @@ -270,11 +274,6 @@ struct filelist struct file_struct { int fs_filedes; /* File descriptor associated with stream */ - uint16_t fs_oflags; /* Open mode flags */ -#if CONFIG_NUNGET_CHARS > 0 - uint8_t fs_nungotten; /* The number of characters buffered for ungetc */ - unsigned char fs_ungotten[CONFIG_NUNGET_CHARS]; -#endif #if CONFIG_STDIO_BUFFER_SIZE > 0 sem_t fs_sem; /* For thread safety */ pid_t fs_holder; /* Holder of sem */ @@ -283,6 +282,12 @@ struct file_struct FAR unsigned char *fs_bufend; /* Pointer to 1 past end of buffer */ FAR unsigned char *fs_bufpos; /* Current position in buffer */ FAR unsigned char *fs_bufread; /* Pointer to 1 past last buffered read char. */ +#endif + uint16_t fs_oflags; /* Open mode flags */ + uint8_t fs_flags; /* Stream flags */ +#if CONFIG_NUNGET_CHARS > 0 + uint8_t fs_nungotten; /* The number of characters buffered for ungetc */ + unsigned char fs_ungotten[CONFIG_NUNGET_CHARS]; #endif }; diff --git a/nuttx/include/stdio.h b/nuttx/include/stdio.h index e9218046c5..8796861a40 100644 --- a/nuttx/include/stdio.h +++ b/nuttx/include/stdio.h @@ -102,6 +102,9 @@ extern "C" { /* ANSI-like File System Interfaces */ +/* Operations on streams (FILE) */ + +EXTERN void clearerr(register FILE *stream); EXTERN int fclose(FAR FILE *stream); EXTERN int fflush(FAR FILE *stream); EXTERN int feof(FAR FILE *stream); @@ -120,6 +123,9 @@ EXTERN int fsetpos(FAR FILE *stream, FAR fpos_t *pos); EXTERN long ftell(FAR FILE *stream); EXTERN size_t fwrite(FAR const void *ptr, size_t size, size_t n_items, FAR FILE *stream); EXTERN FAR char *gets(FAR char *s); +EXTERN int ungetc(int c, FAR FILE *stream); + +/* Operations on the stdout stream, buffers, paths, and the whole printf-family */ EXTERN int printf(const char *format, ...); EXTERN int puts(FAR const char *s); @@ -130,7 +136,6 @@ EXTERN int snprintf(FAR char *buf, size_t size, const char *format, ...); EXTERN int sscanf(const char *buf, const char *fmt, ...); EXTERN void perror(FAR const char *s); -EXTERN int ungetc(int c, FAR FILE *stream); EXTERN int vprintf(FAR const char *format, va_list ap); EXTERN int vfprintf(FAR FILE *stream, const char *format, va_list ap); EXTERN int vsprintf(FAR char *buf, const char *format, va_list ap); diff --git a/nuttx/lib/stdio/Make.defs b/nuttx/lib/stdio/Make.defs index f88a5edd9e..e4ee5e9699 100644 --- a/nuttx/lib/stdio/Make.defs +++ b/nuttx/lib/stdio/Make.defs @@ -34,27 +34,39 @@ ############################################################################ # Add the stdio C files to the build +# This first group of C files do not depend on having file descriptors or +# C streams. CSRCS += lib_fileno.c lib_printf.c lib_rawprintf.c lib_lowprintf.c \ - lib_sprintf.c lib_asprintf.c lib_snprintf.c lib_libsprintf.c \ - lib_vsprintf.c lib_avsprintf.c lib_vsnprintf.c lib_libvsprintf.c \ - lib_meminstream.c lib_memoutstream.c lib_lowinstream.c \ - lib_lowoutstream.c lib_zeroinstream.c lib_nullinstream.c \ - lib_nulloutstream.c lib_sscanf.c + lib_sprintf.c lib_asprintf.c lib_snprintf.c lib_libsprintf.c \ + lib_vsprintf.c lib_avsprintf.c lib_vsnprintf.c lib_libvsprintf.c \ + lib_meminstream.c lib_memoutstream.c lib_lowinstream.c \ + lib_lowoutstream.c lib_zeroinstream.c lib_nullinstream.c \ + lib_nulloutstream.c lib_sscanf.c + +# The remaining sources files depend upon file descriptors ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) + CSRCS += lib_rawinstream.c lib_rawoutstream.c + +# And these depend upon both file descriptors and C streams + ifneq ($(CONFIG_NFILE_STREAMS),0) + CSRCS += lib_fopen.c lib_fclose.c lib_fread.c lib_libfread.c lib_fseek.c \ - lib_ftell.c lib_fsetpos.c lib_fgetpos.c lib_fgetc.c lib_fgets.c \ - lib_gets.c lib_fwrite.c lib_libfwrite.c lib_fflush.c \ - lib_libflushall.c lib_libfflush.c lib_rdflush.c lib_wrflush.c \ - lib_fputc.c lib_puts.c lib_fputs.c lib_ungetc.c lib_vprintf.c \ - lib_fprintf.c lib_vfprintf.c lib_stdinstream.c lib_stdoutstream.c \ - lib_perror.c + lib_ftell.c lib_fsetpos.c lib_fgetpos.c lib_fgetc.c lib_fgets.c \ + lib_gets.c lib_fwrite.c lib_libfwrite.c lib_fflush.c \ + lib_libflushall.c lib_libfflush.c lib_rdflush.c lib_wrflush.c \ + lib_fputc.c lib_puts.c lib_fputs.c lib_ungetc.c lib_vprintf.c \ + lib_fprintf.c lib_vfprintf.c lib_stdinstream.c lib_stdoutstream.c \ + lib_perror.c lib_feof.c lib_ferror.c lib_clearerr.c + endif endif +# Other support that depends on specific, configured features. + ifeq ($(CONFIG_SYSLOG),y) CSRCS += lib_syslogstream.c endif diff --git a/nuttx/lib/stdio/lib_clearerr.c b/nuttx/lib/stdio/lib_clearerr.c new file mode 100644 index 0000000000..7f7ded5bb4 --- /dev/null +++ b/nuttx/lib/stdio/lib_clearerr.c @@ -0,0 +1,69 @@ +/**************************************************************************** + * lib/stdio/lib_clearerr.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#if CONFIG_NFILE_STREAMS > 0 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: Functions + * + * Description: + * Clear any end-of-file or error conditions. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void clearerr(FILE *stream) +{ + stream->fs_flags = 0; +} +#endif /* CONFIG_NFILE_STREAMS */ + diff --git a/nuttx/lib/stdio/lib_feof.c b/nuttx/lib/stdio/lib_feof.c new file mode 100644 index 0000000000..e44c6a3c92 --- /dev/null +++ b/nuttx/lib/stdio/lib_feof.c @@ -0,0 +1,77 @@ +/**************************************************************************** + * lib/stdio/lib_feof.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#if CONFIG_NFILE_STREAMS > 0 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: feof + * + * Description: + * The feof() function shall test if the currently file pointer for the + * stream is at the end of file. + * + * Returned Value: + * This function will return non-zero if the the file pointer is positioned + * at the end of file. + * + ****************************************************************************/ + +int feof(FILE *stream) +{ + /* If the end-of-file condition is encountered by any of the C-buffered + * I/O functions that perform read operations, they should set the + * __FS_FLAG_EOF in the fs_flags field of struct file_struct. + */ + + return (stream->fs_flags & __FS_FLAG_EOF) != 0; +} + +#endif /* CONFIG_NFILE_STREAMS */ + diff --git a/nuttx/lib/stdio/lib_ferror.c b/nuttx/lib/stdio/lib_ferror.c new file mode 100644 index 0000000000..4ad7d8cfca --- /dev/null +++ b/nuttx/lib/stdio/lib_ferror.c @@ -0,0 +1,90 @@ +/**************************************************************************** + * lib/stdio/lib_ferror.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#if CONFIG_NFILE_STREAMS > 0 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: ferror + * + * Description: + * This function will test if the last operation resulted in an eror. This + * is used to disambiguate EOF and error conditions. + * + * Return Value: + * A non-zero value is returned to indicate the error condition. + * + ****************************************************************************/ + +int ferror(FILE *stream) +{ +#if 0 + /* If an error is encountered by any of the C-buffered I/O functions, they + * should set the __FS_FLAG_ERROR in the fs_flags field of struct + * file_struct. + */ + + return (stream->fs_flags & __FS_FLAG_ERROR) != 0; +#else + /* However, nothing currenlty sets the __FS_FLAG_ERROR flag (that is a job + * for another day). The __FS_FLAG_EOF is set by operations that perform + * read operations. Since ferror() is probably only called to disambiguate + * the meaning of other functions that return EOF, to indicate either EOF or + * an error, just testing for not EOF is probably sufficient for now. + * + * This approach would not work if ferror() is called in other contexts. In + * those cases, ferror() will always report an error. + */ + + return (stream->fs_flags & __FS_FLAG_EOF) == 0; +#endif +} + +#endif /* CONFIG_NFILE_STREAMS */ + diff --git a/nuttx/lib/stdio/lib_libfread.c b/nuttx/lib/stdio/lib_libfread.c index 03b47eda66..5585acbaea 100644 --- a/nuttx/lib/stdio/lib_libfread.c +++ b/nuttx/lib/stdio/lib_libfread.c @@ -187,7 +187,10 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) } else if (bytes_read == 0) { - /* We are at the end of the file */ + /* We are at the end of the file. But we may already + * have buffered data. In that case, we will report + * the EOF indication later. + */ goto shortread; } @@ -232,7 +235,10 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) } else if (bytes_read == 0) { - /* We are at the end of the file */ + /* We are at the end of the file. But we may already + * have buffered data. In that case, we will report + * the EOF indication later. + */ goto shortread; } @@ -261,6 +267,11 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) } else if (bytes_read == 0) { + /* We are at the end of the file. But we may already + * have buffered data. In that case, we will report + * the EOF indication later. + */ + break; } else @@ -270,12 +281,26 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) } } #endif - /* Here after a successful (but perhaps short) read */ + /* Here after a successful (but perhaps short) read */ #if CONFIG_STDIO_BUFFER_SIZE > 0 shortread: #endif bytes_read = dest - (unsigned char*)ptr; + + /* Set or clear the EOF indicator. If we get here because of a + * short read and the total number of* bytes read is zero, then + * we must be at the end-of-file. + */ + + if (bytes_read > 0) + { + stream->fs_flags &= ~__FS_FLAG_EOF; + } + else + { + stream->fs_flags |= __FS_FLAG_EOF; + } } lib_give_semaphore(stream); From 1214744afca8851c7888b6b3f2bb8b47c5a815e2 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 1 Nov 2012 15:31:10 +0000 Subject: [PATCH 060/206] ST32F4Discovery board.h patches from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5291 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 3 +++ nuttx/configs/stm32f4discovery/include/board.h | 8 ++++---- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index e14cac1e2a..40ff0a51b7 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3545,3 +3545,6 @@ lib_feof.c, and lib_clearerr.c: Add support for ferror(), feof(), and clearerror(). ferror() support is bogus at the moment (it is equivalent to !feof()); the others should be good. + * configs/stm32f4discovery/include/board.h: Correct timer 2-7 + base frequency (provided by Freddie Chopin). + diff --git a/nuttx/configs/stm32f4discovery/include/board.h b/nuttx/configs/stm32f4discovery/include/board.h index 9b866d56fa..01ae56b300 100644 --- a/nuttx/configs/stm32f4discovery/include/board.h +++ b/nuttx/configs/stm32f4discovery/include/board.h @@ -66,7 +66,7 @@ * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) - * HSE Frequency(Hz) : 25000000 (STM32_BOARD_XTAL) + * HSE Frequency(Hz) : 8000000 (STM32_BOARD_XTAL) * PLLM : 8 (STM32_PLLCFG_PLLM) * PLLN : 336 (STM32_PLLCFG_PLLN) * PLLP : 2 (STM32_PLLCFG_PLLP) @@ -82,7 +82,7 @@ /* HSI - 16 MHz RC factory-trimmed * LSI - 32 KHz RC - * HSE - On-board crystal frequency is 25MHz + * HSE - On-board crystal frequency is 8MHz * LSE - 32.768 kHz */ @@ -97,7 +97,7 @@ * * PLL source is HSE * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN - * = (25,000,000 / 25) * 336 + * = (8,000,000 / 8) * 336 * = 336,000,000 * SYSCLK = PLL_VCO / PLLP * = 336,000,000 / 2 = 168,000,000 @@ -155,7 +155,7 @@ */ #define STM32_TIM18_FREQUENCY STM32_HCLK_FREQUENCY -#define STM32_TIM27_FREQUENCY STM32_HCLK_FREQUENCY +#define STM32_TIM27_FREQUENCY (STM32_HCLK_FREQUENCY/2) /* LED definitions ******************************************************************/ /* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any From eb26187767da1e752bfdc6571ccb70e3f84fd954 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 1 Nov 2012 16:50:53 +0000 Subject: [PATCH 061/206] Add __cxa_atexit(); atexit() is now built on top of on_exit() git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5292 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 8 +- nuttx/configs/sim/cxxtest/defconfig | 3 +- nuttx/include/nuttx/sched.h | 6 +- nuttx/libxx/Makefile | 6 +- nuttx/libxx/libxx_cxa_atexit.cxx | 143 ++++++++++++++++++++++++++++ nuttx/libxx/libxx_eabi_atexit.cxx | 23 ++--- nuttx/libxx/libxx_internal.hxx | 67 +++++++++++++ nuttx/sched/Kconfig | 11 ++- nuttx/sched/atexit.c | 16 +++- nuttx/sched/on_exit.c | 5 +- nuttx/sched/task_exithook.c | 4 +- 11 files changed, 263 insertions(+), 29 deletions(-) create mode 100644 nuttx/libxx/libxx_cxa_atexit.cxx create mode 100644 nuttx/libxx/libxx_internal.hxx diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 40ff0a51b7..6fa9ffbfed 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3547,4 +3547,10 @@ is equivalent to !feof()); the others should be good. * configs/stm32f4discovery/include/board.h: Correct timer 2-7 base frequency (provided by Freddie Chopin). - + * include/nuttx/sched.h, sched/atexit.c, and sched/task_deletehook.c: + If both atexit() and on_exit() are enabled, then implement atexit() + as just a special caseof on_exit(). This assumes that the ABI can + handle receipt of more call parameters than the receiving function + expects. That is usually the case if parameters are passed in + registers. + * libxx/libxx_cxa_atexit(): Implements __cxa_atexit() diff --git a/nuttx/configs/sim/cxxtest/defconfig b/nuttx/configs/sim/cxxtest/defconfig index 5797c8d4c8..d7f5efff5b 100644 --- a/nuttx/configs/sim/cxxtest/defconfig +++ b/nuttx/configs/sim/cxxtest/defconfig @@ -136,7 +136,8 @@ CONFIG_SDCLONE_DISABLE=y # CONFIG_SCHED_WORKQUEUE is not set # CONFIG_SCHED_WAITPID is not set # CONFIG_SCHED_ATEXIT is not set -# CONFIG_SCHED_ONEXIT is not set +CONFIG_SCHED_ONEXIT=y +CONFIG_SCHED_ONEXIT_MAX=4 CONFIG_USER_ENTRYPOINT="cxxtest_main" CONFIG_DISABLE_OS_API=y # CONFIG_DISABLE_CLOCK is not set diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 241af6210c..172f469011 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -138,11 +138,11 @@ typedef union entry_u entry_t; */ #ifdef CONFIG_SCHED_ATEXIT -typedef void (*atexitfunc_t)(void); +typedef CODE void (*atexitfunc_t)(void); #endif #ifdef CONFIG_SCHED_ONEXIT -typedef void (*onexitfunc_t)(int exitcode, FAR void *arg); +typedef CODE void (*onexitfunc_t)(int exitcode, FAR void *arg); #endif /* POSIX Message queue */ @@ -189,7 +189,7 @@ struct _TCB start_t start; /* Thread start function */ entry_t entry; /* Entry Point into the thread */ -#ifdef CONFIG_SCHED_ATEXIT +#if defined(CONFIG_SCHED_ATEXIT) && !defined(CONFIG_SCHED_ONEXIT) # if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1 atexitfunc_t atexitfunc[CONFIG_SCHED_ATEXIT_MAX]; # else diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile index 922c8d825c..bc8c5012ef 100644 --- a/nuttx/libxx/Makefile +++ b/nuttx/libxx/Makefile @@ -39,8 +39,10 @@ ASRCS = CSRCS = -CXXSRCS = libxx_cxapurevirtual.cxx libxx_delete.cxx libxx_deletea.cxx -CXXSRCS += libxx_eabi_atexit.cxx libxx_new.cxx libxx_newa.cxx + +CXXSRCS = libxx_cxapurevirtual.cxx libxx_delete.cxx libxx_deletea.cxx +CXXSRCS += libxx_eabi_atexit.cxx libxx_cxa_atexit.cxx libxx_new.cxx +CXXSRCS += libxx_newa.cxx # Paths diff --git a/nuttx/libxx/libxx_cxa_atexit.cxx b/nuttx/libxx/libxx_cxa_atexit.cxx new file mode 100644 index 0000000000..7e6d00a377 --- /dev/null +++ b/nuttx/libxx/libxx_cxa_atexit.cxx @@ -0,0 +1,143 @@ +//*************************************************************************** +// libxx/libxx_eabi_atexit.cxx +// +// 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. +// +//*************************************************************************** + +//*************************************************************************** +// Included Files +//*************************************************************************** + +#include + +#include +#include + +#include "libxx_internal.hxx" + +//*************************************************************************** +// Pre-processor Definitions +//*************************************************************************** + +//*************************************************************************** +// Private Types +//*************************************************************************** + +struct __cxa_atexit_s +{ + __cxa_exitfunc_t func; + FAR void *arg; +}; + +//*************************************************************************** +// Private Data +//*************************************************************************** + +extern "C" +{ + //************************************************************************* + // Public Data + //************************************************************************* + + FAR void *__dso_handle = NULL; + + //************************************************************************* + // Private Functions + //************************************************************************* + + //************************************************************************* + // Name: __cxa_callback + // + // Description: + // This is really just an "adaptor" function that matches the form of + // the __cxa_exitfunc_t to an onexitfunc_t using an allocated structure + // to marshall the call parameters. + // + //************************************************************************* + +#if CONFIG_SCHED_ONEXIT + static void __cxa_callback(int exitcode, FAR void *arg) + { + FAR struct __cxa_atexit_s *alloc = (FAR struct __cxa_atexit_s *)arg; + DEBUGASSERT(alloc && alloc->func); + + alloc->func(alloc->arg); + free(alloc); + } +#endif + + //************************************************************************* + // Public Functions + //************************************************************************* + + //************************************************************************* + // Name: __cxa_atexit + // + // Description: + // __cxa_atexit() registers a destructor function to be called by exit(). + // On a call to exit(), the registered functions should be called with + // the single argument 'arg'. Destructor functions shall always be + // called in the reverse order to their registration (i.e. the most + // recently registered function shall be called first), + // + // If shared libraries were supported, the callbacks should be invoked + // when the shared library is unloaded as well. + // + // Reference: + // Linux base + // + //************************************************************************* + + int __cxa_atexit(__cxa_exitfunc_t func, FAR void *arg, FAR void *dso_handle) + { +#if CONFIG_SCHED_ONEXIT + // Allocate memory to hold the marshaled __cxa_exitfunc_t call + // information. + + FAR struct __cxa_atexit_s *alloc = + (FAR struct __cxa_atexit_s *)malloc(sizeof(struct __cxa_atexit_s)); + + if (alloc) + { + // Register the function to be called when the task/thread exists. + + return on_exit(__cxa_callback, alloc); + } + else +#endif + { + // What else can we do? + + return 0; + } + } +} diff --git a/nuttx/libxx/libxx_eabi_atexit.cxx b/nuttx/libxx/libxx_eabi_atexit.cxx index aa0ff6956c..25f8306a84 100644 --- a/nuttx/libxx/libxx_eabi_atexit.cxx +++ b/nuttx/libxx/libxx_eabi_atexit.cxx @@ -40,26 +40,22 @@ #include #include +#include "libxx_internal.hxx" + //*************************************************************************** -// Definitions +// Pre-processor Definitions //*************************************************************************** //*************************************************************************** // Private Data //*************************************************************************** +//*************************************************************************** +// Public Functions +//*************************************************************************** + extern "C" { - //************************************************************************* - // Public Data - //************************************************************************* - - void *__dso_handle = NULL; - - //************************************************************************* - // Public Functions - //************************************************************************* - //************************************************************************* // Name: __aeabi_atexit // @@ -75,9 +71,8 @@ extern "C" // //************************************************************************* - int __aeabi_atexit(void* object, void (*destroyer)(void*), void *dso_handle) + int __aeabi_atexit(FAR void *object, __cxa_exitfunc_t func, FAR void *dso_handle) { - //return __cxa_atexit(destroyer, object, dso_handle); // 0 ? OK; non-0 ? failed } - return 0; + return __cxa_atexit(func, object, dso_handle); // 0 ? OK; non-0 ? failed } } diff --git a/nuttx/libxx/libxx_internal.hxx b/nuttx/libxx/libxx_internal.hxx new file mode 100644 index 0000000000..fe84c763ed --- /dev/null +++ b/nuttx/libxx/libxx_internal.hxx @@ -0,0 +1,67 @@ +//*************************************************************************** +// lib/libxx_internal.h +// +// 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. +// +//*************************************************************************** + +#ifndef __LIBXX_LIBXX_INTERNAL_HXX +#define __LIBXX_LIBXX_INTERNAL_HXX + +//*************************************************************************** +// Included Files +//*************************************************************************** + +#include + +//*************************************************************************** +// Definitions +//*************************************************************************** + +//*************************************************************************** +// Public Types +//***************************************************************************/ + +typedef CODE void (*__cxa_exitfunc_t)(void *arg); + +//*************************************************************************** +// Public Variables +//*************************************************************************** + +extern "C" FAR void *__dso_handle; + +//*************************************************************************** +// Public Function Prototypes +//*************************************************************************** + +extern "C" int __cxa_atexit(__cxa_exitfunc_t func, void *arg, void *dso_handle); + +#endif // __LIBXX_LIBXX_INTERNAL_HXX diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig index 4f7149595e..4a3e877454 100644 --- a/nuttx/sched/Kconfig +++ b/nuttx/sched/Kconfig @@ -214,12 +214,17 @@ config SCHED_ATEXIT config SCHED_ATEXIT_MAX int "Max number of atexit() functions" default 1 - depends on SCHED_ATEXIT + depends on SCHED_ATEXIT && !SCHED_ONEXIT ---help--- By default if SCHED_ATEXIT is selected, only a single atexit() function is supported. That number can be increased by defined this setting to the number that you require. + If both SCHED_ONEXIT and SCHED_ATEXIT are selected, then atexit() is built + on top of the on_exit() implementation. In that case, SCHED_ONEXIT_MAX + determines the size of the combined number of atexit(0) and on_exit calls + and SCHED_ATEXIT_MAX is not used. + config SCHED_ONEXIT bool "Enable on_exit() API" default n @@ -235,6 +240,10 @@ config SCHED_ONEXIT_MAX is supported. That number can be increased by defined this setting to the number that you require. + If both SCHED_ONEXIT and SCHED_ATEXIT are selected, then atexit() is built + on top of the on_exit() implementation. In that case, SCHED_ONEXIT_MAX + determines the size of the combined number of atexit(0) and on_exit calls. + config USER_ENTRYPOINT string "Application entry point" default "user_start" diff --git a/nuttx/sched/atexit.c b/nuttx/sched/atexit.c index f7d81bec20..b0559b01be 100644 --- a/nuttx/sched/atexit.c +++ b/nuttx/sched/atexit.c @@ -96,8 +96,13 @@ * CONFIG_SCHED_ATEXIT_MAX defines a larger number. * 2. atexit functions are not inherited when a new task is * created. + * 3. If both SCHED_ONEXIT and SCHED_ATEXIT are selected, then atexit() + * is built on top of the on_exit() implementation. In that case, + * CONFIG_SCHED_ONEXIT_MAX determines the size of the combined + * number of atexit(0) and on_exit calls and SCHED_ATEXIT_MAX is + * not used. * - * Parameters: + * Input Parameters: * func - A pointer to the function to be called when the task exits. * * Return Value: @@ -107,7 +112,14 @@ int atexit(void (*func)(void)) { -#if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1 +#if defined(CONFIG_SCHED_ONEXIT) + /* atexit is equivalent to on_exit() with no argument (Assuming that the ABI + * can handle a callback function that recieves more parameters than it expects). + */ + + return on_exit(onexitfunc_t func, NULL); + +#elif defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1 _TCB *tcb = (_TCB*)g_readytorun.head; int index; int ret = ERROR; diff --git a/nuttx/sched/on_exit.c b/nuttx/sched/on_exit.c index 5b8be5cd10..19a4f91960 100644 --- a/nuttx/sched/on_exit.c +++ b/nuttx/sched/on_exit.c @@ -117,7 +117,7 @@ int on_exit(CODE void (*func)(int, FAR void *), FAR void *arg) #if defined(CONFIG_SCHED_ONEXIT_MAX) && CONFIG_SCHED_ONEXIT_MAX > 1 _TCB *tcb = (_TCB*)g_readytorun.head; int index; - int ret = ERROR; + int ret = ENOSPC; /* The following must be atomic */ @@ -131,7 +131,6 @@ int on_exit(CODE void (*func)(int, FAR void *), FAR void *arg) * indices. */ - available = -1; for (index = 0; index < CONFIG_SCHED_ONEXIT_MAX; index++) { if (!tcb->onexitfunc[index]) @@ -149,7 +148,7 @@ int on_exit(CODE void (*func)(int, FAR void *), FAR void *arg) return ret; #else _TCB *tcb = (_TCB*)g_readytorun.head; - int ret = ERROR; + int ret = ENOSPC; /* The following must be atomic */ diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index e94476f2a7..6f52ef739e 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -81,8 +81,8 @@ * Call any registerd atexit function(s) * ****************************************************************************/ - -#ifdef CONFIG_SCHED_ATEXIT + +#if defined(CONFIG_SCHED_ATEXIT) && !defined(CONFIG_SCHED_ONEXIT) static inline void task_atexit(FAR _TCB *tcb) { #if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1 From f5776dec9fdc3b655b7f424340d613664a65e2ab Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 1 Nov 2012 21:08:56 +0000 Subject: [PATCH 062/206] uClibc++ compiles... but it is a long way from linking git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5293 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/cxxtest/cxxtest_main.cxx | 4 + misc/uClibc++/compare.sh | 114 ++++++++++++ .../include/uClibc++/basic_definitions | 22 +-- misc/uClibc++/include/uClibc++/fstream | 10 +- misc/uClibc++/include/uClibc++/ios | 4 +- misc/uClibc++/include/uClibc++/istream | 6 +- .../uClibc++/include/uClibc++/istream_helpers | 4 +- misc/uClibc++/include/uClibc++/stdexcept | 5 +- misc/uClibc++/include/uClibc++/string | 1 + misc/uClibc++/include/uClibc++/support | 165 ------------------ .../include/uClibc++/system_configuration.h | 35 ++-- misc/uClibc++/include/uClibc++/unwind-cxx.h | 42 +++-- misc/uClibc++/install.sh | 9 + misc/uClibc++/libxx/uClibc++/Make.defs | 3 +- misc/uClibc++/libxx/uClibc++/eh_alloc.cxx | 128 +++++++++----- misc/uClibc++/libxx/uClibc++/exception.cxx | 63 +++---- .../libxx/uClibc++/func_exception.cxx | 110 +++++++----- misc/uClibc++/libxx/uClibc++/istream.cxx | 4 +- misc/uClibc++/libxx/uClibc++/stdexcept.cxx | 2 +- misc/uClibc++/libxx/uClibc++/support.cxx | 53 ------ nuttx/configs/sim/cxxtest/defconfig | 3 + nuttx/include/cxx/cstdbool | 9 + nuttx/include/cxx/cstdio | 12 +- nuttx/include/nuttx/compiler.h | 6 +- nuttx/libxx/Kconfig | 27 +++ nuttx/libxx/Makefile | 11 +- nuttx/libxx/README.txt | 5 + nuttx/libxx/libxx_cxa_atexit.cxx | 3 + 28 files changed, 446 insertions(+), 414 deletions(-) create mode 100755 misc/uClibc++/compare.sh delete mode 100644 misc/uClibc++/include/uClibc++/support delete mode 100644 misc/uClibc++/libxx/uClibc++/support.cxx diff --git a/apps/examples/cxxtest/cxxtest_main.cxx b/apps/examples/cxxtest/cxxtest_main.cxx index c0d4bfbd1f..70d54109f5 100644 --- a/apps/examples/cxxtest/cxxtest_main.cxx +++ b/apps/examples/cxxtest/cxxtest_main.cxx @@ -179,6 +179,7 @@ static void test_rtti(void) // Name: test_exception //***************************************************************************/ +#ifdef CONFIG_UCLIBCXX_EXCEPTION static void test_exception(void) { cout << "test exception==========================" << endl; @@ -192,6 +193,7 @@ static void test_exception(void) cout << "Catch exception: " << e.what() << endl; } } +#endif //*************************************************************************** // Public Functions @@ -213,7 +215,9 @@ int cxxtest_main(int argc, char *argv[]) test_iostream(); test_stl(); test_rtti(); +#ifdef CONFIG_UCLIBCXX_EXCEPTION test_exception(); +#endif return 0; } diff --git a/misc/uClibc++/compare.sh b/misc/uClibc++/compare.sh new file mode 100755 index 0000000000..ead5e5d696 --- /dev/null +++ b/misc/uClibc++/compare.sh @@ -0,0 +1,114 @@ +#!/bin/bash + +usage="USAGE: $0 " +special="include/features.h" + +# Get the single, required command line argument + +nuttx_path=$1 +if [ -z "${nuttx_path}" ]; then + echo "ERROR: Missing path to the NuttX directory" + echo $usage + exit 1 +fi + +# Lots of sanity checking so that we do not do anything too stupid + +if [ ! -d libxx ]; then + echo "ERROR: Directory libxx does not exist in this directory" + echo " Please CD into the misc/uClibc++ directory and try again" + echo $usage + exit 1 +fi + +if [ ! -d include ]; then + echo "ERROR: Directory include does not exist in this directory" + echo " Please CD into the misc/uClibc++ directory and try again" + echo $usage + exit 1 +fi + +if [ ! -d "${nuttx_path}" ]; then + echo "ERROR: Directory ${nuttx_path} does not exist" + echo $usage + exit 1 +fi + +if [ ! -f "${nuttx_path}/Makefile" ]; then + echo "ERROR: No Makefile in directory ${nuttx_path}" + echo $usage + exit 1 +fi + +libxx_srcdir=${nuttx_path}/libxx + +if [ ! -d "${libxx_srcdir}" ]; then + echo "ERROR: Directory ${libxx_srcdir} does not exist" + echo $usage + exit 1 +fi + +if [ ! -f "${libxx_srcdir}/Makefile" ]; then + echo "ERROR: No Makefile in directory ${libxx_srcdir}" + echo $usage + exit 1 +fi + +uclibc_srcdir=${libxx_srcdir}/uClibc++ + +if [ ! -d "${uclibc_srcdir}" ]; then + echo "ERROR: Directory ${uclibc_srcdir} does not exiss" + echo " uClibc++ has not been installed" + echo $usage + exit 1 +fi + +nuttx_incdir=${nuttx_path}/include + +if [ ! -d "${nuttx_incdir}" ]; then + echo "ERROR: Directory ${nuttx_incdir} does not exist" + echo $usage + exit 1 +fi + +nuttxcxx_incdir=${nuttx_incdir}/cxx + +if [ ! -d "${nuttxcxx_incdir}" ]; then + echo "ERROR: Directory ${nuttxcxx_incdir} does not exist" + echo $usage + exit 1 +fi + +uclibc_incdir=${nuttx_incdir}/uClibc++ + +if [ ! -d "${uclibc_incdir}" ]; then + echo "ERROR: Directory ${uclibc_incdir} does not exist" + echo " uClibc++ has not been installed" + echo $usage + exit 1 +fi + +echo "##### Comparing libxx" + +filelist=`find libxx -type f | fgrep -v '.svn'` + +for file in $filelist; do + diff -u $file ${nuttx_path}/${file} +done + +echo "" +echo "##### Comparing include" + +filelist=`find include -type f | fgrep -v '.svn'` + +for file in $filelist; do + diff -u $file ${nuttx_path}/${file} +done + +echo "" +echo "##### Comparing other files" + +for file in $speical; do + diff -u $file ${nuttx_path}/${file} +done + diff --git a/misc/uClibc++/include/uClibc++/basic_definitions b/misc/uClibc++/include/uClibc++/basic_definitions index e0392b8ea7..4f833ee94b 100644 --- a/misc/uClibc++/include/uClibc++/basic_definitions +++ b/misc/uClibc++/include/uClibc++/basic_definitions @@ -18,31 +18,33 @@ #ifndef __BASIC_DEFINITIONS #define __BASIC_DEFINITIONS 1 +#include +#include + #include #pragma GCC visibility push(default) -//The following is used to support GCC symbol visibility patch +// The following is used to support GCC symbol visibility patch #ifdef GCC_HASCLASSVISIBILITY - #define _UCXXEXPORT __attribute__ ((visibility("default"))) - #define _UCXXLOCAL __attribute__ ((visibility("hidden"))) +# define _UCXXEXPORT __attribute__ ((visibility("default"))) +# define _UCXXLOCAL __attribute__ ((visibility("hidden"))) #else - #define _UCXXEXPORT - #define _UCXXLOCAL - +# define _UCXXEXPORT +# define _UCXXLOCAL #endif #ifdef __GCC__ -#define __UCLIBCXX_NORETURN __attribute__ ((__noreturn__)) +# define __UCLIBCXX_NORETURN __attribute__ ((__noreturn__)) #else -#define __UCLIBCXX_NORETURN +# define __UCLIBCXX_NORETURN #endif #ifdef __UCLIBCXX_HAS_TLS__ - #define __UCLIBCXX_TLS __thread +# define __UCLIBCXX_TLS __thread #else - #define __UCLIBCXX_TLS +# define __UCLIBCXX_TLS #endif diff --git a/misc/uClibc++/include/uClibc++/fstream b/misc/uClibc++/include/uClibc++/fstream index b8dd602c2d..d5c1d083b0 100644 --- a/misc/uClibc++/include/uClibc++/fstream +++ b/misc/uClibc++/include/uClibc++/fstream @@ -69,13 +69,13 @@ namespace std{ _UCXXEXPORT basic_filebuf() : basic_streambuf(), fp(0), pbuffer(0), gbuffer(0) { append=false; - pbuffer = new char_type[__UCLIBCXX_IOSTREAM_BUFSIZE__]; - gbuffer = new char_type[__UCLIBCXX_IOSTREAM_BUFSIZE__]; + pbuffer = new char_type[CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE]; + gbuffer = new char_type[CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE]; - this->setp(pbuffer, pbuffer + __UCLIBCXX_IOSTREAM_BUFSIZE__); + this->setp(pbuffer, pbuffer + CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE); //Position get buffer so that there is no data available - this->setg(gbuffer, gbuffer + __UCLIBCXX_IOSTREAM_BUFSIZE__, - gbuffer + __UCLIBCXX_IOSTREAM_BUFSIZE__); + this->setg(gbuffer, gbuffer + CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE, + gbuffer + CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE); } diff --git a/misc/uClibc++/include/uClibc++/ios b/misc/uClibc++/include/uClibc++/ios index 63dc4edbc8..2af1a14cb2 100644 --- a/misc/uClibc++/include/uClibc++/ios +++ b/misc/uClibc++/include/uClibc++/ios @@ -35,7 +35,7 @@ namespace std{ class _UCXXEXPORT ios_base { public: class failure; -#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ +#ifdef CONFIG_UCLIBCXX_EXCEPTION class failure : public exception { public: explicit failure(const std::string&) { } @@ -303,7 +303,7 @@ namespace std{ } _UCXXEXPORT void setstate(iostate state) { clear(rdstate() | state); -#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ +#ifdef CONFIG_UCLIBCXX_EXCEPTION if(rdstate() & throw_mask){ throw failure(); } diff --git a/misc/uClibc++/include/uClibc++/istream b/misc/uClibc++/include/uClibc++/istream index d67f48f577..37ffa127b6 100644 --- a/misc/uClibc++/include/uClibc++/istream +++ b/misc/uClibc++/include/uClibc++/istream @@ -72,7 +72,7 @@ namespace std{ basic_istream& operator>>(void*& p); basic_istream& operator>>(basic_streambuf* sb); -#ifdef __UCLIBCXX_HAS_FLOATS__ +#ifdef CONFIG_HAVE_FLOAT basic_istream& operator>>(float& f); basic_istream& operator>>(double& f); basic_istream& operator>>(long double& f); @@ -447,7 +447,7 @@ namespace std{ return *this; } -#ifdef __UCLIBCXX_HAS_FLOATS__ +#ifdef CONFIG_HAVE_FLOAT template _UCXXEXPORT basic_istream& basic_istream::operator>>(float& n) { @@ -578,7 +578,7 @@ namespace std{ template <> _UCXXEXPORT istream & istream::operator>>(long int &n); template <> _UCXXEXPORT istream & istream::operator>>(void *& p); -#ifdef __UCLIBCXX_HAS_FLOATS__ +#ifdef CONFIG_HAVE_FLOAT template <> _UCXXEXPORT istream & istream::operator>>(float &f); template <> _UCXXEXPORT istream & istream::operator>>(double &f); template <> _UCXXEXPORT istream & istream::operator>>(long double &f); diff --git a/misc/uClibc++/include/uClibc++/istream_helpers b/misc/uClibc++/include/uClibc++/istream_helpers index 0bdca7d218..36765dd70b 100644 --- a/misc/uClibc++/include/uClibc++/istream_helpers +++ b/misc/uClibc++/include/uClibc++/istream_helpers @@ -302,7 +302,7 @@ namespace std{ }; -#ifdef __UCLIBCXX_HAS_FLOATS__ +#ifdef CONFIG_HAVE_FLOAT template class _UCXXEXPORT __istream_readin{ public: @@ -335,7 +335,7 @@ namespace std{ } }; -#endif // ifdef __UCLIBCXX_HAS_FLOATS__ +#endif // ifdef CONFIG_HAVE_FLOAT template class _UCXXEXPORT __istream_readin{ public: diff --git a/misc/uClibc++/include/uClibc++/stdexcept b/misc/uClibc++/include/uClibc++/stdexcept index 7557f24c49..60305bcd93 100644 --- a/misc/uClibc++/include/uClibc++/stdexcept +++ b/misc/uClibc++/include/uClibc++/stdexcept @@ -24,8 +24,9 @@ #ifndef HEADER_STD_EXCEPTIONS #define HEADER_STD_EXCEPTIONS 1 -//Don't include support if not needed -#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ +// Don't include support if not needed + +#ifdef CONFIG_UCLIBCXX_EXCEPTION #pragma GCC visibility push(default) diff --git a/misc/uClibc++/include/uClibc++/string b/misc/uClibc++/include/uClibc++/string index 7826ce77c1..d045794149 100644 --- a/misc/uClibc++/include/uClibc++/string +++ b/misc/uClibc++/include/uClibc++/string @@ -17,6 +17,7 @@ Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include #include #include #include diff --git a/misc/uClibc++/include/uClibc++/support b/misc/uClibc++/include/uClibc++/support deleted file mode 100644 index 9279987ad9..0000000000 --- a/misc/uClibc++/include/uClibc++/support +++ /dev/null @@ -1,165 +0,0 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -#include -#include -#include - -#ifndef HEADER_ULC_SUPPORT -#define HEADER_ULC_SUPPORT 1 - -using namespace std; - -//From C++ ABI spec -typedef enum { - _URC_NO_REASON = 0, - _URC_FOREIGN_EXCEPTION_CAUGHT = 1, - _URC_FATAL_PHASE2_ERROR = 2, - _URC_FATAL_PHASE1_ERROR = 3, - _URC_NORMAL_STOP = 4, - _URC_END_OF_STACK = 5, - _URC_HANDLER_FOUND = 6, - _URC_INSTALL_CONTEXT = 7, - _URC_CONTINUE_UNWIND = 8 -} _Unwind_Reason_Code; - - -typedef void (*_Unwind_Exception_Cleanup_Fn) - (_Unwind_Reason_Code reason, struct _Unwind_Exception *exc); - -//The following definitions were grabbed from the gcc implementation -typedef unsigned _Unwind_Ptr __attribute__((__mode__(__pointer__))); -typedef unsigned _Unwind_Word __attribute__((__mode__(__word__))); -typedef signed _Unwind_Sword __attribute__((__mode__(__word__))); -typedef unsigned _Unwind_Exception_Class __attribute__((__mode__(__DI__))); -typedef void (*_Unwind_Exception_Cleanup_Fn) (_Unwind_Reason_Code, struct _Unwind_Exception *); - -typedef int _Unwind_Action; -static const _Unwind_Action _UA_SEARCH_PHASE = 1; -static const _Unwind_Action _UA_CLEANUP_PHASE = 2; -static const _Unwind_Action _UA_HANDLER_FRAME = 4; -static const _Unwind_Action _UA_FORCE_UNWIND = 8; - -const _Unwind_Exception_Class __uclibcxx_exception_class = (((((((( - _Unwind_Exception_Class) 'u' << 8 | (_Unwind_Exception_Class) 'l') << 8 - | (_Unwind_Exception_Class) 'i') << 8 | (_Unwind_Exception_Class) 'b') << 8 - | (_Unwind_Exception_Class) 'C')<< 8 | (_Unwind_Exception_Class) '+') << 8 - | (_Unwind_Exception_Class) '+') << 8 | (_Unwind_Exception_Class) '\0'); - - -#define _UA_SEARCH_PHASE 1 -#define _UA_CLEANUP_PHASE 2 -#define _UA_HANDLER_FRAME 4 -#define _UA_FORCE_UNWIND 8 -#define _UA_END_OF_STACK 16 - -struct _Unwind_Exception{ - _Unwind_Exception_Class exception_class; //Type of exception, eg ulibC++\0 - _Unwind_Exception_Cleanup_Fn exception_cleanup; //Destructor if from diff runtime - _Unwind_Word private_1; //Don't touch at all! - _Unwind_Word private_2; //Don't touch at all! -} __attribute__((__aligned__)); - - -//The following structure is system-dependent and defined by the compiler -//Thus it's definition was copied from the gcc 3.4.0 header files -struct _Unwind_Context; -//{ -// void *reg[DWARF_FRAME_REGISTERS+1]; -// void *cfa; -// void *ra; -// void *lsda; -// struct dwarf_eh_bases bases; -// _Unwind_Word args_size; -//}; - - - -_Unwind_Reason_Code _Unwind_RaiseException ( struct _Unwind_Exception *exception_object ); - -//_Unwind_ForcedUnwind - -typedef _Unwind_Reason_Code (*_Unwind_Stop_Fn) - (int version, _Unwind_Action actions, _Unwind_Exception_Class exceptionClass, - struct _Unwind_Exception *exceptionObject, - struct _Unwind_Context *context, void *stop_parameter ); - -_Unwind_Reason_Code _Unwind_ForcedUnwind ( - struct _Unwind_Exception *exception_object, _Unwind_Stop_Fn stop, - void *stop_parameter ); - -void _Unwind_Resume (struct _Unwind_Exception *exception_object); -void _Unwind_DeleteException (struct _Unwind_Exception *exception_object); - -_Unwind_Word _Unwind_GetGR (struct _Unwind_Context *context, int index); -void _Unwind_SetGR (struct _Unwind_Context *context, int index, _Unwind_Word); - -_Unwind_Ptr _Unwind_GetIP (struct _Unwind_Context *context); -void _Unwind_SetIP (struct _Unwind_Context *context, _Unwind_Ptr new_value); - -_Unwind_Ptr _Unwind_GetLanguageSpecificData (struct _Unwind_Context *context); -_Unwind_Ptr _Unwind_GetRegionStart (struct _Unwind_Context *context); - -_Unwind_Reason_Code (*__personality_routine) - (int version, //Should be 1 - _Unwind_Action actions, //Actions the routine will perform (bitmask) - _Unwind_Exception_Class exceptionClass, //Type of exception - vendor is high 4 bytes - struct _Unwind_Exception *exceptionObject, //Points to exception header - struct _Unwind_Context *context); //Unwinder state information - - -/*The following part is the Level II ABI which is required for compatability*/ -//This might be the only stuff that *I* need to implement - -struct __cxa_exception { - std::type_info *exceptionType; //Type of thrown exception - void (*exceptionDestructor) (void *); //Pointer to the destructor - unexpected_handler unexpectedHandler; //Unexpected handler to use - terminate_handler terminateHandler; //Terminate handle to use - __cxa_exception *nextException; //per thread linked list - - int handlerCount; //How many handlers have caught this - int handlerSwitchValue; - const char *actionRecord; - const char *languageSpecificData; - void *catchTemp; - void *adjustedPtr; - - _Unwind_Exception unwindHeader; -}; - -struct __cxa_eh_globals { - __cxa_exception *caughtExceptions; - unsigned int uncaughtExceptions; -}; - -extern "C" __cxa_eh_globals *__cxa_get_globals(void); //Return ptr to the eh_globals object for current thread -extern "C" __cxa_eh_globals *__cxa_get_globals_fast(void); //Same as above, assumes that above called at least once - -extern "C" void *__cxa_allocate_exception(size_t thrown_size); //Allocate space for exception plus header -extern "C" void __cxa_free_exception(void *thrown_exception); //Free space allocated from the above - -extern "C" void __cxa_throw (void *thrown_exception, //This is the actual throw call -// std::type_info *tinfo, //Type of object - void * tinfo, //Type of object - void (*dest) (void *) ); //Pointer to destructor destroy object - - -#endif - diff --git a/misc/uClibc++/include/uClibc++/system_configuration.h b/misc/uClibc++/include/uClibc++/system_configuration.h index 4db8e8bd85..e813f20766 100644 --- a/misc/uClibc++/include/uClibc++/system_configuration.h +++ b/misc/uClibc++/include/uClibc++/system_configuration.h @@ -1,28 +1,20 @@ -/* - * Automatically generated C config: don't edit - */ -/* - * Version Number +/* This file is being deprecated. Eventually all configuration options will + * need to be moved into the NuttX configuration system. */ + +/* Version Number */ + #define __UCLIBCXX_MAJOR__ 0 #define __UCLIBCXX_MINOR__ 2 #define __UCLIBCXX_SUBLEVEL__ 4 -/* - * Target Features and Options - */ -#define __UCLIBCXX_HAS_FLOATS__ 1 -#define __UCLIBCXX_HAS_LONG_DOUBLE__ 1 -#define __UCLIBCXX_HAS_TLS__ 1 -#define __WARNINGS__ "-Wall" -#define __BUILD_EXTRA_LIBRARIES__ "" -#define __HAVE_DOT_CONFIG__ 1 +/* Target Features and Options */ + +#define __UCLIBCXX_HAS_TLS__ 1 + +/* String and I/O Stream Support */ -/* - * String and I/O Stream Support - */ #undef __UCLIBCXX_HAS_WCHAR__ -#define __UCLIBCXX_IOSTREAM_BUFSIZE__ 32 #define __UCLIBCXX_HAS_LFS__ 1 #define __UCLIBCXX_SUPPORT_CDIR__ 1 #define __UCLIBCXX_SUPPORT_CIN__ 1 @@ -30,9 +22,8 @@ #define __UCLIBCXX_SUPPORT_CERR__ 1 #undef __UCLIBCXX_SUPPORT_CLOG__ -/* - * STL and Code Expansion - */ +/* STL and Code Expansion */ + #define __UCLIBCXX_STL_BUFFER_SIZE__ 32 #define __UCLIBCXX_CODE_EXPANSION__ 1 #define __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ 1 @@ -44,5 +35,3 @@ #define __UCLIBCXX_EXPAND_OSTREAM_CHAR__ 1 #define __UCLIBCXX_EXPAND_FSTREAM_CHAR__ 1 #define __UCLIBCXX_EXPAND_SSTREAM_CHAR__ 1 - - diff --git a/misc/uClibc++/include/uClibc++/unwind-cxx.h b/misc/uClibc++/include/uClibc++/unwind-cxx.h index 4a8961a978..b0d5b416b9 100644 --- a/misc/uClibc++/include/uClibc++/unwind-cxx.h +++ b/misc/uClibc++/include/uClibc++/unwind-cxx.h @@ -79,10 +79,10 @@ struct __cxa_exception _Unwind_Exception unwindHeader; }; - // A dependent C++ exception object consists of a header, which is a wrapper // around an unwind object header with additional C++ specific information, // followed by the exception object itself. + struct __cxa_dependent_exception { // The primary exception @@ -112,44 +112,52 @@ struct __cxa_dependent_exception _Unwind_Exception unwindHeader; }; - // Each thread in a C++ program has access to a __cxa_eh_globals object. + struct __cxa_eh_globals { __cxa_exception *caughtExceptions; unsigned int uncaughtExceptions; }; - // The __cxa_eh_globals for the current thread can be obtained by using // either of the following functions. The "fast" version assumes at least // one prior call of __cxa_get_globals has been made from the current // thread, so no initialization is necessary. + extern "C" __cxa_eh_globals *__cxa_get_globals () throw(); extern "C" __cxa_eh_globals *__cxa_get_globals_fast () throw(); // Allocate memory for the primary exception plus the thrown object. + extern "C" void *__cxa_allocate_exception(std::size_t thrown_size) throw(); + // Allocate memory for dependent exception. + extern "C" __cxa_dependent_exception *__cxa_allocate_dependent_exception() throw(); // Free the space allocated for the primary exception. + extern "C" void __cxa_free_exception(void *thrown_exception) throw(); + // Free the space allocated for the dependent exception. + extern "C" void __cxa_free_dependent_exception(__cxa_dependent_exception *dependent_exception) throw(); // Throw the exception. + extern "C" void __cxa_throw (void *thrown_exception, - std::type_info *tinfo, - void (*dest) (void *)) - __attribute__((noreturn)); + std::type_info *tinfo, + void (*dest) (void *)) __attribute__((noreturn)); // Used to implement exception handlers. + extern "C" void *__cxa_begin_catch (void *) throw(); extern "C" void __cxa_end_catch (); extern "C" void __cxa_rethrow () __attribute__((noreturn)); // These facilitate code generation for recurring situations. + extern "C" void __cxa_bad_cast (); extern "C" void __cxa_bad_typeid (); @@ -158,24 +166,28 @@ extern "C" void __cxa_bad_typeid (); // Handles re-checking the exception specification if unexpectedHandler // throws, and if bad_exception needs to be thrown. Called from the // compiler. + extern "C" void __cxa_call_unexpected (void *) __attribute__((noreturn)); // Invokes given handler, dying appropriately if the user handler was // so inconsiderate as to return. + extern void __terminate(std::terminate_handler) __attribute__((noreturn)); extern void __unexpected(std::unexpected_handler) __attribute__((noreturn)); // The current installed user handlers. + extern std::terminate_handler __terminate_handler; extern std::unexpected_handler __unexpected_handler; // These are explicitly GNU C++ specific. // This is the exception class we report -- "GNUCC++\0". -const _Unwind_Exception_Class __gxx_exception_class -= ((((((((_Unwind_Exception_Class) 'G' - << 8 | (_Unwind_Exception_Class) 'N') - << 8 | (_Unwind_Exception_Class) 'U') + +const _Unwind_Exception_Class __gxx_exception_class = + ((((((((_Unwind_Exception_Class) 'G' + << 8 | (_Unwind_Exception_Class) 'N') + << 8 | (_Unwind_Exception_Class) 'U') << 8 | (_Unwind_Exception_Class) 'C') << 8 | (_Unwind_Exception_Class) 'C') << 8 | (_Unwind_Exception_Class) '+') @@ -183,25 +195,27 @@ const _Unwind_Exception_Class __gxx_exception_class << 8 | (_Unwind_Exception_Class) '\0'); // GNU C++ personality routine, Version 0. + extern "C" _Unwind_Reason_Code __gxx_personality_v0 (int, _Unwind_Action, _Unwind_Exception_Class, struct _Unwind_Exception *, struct _Unwind_Context *); // GNU C++ sjlj personality routine, Version 0. + extern "C" _Unwind_Reason_Code __gxx_personality_sj0 (int, _Unwind_Action, _Unwind_Exception_Class, struct _Unwind_Exception *, struct _Unwind_Context *); // Acquire the C++ exception header from the C++ object. -static inline __cxa_exception * -__get_exception_header_from_obj (void *ptr) + +static inline __cxa_exception *__get_exception_header_from_obj (void *ptr) { return reinterpret_cast<__cxa_exception *>(ptr) - 1; } // Acquire the C++ exception header from the generic exception header. -static inline __cxa_exception * -__get_exception_header_from_ue (_Unwind_Exception *exc) + +static inline __cxa_exception *__get_exception_header_from_ue (_Unwind_Exception *exc) { return reinterpret_cast<__cxa_exception *>(exc + 1) - 1; } diff --git a/misc/uClibc++/install.sh b/misc/uClibc++/install.sh index 065738e1a0..d0bf8e211c 100755 --- a/misc/uClibc++/install.sh +++ b/misc/uClibc++/install.sh @@ -261,6 +261,15 @@ if [ ! -d "${nuttxcxx_incdir}" ]; then exit 1 fi +uclibc_incdir=${nuttx_incdir}/uClibc++ + +if [ -d "${uclibc_incdir}" ]; then + echo "ERROR: Directory ${uclibc_incdir} already exists" + echo " Please remove the ${uclibc_incdir} directory and try again" + echo $usage + exit 1 +fi + # Licensing echo "You are about to install the uClibc++ library into the NuttX source" diff --git a/misc/uClibc++/libxx/uClibc++/Make.defs b/misc/uClibc++/libxx/uClibc++/Make.defs index 9f1b2f51f4..a4e7a02f78 100644 --- a/misc/uClibc++/libxx/uClibc++/Make.defs +++ b/misc/uClibc++/libxx/uClibc++/Make.defs @@ -43,8 +43,7 @@ CXXSRCS += iostream.cxx istream.cxx iterator.cxx limits.cxx list.cxx CXXSRCS += locale.cxx map.cxx new_handler.cxx new_op.cxx new_opnt.cxx CXXSRCS += new_opv.cxx new_opvnt.cxx numeric.cxx ostream.cxx queue.cxx CXXSRCS += set.cxx sstream.cxx stack.cxx stdexcept.cxx streambuf.cxx -CXXSRCS += string.cxx support.cxx typeinfo.cxx utility.cxx valarray.cxx -CXXSRCS += vector.cxx +CXXSRCS += string.cxx typeinfo.cxx utility.cxx valarray.cxx vector.cxx # Add the path to the uClibc++ subdirectory diff --git a/misc/uClibc++/libxx/uClibc++/eh_alloc.cxx b/misc/uClibc++/libxx/uClibc++/eh_alloc.cxx index 5098196d85..ea3308a307 100644 --- a/misc/uClibc++/libxx/uClibc++/eh_alloc.cxx +++ b/misc/uClibc++/libxx/uClibc++/eh_alloc.cxx @@ -1,61 +1,93 @@ -/* Copyright (C) 2006 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation, version 2.1 - of the License. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2006 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation, version 2.1 + * of the License. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include #include -//This is a system-specific header which does all of the error-handling management +// This is a system-specific header which does all of the error-handling +// management + #include -namespace __cxxabiv1{ +namespace __cxxabiv1 +{ + extern "C" void *__cxa_allocate_exception(std::size_t thrown_size) throw() + { + void *retval; -extern "C" void * __cxa_allocate_exception(std::size_t thrown_size) throw(){ - void *retval; - //The sizeof crap is required by Itanium ABI because we need to provide space for - //accounting information which is implementaion (gcc) specified - retval = malloc (thrown_size + sizeof(__cxa_exception)); - if (0 == retval){ - std::terminate(); - } - memset (retval, 0, sizeof(__cxa_exception)); - return (void *)((unsigned char *)retval + sizeof(__cxa_exception)); -} + // The amount of data needed is the size of the object *PLUS* + // the size of the header. The header is of struct __cxa_exception + // The address needs to be adjusted because the pointer we return + // should not point to the start of the memory, but to the point + // where the object being thrown actually starts -extern "C" void __cxa_free_exception(void *vptr) throw(){ - free( (char *)(vptr) - sizeof(__cxa_exception) ); -} + retval = malloc (thrown_size + sizeof(__cxa_exception)); + // Check to see that we actuall allocated memory -extern "C" __cxa_dependent_exception * __cxa_allocate_dependent_exception() throw(){ - __cxa_dependent_exception *retval; - //The sizeof crap is required by Itanium ABI because we need to provide space for - //accounting information which is implementaion (gcc) specified - retval = static_cast<__cxa_dependent_exception*>(malloc (sizeof(__cxa_dependent_exception))); - if (0 == retval){ - std::terminate(); - } - memset (retval, 0, sizeof(__cxa_dependent_exception)); - return retval; -} + if (0 == retval) + { + std::terminate(); + } -extern "C" void __cxa_free_dependent_exception(__cxa_dependent_exception *vptr) throw(){ - free( (char *)(vptr) ); -} + // Need to do a typecast to char* otherwize we are doing math with + // a void* which makes the compiler cranky (Like me) + + memset (retval, 0, sizeof(__cxa_exception)); + return (void *)((unsigned char *)retval + sizeof(__cxa_exception)); + } + + extern "C" void __cxa_free_exception(void *vptr) throw() + { + free( (char *)(vptr) - sizeof(__cxa_exception) ); + } + + extern "C" __cxa_dependent_exception *__cxa_allocate_dependent_exception() throw() + { + __cxa_dependent_exception *retval; + + // The amount of data needed is the size of the object *PLUS* + // the size of the header. The header is of struct __cxa_exception + // The address needs to be adjusted because the pointer we return + // should not point to the start of the memory, but to the point + // where the object being thrown actually starts + + retval = static_cast<__cxa_dependent_exception*>(malloc (sizeof(__cxa_dependent_exception))); + + // Check to see that we actuall allocated memory + + if (0 == retval) + { + std::terminate(); + } + + memset (retval, 0, sizeof(__cxa_dependent_exception)); + return retval; + } + + extern "C" void __cxa_free_dependent_exception(__cxa_dependent_exception *vptr) throw() + { + free( (char *)(vptr) ); + } + + extern "C" void __cxa_throw(void *thrown_exception, std::type_info *tinfo, void (*dest) (void *)) + { + } } diff --git a/misc/uClibc++/libxx/uClibc++/exception.cxx b/misc/uClibc++/libxx/uClibc++/exception.cxx index 82021ddb63..6d487a1167 100644 --- a/misc/uClibc++/libxx/uClibc++/exception.cxx +++ b/misc/uClibc++/libxx/uClibc++/exception.cxx @@ -1,52 +1,53 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz +/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. + This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include -//We can't do this yet because gcc is too stupid to be able to handle -//different implementations of exception class. +// We can't do this yet because gcc is too stupid to be able to handle +// different implementations of exception class. -#undef __UCLIBCXX_EXCEPTION_SUPPORT__ +#undef CONFIG_UCLIBCXX_EXCEPTION -#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ +#ifdef CONFIG_UCLIBCXX_EXCEPTION -namespace std{ - _UCXXEXPORT static char * __std_exception_what_value = "exception"; +namespace std +{ + _UCXXEXPORT static char * __std_exception_what_value = "exception"; - //We are providing our own versions to be sneaky + //We are providing our own versions to be sneaky - _UCXXEXPORT exception::~exception() throw(){ - //Empty function - } + _UCXXEXPORT exception::~exception() throw() + { + //Empty function + } - _UCXXEXPORT const char* exception::what() const throw(){ - return __std_exception_what_value; - } - - _UCXXEXPORT bad_exception::~bad_exception() throw(){ - - } + _UCXXEXPORT const char* exception::what() const throw() + { + return __std_exception_what_value; + } + _UCXXEXPORT bad_exception::~bad_exception() throw() + { + } } - #endif diff --git a/misc/uClibc++/libxx/uClibc++/func_exception.cxx b/misc/uClibc++/libxx/uClibc++/func_exception.cxx index fab095f3de..9971871efd 100644 --- a/misc/uClibc++/libxx/uClibc++/func_exception.cxx +++ b/misc/uClibc++/libxx/uClibc++/func_exception.cxx @@ -1,20 +1,20 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz +/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. + This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include @@ -24,60 +24,78 @@ namespace std{ -#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ +#ifdef CONFIG_UCLIBCXX_EXCEPTION -_UCXXEXPORT void __throw_bad_alloc(){ - throw bad_alloc(); +_UCXXEXPORT void __throw_bad_alloc() +{ + throw bad_alloc(); } -_UCXXEXPORT void __throw_out_of_range( const char * message){ - if(message == 0){ - throw out_of_range(); - } - throw out_of_range(message); +_UCXXEXPORT void __throw_out_of_range(const char * message) +{ + if(message == 0) + { + throw out_of_range(); + } + + throw out_of_range(message); } -_UCXXEXPORT void __throw_overflow_error( const char * message){ - if(message == 0){ - throw overflow_error(); - } - throw overflow_error(message); +_UCXXEXPORT void __throw_overflow_error(const char * message) +{ + if(message == 0) + { + throw overflow_error(); + } + + throw overflow_error(message); } -_UCXXEXPORT void __throw_length_error(const char * message){ - if(message == 0){ - throw length_error(); - } - throw length_error(message); +_UCXXEXPORT void __throw_length_error(const char * message) +{ + if(message == 0) + { + throw length_error(); + } + + throw length_error(message); } -_UCXXEXPORT void __throw_invalid_argument(const char * message){ - if(message == 0){ - throw invalid_argument(); - } - throw invalid_argument(message); +_UCXXEXPORT void __throw_invalid_argument(const char * message) +{ + if(message == 0) + { + throw invalid_argument(); + } + + throw invalid_argument(message); } #else -_UCXXEXPORT void __throw_bad_alloc(){ - abort(); +_UCXXEXPORT void __throw_bad_alloc() +{ + abort(); } -_UCXXEXPORT void __throw_out_of_range( const char * ){ - abort(); +_UCXXEXPORT void __throw_out_of_range(const char *) +{ + abort(); } -_UCXXEXPORT void __throw_overflow_error( const char * ){ - abort(); +_UCXXEXPORT void __throw_overflow_error(const char *) +{ + abort(); } -_UCXXEXPORT void __throw_length_error(const char * ){ - abort(); +_UCXXEXPORT void __throw_length_error(const char *) +{ + abort(); } -_UCXXEXPORT void __throw_invalid_argument(const char *){ - abort(); +_UCXXEXPORT void __throw_invalid_argument(const char *) +{ + abort(); } #endif diff --git a/misc/uClibc++/libxx/uClibc++/istream.cxx b/misc/uClibc++/libxx/uClibc++/istream.cxx index 9e9613973f..bcb81c0f9e 100644 --- a/misc/uClibc++/libxx/uClibc++/istream.cxx +++ b/misc/uClibc++/libxx/uClibc++/istream.cxx @@ -22,7 +22,6 @@ #include - namespace std{ #ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ @@ -59,8 +58,7 @@ namespace std{ template _UCXXEXPORT istream & istream::operator>>(void *& p); template _UCXXEXPORT istream & operator>>(istream & is, char & c); - -#ifdef __UCLIBCXX_HAS_FLOATS__ +#ifdef CONFIG_HAVE_FLOAT template _UCXXEXPORT istream & istream::operator>>(float &f); template _UCXXEXPORT istream & istream::operator>>(double &f); template _UCXXEXPORT istream & istream::operator>>(long double &f); diff --git a/misc/uClibc++/libxx/uClibc++/stdexcept.cxx b/misc/uClibc++/libxx/uClibc++/stdexcept.cxx index 90dccc7a49..d372c0b779 100644 --- a/misc/uClibc++/libxx/uClibc++/stdexcept.cxx +++ b/misc/uClibc++/libxx/uClibc++/stdexcept.cxx @@ -20,7 +20,7 @@ #include #include -#ifdef __UCLIBCXX_EXCEPTION_SUPPORT__ +#ifdef CONFIG_UCLIBCXX_EXCEPTION namespace std{ diff --git a/misc/uClibc++/libxx/uClibc++/support.cxx b/misc/uClibc++/libxx/uClibc++/support.cxx deleted file mode 100644 index 875459442e..0000000000 --- a/misc/uClibc++/libxx/uClibc++/support.cxx +++ /dev/null @@ -1,53 +0,0 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -#include - -extern "C" void *__cxa_allocate_exception(size_t thrown_size){ - void * retval; - -// The amount of data needed is the size of the object *PLUS* -// the size of the header. The header is of struct __cxa_exception -// The address needs to be adjusted because the pointer we return -// should not point to the start of the memory, but to the point -// where the object being thrown actually starts -// - retval = malloc(thrown_size + sizeof(__cxa_exception)); - -// Check to see that we actuall allocated memory - if(retval == 0){ - std::terminate(); - } - - //Need to do a typecast to char* otherwize we are doing math with - //a void* which makes the compiler cranky (Like me) - return ((char *)retval + sizeof(__cxa_exception)); -} - -extern "C" void __cxa_free_exception(void *thrown_exception){ - - - -} - -extern "C" void __cxa_throw (void *thrown_exception, void *info,void (*dest) (void *) ){ - - -} - diff --git a/nuttx/configs/sim/cxxtest/defconfig b/nuttx/configs/sim/cxxtest/defconfig index d7f5efff5b..20d4e5c853 100644 --- a/nuttx/configs/sim/cxxtest/defconfig +++ b/nuttx/configs/sim/cxxtest/defconfig @@ -279,6 +279,9 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512 CONFIG_HAVE_CXX=y # CONFIG_HAVE_CXXINITIALIZE is not set # CONFIG_CXX_NEWLONG is not set +CONFIG_UCLIBCXX=y +CONFIG_UCLIBCXX_EXCEPTION=y +CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE=32 # # Application Configuration diff --git a/nuttx/include/cxx/cstdbool b/nuttx/include/cxx/cstdbool index d2f0639d21..192fde490b 100644 --- a/nuttx/include/cxx/cstdbool +++ b/nuttx/include/cxx/cstdbool @@ -46,4 +46,13 @@ // Namespace //*************************************************************************** +//*************************************************************************** +// Namespace +//*************************************************************************** + +namespace std +{ + using ::_Bool8; +} + #endif // __INCLUDE_CXX_CSTDBOOL diff --git a/nuttx/include/cxx/cstdio b/nuttx/include/cxx/cstdio index 900d429cb9..6a9620e1ad 100644 --- a/nuttx/include/cxx/cstdio +++ b/nuttx/include/cxx/cstdio @@ -52,6 +52,8 @@ namespace std using ::FILE; using ::fpos_t; using ::size_t; + + using ::clearerr; using ::fclose; using ::fflush; using ::feof; @@ -69,16 +71,24 @@ namespace std using ::ftell; using ::fwrite; using ::gets; + using ::ungetc; + using ::printf; using ::puts; using ::rename; using ::sprintf; + using ::asprintf; using ::snprintf; - using ::ungetc; + using ::sscanf; + using ::perror; + using ::vprintf; using ::vfprintf; using ::vsprintf; + using ::avsprintf; using ::vsnprintf; + using ::vsscanf; + using ::fdopen; using ::statfs; } diff --git a/nuttx/include/nuttx/compiler.h b/nuttx/include/nuttx/compiler.h index 510f7d4117..f700e539d8 100644 --- a/nuttx/include/nuttx/compiler.h +++ b/nuttx/include/nuttx/compiler.h @@ -197,6 +197,7 @@ /* GCC supports both types double and long long */ # define CONFIG_HAVE_LONG_LONG 1 +# define CONFIG_HAVE_FLOAT 1 # define CONFIG_HAVE_DOUBLE 1 # define CONFIG_HAVE_LONG_DOUBLE 1 @@ -301,6 +302,7 @@ /* SDCC does not support type long long or type double */ # undef CONFIG_HAVE_LONG_LONG +# define CONFIG_HAVE_FLOAT 1 # undef CONFIG_HAVE_DOUBLE # undef CONFIG_HAVE_LONG_DOUBLE @@ -406,6 +408,7 @@ */ # undef CONFIG_HAVE_LONG_LONG +# define CONFIG_HAVE_FLOAT 1 # undef CONFIG_HAVE_DOUBLE # undef CONFIG_HAVE_LONG_DOUBLE @@ -441,8 +444,9 @@ # undef CONFIG_LONG_IS_NOT_INT # undef CONFIG_PTR_IS_NOT_INT # undef CONFIG_HAVE_INLINE -# define inline +# define inline 1 # undef CONFIG_HAVE_LONG_LONG +# define CONFIG_HAVE_FLOAT 1 # undef CONFIG_HAVE_DOUBLE # undef CONFIG_HAVE_LONG_DOUBLE # undef CONFIG_CAN_PASS_STRUCTS diff --git a/nuttx/libxx/Kconfig b/nuttx/libxx/Kconfig index 4133a0ceb9..5ce2a8f7dd 100644 --- a/nuttx/libxx/Kconfig +++ b/nuttx/libxx/Kconfig @@ -10,6 +10,10 @@ config HAVE_CXX Toolchain supports C++ and CXX, CXXFLAGS, and COMPILEXX have been defined in the configurations Make.defs file. +if HAVE_CXX + +comment "Basic CXX Support" + config HAVE_CXXINITIALIZE bool "Have C++ initialization" default n @@ -25,3 +29,26 @@ config CXX_NEWLONG size_t may be type long or type int. This matters for some C++ library routines because the NuttX size_t might not have the same underlying type as your toolchain's size_t. + +comment "uClibc++ Standard C++ Library" + +config UCLIBCXX + bool "Build uClibc++ (must be installed)" + default n + ---help--- + If you have installed uClibc++ into the NuttX source try, then it can + be built by selecting this option. See misc/uClibc++/README.txt for + information on installing uClibc++. + +if UCLIBCXX + +config UCLIBCXX_EXCEPTION + bool "Enable Exception Suppport" + default y + +config UCLIBCXX_IOSTREAM_BUFSIZE + int "IO Stream Buffer Size" + default 32 + +endif +endif diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile index bc8c5012ef..e563b9647e 100644 --- a/nuttx/libxx/Makefile +++ b/nuttx/libxx/Makefile @@ -49,12 +49,19 @@ CXXSRCS += libxx_newa.cxx DEPPATH = --dep-path . VPATH = . -# Include the uClibc++ Make.defs file (if it is present). If is present, +# Include the uClibc++ Make.defs file if selected. If it is included, # the uClibc++/Make.defs file will add its files to the source file list, # add its DEPPATH info, and will add the appropriate paths to the VPATH # variable +# +# Note that an error will occur if you select CONFIG_LIBXX_UCLIBCXX +# without installing the uClibc++ package. This is intentional to let +# you know about the configuration problem. Refer to misc/uClibc++/README.txt +# for more information --include uClibc++/Make.defs +ifeq ($(CONFIG_UCLIBCXX),y) +include uClibc++/Make.defs +endif # Object Files diff --git a/nuttx/libxx/README.txt b/nuttx/libxx/README.txt index 6cf066f080..7a1c51fa70 100644 --- a/nuttx/libxx/README.txt +++ b/nuttx/libxx/README.txt @@ -12,6 +12,10 @@ are recommended: - uClibc++ http://cxx.uclibc.org/ - uSTL http://ustl.sourceforge.net/ +There is a version of uClibc++ that is customized for NuttX that can +be found here: misc/uClibc++. See misc/uClibc++ for installation +instructions. + At present, only the following are supported here: - void *operator new(std::size_t nbytes); @@ -19,6 +23,7 @@ At present, only the following are supported here: - void operator delete[](void *ptr); - void __cxa_pure_virtual(void); - int __aeabi_atexit(void* object, void (*destroyer)(void*), void *dso_handle); + - int __cxa_atexit(__cxa_exitfunc_t func, FAR void *arg, FAR void *dso_handle); operator new ------------ diff --git a/nuttx/libxx/libxx_cxa_atexit.cxx b/nuttx/libxx/libxx_cxa_atexit.cxx index 7e6d00a377..cd31f94f61 100644 --- a/nuttx/libxx/libxx_cxa_atexit.cxx +++ b/nuttx/libxx/libxx_cxa_atexit.cxx @@ -130,6 +130,9 @@ extern "C" { // Register the function to be called when the task/thread exists. + alloc->func = func; + alloc->arg = arg; + return on_exit(__cxa_callback, alloc); } else From d7aefb08f7012f785b9cd623caae9e9cbfc6d5ac Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 1 Nov 2012 21:21:54 +0000 Subject: [PATCH 063/206] Fixes for warnings from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5294 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/pwm/pwm_main.c | 1 + nuttx/drivers/mmcsd/mmcsd_spi.c | 6 ++++-- nuttx/sched/mq_open.c | 3 +-- nuttx/sched/sem_open.c | 3 +-- 4 files changed, 7 insertions(+), 6 deletions(-) diff --git a/apps/examples/pwm/pwm_main.c b/apps/examples/pwm/pwm_main.c index 775bdba6b1..a46c10f55c 100644 --- a/apps/examples/pwm/pwm_main.c +++ b/apps/examples/pwm/pwm_main.c @@ -48,6 +48,7 @@ #include #include #include +#include #include diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c index 7dbadc55fe..39b5705812 100644 --- a/nuttx/drivers/mmcsd/mmcsd_spi.c +++ b/nuttx/drivers/mmcsd/mmcsd_spi.c @@ -508,7 +508,7 @@ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot, } break; - /* The R3 response is 5 bytes long */ + /* The R3 response is 5 bytes long. The first byte is identical to R1. */ case MMCSD_CMDRESP_R3: { @@ -520,8 +520,10 @@ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot, fvdbg("CMD%d[%08x] R1=%02x OCR=%08x\n", cmd->cmd & 0x3f, arg, response, slot->ocr); } + break; + + /* The R7 response is 5 bytes long. The first byte is identical to R1. */ - /* The R7 response is 5 bytes long */ case MMCSD_CMDRESP_R7: default: { diff --git a/nuttx/sched/mq_open.c b/nuttx/sched/mq_open.c index 5e1b9b1377..89d80f072a 100644 --- a/nuttx/sched/mq_open.c +++ b/nuttx/sched/mq_open.c @@ -113,7 +113,6 @@ mqd_t mq_open(const char *mq_name, int oflags, ...) FAR msgq_t *msgq; mqd_t mqdes = NULL; va_list arg; /* Points to each un-named argument */ - mode_t mode; /* MQ creation mode parameter (ignored) */ struct mq_attr *attr; /* MQ creation attributes */ int namelen; /* Length of MQ name */ @@ -170,7 +169,7 @@ mqd_t mq_open(const char *mq_name, int oflags, ...) */ va_start(arg, oflags); - mode = va_arg(arg, mode_t); + (void)va_arg(arg, mode_t); /* MQ creation mode parameter (ignored) */ attr = va_arg(arg, struct mq_attr*); /* Initialize the new named message queue */ diff --git a/nuttx/sched/sem_open.c b/nuttx/sched/sem_open.c index 817c36b49b..b2b76fe380 100644 --- a/nuttx/sched/sem_open.c +++ b/nuttx/sched/sem_open.c @@ -120,7 +120,6 @@ FAR sem_t *sem_open (FAR const char *name, int oflag, ...) FAR nsem_t *psem; FAR sem_t *sem = (FAR sem_t*)ERROR; va_list arg; /* Points to each un-named argument */ - mode_t mode; /* Creation mode parameter (ignored) */ unsigned int value; /* Semaphore value parameter */ /* Make sure that a non-NULL name is supplied */ @@ -165,7 +164,7 @@ FAR sem_t *sem_open (FAR const char *name, int oflag, ...) */ va_start(arg, oflag); - mode = va_arg(arg, mode_t); + (void)va_arg(arg, mode_t); /* Creation mode parameter (ignored) */ value = va_arg(arg, unsigned int); /* Verify that a legal initial value was selected. */ From 73bd482b412ced082acbca49d3143f4cdafef65b Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 1 Nov 2012 22:54:55 +0000 Subject: [PATCH 064/206] uClibc++ updates git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5295 42af7a65-404d-4744-a932-0658087f49c3 --- .../include/uClibc++/basic_definitions | 22 +----- misc/uClibc++/include/uClibc++/exception | 67 ++++++++++------- misc/uClibc++/include/uClibc++/list | 15 ++-- misc/uClibc++/libxx/uClibc++/Make.defs | 2 +- misc/uClibc++/libxx/uClibc++/eh_terminate.cxx | 75 +++++++++++++++++++ misc/uClibc++/libxx/uClibc++/exception.cxx | 43 +++++------ 6 files changed, 145 insertions(+), 79 deletions(-) create mode 100644 misc/uClibc++/libxx/uClibc++/eh_terminate.cxx diff --git a/misc/uClibc++/include/uClibc++/basic_definitions b/misc/uClibc++/include/uClibc++/basic_definitions index 4f833ee94b..ff2b29054e 100644 --- a/misc/uClibc++/include/uClibc++/basic_definitions +++ b/misc/uClibc++/include/uClibc++/basic_definitions @@ -35,34 +35,20 @@ # define _UCXXLOCAL #endif -#ifdef __GCC__ -# define __UCLIBCXX_NORETURN __attribute__ ((__noreturn__)) -#else -# define __UCLIBCXX_NORETURN -#endif - #ifdef __UCLIBCXX_HAS_TLS__ # define __UCLIBCXX_TLS __thread #else # define __UCLIBCXX_TLS #endif +// Testing purposes - -//Testing purposes #define __STRING_MAX_UNITS 65535 -namespace std{ - typedef signed long int streamsize; +namespace std +{ + typedef signed long int streamsize; } #pragma GCC visibility pop - -#endif - - -#ifdef __DODEBUG__ - #define UCLIBCXX_DEBUG 1 -#else - #define UCLIBCXX_DEBUG 0 #endif diff --git a/misc/uClibc++/include/uClibc++/exception b/misc/uClibc++/include/uClibc++/exception index bdf393e6cc..6d91207b80 100644 --- a/misc/uClibc++/include/uClibc++/exception +++ b/misc/uClibc++/include/uClibc++/exception @@ -1,5 +1,5 @@ // Exception Handling support header for -*- C++ -*- - +// // Copyright (C) 1995, 1996, 1997, 1998, 2000, 2001, 2002 // Free Software Foundation // @@ -19,7 +19,7 @@ // along with GNU CC; see the file COPYING. If not, write to // the Free Software Foundation, 59 Temple Place - Suite 330, // Boston, MA 02111-1307, USA. - +// // As a special exception, you may use this file as part of a free software // library without restriction. Specifically, if other files instantiate // templates or use macros or inline functions from this file, or you compile @@ -39,7 +39,8 @@ #include -extern "C++" { +extern "C++" +{ namespace std { @@ -51,43 +52,62 @@ namespace std * your own %exception classes, or use a different hierarchy, or to * throw non-class data (e.g., fundamental types). */ + class exception { public: exception() throw() { } virtual ~exception() throw(); + /** Returns a C-style character string describing the general cause - * of the current error. */ + * of the current error. + */ + virtual const char* what() const throw(); }; /** If an %exception is thrown which is not listed in a function's - * %exception specification, one of these may be thrown. */ + * %exception specification, one of these may be thrown. + */ + class bad_exception : public exception { public: bad_exception() throw() { } + // This declaration is not useless: // http://gcc.gnu.org/onlinedocs/gcc-3.0.2/gcc_6.html#SEC118 + virtual ~bad_exception() throw(); }; - /// If you write a replacement %terminate handler, it must be of this type. - typedef void (*terminate_handler) (); - /// If you write a replacement %unexpected handler, it must be of this type. - typedef void (*unexpected_handler) (); + // If you write a replacement %terminate handler, it must be of this type. + + typedef CODE void (*terminate_handler)(void); + + // If you write a replacement %unexpected handler, it must be of this type. + + typedef CODE void (*unexpected_handler)(void); + + // Takes a new handler function as an argument, returns the old function. - /// Takes a new handler function as an argument, returns the old function. terminate_handler set_terminate(terminate_handler) throw(); - /** The runtime will call this function if %exception handling must be - * abandoned for any reason. */ - void terminate() __UCLIBCXX_NORETURN; - /// Takes a new handler function as an argument, returns the old function. + /** The runtime will call this function if %exception handling must be + * abandoned for any reason. + */ + + void terminate() noreturn_function; + + // Takes a new handler function as an argument, returns the old function. + unexpected_handler set_unexpected(unexpected_handler) throw(); + /** The runtime will call this function if an %exception is thrown which - * violates the function's %exception specification. */ - void unexpected() __UCLIBCXX_NORETURN; + * violates the function's %exception specification. + */ + + void unexpected() noreturn_function; /** [18.6.4]/1: "Returns true after completing evaluation of a * throw-expression until either completing initialization of the @@ -99,21 +119,10 @@ namespace std * 2: "When @c uncaught_exception() is true, throwing an %exception can * result in a call of @c terminate() (15.5.1)." */ + bool uncaught_exception() throw(); -} // namespace std -namespace __gnu_cxx -{ - /** A replacement for the standard terminate_handler which prints more - information about the terminating exception (if any) on stderr. Call - @code - std::set_terminate (__gnu_cxx::__verbose_terminate_handler) - @endcode - to use. For more info, see - http://gcc.gnu.org/onlinedocs/libstdc++/19_diagnostics/howto.html#4 - */ - void __verbose_terminate_handler (); -} // namespace __gnu_cxx +} // namespace std } // extern "C++" diff --git a/misc/uClibc++/include/uClibc++/list b/misc/uClibc++/include/uClibc++/list index de8edadd63..2fe182c66e 100644 --- a/misc/uClibc++/include/uClibc++/list +++ b/misc/uClibc++/include/uClibc++/list @@ -282,17 +282,16 @@ namespace std{ pop_front(); } delete list_start->val; -#if UCLIBCXX_DEBUG +#ifdef CONFIG_DEBUG_LIB list_start->val = 0; #endif delete list_start; -#if UCLIBCXX_DEBUG +#ifdef CONFIG_DEBUG_LIB list_start = 0; list_end = 0; #endif } - template void list::swap_nodes(node * x, node * y){ T * v = x->val; x->val = y->val; @@ -398,7 +397,7 @@ namespace std{ if(elements > 0){ list_start = list_start->next; delete list_start->previous->val; -#if UCLIBCXX_DEBUG +#ifdef CONFIG_DEBUG_LIB list_start->previous->val = 0; list_start->previous->next = 0; list_start->previous->previous = 0; @@ -438,13 +437,13 @@ namespace std{ list_end->previous = temp->previous; } delete temp->val; -#if UCLIBCXX_DEBUG +#ifdef CONFIG_DEBUG_LIB temp->val = 0; temp->next = 0; temp->previous = 0; #endif delete temp; -#if UCLIBCXX_DEBUG +#ifdef CONFIG_DEBUG_LIB temp = 0; #endif --elements; @@ -503,13 +502,13 @@ namespace std{ ++position; } delete temp->val; -#if UCLIBCXX_DEBUG +#ifdef CONFIG_DEBUG_LIB temp->next = 0; temp->previous = 0; temp->val = 0; #endif delete temp; -#if UCLIBCXX_DEBUG +#ifdef CONFIG_DEBUG_LIB temp = 0; #endif --elements; diff --git a/misc/uClibc++/libxx/uClibc++/Make.defs b/misc/uClibc++/libxx/uClibc++/Make.defs index a4e7a02f78..cf69adebe7 100644 --- a/misc/uClibc++/libxx/uClibc++/Make.defs +++ b/misc/uClibc++/libxx/uClibc++/Make.defs @@ -37,7 +37,7 @@ CXXSRCS += algorithm.cxx associative_base.cxx bitset.cxx char_traits.cxx CXXSRCS += complex.cxx del_op.cxx del_opnt.cxx del_opv.cxx del_opvnt.cxx -CXXSRCS += deque.cxx eh_alloc.cxx eh_globals.cxx exception.cxx +CXXSRCS += deque.cxx eh_alloc.cxx eh_globals.cxx eh_terminate.cxx exception.cxx CXXSRCS += fstream.cxx func_exception.cxx iomanip.cxx ios.cxx CXXSRCS += iostream.cxx istream.cxx iterator.cxx limits.cxx list.cxx CXXSRCS += locale.cxx map.cxx new_handler.cxx new_op.cxx new_opnt.cxx diff --git a/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx b/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx new file mode 100644 index 0000000000..f64be60d9c --- /dev/null +++ b/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx @@ -0,0 +1,75 @@ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include +#include + +#ifdef CONFIG_UCLIBCXX_EXCEPTION + +namespace std +{ + _UCXXEXPORT static terminate_handler __terminate_handler = abort; + _UCXXEXPORT static unexpected_handler __unexpected_handler = terminate; + + // Takes a new handler function as an argument, returns the old function. + + _UCXXEXPORT terminate_handler set_terminate(terminate_handler func) throw() + { + terminate_handler old = __terminate_handler; + __terminate_handler = func; + return old; + } + + /** The runtime will call this function if %exception handling must be + * abandoned for any reason. + */ + + _UCXXEXPORT void terminate(void) throw() + { + if (__terminate_handler) + { + __terminate_handler(); + } + + abort(); + } + + _UCXXEXPORT terminate_handler set_unexpected(unexpected_handler func) throw() + { + unexpected_handler old = __unexpected_handler; + __unexpected_handler = func; + return old; + } + + /** The runtime will call this function if an %exception is thrown which + * violates the function's %exception specification. + */ + + _UCXXEXPORT void unexpected(void) throw() + { + if (__unexpected_handler) + { + __unexpected_handler(); + } + + terminate(); + } +} + +#endif diff --git a/misc/uClibc++/libxx/uClibc++/exception.cxx b/misc/uClibc++/libxx/uClibc++/exception.cxx index 6d487a1167..81d0160039 100644 --- a/misc/uClibc++/libxx/uClibc++/exception.cxx +++ b/misc/uClibc++/libxx/uClibc++/exception.cxx @@ -1,22 +1,21 @@ /* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - -*/ + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include @@ -31,22 +30,20 @@ namespace std { _UCXXEXPORT static char * __std_exception_what_value = "exception"; - //We are providing our own versions to be sneaky - + // We are providing our own versions to be sneaky _UCXXEXPORT exception::~exception() throw() { - //Empty function + // Empty function } - _UCXXEXPORT const char* exception::what() const throw() + _UCXXEXPORT const char *exception::what() const throw() { return __std_exception_what_value; } _UCXXEXPORT bad_exception::~bad_exception() throw() { - } } From d1d50b4e0e4852ada470c6cad7d20633e4792ff4 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 2 Nov 2012 00:22:52 +0000 Subject: [PATCH 065/206] Add libsupc++ to sim/cxxtest configuration git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5296 42af7a65-404d-4744-a932-0658087f49c3 --- misc/uClibc++/libxx/uClibc++/Make.defs | 18 +++-- nuttx/arch/arm/src/Makefile | 26 +++---- nuttx/arch/sim/src/Makefile | 51 ++++++++------ nuttx/configs/sim/cxxtest/Make.defs | 98 +++++++++++++------------- nuttx/configs/sim/cxxtest/defconfig | 9 +++ nuttx/libxx/Kconfig | 11 ++- 6 files changed, 120 insertions(+), 93 deletions(-) diff --git a/misc/uClibc++/libxx/uClibc++/Make.defs b/misc/uClibc++/libxx/uClibc++/Make.defs index cf69adebe7..2a877ee3e9 100644 --- a/misc/uClibc++/libxx/uClibc++/Make.defs +++ b/misc/uClibc++/libxx/uClibc++/Make.defs @@ -37,13 +37,17 @@ CXXSRCS += algorithm.cxx associative_base.cxx bitset.cxx char_traits.cxx CXXSRCS += complex.cxx del_op.cxx del_opnt.cxx del_opv.cxx del_opvnt.cxx -CXXSRCS += deque.cxx eh_alloc.cxx eh_globals.cxx eh_terminate.cxx exception.cxx -CXXSRCS += fstream.cxx func_exception.cxx iomanip.cxx ios.cxx -CXXSRCS += iostream.cxx istream.cxx iterator.cxx limits.cxx list.cxx -CXXSRCS += locale.cxx map.cxx new_handler.cxx new_op.cxx new_opnt.cxx -CXXSRCS += new_opv.cxx new_opvnt.cxx numeric.cxx ostream.cxx queue.cxx -CXXSRCS += set.cxx sstream.cxx stack.cxx stdexcept.cxx streambuf.cxx -CXXSRCS += string.cxx typeinfo.cxx utility.cxx valarray.cxx vector.cxx +CXXSRCS += deque.cxx exception.cxx fstream.cxx func_exception.cxx +CXXSRCS += iomanip.cxx ios.cxx iostream.cxx istream.cxx iterator.cxx +CXXSRCS += limits.cxx list.cxx locale.cxx map.cxx new_handler.cxx +CXXSRCS += new_op.cxx new_opnt.cxx new_opv.cxx new_opvnt.cxx numeric.cxx +CXXSRCS += ostream.cxx queue.cxx set.cxx sstream.cxx stack.cxx +CXXSRCS += stdexcept.cxx streambuf.cxx string.cxx typeinfo.cxx utility.cxx +CXXSRCS += valarray.cxx vector.cxx + +ifneq ($(CONFIG_UCLIBCXX_HAVE_LIBSUPCXX),y) +CXXSRCS += eh_alloc.cxx eh_globals.cxx eh_terminate.cxx +endif # Add the path to the uClibc++ subdirectory diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index 74be6c18d1..49a651c4eb 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -100,18 +100,18 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libarch$(LIBEXT): $(OBJS) - @( for obj in $(OBJS) ; do \ + $(Q) ( for obj in $(OBJS) ; do \ $(call ARCHIVE, $@, $${obj}); \ done ; ) board/libboard$(LIBEXT): - @$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) + $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT) - @echo "LD: nuttx" - @$(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ + $(Q) echo "LD: nuttx" + $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ --start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group - @$(NM) $(NUTTX)$(EXEEXT) | \ + $(Q) $(NM) $(NUTTX)$(EXEEXT) | \ grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \ sort > $(TOPDIR)/System.map @@ -121,7 +121,7 @@ nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT) export_head: board/libboard$(LIBEXT) $(HEAD_OBJ) ifneq ($(HEAD_OBJ),) - @if [ -d "$(EXPORT_DIR)/startup" ]; then \ + $(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \ cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \ else \ echo "$(EXPORT_DIR)/startup does not exist"; \ @@ -132,26 +132,26 @@ endif # Dependencies .depend: Makefile chip/Make.defs $(SRCS) - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \ fi - @$(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \ + $(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \ $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) touch $@ depend: .depend clean: - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi - @rm -f libarch$(LIBEXT) *~ .*.swp + $(Q) rm -f libarch$(LIBEXT) *~ .*.swp $(call CLEAN) distclean: clean - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - @rm -f Make.dep .depend + $(Q) rm -f Make.dep .depend -include Make.dep diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile index 43210e37b9..cf8008b16b 100644 --- a/nuttx/arch/sim/src/Makefile +++ b/nuttx/arch/sim/src/Makefile @@ -100,12 +100,17 @@ ifeq ($(CONFIG_SIM_TOUCHSCREEN),y) endif endif +EXTRA_LIBS ?= + ifeq ($(CONFIG_FS_FAT),y) STDLIBS += -lz endif STDLIBS += -lc +LIBGCC := "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}" +GCC_LIBDIR := ${shell dirname $(LIBGCC)} + # Determine which objects are required in the link. The # up_head object normally draws in all that is needed, but # there are a fews that must be included because they @@ -129,7 +134,7 @@ LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS)))) # Add the board-specific library and directory -LDPATHS += -L board +LDPATHS += -L board -L $(GCC_LIBDIR) LDLIBS += -lboard # Make targets begin here @@ -145,13 +150,13 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(HOSTOBJS): %$(OBJEXT): %.c - @echo "CC: $<" - @$(CC) -c $(HOSTCFLAGS) $< -o $@ + $(Q) echo "CC: $<" + $(Q) $(CC) -c $(HOSTCFLAGS) $< -o $@ # The architecture-specific library libarch$(LIBEXT): $(NUTTXOBJS) - @( for obj in $(NUTTXOBJS) ; do \ + $(Q) ( for obj in $(NUTTXOBJS) ; do \ $(call ARCHIVE, $@, $${obj}); \ done ; ) @@ -160,35 +165,35 @@ libarch$(LIBEXT): $(NUTTXOBJS) # that are not hardware-related. board/libboard$(LIBEXT): - @$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) + $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) # A partially linked object containing only NuttX code (no interface to host OS) # Change the names of most symbols that conflict with libc symbols. GNU: - @mkdir ./GNU + $(Q) mkdir ./GNU GNU/Linux-names.dat: GNU nuttx-names.dat - @cp nuttx-names.dat $@ + $(Q) cp nuttx-names.dat $@ Cygwin-names.dat: nuttx-names.dat - @cat $^ | sed -e "s/^/_/g" >$@ + $(Q) cat $^ | sed -e "s/^/_/g" >$@ nuttx.rel : libarch$(LIBEXT) board/libboard$(LIBEXT) $(HOSTOS)-names.dat $(LINKOBJS) - @echo "LD: nuttx.rel" - @$(LD) -r $(LDLINKFLAGS) $(LDPATHS) -o $@ $(REQUIREDOBJS) --start-group $(LDLIBS) $(EXTRA_LIBS) --end-group - @$(OBJCOPY) --redefine-syms=$(HOSTOS)-names.dat $@ + $(Q) echo "LD: nuttx.rel" + $(Q) $(LD) -r $(LDLINKFLAGS) $(LDPATHS) -o $@ $(REQUIREDOBJS) --start-group $(LDLIBS) $(EXTRA_LIBS) --end-group + $(Q) $(OBJCOPY) --redefine-syms=$(HOSTOS)-names.dat $@ # Generate the final NuttX binary by linking the host-specific objects with the NuttX # specific objects (with munged names) nuttx$(EXEEXT): cleanrel nuttx.rel $(HOSTOBJS) - @echo "LD: nuttx$(EXEEXT)" - @$(CC) $(CCLINKFLAGS) $(LDPATHS) -o $(TOPDIR)/$@ nuttx.rel $(HOSTOBJS) $(DRVLIB) $(STDLIBS) - @$(NM) $(TOPDIR)/$@ | \ + $(Q) echo "LD: nuttx$(EXEEXT)" + $(Q) $(CC) $(CCLINKFLAGS) $(LDPATHS) -o $(TOPDIR)/$@ nuttx.rel $(HOSTOBJS) $(DRVLIB) $(STDLIBS) + $(Q) $(NM) $(TOPDIR)/$@ | \ grep -v '\(compiled\)\|\(\.o$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \ sort > $(TOPDIR)/System.map - @rm -f nuttx.rel + $(Q) rm -f nuttx.rel # This is part of the top-level export target @@ -200,26 +205,26 @@ export_head: board/libboard$(LIBEXT) up_head.o $(HOSTOBJS) # Dependencies .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend cleanrel: - @rm -f nuttx.rel GNU/Linux-names.dat Cygwin-names.dat + $(Q) rm -f nuttx.rel GNU/Linux-names.dat Cygwin-names.dat clean: cleanrel - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi - @rm -f nuttx.rel libarch$(LIBEXT) *~ .*.swp + $(Q) rm -f nuttx.rel libarch$(LIBEXT) *~ .*.swp $(call CLEAN) distclean: clean - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - @rm -f Make.dep .depend - @rm -rf GNU + $(Q) rm -f Make.dep .depend + $(Q) rm -rf GNU -include Make.dep diff --git a/nuttx/configs/sim/cxxtest/Make.defs b/nuttx/configs/sim/cxxtest/Make.defs index eac92e9282..eba0b31dd5 100644 --- a/nuttx/configs/sim/cxxtest/Make.defs +++ b/nuttx/configs/sim/cxxtest/Make.defs @@ -36,75 +36,77 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -HOSTOS = ${shell uname -o 2>/dev/null || echo "Other"} +HOSTOS = ${shell uname -o 2>/dev/null || echo "Other"} ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - ARCHOPTIMIZATION = -g + ARCHOPTIMIZATION = -g else - ARCHOPTIMIZATION = -O2 + ARCHOPTIMIZATION = -O2 endif -ARCHCPUFLAGS = -fno-builtin -ARCHCPUFLAGSXX = -fno-builtin -ARCHPICFLAGS = -fpic -ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -ARCHWARNINGSXX = -Wall -Wshadow -ARCHDEFINES = -ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx -isystem $(TOPDIR)/include/uClibc++ -ARCHSCRIPT = +ARCHCPUFLAGS = -fno-builtin +ARCHCPUFLAGSXX = -fno-builtin +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +ARCHDEFINES = +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include +ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx -isystem $(TOPDIR)/include/uClibc++ +ARCHSCRIPT = ifeq ($(CONFIG_SIM_M32),y) - ARCHCPUFLAGS += -m32 - ARCHCPUFLAGSXX += -m32 + ARCHCPUFLAGS += -m32 + ARCHCPUFLAGSXX += -m32 endif -CROSSDEV = -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 = +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 -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -CXXFLAGS = $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGSXX) $(ARCHINCLUDESXX) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -AFLAGS = $(CFLAGS) -D__ASSEMBLY__ +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXFLAGS = $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGSXX) $(ARCHINCLUDESXX) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ -OBJEXT = .o -LIBEXT = .a +OBJEXT = .o +LIBEXT = .a ifeq ($(HOSTOS),Cygwin) - EXEEXT = .exe + EXEEXT = .exe else - EXEEXT = + EXEEXT = endif -LDLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(LD) -CCLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(CC) -LDFLAGS = $(ARCHSCRIPT) # For backward compatibility, same as CCLINKFLAGS +LDLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(LD) +CCLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(CC) +LDFLAGS = $(ARCHSCRIPT) # For backward compatibility, same as CCLINKFLAGS ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - LDLINKFLAGS += -g - CCLINKFLAGS += -g - LDFLAGS += -g + LDLINKFLAGS += -g + CCLINKFLAGS += -g + LDFLAGS += -g endif ifeq ($(CONFIG_SIM_M32),y) - LDLINKFLAGS += -melf_i386 - CCLINKFLAGS += -m32 - LDFLAGS += -m32 + LDLINKFLAGS += -melf_i386 + CCLINKFLAGS += -m32 + LDFLAGS += -m32 endif -MKDEP = $(TOPDIR)/tools/mkdeps.sh +EXTRA_LIBS = -lsupc++ -HOSTCC = gcc -HOSTINCLUDES = -I. -HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -HOSTLDFLAGS = +MKDEP = $(TOPDIR)/tools/mkdeps.sh + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/sim/cxxtest/defconfig b/nuttx/configs/sim/cxxtest/defconfig index 20d4e5c853..d2fef0a554 100644 --- a/nuttx/configs/sim/cxxtest/defconfig +++ b/nuttx/configs/sim/cxxtest/defconfig @@ -276,12 +276,21 @@ CONFIG_ARCH_LOWPUTC=y CONFIG_LIB_SENDFILE_BUFSIZE=512 # CONFIG_ARCH_ROMGETC is not set # CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set + +# +# Basic CXX Support +# CONFIG_HAVE_CXX=y # CONFIG_HAVE_CXXINITIALIZE is not set # CONFIG_CXX_NEWLONG is not set + +# +# uClibc++ Standard C++ Library +# CONFIG_UCLIBCXX=y CONFIG_UCLIBCXX_EXCEPTION=y CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE=32 +CONFIG_UCLIBCXX_HAVE_LIBSUPCXX=y # # Application Configuration diff --git a/nuttx/libxx/Kconfig b/nuttx/libxx/Kconfig index 5ce2a8f7dd..8b5fc42e8b 100644 --- a/nuttx/libxx/Kconfig +++ b/nuttx/libxx/Kconfig @@ -3,6 +3,8 @@ # see misc/tools/kconfig-language.txt. # +comment "Basic CXX Support" + config HAVE_CXX bool "Have C++ compiler" default n @@ -12,8 +14,6 @@ config HAVE_CXX if HAVE_CXX -comment "Basic CXX Support" - config HAVE_CXXINITIALIZE bool "Have C++ initialization" default n @@ -50,5 +50,12 @@ config UCLIBCXX_IOSTREAM_BUFSIZE int "IO Stream Buffer Size" default 32 +config UCLIBCXX_HAVE_LIBSUPCXX + bool "Have libsupc++ (required)" + default y + ---help--- + Select if your toolchain provides libsupc++. This option is required + at present because the built-in libsupc++ support is incomplete. + endif endif From 4960d58d8b9494849f54a4972e91f0f0fa7ef077 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 2 Nov 2012 13:46:45 +0000 Subject: [PATCH 066/206] Fixes to STM32 definitions from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5297 42af7a65-404d-4744-a932-0658087f49c3 --- .../arch/arm/include/stm32/stm32f10xxx_irq.h | 48 +++++++------ .../arm/src/stm32/chip/stm32f103vc_pinmap.h | 2 +- .../arm/src/stm32/chip/stm32f105vb_pinmap.h | 2 +- .../arm/src/stm32/chip/stm32f107vc_pinmap.h | 2 +- .../src/stm32/chip/stm32f10xxx_memorymap.h | 71 ++++++++++++------- .../arm/src/stm32/chip/stm32f10xxx_vectors.h | 10 +-- 6 files changed, 82 insertions(+), 53 deletions(-) diff --git a/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h b/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h index 67f4ba436b..0a7c230bce 100644 --- a/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h +++ b/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h @@ -61,11 +61,13 @@ * External interrupts (vectors >= 16) */ -#if defined(CONFIG_STM32_VALUELINE) && defined(CONFIG_STM32_MEDIUMDENSITY) + /* Value line devices */ + +#if defined(CONFIG_STM32_VALUELINE) # define STM32_IRQ_WWDG (16) /* 0: Window Watchdog interrupt */ # define STM32_IRQ_PVD (17) /* 1: PVD through EXTI Line detection interrupt */ # define STM32_IRQ_TAMPER (18) /* 2: Tamper interrupt */ -# define STM32_IRQ_RTC (19) /* 3: RTC global interrupt */ +# define STM32_IRQ_RTC (19) /* 3: RTC Wakeup through EXTI line interrupt */ # define STM32_IRQ_FLASH (20) /* 4: Flash global interrupt */ # define STM32_IRQ_RCC (21) /* 5: RCC global interrupt */ # define STM32_IRQ_EXTI0 (22) /* 6: EXTI Line 0 interrupt */ @@ -80,12 +82,15 @@ # define STM32_IRQ_DMA1CH5 (31) /* 15: DMA1 Channel 5 global interrupt */ # define STM32_IRQ_DMA1CH6 (32) /* 16: DMA1 Channel 6 global interrupt */ # define STM32_IRQ_DMA1CH7 (33) /* 17: DMA1 Channel 7 global interrupt */ -# define STM32_IRQ_ADC12 (34) /* 18: ADC1 and ADC2 global interrupt */ +# define STM32_IRQ_ADC1 (34) /* 18: ADC1 global interrupt */ /* 19-22: reserved */ # define STM32_IRQ_EXTI95 (39) /* 23: EXTI Line[9:5] interrupts */ # define STM32_IRQ_TIM1BRK (40) /* 24: TIM1 Break interrupt */ -# define STM32_IRQ_TIM1UP (41) /* 25: TIM1 Update interrupt (TIM16 global interrupt) */ -# define STM32_IRQ_TIM1TRGCOM (42) /* 26: TIM1 Trigger and Commutation interrupts (TIM17 global interrupt) */ +# define STM32_IRQ_TIM15 (40) /* TIM15 global interrupt */ +# define STM32_IRQ_TIM1UP (41) /* 25: TIM1 Update interrupt */ +# define STM32_IRQ_TIM16 (41) /* TIM16 global interrupt */ +# define STM32_IRQ_TIM1TRGCOM (42) /* 26: TIM1 Trigger and Commutation interrupts */ +# define STM32_IRQ_TIM17 (42) /* TIM17 global interrupt */ # define STM32_IRQ_TIM1CC (43) /* 27: TIM1 Capture Compare interrupt */ # define STM32_IRQ_TIM2 (44) /* 28: TIM2 global interrupt */ # define STM32_IRQ_TIM3 (45) /* 29: TIM3 global interrupt */ @@ -100,29 +105,29 @@ # define STM32_IRQ_USART2 (54) /* 38: USART2 global interrupt */ # define STM32_IRQ_USART3 (55) /* 39: USART3 global interrupt */ # define STM32_IRQ_EXTI1510 (56) /* 40: EXTI Line[15:10] interrupts */ -# define STM32_IRQ_RTCALR (57) /* 41: RTC alarm through EXTI line interrupt */ +# define STM32_IRQ_RTCALR (57) /* 41: RTC alarms (A and B) through EXTI line interrupt */ # define STM32_IRQ_CEC (58) /* 42: CEC global interrupt */ -# if defined(CONFIG_STM32_HIGHDENSITY) -# define STM32_IRQ_TIM12 (59) /* 43: TIM12 global interrupt */ -# define STM32_IRQ_TIM13 (60) /* 44: TIM13 global interrupt */ -# define STM32_IRQ_TIM14 (61) /* 45: TIM14 global interrupt */ +# define STM32_IRQ_TIM12 (59) /* 43: TIM12 global interrupt */ +# define STM32_IRQ_TIM13 (60) /* 44: TIM13 global interrupt */ +# define STM32_IRQ_TIM14 (61) /* 45: TIM14 global interrupt */ /* 46-47: reserved */ -# define STM32_IRQ_FSMC (64) /* 48: FSMC global interrupt */ +# define STM32_IRQ_FSMC (64) /* 48: FSMC global interrupt */ /* 49: reserved */ -# define STM32_IRQ_TIM5 (66) /* 50: TIM5 global interrupt */ -# define STM32_IRQ_SPI3 (67) /* 51: SPI1 global interrupt */ -# define STM32_IRQ_UART4 (68) /* 52: USART2 global interrupt */ -# define STM32_IRQ_UART5 (69) /* 53: USART3 global interrupt */ -# else - /* 43-53: reserved */ -# endif +# define STM32_IRQ_TIM5 (66) /* 50: TIM5 global interrupt */ +# define STM32_IRQ_SPI3 (67) /* 51: SPI3 global interrupt */ +# define STM32_IRQ_UART4 (68) /* 52: USART2 global interrupt */ +# define STM32_IRQ_UART5 (69) /* 53: USART5 global interrupt */ # define STM32_IRQ_TIM6 (70) /* 54: TIM6 global interrupt */ # define STM32_IRQ_TIM7 (71) /* 55: TIM7 global interrupt */ # define STM32_IRQ_DMA2CH1 (72) /* 56: DMA2 Channel 1 global interrupt */ # define STM32_IRQ_DMA2CH2 (73) /* 57: DMA2 Channel 2 global interrupt */ # define STM32_IRQ_DMA2CH3 (74) /* 58: DMA2 Channel 3 global interrupt */ -# define STM32_IRQ_DMA2CH45 (75) /* 59: DMA2 Channel 4 global interrupt */ -# define NR_IRQS (76) +# define STM32_IRQ_DMA2CH45 (75) /* 59: DMA2 Channel 4 and 5 global interrupt */ +# define STM32_IRQ_DMA2CH5 (76) /* 60: DMA2 Channel 5 global interrupt */ +# define NR_IRQS (77) + +/* Connectivity Line Devices */ + #elif defined(CONFIG_STM32_CONNECTIVITYLINE) # define STM32_IRQ_WWDG (16) /* 0: Window Watchdog interrupt */ # define STM32_IRQ_PVD (17) /* 1: PVD through EXTI Line detection interrupt */ @@ -193,6 +198,9 @@ # define STM32_IRQ_CAN2SCE (82) /* 66: CAN2 SCE interrupt */ # define STM32_IRQ_OTGFS (83) /* 67: USB On The Go FS global interrupt */ # define NR_IRQS (84) + +/* Medium and High Density Devices */ + #else # define STM32_IRQ_WWDG (16) /* 0: Window Watchdog interrupt */ # define STM32_IRQ_PVD (17) /* 1: PVD through EXTI Line detection interrupt */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h index 1606768025..52a513215d 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h @@ -129,7 +129,7 @@ #if 0 /* Needs further investigation */ -#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUTz|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) #define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) #endif diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h index 7a5ec3381e..054a7337db 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h @@ -85,7 +85,7 @@ #endif #if 0 /* Needs further investigation */ -#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUTz|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) #define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) #endif diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h index 9bbc214798..2419620fc4 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h @@ -85,7 +85,7 @@ #endif #if 0 /* Needs further investigation */ -#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUTz|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) #define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) #endif diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h index ed1bc26259..e38414f311 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h @@ -60,7 +60,14 @@ #define STM32_TIM5_BASE 0x40000c00 /* 0x40000c00 - 0x40000fff: TIM5 timer */ #define STM32_TIM6_BASE 0x40001000 /* 0x40001000 - 0x400013ff: TIM6 timer */ #define STM32_TIM7_BASE 0x40001400 /* 0x40001400 - 0x400007ff: TIM7 timer */ - /* 0x40001800 - 0x40000fff: Reserved */ +#if defined(CONFIG_STM32_VALUELINE) +# define STM32_TIM12_BASE 0x40001800 /* 0x40001800 - 0x40001bff: TIM12 timer */ +# define STM32_TIM13_BASE 0x40001c00 /* 0x40001c00 - 0x40001fff: TIM13 timer */ +# define STM32_TIM14_BASE 0x40002000 /* 0x40002000 - 0x400023ff: TIM14 timer */ + /* 0x40002400 - 0x400027ff: Reserved */ +#else + /* 0x40001800 - 0x40027fff: Reserved */ +#endif #define STM32_RTC_BASE 0x40002800 /* 0x40002800 - 0x40002bff: RTC */ #define STM32_WWDG_BASE 0x40002c00 /* 0x40002C00 - 0x40002fff: Window watchdog (WWDG) */ #define STM32_IWDG_BASE 0x40003000 /* 0x40003000 - 0x400033ff: Independent watchdog (IWDG) */ @@ -83,7 +90,12 @@ #define STM32_BKP_BASE 0x40006c00 /* 0x40006c00 - 0x40006fff: Backup registers (BKP) */ #define STM32_PWR_BASE 0x40007000 /* 0x40007000 - 0x400073ff: Power control PWR */ #define STM32_DAC_BASE 0x40007400 /* 0x40007400 - 0x400077ff: DAC */ +#if defined(CONFIG_STM32_VALUELINE) +# define STM32_CEC_BASE 0x40007800 /* 0x40007800 - 0x40007bff: CEC */ + /* 0x40007c00 - 0x4000ffff: Reserved */ +#else /* 0x40007800 - 0x4000ffff: Reserved */ +#endif /* APB2 bus */ @@ -102,44 +114,53 @@ #define STM32_SPI1_BASE 0x40013000 /* 0x40013000 - 0x400133ff: SPI1 */ #define STM32_TIM8_BASE 0x40013400 /* 0x40013400 - 0x400137ff: TIM8 timer */ #define STM32_USART1_BASE 0x40013800 /* 0x40013800 - 0x40013bff: USART1 */ -#define STM32_ADC3_BASE 0x40012800 /* 0x40012800 - 0x40013fff: ADC3 */ - /* 0x40014000 - 0x40017fff: Reserved */ +#define STM32_ADC3_BASE 0x40012800 /* 0x40012800 - 0x40013c00: ADC3 */ +#if defined(CONFIG_STM32_VALUELINE) + /* 0x40013c00 - 0x40013fff: Reserved */ +# define STM32_TIM15_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM15 */ +# define STM32_TIM16_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM16 */ +# define STM32_TIM17_BASE 0x40014800 /* 0x40014800 - 0x40014bff: TIM17 */ + /* 0x40014c00 - 0x4001ffff: Reserved */ +#else + /* 0x40013c00 - 0x4001ffff: Reserved */ +#endif + /* AHB bus */ -#define STM32_SDIO_BASE 0x40018000 /* 0x40018000 - 0x400183ff: SDIO */ - /* 0x40018400 - 0x40017fff: Reserved */ -#define STM32_DMA1_BASE 0x40020000 /* 0x40020000 - 0x400203ff: DMA1 */ -#define STM32_DMA2_BASE 0x40020400 /* 0x40020000 - 0x400207ff: DMA2 */ - /* 0x40020800 - 0x40020fff: Reserved */ -#define STM32_RCC_BASE 0x40021000 /* 0x40021000 - 0x400213ff: Reset and Clock control RCC */ - /* 0x40021400 - 0x40021fff: Reserved */ -#define STM32_OTGFS_BASE 0x50000000 /* 0x50000000 - 0x500003ff: USB OTG FS */ -#define STM32_FLASHIF_BASE 0x40022000 /* 0x40022000 - 0x400223ff: Flash memory interface */ -#define STM32_CRC_BASE 0x40028000 /* 0x40023000 - 0x400233ff: CRC */ - /* 0x40023400 - 0x40027fff: Reserved */ -#define STM32_ETHERNET_BASE 0x40028000 /* 0x40028000 - 0x40029fff: Ethernet */ - /* 0x40030000 - 0x4fffffff: Reserved */ +#define STM32_SDIO_BASE 0x40018000 /* 0x40018000 - 0x400183ff: SDIO */ + /* 0x40018400 - 0x40017fff: Reserved */ +#define STM32_DMA1_BASE 0x40020000 /* 0x40020000 - 0x400203ff: DMA1 */ +#define STM32_DMA2_BASE 0x40020400 /* 0x40020000 - 0x400207ff: DMA2 */ + /* 0x40020800 - 0x40020fff: Reserved */ +#define STM32_RCC_BASE 0x40021000 /* 0x40021000 - 0x400213ff: Reset and Clock control RCC */ + /* 0x40021400 - 0x40021fff: Reserved */ +#define STM32_OTGFS_BASE 0x50000000 /* 0x50000000 - 0x500003ff: USB OTG FS */ +#define STM32_FLASHIF_BASE 0x40022000 /* 0x40022000 - 0x400223ff: Flash memory interface */ +#define STM32_CRC_BASE 0x40028000 /* 0x40023000 - 0x400233ff: CRC */ + /* 0x40023400 - 0x40027fff: Reserved */ +#define STM32_ETHERNET_BASE 0x40028000 /* 0x40028000 - 0x40029fff: Ethernet */ + /* 0x40030000 - 0x4fffffff: Reserved */ /* Peripheral BB base */ -#define STM32_PERIPHBB_BASE 0x42000000 +#define STM32_PERIPHBB_BASE 0x42000000 /* Flexible SRAM controller (FSMC) */ -#define STM32_FSMC_BANK1 0x60000000 /* 0x60000000-0x6fffffff: 256Mb NOR/SRAM */ -#define STM32_FSMC_BANK2 0x70000000 /* 0x70000000-0x7fffffff: 256Mb NAND FLASH */ -#define STM32_FSMC_BANK3 0x80000000 /* 0x80000000-0x8fffffff: 256Mb NAND FLASH */ -#define STM32_FSMC_BANK4 0x90000000 /* 0x90000000-0x9fffffff: 256Mb PC CARD*/ -#define STM32_IS_EXTSRAM(a) ((((uint32_t)(a)) & STM32_REGION_MASK) == STM32_FSMC_BANK1) +#define STM32_FSMC_BANK1 0x60000000 /* 0x60000000-0x6fffffff: 256Mb NOR/SRAM */ +#define STM32_FSMC_BANK2 0x70000000 /* 0x70000000-0x7fffffff: 256Mb NAND FLASH */ +#define STM32_FSMC_BANK3 0x80000000 /* 0x80000000-0x8fffffff: 256Mb NAND FLASH */ +#define STM32_FSMC_BANK4 0x90000000 /* 0x90000000-0x9fffffff: 256Mb PC CARD*/ +#define STM32_IS_EXTSRAM(a) ((((uint32_t)(a)) & STM32_REGION_MASK) == STM32_FSMC_BANK1) -#define STM32_FSMC_BASE 0xa0000000 /* 0xa0000000-0xbfffffff: 512Mb FSMC register block */ +#define STM32_FSMC_BASE 0xa0000000 /* 0xa0000000-0xbfffffff: 512Mb FSMC register block */ /* Other registers -- see armv7-m/nvic.h for standard Cortex-M3 registers in this * address range */ -#define STM32_SCS_BASE 0xe000e000 -#define STM32_DEBUGMCU_BASE 0xe0042000 +#define STM32_SCS_BASE 0xe000e000 +#define STM32_DEBUGMCU_BASE 0xe0042000 #endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F10XXX_MEMORYMAP_H */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h index b8d71799fe..1259f2fce8 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h @@ -49,15 +49,15 @@ * definition that provides the number of supported vectors. */ -#ifdef CONFIG_ARMV7M_CMNVECTOR +# ifdef CONFIG_ARMV7M_CMNVECTOR -/* Reserve 60 interrupt table entries for I/O interrupts. */ +/* Reserve 61 interrupt table entries for I/O interrupts. */ -# define ARMV7M_PERIPHERAL_INTERRUPTS 60 +# define ARMV7M_PERIPHERAL_INTERRUPTS 61 #else -# error This target requires CONFIG_ARMV7M_CMNVECTOR -#endif /* CONFIG_ARMV7M_CMNVECTOR */ +# error This target requires CONFIG_ARMV7M_CMNVECTOR +# endif /* CONFIG_ARMV7M_CMNVECTOR */ #elif defined(CONFIG_STM32_CONNECTIVITYLINE) From 1850aff2781332939dcffdf9964cb8f291017f18 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 2 Nov 2012 13:55:04 +0000 Subject: [PATCH 067/206] Another fix to STM32 definitions from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5298 42af7a65-404d-4744-a932-0658087f49c3 --- .../arm/src/stm32/chip/stm32f103ze_pinmap.h | 94 +++++++++---------- 1 file changed, 47 insertions(+), 47 deletions(-) diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h index 9bcee49f57..581b026a09 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h @@ -50,53 +50,53 @@ /* ADC */ -#define GPIO_ADC1_IN0 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -#define GPIO_ADC1_IN1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) -#define GPIO_ADC1_IN2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -#define GPIO_ADC1_IN3 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -#define GPIO_ADC1_IN4 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) -#define GPIO_ADC1_IN5 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) -#define GPIO_ADC1_IN6 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) -#define GPIO_ADC1_IN7 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) -#define GPIO_ADC1_IN8 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) -#define GPIO_ADC1_IN9 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) -#define GPIO_ADC1_IN10 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) -#define GPIO_ADC1_IN11 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) -#define GPIO_ADC1_IN12 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) -#define GPIO_ADC1_IN13 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) -#define GPIO_ADC1_IN14 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) -#define GPIO_ADC1_IN15 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) +#define GPIO_ADC1_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC1_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC1_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC1_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC1_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC1_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC1_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC1_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC1_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC1_IN9 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) +#define GPIO_ADC1_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC1_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC1_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC1_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC1_IN14 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC1_IN15 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) -#define GPIO_ADC2_IN0 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -#define GPIO_ADC2_IN1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) -#define GPIO_ADC2_IN2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -#define GPIO_ADC2_IN3 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -#define GPIO_ADC2_IN4 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) -#define GPIO_ADC2_IN5 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) -#define GPIO_ADC2_IN6 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) -#define GPIO_ADC2_IN7 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) -#define GPIO_ADC2_IN8 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) -#define GPIO_ADC2_IN9 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) -#define GPIO_ADC2_IN10 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) -#define GPIO_ADC2_IN11 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) -#define GPIO_ADC2_IN12 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) -#define GPIO_ADC2_IN13 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) -#define GPIO_ADC2_IN14 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) -#define GPIO_ADC2_IN15 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) +#define GPIO_ADC2_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC2_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC2_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC2_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC2_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC2_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC2_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC2_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC2_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC2_IN9 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) +#define GPIO_ADC2_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC2_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC2_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC2_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC2_IN14 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC2_IN15 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) -#define GPIO_ADC3_IN0 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -#define GPIO_ADC3_IN1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) -#define GPIO_ADC3_IN2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -#define GPIO_ADC3_IN3 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -#define GPIO_ADC3_IN4 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN6) -#define GPIO_ADC3_IN5 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN7) -#define GPIO_ADC3_IN6 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN8) -#define GPIO_ADC3_IN7 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN9) -#define GPIO_ADC3_IN8 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN10) -#define GPIO_ADC3_IN10 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) -#define GPIO_ADC3_IN11 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) -#define GPIO_ADC3_IN12 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) -#define GPIO_ADC3_IN13 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC3_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC3_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC3_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC3_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC3_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN6) +#define GPIO_ADC3_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN7) +#define GPIO_ADC3_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN8) +#define GPIO_ADC3_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN9) +#define GPIO_ADC3_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN10) +#define GPIO_ADC3_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC3_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC3_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC3_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) /* DAC - "Once the DAC channelx is enabled, the corresponding GPIO pin * (PA4 or PA5) is automatically connected to the analog converter output @@ -104,8 +104,8 @@ * should first be configured to analog (AIN)." */ -#define GPIO_DAC_OUT1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN10) -#define GPIO_DAC_OUT2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PIN10) +#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) /* TIMERS */ From 708ebb52f0dd9c4305aedf7dcbd4ad8dc5f03aed Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 2 Nov 2012 16:35:37 +0000 Subject: [PATCH 068/206] More uClibc++ build fixes git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5299 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/README.txt | 6 +- misc/uClibc++/include/uClibc++/deque | 1910 +++++++++------- misc/uClibc++/include/uClibc++/string | 1991 ++++++++++------- misc/uClibc++/libxx/uClibc++/Make.defs | 17 +- misc/uClibc++/libxx/uClibc++/eh_terminate.cxx | 4 - .../libxx/uClibc++/func_exception.cxx | 16 +- misc/uClibc++/libxx/uClibc++/stdexcept.cxx | 93 +- misc/uClibc++/libxx/uClibc++/string.cxx | 130 +- nuttx/configs/sim/README.txt | 13 + nuttx/configs/sim/cxxtest/Make.defs | 6 +- 10 files changed, 2339 insertions(+), 1847 deletions(-) diff --git a/apps/examples/README.txt b/apps/examples/README.txt index bfd61b73e8..3f24ec4e29 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -247,9 +247,13 @@ examples/cxxtest is not included in the NuttX source tree by default, but must be installed (see misc/uClibc++/README.txt for installation). - The only NuttX setting that is required is: + The NuttX setting that are required include: CONFIG_HAVE_CXX=y + CONFIG_HAVE_CXXINITIALIZE=y + CONFIG_UCLIBCXX=y + + Additional uClibc++ settings may be required in your build environment. The uClibc++ test includes simple test of: diff --git a/misc/uClibc++/include/uClibc++/deque b/misc/uClibc++/include/uClibc++/deque index ff07ab51c9..19be5c8bb4 100644 --- a/misc/uClibc++/include/uClibc++/deque +++ b/misc/uClibc++/include/uClibc++/deque @@ -1,22 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. +/* Copyright (C) 2004 Garrett A. Kajmowicz + This file is part of the uClibc++ Library. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ - #include #include #include @@ -26,854 +25,1039 @@ #ifndef __STD_HEADER_DEQUE #define __STD_HEADER_DEQUE - -namespace std{ - template > class deque; - template bool operator==(const deque& x, const deque& y); - template bool operator< (const deque& x, const deque& y); - template bool operator!=(const deque& x, const deque& y); - template bool operator> (const deque& x, const deque& y); - template bool operator>=(const deque& x, const deque& y); - template bool operator<=(const deque& x, const deque& y); - template void swap(deque& x, deque& y); - - template class _UCXXEXPORT deque { - public: - friend bool operator==<>(const deque& x, const deque& y); - friend class deque_iter; - friend class deque_citer; - class deque_iter; - class deque_citer; - - typedef typename Allocator::reference reference; - typedef typename Allocator::const_reference const_reference; - typedef deque_iter iterator; - typedef deque_citer const_iterator; - typedef typename Allocator::size_type size_type; - typedef typename Allocator::difference_type difference_type; - typedef T value_type; - typedef Allocator allocator_type; - typedef typename Allocator::pointer pointer; - typedef typename Allocator::const_pointer const_pointer; - typedef std::reverse_iterator reverse_iterator; - typedef std::reverse_iterator const_reverse_iterator; - - explicit deque(const Allocator& al = Allocator()); - explicit deque(size_type n, const T& value = T(), const Allocator& al = Allocator()); - template deque(InputIterator first, InputIterator last, const Allocator& = Allocator()); - deque(const deque& x); - ~deque(); - - deque& operator=(const deque& x); - template void assign(InputIterator first, InputIterator last); - template void assign(Size n, const U& u = U()); - allocator_type get_allocator() const; - - iterator begin(); - const_iterator begin() const; - iterator end(); - const_iterator end() const; - reverse_iterator rbegin(); - const_reverse_iterator rbegin() const; - reverse_iterator rend(); - const_reverse_iterator rend() const; - - size_type size() const; - size_type max_size() const; - void resize(size_type sz, T c = T()); - bool empty() const; - - reference operator[](size_type n); - const_reference operator[](size_type n) const; - reference at(size_type n); - const_reference at(size_type n) const; - reference front(); - const_reference front() const; - reference back(); - const_reference back() const; - - void push_front(const T& x); - void push_back(const T& x); - iterator insert(iterator position, const T& x = T()); - void insert(iterator position, size_type n, const T& x); - template void insert (iterator position, InputIterator first, InputIterator last); - void pop_front(); - void pop_back(); - - iterator erase(iterator position); - iterator erase(iterator first, iterator last); - void swap(deque&); - void clear(); - - protected: - void reserve(size_type n); - inline size_type array_element(size_type deque_element) const{ - if(deque_element < (data_size - first_element)){ - return first_element + deque_element; - } - return deque_element - (data_size - first_element); - } - inline size_type first_subtract(size_type sub_size) const{ - if(sub_size > first_element){ - return (data_size - first_element) - sub_size; - } - return first_element - sub_size; - } - - T * data; - size_type data_size; //Physical size of array - size_type elements; //Elements in array - size_type first_element; //Element number of array 0..n - size_type last_element; //Element number of array 0..n - Allocator a; - - }; - - - template class _UCXXEXPORT deque::deque_iter - : public std::iterator< - random_access_iterator_tag, - T, - typename Allocator::difference_type, - typename Allocator::pointer, - typename Allocator::reference - > - { - friend class deque; - protected: - deque * container; - typename Allocator::size_type element; - - public: - deque_iter() : container(0), element(0) { } - deque_iter(const deque_iter & d) : container (d.container), element(d.element) { } - deque_iter(deque * c, typename Allocator::size_type e) - : container(c), element(e) - { - return; - } - ~deque_iter() { } - deque_iter & operator=(const deque_iter & d){ - container = d.container; - element = d.element; - return *this; - } - T & operator*(){ - return container->data[container->array_element(element)]; - } - T * operator->(){ - return container->data + container->array_element(element); - } - const T & operator*() const{ - return container->data[container->array_element(element)]; - } - const T * operator->() const{ - return container->data + container->array_element(element); - } - bool operator==(const deque_iter & d) const{ - if(container == d.container && element == d.element){ - return true; - } - return false; - } - bool operator==(const deque_citer & d) const{ - if(container == d.container && element == d.element){ - return true; - } - return false; - } - bool operator!=(const deque_iter & d) const{ - if(container != d.container || element != d.element){ - return true; - } - return false; - } - bool operator!=(const deque_citer & d) const{ - if(container != d.container || element != d.element){ - return true; - } - return false; - } - bool operator<(const deque_iter & d) const{ - if(element < d.element){ - return true; - } - return false; - } - bool operator<(const deque_citer & d) const{ - if(element < d.element){ - return true; - } - return false; - } - bool operator<=(const deque_iter & d) const{ - if(element <= d.element){ - return true; - } - return false; - } - bool operator<=(const deque_citer & d) const{ - if(element <= d.element){ - return true; - } - return false; - } - bool operator>(const deque_iter & d) const{ - if(element > d.element){ - return true; - } - return false; - } - bool operator>(const deque_citer & d) const{ - if(element > d.element){ - return true; - } - return false; - } - bool operator>=(const deque_iter & d) const{ - if(element >= d.element){ - return true; - } - return false; - } - bool operator>=(const deque_citer & d) const{ - if(element >= d.element){ - return true; - } - return false; - } - deque_iter & operator++(){ - ++element; - return *this; - } - deque_iter operator++(int){ - deque_iter temp(container, element); - ++element; - return temp; - } - deque_iter operator+(typename Allocator::size_type n){ - deque_iter temp(container, element + n); - return temp; - } - deque_iter & operator+=(typename Allocator::size_type n){ - element += n; - return *this; - } - deque_iter & operator--(){ - --element; - return *this; - } - deque_iter operator--(int){ - deque_iter temp(container, element); - --element; - return temp; - } - deque_iter operator-(typename Allocator::size_type n){ - deque_iter temp(container, element - n); - return temp; - } - deque_iter & operator-=(typename Allocator::size_type n){ - element -= n; - return *this; - } - typename Allocator::size_type operator-(const deque_iter & d){ - return element - d.element; - } - - }; - - template class _UCXXEXPORT deque::deque_citer - : public std::iterator< - random_access_iterator_tag, - T, - typename Allocator::difference_type, - typename Allocator::const_pointer, - typename Allocator::const_reference - > - { - friend class deque; - protected: - const deque * container; - typename Allocator::size_type element; - - public: - deque_citer() : container(0), element(0) { } - deque_citer(const deque_citer & d) : container (d.container), element(d.element) { } - deque_citer(const deque_iter & d) : container (d.container), element(d.element) { } - deque_citer(const deque * c, typename Allocator::size_type e) - : container(c), element(e) - { - return; - } - ~deque_citer() { } - deque_citer & operator=(const deque_iter & d){ - container = d.container; - element = d.element; - return *this; - } - const T & operator*() const{ - return container->data[container->array_element(element)]; - } - const T * operator->() const{ - return container->data + container->array_element(element); - } - bool operator==(const deque_citer & d) const{ - if(container == d.container && element == d.element){ - return true; - } - return false; - } - bool operator==(const deque_iter & d) const{ - if(container == d.container && element == d.element){ - return true; - } - return false; - } - bool operator!=(const deque_citer & d) const{ - if(container != d.container || element != d.element){ - return true; - } - return false; - } - bool operator!=(const deque_iter & d) const{ - if(container != d.container || element != d.element){ - return true; - } - return false; - } - bool operator<(const deque_citer & d) const{ - if(element < d.element){ - return true; - } - return false; - } - bool operator<(const deque_iter & d) const{ - if(element < d.element){ - return true; - } - return false; - } - bool operator<=(const deque_citer & d) const{ - if(element <= d.element){ - return true; - } - return false; - } - bool operator<=(const deque_iter & d) const{ - if(element <= d.element){ - return true; - } - return false; - } - bool operator>(const deque_citer & d) const{ - if(element > d.element){ - return true; - } - return false; - } - bool operator>(const deque_iter & d) const{ - if(element > d.element){ - return true; - } - return false; - } - bool operator>=(const deque_citer & d){ - if(element >= d.element){ - return true; - } - return false; - } - bool operator>=(const deque_iter & d){ - if(element >= d.element){ - return true; - } - return false; - } - deque_citer & operator++(){ - ++element; - return *this; - } - deque_citer operator++(int){ - deque_citer temp(container, element); - ++element; - return temp; - } - deque_citer operator+(typename Allocator::size_type n){ - deque_citer temp(container, element + n); - return temp; - } - deque_citer & operator+=(typename Allocator::size_type n){ - element += n; - return *this; - } - deque_citer & operator--(){ - --element; - return *this; - } - deque_citer operator--(int){ - deque_citer temp(container, element); - --element; - return temp; - } - deque_citer operator-(typename Allocator::size_type n){ - deque_citer temp(container, element - n); - return temp; - } - deque_citer & operator-=(typename Allocator::size_type n){ - element -= n; - return *this; - } - typename Allocator::size_type operator-(const deque_citer & d){ - return element - d.element; - } - - }; - - template deque::deque(const Allocator& al) - : data(0), - data_size(0), elements(0), first_element(0), last_element(0), a(al) - { - data_size = __UCLIBCXX_STL_BUFFER_SIZE__; - data = a.allocate(data_size); - first_element = data_size /2; - last_element = first_element; - } - - - template deque::deque( - size_type n, const T& value, const Allocator& al) - : data(0), - elements(n), first_element(0), last_element(0), a(al) - { - data_size = elements + __UCLIBCXX_STL_BUFFER_SIZE__; - data = a.allocate(data_size); - first_element = (data_size - elements) / 2; - last_element = first_element; - - for(n=first_element ; n < last_element; ++n ){ - a.construct(data+n, value); - } - } - - - template template - deque::deque(InputIterator first, InputIterator last, const Allocator& al) - : data(0), - data_size(0), elements(0), first_element(0), last_element(0), a(al) - { - data_size = __UCLIBCXX_STL_BUFFER_SIZE__; - data = a.allocate(data_size); - first_element = data_size / 4; //Note sure how big, but let's add a little space... - last_element = first_element; - while(first != last){ - push_back(*first); - ++first; - } - } - - - template deque::deque(const deque& x) - : data(0), - elements(0), first_element(0), last_element(0), a(x.a) - { - data_size = x.elements + __UCLIBCXX_STL_BUFFER_SIZE__; - data = a.allocate(data_size); - first_element = (data_size - x.elements) / 2; - last_element = first_element; - for(size_type i=0; i < x.elements; ++i){ - push_back(x[i]); - } - } - - - template deque::~deque(){ - clear(); - a.deallocate(data, data_size); - } - - template deque& deque:: - operator=(const deque& x) - { - if(&x == this){ - return *this; - } - resize(x.elements); - for(size_t i = 0; i < elements; ++i){ - data[array_element(i)] = x[i]; - } - return *this; - } - - - template template void - deque::assign(InputIterator first, InputIterator last) - { - clear(); - while(first !=last){ - push_back(*first); - ++first; - } - } - - - template template void - deque::assign(Size n, const U& u) - { - if(&u == this){ - return; - } - clear(); - for(size_type i = 0; i < n; ++i){ - push_back(u); - } - } - - - template typename deque::allocator_type - deque::get_allocator() const - { - return a; - } - - template typename - deque::iterator deque::begin() - { - return deque_iter(this, 0); - } - - - template typename deque::const_iterator - deque::begin() const - { - return deque_citer(this, 0); - } - - template typename - deque::iterator deque::end() - { - return deque_iter(this, elements); - } - - template typename - deque::const_iterator deque::end() const - { - return deque_citer(this, elements); - } - - template typename - deque::reverse_iterator deque::rbegin() - { - return reverse_iterator(end()); - } - - template typename - deque::const_reverse_iterator deque::rbegin() const - { - return const_reverse_iterator(end()); - } - - template typename - deque::reverse_iterator deque::rend() - { - return reverse_iterator(begin()); - } - - template typename - deque::const_reverse_iterator deque::rend() const - { - return const_reverse_iterator(begin()); - } - - template typename - deque::size_type deque::size() const - { - return elements; - } - - template typename - deque::size_type deque::max_size() const - { - return ((size_type)(-1)) / sizeof(T); - } - - template void deque::resize(size_type sz, T c){ - reserve(sz); - while(sz > size()){ - push_back(c); - } - while(sz < size()){ - pop_back(); - } - } - - template bool deque::empty() const{ - return (elements == 0); - } - - template typename - deque::reference deque::operator[](size_type n) - { - return data[array_element(n)]; - } - - template typename - deque::const_reference deque::operator[](size_type n) const - { - return data[array_element(n)]; - } - - template typename - deque::reference deque::at(size_type n) - { - if(n > elements){ - __throw_out_of_range("Out of deque range"); - } - return data[array_element(n)]; - } - - template typename - deque::const_reference deque::at(size_type n) const - { - if(n > elements){ - __throw_out_of_range("Out of deque range"); - } - return data[array_element(n)]; - } - - template typename - deque::reference deque::front() - { - return data[first_element]; - } - - template typename - deque::const_reference deque::front() const - { - return data[first_element]; - } - - template typename - deque::reference deque::back() - { - return data[array_element(elements-1)]; - } - - template typename - deque::const_reference deque::back() const - { - return data[array_element(elements-1)]; - } - - template void deque::push_front(const T& x){ - reserve(elements + 1); - first_element = first_subtract(1); - a.construct(data + first_element, x); - ++elements; - } - - template void deque::push_back(const T& x){ - reserve(elements + 1); - a.construct(data + last_element, x); - ++elements; - last_element = array_element(elements); - } - - template typename - deque::iterator deque::insert(iterator position, const T& x) - { - reserve(elements+1); - if(position.element > (elements/2)){ - //Push all elements back 1 - push_back(x); - for(size_type i = elements-1; i > position.element; --i){ - at(i) = at(i-1); - } - }else{ - //Push all elements forward 1 - push_front(x); - for(size_type i = 0; i < position.element; ++i){ - at(i) = at(i+1); - } - } - at(position.element) = x; - return deque_iter(this, position.element); - } - - template void deque:: - insert(typename deque::iterator position, size_type n, const T& x) - { - reserve(elements + n); - for(size_t i =0; i < n; ++i){ - position = insert(position, x); - } - } - - template template - void deque::insert (iterator position, InputIterator first, InputIterator last) - { - while(first != last){ - position = insert(position, *first); - ++first; - } - } - - template void deque::pop_front(){ - if(elements == 0){ - __throw_out_of_range("deque pop_front"); - } - a.destroy(data + first_element); - first_element = array_element(1); - --elements; - } - - template void deque::pop_back(){ - last_element = array_element(elements - 1); - a.destroy(data + last_element); - --elements; - } - - template typename - deque::iterator deque::erase(typename deque::iterator position) - { - if(position.element > (elements /2)){ - for(size_type i = position.element; i < elements - 1; ++i){ - at(i) = at(i+1); - } - pop_back(); - }else{ - for(size_type i = position.element; i > 0; --i){ - at(i) = at(i-1); - } - pop_front(); - } - return deque_iter(this, position.element); - } - - template typename deque::iterator - deque:: - erase(typename deque::iterator first, typename deque::iterator last) - { - //Shift backwards - size_type num_move = last.element - first.element; - if( first.element > (elements - last.element) ){ - for(size_type i = last.element; i < elements ; ++i){ - at(i-num_move) = at(i); - } - for(size_type i = 0; i < num_move ; ++i){ - pop_back(); - } - }else{ - for(size_type i = 0; i < first.element ; ++i){ - at(last.element - i - 1) = at(first.element - i - 1); - } - for(size_type i = 0; i < num_move ; ++i){ - pop_front(); - } - } - return deque_iter(this, first.element); - } - - template void deque::swap(deque& x) - { - T * temp_data; - typename deque::size_type temp_size; - - //Swap data pointers - temp_data = x.data; - x.data = data; - data = temp_data; - - //Swap array sizes - temp_size = x.data_size; - x.data_size = data_size; - data_size = temp_size; - - //Swap num array elements - temp_size = x.elements; - x.elements = elements; - elements = temp_size; - - //Swap first_pointer - temp_size = x.first_element; - x.first_element = first_element; - first_element = temp_size; - - //Swap last_pointer - temp_size = x.last_element; - x.last_element = last_element; - last_element = temp_size; - } - - template void deque::clear() - { - while(elements > 0 ){ - pop_back(); - } - } - - - template void deque::reserve(typename deque::size_type n) - { - if(data_size >= n){ - return; - } - - size_type size_temp; - size_type first_temp; - T * data_temp; - size_temp = n + __UCLIBCXX_STL_BUFFER_SIZE__; //Reserve extra 'cause we can - data_temp = a.allocate(size_temp); - - first_temp = (size_temp - elements) / 2; - for(size_type i = 0; i < elements; ++i){ - a.construct(data_temp + first_temp + i, data[array_element(i)]); - a.destroy(data + array_element(i)); - } - - //Now shuffle pointers - a.deallocate(data, data_size); - data = data_temp; - data_size = size_temp; - first_element = first_temp; - last_element = first_element + elements; - } - - - template _UCXXEXPORT - bool - operator==(const deque& x, const deque& y) - { - if(x.elements != y.elements){ - return false; - } - for(typename deque::size_type i = 0; i < x.elements; ++i){ - if(x[i] < y[i] || y[i] < x[i]){ - return false; - } - } - return true; - } - - template bool operator< (const deque& x, const deque& y); - template _UCXXEXPORT - bool - operator!=(const deque& x, const deque& y) - { - if(x == y){ - return false; - } - return true; - } - template bool operator> (const deque& x, const deque& y); - template bool operator>=(const deque& x, const deque& y); - template bool operator<=(const deque& x, const deque& y); - template _UCXXEXPORT void swap(deque& x, deque& y){ - x.swap(y); - } - - - -} +namespace std +{ + template > class deque; + template bool operator==(const deque& x, const deque& y); + template bool operator< (const deque& x, const deque& y); + template bool operator!=(const deque& x, const deque& y); + template bool operator> (const deque& x, const deque& y); + template bool operator>=(const deque& x, const deque& y); + template bool operator<=(const deque& x, const deque& y); + template void swap(deque& x, deque& y); + + template class _UCXXEXPORT deque { + public: + friend bool operator==<>(const deque& x, const deque& y); + friend class deque_iter; + friend class deque_citer; + class deque_iter; + class deque_citer; + + typedef typename Allocator::reference reference; + typedef typename Allocator::const_reference const_reference; + typedef deque_iter iterator; + typedef deque_citer const_iterator; + typedef typename Allocator::size_type size_type; + typedef typename Allocator::difference_type difference_type; + typedef T value_type; + typedef Allocator allocator_type; + typedef typename Allocator::pointer pointer; + typedef typename Allocator::const_pointer const_pointer; + typedef std::reverse_iterator reverse_iterator; + typedef std::reverse_iterator const_reverse_iterator; + + explicit deque(const Allocator& al = Allocator()); + explicit deque(size_type n, const T& value = T(), const Allocator& al = Allocator()); + template deque(InputIterator first, InputIterator last, const Allocator& = Allocator()); + deque(const deque& x); + ~deque(); + + deque& operator=(const deque& x); + template void assign(InputIterator first, InputIterator last); + template void assign(Size n, const U& u = U()); + allocator_type get_allocator() const; + + iterator begin(); + const_iterator begin() const; + iterator end(); + const_iterator end() const; + reverse_iterator rbegin(); + const_reverse_iterator rbegin() const; + reverse_iterator rend(); + const_reverse_iterator rend() const; + + size_type size() const; + size_type max_size() const; + void resize(size_type sz, T c = T()); + bool empty() const; + + reference operator[](size_type n); + const_reference operator[](size_type n) const; + reference at(size_type n); + const_reference at(size_type n) const; + reference front(); + const_reference front() const; + reference back(); + const_reference back() const; + + void push_front(const T& x); + void push_back(const T& x); + iterator insert(iterator position, const T& x = T()); + void insert(iterator position, size_type n, const T& x); + template void insert (iterator position, InputIterator first, InputIterator last); + void pop_front(); + void pop_back(); + + iterator erase(iterator position); + iterator erase(iterator first, iterator last); + void swap(deque&); + void clear(); + + protected: + void reserve(size_type n); + + inline size_type array_element(size_type deque_element) const + { + if (deque_element < (data_size - first_element)) + { + return first_element + deque_element; + } + return deque_element - (data_size - first_element); + } + + inline size_type first_subtract(size_type sub_size) const + { + if (sub_size > first_element) + { + return (data_size - first_element) - sub_size; + } + return first_element - sub_size; + } + + T * data; + size_type data_size; //Physical size of array + size_type elements; //Elements in array + size_type first_element; //Element number of array 0..n + size_type last_element; //Element number of array 0..n + Allocator a; + + }; + + template class _UCXXEXPORT deque::deque_iter + : public std::iterator< + random_access_iterator_tag, + T, + typename Allocator::difference_type, + typename Allocator::pointer, + typename Allocator::reference + > + { + friend class deque; + protected: + deque * container; + typename Allocator::size_type element; + + public: + deque_iter() : container(0), element(0) { } + deque_iter(const deque_iter & d) : container (d.container), element(d.element) { } + + deque_iter(deque * c, typename Allocator::size_type e) + : container(c), element(e) + { + return; + } + + ~deque_iter() { } + + deque_iter & operator=(const deque_iter & d) + { + container = d.container; + element = d.element; + return *this; + } + + T & operator*() + { + return container->data[container->array_element(element)]; + } + + T * operator->() + { + return container->data + container->array_element(element); + } + + const T & operator*() const + { + return container->data[container->array_element(element)]; + } + + const T * operator->() const + { + return container->data + container->array_element(element); + } + + bool operator==(const deque_iter & d) const + { + if (container == d.container && element == d.element) + { + return true; + } + + return false; + } + + bool operator==(const deque_citer & d) const + { + if (container == d.container && element == d.element){ + return true; + } + return false; + } + + bool operator!=(const deque_iter & d) const + { + if (container != d.container || element != d.element) + { + return true; + } + return false; + } + + bool operator!=(const deque_citer & d) const + { + if (container != d.container || element != d.element) + { + return true; + } + return false; + } + + bool operator<(const deque_iter & d) const + { + if (element < d.element){ + return true; + } + return false; + } + + bool operator<(const deque_citer & d) const + { + if (element < d.element){ + return true; + } + return false; + } + + bool operator<=(const deque_iter & d) const + { + if (element <= d.element){ + return true; + } + return false; + } + + bool operator<=(const deque_citer & d) const + { + if (element <= d.element){ + return true; + } + return false; + } + + bool operator>(const deque_iter & d) const + { + if (element > d.element) + { + return true; + } + + return false; + } + + bool operator>(const deque_citer & d) const + { + if (element > d.element) + { + return true; + } + + return false; + } + + bool operator>=(const deque_iter & d) const + { + if (element >= d.element) + { + return true; + } + + return false; + } + + bool operator>=(const deque_citer & d) const + { + if (element >= d.element) + { + return true; + } + + return false; + } + + deque_iter & operator++() + { + ++element; + return *this; + } + + deque_iter operator++(int) + { + deque_iter temp(container, element); + ++element; + return temp; + } + + deque_iter operator+(typename Allocator::size_type n) + { + deque_iter temp(container, element + n); + return temp; + } + + deque_iter & operator+=(typename Allocator::size_type n) + { + element += n; + return *this; + } + + deque_iter & operator--() + { + --element; + return *this; + } + + deque_iter operator--(int) + { + deque_iter temp(container, element); + --element; + return temp; + } + + deque_iter operator-(typename Allocator::size_type n) + { + deque_iter temp(container, element - n); + return temp; + } + + deque_iter & operator-=(typename Allocator::size_type n) + { + element -= n; + return *this; + } + + typename Allocator::size_type operator-(const deque_iter & d) + { + return element - d.element; + } + + }; + + template class _UCXXEXPORT deque::deque_citer + : public std::iterator< + random_access_iterator_tag, + T, + typename Allocator::difference_type, + typename Allocator::const_pointer, + typename Allocator::const_reference + > + { + friend class deque; + protected: + const deque * container; + typename Allocator::size_type element; + + public: + deque_citer() : container(0), element(0) { } + deque_citer(const deque_citer & d) : container (d.container), element(d.element) { } + deque_citer(const deque_iter & d) : container (d.container), element(d.element) { } + + deque_citer(const deque * c, typename Allocator::size_type e) + : container(c), element(e) + { + return; + } + + ~deque_citer() { } + + deque_citer & operator=(const deque_iter & d) + { + container = d.container; + element = d.element; + return *this; + } + + const T & operator*() const + { + return container->data[container->array_element(element)]; + } + + const T * operator->() const + { + return container->data + container->array_element(element); + } + + bool operator==(const deque_citer & d) const + { + if (container == d.container && element == d.element) + { + return true; + } + return false; + } + + bool operator==(const deque_iter & d) const + { + if (container == d.container && element == d.element) + { + return true; + } + return false; + } + + bool operator!=(const deque_citer & d) const + { + if (container != d.container || element != d.element) + { + return true; + } + return false; + } + + bool operator!=(const deque_iter & d) const + { + if (container != d.container || element != d.element) + { + return true; + } + + return false; + } + + bool operator<(const deque_citer & d) const + { + if (element < d.element){ + return true; + } + return false; + } + + bool operator<(const deque_iter & d) const + { + if (element < d.element){ + return true; + } + return false; + } + + bool operator<=(const deque_citer & d) const + { + if (element <= d.element){ + return true; + } + return false; + } + + bool operator<=(const deque_iter & d) const + { + if (element <= d.element){ + return true; + } + return false; + } + + bool operator>(const deque_citer & d) const + { + if (element > d.element){ + return true; + } + return false; + } + + bool operator>(const deque_iter & d) const + { + if (element > d.element){ + return true; + } + return false; + } + + bool operator>=(const deque_citer & d) + { + if (element >= d.element) + { + return true; + } + return false; + } + + bool operator>=(const deque_iter & d) + { + if (element >= d.element){ + return true; + } + return false; + } + + deque_citer & operator++() + { + ++element; + return *this; + } + + deque_citer operator++(int) + { + deque_citer temp(container, element); + ++element; + return temp; + } + + deque_citer operator+(typename Allocator::size_type n) + { + deque_citer temp(container, element + n); + return temp; + } + + deque_citer & operator+=(typename Allocator::size_type n) + { + element += n; + return *this; + } + + deque_citer & operator--() + { + --element; + return *this; + } + + deque_citer operator--(int) + { + deque_citer temp(container, element); + --element; + return temp; + } + + deque_citer operator-(typename Allocator::size_type n) + { + deque_citer temp(container, element - n); + return temp; + } + + deque_citer & operator-=(typename Allocator::size_type n) + { + element -= n; + return *this; + } + + typename Allocator::size_type operator-(const deque_citer & d) + { + return element - d.element; + } + + }; + + template deque::deque(const Allocator& al) + : data(0), + data_size(0), elements(0), first_element(0), last_element(0), a(al) + { + data_size = __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + first_element = data_size /2; + last_element = first_element; + } + + + template deque::deque( + size_type n, const T& value, const Allocator& al) + : data(0), + elements(n), first_element(0), last_element(0), a(al) + { + data_size = elements + __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + first_element = (data_size - elements) / 2; + last_element = first_element; + + for (n=first_element ; n < last_element; ++n) + { + a.construct(data+n, value); + } + } + + + template template + deque::deque(InputIterator first, InputIterator last, const Allocator& al) + : data(0), + data_size(0), elements(0), first_element(0), last_element(0), a(al) + { + data_size = __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + first_element = data_size / 4; //Note sure how big, but let's add a little space... + last_element = first_element; + while (first != last) + { + push_back(*first); + ++first; + } + } + + + template deque::deque(const deque& x) + : data(0), + elements(0), first_element(0), last_element(0), a(x.a) + { + data_size = x.elements + __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + first_element = (data_size - x.elements) / 2; + last_element = first_element; + for (size_type i=0; i < x.elements; ++i) + { + push_back(x[i]); + } + } + + + template deque::~deque() + { + clear(); + a.deallocate(data, data_size); + } + + template deque& deque:: + operator=(const deque& x) + { + if (&x == this) + { + return *this; + } + + resize(x.elements); + for (size_t i = 0; i < elements; ++i) + { + data[array_element(i)] = x[i]; + } + return *this; + } + + template template void + deque::assign(InputIterator first, InputIterator last) + { + clear(); + while (first !=last) + { + push_back(*first); + ++first; + } + } + + template template void + deque::assign(Size n, const U& u) + { + if (&u == this) + { + return; + } + + clear(); + for (size_type i = 0; i < n; ++i) + { + push_back(u); + } + } + + template typename deque::allocator_type + deque::get_allocator() const + { + return a; + } + + template typename + deque::iterator deque::begin() + { + return deque_iter(this, 0); + } + + template typename deque::const_iterator + deque::begin() const + { + return deque_citer(this, 0); + } + + template typename + deque::iterator deque::end() + { + return deque_iter(this, elements); + } + + template typename + deque::const_iterator deque::end() const + { + return deque_citer(this, elements); + } + + template typename + deque::reverse_iterator deque::rbegin() + { + return reverse_iterator(end()); + } + + template typename + deque::const_reverse_iterator deque::rbegin() const + { + return const_reverse_iterator(end()); + } + + template typename + deque::reverse_iterator deque::rend() + { + return reverse_iterator(begin()); + } + + template typename + deque::const_reverse_iterator deque::rend() const + { + return const_reverse_iterator(begin()); + } + + template typename + deque::size_type deque::size() const + { + return elements; + } + + template typename + deque::size_type deque::max_size() const + { + return ((size_type)(-1)) / sizeof(T); + } + + template void deque::resize(size_type sz, T c) + { + reserve(sz); + while (sz > size()) + { + push_back(c); + } + + while (sz < size()) + { + pop_back(); + } + } + + template bool deque::empty() const + { + return (elements == 0); + } + + template typename + deque::reference deque::operator[](size_type n) + { + return data[array_element(n)]; + } + + template typename + deque::const_reference deque::operator[](size_type n) const + { + return data[array_element(n)]; + } + + template typename + deque::reference deque::at(size_type n) + { + if (n > elements) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range("Out of deque range"); +#else + std::terminate(); +#endif + } + return data[array_element(n)]; + } + + template typename + deque::const_reference deque::at(size_type n) const + { + if (n > elements) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range("Out of deque range"); +#else + std::terminate(); +#endif + } + return data[array_element(n)]; + } + + template typename + deque::reference deque::front() + { + return data[first_element]; + } + + template typename + deque::const_reference deque::front() const + { + return data[first_element]; + } + + template typename + deque::reference deque::back() + { + return data[array_element(elements-1)]; + } + + template typename + deque::const_reference deque::back() const + { + return data[array_element(elements-1)]; + } + + template void deque::push_front(const T& x) + { + reserve(elements + 1); + first_element = first_subtract(1); + a.construct(data + first_element, x); + ++elements; + } + + template void deque::push_back(const T& x) + { + reserve(elements + 1); + a.construct(data + last_element, x); + ++elements; + last_element = array_element(elements); + } + + template typename + deque::iterator deque::insert(iterator position, const T& x) + { + reserve(elements+1); + if (position.element > (elements/2)) + { + //Push all elements back 1 + + push_back(x); + for (size_type i = elements-1; i > position.element; --i) + { + at(i) = at(i-1); + } + } + else + { + //Push all elements forward 1 + + push_front(x); + for (size_type i = 0; i < position.element; ++i){ + at(i) = at(i+1); + } + } + + at(position.element) = x; + return deque_iter(this, position.element); + } + + template void deque:: + insert(typename deque::iterator position, size_type n, const T& x) + { + reserve(elements + n); + for (size_t i =0; i < n; ++i){ + position = insert(position, x); + } + } + + template template + void deque::insert (iterator position, InputIterator first, InputIterator last) + { + while (first != last){ + position = insert(position, *first); + ++first; + } + } + + template void deque::pop_front() + { + if (elements == 0) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range("deque pop_front"); +#else + std::terminate(); +#endif + } + a.destroy(data + first_element); + first_element = array_element(1); + --elements; + } + + template void deque::pop_back() + { + last_element = array_element(elements - 1); + a.destroy(data + last_element); + --elements; + } + + template typename + deque::iterator deque::erase(typename deque::iterator position) + { + if (position.element > (elements /2)) + { + for (size_type i = position.element; i < elements - 1; ++i) + { + at(i) = at(i+1); + } + pop_back(); + } + else + { + for (size_type i = position.element; i > 0; --i) + { + at(i) = at(i-1); + } + pop_front(); + } + return deque_iter(this, position.element); + } + + template typename deque::iterator + deque:: + erase(typename deque::iterator first, typename deque::iterator last) + { + //Shift backwards + size_type num_move = last.element - first.element; + if (first.element > (elements - last.element)) + { + for (size_type i = last.element; i < elements ; ++i) + { + at(i-num_move) = at(i); + } + + for (size_type i = 0; i < num_move ; ++i) + { + pop_back(); + } + } + else + { + for (size_type i = 0; i < first.element ; ++i) + { + at(last.element - i - 1) = at(first.element - i - 1); + } + + for (size_type i = 0; i < num_move ; ++i) + { + pop_front(); + } + } + return deque_iter(this, first.element); + } + + template void deque::swap(deque& x) + { + T * temp_data; + typename deque::size_type temp_size; + + //Swap data pointers + + temp_data = x.data; + x.data = data; + data = temp_data; + + //Swap array sizes + + temp_size = x.data_size; + x.data_size = data_size; + data_size = temp_size; + + //Swap num array elements + + temp_size = x.elements; + x.elements = elements; + elements = temp_size; + + //Swap first_pointer + + temp_size = x.first_element; + x.first_element = first_element; + first_element = temp_size; + + //Swap last_pointer + + temp_size = x.last_element; + x.last_element = last_element; + last_element = temp_size; + } + + template void deque::clear() + { + while (elements > 0) + { + pop_back(); + } + } + + + template void deque::reserve(typename deque::size_type n) + { + if (data_size >= n) + { + return; + } + + size_type size_temp; + size_type first_temp; + T * data_temp; + size_temp = n + __UCLIBCXX_STL_BUFFER_SIZE__; //Reserve extra 'cause we can + data_temp = a.allocate(size_temp); + + first_temp = (size_temp - elements) / 2; + for (size_type i = 0; i < elements; ++i) + { + a.construct(data_temp + first_temp + i, data[array_element(i)]); + a.destroy(data + array_element(i)); + } + + //Now shuffle pointers + + a.deallocate(data, data_size); + data = data_temp; + data_size = size_temp; + first_element = first_temp; + last_element = first_element + elements; + } + + template _UCXXEXPORT + bool + operator==(const deque& x, const deque& y) + { + if (x.elements != y.elements){ + return false; + } + for (typename deque::size_type i = 0; i < x.elements; ++i){ + if (x[i] < y[i] || y[i] < x[i]){ + return false; + } + } + return true; + } + + template bool operator< (const deque& x, const deque& y); + template _UCXXEXPORT + bool + operator!=(const deque& x, const deque& y) + { + if (x == y){ + return false; + } + return true; + } + + template bool operator> (const deque& x, const deque& y); + template bool operator>=(const deque& x, const deque& y); + template bool operator<=(const deque& x, const deque& y); + template _UCXXEXPORT void swap(deque& x, deque& y){ + x.swap(y); + } +} // namespace #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/string b/misc/uClibc++/include/uClibc++/string index d045794149..f128e7e5ad 100644 --- a/misc/uClibc++/include/uClibc++/string +++ b/misc/uClibc++/include/uClibc++/string @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -25,7 +25,6 @@ #include #include - #ifdef __UCLIBCXX_HAS_WCHAR__ #include #include @@ -36,979 +35,1278 @@ #pragma GCC visibility push(default) -namespace std{ - - //Basic basic_string - - template, class A = allocator > class basic_string; - - typedef basic_string string; - #ifdef __UCLIBCXX_HAS_WCHAR__ - typedef basic_string wstring; - #endif +namespace std +{ + // Basic basic_string + template, class A = allocator > class basic_string; + typedef basic_string string; + #ifdef __UCLIBCXX_HAS_WCHAR__ + typedef basic_string wstring; + #endif //template, class A = allocator > class _UCXXEXPORT basic_string template class basic_string - : public std::vector + : public std::vector { public: - typedef Tr traits_type; - typedef typename Tr::char_type value_type; - typedef A allocator_type; - typedef typename A::size_type size_type; - typedef typename A::difference_type difference_type; - - typedef typename A::reference reference; - typedef typename A::const_reference const_reference; - typedef typename A::pointer pointer; - typedef typename A::const_pointer const_pointer; - - typedef typename vector::iterator iterator; - typedef typename vector::const_iterator const_iterator; - - typedef typename vector::reverse_iterator reverse_iterator; - typedef typename vector::const_reverse_iterator const_reverse_iterator; - - static const size_type npos = (size_type)-1; - - explicit _UCXXEXPORT basic_string(const A& al = A()) : vector(al){ return; } - - _UCXXEXPORT basic_string(const basic_string& str, size_type pos = 0, size_type n = npos, const A& al = A()); //Below - - _UCXXEXPORT basic_string(const Ch* s, size_type n, const A& al = A()) - : vector(al) - { - if(n == npos){ - __throw_out_of_range(); - } - if(s > 0){ - resize(n); - Tr::copy(vector::data, s, vector::elements); - } - } - - _UCXXEXPORT basic_string(const Ch* s, const A& al = A()); //Below - - _UCXXEXPORT basic_string(size_type n, Ch c, const A& al = A()) - : vector(n, c, al) - { - } - - template _UCXXEXPORT basic_string(InputIterator begin, InputIterator end, const A& a = A()) - :vector(begin, end) - { - - } - - _UCXXEXPORT ~basic_string() { - return; - } - - _UCXXEXPORT basic_string& operator=(const basic_string& str); //Below - - _UCXXEXPORT basic_string& operator=(const Ch* s){ - vector::clear(); - if(s!=0){ - size_type len = Tr::length(s); - resize(len); - Tr::copy( vector::data, s, len); - } - return *this; - } - - _UCXXEXPORT basic_string& operator=(Ch c){ - vector::clear(); - vector::push_back(c); - return *this; - } - - inline _UCXXEXPORT size_type length() const { return vector::size(); } - - void _UCXXEXPORT resize(size_type n, Ch c = Ch()){ - vector::resize(n, c); - } - - _UCXXEXPORT basic_string& operator+=(const basic_string& str){ - return append(str); - } - - _UCXXEXPORT basic_string& operator+=(const Ch * s){ - return append(s); - } - - _UCXXEXPORT basic_string& operator+=(Ch c){ - vector::push_back(c); - return *this; - } - - _UCXXEXPORT basic_string& append(const basic_string& str){ - size_t temp = vector::elements; - resize(vector::elements + str.elements); - Tr::copy( vector::data + temp, str.vector::data, str.elements); - - return *this; - } - - _UCXXEXPORT basic_string& append(const basic_string& str, size_type pos, size_type n){ - if(pos > str.size()){ - __throw_out_of_range(); - } - - size_type rlen = str.elements - pos; - if(rlen > n){ - rlen = n; - } - if(vector::elements > npos - rlen){ - __throw_length_error(); - } - size_t temp = vector::elements; - resize(vector::elements + rlen); - Tr::copy( vector::data + temp, str.vector::data + pos, rlen); - return *this; - } - - _UCXXEXPORT basic_string& append(const Ch* s, size_type n){ - size_t temp = vector::elements; - resize(vector::elements + n); - Tr::copy( vector::data + temp, s, n); - return *this; - } - - _UCXXEXPORT basic_string& append(const Ch* s){ - size_type strLen = Tr::length(s); - size_t temp = vector::elements; - resize(vector::elements + strLen); - Tr::copy( vector::data + temp, s, strLen); - return *this; - } - - _UCXXEXPORT basic_string& append(size_type n, Ch c){ - vector::resize(vector::elements + n, c); - return *this; - } - - _UCXXEXPORT basic_string& assign(const basic_string& str){ - operator=(str); - return *this; - } - - _UCXXEXPORT basic_string& assign(const basic_string& str, size_type pos, size_type n){ - if(pos > str.elements){ - __throw_out_of_range(); - } - size_type r = str.elements - pos; - if(r > n){ - r = n; - } - resize(r); - Tr::copy(vector::data, str.vector::data + pos, r); - return *this; - } - - _UCXXEXPORT basic_string& assign(const Ch* s, size_type n){ - resize(n); - Tr::copy(vector::data, s, n); - return *this; - } - - _UCXXEXPORT basic_string& assign(const Ch* s){ - size_type len = Tr::length(s); - return assign(s, len); - } - - _UCXXEXPORT basic_string& assign(size_type n, Ch c){ - vector::clear(); - vector::resize(n, Ch() ); - return *this; - } - - template _UCXXEXPORT basic_string& assign(InputIterator first, InputIterator last){ - vector::resize(0, Ch()); - while (first != last){ - append(*first); - ++first; - } - return *this; - } - - _UCXXEXPORT basic_string& insert(size_type pos1, const basic_string& str, size_type pos2=0, size_type n=npos){ - if(pos1 > vector::elements || pos2 > str.elements){ - __throw_out_of_range(); - } - size_type r = str.elements - pos2; - if( r > n){ - r = n; - } - if(vector::elements > npos - r){ - __throw_length_error(); - } - size_type temp = vector::elements; - resize(vector::elements + r); - Tr::move(vector::data + pos1 + r, vector::data + pos1, temp - pos1); - Tr::copy(vector::data + pos1, str.vector::data + pos2, r); - return *this; - } - - _UCXXEXPORT basic_string& insert(size_type pos, const Ch* s, size_type n){ - if(pos > vector::elements){ - __throw_out_of_range(); - } - if(vector::elements > npos - n){ - __throw_length_error(); - } - size_type temp = vector::elements; - resize(vector::elements + n); - Tr::move(vector::data + pos + n, vector::data + pos, temp - pos); - Tr::copy(vector::data + pos, s, n); - return *this; - } - - inline _UCXXEXPORT basic_string& insert(size_type pos, const Ch* s){ - size_type len = Tr::length(s); - return insert(pos, s, len); - } - - _UCXXEXPORT basic_string& insert(size_type pos, size_type n, Ch c){ - if(pos > vector::elements){ - __throw_out_of_range(); - } - if(vector::elements > npos - n){ - __throw_length_error(); - } - size_type temp = vector::elements; - resize(vector::elements + n); - Tr::move(vector::data + pos + n, vector::data + pos, temp - pos); - Tr::assign(vector::data + pos, n, c); - return *this; - } - - using vector::insert; -// void insert(iterator p, size_type n, charT c); -// template void insert(iterator p, InputIterator first, InputIterator last); - - _UCXXEXPORT basic_string& erase(size_type pos = 0, size_type n = npos){ - size_type xlen = vector::elements - pos; - - if(xlen > n){ - xlen = n; - } - size_type temp = vector::elements; - - Tr::move(vector::data + pos, vector::data + pos + xlen, temp - pos - xlen); - resize(temp - xlen); - return *this; - } - - _UCXXEXPORT iterator erase(iterator position){ - if(position == vector::end()){ - return position; - } - - ++position; - - iterator temp = position; - - while(position != vector::end()){ - *(position-1) = *position; - ++position; - } - vector::pop_back(); - return temp; - } - - _UCXXEXPORT iterator erase(iterator first, iterator last){ - size_t count = last - first; - - iterator temp = last; - - while(last != vector::end()){ - *(last - count) = *last; - ++last; - } - - resize( vector::elements-count); - - return temp; - } - - _UCXXEXPORT basic_string& - replace(size_type pos1, size_type n1, const basic_string& str, size_type pos2=0, size_type n2=npos) - { - if(pos1 > vector::elements){ - __throw_out_of_range(); - } - size_type xlen = vector::elements - pos1; - if(xlen > n1){ - xlen = n1; - } - size_type rlen = str.elements - pos2; - if(rlen > n2){ - rlen = n2; - } - if((vector::elements - xlen) >= (npos - rlen)){ - __throw_length_error(); - } - - size_t temp = vector::elements; - - if(rlen > xlen){ //Only if making larger - resize(temp - xlen + rlen); - } - - //Final length = vector::elements - xlen + rlen - //Initial block is of size pos1 - //Block 2 is of size len - - Tr::move(vector::data + pos1 + rlen, vector::data + pos1 + xlen, temp - pos1 - xlen); - Tr::copy(vector::data + pos1, str.vector::data + pos2, rlen); - resize(temp - xlen + rlen); - return *this; - } - - _UCXXEXPORT basic_string& replace(size_type pos, size_type n1, const Ch* s, size_type n2){ - return replace(pos,n1,basic_string(s,n2)); - - } - - inline _UCXXEXPORT basic_string& replace(size_type pos, size_type n1, const Ch* s){ - return replace(pos,n1,basic_string(s)); - } - - _UCXXEXPORT basic_string& replace(size_type pos, size_type n1, size_type n2, Ch c){ - return replace(pos,n1,basic_string(n2,c)); - } -// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, const basic_string& str); -// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, const Ch* s, size_type n); -// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, const Ch* s); -// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, size_type n, Ch c); -/* template _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, - InputIterator j1, InputIterator j2);*/ - - size_type _UCXXEXPORT copy(Ch* s, size_type n, size_type pos = 0) const{ - if(pos > vector::elements){ - __throw_out_of_range(); - } - size_type r = vector::elements - pos; - if(r > n){ - r = n; - } - Tr::copy(s, vector::data + pos, r); - return r; - } - - _UCXXEXPORT void swap(basic_string& s){ - //Data pointers - - vector::swap(s); - } - - _UCXXEXPORT const Ch* c_str() const{ - const_cast *>(this)->reserve(vector::elements+1); - vector::data[vector::elements] = 0; //Add 0 at the end - return vector::data; - } - - _UCXXEXPORT const Ch* data() const{ - return vector::data; - } - _UCXXEXPORT allocator_type get_allocator() const{ - return vector::a; - } - - _UCXXEXPORT size_type find (const basic_string& str, size_type pos = 0) const; //Below - - _UCXXEXPORT size_type find (const Ch* s, size_type pos, size_type n) const{ - return find(basic_string(s,n), pos); - } - _UCXXEXPORT size_type find (const Ch* s, size_type pos = 0) const{ - return find(basic_string(s), pos); - } - _UCXXEXPORT size_type find (Ch c, size_type pos = 0) const{ - for(size_type i = pos; i < length(); ++i){ - if(this->operator[](i) == c){ - return i; - } - } - return npos; - } - _UCXXEXPORT size_type rfind(const basic_string& str, size_type pos = npos) const{ - if(pos >= length()){ - pos = length(); - } - for(size_type i = pos; i > 0; --i){ - if(str == substr(i-1, str.length())){ - return i-1; - } - } - return npos; - } - _UCXXEXPORT size_type rfind(const Ch* s, size_type pos, size_type n) const{ - return rfind(basic_string(s,n),pos); - } - _UCXXEXPORT size_type rfind(const Ch* s, size_type pos = npos) const{ - return rfind(basic_string(s),pos); - } - _UCXXEXPORT size_type rfind(Ch c, size_type pos = npos) const{ - return rfind(basic_string(1,c),pos); - } - - _UCXXEXPORT size_type find_first_of(const basic_string& str, size_type pos = 0) const{ - for(size_type i = pos; i < length(); ++i){ - for(size_type j = 0; j < str.length() ; ++j){ - if( Tr::eq(str[j], this->operator[](i)) ){ - return i; - } - } - } - return npos; - } - - _UCXXEXPORT size_type find_first_of(const Ch* s, size_type pos, size_type n) const{ - return find_first_of(basic_string(s,n),pos); - } - _UCXXEXPORT size_type find_first_of(const Ch* s, size_type pos = 0) const{ - return find_first_of(basic_string(s),pos); - } - _UCXXEXPORT size_type find_first_of(Ch c, size_type pos = 0) const{ - for(size_type i = pos; i< length(); ++i){ - if( Tr::eq(this->operator[](i), c) ){ - return i; - } - } - return npos; - } - - _UCXXEXPORT size_type find_last_of (const basic_string& str, size_type pos = npos) const{ - if(pos > length()){ - pos = length(); - } - for(size_type i = pos; i >0 ; --i){ - for(size_type j = 0 ; j < str.length(); ++j){ - if( Tr::eq(this->operator[](i-1), str[j]) ){ - return i-1; - } - } - } - return npos; - } - _UCXXEXPORT size_type find_last_of (const Ch* s, size_type pos, size_type n) const{ - return find_last_of(basic_string(s,n),pos); - } - _UCXXEXPORT size_type find_last_of (const Ch* s, size_type pos = npos) const{ - return find_last_of(basic_string(s),pos); - } - _UCXXEXPORT size_type find_last_of (Ch c, size_type pos = npos) const{ - if(pos > length()){ - pos = length(); - } - for(size_type i = pos; i >0 ; --i){ - if( Tr::eq(this->operator[](i-1), c) ){ - return i-1; - } - } - return npos; - } - - _UCXXEXPORT size_type find_first_not_of(const basic_string& str, size_type pos = 0) const{ - bool foundCharacter; - for(size_type i = pos; i < length(); ++i){ - foundCharacter = false; - for(size_type j = 0; j < str.length() ; ++j){ - if( Tr::eq(str[j], this->operator[](i)) ){ - foundCharacter = true; - } - } - if(foundCharacter == false){ - return i; - } - } - return npos; - } - - _UCXXEXPORT size_type find_first_not_of(const Ch* s, size_type pos, size_type n) const{ - return find_first_not_of(basic_string(s,n),pos); - } - _UCXXEXPORT size_type find_first_not_of(const Ch* s, size_type pos = 0) const{ - return find_first_not_of(basic_string(s),pos); - } - _UCXXEXPORT size_type find_first_not_of(Ch c, size_type pos = 0) const{ - for(size_type i = pos; i < length() ; ++i){ - if(this->operator[](i) != c){ - return i; - } - } - return npos; - } - _UCXXEXPORT size_type find_last_not_of (const basic_string& str, size_type pos = npos) const{ - size_type xpos(length() - 1); - if(xpos > pos){ - xpos = pos; - } - - while(xpos != npos && npos != str.find_first_of(this->at(xpos))){ - --xpos; - } - - return xpos; - } - - _UCXXEXPORT size_type find_last_not_of (const Ch* s, size_type pos, size_type n) const{ - return find_last_not_of(basic_string(s,n),pos); - } - _UCXXEXPORT size_type find_last_not_of (const Ch* s, size_type pos = npos) const{ - return find_last_not_of(basic_string(s),pos); - } - _UCXXEXPORT size_type find_last_not_of (Ch c, size_type pos = npos) const{ - size_type xpos(length() - 1); - if(xpos > pos){ - xpos = pos; - } - while(xpos != npos && Tr::eq(this->at(xpos), c)){ - --xpos; - } - return xpos; - - } - - _UCXXEXPORT basic_string substr(size_type pos = 0, size_type n = npos) const; - - _UCXXEXPORT int compare(const basic_string& str) const{ - size_type rlen = vector::elements; - if(rlen > str.elements){ - rlen = str.elements; - } - int retval = Tr::compare(vector::data, str.vector::data, rlen); - if(retval == 0){ - if(vector::elements < str.elements){ - retval = -1; - } - if(vector::elements > str.elements){ - retval = 1; - } - } - return retval; - } - - _UCXXEXPORT int compare(size_type pos1, size_type n1, const basic_string& str, - size_type pos2=0, size_type n2=npos) const{ - size_type len1 = vector::elements - pos1; - if(len1 > n1){ - len1 = n1; - } - size_type len2 = str.vector::elements - pos2; - if(len2 > n2){ - len2 = n2; - } - size_type rlen = len1; - if(rlen > len2){ - rlen = len2; - } - int retval = Tr::compare(vector::data + pos1, str.vector::data + pos2, rlen); - if(retval == 0){ - if(len1 < len2){ - retval = -1; - } - if(len1 > len2){ - retval = 1; - } - } - return retval; - } - - _UCXXEXPORT int compare(const Ch* s) const{ - size_type slen = Tr::length(s); - size_type rlen = slen; - if(rlen > vector::elements){ - rlen=vector::elements; - } - int retval = Tr::compare(vector::data, s, rlen); - if(retval==0){ - if(vector::elements < slen){ - retval = -1; - } - if(vector::elements > slen){ - retval = 1; - } - } - return retval; - } - - _UCXXEXPORT int compare(size_type pos1, size_type n1, const Ch* s, size_type n2 = npos) const{ - size_type len1 = vector::elements - pos1; - if(len1 > n1){ - len1 = n1; - } - size_type slen = Tr::length(s); - size_type len2 = slen; - if(len2 > n2){ - len2 = n2; - } - size_type rlen = len1; - if(rlen > len2){ - rlen = len2; - } - int retval = Tr::compare(vector::data + pos1, s, rlen); - if(retval == 0){ - if(len1 < len2){ - retval = -1; - } - if(len1 > len2){ - retval = 1; - } - } - return retval; - } - + typedef Tr traits_type; + typedef typename Tr::char_type value_type; + typedef A allocator_type; + typedef typename A::size_type size_type; + typedef typename A::difference_type difference_type; + + typedef typename A::reference reference; + typedef typename A::const_reference const_reference; + typedef typename A::pointer pointer; + typedef typename A::const_pointer const_pointer; + + typedef typename vector::iterator iterator; + typedef typename vector::const_iterator const_iterator; + + typedef typename vector::reverse_iterator reverse_iterator; + typedef typename vector::const_reverse_iterator const_reverse_iterator; + + static const size_type npos = (size_type)-1; + + explicit _UCXXEXPORT basic_string(const A& al = A()) : vector(al){ return; } + + _UCXXEXPORT basic_string(const basic_string& str, size_type pos = 0, size_type n = npos, const A& al = A()); //Below + + _UCXXEXPORT basic_string(const Ch* s, size_type n, const A& al = A()) + : vector(al) + { + if (n == npos) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range(); +#else + std::terminate(); +#endif + } + + if (s > 0) + { + resize(n); + Tr::copy(vector::data, s, vector::elements); + } + } + + _UCXXEXPORT basic_string(const Ch* s, const A& al = A()); //Below + + _UCXXEXPORT basic_string(size_type n, Ch c, const A& al = A()) + : vector(n, c, al) + { + } + + template _UCXXEXPORT basic_string(InputIterator begin, InputIterator end, const A& a = A()) + :vector(begin, end) + { + + } + + _UCXXEXPORT ~basic_string() + { + return; + } + + _UCXXEXPORT basic_string& operator=(const basic_string& str); // Below + + _UCXXEXPORT basic_string& operator=(const Ch* s) + { + vector::clear(); + if (s != 0) + { + size_type len = Tr::length(s); + resize(len); + Tr::copy(vector::data, s, len); + } + + return *this; + } + + _UCXXEXPORT basic_string& operator=(Ch c) + { + vector::clear(); + vector::push_back(c); + return *this; + } + + inline _UCXXEXPORT size_type length() const { return vector::size(); } + + void _UCXXEXPORT resize(size_type n, Ch c = Ch()) + { + vector::resize(n, c); + } + + _UCXXEXPORT basic_string& operator+=(const basic_string& str) + { + return append(str); + } + + _UCXXEXPORT basic_string& operator+=(const Ch * s) + { + return append(s); + } + + _UCXXEXPORT basic_string& operator+=(Ch c) + { + vector::push_back(c); + return *this; + } + + _UCXXEXPORT basic_string& append(const basic_string& str) + { + size_t temp = vector::elements; + resize(vector::elements + str.elements); + Tr::copy(vector::data + temp, str.vector::data, str.elements); + + return *this; + } + + _UCXXEXPORT basic_string& append(const basic_string& str, size_type pos, size_type n) + { + if (pos > str.size()) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range(); +#else + std::terminate(); +#endif + } + + size_type rlen = str.elements - pos; + if (rlen > n) + { + rlen = n; + } + + if (vector::elements > npos - rlen) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_length_error(); +#else + std::terminate(); +#endif + } + + size_t temp = vector::elements; + resize(vector::elements + rlen); + Tr::copy(vector::data + temp, str.vector::data + pos, rlen); + return *this; + } + + _UCXXEXPORT basic_string& append(const Ch* s, size_type n) + { + size_t temp = vector::elements; + resize(vector::elements + n); + Tr::copy(vector::data + temp, s, n); + return *this; + } + + _UCXXEXPORT basic_string& append(const Ch* s) + { + size_type strLen = Tr::length(s); + size_t temp = vector::elements; + resize(vector::elements + strLen); + Tr::copy(vector::data + temp, s, strLen); + return *this; + } + + _UCXXEXPORT basic_string& append(size_type n, Ch c) + { + vector::resize(vector::elements + n, c); + return *this; + } + + _UCXXEXPORT basic_string& assign(const basic_string& str) + { + operator=(str); + return *this; + } + + _UCXXEXPORT basic_string& assign(const basic_string& str, size_type pos, size_type n) + { + if (pos > str.elements) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range(); +#else + std::terminate(); +#endif + } + + size_type r = str.elements - pos; + if (r > n) + { + r = n; + } + + resize(r); + Tr::copy(vector::data, str.vector::data + pos, r); + return *this; + } + + _UCXXEXPORT basic_string& assign(const Ch* s, size_type n) + { + resize(n); + Tr::copy(vector::data, s, n); + return *this; + } + + _UCXXEXPORT basic_string& assign(const Ch* s) + { + size_type len = Tr::length(s); + return assign(s, len); + } + + _UCXXEXPORT basic_string& assign(size_type n, Ch c) + { + vector::clear(); + vector::resize(n, Ch()); + return *this; + } + + template _UCXXEXPORT basic_string& assign(InputIterator first, InputIterator last) + { + vector::resize(0, Ch()); + while (first != last) + { + append(*first); + ++first; + } + + return *this; + } + + _UCXXEXPORT basic_string& insert(size_type pos1, const basic_string& str, size_type pos2=0, size_type n=npos) + { + if (pos1 > vector::elements || pos2 > str.elements) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range(); +#else + std::terminate(); +#endif + } + + size_type r = str.elements - pos2; + if (r > n) + { + r = n; + } + + if (vector::elements > npos - r) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_length_error(); +#else + std::terminate(); +#endif + } + + size_type temp = vector::elements; + resize(vector::elements + r); + Tr::move(vector::data + pos1 + r, vector::data + pos1, temp - pos1); + Tr::copy(vector::data + pos1, str.vector::data + pos2, r); + return *this; + } + + _UCXXEXPORT basic_string& insert(size_type pos, const Ch* s, size_type n) + { + if (pos > vector::elements) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range(); +#else + std::terminate(); +#endif + } + + if (vector::elements > npos - n) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_length_error(); +#else + std::terminate(); +#endif + } + + size_type temp = vector::elements; + resize(vector::elements + n); + Tr::move(vector::data + pos + n, vector::data + pos, temp - pos); + Tr::copy(vector::data + pos, s, n); + return *this; + } + + inline _UCXXEXPORT basic_string& insert(size_type pos, const Ch* s) + { + size_type len = Tr::length(s); + return insert(pos, s, len); + } + + _UCXXEXPORT basic_string& insert(size_type pos, size_type n, Ch c) + { + if (pos > vector::elements) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range(); +#else + std::terminate(); +#endif + } + + if (vector::elements > npos - n) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_length_error(); +#else + std::terminate(); +#endif + } + + size_type temp = vector::elements; + resize(vector::elements + n); + Tr::move(vector::data + pos + n, vector::data + pos, temp - pos); + Tr::assign(vector::data + pos, n, c); + return *this; + } + + using vector::insert; +// void insert(iterator p, size_type n, charT c); +// template void insert(iterator p, InputIterator first, InputIterator last); + + _UCXXEXPORT basic_string& erase(size_type pos = 0, size_type n = npos) + { + size_type xlen = vector::elements - pos; + + if (xlen > n) + { + xlen = n; + } + + size_type temp = vector::elements; + + Tr::move(vector::data + pos, vector::data + pos + xlen, temp - pos - xlen); + resize(temp - xlen); + return *this; + } + + _UCXXEXPORT iterator erase(iterator position) + { + if (position == vector::end()) + { + return position; + } + + ++position; + + iterator temp = position; + + while (position != vector::end()) + { + *(position-1) = *position; + ++position; + } + + vector::pop_back(); + return temp; + } + + _UCXXEXPORT iterator erase(iterator first, iterator last) + { + size_t count = last - first; + + iterator temp = last; + + while (last != vector::end()) + { + *(last - count) = *last; + ++last; + } + + resize(vector::elements-count); + + return temp; + } + + _UCXXEXPORT basic_string& + replace(size_type pos1, size_type n1, const basic_string& str, size_type pos2=0, size_type n2=npos) + { + if (pos1 > vector::elements) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range(); +#else + std::terminate(); +#endif + } + + size_type xlen = vector::elements - pos1; + if (xlen > n1) + { + xlen = n1; + } + + size_type rlen = str.elements - pos2; + if (rlen > n2) + { + rlen = n2; + } + + if ((vector::elements - xlen) >= (npos - rlen)) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_length_error(); +#else + std::terminate(); +#endif + } + + size_t temp = vector::elements; + + if (rlen > xlen) + { + //Only if making larger + + resize(temp - xlen + rlen); + } + + //Final length = vector::elements - xlen + rlen + //Initial block is of size pos1 + //Block 2 is of size len + + Tr::move(vector::data + pos1 + rlen, vector::data + pos1 + xlen, temp - pos1 - xlen); + Tr::copy(vector::data + pos1, str.vector::data + pos2, rlen); + resize(temp - xlen + rlen); + return *this; + } + + _UCXXEXPORT basic_string& replace(size_type pos, size_type n1, const Ch* s, size_type n2) + { + return replace(pos,n1,basic_string(s,n2)); + } + + inline _UCXXEXPORT basic_string& replace(size_type pos, size_type n1, const Ch* s) + { + return replace(pos,n1,basic_string(s)); + } + + _UCXXEXPORT basic_string& replace(size_type pos, size_type n1, size_type n2, Ch c) + { + return replace(pos,n1,basic_string(n2,c)); + } + +// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, const basic_string& str); +// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, const Ch* s, size_type n); +// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, const Ch* s); +// _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, size_type n, Ch c); +/* template _UCXXEXPORT basic_string& replace(iterator i1, iterator i2, + InputIterator j1, InputIterator j2);*/ + + size_type _UCXXEXPORT copy(Ch* s, size_type n, size_type pos = 0) const + { + if (pos > vector::elements) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range(); +#else + std::terminate(); +#endif + } + + size_type r = vector::elements - pos; + if (r > n) + { + r = n; + } + + Tr::copy(s, vector::data + pos, r); + return r; + } + + _UCXXEXPORT void swap(basic_string& s) + { + //Data pointers + + vector::swap(s); + } + + _UCXXEXPORT const Ch* c_str() const + { + const_cast *>(this)->reserve(vector::elements+1); + vector::data[vector::elements] = 0; //Add 0 at the end + return vector::data; + } + + _UCXXEXPORT const Ch* data() const + { + return vector::data; + } + + _UCXXEXPORT allocator_type get_allocator() const + { + return vector::a; + } + + _UCXXEXPORT size_type find (const basic_string& str, size_type pos = 0) const; //Below + + _UCXXEXPORT size_type find (const Ch* s, size_type pos, size_type n) const + { + return find(basic_string(s,n), pos); + } + + _UCXXEXPORT size_type find (const Ch* s, size_type pos = 0) const + { + return find(basic_string(s), pos); + } + + _UCXXEXPORT size_type find (Ch c, size_type pos = 0) const + { + for (size_type i = pos; i < length(); ++i) + { + if (this->operator[](i) == c) + { + return i; + } + } + + return npos; + } + + _UCXXEXPORT size_type rfind(const basic_string& str, size_type pos = npos) const + { + if (pos >= length()) + { + pos = length(); + } + + for (size_type i = pos; i > 0; --i) + { + if (str == substr(i-1, str.length())) + { + return i-1; + } + } + + return npos; + } + + _UCXXEXPORT size_type rfind(const Ch* s, size_type pos, size_type n) const + { + return rfind(basic_string(s,n),pos); + } + + _UCXXEXPORT size_type rfind(const Ch* s, size_type pos = npos) const + { + return rfind(basic_string(s),pos); + } + + _UCXXEXPORT size_type rfind(Ch c, size_type pos = npos) const + { + return rfind(basic_string(1,c),pos); + } + + _UCXXEXPORT size_type find_first_of(const basic_string& str, size_type pos = 0) const + { + for (size_type i = pos; i < length(); ++i) + { + for (size_type j = 0; j < str.length() ; ++j) + { + if (Tr::eq(str[j], this->operator[](i))) + { + return i; + } + } + } + + return npos; + } + + _UCXXEXPORT size_type find_first_of(const Ch* s, size_type pos, size_type n) const + { + return find_first_of(basic_string(s,n),pos); + } + + _UCXXEXPORT size_type find_first_of(const Ch* s, size_type pos = 0) const + { + return find_first_of(basic_string(s),pos); + } + + _UCXXEXPORT size_type find_first_of(Ch c, size_type pos = 0) const + { + for (size_type i = pos; i< length(); ++i) + { + if (Tr::eq(this->operator[](i), c)) + { + return i; + } + } + + return npos; + } + + _UCXXEXPORT size_type find_last_of (const basic_string& str, size_type pos = npos) const + { + if (pos > length()) + { + pos = length(); + } + + for (size_type i = pos; i >0 ; --i) + { + for (size_type j = 0 ; j < str.length(); ++j) + { + if (Tr::eq(this->operator[](i-1), str[j])) + { + return i-1; + } + } + } + + return npos; + } + + _UCXXEXPORT size_type find_last_of (const Ch* s, size_type pos, size_type n) const + { + return find_last_of(basic_string(s,n),pos); + } + + _UCXXEXPORT size_type find_last_of (const Ch* s, size_type pos = npos) const + { + return find_last_of(basic_string(s),pos); + } + + _UCXXEXPORT size_type find_last_of (Ch c, size_type pos = npos) const + { + if (pos > length()) + { + pos = length(); + } + + for (size_type i = pos; i >0 ; --i) + { + if (Tr::eq(this->operator[](i-1), c)) + { + return i-1; + } + } + + return npos; + } + + _UCXXEXPORT size_type find_first_not_of(const basic_string& str, size_type pos = 0) const + { + bool foundCharacter; + for (size_type i = pos; i < length(); ++i) + { + foundCharacter = false; + for (size_type j = 0; j < str.length() ; ++j) + { + if (Tr::eq(str[j], this->operator[](i))) + { + foundCharacter = true; + } + } + + if (foundCharacter == false) + { + return i; + } + } + + return npos; + } + + _UCXXEXPORT size_type find_first_not_of(const Ch* s, size_type pos, size_type n) const + { + return find_first_not_of(basic_string(s,n),pos); + } + + _UCXXEXPORT size_type find_first_not_of(const Ch* s, size_type pos = 0) const + { + return find_first_not_of(basic_string(s),pos); + } + + _UCXXEXPORT size_type find_first_not_of(Ch c, size_type pos = 0) const + { + for (size_type i = pos; i < length() ; ++i) + { + if (this->operator[](i) != c) + { + return i; + } + } + + return npos; + } + + _UCXXEXPORT size_type find_last_not_of (const basic_string& str, size_type pos = npos) const + { + size_type xpos(length() - 1); + if (xpos > pos) + { + xpos = pos; + } + + while (xpos != npos && npos != str.find_first_of(this->at(xpos))) + { + --xpos; + } + + return xpos; + } + + _UCXXEXPORT size_type find_last_not_of (const Ch* s, size_type pos, size_type n) const + { + return find_last_not_of(basic_string(s,n),pos); + } + + _UCXXEXPORT size_type find_last_not_of (const Ch* s, size_type pos = npos) const + { + return find_last_not_of(basic_string(s),pos); + } + + _UCXXEXPORT size_type find_last_not_of (Ch c, size_type pos = npos) const + { + size_type xpos(length() - 1); + if (xpos > pos) + { + xpos = pos; + } + + while (xpos != npos && Tr::eq(this->at(xpos), c)) + { + --xpos; + } + + return xpos; + } + + _UCXXEXPORT basic_string substr(size_type pos = 0, size_type n = npos) const; + + _UCXXEXPORT int compare(const basic_string& str) const + { + size_type rlen = vector::elements; + if (rlen > str.elements) + { + rlen = str.elements; + } + + int retval = Tr::compare(vector::data, str.vector::data, rlen); + if (retval == 0) + { + if (vector::elements < str.elements) + { + retval = -1; + } + + if (vector::elements > str.elements) + { + retval = 1; + } + } + + return retval; + } + + _UCXXEXPORT int compare(size_type pos1, size_type n1, const basic_string& str, + size_type pos2=0, size_type n2=npos) const + { + size_type len1 = vector::elements - pos1; + if (len1 > n1) + { + len1 = n1; + } + + size_type len2 = str.vector::elements - pos2; + if (len2 > n2) + { + len2 = n2; + } + + size_type rlen = len1; + if (rlen > len2) + { + rlen = len2; + } + + int retval = Tr::compare(vector::data + pos1, str.vector::data + pos2, rlen); + if (retval == 0) + { + if (len1 < len2) + { + retval = -1; + } + + if (len1 > len2) + { + retval = 1; + } + } + + return retval; + } + + _UCXXEXPORT int compare(const Ch* s) const + { + size_type slen = Tr::length(s); + size_type rlen = slen; + if (rlen > vector::elements) + { + rlen=vector::elements; + } + + int retval = Tr::compare(vector::data, s, rlen); + if (retval==0) + { + if (vector::elements < slen) + { + retval = -1; + } + + if (vector::elements > slen) + { + retval = 1; + } + } + + return retval; + } + + _UCXXEXPORT int compare(size_type pos1, size_type n1, const Ch* s, size_type n2 = npos) const + { + size_type len1 = vector::elements - pos1; + if (len1 > n1) + { + len1 = n1; + } + + size_type slen = Tr::length(s); + size_type len2 = slen; + if (len2 > n2) + { + len2 = n2; + } + + size_type rlen = len1; + if (rlen > len2) + { + rlen = len2; + } + + int retval = Tr::compare(vector::data + pos1, s, rlen); + if (retval == 0) + { + if (len1 < len2) + { + retval = -1; + } + + if (len1 > len2) + { + retval = 1; + } + } + + return retval; + } }; //Functions template _UCXXEXPORT basic_string::basic_string(const Ch* s, const A& al) - : vector(al) + : vector(al) { - if(s!=0){ - size_type temp = Tr::length(s); - append(s, temp); - } + if (s!=0) + { + size_type temp = Tr::length(s); + append(s, temp); + } } template _UCXXEXPORT basic_string:: - basic_string(const basic_string& str, size_type pos, size_type n, const A& al) - : vector(al) + basic_string(const basic_string& str, size_type pos, size_type n, const A& al) + : vector(al) { - if(pos>str.size()){ - __throw_out_of_range(); - } - size_type rlen = str.size() - pos; - if( rlen > n){ - rlen = n; - } - resize(rlen); - Tr::copy(vector::data, str.vector::data + pos, vector::elements); + if (pos>str.size()) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range(); +#else + std::terminate(); +#endif + } + + size_type rlen = str.size() - pos; + if (rlen > n) + { + rlen = n; + } + + resize(rlen); + Tr::copy(vector::data, str.vector::data + pos, vector::elements); } template _UCXXEXPORT basic_string& - basic_string::operator=(const basic_string & str) + basic_string::operator=(const basic_string & str) { - if(&str == this){ //Check if we are doing a=a - return *this; - } - vector::clear(); - resize(str.elements); - Tr::copy( vector::data, str.vector::data, str.elements); - return *this; -} + if (&str == this) + { + //Check if we are doing a=a + return *this; + } + + vector::clear(); + resize(str.elements); + Tr::copy(vector::data, str.vector::data, str.elements); + return *this; +} template _UCXXEXPORT typename basic_string::size_type - basic_string::find (const basic_string& str, size_type pos) const + basic_string::find (const basic_string& str, size_type pos) const { - if(str.length() > length()){ - return npos; - } - size_type max_string_start = 1 + length() - str.length(); - for(size_type i = pos; i < max_string_start; ++i){ - if(str == substr(i, str.length())){ - return i; - } - } - return npos; -} + if (str.length() > length()) + { + return npos; + } + size_type max_string_start = 1 + length() - str.length(); + for (size_type i = pos; i < max_string_start; ++i) + { + if (str == substr(i, str.length())) + { + return i; + } + } + + return npos; +} template - _UCXXEXPORT basic_string basic_string::substr(size_type pos, size_type n) const + _UCXXEXPORT basic_string basic_string::substr(size_type pos, size_type n) const { - if(pos > vector::elements){ - __throw_out_of_range(); - } - size_type rlen = vector::elements - pos; - if(rlen > n){ - rlen = n; - } - return basic_string(vector::data + pos,rlen); + if (pos > vector::elements) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + __throw_out_of_range(); +#else + std::terminate(); +#endif + } + + size_type rlen = vector::elements - pos; + if (rlen > n) + { + rlen = n; + } + + return basic_string(vector::data + pos,rlen); } - - - #ifdef __UCLIBCXX_EXPAND_STRING_CHAR__ #ifndef __UCLIBCXX_COMPILE_STRING__ - #ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template <> _UCXXEXPORT string::basic_string(const allocator &); - template <> _UCXXEXPORT string::basic_string(size_type n, char c, const allocator & ); - template <> _UCXXEXPORT string::basic_string(const char* s, const allocator& al); - template <> _UCXXEXPORT string::basic_string(const basic_string& str, size_type pos, size_type n, const allocator& al); - template <> _UCXXEXPORT string::~basic_string(); + template <> _UCXXEXPORT string::basic_string(const allocator &); + template <> _UCXXEXPORT string::basic_string(size_type n, char c, const allocator &); + template <> _UCXXEXPORT string::basic_string(const char* s, const allocator& al); + template <> _UCXXEXPORT string::basic_string(const basic_string& str, size_type pos, size_type n, const allocator& al); + template <> _UCXXEXPORT string::~basic_string(); #endif - template <> _UCXXEXPORT string & string::append(const char * s, size_type n); + template <> _UCXXEXPORT string & string::append(const char * s, size_type n); + template <> _UCXXEXPORT string::size_type string::find(const string & str, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find(const char* s, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find (char c, size_type pos) const; - template <> _UCXXEXPORT string::size_type string::find(const string & str, size_type pos) const; - template <> _UCXXEXPORT string::size_type string::find(const char* s, size_type pos) const; - template <> _UCXXEXPORT string::size_type string::find (char c, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::rfind(const string & str, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::rfind(char c, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::rfind(const char* s, size_type pos) const; - template <> _UCXXEXPORT string::size_type string::rfind(const string & str, size_type pos) const; - template <> _UCXXEXPORT string::size_type string::rfind(char c, size_type pos) const; - template <> _UCXXEXPORT string::size_type string::rfind(const char* s, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find_first_of(const string &, size_type) const; + template <> _UCXXEXPORT string::size_type string::find_first_of(const char *, size_type pos, size_type n) const; + template <> _UCXXEXPORT string::size_type string::find_first_of(const char*, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find_first_of(char c, size_type pos) const; - template <> _UCXXEXPORT string::size_type string::find_first_of(const string &, size_type) const; - template <> _UCXXEXPORT string::size_type string::find_first_of(const char *, size_type pos, size_type n) const; - template <> _UCXXEXPORT string::size_type string::find_first_of(const char*, size_type pos) const; - template <> _UCXXEXPORT string::size_type string::find_first_of(char c, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find_last_of (const string & , size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos, size_type n) const; + template <> _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find_last_of (char c, size_type pos) const; - template <> _UCXXEXPORT string::size_type string::find_last_of (const string & , size_type pos) const; - template <> _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos, size_type n) const; - template <> _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos) const; - template <> _UCXXEXPORT string::size_type string::find_last_of (char c, size_type pos) const; + template <> _UCXXEXPORT string::size_type string::find_first_not_of(const string &, size_type) const; + template <> _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type, size_type) const; + template <> _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type) const; + template <> _UCXXEXPORT string::size_type string::find_first_not_of(char c, size_type) const; - template <> _UCXXEXPORT string::size_type string::find_first_not_of(const string &, size_type) const; - template <> _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type, size_type) const; - template <> _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type) const; - template <> _UCXXEXPORT string::size_type string::find_first_not_of(char c, size_type) const; + template <> _UCXXEXPORT int string::compare(const string & str) const; + template <> _UCXXEXPORT int string::compare( + size_type pos1, size_type n1, const string & str, size_type pos2, size_type n2) const; - template <> _UCXXEXPORT int string::compare(const string & str) const; - template <> _UCXXEXPORT int string::compare( - size_type pos1, size_type n1, const string & str, size_type pos2, size_type n2) const; + template <> _UCXXEXPORT string string::substr(size_type pos, size_type n) const; - template <> _UCXXEXPORT string string::substr(size_type pos, size_type n) const; - - template <> _UCXXEXPORT string & string::operator=(const string & str); - template <> _UCXXEXPORT string & string::operator=(const char * s); + template <> _UCXXEXPORT string & string::operator=(const string & str); + template <> _UCXXEXPORT string & string::operator=(const char * s); #endif #endif - - - //typedef basic_string string; template _UCXXEXPORT basic_string - operator+(const basic_string& lhs, const basic_string& rhs) + operator+(const basic_string& lhs, const basic_string& rhs) { - basic_string temp(lhs); - temp.append(rhs); - return temp; + basic_string temp(lhs); + temp.append(rhs); + return temp; } template _UCXXEXPORT basic_string - operator+(const charT* lhs, const basic_string& rhs) + operator+(const charT* lhs, const basic_string& rhs) { - basic_string temp(lhs); - temp.append(rhs); - return temp; -} - - -template _UCXXEXPORT basic_string - operator+(charT lhs, const basic_string& rhs) -{ - basic_string temp(1, lhs); - temp.append(rhs); - return temp; + basic_string temp(lhs); + temp.append(rhs); + return temp; } template _UCXXEXPORT basic_string - operator+(const basic_string& lhs, const charT* rhs) + operator+(charT lhs, const basic_string& rhs) { - basic_string temp(lhs); - temp.append(rhs); - return temp; + basic_string temp(1, lhs); + temp.append(rhs); + return temp; } template _UCXXEXPORT basic_string - operator+(const basic_string& lhs, charT rhs) + operator+(const basic_string& lhs, const charT* rhs) { - basic_string temp(lhs); - temp+=rhs; - return temp; + basic_string temp(lhs); + temp.append(rhs); + return temp; +} + +template _UCXXEXPORT basic_string + operator+(const basic_string& lhs, charT rhs) +{ + basic_string temp(lhs); + temp+=rhs; + return temp; } template _UCXXEXPORT bool - operator==(const basic_string& lhs, const basic_string& rhs) + operator==(const basic_string& lhs, const basic_string& rhs) { - if(lhs.compare(rhs) == 0){ - return true; - } - return false; + if (lhs.compare(rhs) == 0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator==(const charT* lhs, const basic_string& rhs) + operator==(const charT* lhs, const basic_string& rhs) { - if(rhs.compare(lhs) == 0){ - return true; - } - return false; + if (rhs.compare(lhs) == 0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator==(const basic_string& lhs, const charT* rhs) + operator==(const basic_string& lhs, const charT* rhs) { - if(lhs.compare(rhs)==0){ - return true; - } - return false; + if (lhs.compare(rhs)==0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator!=(const basic_string& lhs, const basic_string& rhs) + operator!=(const basic_string& lhs, const basic_string& rhs) { - if(lhs.compare(rhs) !=0){ - return true; - } - return false; + if (lhs.compare(rhs) !=0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator!=(const charT* lhs, const basic_string& rhs) + operator!=(const charT* lhs, const basic_string& rhs) { - basic_string temp(lhs); - return (temp != rhs); + basic_string temp(lhs); + return (temp != rhs); } template _UCXXEXPORT bool - operator!=(const basic_string& lhs, const charT* rhs) + operator!=(const basic_string& lhs, const charT* rhs) { - basic_string temp(rhs); - return (lhs != temp); + basic_string temp(rhs); + return (lhs != temp); } template _UCXXEXPORT bool - operator< (const basic_string& lhs, const basic_string& rhs) + operator< (const basic_string& lhs, const basic_string& rhs) { - if(lhs.compare(rhs) < 0){ - return true; - } - return false; + if (lhs.compare(rhs) < 0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator< (const basic_string& lhs, const charT* rhs) + operator< (const basic_string& lhs, const charT* rhs) { - basic_string temp(rhs); - if(lhs.compare(rhs) < 0){ - return true; - } - return false; + basic_string temp(rhs); + if (lhs.compare(rhs) < 0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator< (const charT* lhs, const basic_string& rhs) + operator< (const charT* lhs, const basic_string& rhs) { - basic_string temp(lhs); - if(temp.compare(rhs) < 0){ - return true; - } - return false; + basic_string temp(lhs); + if (temp.compare(rhs) < 0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator> (const basic_string& lhs, const basic_string& rhs) + operator> (const basic_string& lhs, const basic_string& rhs) { - if(lhs.compare(rhs) > 0){ - return true; - } - return false; + if (lhs.compare(rhs) > 0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator> (const basic_string& lhs, const charT* rhs) + operator> (const basic_string& lhs, const charT* rhs) { - basic_string temp(rhs); - if(lhs.compare(rhs) > 0){ - return true; - } - return false; + basic_string temp(rhs); + if (lhs.compare(rhs) > 0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator> (const charT* lhs, const basic_string& rhs) + operator> (const charT* lhs, const basic_string& rhs) { - basic_string temp(lhs); - if(temp.compare(rhs) > 0){ - return true; - } - return false; + basic_string temp(lhs); + if (temp.compare(rhs) > 0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator<=(const basic_string& lhs, const basic_string& rhs) + operator<=(const basic_string& lhs, const basic_string& rhs) { - if(lhs.compare(rhs) <=0){ - return true; - } - return false; + if (lhs.compare(rhs) <=0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator<=(const basic_string& lhs, const charT* rhs) + operator<=(const basic_string& lhs, const charT* rhs) { - basic_string temp(rhs); - if(lhs.compare(temp) <=0 ){ - return true; - } - return false; + basic_string temp(rhs); + if (lhs.compare(temp) <=0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator<=(const charT* lhs, const basic_string& rhs) + operator<=(const charT* lhs, const basic_string& rhs) { - basic_string temp(lhs); - if(temp.compare(rhs) <= 0){ - return true; - } - return false; + basic_string temp(lhs); + if (temp.compare(rhs) <= 0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator>=(const basic_string& lhs, const basic_string& rhs) + operator>=(const basic_string& lhs, const basic_string& rhs) { - if(lhs.compare(rhs) >=0){ - return true; - } - return false; + if (lhs.compare(rhs) >=0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator>=(const basic_string& lhs, const charT* rhs) + operator>=(const basic_string& lhs, const charT* rhs) { - basic_string temp(rhs); - if(lhs.compare(temp) >=0 ){ - return true; - } - return false; + basic_string temp(rhs); + if (lhs.compare(temp) >=0) + { + return true; + } + + return false; } template _UCXXEXPORT bool - operator>=(const charT* lhs, const basic_string& rhs) + operator>=(const charT* lhs, const basic_string& rhs) { - basic_string temp(lhs); - if(temp.compare(rhs) >=0 ){ - return true; - } - return false; + basic_string temp(lhs); + if (temp.compare(rhs) >=0) + { + return true; + } + + return false; } template _UCXXEXPORT void - swap(basic_string& lhs, basic_string& rhs) + swap(basic_string& lhs, basic_string& rhs) { - lhs.swap(rhs); + lhs.swap(rhs); } /*template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, const basic_string& str) + operator<<(basic_ostream& os, const basic_string& str) { - return os.write(str.data(), str.length()); + return os.write(str.data(), str.length()); }*/ #ifdef __UCLIBCXX_EXPAND_STRING_CHAR__ @@ -1031,12 +1329,9 @@ template <> _UCXXEXPORT string operator+(const string & lhs, const string & rhs) template <> _UCXXEXPORT bool operator> (const string & lhs, const string & rhs); template <> _UCXXEXPORT bool operator< (const string & lhs, const string & rhs); - #endif #endif - - -} +} // namespace #pragma GCC visibility pop diff --git a/misc/uClibc++/libxx/uClibc++/Make.defs b/misc/uClibc++/libxx/uClibc++/Make.defs index 2a877ee3e9..b8f7a70920 100644 --- a/misc/uClibc++/libxx/uClibc++/Make.defs +++ b/misc/uClibc++/libxx/uClibc++/Make.defs @@ -37,13 +37,16 @@ CXXSRCS += algorithm.cxx associative_base.cxx bitset.cxx char_traits.cxx CXXSRCS += complex.cxx del_op.cxx del_opnt.cxx del_opv.cxx del_opvnt.cxx -CXXSRCS += deque.cxx exception.cxx fstream.cxx func_exception.cxx -CXXSRCS += iomanip.cxx ios.cxx iostream.cxx istream.cxx iterator.cxx -CXXSRCS += limits.cxx list.cxx locale.cxx map.cxx new_handler.cxx -CXXSRCS += new_op.cxx new_opnt.cxx new_opv.cxx new_opvnt.cxx numeric.cxx -CXXSRCS += ostream.cxx queue.cxx set.cxx sstream.cxx stack.cxx -CXXSRCS += stdexcept.cxx streambuf.cxx string.cxx typeinfo.cxx utility.cxx -CXXSRCS += valarray.cxx vector.cxx +CXXSRCS += deque.cxx fstream.cxx iomanip.cxx ios.cxx iostream.cxx +CXXSRCS += istream.cxx iterator.cxx limits.cxx list.cxx locale.cxx +CXXSRCS += map.cxx new_handler.cxx new_op.cxx new_opnt.cxx new_opv.cxx +CXXSRCS += new_opvnt.cxx numeric.cxx ostream.cxx queue.cxx set.cxx +CXXSRCS += sstream.cxx stack.cxx streambuf.cxx string.cxx typeinfo.cxx +CXXSRCS += utility.cxx valarray.cxx vector.cxx + +ifeq ($(CONFIG_UCLIBCXX_EXCEPTION),y) +CXXSRCS += exception.cxx func_exception.cxx stdexcept.cxx +endif ifneq ($(CONFIG_UCLIBCXX_HAVE_LIBSUPCXX),y) CXXSRCS += eh_alloc.cxx eh_globals.cxx eh_terminate.cxx diff --git a/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx b/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx index f64be60d9c..1d1aa9eb7a 100644 --- a/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx +++ b/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx @@ -20,8 +20,6 @@ #include #include -#ifdef CONFIG_UCLIBCXX_EXCEPTION - namespace std { _UCXXEXPORT static terminate_handler __terminate_handler = abort; @@ -71,5 +69,3 @@ namespace std terminate(); } } - -#endif diff --git a/misc/uClibc++/libxx/uClibc++/func_exception.cxx b/misc/uClibc++/libxx/uClibc++/func_exception.cxx index 9971871efd..d5bbe001fd 100644 --- a/misc/uClibc++/libxx/uClibc++/func_exception.cxx +++ b/misc/uClibc++/libxx/uClibc++/func_exception.cxx @@ -22,8 +22,8 @@ #include #include -namespace std{ - +namespace std +{ #ifdef CONFIG_UCLIBCXX_EXCEPTION _UCXXEXPORT void __throw_bad_alloc() @@ -33,7 +33,7 @@ _UCXXEXPORT void __throw_bad_alloc() _UCXXEXPORT void __throw_out_of_range(const char * message) { - if(message == 0) + if (message == 0) { throw out_of_range(); } @@ -43,7 +43,7 @@ _UCXXEXPORT void __throw_out_of_range(const char * message) _UCXXEXPORT void __throw_overflow_error(const char * message) { - if(message == 0) + if (message == 0) { throw overflow_error(); } @@ -53,7 +53,7 @@ _UCXXEXPORT void __throw_overflow_error(const char * message) _UCXXEXPORT void __throw_length_error(const char * message) { - if(message == 0) + if (message == 0) { throw length_error(); } @@ -63,7 +63,7 @@ _UCXXEXPORT void __throw_length_error(const char * message) _UCXXEXPORT void __throw_invalid_argument(const char * message) { - if(message == 0) + if (message == 0) { throw invalid_argument(); } @@ -100,6 +100,4 @@ _UCXXEXPORT void __throw_invalid_argument(const char *) #endif - - -} +} // namespace diff --git a/misc/uClibc++/libxx/uClibc++/stdexcept.cxx b/misc/uClibc++/libxx/uClibc++/stdexcept.cxx index d372c0b779..73238526f4 100644 --- a/misc/uClibc++/libxx/uClibc++/stdexcept.cxx +++ b/misc/uClibc++/libxx/uClibc++/stdexcept.cxx @@ -1,63 +1,64 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include #ifdef CONFIG_UCLIBCXX_EXCEPTION -namespace std{ +namespace std +{ + _UCXXEXPORT logic_error::logic_error() throw() : mstring() + { + } - _UCXXEXPORT logic_error::logic_error() throw() : mstring(){ + _UCXXEXPORT logic_error::logic_error(const string& what_arg) : mstring(what_arg) + { + } - } + _UCXXEXPORT const char * logic_error::what() const throw() + { + return mstring.c_str(); + } - _UCXXEXPORT logic_error::logic_error(const string& what_arg) : mstring(what_arg){ + _UCXXEXPORT out_of_range::out_of_range() : logic_error() + { + } - } + _UCXXEXPORT out_of_range::out_of_range(const string & what_arg) : logic_error(what_arg) + { + } - _UCXXEXPORT const char * logic_error::what() const throw(){ - return mstring.c_str(); - } + _UCXXEXPORT runtime_error::runtime_error() : mstring() + { + } + _UCXXEXPORT runtime_error::runtime_error(const string& what_arg) : mstring(what_arg) + { + } - _UCXXEXPORT out_of_range::out_of_range() : logic_error(){ + _UCXXEXPORT const char * runtime_error::what() const throw() + { + return mstring.c_str(); + } - } - - _UCXXEXPORT out_of_range::out_of_range(const string & what_arg) : logic_error(what_arg) { - - } - - _UCXXEXPORT runtime_error::runtime_error() : mstring(){ - - } - - _UCXXEXPORT runtime_error::runtime_error(const string& what_arg) : mstring(what_arg){ - - } - - _UCXXEXPORT const char * runtime_error::what() const throw(){ - return mstring.c_str(); - } - -} +} // namespace #endif diff --git a/misc/uClibc++/libxx/uClibc++/string.cxx b/misc/uClibc++/libxx/uClibc++/string.cxx index 1edf69b5d9..dc99fe29ef 100644 --- a/misc/uClibc++/libxx/uClibc++/string.cxx +++ b/misc/uClibc++/libxx/uClibc++/string.cxx @@ -1,20 +1,20 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz +/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. + This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #define __UCLIBCXX_COMPILE_STRING__ 1 @@ -26,87 +26,81 @@ #include #include -namespace std{ - +namespace std +{ #ifdef __UCLIBCXX_EXPAND_STRING_CHAR__ - #ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template _UCXXEXPORT string::basic_string(const allocator &); - template _UCXXEXPORT string::basic_string(size_type n, char c, const allocator & ); - template _UCXXEXPORT string::basic_string(const char* s, const allocator& al); - template _UCXXEXPORT string::basic_string(const basic_string& str, size_type pos, size_type n, const allocator& al); - template _UCXXEXPORT string::~basic_string(); + template _UCXXEXPORT string::basic_string(const allocator &); + template _UCXXEXPORT string::basic_string(size_type n, char c, const allocator & ); + template _UCXXEXPORT string::basic_string(const char* s, const allocator& al); + template _UCXXEXPORT string::basic_string(const basic_string& str, size_type pos, size_type n, const allocator& al); + template _UCXXEXPORT string::~basic_string(); #endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template _UCXXEXPORT string & string::append(const char * s, size_type n); + template _UCXXEXPORT string & string::append(const char * s, size_type n); - template _UCXXEXPORT string::size_type string::find(const string & str, size_type pos) const; - template _UCXXEXPORT string::size_type string::find(const char* s, size_type pos) const; - template _UCXXEXPORT string::size_type string::find (char c, size_type pos) const; - template _UCXXEXPORT string::size_type string::rfind(const string & str, size_type pos) const; - template _UCXXEXPORT string::size_type string::rfind(char c, size_type pos) const; - template _UCXXEXPORT string::size_type string::rfind(const char* s, size_type pos) const; + template _UCXXEXPORT string::size_type string::find(const string & str, size_type pos) const; + template _UCXXEXPORT string::size_type string::find(const char* s, size_type pos) const; + template _UCXXEXPORT string::size_type string::find (char c, size_type pos) const; + template _UCXXEXPORT string::size_type string::rfind(const string & str, size_type pos) const; + template _UCXXEXPORT string::size_type string::rfind(char c, size_type pos) const; + template _UCXXEXPORT string::size_type string::rfind(const char* s, size_type pos) const; - template _UCXXEXPORT string::size_type string::find_first_of(const string &, size_type) const; - template _UCXXEXPORT string::size_type string::find_first_of(const char *, size_type pos, size_type n) const; - template _UCXXEXPORT string::size_type string::find_first_of(const char*, size_type pos) const; - template _UCXXEXPORT string::size_type string::find_first_of(char c, size_type pos) const; + template _UCXXEXPORT string::size_type string::find_first_of(const string &, size_type) const; + template _UCXXEXPORT string::size_type string::find_first_of(const char *, size_type pos, size_type n) const; + template _UCXXEXPORT string::size_type string::find_first_of(const char*, size_type pos) const; + template _UCXXEXPORT string::size_type string::find_first_of(char c, size_type pos) const; - template _UCXXEXPORT string::size_type string::find_last_of (const string & , size_type pos) const; - template _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos, size_type n) const; - template _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos) const; - template _UCXXEXPORT string::size_type string::find_last_of (char c, size_type pos) const; + template _UCXXEXPORT string::size_type string::find_last_of (const string & , size_type pos) const; + template _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos, size_type n) const; + template _UCXXEXPORT string::size_type string::find_last_of (const char* s, size_type pos) const; + template _UCXXEXPORT string::size_type string::find_last_of (char c, size_type pos) const; - template _UCXXEXPORT string::size_type string::find_first_not_of(const string &, size_type) const; - template _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type, size_type) const; - template _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type) const; - template _UCXXEXPORT string::size_type string::find_first_not_of(char c, size_type) const; + template _UCXXEXPORT string::size_type string::find_first_not_of(const string &, size_type) const; + template _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type, size_type) const; + template _UCXXEXPORT string::size_type string::find_first_not_of(const char*, size_type) const; + template _UCXXEXPORT string::size_type string::find_first_not_of(char c, size_type) const; - template _UCXXEXPORT int string::compare(const string & str) const; -// template _UCXXEXPORT int string::compare(size_type pos1, size_type n1, const string & str) const; - template _UCXXEXPORT int string::compare( - size_type pos1, size_type n1, const string & str, size_type pos2, size_type n2) const; + template _UCXXEXPORT int string::compare(const string & str) const; +//template _UCXXEXPORT int string::compare(size_type pos1, size_type n1, const string & str) const; + template _UCXXEXPORT int string::compare( + size_type pos1, size_type n1, const string & str, size_type pos2, size_type n2) const; - template _UCXXEXPORT string string::substr(size_type pos, size_type n) const; + template _UCXXEXPORT string string::substr(size_type pos, size_type n) const; - template _UCXXEXPORT string & string::operator=(const string & str); - template _UCXXEXPORT string & string::operator=(const char * s); + template _UCXXEXPORT string & string::operator=(const string & str); + template _UCXXEXPORT string & string::operator=(const char * s); - template _UCXXEXPORT bool operator==(const string & lhs, const string & rhs); - template _UCXXEXPORT bool operator==(const char * lhs, const string & rhs); - template _UCXXEXPORT bool operator==(const string & lhs, const char * rhs); + template _UCXXEXPORT bool operator==(const string & lhs, const string & rhs); + template _UCXXEXPORT bool operator==(const char * lhs, const string & rhs); + template _UCXXEXPORT bool operator==(const string & lhs, const char * rhs); - template _UCXXEXPORT bool operator!=(const string & lhs, const string & rhs); - template _UCXXEXPORT bool operator!=(const char * lhs, const string & rhs); - template _UCXXEXPORT bool operator!=(const string & lhs, const char * rhs); + template _UCXXEXPORT bool operator!=(const string & lhs, const string & rhs); + template _UCXXEXPORT bool operator!=(const char * lhs, const string & rhs); + template _UCXXEXPORT bool operator!=(const string & lhs, const char * rhs); - template _UCXXEXPORT string operator+(const string & lhs, const char* rhs); - template _UCXXEXPORT string operator+(const char* lhs, const string & rhs); - template _UCXXEXPORT string operator+(const string & lhs, const string & rhs); + template _UCXXEXPORT string operator+(const string & lhs, const char* rhs); + template _UCXXEXPORT string operator+(const char* lhs, const string & rhs); + template _UCXXEXPORT string operator+(const string & lhs, const string & rhs); - template _UCXXEXPORT bool operator> (const string & lhs, const string & rhs); - template _UCXXEXPORT bool operator< (const string & lhs, const string & rhs); + template _UCXXEXPORT bool operator> (const string & lhs, const string & rhs); + template _UCXXEXPORT bool operator< (const string & lhs, const string & rhs); +// Functions dependent upon OSTREAM -//Functions dependent upon OSTREAM #ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ - template _UCXXEXPORT ostream & operator<<(ostream & os, const string & str); - #endif -//Functions dependent upon ISTREAM +// Functions dependent upon ISTREAM + #ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ - template _UCXXEXPORT istream & operator>>(istream & is, string & str); - +#endif #endif - -#endif - -} +} // namespace diff --git a/nuttx/configs/sim/README.txt b/nuttx/configs/sim/README.txt index bc8173fcf5..654ce93146 100644 --- a/nuttx/configs/sim/README.txt +++ b/nuttx/configs/sim/README.txt @@ -215,6 +215,19 @@ cxxtest b. Execute 'make menuconfig' in nuttx/ in order to start the reconfiguration process. + 3. At presenet (2012/11/02), this example builds only with exceptions + disabled (CONFIG_UCLIBCXX_EXCEPTIONS=n). And even then, it will + not run. + + The reason that the example will will not run on the simulator has + to do with when static constructors are enabled: In the simulator + it will attempt to execute the static constructros before main() + starts. BUT... NuttX is not initialized and this results in a crash. + + To really use this example, I will have to think of some way to + postpone running C++ static initializers until NuttX has been + initialied. + mount Description diff --git a/nuttx/configs/sim/cxxtest/Make.defs b/nuttx/configs/sim/cxxtest/Make.defs index eba0b31dd5..7b0c524b4f 100644 --- a/nuttx/configs/sim/cxxtest/Make.defs +++ b/nuttx/configs/sim/cxxtest/Make.defs @@ -45,7 +45,11 @@ else endif ARCHCPUFLAGS = -fno-builtin -ARCHCPUFLAGSXX = -fno-builtin +ifeq ($(CONFIG_UCLIBCXX_EXCEPTION),y) + ARCHCPUFLAGSXX = -fno-builtin +else + ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions +endif ARCHPICFLAGS = -fpic ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow ARCHWARNINGSXX = -Wall -Wshadow From 23e8d5321a4de9c08a5f9c1e3a919aa740acca78 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 2 Nov 2012 23:22:48 +0000 Subject: [PATCH 069/206] Create an STM32F4Discovery configuration for testing uClibc++ git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5300 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/cxxtest/cxxtest_main.cxx | 22 +- misc/uClibc++/include/uClibc++/algorithm | 3764 +++++++++-------- .../include/uClibc++/associative_base | 1160 ++--- misc/uClibc++/include/uClibc++/bitset | 882 ++-- misc/uClibc++/include/uClibc++/char_traits | 323 +- misc/uClibc++/include/uClibc++/complex | 678 +-- misc/uClibc++/include/uClibc++/deque | 36 +- misc/uClibc++/include/uClibc++/fstream | 1297 +++--- misc/uClibc++/include/uClibc++/functional | 860 ++-- misc/uClibc++/include/uClibc++/iomanip | 195 +- misc/uClibc++/include/uClibc++/ios | 903 ++-- misc/uClibc++/include/uClibc++/iosfwd | 153 +- misc/uClibc++/include/uClibc++/iostream | 106 +- misc/uClibc++/include/uClibc++/istream | 1146 ++--- .../uClibc++/include/uClibc++/istream_helpers | 747 ++-- misc/uClibc++/include/uClibc++/iterator | 432 +- misc/uClibc++/include/uClibc++/iterator_base | 566 +-- misc/uClibc++/include/uClibc++/limits | 1287 +++--- misc/uClibc++/include/uClibc++/list | 1847 ++++---- misc/uClibc++/include/uClibc++/map | 379 +- misc/uClibc++/include/uClibc++/memory | 334 +- misc/uClibc++/include/uClibc++/new | 63 +- misc/uClibc++/include/uClibc++/numeric | 297 +- misc/uClibc++/include/uClibc++/ostream | 857 ++-- .../uClibc++/include/uClibc++/ostream_helpers | 1070 +++-- misc/uClibc++/include/uClibc++/queue | 217 +- misc/uClibc++/include/uClibc++/set | 675 +-- misc/uClibc++/include/uClibc++/sstream | 704 +-- misc/uClibc++/include/uClibc++/stack | 130 +- misc/uClibc++/include/uClibc++/streambuf | 587 +-- misc/uClibc++/include/uClibc++/string | 4 + .../uClibc++/include/uClibc++/string_iostream | 184 +- misc/uClibc++/include/uClibc++/type_traits | 139 +- misc/uClibc++/include/uClibc++/utility | 157 +- misc/uClibc++/include/uClibc++/valarray | 2495 ++++++----- misc/uClibc++/include/uClibc++/vector | 1040 ++--- .../libxx/uClibc++/associative_base.cxx | 44 +- misc/uClibc++/libxx/uClibc++/bitset.cxx | 44 +- nuttx/ChangeLog | 8 + nuttx/arch/arm/src/Makefile | 80 +- nuttx/arch/sim/src/Makefile | 8 +- nuttx/configs/sim/README.txt | 8 +- nuttx/configs/sim/cxxtest/Make.defs | 6 +- nuttx/configs/sim/cxxtest/defconfig | 2 +- nuttx/configs/sim/ostest/Make.defs | 96 +- nuttx/configs/stm32f4discovery/README.txt | 29 + .../stm32f4discovery/cxxtest/Make.defs | 184 + .../stm32f4discovery/cxxtest/defconfig | 573 +++ .../stm32f4discovery/cxxtest/setenv.sh | 75 + .../configs/stm32f4discovery/ostest/defconfig | 2 +- 50 files changed, 15444 insertions(+), 11451 deletions(-) create mode 100644 nuttx/configs/stm32f4discovery/cxxtest/Make.defs create mode 100644 nuttx/configs/stm32f4discovery/cxxtest/defconfig create mode 100755 nuttx/configs/stm32f4discovery/cxxtest/setenv.sh diff --git a/apps/examples/cxxtest/cxxtest_main.cxx b/apps/examples/cxxtest/cxxtest_main.cxx index 70d54109f5..9c2974826f 100644 --- a/apps/examples/cxxtest/cxxtest_main.cxx +++ b/apps/examples/cxxtest/cxxtest_main.cxx @@ -203,21 +203,25 @@ static void test_exception(void) // Name: cxxtest_main //***************************************************************************/ -int cxxtest_main(int argc, char *argv[]) +extern "C" { - // If C++ initialization for static constructors is supported, then do - // that first + int cxxtest_main(int argc, char *argv[]) + { + // If C++ initialization for static constructors is supported, then do + // that first #ifdef CONFIG_HAVE_CXXINITIALIZE - up_cxxinitialize(); + up_cxxinitialize(); #endif - test_iostream(); - test_stl(); - test_rtti(); + test_iostream(); + test_stl(); + test_rtti(); #ifdef CONFIG_UCLIBCXX_EXCEPTION - test_exception(); + test_exception(); #endif - return 0; + return 0; + } } + diff --git a/misc/uClibc++/include/uClibc++/algorithm b/misc/uClibc++/include/uClibc++/algorithm index 5e8f139c06..e13713cfc4 100644 --- a/misc/uClibc++/include/uClibc++/algorithm +++ b/misc/uClibc++/include/uClibc++/algorithm @@ -1,19 +1,20 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -23,1669 +24,2084 @@ #ifndef __STD_HEADER_ALGORITHM #define __STD_HEADER_ALGORITHM 1 -//Elliminate any previously defined macro +//Eliminate any previously defined macro + #undef min #undef max #pragma GCC visibility push(default) -namespace std{ - - // subclause _lib.alg.nonmodifying_, non-modifying sequence operations: - template _UCXXEXPORT - Function for_each(InputIterator first, InputIterator last, Function f) - { - while(first !=last){ - f(*first); - ++first; - } - return f; - } - - - template _UCXXEXPORT - InputIterator find(InputIterator first, InputIterator last, const T& value) - { - while(first !=last && *first != value){ - ++first; - } - return first; - } - - template _UCXXEXPORT - InputIterator find_if(InputIterator first, InputIterator last, Predicate pred) - { - while(first !=last && !pred(*first)){ - ++first; - } - return first; - } - - template _UCXXEXPORT ForwardIterator1 - find_end(ForwardIterator1 first1, ForwardIterator1 last1, - ForwardIterator2 first2, ForwardIterator2 last2) - { - ForwardIterator1 retval = last1; - while(first1 !=last1){ - ForwardIterator1 temp1(first1); - ForwardIterator2 temp2(first2); - while(temp2!=last2 && temp1!= last1){ - if(*temp1 != *temp2){ - break; //Exit while loop - } - ++temp1; - ++temp2; - if(temp2 == last2){ //Have successfully checked the whole sequence - retval = first1; - } - } - } - return retval; - } - - template _UCXXEXPORT - ForwardIterator1 - find_end(ForwardIterator1 first1, ForwardIterator1 last1, - ForwardIterator2 first2, ForwardIterator2 last2, - BinaryPredicate pred) - { - ForwardIterator1 retval = last1; - while(first1 !=last1){ - ForwardIterator1 temp1(first1); - ForwardIterator2 temp2(first2); - while(temp2!=last2 && temp1!= last1){ - if( ! pred(*temp1, *temp2)){ - break; //Exit while loop - } - ++temp1; - ++temp2; - if(temp2 == last2){ //Have successfully checked the whole sequence - retval = first1; - } - } - } - return retval; - } - - template _UCXXEXPORT - ForwardIterator1 - find_first_of(ForwardIterator1 first1, ForwardIterator1 last1, - ForwardIterator2 first2, ForwardIterator2 last2) - { - while(first1 != last1){ - ForwardIterator2 temp2(first2); - while(temp2 != last2 ){ - if(*temp2 == first1){ - return first1; - } - ++temp2; - } - - } - return last1; - } - - template _UCXXEXPORT - ForwardIterator1 - find_first_of(ForwardIterator1 first1, ForwardIterator1 last1, - ForwardIterator2 first2, ForwardIterator2 last2, - BinaryPredicate pred) - { - while(first1 != last1){ - ForwardIterator2 temp2(first2); - while(temp2 != last2 ){ - if(*temp2 == first1){ - return first1; - } - ++temp2; - } - - } - return last1; - } - - template _UCXXEXPORT ForwardIterator - adjacent_find(ForwardIterator first, ForwardIterator last) - { - ForwardIterator temp; - while(first != last){ - temp = first; - ++temp; - if(*temp == *first){ - return first; - } - ++first; - } - return first; - } - - template _UCXXEXPORT - ForwardIterator - adjacent_find(ForwardIterator first, ForwardIterator last, BinaryPredicate pred) - { - ForwardIterator temp; - while(first != last){ - temp = first; - ++temp; - if( pred(*temp, *first)){ - return first; - } - ++first; - } - return first; - } - - template _UCXXEXPORT - typename iterator_traits::difference_type - count(InputIterator first, InputIterator last, const T& value) - { - typename iterator_traits::difference_type i = 0; - while(first!=last){ - if(*first == value){ - ++i; - } - ++first; - } - return i; - } - - template _UCXXEXPORT - typename iterator_traits::difference_type - count_if(InputIterator first, InputIterator last, Predicate pred) - { - typename iterator_traits::difference_type i = 0; - while(first!=last){ - if( pred(*first) ){ - ++i; - } - ++first; - } - return i; - } - - template _UCXXEXPORT - pair - mismatch(InputIterator1 first1, InputIterator1 last1, InputIterator2 first2) - { - while(first1 != last1){ - if(*first1 != *first2){ - break; - } - ++first1; - ++first2; - } - - pair retval; - retval.first = first1; - retval.second = first2; - return retval; - } - - template _UCXXEXPORT - pair - mismatch(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, BinaryPredicate pred) - { - while(first1 != last1){ - if( !pred(*first1, *first2) ){ - break; - } - ++first1; - ++first2; - } - - pair retval; - retval.first = first1; - retval.second = first2; - return retval; - } - - template _UCXXEXPORT - bool - equal(InputIterator1 first1, InputIterator1 last1, InputIterator2 first2) - { - while(first1 !=last1){ - if(*first1 != *first2){ - return false; - } - ++first1; - ++first2; - } - return true; - } - - template _UCXXEXPORT - bool - equal(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, BinaryPredicate pred) - { - while(first1 !=last1){ - if( !pred(*first1, *first2) ){ - return false; - } - ++first1; - ++first2; - } - return true; - } - - template _UCXXEXPORT - ForwardIterator1 search(ForwardIterator1 first1, ForwardIterator1 last1, - ForwardIterator2 first2, ForwardIterator2 last2) - { - equal_to::value_type> c; - return search(first1, last1, first2, last2, c); - } - - - template _UCXXEXPORT - ForwardIterator1 - search(ForwardIterator1 first1, ForwardIterator1 last1, - ForwardIterator2 first2, ForwardIterator2 last2, - BinaryPredicate pred) - { - while(first1 != last1){ - ForwardIterator1 temp1(first1); - ForwardIterator2 temp2(first2); - while(temp2 != last2 && temp1 != last1){ - if( !pred(*temp2, *temp1) ){ - break; - } - ++temp1; - ++temp2; - if(temp2 == last2){ - return first1; - } - } - ++first1; - } - return last1; - } - - - template _UCXXEXPORT - ForwardIterator - search_n(ForwardIterator first, ForwardIterator last, Size count, const T& value) - { - while( first != last ){ - if(*first == value){ - ForwardIterator temp(first); - Size i = 1; - ++first; //Avoid doing the same comparison over again - while(i < count && *temp == value){ - ++first; - ++i; - } - if(i == count){ - return first; - } - } - ++first; - } - return first; - } - - - template _UCXXEXPORT - ForwardIterator - search_n(ForwardIterator first, ForwardIterator last, - Size count, const T& value, BinaryPredicate pred) - { - while( first != last ){ - if( pred(*first, value) ){ - ForwardIterator temp(first); - Size i = 1; - ++first; //Avoid doing the same comparison over again - while(i < count && pred(*temp, value) ){ - ++first; - ++i; - } - if(i == count){ - return first; - } - } - ++first; - } - return first; - - } - - // subclause _lib.alg.modifying.operations_, modifying sequence operations: - - template _UCXXEXPORT - OutputIterator - copy(InputIterator first, InputIterator last, OutputIterator result) - { - while(first != last){ - *result = *first; - ++first; - ++result; - } - return result; - } - - template _UCXXEXPORT - BidirectionalIterator2 - copy_backward(BidirectionalIterator1 first, BidirectionalIterator1 last, - BidirectionalIterator2 result) - { - while(first !=last ){ - --result; - --last; - *result = *last; - } - return result; - } - - template _UCXXEXPORT void swap(T& a, T& b){ - T temp(a); - a = b; - b = temp; - } - - template _UCXXEXPORT - ForwardIterator2 - swap_ranges(ForwardIterator1 first1, ForwardIterator1 last1, ForwardIterator2 first2) - { - while(first1 != last1){ - iter_swap(first1, first2); - ++first1; - ++first2; - } - return first2; - } - - - template _UCXXEXPORT - void - iter_swap(ForwardIterator1 a, ForwardIterator2 b) - { - typename iterator_traits::value_type temp(*a); - *a = *b; - *b = temp; - } - - - template _UCXXEXPORT - OutputIterator - transform(InputIterator first, InputIterator last, - OutputIterator result, UnaryOperation op) - { - while(first != last){ - *result = op(*first); - ++first; - ++result; - } - return result; - } - - - template _UCXXEXPORT - OutputIterator transform(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, OutputIterator result, - BinaryOperation binary_op) - { - while(first1 != last1){ - *result = binary_op(*first1, *first2); - ++first1; - ++first2; - ++result; - } - return result; - } - - - template _UCXXEXPORT - void - replace(ForwardIterator first, ForwardIterator last, - const T& old_value, const T& new_value) - { - while(first != last){ - if(*first == old_value){ - *first = new_value; - } - ++first; - } - } - - template _UCXXEXPORT - void - replace_if(ForwardIterator first, ForwardIterator last, - Predicate pred, const T& new_value) - { - while(first != last){ - if( pred(*first) ){ - *first = new_value; - } - ++first; - } - } - - - template _UCXXEXPORT - OutputIterator - replace_copy(InputIterator first, InputIterator last, - OutputIterator result, const T& old_value, const T& new_value) - { - while(first != last){ - if(*first == old_value){ - *result = new_value; - }else{ - *result = *first; - } - ++first; - ++result; - } - return result; - } - - template _UCXXEXPORT - OutputIterator - replace_copy_if(Iterator first, Iterator last, - OutputIterator result, Predicate pred, const T& new_value) - { - while(first != last){ - if( pred(*first) ){ - *result = new_value; - }else{ - *result = *first; - } - ++first; - ++result; - } - return result; - } - - template _UCXXEXPORT - void - fill(ForwardIterator first, ForwardIterator last, const T& value) - { - while(first != last){ - *first = value; - ++first; - } - } - - template _UCXXEXPORT - void - fill_n(OutputIterator first, Size n, const T& value) - { - while(n != 0){ - *first = value; - --n; - ++first; - } - } - - template _UCXXEXPORT - void - generate(ForwardIterator first, ForwardIterator last, Generator gen) - { - while(first != last){ - *first = gen(); - ++first; - } - } - - template _UCXXEXPORT - void - generate_n(OutputIterator first, Size n, Generator gen) - { - while(n !=0){ - *first = gen(); - --n; - ++first; - } - } - - template _UCXXEXPORT - ForwardIterator - remove(ForwardIterator first, ForwardIterator last, const T& value) - { - ForwardIterator temp(first); - while(temp !=last){ - if(*temp == value){ - - }else{ - *first = *temp; - ++first; - } - ++temp; - } - return first; - } - - template _UCXXEXPORT - ForwardIterator - remove_if(ForwardIterator first, ForwardIterator last, Predicate pred) - { - ForwardIterator temp(first); - while(temp !=last){ - if( pred(*temp) ){ - - }else{ - *first = *temp; - ++first; - } - ++temp; - } - return first; - } - - - template _UCXXEXPORT - OutputIterator - remove_copy(InputIterator first, InputIterator last, - OutputIterator result, const T& value) - { - while(first !=last){ - if(*first != value){ - *result = *first; - ++result; - } - ++first; - } - return result; - } - - template _UCXXEXPORT - OutputIterator - remove_copy_if(InputIterator first, InputIterator last, - OutputIterator result, Predicate pred) - { - while(first !=last){ - if( !pred(*first) ){ - *result = *first; - ++result; - } - ++first; - } - return result; - } - - template _UCXXEXPORT - ForwardIterator - unique(ForwardIterator first, ForwardIterator last) - { - ForwardIterator new_val(first); - ForwardIterator old_val(first); - - while(new_val !=last){ - if(*new_val == *old_val && new_val != old_val){ - - }else{ - *first = *new_val; - old_val = new_val; - ++first; - } - ++new_val; - } - return first; - } - - template _UCXXEXPORT - ForwardIterator - unique(ForwardIterator first, ForwardIterator last, BinaryPredicate pred) - { - ForwardIterator new_val(first); - ForwardIterator old_val(first); - - while(new_val !=last){ - if( pred(*new_val, *old_val) && new_val != old_val){ - - }else{ - *first = *new_val; - old_val = new_val; - ++first; - } - ++new_val; - } - return first; - } - - template _UCXXEXPORT - OutputIterator - unique_copy(InputIterator first, InputIterator last, OutputIterator result) - { - InputIterator temp(first); - while(first !=last ){ - if(*first == *temp && first != temp){ - - }else{ - *result = *first; - temp = first; - ++result; - } - ++first; - } - return result; - } - - template _UCXXEXPORT - OutputIterator - unique_copy(InputIterator first, InputIterator last, - OutputIterator result, BinaryPredicate pred) - { - InputIterator temp(first); - while(first !=last ){ - if( pred(*first, *temp) && first != temp){ - - }else{ - *result = *first; - temp = first; - ++result; - } - ++first; - } - return result; - } - - template _UCXXEXPORT - void - reverse(BidirectionalIterator first, BidirectionalIterator last) - { - --last; //Don't work with one past the end element - while(first < last){ - iter_swap(first, last); - ++first; - --last; - } - } - - template _UCXXEXPORT - OutputIterator - reverse_copy(BidirectionalIterator first, BidirectionalIterator last, - OutputIterator result) - { - while(last > first){ - --last; - *result = *last; - ++result; - } - return result; - } - - template _UCXXEXPORT - void - rotate(ForwardIterator first, ForwardIterator middle, ForwardIterator last) - { - if ((first == middle) || (last == middle)){ - return; - } - - ForwardIterator first2 = middle; - - do { - swap(*first, *first2); - first++; - first2++; - if(first == middle){ - middle = first2; - } - } while(first2 != last); - - first2 = middle; - - while (first2 != last) { - swap(*first, *first2); - first++; - first2++; - if (first == middle){ - middle = first2; - }else if (first2 == last){ - first2 = middle; - } - } - } - - template _UCXXEXPORT - OutputIterator - rotate_copy(ForwardIterator first, ForwardIterator middle, - ForwardIterator last, OutputIterator result) - { - ForwardIterator temp(middle); - while(temp !=last){ - *result = *temp; - ++temp; - ++result; - } - while(first != middle){ - *result = *first; - ++first; - ++result; - } - return result; - } - - - template _UCXXEXPORT - void - random_shuffle(RandomAccessIterator first, RandomAccessIterator last) - { - --last; - while(first != last){ - iter_swap(first, (first + (rand() % (last - first) ) ) ); - ++first; - } - } - - template _UCXXEXPORT - void - random_shuffle(RandomAccessIterator first, RandomAccessIterator last, - RandomNumberGenerator& rand) - { - --last; - while(first != last){ - iter_swap(first, (first + (rand(last - first) ) ) ); - ++first; - } - } - - // _lib.alg.partitions_, partitions: - template _UCXXEXPORT BidirectionalIterator - partition(BidirectionalIterator first, BidirectionalIterator last, Predicate pred) - { - return stable_partition(first, last, pred); - } - - template _UCXXEXPORT BidirectionalIterator - stable_partition(BidirectionalIterator first, BidirectionalIterator last, Predicate pred) - { - //first now points to the first non-desired element - while( first != last && pred(*first) ){ - ++first; - } - - BidirectionalIterator tempb; - BidirectionalIterator tempe = first; - - while( tempe != last ){ - //Find the next desired element - while( !pred(*tempe) ){ - ++tempe; - - //See if we should exit - if(tempe == last){ - return first; - } - } - - //Rotate the element back to the begining - tempb = tempe; - while(tempb != first){ - iter_swap(tempb, tempb-1 ); - --tempb; - } - //First now has a desired element - ++first; - } - - return first; - } - - template _UCXXEXPORT - void sort(RandomAccessIterator first, RandomAccessIterator last) - { - less::value_type> c; - sort(first, last, c ); - } - - template _UCXXEXPORT - void sort(RandomAccessIterator first, RandomAccessIterator last, Compare comp) - { - stable_sort(first, last, comp); - } - - template _UCXXEXPORT - void stable_sort(RandomAccessIterator first, RandomAccessIterator last) - { - less::value_type> c; - stable_sort(first, last, c); - } - - template _UCXXEXPORT - void stable_sort(RandomAccessIterator first, RandomAccessIterator last, Compare comp) - { - //FIXME - bubble sort - RandomAccessIterator temp; - --last; - while(last - first > 0){ - temp = last; - while(temp != first){ - if( comp( *temp, *(temp-1) ) ){ - iter_swap( temp-1, temp); - } - --temp; - } - ++first; - } - } - - template _UCXXEXPORT - void partial_sort(RandomAccessIterator first, RandomAccessIterator middle, RandomAccessIterator last) - { - less::value_type> c; - partial_sort(first, middle, last, c); - } - template _UCXXEXPORT - void partial_sort(RandomAccessIterator first, RandomAccessIterator middle, - RandomAccessIterator last, Compare comp) - { - //Fixme - partial bubble sort - RandomAccessIterator temp; - --last; - while(first < middle){ - temp = last; - while(temp != first){ - if( comp(*temp, *(temp -1 ) ) ) { - iter_swap( temp-1, temp); - } - --temp; - } - ++first; - } - } - template _UCXXEXPORT - RandomAccessIterator - partial_sort_copy(InputIterator first, InputIterator last, - RandomAccessIterator result_first, RandomAccessIterator result_last) - { - less::value_type> c; - return partial_sort_copy(first, last, result_first, result_last, c); - } - template _UCXXEXPORT - RandomAccessIterator - partial_sort_copy(InputIterator first, InputIterator last, - RandomAccessIterator result_first, RandomAccessIterator result_last, Compare comp) - { - size_t output_size = last-first; - size_t temp_size = result_last - result_first; - if(temp_size < output_size){ - output_size = temp_size; - } - - RandomAccessIterator middle = result_first + output_size; - RandomAccessIterator temp = result_first; - - while(temp != middle){ - *temp = *first; - ++temp; - ++first; - } - sort(result_first, middle, comp); - - while( first != last){ - if( comp( *first, *(middle-1) ) ){ - *(middle-1) = *first; - sort(result_first, middle, comp); - } - ++first; - } - - return middle; - } - template _UCXXEXPORT - void nth_element(RandomAccessIterator first, RandomAccessIterator nth, RandomAccessIterator last) - { - less::value_type> c; - nth_element(first, nth, last, c); - } - template _UCXXEXPORT - void nth_element(RandomAccessIterator first, RandomAccessIterator nth, - RandomAccessIterator last, Compare comp) - { - partial_sort(first, nth, last, comp); - } - - template _UCXXEXPORT - ForwardIterator lower_bound(ForwardIterator first, ForwardIterator last, - const T& value) - { - less::value_type> c; - return lower_bound(first, last, value, c); - } - - template _UCXXEXPORT - ForwardIterator lower_bound(ForwardIterator first, ForwardIterator last, - const T& value, Compare comp) - { - if(first == last){ - return last; - } - //If below or equal to the first element - if( comp(*first, value) == false){ - return first; - } - ForwardIterator middle; - - //If greater than the top element - middle = first; - advance(middle, distance(first, last) - 1); - if( comp(*middle, value) ){ - return last; - } - - //Now begin the actual search for the begining - while( distance(first, last) > 1 ){ - //Find middle - middle = first; - advance(middle, (distance(first, last)/2) ); - if( !comp(*middle, value) ){ - last = middle; - }else{ - first = middle; - } - } - - if( !comp(*first, value) ){ - return first; - } - return last; - } - - template _UCXXEXPORT - ForwardIterator upper_bound(ForwardIterator first, ForwardIterator last, - const T& value) - { - less::value_type> c; - return upper_bound(first, last, value, c); - } - - - template _UCXXEXPORT - ForwardIterator upper_bound(ForwardIterator first, ForwardIterator last, - const T& value, Compare comp) - { - if(first == last){ - return last; - } - //If below the first element - if( comp(value, *first) == true){ - return first; - } - - ForwardIterator middle; - - //If greater than the top element - middle = first; - advance(middle, distance(first, last) - 1); - if( comp(*middle, value) ){ - return last; - } - - //Now begin the actual search for the end - while( distance(first, last) > 1 ){ - //Find middle - middle = first; - advance(middle, (distance(first, last)/2) ); - if( comp(value, *middle) ){ - last = middle; - }else{ - first = middle; - } - } - - if( comp(value, *first) ){ - return first; - } - return last; - } - - - template _UCXXEXPORT - pair - equal_range(ForwardIterator first, ForwardIterator last, const T& value) - { - less::value_type> c; - return equal_range(first, last, value, c); - } - - template _UCXXEXPORT - pair - equal_range(ForwardIterator first, ForwardIterator last, const T& value, Compare comp) - { - pair retval; - retval.first = lower_bound(first, last, value, comp); - //Reuse retval.first in order to (possibly) save a few comparisons - retval.second = upper_bound(retval.first, last, value, comp); - return retval; - - } - - template _UCXXEXPORT - bool binary_search(ForwardIterator first, ForwardIterator last, - const T& value) - { - less::value_type> c; - return binary_search(first, last, value, c); - } - - template _UCXXEXPORT - bool binary_search(ForwardIterator first, ForwardIterator last, - const T& value, Compare comp) - { - if( distance(first, last) == 0){ - return false; - } - - ForwardIterator middle; - - while( distance(first, last) > 1 ){ - //Set middle between first and last - middle = first; - advance(middle, distance(first, last)/2 ); - - if( comp(*middle, value ) == true){ - first = middle; - }else{ - last = middle; - } - } - - if( !comp(*first, value) && !comp(value, *first) ){ - return true; - } - if( !comp(*last, value) && !comp(value, *last) ){ - return true; - } - - return false; - } - - // _lib.alg.merge_, merge: - template _UCXXEXPORT - OutputIterator - merge(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, OutputIterator result) - { - less::value_type> c; - return merge(first1, last1, first2, last2, result, c); - } - template _UCXXEXPORT - OutputIterator - merge(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) - { - while( first1 != last1 && first2 != last2){ - //If in this order so first1 elements which are equal come first - if( comp(*first2, *first1) ){ - *result = *first2; - ++first2; - }else{ - *result = *first1; - ++first1; - } - ++result; - } - //Clean up remaining elements - while(first1 != last1){ - *result = *first1; - ++first1; - ++result; - } - while(first2 != last2){ - *result = *first2; - ++first2; - ++result; - } - return result; - } - template _UCXXEXPORT - void inplace_merge(BidirectionalIterator first, - BidirectionalIterator middle, BidirectionalIterator last) - { - less::value_type> c; - inplace_merge(first, middle, last, c); - } - template _UCXXEXPORT - void inplace_merge(BidirectionalIterator first, - BidirectionalIterator middle, BidirectionalIterator last, Compare comp) - { - //FIXME - using a bubble exchange method - while(first != middle && middle !=last){ - if( comp(*middle, *first) ){ - BidirectionalIterator temp(middle); - while( temp != first){ - iter_swap(temp, temp-1); - --temp; - } - ++middle; - } - ++first; - } - } - - // _lib.alg.set.operations_, set operations: - template _UCXXEXPORT - bool includes(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2) - { - less::value_type> c; - return includes(first1, last1, first2, last2, c ); - } - - template _UCXXEXPORT - bool includes(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, Compare comp) - { - while(first2 != last2){ - //Advance the large set until no longer smaller than the element we are looking for - while( comp(*first1, *first2) ){ - ++first1; - //If we are at the end of the list, we don't have the desired element - if(first1 == last1){ - return false; - } - } - //If we are past the element we want, it isn't here - if( comp(*first2, *first1) ){ - return false; - } - ++first2; //Move to next element - } - return true; - } - - template _UCXXEXPORT - OutputIterator set_union(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, OutputIterator result) - { - less::value_type> c; - return set_union(first1, last1, first2, last2, result, c); - } - - template _UCXXEXPORT - OutputIterator set_union(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) - { - while( first1 != last1 && first2 != last2){ - if( comp(*first2, *first1) ){ - *result = *first2; - - //Elliminate duplicates - InputIterator2 temp = first2; - while( first1 != last1 && !comp( *temp, *first1) ){ - ++first1; - } - while( first2 != last2 && !comp( *temp, *first2) ){ - ++first2; - } - }else{ - *result = *first1; - //Elliminate duplicates - InputIterator1 temp = first1; - while( first1 != last1 && !comp( *temp, *first1) ){ - ++first1; - } - while( first2 != last2 && !comp( *temp, *first2) ){ - ++first2; - } - } - ++result; - } - - //Clean up remaining elements - while(first1 != last1){ - *result = *first1; - ++result; - InputIterator1 temp = first1; - while( first1 != last1 && !comp( *temp, *first1) ){ - ++first1; - } - } - - while(first2 != last2){ - *result = *first2; - ++result; - InputIterator2 temp = first2; - while( first2 != last2 && !comp( *temp, *first2) ){ - ++first2; - } - } - return result; - } - - template _UCXXEXPORT - OutputIterator set_intersection(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, OutputIterator result) - { - less::value_type> c; - return set_intersection(first1, last1, first2, last2, result, c); - } - template _UCXXEXPORT - OutputIterator set_intersection(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) - { - while( first1 != last1 && first2 != last2){ - if( comp(*first2, *first1) ){ - ++first2; - }else if( comp(*first1, *first2) ) { - ++first1; - }else{ - *result = *first1; - ++result; - InputIterator1 temp = first1; - while( first1 != last1 && !comp( *temp, *first1) ){ - ++first1; - } - ++first2; - } - } - return result; - } - template _UCXXEXPORT - OutputIterator set_difference(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, OutputIterator result) - { - less::value_type> c; - return set_difference(first1, last1, first2, last2, result, c); - } - template _UCXXEXPORT - OutputIterator set_difference(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) - { - while( first1 != last1 && first2 != last2){ - if( comp(*first1, *first2) ){ - *result = *first1; - ++result; - - //Elliminate duplicates - InputIterator1 temp = first1; - while( first1 != last1 && !comp( *temp, *first1) ){ - ++first1; - } - }else if( comp(*first2, *first1) ){ - - //Elliminate duplicates - InputIterator2 temp = first2; - while( first2 != last2 && !comp( *temp, *first2) ){ - ++first2; - } - - }else{ //They are identical - skip - //Elliminate duplicates - InputIterator1 temp = first1; - while( first1 != last1 && !comp( *temp, *first1) ){ - ++first1; - } - while( first2 != last2 && !comp( *temp, *first2) ){ - ++first2; - } - } - } - - //Clean up remaining elements - while(first1 != last1){ - *result = *first1; - ++result; - InputIterator1 temp = first1; - while( first1 != last1 && !comp( *temp, *first1) ){ - ++first1; - } - } - - return result; - } - template _UCXXEXPORT - OutputIterator set_symmetric_difference(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, OutputIterator result) - { - less::value_type> c; - return set_symmetric_difference(first1, last1, first2, last2, result, c); - } - template _UCXXEXPORT - OutputIterator set_symmetric_difference(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) - { - while( first1 != last1 && first2 != last2){ - if( comp(*first1, *first2) ){ - *result = *first1; - ++result; - - //Elliminate duplicates - InputIterator1 temp = first1; - while( first1 != last1 && !comp( *temp, *first1) ){ - ++first1; - } - }else if( comp(*first2, *first1) ){ - *result = *first2; - ++result; - - //Elliminate duplicates - InputIterator2 temp = first2; - while( first2 != last2 && !comp( *temp, *first2) ){ - ++first2; - } - - }else{ //They are identical - skip - //Elliminate duplicates - InputIterator1 temp = first1; - while( first1 != last1 && !comp( *temp, *first1) ){ - ++first1; - } - while( first2 != last2 && !comp( *temp, *first2) ){ - ++first2; - } - } - } - - //Clean up remaining elements - while(first1 != last1){ - *result = *first1; - ++result; - InputIterator1 temp = first1; - while( first1 != last1 && !comp( *temp, *first1) ){ - ++first1; - } - } - - while(first2 != last2){ - *result = *first2; - ++result; - InputIterator2 temp = first2; - while( first2 != last2 && !comp( *temp, *first2) ){ - ++first2; - } - } - - return result; - } - - // _lib.alg.heap.operations_, heap operations: - - template _UCXXEXPORT - void push_heap(RandomAccessIterator first, RandomAccessIterator last) - { - less::value_type> c; - push_heap(first, last, c); - } - - template _UCXXEXPORT - void push_heap(RandomAccessIterator first, RandomAccessIterator last, Compare comp) - { - // *(last - 1) is the last element - RandomAccessIterator begin, middle, end; - begin = first; - end = last - 2; - if(last - first < 2){ //Empty heap - return; - } - if ( comp(*(last-1), *end) ){ //Belongs past the end - already in place - return; - } - while(end - begin > 1){ - middle = begin + ((end - begin)/2); - if( comp(*middle, *(last-1) ) ){ - end = middle; - }else{ - begin = middle; - } - } - - if( comp(*begin, *(last-1)) ){ - middle = begin; - }else{ - middle = end; - } - - //Now all we do is swap the elements up to the begining - --last; - - while(last > middle){ - iter_swap(last, last-1); - --last; - } - } - - template _UCXXEXPORT - void pop_heap(RandomAccessIterator first, RandomAccessIterator last) - { - less::value_type> c; - pop_heap(first, last, c); - } - template _UCXXEXPORT - void pop_heap(RandomAccessIterator first, RandomAccessIterator last, Compare) - { - --last; - while(first < last){ - iter_swap( first, first+1); - ++first; - } - } - - template _UCXXEXPORT - void make_heap(RandomAccessIterator first, RandomAccessIterator last) - { - less::value_type> c; - make_heap(first, last, c); - } - template _UCXXEXPORT - void make_heap(RandomAccessIterator first, RandomAccessIterator last, Compare comp) - { - sort( reverse_iterator(last), reverse_iterator(first), comp); - } - template _UCXXEXPORT - void sort_heap(RandomAccessIterator first, RandomAccessIterator last) - { - less::value_type> c; - sort_heap(first, last, c); - } - template _UCXXEXPORT - void sort_heap(RandomAccessIterator first, RandomAccessIterator last, Compare comp) - { - sort( first, last, comp); - } - - - // _lib.alg.min.max_, minimum and maximum: - template _UCXXEXPORT - const T& min(const T& a, const T& b) - { - if(b < a){ - return b; - } - return a; - } - - template _UCXXEXPORT - const T& min(const T& a, const T& b, Compare comp) - { - if( comp(b, a) == true){ - return b; - } - return a; - } - - template _UCXXEXPORT - const T& max(const T& a, const T& b) - { - if( a < b){ - return b; - } - return a; - } - - template _UCXXEXPORT - const T& max(const T& a, const T& b, Compare comp) - { - if( comp(a, b) ){ - return b; - } - return a; - } - - template _UCXXEXPORT - ForwardIterator min_element(ForwardIterator first, ForwardIterator last) - { - less::value_type> c; - return min_element(first, last, c); - } - - template _UCXXEXPORT - ForwardIterator min_element(ForwardIterator first, ForwardIterator last, Compare comp) - { - ForwardIterator retval = first; - ++first; - while(first != last){ - if( comp( *first, *retval) ){ - retval = first; - } - ++first; - } - return retval; - } - - template _UCXXEXPORT - ForwardIterator max_element(ForwardIterator first, ForwardIterator last) - { - less::value_type> c; - return max_element(first, last, c); - } - - template _UCXXEXPORT - ForwardIterator max_element(ForwardIterator first, ForwardIterator last, Compare comp) - { - ForwardIterator retval = first; - ++first; - while(first != last){ - if( comp( *retval, *first ) ){ - retval = first; - } - ++first; - } - return retval; - } - - template _UCXXEXPORT - bool lexicographical_compare(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2) - { - less::value_type> c; - return lexicographical_compare(first1, last1, first2, last2, c); - } - - template _UCXXEXPORT - bool lexicographical_compare(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, InputIterator2 last2, Compare comp) - { - while(first1 != last1 && first2 != last2){ - if( comp(*first1, *first2) ){ - return true; - } - if( comp(*first2, *first1) ){ - return false; - } - ++first1; - ++first2; - } - return first1==last1 && first2 != last2; - } - - // _lib.alg.permutation.generators_, permutations - template _UCXXEXPORT - bool next_permutation(BidirectionalIterator first, BidirectionalIterator last) - { - less::value_type> c; - return next_permutation(first, last, c); - } - - template _UCXXEXPORT - bool next_permutation(BidirectionalIterator first, BidirectionalIterator last, Compare comp) - { - if(first == last){ - return false; // No data - } - BidirectionalIterator i = last; - --i; - if(i == first){ - return false; //Only one element - } - BidirectionalIterator ii = i; - --ii; - //If the last two items are in order, swap them and call it done - if( comp(*ii, *i) ){ - iter_swap(ii, i); - return true; - } - - - //This part of the algorithm copied from G++ header files ver. 3.4.2 - i = last; - --i; - for(;;){ - ii = i; - --i; - if ( comp(*i, *ii) ){ - BidirectionalIterator j = last; - --j; - while ( !comp(*i, *j)){ - --j; - } - iter_swap(i, j); - reverse(ii, last); - return true; - } - if (i == first){ - reverse(first, last); - return false; - } - } - - - } - - template _UCXXEXPORT - bool prev_permutation(BidirectionalIterator first, BidirectionalIterator last) - { - less::value_type> c; - return prev_permutation(first, last, c); - } - - template _UCXXEXPORT - bool prev_permutation(BidirectionalIterator first, BidirectionalIterator last, Compare comp) - { - if(first == last){ - return false; // No data - } - BidirectionalIterator i = last; - --i; - if(i == first){ - return false; //Only one element - } - BidirectionalIterator ii = i; - --ii; - //If the last two items are in reverse order, swap them and call it done - if( comp(*i, *ii) ){ - iter_swap(ii, i); - return true; - } - - //Copied from GNU GCC header files version 3.4.2 - i = last; - --i; - - for(;;){ - ii = i; - --i; - if ( comp(*ii, *i)){ - BidirectionalIterator j = last; - --j; - while ( !comp(*j, *i)){ - --j; - } - iter_swap(i, j); - reverse(ii, last); - return true; - } - if (i == first){ - reverse(first, last); - return false; - } - } - - } - -} +extern "C++" +{ + +namespace std +{ + + // Subclause _lib.alg.nonmodifying_, non-modifying sequence operations: + + template _UCXXEXPORT + Function for_each(InputIterator first, InputIterator last, Function f) + { + while (first !=last) + { + f(*first); + ++first; + } + + return f; + } + + template _UCXXEXPORT + InputIterator find(InputIterator first, InputIterator last, const T& value) + { + while (first !=last && *first != value) + { + ++first; + } + + return first; + } + + template _UCXXEXPORT + InputIterator find_if (InputIterator first, InputIterator last, Predicate pred) + { + while (first !=last && !pred(*first)) + { + ++first; + } + + return first; + } + + template _UCXXEXPORT ForwardIterator1 + find_end(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2) + { + ForwardIterator1 retval = last1; + while (first1 != last1) + { + ForwardIterator1 temp1(first1); + ForwardIterator2 temp2(first2); + + while (temp2!=last2 && temp1!= last1) + { + if (*temp1 != *temp2) + { + break; //Exit while loop + } + + ++temp1; + ++temp2; + if (temp2 == last2) + { + //Have successfully checked the whole sequence + + retval = first1; + } + } + } + + return retval; + } + + template _UCXXEXPORT + ForwardIterator1 + find_end(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2, + BinaryPredicate pred) + { + ForwardIterator1 retval = last1; + while (first1 !=last1) + { + ForwardIterator1 temp1(first1); + ForwardIterator2 temp2(first2); + while (temp2!=last2 && temp1!= last1) + { + if (!pred(*temp1, *temp2)) + { + break; //Exit while loop + } + + ++temp1; + ++temp2; + if (temp2 == last2) + { + // Have successfully checked the whole sequence + + retval = first1; + } + } + } + + return retval; + } + + template _UCXXEXPORT + ForwardIterator1 + find_first_of(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2) + { + while (first1 != last1) + { + ForwardIterator2 temp2(first2); + while (temp2 != last2) + { + if (*temp2 == first1) + { + return first1; + } + + ++temp2; + } + } + + return last1; + } + + template _UCXXEXPORT + ForwardIterator1 + find_first_of(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2, + BinaryPredicate pred) + { + while (first1 != last1) + { + ForwardIterator2 temp2(first2); + while (temp2 != last2) + { + if (*temp2 == first1) + { + return first1; + } + + ++temp2; + } + } + + return last1; + } + + template _UCXXEXPORT ForwardIterator + adjacent_find(ForwardIterator first, ForwardIterator last) + { + ForwardIterator temp; + while (first != last) + { + temp = first; + ++temp; + if (*temp == *first) + { + return first; + } + + ++first; + } + + return first; + } + + template _UCXXEXPORT + ForwardIterator + adjacent_find(ForwardIterator first, ForwardIterator last, BinaryPredicate pred) + { + ForwardIterator temp; + while (first != last) + { + temp = first; + ++temp; + if (pred(*temp, *first)) + { + return first; + } + + ++first; + } + + return first; + } + + template _UCXXEXPORT + typename iterator_traits::difference_type + count(InputIterator first, InputIterator last, const T& value) + { + typename iterator_traits::difference_type i = 0; + while (first!=last) + { + if (*first == value) + { + ++i; + } + + ++first; + } + + return i; + } + + template _UCXXEXPORT + typename iterator_traits::difference_type + count_if (InputIterator first, InputIterator last, Predicate pred) + { + typename iterator_traits::difference_type i = 0; + while (first!=last) + { + if (pred(*first)) + { + ++i; + } + + ++first; + } + + return i; + } + + template _UCXXEXPORT + pair + mismatch(InputIterator1 first1, InputIterator1 last1, InputIterator2 first2) + { + while (first1 != last1) + { + if (*first1 != *first2) + { + break; + } + + ++first1; + ++first2; + } + + pair retval; + retval.first = first1; + retval.second = first2; + return retval; + } + + template _UCXXEXPORT + pair + mismatch(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, BinaryPredicate pred) + { + while (first1 != last1) + { + if (!pred(*first1, *first2)) + { + break; + } + + ++first1; + ++first2; + } + + pair retval; + retval.first = first1; + retval.second = first2; + return retval; + } + + template _UCXXEXPORT + bool + equal(InputIterator1 first1, InputIterator1 last1, InputIterator2 first2) + { + while (first1 !=last1) + { + if (*first1 != *first2) + { + return false; + } + + ++first1; + ++first2; + } + + return true; + } + + template _UCXXEXPORT + bool + equal(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, BinaryPredicate pred) + { + while (first1 !=last1) + { + if (!pred(*first1, *first2)) + { + return false; + } + + ++first1; + ++first2; + } + + return true; + } + + template _UCXXEXPORT + ForwardIterator1 search(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2) + { + equal_to::value_type> c; + return search(first1, last1, first2, last2, c); + } + + template _UCXXEXPORT + ForwardIterator1 + search(ForwardIterator1 first1, ForwardIterator1 last1, + ForwardIterator2 first2, ForwardIterator2 last2, + BinaryPredicate pred) + { + while (first1 != last1) + { + ForwardIterator1 temp1(first1); + ForwardIterator2 temp2(first2); + while (temp2 != last2 && temp1 != last1) + { + if (!pred(*temp2, *temp1)) + { + break; + } + + ++temp1; + ++temp2; + if (temp2 == last2) + { + return first1; + } + } + + ++first1; + } + + return last1; + } + + + template _UCXXEXPORT + ForwardIterator + search_n(ForwardIterator first, ForwardIterator last, Size count, const T& value) + { + while (first != last) + { + if (*first == value) + { + ForwardIterator temp(first); + Size i = 1; + ++first; // Avoid doing the same comparison over again + while (i < count && *temp == value) + { + ++first; + ++i; + } + + if (i == count) + { + return first; + } + } + + ++first; + } + + return first; + } + + + template _UCXXEXPORT + ForwardIterator + search_n(ForwardIterator first, ForwardIterator last, + Size count, const T& value, BinaryPredicate pred) + { + while (first != last) + { + if (pred(*first, value)) + { + ForwardIterator temp(first); + Size i = 1; + ++first; // Avoid doing the same comparison over again + while (i < count && pred(*temp, value)) + { + ++first; + ++i; + } + + if (i == count) + { + return first; + } + } + + ++first; + } + + return first; + } + + // Subclause _lib.alg.modifying.operations_, modifying sequence operations: + + template _UCXXEXPORT + OutputIterator + copy(InputIterator first, InputIterator last, OutputIterator result) + { + while (first != last) + { + *result = *first; + ++first; + ++result; + } + + return result; + } + + template _UCXXEXPORT + BidirectionalIterator2 + copy_backward(BidirectionalIterator1 first, BidirectionalIterator1 last, + BidirectionalIterator2 result) + { + while (first !=last) + { + --result; + --last; + *result = *last; + } + + return result; + } + + template _UCXXEXPORT void swap(T& a, T& b) + { + T temp(a); + a = b; + b = temp; + } + + template _UCXXEXPORT + ForwardIterator2 + swap_ranges(ForwardIterator1 first1, ForwardIterator1 last1, ForwardIterator2 first2) + { + while (first1 != last1) + { + iter_swap(first1, first2); + ++first1; + ++first2; + } + + return first2; + } + + template _UCXXEXPORT + void + iter_swap(ForwardIterator1 a, ForwardIterator2 b) + { + typename iterator_traits::value_type temp(*a); + *a = *b; + *b = temp; + } + + template _UCXXEXPORT + OutputIterator + transform(InputIterator first, InputIterator last, + OutputIterator result, UnaryOperation op) + { + while (first != last) + { + *result = op(*first); + ++first; + ++result; + } + + return result; + } + + template _UCXXEXPORT + OutputIterator transform(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, OutputIterator result, + BinaryOperation binary_op) + { + while (first1 != last1) + { + *result = binary_op(*first1, *first2); + ++first1; + ++first2; + ++result; + } + + return result; + } + + template _UCXXEXPORT + void + replace(ForwardIterator first, ForwardIterator last, + const T& old_value, const T& new_value) + { + while (first != last) + { + if (*first == old_value) + { + *first = new_value; + } + + ++first; + } + } + + template _UCXXEXPORT + void + replace_if (ForwardIterator first, ForwardIterator last, + Predicate pred, const T& new_value) + { + while (first != last) + { + if (pred(*first)) + { + *first = new_value; + } + + ++first; + } + } + + template _UCXXEXPORT + OutputIterator + replace_copy(InputIterator first, InputIterator last, + OutputIterator result, const T& old_value, const T& new_value) + { + while (first != last) + { + if (*first == old_value) + { + *result = new_value; + } + else + { + *result = *first; + } + + ++first; + ++result; + } + + return result; + } + + template _UCXXEXPORT + OutputIterator + replace_copy_if (Iterator first, Iterator last, + OutputIterator result, Predicate pred, const T& new_value) + { + while (first != last) + { + if (pred(*first)) + { + *result = new_value; + } + else + { + *result = *first; + } + + ++first; + ++result; + } + + return result; + } + + template _UCXXEXPORT + void + fill(ForwardIterator first, ForwardIterator last, const T& value) + { + while (first != last) + { + *first = value; + ++first; + } + } + + template _UCXXEXPORT + void + fill_n(OutputIterator first, Size n, const T& value) + { + while (n != 0) + { + *first = value; + --n; + ++first; + } + } + + template _UCXXEXPORT + void + generate(ForwardIterator first, ForwardIterator last, Generator gen) + { + while (first != last) + { + *first = gen(); + ++first; + } + } + + template _UCXXEXPORT + void + generate_n(OutputIterator first, Size n, Generator gen) + { + while (n !=0) + { + *first = gen(); + --n; + ++first; + } + } + + template _UCXXEXPORT + ForwardIterator + remove(ForwardIterator first, ForwardIterator last, const T& value) + { + ForwardIterator temp(first); + while (temp !=last) + { + if (*temp == value) + { + + } + else + { + *first = *temp; + ++first; + } + + ++temp; + } + + return first; + } + + template _UCXXEXPORT + ForwardIterator + remove_if (ForwardIterator first, ForwardIterator last, Predicate pred) + { + ForwardIterator temp(first); + while (temp !=last) + { + if (pred(*temp)) + { + } + else + { + *first = *temp; + ++first; + } + + ++temp; + } + + return first; + } + + template _UCXXEXPORT + OutputIterator + remove_copy(InputIterator first, InputIterator last, + OutputIterator result, const T& value) + { + while (first !=last) + { + if (*first != value) + { + *result = *first; + ++result; + } + + ++first; + } + + return result; + } + + template _UCXXEXPORT + OutputIterator + remove_copy_if (InputIterator first, InputIterator last, + OutputIterator result, Predicate pred) + { + while (first !=last) + { + if (!pred(*first)) + { + *result = *first; + ++result; + } + + ++first; + } + + return result; + } + + template _UCXXEXPORT + ForwardIterator + unique(ForwardIterator first, ForwardIterator last) + { + ForwardIterator new_val(first); + ForwardIterator old_val(first); + + while (new_val !=last) + { + if (*new_val == *old_val && new_val != old_val) + { + } + else + { + *first = *new_val; + old_val = new_val; + ++first; + } + + ++new_val; + } + + return first; + } + + template _UCXXEXPORT + ForwardIterator + unique(ForwardIterator first, ForwardIterator last, BinaryPredicate pred) + { + ForwardIterator new_val(first); + ForwardIterator old_val(first); + + while (new_val !=last) + { + if (pred(*new_val, *old_val) && new_val != old_val) + { + } + else + { + *first = *new_val; + old_val = new_val; + ++first; + } + + ++new_val; + } + + return first; + } + + template _UCXXEXPORT + OutputIterator + unique_copy(InputIterator first, InputIterator last, OutputIterator result) + { + InputIterator temp(first); + while (first !=last) + { + if (*first == *temp && first != temp) + { + } + else + { + *result = *first; + temp = first; + ++result; + } + + ++first; + } + + return result; + } + + template _UCXXEXPORT + OutputIterator + unique_copy(InputIterator first, InputIterator last, + OutputIterator result, BinaryPredicate pred) + { + InputIterator temp(first); + while (first !=last) + { + if (pred(*first, *temp) && first != temp) + { + } + else + { + *result = *first; + temp = first; + ++result; + } + + ++first; + } + + return result; + } + + template _UCXXEXPORT + void + reverse(BidirectionalIterator first, BidirectionalIterator last) + { + --last; //Don't work with one past the end element + while (first < last) + { + iter_swap(first, last); + ++first; + --last; + } + } + + template _UCXXEXPORT + OutputIterator + reverse_copy(BidirectionalIterator first, BidirectionalIterator last, + OutputIterator result) + { + while (last > first) + { + --last; + *result = *last; + ++result; + } + + return result; + } + + template _UCXXEXPORT + void + rotate(ForwardIterator first, ForwardIterator middle, ForwardIterator last) + { + if ((first == middle) || (last == middle)) + { + return; + } + + ForwardIterator first2 = middle; + + do + { + swap(*first, *first2); + first++; + first2++; + if (first == middle) + { + middle = first2; + } + } + while (first2 != last); + + first2 = middle; + + while (first2 != last) + { + swap(*first, *first2); + first++; + first2++; + if (first == middle) + { + middle = first2; + } + else if (first2 == last) + { + first2 = middle; + } + } + } + + template _UCXXEXPORT + OutputIterator + rotate_copy(ForwardIterator first, ForwardIterator middle, + ForwardIterator last, OutputIterator result) + { + ForwardIterator temp(middle); + while (temp !=last) + { + *result = *temp; + ++temp; + ++result; + } + + while (first != middle) + { + *result = *first; + ++first; + ++result; + } + + return result; + } + + template _UCXXEXPORT + void + random_shuffle(RandomAccessIterator first, RandomAccessIterator last) + { + --last; + while (first != last) + { + iter_swap(first, (first + (rand() % (last - first)))); + ++first; + } + } + + template _UCXXEXPORT + void + random_shuffle(RandomAccessIterator first, RandomAccessIterator last, + RandomNumberGenerator& rand) + { + --last; + while (first != last) + { + iter_swap(first, (first + (rand(last - first)))); + ++first; + } + } + + // _lib.alg.partitions_, partitions: + + template _UCXXEXPORT BidirectionalIterator + partition(BidirectionalIterator first, BidirectionalIterator last, Predicate pred) + { + return stable_partition(first, last, pred); + } + + template _UCXXEXPORT BidirectionalIterator + stable_partition(BidirectionalIterator first, BidirectionalIterator last, Predicate pred) + { + // First now points to the first non-desired element + + while (first != last && pred(*first)){ + ++first; + } + + BidirectionalIterator tempb; + BidirectionalIterator tempe = first; + + while (tempe != last) + { + //Find the next desired element + + while (!pred(*tempe)) + { + ++tempe; + + //See if we should exit + + if (tempe == last) + { + return first; + } + } + + // Rotate the element back to the begining + + tempb = tempe; + while (tempb != first) + { + iter_swap(tempb, tempb-1); + --tempb; + } + + // First now has a desired element + + ++first; + } + + return first; + } + + template _UCXXEXPORT + void sort(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + sort(first, last, c); + } + + template _UCXXEXPORT + void sort(RandomAccessIterator first, RandomAccessIterator last, Compare comp) + { + stable_sort(first, last, comp); + } + + template _UCXXEXPORT + void stable_sort(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + stable_sort(first, last, c); + } + + template _UCXXEXPORT + void stable_sort(RandomAccessIterator first, RandomAccessIterator last, Compare comp) + { + //FIXME - bubble sort + + RandomAccessIterator temp; + --last; + while (last - first > 0) + { + temp = last; + while (temp != first) + { + if (comp(*temp, *(temp-1))) + { + iter_swap(temp-1, temp); + } + + --temp; + } + + ++first; + } + } + + template _UCXXEXPORT + void partial_sort(RandomAccessIterator first, RandomAccessIterator middle, RandomAccessIterator last) + { + less::value_type> c; + partial_sort(first, middle, last, c); + } + + template _UCXXEXPORT + void partial_sort(RandomAccessIterator first, RandomAccessIterator middle, + RandomAccessIterator last, Compare comp) + { + //Fixme - partial bubble sort + + RandomAccessIterator temp; + --last; + while (first < middle) + { + temp = last; + while (temp != first) + { + if (comp(*temp, *(temp -1))) + { + iter_swap(temp-1, temp); + } + + --temp; + } + + ++first; + } + } + + template _UCXXEXPORT + RandomAccessIterator + partial_sort_copy(InputIterator first, InputIterator last, + RandomAccessIterator result_first, RandomAccessIterator result_last) + { + less::value_type> c; + return partial_sort_copy(first, last, result_first, result_last, c); + } + + template _UCXXEXPORT + RandomAccessIterator + partial_sort_copy(InputIterator first, InputIterator last, + RandomAccessIterator result_first, RandomAccessIterator result_last, Compare comp) + { + size_t output_size = last-first; + size_t temp_size = result_last - result_first; + if (temp_size < output_size) + { + output_size = temp_size; + } + + RandomAccessIterator middle = result_first + output_size; + RandomAccessIterator temp = result_first; + + while (temp != middle) + { + *temp = *first; + ++temp; + ++first; + } + + sort(result_first, middle, comp); + + while (first != last) + { + if (comp(*first, *(middle-1))) + { + *(middle-1) = *first; + sort(result_first, middle, comp); + } + + ++first; + } + + return middle; + } + + template _UCXXEXPORT + void nth_element(RandomAccessIterator first, RandomAccessIterator nth, RandomAccessIterator last) + { + less::value_type> c; + nth_element(first, nth, last, c); + } + + template _UCXXEXPORT + void nth_element(RandomAccessIterator first, RandomAccessIterator nth, + RandomAccessIterator last, Compare comp) + { + partial_sort(first, nth, last, comp); + } + + template _UCXXEXPORT + ForwardIterator lower_bound(ForwardIterator first, ForwardIterator last, + const T& value) + { + less::value_type> c; + return lower_bound(first, last, value, c); + } + + template _UCXXEXPORT + ForwardIterator lower_bound(ForwardIterator first, ForwardIterator last, + const T& value, Compare comp) + { + if (first == last) + { + return last; + } + + // If below or equal to the first element + + if (comp(*first, value) == false) + { + return first; + } + + ForwardIterator middle; + + // If greater than the top element + + middle = first; + advance(middle, distance(first, last) - 1); + if (comp(*middle, value)) + { + return last; + } + + // Now begin the actual search for the begining + + while (distance(first, last) > 1) + { + // Find middle + + middle = first; + advance(middle, (distance(first, last)/2)); + if (!comp(*middle, value)) + { + last = middle; + } + else + { + first = middle; + } + } + + if (!comp(*first, value)) + { + return first; + } + + return last; + } + + template _UCXXEXPORT + ForwardIterator upper_bound(ForwardIterator first, ForwardIterator last, + const T& value) + { + less::value_type> c; + return upper_bound(first, last, value, c); + } + + template _UCXXEXPORT + ForwardIterator upper_bound(ForwardIterator first, ForwardIterator last, + const T& value, Compare comp) + { + if (first == last) + { + return last; + } + + // If below the first element + + if (comp(value, *first) == true) + { + return first; + } + + ForwardIterator middle; + + // If greater than the top element + + middle = first; + advance(middle, distance(first, last) - 1); + if (comp(*middle, value)) + { + return last; + } + + // Now begin the actual search for the end + + while (distance(first, last) > 1) + { + // Find middle + + middle = first; + advance(middle, (distance(first, last)/2)); + if (comp(value, *middle)) + { + last = middle; + } + else + { + first = middle; + } + } + + if (comp(value, *first)) + { + return first; + } + + return last; + } + + template _UCXXEXPORT + pair + equal_range(ForwardIterator first, ForwardIterator last, const T& value) + { + less::value_type> c; + return equal_range(first, last, value, c); + } + + template _UCXXEXPORT + pair + equal_range(ForwardIterator first, ForwardIterator last, const T& value, Compare comp) + { + pair retval; + retval.first = lower_bound(first, last, value, comp); + + //Reuse retval.first in order to (possibly) save a few comparisons + + retval.second = upper_bound(retval.first, last, value, comp); + return retval; + + } + + template _UCXXEXPORT + bool binary_search(ForwardIterator first, ForwardIterator last, + const T& value) + { + less::value_type> c; + return binary_search(first, last, value, c); + } + + template _UCXXEXPORT + bool binary_search(ForwardIterator first, ForwardIterator last, + const T& value, Compare comp) + { + if (distance(first, last) == 0) + { + return false; + } + + ForwardIterator middle; + + while (distance(first, last) > 1) + { + //Set middle between first and last + + middle = first; + advance(middle, distance(first, last)/2); + + if (comp(*middle, value) == true) + { + first = middle; + } + else + { + last = middle; + } + } + + if (!comp(*first, value) && !comp(value, *first)) + { + return true; + } + + if (!comp(*last, value) && !comp(value, *last)) + { + return true; + } + + return false; + } + + // _lib.alg.merge_, merge: + + template _UCXXEXPORT + OutputIterator + merge(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result) + { + less::value_type> c; + return merge(first1, last1, first2, last2, result, c); + } + + template _UCXXEXPORT + OutputIterator + merge(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) + { + while (first1 != last1 && first2 != last2) + { + //If in this order so first1 elements which are equal come first + + if (comp(*first2, *first1)) + { + *result = *first2; + ++first2; + } + else + { + *result = *first1; + ++first1; + } + + ++result; + } + + //Clean up remaining elements + + while (first1 != last1) + { + *result = *first1; + ++first1; + ++result; + } + + while (first2 != last2) + { + *result = *first2; + ++first2; + ++result; + } + + return result; + } + + template _UCXXEXPORT + void inplace_merge(BidirectionalIterator first, + BidirectionalIterator middle, BidirectionalIterator last) + { + less::value_type> c; + inplace_merge(first, middle, last, c); + } + + template _UCXXEXPORT + void inplace_merge(BidirectionalIterator first, + BidirectionalIterator middle, BidirectionalIterator last, Compare comp) + { + //FIXME - using a bubble exchange method + + while (first != middle && middle !=last) + { + if (comp(*middle, *first)) + { + BidirectionalIterator temp(middle); + while (temp != first) + { + iter_swap(temp, temp-1); + --temp; + } + + ++middle; + } + + ++first; + } + } + + // _lib.alg.set.operations_, set operations: + + template _UCXXEXPORT + bool includes(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2) + { + less::value_type> c; + return includes(first1, last1, first2, last2, c); + } + + template _UCXXEXPORT + bool includes(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, Compare comp) + { + while (first2 != last2) + { + //Advance the large set until no longer smaller than the element we are looking for + + while (comp(*first1, *first2)) + { + ++first1; + + // If we are at the end of the list, we don't have the desired element + + if (first1 == last1) + { + return false; + } + } + + // If we are past the element we want, it isn't here + + if (comp(*first2, *first1)) + { + return false; + } + + ++first2; //Move to next element + } + + return true; + } + + template _UCXXEXPORT + OutputIterator set_union(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result) + { + less::value_type> c; + return set_union(first1, last1, first2, last2, result, c); + } + + template _UCXXEXPORT + OutputIterator set_union(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) + { + while (first1 != last1 && first2 != last2) + { + if (comp(*first2, *first1)) + { + *result = *first2; + + // Eliminate duplicates + + InputIterator2 temp = first2; + while (first1 != last1 && !comp(*temp, *first1)) + { + ++first1; + } + + while (first2 != last2 && !comp(*temp, *first2)) + { + ++first2; + } + } + else + { + *result = *first1; + + // Eliminate duplicates + + InputIterator1 temp = first1; + while (first1 != last1 && !comp(*temp, *first1)) + { + ++first1; + } + + while (first2 != last2 && !comp(*temp, *first2)) + { + ++first2; + } + } + ++result; + } + + // Clean up remaining elements + + while (first1 != last1) + { + *result = *first1; + ++result; + InputIterator1 temp = first1; + while (first1 != last1 && !comp(*temp, *first1)) + { + ++first1; + } + } + + while (first2 != last2) + { + *result = *first2; + ++result; + InputIterator2 temp = first2; + while (first2 != last2 && !comp(*temp, *first2)) + { + ++first2; + } + } + + return result; + } + + template _UCXXEXPORT + OutputIterator set_intersection(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result) + { + less::value_type> c; + return set_intersection(first1, last1, first2, last2, result, c); + } + + template _UCXXEXPORT + OutputIterator set_intersection(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) + { + while (first1 != last1 && first2 != last2) + { + if (comp(*first2, *first1)) + { + ++first2; + } + else if (comp(*first1, *first2)) + { + ++first1; + } + else + { + *result = *first1; + ++result; + InputIterator1 temp = first1; + while (first1 != last1 && !comp(*temp, *first1)) + { + ++first1; + } + + ++first2; + } + } + + return result; + } + + template _UCXXEXPORT + OutputIterator set_difference(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result) + { + less::value_type> c; + return set_difference(first1, last1, first2, last2, result, c); + } + + template _UCXXEXPORT + OutputIterator set_difference(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) + { + while (first1 != last1 && first2 != last2) + { + if (comp(*first1, *first2)) + { + *result = *first1; + ++result; + + // Eliminate duplicates + + InputIterator1 temp = first1; + while (first1 != last1 && !comp(*temp, *first1)) + { + ++first1; + } + } + else if (comp(*first2, *first1)) + { + // Eliminate duplicates + + InputIterator2 temp = first2; + while (first2 != last2 && !comp(*temp, *first2)) + { + ++first2; + } + + } + else + { + //They are identical - skip + // Eliminate duplicates + + InputIterator1 temp = first1; + while (first1 != last1 && !comp(*temp, *first1)) + { + ++first1; + } + + while (first2 != last2 && !comp(*temp, *first2)) + { + ++first2; + } + } + } + + // Clean up remaining elements + + while (first1 != last1) + { + *result = *first1; + ++result; + InputIterator1 temp = first1; + while (first1 != last1 && !comp(*temp, *first1)) + { + ++first1; + } + } + + return result; + } + + template _UCXXEXPORT + OutputIterator set_symmetric_difference(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result) + { + less::value_type> c; + return set_symmetric_difference(first1, last1, first2, last2, result, c); + } + + template _UCXXEXPORT + OutputIterator set_symmetric_difference(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, OutputIterator result, Compare comp) + { + while (first1 != last1 && first2 != last2) + { + if (comp(*first1, *first2)) + { + *result = *first1; + ++result; + + // Eliminate duplicates + + InputIterator1 temp = first1; + while (first1 != last1 && !comp(*temp, *first1)) + { + ++first1; + } + } + else if (comp(*first2, *first1)) + { + *result = *first2; + ++result; + + // Eliminate duplicates + + InputIterator2 temp = first2; + while (first2 != last2 && !comp(*temp, *first2)) + { + ++first2; + } + + } + else + { + //They are identical - skip + // Eliminate duplicates + + InputIterator1 temp = first1; + while (first1 != last1 && !comp(*temp, *first1)) + { + ++first1; + } + + while (first2 != last2 && !comp(*temp, *first2)) + { + ++first2; + } + } + } + + // Clean up remaining elements + + while (first1 != last1) + { + *result = *first1; + ++result; + InputIterator1 temp = first1; + while (first1 != last1 && !comp(*temp, *first1)) + { + ++first1; + } + } + + while (first2 != last2) + { + *result = *first2; + ++result; + InputIterator2 temp = first2; + while (first2 != last2 && !comp(*temp, *first2)) + { + ++first2; + } + } + + return result; + } + + // _lib.alg.heap.operations_, heap operations: + + template _UCXXEXPORT + void push_heap(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + push_heap(first, last, c); + } + + template _UCXXEXPORT + void push_heap(RandomAccessIterator first, RandomAccessIterator last, Compare comp) + { + // *(last - 1) is the last element + + RandomAccessIterator begin, middle, end; + begin = first; + end = last - 2; + + if (last - first < 2) + { + //Empty heap + + return; + } + + if (comp(*(last-1), *end)) + { + //Belongs past the end - already in place + + return; + } + + while (end - begin > 1) + { + middle = begin + ((end - begin)/2); + if (comp(*middle, *(last-1))) + { + end = middle; + } + else + { + begin = middle; + } + } + + if (comp(*begin, *(last-1))) + { + middle = begin; + } + else + { + middle = end; + } + + // Now all we do is swap the elements up to the begining + + --last; + + while (last > middle) + { + iter_swap(last, last-1); + --last; + } + } + + template _UCXXEXPORT + void pop_heap(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + pop_heap(first, last, c); + } + + template _UCXXEXPORT + void pop_heap(RandomAccessIterator first, RandomAccessIterator last, Compare) + { + --last; + while (first < last) + { + iter_swap(first, first+1); + ++first; + } + } + + template _UCXXEXPORT + void make_heap(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + make_heap(first, last, c); + } + + template _UCXXEXPORT + void make_heap(RandomAccessIterator first, RandomAccessIterator last, Compare comp) + { + sort(reverse_iterator(last), reverse_iterator(first), comp); + } + + template _UCXXEXPORT + void sort_heap(RandomAccessIterator first, RandomAccessIterator last) + { + less::value_type> c; + sort_heap(first, last, c); + } + + template _UCXXEXPORT + void sort_heap(RandomAccessIterator first, RandomAccessIterator last, Compare comp) + { + sort(first, last, comp); + } + + // _lib.alg.min.max_, minimum and maximum: + + template _UCXXEXPORT + const T& min(const T& a, const T& b) + { + if (b < a) + { + return b; + } + + return a; + } + + template _UCXXEXPORT + const T& min(const T& a, const T& b, Compare comp) + { + if (comp(b, a) == true) + { + return b; + } + + return a; + } + + template _UCXXEXPORT + const T& max(const T& a, const T& b) + { + if (a < b) + { + return b; + } + + return a; + } + + template _UCXXEXPORT + const T& max(const T& a, const T& b, Compare comp) + { + if (comp(a, b)) + { + return b; + } + + return a; + } + + template _UCXXEXPORT + ForwardIterator min_element(ForwardIterator first, ForwardIterator last) + { + less::value_type> c; + return min_element(first, last, c); + } + + template _UCXXEXPORT + ForwardIterator min_element(ForwardIterator first, ForwardIterator last, Compare comp) + { + ForwardIterator retval = first; + ++first; + while (first != last) + { + if (comp(*first, *retval)) + { + retval = first; + } + + ++first; + } + + return retval; + } + + template _UCXXEXPORT + ForwardIterator max_element(ForwardIterator first, ForwardIterator last) + { + less::value_type> c; + return max_element(first, last, c); + } + + template _UCXXEXPORT + ForwardIterator max_element(ForwardIterator first, ForwardIterator last, Compare comp) + { + ForwardIterator retval = first; + ++first; + while (first != last) + { + if (comp(*retval, *first)) + { + retval = first; + } + + ++first; + } + + return retval; + } + + template _UCXXEXPORT + bool lexicographical_compare(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2) + { + less::value_type> c; + return lexicographical_compare(first1, last1, first2, last2, c); + } + + template _UCXXEXPORT + bool lexicographical_compare(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, InputIterator2 last2, Compare comp) + { + while (first1 != last1 && first2 != last2) + { + if (comp(*first1, *first2)) + { + return true; + } + + if (comp(*first2, *first1)) + { + return false; + } + + ++first1; + ++first2; + } + + return first1 == last1 && first2 != last2; + } + + // _lib.alg.permutation.generators_, permutations + + template _UCXXEXPORT + bool next_permutation(BidirectionalIterator first, BidirectionalIterator last) + { + less::value_type> c; + return next_permutation(first, last, c); + } + + template _UCXXEXPORT + bool next_permutation(BidirectionalIterator first, BidirectionalIterator last, Compare comp) + { + if (first == last) + { + return false; // No data + } + + BidirectionalIterator i = last; + --i; + if (i == first) + { + return false; //Only one element + } + + BidirectionalIterator ii = i; + --ii; + + // If the last two items are in order, swap them and call it done + + if (comp(*ii, *i)) + { + iter_swap(ii, i); + return true; + } + + // This part of the algorithm copied from G++ header files ver. 3.4.2 + + i = last; + --i; + for (;;) + { + ii = i; + --i; + if (comp(*i, *ii)) + { + BidirectionalIterator j = last; + --j; + while (!comp(*i, *j)) + { + --j; + } + + iter_swap(i, j); + reverse(ii, last); + return true; + } + + if (i == first) + { + reverse(first, last); + return false; + } + } + } + + template _UCXXEXPORT + bool prev_permutation(BidirectionalIterator first, BidirectionalIterator last) + { + less::value_type> c; + return prev_permutation(first, last, c); + } + + template _UCXXEXPORT + bool prev_permutation(BidirectionalIterator first, BidirectionalIterator last, Compare comp) + { + if (first == last) + { + return false; // No data + } + + BidirectionalIterator i = last; + --i; + if (i == first) + { + return false; //Only one element + } + + BidirectionalIterator ii = i; + --ii; + + // If the last two items are in reverse order, swap them and call it done + + if (comp(*i, *ii)) + { + iter_swap(ii, i); + return true; + } + + // Copied from GNU GCC header files version 3.4.2 + + i = last; + --i; + + for (;;) + { + ii = i; + --i; + if (comp(*ii, *i)) + { + BidirectionalIterator j = last; + --j; + while (!comp(*j, *i)) + { + --j; + } + + iter_swap(i, j); + reverse(ii, last); + return true; + } + + if (i == first) + { + reverse(first, last); + return false; + } + } + } + +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/associative_base b/misc/uClibc++/include/uClibc++/associative_base index 27ae0ef9f8..67122691b3 100644 --- a/misc/uClibc++/include/uClibc++/associative_base +++ b/misc/uClibc++/include/uClibc++/associative_base @@ -1,47 +1,46 @@ -/* Copyright (C) 2007 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - - - -#include -#include -#include -#include -#include +/* Copyright (C) 2007 Garrett A. Kajmowicz + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include +#include +#include +#include +#include #ifndef __STD_HEADER_ASSOCIATIVE_BASE #define __STD_HEADER_ASSOCIATIVE_BASE #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ -/* - * The basic premise here is that most of the code used by map, multimap, set and - * multiset is really common. There are a number of interface additions, and - * considerations about how to address multiple entries with the same key. - * The goal is that the tree/storage code should be here, and managing - * single or multiple counts will be left to subclasses. - * Yes, inheritence for the purpose of code sharing is usually a bad idea. - * However, since our goal is to reduce the total amount of code written - * and the overall binary size, this seems to be the best approach possible. +/* The basic premise here is that most of the code used by map, multimap, set and + * multiset is really common. There are a number of interface additions, and + * considerations about how to address multiple entries with the same key. + * The goal is that the tree/storage code should be here, and managing + * single or multiple counts will be left to subclasses. + * Yes, inheritence for the purpose of code sharing is usually a bad idea. + * However, since our goal is to reduce the total amount of code written + * and the overall binary size, this seems to be the best approach possible. */ template, class Allocator = allocator > class __base_associative; @@ -56,585 +55,712 @@ template class _UCXX protected: public: - typedef Key key_type; - typedef ValueType value_type; - typedef Compare key_compare; - typedef Allocator allocator_type; - typedef typename Allocator::reference reference; - typedef typename Allocator::const_reference const_reference; - typedef typename Allocator::size_type size_type; - typedef typename Allocator::difference_type difference_type; - typedef typename Allocator::pointer pointer; - typedef typename Allocator::const_pointer const_pointer; - typedef __base_associative associative_type; + typedef Key key_type; + typedef ValueType value_type; + typedef Compare key_compare; + typedef Allocator allocator_type; + typedef typename Allocator::reference reference; + typedef typename Allocator::const_reference const_reference; + typedef typename Allocator::size_type size_type; + typedef typename Allocator::difference_type difference_type; + typedef typename Allocator::pointer pointer; + typedef typename Allocator::const_pointer const_pointer; + typedef __base_associative associative_type; - typedef _associative_iter iterator; - typedef _associative_citer const_iterator; - typedef typename std::reverse_iterator reverse_iterator; - typedef typename std::reverse_iterator const_reverse_iterator; + typedef _associative_iter iterator; + typedef _associative_citer const_iterator; + typedef typename std::reverse_iterator reverse_iterator; + typedef typename std::reverse_iterator const_reverse_iterator; + explicit __base_associative(const Compare& comp, const Allocator& A, const key_type (*v_to_k)(const value_type)) + : c(comp), value_to_key(v_to_k) { } - explicit __base_associative(const Compare& comp, const Allocator& A, const key_type (*v_to_k)(const value_type)) - : c(comp), value_to_key(v_to_k) { } protected: - __base_associative(const associative_type& x) - : c(x.c), backing(x.backing), value_to_key(x.value_to_key) { } + __base_associative(const associative_type& x) + : c(x.c), backing(x.backing), value_to_key(x.value_to_key) { } public: - ~__base_associative(){ - } + ~__base_associative() + { + } - bool empty() const{ - return backing.empty(); - } - size_type size() const{ - return backing.size(); - } - size_type max_size() const{ - return backing.max_size(); - } + bool empty() const + { + return backing.empty(); + } - iterator begin(){ - return iterator(backing.begin()); - } + size_type size() const + { + return backing.size(); + } - const_iterator begin() const{ - return const_iterator(backing.begin()); - } + size_type max_size() const + { + return backing.max_size(); + } - iterator end() { - return iterator(backing.end()); - } + iterator begin() + { + return iterator(backing.begin()); + } - const_iterator end() const{ - return const_iterator(backing.end()); - } + const_iterator begin() const + { + return const_iterator(backing.begin()); + } - reverse_iterator rbegin(){ - return reverse_iterator(end()); - } + iterator end() + { + return iterator(backing.end()); + } - const_reverse_iterator rbegin() const{ - return const_reverse_iterator(end()); - } + const_iterator end() const + { + return const_iterator(backing.end()); + } - reverse_iterator rend(){ - return reverse_iterator(begin()); - } + reverse_iterator rbegin() + { + return reverse_iterator(end()); + } - const_reverse_iterator rend() const{ - return const_reverse_iterator(begin()); - } + const_reverse_iterator rbegin() const + { + return const_reverse_iterator(end()); + } + reverse_iterator rend() + { + return reverse_iterator(begin()); + } - iterator lower_bound(const key_type &x); - const_iterator lower_bound(const key_type &x) const; - iterator upper_bound(const key_type &x); - const_iterator upper_bound(const key_type &x) const; + const_reverse_iterator rend() const + { + return const_reverse_iterator(begin()); + } - pair equal_range(const key_type& x){ - pair retval; - retval.first = lower_bound(x); - retval.second = retval.first; - while(retval.second != end() && !c(x, value_to_key(*retval.second))){ - ++retval.second; - } - return retval; - } - pair equal_range(const key_type& x) const{ - pair retval; - retval.first = lower_bound(x); - retval.second = retval.first; - while(retval.second != end() && !c(x, value_to_key(*retval.second))){ - ++retval.second; - } - return retval; - } + iterator lower_bound(const key_type &x); + const_iterator lower_bound(const key_type &x) const; + iterator upper_bound(const key_type &x); + const_iterator upper_bound(const key_type &x) const; - iterator find(const key_type& x){ - iterator retval = lower_bound(x); - if(retval == end()){ - return retval; - } - if(c(x, value_to_key(*retval))){ - return end(); - } - return retval; - } - const_iterator find(const key_type& x) const{ - const_iterator retval = lower_bound(x); - if(retval == end()){ - return retval; - } - if(c(x, value_to_key(*retval))){ - return end(); - } - return retval; - } - size_type count(const key_type& x) const{ - size_type retval(0); - const_iterator first = lower_bound(x); - while(first != end() && !c(x, value_to_key(*first))){ - ++retval; - ++first; - } - return retval; - } + pair equal_range(const key_type& x) + { + pair retval; + retval.first = lower_bound(x); + retval.second = retval.first; + while (retval.second != end() && !c(x, value_to_key(*retval.second))) + { + ++retval.second; + } - void clear(){ - backing.clear(); - } + return retval; + } - void erase(iterator pos){ - backing.erase(pos.base_iterator()); - } - size_type erase(const key_type& x){ - size_type count(0); - iterator start = lower_bound(x); - iterator end = upper_bound(x); - while(start != end){ - start = backing.erase(start.base_iterator()); - ++count; - } - return count; - } - void erase(iterator first, iterator last){ - while(first != last){ - backing.erase(first.base_iterator()); - ++first; - } - } + pair equal_range(const key_type& x) const + { + pair retval; + retval.first = lower_bound(x); + retval.second = retval.first; + while (retval.second != end() && !c(x, value_to_key(*retval.second))) + { + ++retval.second; + } - key_compare key_comp() const{ - return c; - } + return retval; + } - __base_associative &operator=(const __base_associative & x){ - c = x.c; - backing = x.backing; - value_to_key = x.value_to_key; - return *this; - } - bool operator==(const __base_associative & x){ - return x.backing == backing; - } - bool operator!=(const __base_associative & x){ - return !(x.backing == backing); - } + iterator find(const key_type& x) + { + iterator retval = lower_bound(x); + if (retval == end()) + { + return retval; + } + + if (c(x, value_to_key(*retval))) + { + return end(); + } + + return retval; + } + + const_iterator find(const key_type& x) const + { + const_iterator retval = lower_bound(x); + if (retval == end()) + { + return retval; + } + + if (c(x, value_to_key(*retval))) + { + return end(); + } + + return retval; + } + + size_type count(const key_type& x) const + { + size_type retval(0); + const_iterator first = lower_bound(x); + while (first != end() && !c(x, value_to_key(*first))) + { + ++retval; + ++first; + } + + return retval; + } + + void clear() + { + backing.clear(); + } + + void erase(iterator pos) + { + backing.erase(pos.base_iterator()); + } + + size_type erase(const key_type& x) + { + size_type count(0); + iterator start = lower_bound(x); + iterator end = upper_bound(x); + while (start != end) + { + start = backing.erase(start.base_iterator()); + ++count; + } + + return count; + } + + void erase(iterator first, iterator last) + { + while (first != last) + { + backing.erase(first.base_iterator()); + ++first; + } + } + + key_compare key_comp() const + { + return c; + } + + __base_associative &operator=(const __base_associative & x) + { + c = x.c; + backing = x.backing; + value_to_key = x.value_to_key; + return *this; + } + + bool operator==(const __base_associative & x) + { + return x.backing == backing; + } + + bool operator!=(const __base_associative & x) + { + return !(x.backing == backing); + } protected: - void swap(__base_associative & x); + void swap(__base_associative & x); - Compare c; - std::list backing; - - const key_type (*value_to_key)(const value_type); + Compare c; + std::list backing; + const key_type (*value_to_key)(const value_type); }; - -/* - * Tree iterators for the base associative class - */ +/* Tree iterators for the base associative class */ template class _associative_citer - : public std::iterator< - bidirectional_iterator_tag, - ValueType, - typename Allocator::difference_type, - ValueType*, - ValueType& - > + : public std::iterator< + bidirectional_iterator_tag, + ValueType, + typename Allocator::difference_type, + ValueType*, + ValueType& + > { protected: - typedef std::list listtype; + typedef std::list listtype; + + typename listtype::const_iterator base_iter; + friend class _associative_iter; - typename listtype::const_iterator base_iter; - friend class _associative_iter; public: - _associative_citer() { } - _associative_citer(const _associative_citer & m) - : base_iter(m.base_iter) { } - _associative_citer(const typename listtype::const_iterator & m) - : base_iter(m) { } - ~_associative_citer() { } - ValueType operator*() const{ - return *base_iter; - } - const ValueType * operator->() const{ - return &(*base_iter); - } - _associative_citer & operator=(const _associative_citer & m){ - base_iter = m.base_iter; - return *this; - } - bool operator==(const _associative_citer & m) const{ - return m.base_iter == base_iter; - } - bool operator!=(const _associative_citer & m) const{ - return m.base_iter != base_iter; - } - _associative_citer & operator++(){ - ++base_iter; - return *this; - } - _associative_citer operator++(int){ - //The following approach ensures that we only need to - //provide code for ++ in one place (above) - _associative_citer temp(base_iter); - ++base_iter; - return temp; - } - _associative_citer & operator--(){ - --base_iter; - return *this; - } - _associative_citer operator--(int){ - //The following approach ensures that we only need to - //provide code for -- in one place (above) - _associative_citer temp(base_iter); - --base_iter; - return temp; - } + _associative_citer() { } + _associative_citer(const _associative_citer & m) + : base_iter(m.base_iter) { } + _associative_citer(const typename listtype::const_iterator & m) + : base_iter(m) { } + ~_associative_citer() { } - //This is an implementation-defined function designed to make internals work correctly - typename listtype::const_iterator base_iterator(){ - return base_iter; - } + ValueType operator*() const + { + return *base_iter; + } + + const ValueType * operator->() const + { + return &(*base_iter); + } + + _associative_citer & operator=(const _associative_citer & m) + { + base_iter = m.base_iter; + return *this; + } + + bool operator==(const _associative_citer & m) const + { + return m.base_iter == base_iter; + } + + bool operator!=(const _associative_citer & m) const{ + return m.base_iter != base_iter; + } + + _associative_citer & operator++() + { + ++base_iter; + return *this; + } + + _associative_citer operator++(int) + { + // The following approach ensures that we only need to + // provide code for ++ in one place (above) + + _associative_citer temp(base_iter); + ++base_iter; + return temp; + } + + _associative_citer & operator--() + { + --base_iter; + return *this; + } + + _associative_citer operator--(int) + { + // The following approach ensures that we only need to + // provide code for -- in one place (above) + + _associative_citer temp(base_iter); + --base_iter; + return temp; + } + + // This is an implementation-defined function designed to make internals work correctly + + typename listtype::const_iterator base_iterator() + { + return base_iter; + } }; - template class _associative_iter - : public std::iterator< - bidirectional_iterator_tag, - ValueType, - typename Allocator::difference_type, - ValueType*, - ValueType& - > + : public std::iterator< + bidirectional_iterator_tag, + ValueType, + typename Allocator::difference_type, + ValueType*, + ValueType& + > { protected: - typedef std::list listtype; + typedef std::list listtype; - typename listtype::iterator base_iter; - typedef _associative_citer __associative_citer; + typename listtype::iterator base_iter; + typedef _associative_citer __associative_citer; public: - _associative_iter() { } - _associative_iter(const _associative_iter & m) - : base_iter(m.base_iter) { } - _associative_iter(const typename listtype::iterator & m) - : base_iter(m) { } - ~_associative_iter() { } - const ValueType & operator*() const{ - return *base_iter; - } - ValueType & operator*(){ - return *base_iter; - } - ValueType * operator->(){ - return &(*base_iter); - } - const ValueType * operator->() const{ - return &(*base_iter); - } - _associative_iter & operator=(const _associative_iter & m){ - base_iter = m.base_iter; - return *this; - } - bool operator==(const _associative_iter & m) const{ - return m.base_iter == base_iter; - } - bool operator==(const __associative_citer & m) const{ - return m.base_iter == base_iter; - } - bool operator!=(const _associative_iter & m) const{ - return m.base_iter != base_iter; - } - bool operator!=(const __associative_citer & m) const{ - return m.base_iter != base_iter; - } - _associative_iter & operator++(){ - ++base_iter; - return *this; - } - _associative_iter operator++(int){ - //The following approach ensures that we only need to - //provide code for ++ in one place (above) - _associative_iter temp(base_iter); - ++base_iter; - return temp; - } - _associative_iter & operator--(){ - --base_iter; - return *this; - } - _associative_iter operator--(int){ - //The following approach ensures that we only need to - //provide code for -- in one place (above) - _associative_iter temp(base_iter); - --base_iter; - return temp; - } - operator __associative_citer() const{ - return __associative_citer(base_iter); - } - typename listtype::iterator base_iterator(){ - return base_iter; - } - const typename listtype::iterator base_iterator() const{ - return base_iter; - } + _associative_iter() { } + _associative_iter(const _associative_iter & m) + : base_iter(m.base_iter) { } + _associative_iter(const typename listtype::iterator & m) + : base_iter(m) { } + ~_associative_iter() { } + const ValueType & operator*() const + { + return *base_iter; + } + + ValueType & operator*() + { + return *base_iter; + } + + ValueType * operator->() + { + return &(*base_iter); + } + + const ValueType * operator->() const + { + return &(*base_iter); + } + + _associative_iter & operator=(const _associative_iter & m) + { + base_iter = m.base_iter; + return *this; + } + + bool operator==(const _associative_iter & m) const + { + return m.base_iter == base_iter; + } + + bool operator==(const __associative_citer & m) const + { + return m.base_iter == base_iter; + } + + bool operator!=(const _associative_iter & m) const + { + return m.base_iter != base_iter; + } + + bool operator!=(const __associative_citer & m) const + { + return m.base_iter != base_iter; + } + + _associative_iter & operator++() + { + ++base_iter; + return *this; + } + + _associative_iter operator++(int) + { + // The following approach ensures that we only need to + // provide code for ++ in one place (above) + + _associative_iter temp(base_iter); + ++base_iter; + return temp; + } + + _associative_iter & operator--() + { + --base_iter; + return *this; + } + + _associative_iter operator--(int) + { + // The following approach ensures that we only need to + // provide code for -- in one place (above) + + _associative_iter temp(base_iter); + --base_iter; + return temp; + } + + operator __associative_citer() const + { + return __associative_citer(base_iter); + } + + typename listtype::iterator base_iterator() + { + return base_iter; + } + + const typename listtype::iterator base_iterator() const + { + return base_iter; + } }; - - // The lower_bound code is really crappy linear search. However, it is a dead - // simple implementation (easy to audit). It can also be easily replaced. + // The lower_bound code is really crappy linear search. However, it is a dead + // simple implementation (easy to audit). It can also be easily replaced. - template - typename __base_associative::iterator - __base_associative::lower_bound(const key_type &x) - { - iterator retval = begin(); - while(retval != end() && c(value_to_key(*retval), x)){ - ++retval; - } - return retval; - } + template + typename __base_associative::iterator + __base_associative::lower_bound(const key_type &x) + { + iterator retval = begin(); + while (retval != end() && c(value_to_key(*retval), x)) + { + ++retval; + } - template - typename __base_associative::const_iterator - __base_associative::lower_bound(const key_type &x) const - { - const_iterator retval = begin(); - while(retval != end() && c(value_to_key(*retval), x)){ - ++retval; - } - return retval; - } + return retval; + } - // Upper bound search is linear from the point of lower_bound. This is likely the best solution - // in all but the most pathological of cases. + template + typename __base_associative::const_iterator + __base_associative::lower_bound(const key_type &x) const + { + const_iterator retval = begin(); + while (retval != end() && c(value_to_key(*retval), x)) + { + ++retval; + } - template - typename __base_associative::iterator - __base_associative::upper_bound(const key_type &x) - { - iterator retval = lower_bound(x); - while(retval != end() && !c(x, value_to_key(*retval))){ - ++retval; - } - return retval; - } + return retval; + } - template - typename __base_associative::const_iterator - __base_associative::upper_bound(const key_type &x) const - { - const_iterator retval = begin(); - while(retval != end() && !c(x, value_to_key(*retval))){ - ++retval; - } - return retval; - } + // Upper bound search is linear from the point of lower_bound. This is likely the best solution + // in all but the most pathological of cases. + template + typename __base_associative::iterator + __base_associative::upper_bound(const key_type &x) + { + iterator retval = lower_bound(x); + while (retval != end() && !c(x, value_to_key(*retval))) + { + ++retval; + } - template - void __base_associative::swap(__base_associative& m) - { - Compare n = c; - c = m.c; - m.c = n; + return retval; + } - m.backing.swap(backing); - } + template + typename __base_associative::const_iterator + __base_associative::upper_bound(const key_type &x) const + { + const_iterator retval = begin(); + while (retval != end() && !c(x, value_to_key(*retval))) + { + ++retval; + } + return retval; + } + + template + void __base_associative::swap(__base_associative& m) + { + Compare n = c; + c = m.c; + m.c = n; + + m.backing.swap(backing); + } template class _UCXXEXPORT __single_associative : - public __base_associative + public __base_associative { protected: - typedef __base_associative base; - using base::backing; + typedef __base_associative base; + using base::backing; - using base::c; + using base::c; public: - typedef typename base::key_type key_type; - typedef typename base::value_type value_type; - typedef typename base::key_compare key_compare; - typedef typename base::allocator_type allocator_type; - typedef typename base::reference reference; - typedef typename base::const_reference const_reference; - typedef typename base::iterator iterator; - typedef typename base::const_iterator const_iterator; - typedef typename base::size_type size_type; - typedef typename base::difference_type difference_type; - typedef typename base::pointer pointer; - typedef typename base::const_pointer const_pointer; - typedef typename base::reverse_iterator reverse_iterator; - typedef typename base::const_reverse_iterator const_reverse_iterator; + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; - using base::begin; - using base::end; - using base::rbegin; - using base::rend; + using base::begin; + using base::end; + using base::rbegin; + using base::rend; - using base::empty; - using base::size; - using base::max_size; + using base::empty; + using base::size; + using base::max_size; - using base::find; - using base::count; - using base::lower_bound; - using base::upper_bound; - using base::equal_range; + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; - using base::operator=; - using base::operator==; - using base::operator!=; + using base::operator=; + using base::operator==; + using base::operator!=; - explicit __single_associative(const Compare& comp, const Allocator& A, const key_type (*v_to_k)(const value_type)) - : base(comp, A, v_to_k) { } + explicit __single_associative(const Compare& comp, const Allocator& A, const key_type (*v_to_k)(const value_type)) + : base(comp, A, v_to_k) { } - template __single_associative( - InputIterator first, - InputIterator last, - const Compare& comp, - const Allocator& A, - const key_type (*v_to_k)(const value_type) - ) : base(comp, A, v_to_k) { - insert(first, last); - } + template __single_associative( + InputIterator first, + InputIterator last, + const Compare& comp, + const Allocator& A, + const key_type (*v_to_k)(const value_type) + ) : base(comp, A, v_to_k) + { + insert(first, last); + } - pair insert(const value_type& x){ - pair retval; - iterator location = lower_bound(this->value_to_key(x)); - retval.second = true; - //Empty list or need to insert at end - if(end() == location){ - backing.push_back(x); - retval.first = --(end()); - return retval; - } - //Something in the list - if(c(this->value_to_key(x), this->value_to_key(*location))){ - location = backing.insert(location.base_iterator(), x); - retval.first = location; - }else{ - retval.second = false; - retval.first = location; - } - return retval; - } + pair insert(const value_type& x) + { + pair retval; + iterator location = lower_bound(this->value_to_key(x)); + retval.second = true; - iterator insert(iterator position, const value_type& x){ - // FIXME - this is cheating and probably should be more efficient since we are - // now log(n) to find for inserts - return insert(x).first; - } + // Empty list or need to insert at end - template void insert(InputIterator first, InputIterator last){ - while(first != last){ - insert(*first); - ++first; - } - } + if (end() == location) + { + backing.push_back(x); + retval.first = --(end()); + return retval; + } + // Something in the list + + if (c(this->value_to_key(x), this->value_to_key(*location))) + { + location = backing.insert(location.base_iterator(), x); + retval.first = location; + } + else + { + retval.second = false; + retval.first = location; + } + + return retval; + } + + iterator insert(iterator position, const value_type& x) + { + // FIXME - this is cheating and probably should be more efficient since we are + // now log(n) to find for inserts + + return insert(x).first; + } + + template void insert(InputIterator first, InputIterator last) + { + while (first != last) + { + insert(*first); + ++first; + } + } }; template class _UCXXEXPORT __multi_associative : - public __base_associative + public __base_associative { protected: - typedef __base_associative base; - using base::backing; + typedef __base_associative base; + using base::backing; - using base::c; + using base::c; public: - typedef typename base::key_type key_type; - typedef typename base::value_type value_type; - typedef typename base::key_compare key_compare; - typedef typename base::allocator_type allocator_type; - typedef typename base::reference reference; - typedef typename base::const_reference const_reference; - typedef typename base::iterator iterator; - typedef typename base::const_iterator const_iterator; - typedef typename base::size_type size_type; - typedef typename base::difference_type difference_type; - typedef typename base::pointer pointer; - typedef typename base::const_pointer const_pointer; - typedef typename base::reverse_iterator reverse_iterator; - typedef typename base::const_reverse_iterator const_reverse_iterator; + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; - using base::begin; - using base::end; - using base::rbegin; - using base::rend; + using base::begin; + using base::end; + using base::rbegin; + using base::rend; - using base::empty; - using base::size; - using base::max_size; + using base::empty; + using base::size; + using base::max_size; - using base::find; - using base::count; - using base::lower_bound; - using base::upper_bound; - using base::equal_range; + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; - using base::operator=; - using base::operator==; + using base::operator=; + using base::operator==; - explicit __multi_associative(const Compare& comp, const Allocator& A, const key_type (*v_to_k)(const value_type)) - : base(comp, A, v_to_k) { } + explicit __multi_associative(const Compare& comp, const Allocator& A, const key_type (*v_to_k)(const value_type)) + : base(comp, A, v_to_k) { } - template __multi_associative( - InputIterator first, - InputIterator last, - const Compare& comp, - const Allocator& A, - const key_type (*v_to_k)(const value_type) - ) : base(comp, A, v_to_k) { - insert(first, last); - } + template __multi_associative( + InputIterator first, + InputIterator last, + const Compare& comp, + const Allocator& A, + const key_type (*v_to_k)(const value_type) + ) : base(comp, A, v_to_k) + { + insert(first, last); + } - iterator insert(const value_type& x){ - iterator location = lower_bound(this->value_to_key(x)); + iterator insert(const value_type& x) + { + iterator location = lower_bound(this->value_to_key(x)); - if(location == begin()){ - backing.push_front(x); - location = begin(); - }else{ - location = backing.insert(location.base_iterator(), x); - } - return location; - } + if (location == begin()) + { + backing.push_front(x); + location = begin(); + } + else + { + location = backing.insert(location.base_iterator(), x); + } - iterator insert(iterator position, const value_type& x){ - // FIXME - this is cheating and probably should be more efficient since we are - // now log(n) to find for inserts - return insert(x); - } + return location; + } - template void insert(InputIterator first, InputIterator last){ - while(first != last){ - insert(*first); - ++first; - } - } + iterator insert(iterator position, const value_type& x) + { + // FIXME - this is cheating and probably should be more efficient since we are + // now log(n) to find for inserts + + return insert(x); + } + + template void insert(InputIterator first, InputIterator last) + { + while (first != last) + { + insert(*first); + ++first; + } + } }; - - - -} +} // namespace +} // extern "C++" #pragma GCC visibility pop -#endif //__STD_HEADER_ASSOCIATIVE_BASE +#endif //__STD_HEADER_ASSOCIATIVE_BASE diff --git a/misc/uClibc++/include/uClibc++/bitset b/misc/uClibc++/include/uClibc++/bitset index 50d540469a..92243b208f 100644 --- a/misc/uClibc++/include/uClibc++/bitset +++ b/misc/uClibc++/include/uClibc++/bitset @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -29,395 +29,551 @@ #pragma GCC visibility push(default) -namespace std{ - template class bitset; +extern "C++" +{ +namespace std +{ + template class bitset; + template bitset operator&(const bitset&, const bitset&); + template bitset operator|(const bitset&, const bitset&); + template bitset operator^(const bitset&, const bitset&); + template basic_istream& + operator>>(basic_istream& is, bitset& x); - template bitset operator&(const bitset&, const bitset&); - template bitset operator|(const bitset&, const bitset&); - template bitset operator^(const bitset&, const bitset&); - template basic_istream& - operator>>(basic_istream& is, bitset& x); + template basic_ostream& + operator<<(basic_ostream& os, const bitset& x); + + // Actual Code - template basic_ostream& - operator<<(basic_ostream& os, const bitset& x); - - //Actual Code + template class _UCXXEXPORT bitset { + private: + //Number of characters allocated to hold the bits + static const size_t WORD_SIZE = CHAR_BIT; //Use int maybe? + static const size_t num_bytes = (N + WORD_SIZE - 1) / WORD_SIZE; - template class _UCXXEXPORT bitset { - private: - //Number of characters allocated to hold the bits - static const size_t WORD_SIZE = CHAR_BIT; //Use int maybe? - static const size_t num_bytes = (N + WORD_SIZE - 1) / WORD_SIZE; + //From the bit number, figure out which byte we are working with - //From the bit number, figure out which byte we are working with - size_t byte_num(size_t bit_num) const{ - if(WORD_SIZE == 8){ - return (bit_num >> 3); - } - if(WORD_SIZE == 16){ - return (bit_num >> 4); - } - if(WORD_SIZE == 32){ - return (bit_num >> 5); - } - if(WORD_SIZE == 64){ - return (bit_num >> 6); - } - return bit_num / WORD_SIZE; - } - //From the bit number, figure out which bit inside the byte we need - size_t bit_num(const size_t bit_num) const{ - return bit_num % WORD_SIZE; - } + size_t byte_num(size_t bit_num) const + { + if (WORD_SIZE == 8) + { + return (bit_num >> 3); + } + if (WORD_SIZE == 16) + { + return (bit_num >> 4); + } - //Point to the actual data - char data[num_bytes]; - public: + if (WORD_SIZE == 32) + { + return (bit_num >> 5); + } - class _UCXXEXPORT reference { - friend class bitset; - reference() : bit_num(0), parent(0) { } - size_t bit_num; - bitset * parent; - public: - ~reference() { } - reference& operator=(bool x){ // for b[i] = x; - parent->set(bit_num, x); - return *this; - } - reference& operator=(const reference& x){ // for b[i] = b[j]; - parent->set(bit_num, x); - return *this; - } - bool operator~() const{ // flips the bit - return !parent->test(bit_num); - } - operator bool() const{ // for x = b[i]; - return parent->test(bit_num); - } - reference& flip(){ // for b[i].flip(); - parent->flip(bit_num); - return *this; - } - }; + if (WORD_SIZE == 64) + { + return (bit_num >> 6); + } - bitset(){ - reset(); - } - bitset(unsigned long val){ - reset(); - size_t count = sizeof(val) * CHAR_BIT; - if(count > N){ - count = N; - } - for(size_t i = 0; i < count; ++i){ - set(i, ((val >> i) & 1)); - } - } + return bit_num / WORD_SIZE; + } - bitset(const bitset & val){ - for(size_t i = 0; i < num_bytes; ++i){ - data[i] = val.data[i]; - } - } + // From the bit number, figure out which bit inside the byte we need - template _UCXXEXPORT - explicit bitset( - const basic_string& str, - typename basic_string::size_type pos = 0, - typename basic_string::size_type n = - basic_string::npos - - ){ - reset(); - if(n > str.length()){ - n = str.length(); - } - size_t width = n; - if (width + pos > str.length()){ - width = str.length() - pos; - } + size_t bit_num(const size_t bit_num) const + { + return bit_num % WORD_SIZE; + } - for(size_t i = 0; i < width; ++i){ - switch(str[pos + width - i - 1]){ - case '0': - break; - case '1': - set(i); - break; - default: - __throw_invalid_argument(); - } - } - } + //Point to the actual data - bitset& operator&=(const bitset& rhs){ - for(size_t i =0; i < num_bytes; ++i){ - data[i] &= rhs.data[i]; - } - return *this; - } + char data[num_bytes]; - bitset& operator|=(const bitset& rhs){ - for(size_t i =0; i < num_bytes; ++i){ - data[i] |= rhs.data[i]; - } - return *this; - } - bitset& operator^=(const bitset& rhs){ - for(size_t i=0; i < num_bytes; ++i){ - data[i] ^= rhs.data[i]; - } - return *this; - } + public: - bitset& operator<<=(size_t pos){ - for(size_t i = N-1; i >=pos; --i){ - set(i, test(i - pos)); - } - for(size_t i = 0; i < pos; ++i){ - reset(i); - } - return *this; - } + class _UCXXEXPORT reference + { + friend class bitset; + reference() : bit_num(0), parent(0) { } + size_t bit_num; + bitset * parent; + public: + ~reference() { } - bitset& operator>>=(size_t pos){ - for(size_t i = 0; i < (N - pos); ++i){ - set(i, test(i + pos)); - } - for(size_t i = pos; i > 0; --i){ - reset(N - i); - } - return *this; - } + reference& operator=(bool x) + { + // for b[i] = x; - bitset& set(){ - size_t i; - for(i = 0; i < N ; ++i){ - data[byte_num(i)] |= (1<& set(size_t pos, int val = true){ - if(val == true){ - data[byte_num(pos)] |= (1<& reset(){ - for(size_t i = 0; i < num_bytes; ++i){ - data[i] = 0; - } - return *this; - } - bitset& reset(size_t pos){ - data[byte_num(pos)] &= ~(1< operator~() const{ - bitset retval(*this); - retval.flip(); - return retval; - } + parent->set(bit_num, x); + return *this; + } - bitset& flip(){ - for(size_t i = 0; i < num_bytes; ++i){ - data[i] = ~data[i]; - } - return *this; - } - bitset& flip(size_t pos){ - char temp = data[byte_num(pos)] & (1 << bit_num(pos)); - if(temp == 0){ //Bit was 0 - data[byte_num(pos)] |= (1 << bit_num(pos)); - }else{ //Bit was 1 - data[byte_num(pos)] &= ~(1<set(bit_num, x); + return *this; + } - unsigned long to_ulong() const{ - if(N > sizeof(unsigned long) * CHAR_BIT){ - __throw_overflow_error(); - } - unsigned long retval = 0; - size_t count = N; - for(size_t i = count; i > 0; --i){ - if(test(i)){ - retval +=1; - } - retval<<=1; - } - if(test(0)){ - retval +=1; - } - return retval; - } + bool operator~() const + { + // flips the bit - template - basic_string to_string() const - { - basic_string retval; - retval.reserve(N); - for(size_t i = N ; i > 0; --i){ - if(test(i-1) == true){ - retval.append("1"); - }else{ - retval.append("0"); - } - } - return retval; - } + return !parent->test(bit_num); + } + operator bool() const + { + // for x = b[i]; - size_t count() const{ - size_t retval = 0; - for(size_t i =0; i < N; ++i){ - if(test(i)){ - ++retval; - } - } - return retval; - } - size_t size() const{ - return N; - } + return parent->test(bit_num); + } - bitset& operator=(const bitset & rhs){ - if(&rhs == this){ - return *this; - } - for(size_t i = 0; i <= byte_num(N); ++i){ - data[i] = rhs.data[i]; - } - return *this; - } + reference& flip() + { + // for b[i].flip(); + parent->flip(bit_num); + return *this; + } + }; - bool operator==(const bitset& rhs) const{ - for(size_t i =0; i< N; ++i){ - if(test(i) != rhs.test(i)){ - return false; - } - } - return true; - } + bitset() + { + reset(); + } - bool operator!=(const bitset& rhs) const{ - for(size_t i =0; i< N; ++i){ - if(test(i) != rhs.test(i)){ - return true; - } - } - return false; - } + bitset(unsigned long val) + { + reset(); + size_t count = sizeof(val) * CHAR_BIT; + if (count > N) + { + count = N; + } - bool test(size_t pos) const{ - return (data[byte_num(pos)] & (1<> i) & 1)); + } + } - bool any() const{ - for(size_t i = 0; i< N; ++i){ - if(test(i)==true){ - return true; - } - } - return false; - } + bitset(const bitset & val) + { + for (size_t i = 0; i < num_bytes; ++i) + { + data[i] = val.data[i]; + } + } - bool none() const{ - if(any() == true){ - return false; - } - return true; - } + template _UCXXEXPORT + explicit bitset + ( + const basic_string& str, + typename basic_string::size_type pos = 0, + typename basic_string::size_type n = + basic_string::npos + + ) + { + reset(); + if (n > str.length()) + { + n = str.length(); + } - bitset operator<<(size_t pos) const{ - bitset retval(*this); - retval<<=pos; - return retval; - } - bitset operator>>(size_t pos) const{ - bitset retval(*this); - retval>>=pos; - return retval; - } - }; + size_t width = n; + if (width + pos > str.length()) + { + width = str.length() - pos; + } - //Non-member functions + for (size_t i = 0; i < width; ++i) + { + switch (str[pos + width - i - 1]) + { + case '0': + break; + case '1': + set(i); + break; + default: + __throw_invalid_argument(); + } + } + } + bitset& operator&=(const bitset& rhs) + { + for (size_t i =0; i < num_bytes; ++i) + { + data[i] &= rhs.data[i]; + } - template _UCXXEXPORT bitset operator&(const bitset& lhs, const bitset& rhs){ - bitset retval(lhs); - retval &= rhs; - return retval; - } + return *this; + } - template _UCXXEXPORT bitset operator|(const bitset& lhs, const bitset& rhs){ - bitset retval(lhs); - retval |= rhs; - return retval; - } + bitset& operator|=(const bitset& rhs) + { + for (size_t i =0; i < num_bytes; ++i) + { + data[i] |= rhs.data[i]; + } - template _UCXXEXPORT bitset operator^(const bitset& lhs, const bitset& rhs){ - bitset retval(lhs); - retval ^= rhs; - return retval; - } + return *this; + } - template _UCXXEXPORT basic_istream& - operator>>(basic_istream& is, bitset& x) - { - string s; - charT c; - for(size_t i = 0; i < N; ++i){ - is.get(c); - if(!is.good()){ - break; - } - if(c != '1' && c !='0'){ - is.putback(c); - break; - } - s+=c; - } - bitset temp(s); - x = temp; - - return is; - } + bitset& operator^=(const bitset& rhs) + { + for (size_t i=0; i < num_bytes; ++i) + { + data[i] ^= rhs.data[i]; + } - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, const bitset& x) - { - for(size_t i = N ; i > 0; --i){ - if(x.test(i-1) == true){ - os << "1"; - }else{ - os << "0"; - } - } - return os; - } + return *this; + } + bitset& operator<<=(size_t pos) + { + for (size_t i = N-1; i >=pos; --i) + { + set(i, test(i - pos)); + } + for (size_t i = 0; i < pos; ++i) + { + reset(i); + } + return *this; + } -} + bitset& operator>>=(size_t pos) + { + for (size_t i = 0; i < (N - pos); ++i) + { + set(i, test(i + pos)); + } + + for (size_t i = pos; i > 0; --i) + { + reset(N - i); + } + + return *this; + } + + bitset& set() + { + size_t i; + for (i = 0; i < N ; ++i) + { + data[byte_num(i)] |= (1<& set(size_t pos, int val = true) + { + if (val == true) + { + data[byte_num(pos)] |= (1<& reset() + { + for (size_t i = 0; i < num_bytes; ++i) + { + data[i] = 0; + } + + return *this; + } + + bitset& reset(size_t pos) + { + data[byte_num(pos)] &= ~(1< operator~() const + { + bitset retval(*this); + retval.flip(); + return retval; + } + + bitset& flip() + { + for (size_t i = 0; i < num_bytes; ++i) + { + data[i] = ~data[i]; + } + + return *this; + } + + bitset& flip(size_t pos) + { + char temp = data[byte_num(pos)] & (1 << bit_num(pos)); + if (temp == 0) + { + // Bit was 0 + + data[byte_num(pos)] |= (1 << bit_num(pos)); + } + else + { + // Bit was 1 + + data[byte_num(pos)] &= ~(1< sizeof(unsigned long) * CHAR_BIT) + { + __throw_overflow_error(); + } + + unsigned long retval = 0; + size_t count = N; + for (size_t i = count; i > 0; --i) + { + if (test(i)) + { + retval +=1; + } + + retval <<= 1; + } + + if (test(0)) + { + retval +=1; + } + + return retval; + } + + template + basic_string to_string() const + { + basic_string retval; + retval.reserve(N); + for (size_t i = N ; i > 0; --i) + { + if (test(i-1) == true) + { + retval.append("1"); + } + else + { + retval.append("0"); + } + } + + return retval; + } + + size_t count() const + { + size_t retval = 0; + for (size_t i =0; i < N; ++i) + { + if (test(i)) + { + ++retval; + } + } + + return retval; + } + + size_t size() const + { + return N; + } + + bitset& operator=(const bitset & rhs) + { + if (&rhs == this) + { + return *this; + } + + for (size_t i = 0; i <= byte_num(N); ++i) + { + data[i] = rhs.data[i]; + } + + return *this; + } + + bool operator==(const bitset& rhs) const + { + for (size_t i =0; i< N; ++i) + { + if (test(i) != rhs.test(i)) + { + return false; + } + } + + return true; + } + + bool operator!=(const bitset& rhs) const + { + for (size_t i =0; i< N; ++i) + { + if (test(i) != rhs.test(i)) + { + return true; + } + } + + return false; + } + + bool test(size_t pos) const + { + return (data[byte_num(pos)] & (1< operator<<(size_t pos) const + { + bitset retval(*this); + retval<<=pos; + return retval; + } + + bitset operator>>(size_t pos) const + { + bitset retval(*this); + retval>>=pos; + return retval; + } + }; + + // Non-member functions + + template _UCXXEXPORT bitset operator&(const bitset& lhs, const bitset& rhs) + { + bitset retval(lhs); + retval &= rhs; + return retval; + } + + template _UCXXEXPORT bitset operator|(const bitset& lhs, const bitset& rhs) + { + bitset retval(lhs); + retval |= rhs; + return retval; + } + + template _UCXXEXPORT bitset operator^(const bitset& lhs, const bitset& rhs) + { + bitset retval(lhs); + retval ^= rhs; + return retval; + } + + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, bitset& x) + { + string s; + charT c; + for (size_t i = 0; i < N; ++i) + { + is.get(c); + if (!is.good()) + { + break; + } + + if (c != '1' && c !='0') + { + is.putback(c); + break; + } + + s += c; + } + + bitset temp(s); + x = temp; + return is; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const bitset& x) + { + for (size_t i = N ; i > 0; --i) + { + if (x.test(i-1) == true) + { + os << "1"; + } + else + { + os << "0"; + } + } + + return os; + } + +} // namespace +} // extern "C++" #pragma GCC visibility pop #endif - diff --git a/misc/uClibc++/include/uClibc++/char_traits b/misc/uClibc++/include/uClibc++/char_traits index d09de41b6d..ec2900ba77 100644 --- a/misc/uClibc++/include/uClibc++/char_traits +++ b/misc/uClibc++/include/uClibc++/char_traits @@ -32,8 +32,7 @@ // POSSIBILITY OF SUCH DAMAGE. // //*************************************************************************** -//#ifndef __INCLUDE_CXX_CHAR1_TRAITS -//#define __INCLUDE_CXX_CHAR1_TRAITS + #include #include #include @@ -47,169 +46,223 @@ #ifndef __HEADER_CHAR_TRAITS #define __HEADER_CHAR_TRAITS 1 -namespace std{ - /* Inlining all wrapped function calls to shrink the amount of code generated*/ - //Typedefs to use for stuff - typedef signed int char_traits_off_type; +extern "C++" +{ - //Generic char_traits - template struct _UCXXEXPORT char_traits { }; +namespace std +{ + /* Inlining all wrapped function calls to shrink the amount of code generated */ + // Typedefs to use for stuff - //Specialize for char - template<> struct _UCXXEXPORT char_traits { - typedef char char_type; - typedef short int int_type; - typedef char_traits_off_type off_type; - typedef char_traits_off_type pos_type; - typedef char state_type; - - inline static void assign(char_type & c, const char_type & d) { c = d; } + typedef signed int char_traits_off_type; - static bool eq(const char_type& c1, const char_type& c2); + // Generic char_traits - static char_type to_char_type(const int_type & i); + template struct _UCXXEXPORT char_traits { }; - inline static int_type to_int_type(const char_type & c){ - return (short int)(unsigned char)c; - } + // Specialize for char - inline static bool eq_int_type(const int_type & a, const int_type & b){ - if(a==b){ - return true; - } - return false; - } + template<> struct _UCXXEXPORT char_traits + { + typedef char char_type; + typedef short int int_type; + typedef char_traits_off_type off_type; + typedef char_traits_off_type pos_type; + typedef char state_type; + + inline static void assign(char_type & c, const char_type & d) { c = d; } + static bool eq(const char_type& c1, const char_type& c2); - inline static bool lt(const char_type& c1, const char_type& c2){ - if(strncmp(&c1, &c2, 1) < 0){ - return true; - } - return false; - } + static char_type to_char_type(const int_type & i); - inline static char_type* move(char_type* s1, const char_type* s2, size_t n){ - return (char*) memmove(s1, s2, n); - } + inline static int_type to_int_type(const char_type & c) + { + return (short int)(unsigned char)c; + } - inline static char_type* copy(char_type* s1, const char_type* s2, size_t n){ - for(unsigned long int i=0; i< n; ++i){ - assign(s1[i], s2[i]); - } - return s1 + n; - } + inline static bool eq_int_type(const int_type & a, const int_type & b) + { + if (a==b) + { + return true; + } - inline static char_type* assign(char_type* s, size_t n, char_type a){ - return (char *)memset(s, a, n); - } + return false; + } - inline static int compare(const char_type* s1, const char_type* s2, size_t n){ - return strncmp(s1, s2, n); - } + inline static bool lt(const char_type& c1, const char_type& c2) + { + if (strncmp(&c1, &c2, 1) < 0) + { + return true; + } - inline static size_t length(const char_type* s){ - return strlen(s); - } + return false; + } - static const char_type* find(const char_type* s, int n, const char_type& a); + inline static char_type* move(char_type* s1, const char_type* s2, size_t n) + { + return (char*) memmove(s1, s2, n); + } - inline static char_type eos() { return 0; } - inline static int_type eof() { return -1; } - inline static int_type not_eof(const int_type & i) { - if(i == -1){ - return 0; - } else { - return i; - } - } - static state_type get_state(pos_type p){ - p = p; - state_type a; - return a; - } - }; + inline static char_type* copy(char_type* s1, const char_type* s2, size_t n) + { + for (unsigned long int i=0; i< n; ++i) + { + assign(s1[i], s2[i]); + } + return s1 + n; + } + + inline static char_type* assign(char_type* s, size_t n, char_type a) + { + return (char *)memset(s, a, n); + } + + inline static int compare(const char_type* s1, const char_type* s2, size_t n) + { + return strncmp(s1, s2, n); + } + + inline static size_t length(const char_type* s) + { + return strlen(s); + } + + static const char_type* find(const char_type* s, int n, const char_type& a); + + inline static char_type eos() { return 0; } + inline static int_type eof() { return -1; } + + inline static int_type not_eof(const int_type & i) + { + if (i == -1) + { + return 0; + } + else + { + return i; + } + } + + static state_type get_state(pos_type p) + { + p = p; + state_type a; + return a; + } + }; #ifdef __UCLIBCXX_HAS_WCHAR__ - template<> struct _UCXXEXPORT char_traits { - typedef wchar_t char_type; - typedef wint_t int_type; - typedef char_traits_off_type off_type; - typedef char_traits_off_type pos_type; - typedef mbstate_t state_type; + template<> struct _UCXXEXPORT char_traits + { + typedef wchar_t char_type; + typedef wint_t int_type; + typedef char_traits_off_type off_type; + typedef char_traits_off_type pos_type; + typedef mbstate_t state_type; - static void assign(char_type & c, const char_type & d){ c=d; } + static void assign(char_type & c, const char_type & d){ c=d; } - static char_type to_char_type(const int_type & i){ - return i; - } + static char_type to_char_type(const int_type & i) + { + return i; + } - static int_type to_int_type(const char_type & c){ - return c; - } + static int_type to_int_type(const char_type & c) + { + return c; + } - inline static bool eq_int_type(const int_type & a, const int_type & b){ - if(a==b){ - return true; - } - return false; - } + inline static bool eq_int_type(const int_type & a, const int_type & b) + { + if (a == b) + { + return true; + } - inline static bool eq(const char_type& c1, const char_type& c2){ - if(wcsncmp(&c1, &c2, 1) == 0){ - return true; - } - return false; - } + return false; + } - inline static bool lt(const char_type& c1, const char_type& c2){ - if(wcsncmp(&c1, &c2, 1) < 0){ - return true; - } - return false; - } + inline static bool eq(const char_type& c1, const char_type& c2) + { + if (wcsncmp(&c1, &c2, 1) == 0) + { + return true; + } - inline static char_type* move(char_type* s1, const char_type* s2, size_t n){ - return (char_type*) memmove(s1, s2, n * sizeof(char_type)); - } + return false; + } - inline static char_type* copy(char_type* s1, const char_type* s2, size_t n){ - for(unsigned long int i=0; i< n; ++i){ - assign(s1[i], s2[i]); - } - return s1 + n; - } + inline static bool lt(const char_type& c1, const char_type& c2) + { + if(wcsncmp(&c1, &c2, 1) < 0) + { + return true; + } - inline static char_type* assign(char_type* s, size_t n, char_type a){ - return (char_type *)memset(s, a, n); /*FIXME*/ - } + return false; + } - inline static int compare(const char_type* s1, const char_type* s2, size_t n){ - return wcsncmp(s1, s2, n); - } + inline static char_type* move(char_type* s1, const char_type* s2, size_t n) + { + return (char_type*) memmove(s1, s2, n * sizeof(char_type)); + } - inline static size_t length(const char_type* s){ - return wcslen(s); - } + inline static char_type* copy(char_type* s1, const char_type* s2, size_t n) + { + for (unsigned long int i = 0; i< n; ++i) + { + assign(s1[i], s2[i]); + } - static const char_type* find(const char_type* s, int n, const char_type& a); + return s1 + n; + } - inline static char_type eos() { return 0; } - inline static int_type eof() { return WEOF; } - inline static int_type not_eof(const int_type & i) { - if(i == WEOF){ - return (int_type)0; - } else { - return i; - } - } - static state_type get_state(pos_type){ - state_type a; - return a; - } - }; -#endif + inline static char_type* assign(char_type* s, size_t n, char_type a) + { + return (char_type *)memset(s, a, n); /*FIXME*/ + } -} + inline static int compare(const char_type* s1, const char_type* s2, size_t n) + { + return wcsncmp(s1, s2, n); + } -#endif + inline static size_t length(const char_type* s) + { + return wcslen(s); + } + + static const char_type* find(const char_type* s, int n, const char_type& a); + + inline static char_type eos() { return 0; } + inline static int_type eof() { return WEOF; } + + inline static int_type not_eof(const int_type & i) + { + if (i == WEOF) + { + return (int_type)0; + } + else + { + return i; + } + } + + static state_type get_state(pos_type) + { + state_type a; + return a; + } + }; +#endif // __UCLIBCXX_HAS_WCHAR__ + +} // namespace +} // extern "C++" + +#endif // __HEADER_CHAR_TRAITS diff --git a/misc/uClibc++/include/uClibc++/complex b/misc/uClibc++/include/uClibc++/complex index 2c3c82b961..9081ec83c7 100644 --- a/misc/uClibc++/include/uClibc++/complex +++ b/misc/uClibc++/include/uClibc++/complex @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -23,305 +23,411 @@ #ifndef __STD_HEADER_COMPLEX #define __STD_HEADER_COMPLEX 1 +extern "C++" +{ +namespace std +{ +// class complex; +// class complex; +// class complex; -namespace std { -// class complex; -// class complex; -// class complex; + template class _UCXXEXPORT complex{ + public: + typedef T value_type; - template class _UCXXEXPORT complex{ - public: - typedef T value_type; + complex(const T& re = T(), const T& im = T()) : r(re), i(im) { } + complex(const complex& c): r(c.r), i(c.i){ } + template complex(const complex& c): r(c.r), i(c.i){ } - complex(const T& re = T(), const T& im = T()) : r(re), i(im) { } - complex(const complex& c): r(c.r), i(c.i){ } - template complex(const complex& c): r(c.r), i(c.i){ } + inline T real() const + { + return r; + } - inline T real() const{ - return r; - } - inline T imag() const{ - return i; - } + inline T imag() const + { + return i; + } - complex& operator= (const T& v){ - r = v; - i = 0; - return *this; - } - complex& operator+=(const T& v){ - r +=v; - return *this; - } - complex& operator-=(const T& v){ - r -=v; - return *this; - } - complex& operator*=(const T& v){ - r*=v; - i*=v; - return *this; - } - complex& operator/=(const T& v){ - r/=v; - i/=v; - return *this; - } - complex& operator=(const complex& v){ - if(&v != this){ - r = v.r; - i = v.i; - } - return *this; - } - template complex& operator= (const complex& v){ - r = v.r; - i = v.i; - return *this; - } - template complex& operator+=(const complex& v){ - r+=v.r; - i+=v.i; - return *this; - } - template complex& operator-=(const complex& v){ - r-=v.r; - i-=v.i; - return *this; - } - template complex& operator*=(const complex& v){ - T tempr = r*v.r - i*v.i; - T tempi = r*v.i + i*v.r; - r = tempr; - i = tempi; - return *this; - } - template complex& operator/=(const complex& v){ - T tempr = (r*v.r + i*v.i) / (v.r*v.r + v.i*v.i); - T tempi = (i*v.r - r*v.i) / (v.r*v.r + v.i*v.i); - r = tempr; - i = tempi; - return *this; - } - private: - T r; - T i; - }; + complex& operator= (const T& v) + { + r = v; + i = 0; + return *this; + } - template _UCXXEXPORT complex operator+(const complex& ls, const complex& rs){ - complex retval(ls); - retval += rs; - return retval; - } - template _UCXXEXPORT complex operator+(const complex& ls, const T& rs){ - complex retval(ls); - ls += rs; - return retval; - } - template _UCXXEXPORT inline complex operator+(const T& ls, const complex& rs){ - return rs + ls; - } - template _UCXXEXPORT complex operator-(const complex& ls, const complex& rs){ - complex retval(ls); - retval -= rs; - return retval; - } - template _UCXXEXPORT complex operator-(const complex& ls, const T& rs){ - complex retval(ls); - retval -= rs; - return retval; - } - template _UCXXEXPORT complex operator-(const T& ls, const complex& rs){ - complex retval(ls); - retval -= rs; - return retval; - } - template _UCXXEXPORT complex operator*(const complex& ls, const complex& rs){ - complex retval(ls); - retval *= rs; - return retval; - } - template _UCXXEXPORT complex operator*(const complex& ls, const T& rs){ - complex retval(ls); - retval *= rs; - return retval; - } - template _UCXXEXPORT complex operator*(const T& ls, const complex& rs){ - complex retval(ls); - retval *=rs; - return retval; - } - template _UCXXEXPORT complex operator/(const complex& ls, const complex& rs){ - complex retval(ls); - retval/=rs; - return retval; - } - template _UCXXEXPORT complex operator/(const complex& ls, const T& rs){ - complex retval(ls); - retval/=rs; - return retval; - } - template _UCXXEXPORT complex operator/(const T& ls, const complex& rs){ - complex retval(ls); - retval/=rs; - return retval; - } - template _UCXXEXPORT complex operator+(const complex& v){ - return v; - } - template _UCXXEXPORT complex operator-(const complex& v){ - return complex (-v.real(), -v.imag()); - } - template _UCXXEXPORT bool operator==(const complex& ls, const complex& rs){ - if( ls.real() == rs.real() && ls.imag() == rs.image()){ - return true; - } - return false; - } - template _UCXXEXPORT bool operator==(const complex& ls, const T& rs){ - if(ls.real() == rs && ls.imag() == T()){ - return true; - } - return false; - } - template _UCXXEXPORT bool operator==(const T& ls, const complex& rs){ - if(ls == rs.real() && rs.imag() == T()){ - return true; - } - return false; - } - template _UCXXEXPORT bool operator!=(const complex& ls, const complex& rs){ - if(ls == rs){ - return false; - } - return true; - } - template _UCXXEXPORT bool operator!=(const complex& ls, const T& rs){ - if(ls == rs){ - return false; - } - return true; - } - template _UCXXEXPORT bool operator!=(const T& ls, const complex& rs){ - if(ls == rs){ - return false; - } - return true; - } - template _UCXXEXPORT basic_istream& - operator>>(basic_istream& is, complex& v) - { - T tempr; - T tempi; - is >> tempr; - is.get(); - is >> tempi; - v = complex(tempr, tempi); - return is; - } + complex& operator+=(const T& v) + { + r +=v; + return *this; + } - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, const complex&v) - { - os << v.real() << ", " << v.imag(); - return os; - } + complex& operator-=(const T& v) + { + r -=v; + return *this; + } - template _UCXXEXPORT T real(const complex& v){ - return v.real(); - } + complex& operator*=(const T& v) + { + r*=v; + i*=v; + return *this; + } - template _UCXXEXPORT T imag(const complex& v){ - return v.imag(); - } + complex& operator/=(const T& v) + { + r/=v; + i/=v; + return *this; + } - template _UCXXEXPORT T norm(const complex& v){ - return (v.real() * v.real() + v.imag() * v.imag()); - } + complex& operator=(const complex& v) + { + if (&v != this){ + r = v.r; + i = v.i; + } + return *this; + } - template _UCXXEXPORT complex conj(const complex& v){ - return complex(v.real(), -v.imag()); - } + template complex& operator= (const complex& v) + { + r = v.r; + i = v.i; + return *this; + } -#ifdef __UCLIBCXX_SUPPORT_MATH__ //Can we link with libm? + template complex& operator+=(const complex& v) + { + r+=v.r; + i+=v.i; + return *this; + } - template _UCXXEXPORT T abs(const complex& v){ - return sqrt(v.real() * v.real() + v.imag() * v.imag()); - } + template complex& operator-=(const complex& v) + { + r-=v.r; + i-=v.i; + return *this; + } - template _UCXXEXPORT T arg(const complex& v){ - return atan2(v.imag(), v.real()); - } + template complex& operator*=(const complex& v) + { + T tempr = r*v.r - i*v.i; + T tempi = r*v.i + i*v.r; + r = tempr; + i = tempi; + return *this; + } - template _UCXXEXPORT complex polar(const T& rho, const T& theta){ - return complex(rho * cos(theta), rho * sin(theta)); - } + template complex& operator/=(const complex& v) + { + T tempr = (r*v.r + i*v.i) / (v.r*v.r + v.i*v.i); + T tempi = (i*v.r - r*v.i) / (v.r*v.r + v.i*v.i); + r = tempr; + i = tempi; + return *this; + } - template _UCXXEXPORT complex cos (const complex& v){ - return complex(cos(v.real()) * cosh(v.imag()), -sin(v.real()) * sinh(v.imag())); - } + private: + T r; + T i; + }; - template _UCXXEXPORT complex cosh (const complex& v){ - return complex(cosh(v.real()) * cos(v.imag()), sinh(v.real()) * sin(v.imag())); - } + template _UCXXEXPORT complex operator+(const complex& ls, const complex& rs) + { + complex retval(ls); + retval += rs; + return retval; + } - template _UCXXEXPORT complex exp (const complex& v){ - return polar(exp(v.real()), v.imag()); - } + template _UCXXEXPORT complex operator+(const complex& ls, const T& rs) + { + complex retval(ls); + ls += rs; + return retval; + } - template _UCXXEXPORT complex log (const complex& v){ - return complex(log(abs(v)), arg(v)); - } + template _UCXXEXPORT inline complex operator+(const T& ls, const complex& rs) + { + return rs + ls; + } - template _UCXXEXPORT complex log10(const complex& v){ - return (log(v) / log(T(10.0))); - } + template _UCXXEXPORT complex operator-(const complex& ls, const complex& rs) + { + complex retval(ls); + retval -= rs; + return retval; + } - template _UCXXEXPORT complex pow(const complex& v, int p){ - T rho = pow(abs(v), p); - T theta = arg(v); - return complex(rho * cos(p * theta), rho * sin(p * theta) ); - } + template _UCXXEXPORT complex operator-(const complex& ls, const T& rs) + { + complex retval(ls); + retval -= rs; + return retval; + } - template _UCXXEXPORT complex pow(const complex& v, const T& p){ - return polar( pow(abs(v),p), arg(v)*p ); - } + template _UCXXEXPORT complex operator-(const T& ls, const complex& rs) + { + complex retval(ls); + retval -= rs; + return retval; + } - template _UCXXEXPORT complex pow(const complex& v, const complex& p){ - if(v == T()){ - //We are using "0" as the value - return T(); - } - return exp(p * log(v)); - } + template _UCXXEXPORT complex operator*(const complex& ls, const complex& rs) + { + complex retval(ls); + retval *= rs; + return retval; + } - template _UCXXEXPORT complex pow(const T& v, const complex& p){ - if(v == T()){ - return T(); - } - return polar(pow(v,p.real()), y.imag() * log(x) ); - } + template _UCXXEXPORT complex operator*(const complex& ls, const T& rs) + { + complex retval(ls); + retval *= rs; + return retval; + } - template _UCXXEXPORT complex sin (const complex& v){ - return complex(sin(v.real()) * cosh(v.imag()), cosh(v.real()) * sin(v.imag())); - } + template _UCXXEXPORT complex operator*(const T& ls, const complex& rs) + { + complex retval(ls); + retval *=rs; + return retval; + } - template _UCXXEXPORT complex sinh (const complex& v){ - return complext(sinh(v.real()) * cos(v.imag()), cosh(v.real()) * sin(v.imag()) ); - } + template _UCXXEXPORT complex operator/(const complex& ls, const complex& rs) + { + complex retval(ls); + retval/=rs; + return retval; + } - template _UCXXEXPORT complex sqrt (const complex&); - template _UCXXEXPORT complex tan (const complex& v){ - return sin(v) / cos(v); - } + template _UCXXEXPORT complex operator/(const complex& ls, const T& rs) + { + complex retval(ls); + retval/=rs; + return retval; + } - template _UCXXEXPORT complex tanh (const complex& v){ - return sinh(v) / cosh(v); - } + template _UCXXEXPORT complex operator/(const T& ls, const complex& rs) + { + complex retval(ls); + retval/=rs; + return retval; + } + + template _UCXXEXPORT complex operator+(const complex& v) + { + return v; + } + + template _UCXXEXPORT complex operator-(const complex& v) + { + return complex (-v.real(), -v.imag()); + } + + template _UCXXEXPORT bool operator==(const complex& ls, const complex& rs) + { + if (ls.real() == rs.real() && ls.imag() == rs.image()) + { + return true; + } + + return false; + } + + template _UCXXEXPORT bool operator==(const complex& ls, const T& rs) + { + if (ls.real() == rs && ls.imag() == T()) + { + return true; + } + + return false; + } + + template _UCXXEXPORT bool operator==(const T& ls, const complex& rs) + { + if (ls == rs.real() && rs.imag() == T()) + { + return true; + } + + return false; + } + + template _UCXXEXPORT bool operator!=(const complex& ls, const complex& rs) + { + if (ls == rs) + { + return false; + } + + return true; + } + + template _UCXXEXPORT bool operator!=(const complex& ls, const T& rs) + { + if (ls == rs) + { + return false; + } + + return true; + } + + template _UCXXEXPORT bool operator!=(const T& ls, const complex& rs) + { + if (ls == rs) + { + return false; + } + + return true; + } + + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, complex& v) + { + T tempr; + T tempi; + is >> tempr; + is.get(); + is >> tempi; + v = complex(tempr, tempi); + return is; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& os, const complex&v) + { + os << v.real() << ", " << v.imag(); + return os; + } + + template _UCXXEXPORT T real(const complex& v) + { + return v.real(); + } + + template _UCXXEXPORT T imag(const complex& v) + { + return v.imag(); + } + + template _UCXXEXPORT T norm(const complex& v) + { + return (v.real() * v.real() + v.imag() * v.imag()); + } + + template _UCXXEXPORT complex conj(const complex& v) + { + return complex(v.real(), -v.imag()); + } + +#ifdef __UCLIBCXX_SUPPORT_MATH__ //Can we link with libm? + + template _UCXXEXPORT T abs(const complex& v) + { + return sqrt(v.real() * v.real() + v.imag() * v.imag()); + } + + template _UCXXEXPORT T arg(const complex& v) + { + return atan2(v.imag(), v.real()); + } + + template _UCXXEXPORT complex polar(const T& rho, const T& theta) + { + return complex(rho * cos(theta), rho * sin(theta)); + } + + template _UCXXEXPORT complex cos (const complex& v) + { + return complex(cos(v.real()) * cosh(v.imag()), -sin(v.real()) * sinh(v.imag())); + } + + template _UCXXEXPORT complex cosh (const complex& v) + { + return complex(cosh(v.real()) * cos(v.imag()), sinh(v.real()) * sin(v.imag())); + } + + template _UCXXEXPORT complex exp (const complex& v) + { + return polar(exp(v.real()), v.imag()); + } + + template _UCXXEXPORT complex log (const complex& v) + { + return complex(log(abs(v)), arg(v)); + } + + template _UCXXEXPORT complex log10(const complex& v) + { + return (log(v) / log(T(10.0))); + } + + template _UCXXEXPORT complex pow(const complex& v, int p) + { + T rho = pow(abs(v), p); + T theta = arg(v); + return complex(rho * cos(p * theta), rho * sin(p * theta)); + } + + template _UCXXEXPORT complex pow(const complex& v, const T& p) + { + return polar(pow(abs(v),p), arg(v)*p); + } + + template _UCXXEXPORT complex pow(const complex& v, const complex& p) + { + if (v == T()) + { + // We are using "0" as the value + + return T(); + } + + return exp(p * log(v)); + } + + template _UCXXEXPORT complex pow(const T& v, const complex& p) + { + if (v == T()) + { + return T(); + } + + return polar(pow(v,p.real()), y.imag() * log(x)); + } + + template _UCXXEXPORT complex sin (const complex& v) + { + return complex(sin(v.real()) * cosh(v.imag()), cosh(v.real()) * sin(v.imag())); + } + + template _UCXXEXPORT complex sinh (const complex& v) + { + return complext(sinh(v.real()) * cos(v.imag()), cosh(v.real()) * sin(v.imag())); + } + + template _UCXXEXPORT complex sqrt (const complex&); + + template _UCXXEXPORT complex tan (const complex& v) + { + return sin(v) / cos(v); + } + + template _UCXXEXPORT complex tanh (const complex& v) + { + return sinh(v) / cosh(v); + } #endif -} +} // namespace +} // extern "C++" #endif diff --git a/misc/uClibc++/include/uClibc++/deque b/misc/uClibc++/include/uClibc++/deque index 19be5c8bb4..48b5db3b33 100644 --- a/misc/uClibc++/include/uClibc++/deque +++ b/misc/uClibc++/include/uClibc++/deque @@ -1,20 +1,20 @@ /* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - -*/ + * + * This file is part of the uClibc++ Library. + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -25,6 +25,8 @@ #ifndef __STD_HEADER_DEQUE #define __STD_HEADER_DEQUE +extern "C++" +{ namespace std { template > class deque; @@ -1057,7 +1059,9 @@ namespace std template _UCXXEXPORT void swap(deque& x, deque& y){ x.swap(y); } + } // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/fstream b/misc/uClibc++/include/uClibc++/fstream index d5c1d083b0..0f0388e5dd 100644 --- a/misc/uClibc++/include/uClibc++/fstream +++ b/misc/uClibc++/include/uClibc++/fstream @@ -1,25 +1,24 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #ifndef __STD_HEADER_FSTREAM #define __STD_HEADER_FSTREAM 1 - #include #include @@ -40,637 +39,821 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ + template class basic_filebuf; - template class basic_filebuf; - - typedef basic_filebuf filebuf; + typedef basic_filebuf filebuf; #ifdef __UCLIBCXX_HAS_WCHAR__ - typedef basic_filebuf wfilebuf; + typedef basic_filebuf wfilebuf; #endif - - template class _UCXXEXPORT basic_filebuf - : public basic_streambuf - { + template class _UCXXEXPORT basic_filebuf + : public basic_streambuf + { #ifdef __UCLIBCXX_SUPPORT_CDIR__ - friend ios_base::Init::Init(); //Needed for cout/cin stuff + friend ios_base::Init::Init(); // Needed for cout/cin stuff #endif - public: - // Types (inherited from basic_streambuf: - typedef typename basic_streambuf::char_type char_type; - typedef typename basic_streambuf::int_type int_type; - typedef typename basic_streambuf::pos_type pos_type; - typedef typename basic_streambuf::off_type off_type; - typedef traits traits_type; + public: + // Types (inherited from basic_streambuf: - //Constructors/destructor: + typedef typename basic_streambuf::char_type char_type; + typedef typename basic_streambuf::int_type int_type; + typedef typename basic_streambuf::pos_type pos_type; + typedef typename basic_streambuf::off_type off_type; + typedef traits traits_type; - _UCXXEXPORT basic_filebuf() : basic_streambuf(), fp(0), pbuffer(0), gbuffer(0) - { - append=false; - pbuffer = new char_type[CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE]; - gbuffer = new char_type[CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE]; + // Constructors/destructor: - this->setp(pbuffer, pbuffer + CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE); - //Position get buffer so that there is no data available - this->setg(gbuffer, gbuffer + CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE, - gbuffer + CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE); - } + _UCXXEXPORT basic_filebuf() : basic_streambuf(), fp(0), pbuffer(0), gbuffer(0) + { + append=false; + pbuffer = new char_type[CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE]; + gbuffer = new char_type[CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE]; + this->setp(pbuffer, pbuffer + CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE); - _UCXXEXPORT virtual ~basic_filebuf(){ - sync(); - close(); - delete [] pbuffer; - delete [] gbuffer; - pbuffer = 0; - gbuffer = 0; - } + //Position get buffer so that there is no data available + this->setg(gbuffer, gbuffer + CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE, + gbuffer + CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE); + } - //Members: + _UCXXEXPORT virtual ~basic_filebuf(){ + sync(); + close(); + delete [] pbuffer; + delete [] gbuffer; + pbuffer = 0; + gbuffer = 0; + } - _UCXXEXPORT bool is_open() const{ - if(fp == 0){ - return false; - } - return true; - } + // Members: - _UCXXEXPORT basic_filebuf* open(const char* s, ios_base::openmode mode){ - bool move_end = (mode & ios_base::ate) != 0; - if(is_open() !=false){ //Must call close() first - return 0; - } - basic_streambuf::openedFor = mode; - mode = mode & ~ios_base::ate; + _UCXXEXPORT bool is_open() const + { + if (fp == 0) + { + return false; + } + return true; + } - if(mode == ios_base::out || mode == (ios_base::out | ios_base::trunc)){ - fp = fopen(s, "w" ); - }else if((mode & ios_base::app) && ! (mode & ios_base::trunc)){ - if(mode & ios_base::binary){ - if(mode & ios_base::in){ - fp = fopen(s, "a+b"); - }else{ - fp = fopen(s, "ab"); - } - }else{ - if(mode & ios_base::in){ - fp = fopen(s, "a+"); - }else{ - fp = fopen(s, "a"); - } - } - }else if(mode == ios_base::in){ - fp = fopen(s, "r"); - }else if(mode == (ios_base::in | ios_base::out)){ - fp = fopen(s, "r+"); - }else if(mode == (ios_base::in | ios_base::out | ios_base::trunc)){ - fp = fopen(s, "w+"); - }else if(mode == (ios_base::binary | ios_base::out)){ - fp = fopen(s, "wb"); - }else if(mode == (ios_base::in | ios_base::binary)){ - fp = fopen(s, "rb"); - }else if(mode == (ios_base::in | ios_base::binary | ios_base::out)){ - fp = fopen(s, "r+b"); - }else if(mode==(ios_base::binary | ios_base::out | ios_base::trunc)){ - fp = fopen(s, "w+b"); - }else if(mode == (ios_base::in | ios_base::binary | ios_base::out | ios_base::trunc)){ - fp = fopen(s, "w+b"); - } + _UCXXEXPORT basic_filebuf* open(const char* s, ios_base::openmode mode) + { + bool move_end = (mode & ios_base::ate) != 0; + if (is_open() !=false) + { + // Must call close() first - if(fp == 0){ - return 0; - } - if(ferror(fp)){ - fclose(fp); - fp=0; - return 0; - } - int retval = 0; + return 0; + } - //Check to make sure the stream is good - if(move_end == true){ - retval = fseek(fp, 0, SEEK_END); - }else{ - retval = fseek(fp, 0, SEEK_SET); - } - if(retval!=0){ //Seek error - fclose(fp); - fp=0; - return 0; - } + basic_streambuf::openedFor = mode; + mode = mode & ~ios_base::ate; - basic_streambuf::mgnext = basic_streambuf::mgend; + if (mode == ios_base::out || mode == (ios_base::out | ios_base::trunc)) + { + fp = fopen(s, "w"); + } + else if ((mode & ios_base::app) && ! (mode & ios_base::trunc)) + { + if (mode & ios_base::binary) + { + if (mode & ios_base::in) + { + fp = fopen(s, "a+b"); + } + else + { + fp = fopen(s, "ab"); + } + } + else + { + if (mode & ios_base::in) + { + fp = fopen(s, "a+"); + } + else + { + fp = fopen(s, "a"); + } + } + } + else if (mode == ios_base::in) + { + fp = fopen(s, "r"); + } + else if (mode == (ios_base::in | ios_base::out)) + { + fp = fopen(s, "r+"); + } + else if (mode == (ios_base::in | ios_base::out | ios_base::trunc)) + { + fp = fopen(s, "w+"); + } + else if (mode == (ios_base::binary | ios_base::out)) + { + fp = fopen(s, "wb"); + } + else if (mode == (ios_base::in | ios_base::binary)) + { + fp = fopen(s, "rb"); + } + else if (mode == (ios_base::in | ios_base::binary | ios_base::out)) + { + fp = fopen(s, "r+b"); + } + else if (mode==(ios_base::binary | ios_base::out | ios_base::trunc)) + { + fp = fopen(s, "w+b"); + } + else if (mode == (ios_base::in | ios_base::binary | ios_base::out | ios_base::trunc)) + { + fp = fopen(s, "w+b"); + } - return this; - } - _UCXXEXPORT basic_filebuf* close(){ - if(fp != 0 && fp != stdin && fp != stdout && fp !=stderr ){ - overflow(); - sync(); - int retval = fclose(fp); - if(retval !=0){ //Error of some sort - return 0; - } - fp=0; - } - return this; - } - protected: - _UCXXEXPORT basic_filebuf(const basic_filebuf &){ } - _UCXXEXPORT basic_filebuf & operator=(const basic_filebuf &){ return *this; } + if (fp == 0) + { + return 0; + } - //Overridden virtual functions: + if (ferror(fp)) + { + fclose(fp); + fp = 0; + return 0; + } - virtual _UCXXEXPORT int showmanyc(){ - return basic_streambuf::egptr() - basic_streambuf::gptr(); - } - virtual _UCXXEXPORT int_type underflow(){ - /* Some variables used internally: - Buffer pointers: - charT * mgbeg; - charT * mgnext; - charT * mgend; + int retval = 0; - eback() returns mgbeg - gptr() returns mgnext - egptr() returns mgend + // Check to make sure the stream is good - gbump(int n) mgnext+=n + if (move_end == true) + { + retval = fseek(fp, 0, SEEK_END); + } + else + { + retval = fseek(fp, 0, SEEK_SET); + } - */ + if (retval != 0) + { + //Seek error - if(!is_open()){ - return traits::eof(); - } + fclose(fp); + fp=0; + return 0; + } - if(basic_streambuf::eback() == 0){ - //No buffer, so... - charT c; - int retval; - retval = fread(&c, sizeof(charT), 1, fp); + basic_streambuf::mgnext = basic_streambuf::mgend; - if(retval == 0 || feof(fp) || ferror(fp) ){ - return traits::eof(); - } - return traits::to_int_type(c); - } + return this; + } - if(basic_streambuf::eback() == basic_streambuf::gptr()){ //Buffer is full - return traits::to_int_type(*basic_streambuf::gptr()); - } - //Shift entire buffer back to the begining - size_t offset = basic_streambuf::gptr() - basic_streambuf::eback(); - size_t amountData = basic_streambuf::egptr() - basic_streambuf::gptr(); + _UCXXEXPORT basic_filebuf* close() + { + if (fp != 0 && fp != stdin && fp != stdout && fp !=stderr) + { + overflow(); + sync(); + int retval = fclose(fp); + if (retval !=0) + { + //Error of some sort - for(charT * i = basic_streambuf::gptr(); i < basic_streambuf::egptr(); ++i){ - *(i-offset) = *i; - } + return 0; + } - size_t retval = 0; - //Save operating flags from file descriptor - int fcntl_flags = fcntl(fileno(fp), F_GETFL); - retval = 0; + fp=0; + } - //Set to non_blocking mode - fcntl(fileno(fp), F_SETFL, fcntl_flags | O_NONBLOCK); + return this; + } - //Fill rest of buffer - retval = fread(basic_streambuf::egptr() - - basic_streambuf::gptr() + basic_streambuf::eback(), - sizeof(charT), - offset, - fp - ); + protected: + _UCXXEXPORT basic_filebuf(const basic_filebuf &){ } + _UCXXEXPORT basic_filebuf & operator=(const basic_filebuf &){ return *this; } - //Clear problems where we didn't read in enough characters - if(EAGAIN == errno){ - clearerr(fp); - } + //Overridden virtual functions: - //Restore file descriptor clase - fcntl(fileno(fp), F_SETFL, fcntl_flags); + virtual _UCXXEXPORT int showmanyc() + { + return basic_streambuf::egptr() - basic_streambuf::gptr(); + } - //Now we are going to make sure that we read in at least one character. The hard way. - if(retval == 0){ - fcntl_flags = fcntl(fileno(fp), F_GETFL); - //Set to blocking mode - fcntl(fileno(fp), F_SETFL, fcntl_flags & ~O_NONBLOCK); + virtual _UCXXEXPORT int_type underflow() + { + /* Some variables used internally: + Buffer pointers: + charT * mgbeg; + charT * mgnext; + charT * mgend; - retval = fread(basic_streambuf::egptr() - - basic_streambuf::gptr() + basic_streambuf::eback(), - sizeof(charT), - 1, - fp - ); + eback() returns mgbeg + gptr() returns mgnext + egptr() returns mgend - //Restore file descriptor clase - fcntl(fileno(fp), F_SETFL, fcntl_flags); + gbump(int n) mgnext+=n + */ - } + if (!is_open()) + { + return traits::eof(); + } - if(retval !=offset){ //Slide buffer forward again - for(size_t i = 0; i < amountData + retval; ++i){ - *(basic_streambuf::egptr() - i - 1) = - *(basic_streambuf::eback() + amountData + retval - i - 1); - } - } + if (basic_streambuf::eback() == 0) + { + // No buffer, so... - basic_streambuf::mgnext -= retval; + charT c; + int retval; + retval = fread(&c, sizeof(charT), 1, fp); - if( (retval <= 0 && feof(fp)) || ferror(fp) ){ - return traits::eof(); - } + if (retval == 0 || feof(fp) || ferror(fp)) + { + return traits::eof(); + } - return traits::to_int_type(*basic_streambuf::gptr()); - } - virtual _UCXXEXPORT int_type uflow(){ - bool dobump = (basic_streambuf::gptr() != 0); - int_type retval = underflow(); - if(dobump){ - basic_streambuf::gbump(1); - } - return retval; - } - virtual _UCXXEXPORT int_type pbackfail(int_type c = traits::eof()){ - if(is_open() == false || - basic_streambuf::gptr() == basic_streambuf::eback()) - { - return traits::eof(); - } - if(traits::eq_int_type(c,traits::eof()) == false){ - if(traits::eq(traits::to_char_type(c), basic_streambuf::gptr()[-1]) == true){ - basic_streambuf::gbump(-1); - }else{ - basic_streambuf::gbump(-1); - basic_streambuf::gptr()[0] = c; - } - return c; - }else{ - basic_streambuf::gbump(-1); - return traits::not_eof(c); - } - } + return traits::to_int_type(c); + } - virtual _UCXXEXPORT int_type overflow(int_type c = traits::eof()){ - if(is_open() == false){ - //Can't do much - return traits::eof(); - } - if(basic_streambuf::pbase() == 0){ //Unbuffered - elliminate dupe code below - if(fputc(c, fp) == EOF){ - return traits::eof(); - } - return c; - } - if(basic_streambuf::pbase() == 0 && traits::eq_int_type(c,traits::eof()) ){ - //Nothing to flush - return traits::not_eof(c); - } - size_t r = basic_streambuf::pptr() - basic_streambuf::pbase(); + if (basic_streambuf::eback() == basic_streambuf::gptr()) + { + // Buffer is full - if( r == 0 && traits::eq_int_type(c,traits::eof()) ){ - return traits::not_eof(c); - }else if (r == 0 ){ - if(fputc(c, fp) == EOF){ - return traits::eof(); - } - return c; - } + return traits::to_int_type(*basic_streambuf::gptr()); + } - size_t totalChars = r; + // Shift entire buffer back to the begining - char_type *buffer = 0; - if(traits::eq_int_type(c,traits::eof())){ - buffer = new char_type[r]; - }else{ - buffer = new char_type[r+1]; - buffer[r] = c; - totalChars++; - } + size_t offset = basic_streambuf::gptr() - basic_streambuf::eback(); + size_t amountData = basic_streambuf::egptr() - basic_streambuf::gptr(); - traits::copy(buffer, basic_streambuf::pbase(), r); -// memcpy(buffer, basic_streambuf::pbase(), r); + for (charT * i = basic_streambuf::gptr(); i < basic_streambuf::egptr(); ++i) + { + *(i-offset) = *i; + } - size_t retval = fwrite(buffer, sizeof(charT), totalChars, fp); - if(retval !=totalChars){ - if(retval == 0){ - delete [] buffer; - return traits::eof(); - } - basic_streambuf::pbump(-retval); - fprintf(stderr, "***** Did not write the full buffer out. Should be: %d, actually: %d\n", - totalChars, retval); - }else{ - basic_streambuf::pbump(-r); - } + size_t retval = 0; - delete [] buffer; - return traits::not_eof(c); - } + // Save operating flags from file descriptor - virtual _UCXXEXPORT basic_streambuf* setbuf(char_type* s, streamsize n){ - if(s == 0 && n == 0){ //Unbuffered - if(pbuffer !=0){ - delete [] pbuffer; - } - if(gbuffer !=0){ - delete [] gbuffer; - } - pbuffer = 0; - gbuffer = 0; - }else if(basic_streambuf::gptr() !=0 && - basic_streambuf::gptr()==basic_streambuf::egptr()) - { - delete [] pbuffer; - pbuffer = s; - } - return this; - } - virtual _UCXXEXPORT pos_type seekoff(off_type off, ios_base::seekdir way, - ios_base::openmode = ios_base::in | ios_base::out) - { - if(is_open() == false){ - return -1; - } - int whence = SEEK_SET; // if(way == basic_ios::beg) - off_type position = off; + int fcntl_flags = fcntl(fileno(fp), F_GETFL); + retval = 0; - if(way == basic_ios::cur){ - whence = SEEK_CUR; - position -= (basic_streambuf::egptr() - basic_streambuf::gptr()); - }else if(way == basic_ios::end){ - whence = SEEK_END; - } + // Set to non_blocking mode - sync(); + fcntl(fileno(fp), F_SETFL, fcntl_flags | O_NONBLOCK); - int retval = fseek( - fp, - sizeof(charT)*(position), - whence - ); + // Fill rest of buffer - //Invalidate read buffer - basic_streambuf::gbump( - basic_streambuf::egptr() - basic_streambuf::gptr() - ); + retval = fread(basic_streambuf::egptr() - + basic_streambuf::gptr() + basic_streambuf::eback(), + sizeof(charT), + offset, + fp); - if(-1 != retval){ - retval = ftell(fp); - } + // Clear problems where we didn't read in enough characters - return retval; - } - virtual _UCXXEXPORT pos_type seekpos(pos_type sp, ios_base::openmode = ios_base::in | ios_base::out){ - if(is_open() == false){ - return -1; - } - sync(); + if (EAGAIN == errno) + { + clearerr(fp); + } - int retval = fseek(fp,sizeof(charT)* sp, SEEK_SET); + // Restore file descriptor clase - //Invalidate read buffer - basic_streambuf::gbump(basic_streambuf::egptr() - basic_streambuf::gptr()); - if(retval > -1){ - return sp; - } - return -1; - } - virtual _UCXXEXPORT int sync(){ - if(pbuffer !=0){ - if(overflow() == traits::eof()){ - return -1; - } - } - if(0 != fp && 0 != fflush(fp)){ - return -1; - } - return 0; - } - virtual _UCXXEXPORT void imbue(const locale&){ - return; - } + fcntl(fileno(fp), F_SETFL, fcntl_flags); + // Now we are going to make sure that we read in at least one character. The hard way. - virtual _UCXXEXPORT streamsize xsputn(const char_type* s, streamsize n){ - if(is_open() == false){ - return 0; - } - //Check to see if buffered + if (retval == 0) + { + fcntl_flags = fcntl(fileno(fp), F_GETFL); - //Check to see if we can buffer the data - streamsize buffer_avail = basic_streambuf::epptr() - basic_streambuf::pptr(); + // Set to blocking mode - if(n > buffer_avail){ //Flush buffer and write directly - overflow(); //Flush the buffer - return fwrite(s, sizeof(charT), n, fp); - } + fcntl(fileno(fp), F_SETFL, fcntl_flags & ~O_NONBLOCK); - //Add to buffer to be written later + retval = fread(basic_streambuf::egptr() - + basic_streambuf::gptr() + basic_streambuf::eback(), + sizeof(charT), + 1, + fp); - traits::copy(basic_streambuf::pptr(), s, n); - basic_streambuf::pbump(n); + // Restore file descriptor clase - return n; - } + fcntl(fileno(fp), F_SETFL, fcntl_flags); + } - FILE * fp; - char_type * pbuffer; - char_type * gbuffer; - bool append; - }; + if (retval !=offset) + { + // Slide buffer forward again + for (size_t i = 0; i < amountData + retval; ++i) + { + *(basic_streambuf::egptr() - i - 1) = + *(basic_streambuf::eback() + amountData + retval - i - 1); + } + } + + basic_streambuf::mgnext -= retval; + + if ((retval <= 0 && feof(fp)) || ferror(fp)) + { + return traits::eof(); + } + + return traits::to_int_type(*basic_streambuf::gptr()); + } + + virtual _UCXXEXPORT int_type uflow() + { + bool dobump = (basic_streambuf::gptr() != 0); + int_type retval = underflow(); + if (dobump) + { + basic_streambuf::gbump(1); + } + + return retval; + } + + virtual _UCXXEXPORT int_type pbackfail(int_type c = traits::eof()) + { + if (is_open() == false || + basic_streambuf::gptr() == basic_streambuf::eback()) + { + return traits::eof(); + } + + if (traits::eq_int_type(c,traits::eof()) == false) + { + if (traits::eq(traits::to_char_type(c), basic_streambuf::gptr()[-1]) == true) + { + basic_streambuf::gbump(-1); + } + else + { + basic_streambuf::gbump(-1); + basic_streambuf::gptr()[0] = c; + } + + return c; + } + else + { + basic_streambuf::gbump(-1); + return traits::not_eof(c); + } + } + + virtual _UCXXEXPORT int_type overflow(int_type c = traits::eof()) + { + if (is_open() == false) + { + // Can't do much + + return traits::eof(); + } + + if (basic_streambuf::pbase() == 0) + { + // Unbuffered - elliminate dupe code below + + if (fputc(c, fp) == EOF) + { + return traits::eof(); + } + + return c; + } + + if (basic_streambuf::pbase() == 0 && traits::eq_int_type(c,traits::eof())) + { + // Nothing to flush + + return traits::not_eof(c); + } + + size_t r = basic_streambuf::pptr() - basic_streambuf::pbase(); + + if (r == 0 && traits::eq_int_type(c,traits::eof())) + { + return traits::not_eof(c); + } + else if (r == 0) + { + if (fputc(c, fp) == EOF) + { + return traits::eof(); + } + + return c; + } + + size_t totalChars = r; + + char_type *buffer = 0; + if (traits::eq_int_type(c,traits::eof())) + { + buffer = new char_type[r]; + } + else + { + buffer = new char_type[r+1]; + buffer[r] = c; + totalChars++; + } + + traits::copy(buffer, basic_streambuf::pbase(), r); +// memcpy(buffer, basic_streambuf::pbase(), r); + + size_t retval = fwrite(buffer, sizeof(charT), totalChars, fp); + if (retval !=totalChars) + { + if (retval == 0) + { + delete [] buffer; + return traits::eof(); + } + + basic_streambuf::pbump(-retval); + fprintf(stderr, "***** Did not write the full buffer out. Should be: %d, actually: %d\n", + totalChars, retval); + } + else + { + basic_streambuf::pbump(-r); + } + + delete [] buffer; + return traits::not_eof(c); + } + + virtual _UCXXEXPORT basic_streambuf* setbuf(char_type* s, streamsize n) + { + if (s == 0 && n == 0) + { + // Unbuffered + + if (pbuffer !=0) + { + delete [] pbuffer; + } + + if (gbuffer !=0) + { + delete [] gbuffer; + } + + pbuffer = 0; + gbuffer = 0; + } + else if (basic_streambuf::gptr() !=0 && + basic_streambuf::gptr()==basic_streambuf::egptr()) + { + delete [] pbuffer; + pbuffer = s; + } + + return this; + } + + virtual _UCXXEXPORT pos_type seekoff(off_type off, ios_base::seekdir way, + ios_base::openmode = ios_base::in | ios_base::out) + { + if (is_open() == false) + { + return -1; + } + + int whence = SEEK_SET; // if (way == basic_ios::beg) + off_type position = off; + + if (way == basic_ios::cur) + { + whence = SEEK_CUR; + position -= (basic_streambuf::egptr() - basic_streambuf::gptr()); + } + else if (way == basic_ios::end) + { + whence = SEEK_END; + } + + sync(); + + int retval = fseek( + fp, + sizeof(charT)*(position), + whence); + + // Invalidate read buffer + + basic_streambuf::gbump( + basic_streambuf::egptr() - basic_streambuf::gptr()); + + if (-1 != retval) + { + retval = ftell(fp); + } + + return retval; + } + + virtual _UCXXEXPORT pos_type seekpos(pos_type sp, ios_base::openmode = ios_base::in | ios_base::out) + { + if (is_open() == false) + { + return -1; + } + + sync(); + + int retval = fseek(fp,sizeof(charT)* sp, SEEK_SET); + + // Invalidate read buffer + + basic_streambuf::gbump(basic_streambuf::egptr() - basic_streambuf::gptr()); + if (retval > -1) + { + return sp; + } + + return -1; + } + + virtual _UCXXEXPORT int sync() + { + if (pbuffer !=0) + { + if (overflow() == traits::eof()) + { + return -1; + } + } + + if (0 != fp && 0 != fflush(fp)) + { + return -1; + } + + return 0; + } + + virtual _UCXXEXPORT void imbue(const locale&) + { + return; + } + + virtual _UCXXEXPORT streamsize xsputn(const char_type* s, streamsize n) + { + if (is_open() == false) + { + return 0; + } + + // Check to see if buffered + + // Check to see if we can buffer the data + + streamsize buffer_avail = basic_streambuf::epptr() - basic_streambuf::pptr(); + + if (n > buffer_avail) + { + // Flush buffer and write directly + + overflow(); // Flush the buffer + return fwrite(s, sizeof(charT), n, fp); + } + + // Add to buffer to be written later + + traits::copy(basic_streambuf::pptr(), s, n); + basic_streambuf::pbump(n); + + return n; + } + + FILE * fp; + char_type * pbuffer; + char_type * gbuffer; + bool append; + }; #ifdef __UCLIBCXX_HAS_WCHAR__ template <> _UCXXEXPORT basic_filebuf >::int_type - basic_filebuf >::overflow(int_type c); + basic_filebuf >::overflow(int_type c); template <> _UCXXEXPORT basic_filebuf >::int_type - basic_filebuf >::underflow(); + basic_filebuf >::underflow(); #endif //__UCLIBCXX_HAS_WCHAR__ +#ifdef __UCLIBCXX_EXPAND_FSTREAM_CHAR__ +#ifndef __UCLIBCXX_COMPILE_FSTREAM__ +#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT filebuf::basic_filebuf(); + template <> _UCXXEXPORT filebuf::~basic_filebuf(); + +#endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ + + template <> _UCXXEXPORT filebuf::int_type filebuf::pbackfail(filebuf::int_type c); + template <> _UCXXEXPORT filebuf * filebuf::open(const char* s, ios_base::openmode mode); + template <> _UCXXEXPORT filebuf * filebuf::close(); + template <> _UCXXEXPORT filebuf::int_type filebuf::overflow(filebuf::int_type c); + template <> _UCXXEXPORT filebuf::int_type filebuf::underflow (); + + template <> _UCXXEXPORT basic_streambuf > * filebuf::setbuf(char * s, streamsize n); + template <> _UCXXEXPORT streamsize filebuf::xsputn(const char* s, streamsize n); + +#endif +#endif + + template class _UCXXEXPORT basic_ifstream + : public basic_istream + { + public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + _UCXXEXPORT basic_ifstream(): basic_ios(&sb), basic_istream(&sb){ + //Passing the address of sb + } + + explicit _UCXXEXPORT basic_ifstream(const char* s, ios_base::openmode mode = ios_base::in) + : basic_ios(&sb), basic_istream(&sb) + { + if (sb.open(s, mode) == 0) + { + basic_ios::setstate(ios_base::failbit); + } + } + + virtual _UCXXEXPORT ~basic_ifstream() + { + } + + _UCXXEXPORT basic_filebuf* rdbuf() const + { + return (basic_filebuf*)&sb; + } + + _UCXXEXPORT bool is_open() const + { + return sb.is_open(); + } + + _UCXXEXPORT void open(const char* s, ios_base::openmode mode = ios_base::in) + { + if (sb.open(s, mode) == 0) + { + basic_ios::setstate(ios_base::failbit); + } + } + + _UCXXEXPORT void close() + { + sb.close(); + } + + private: + basic_filebuf sb; + }; + + template class _UCXXEXPORT basic_ofstream + : public basic_ostream + { + public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + _UCXXEXPORT basic_ofstream() : basic_ios(&sb), basic_ostream(&sb) + { + } + + virtual _UCXXEXPORT ~basic_ofstream(); + + explicit _UCXXEXPORT basic_ofstream(const char* s, ios_base::openmode mode = ios_base::out | ios_base::trunc) : + basic_ios(&sb), basic_ostream(&sb) + { + if (sb.open(s, mode | ios_base::out) == 0) + { + basic_ios::setstate(ios_base::failbit); + } + } + + _UCXXEXPORT basic_filebuf* rdbuf() const + { + return (basic_filebuf*)&sb; + } + + _UCXXEXPORT bool is_open() const + { + return sb.is_open(); + } + + _UCXXEXPORT void open(const char* s, ios_base::openmode mode = ios_base::out | ios_base::trunc) + { + if (sb.open(s, mode) == 0) + { + basic_ios::setstate(ios_base::failbit); + } + } + + _UCXXEXPORT void close() + { + sb.close(); + } + + private: + basic_filebuf sb; + }; + + template _UCXXEXPORT basic_ofstream::~basic_ofstream() + { + basic_ostream::flush(); + } + + template class _UCXXEXPORT basic_fstream + : public basic_iostream + { + public: + typedef charT char_type; + typedef typename traits::int_type ins_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + _UCXXEXPORT basic_fstream(): basic_ios(&sb), basic_iostream(&sb){ } + + explicit _UCXXEXPORT basic_fstream(const char* s, ios_base::openmode mode = ios_base::in|ios_base::out): + basic_ios(&sb), basic_iostream(&sb) + { + if (sb.open(s, mode) == 0) + { + basic_ios::setstate(ios_base::failbit); + } + } + + _UCXXEXPORT basic_filebuf* rdbuf() const + { + return (basic_filebuf*)&sb; + } + + _UCXXEXPORT bool is_open() const + { + return sb.is_open(); + } + + _UCXXEXPORT void open(const char* s, ios_base::openmode mode = ios_base::in|ios_base::out) + { + if (sb.open(s, mode) == 0) + { + basic_ios::setstate(ios_base::failbit); + } + } + + _UCXXEXPORT void close() + { + sb.close(); + } + + private: + basic_filebuf sb; + }; #ifdef __UCLIBCXX_EXPAND_FSTREAM_CHAR__ #ifndef __UCLIBCXX_COMPILE_FSTREAM__ #ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template <> _UCXXEXPORT filebuf::basic_filebuf(); - template <> _UCXXEXPORT filebuf::~basic_filebuf(); + template <> _UCXXEXPORT basic_ofstream >::basic_ofstream(); + template <> _UCXXEXPORT basic_ofstream >::basic_ofstream(const char* s, ios_base::openmode mode); + template <> _UCXXEXPORT basic_ofstream >::~basic_ofstream(); -#endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - - template <> _UCXXEXPORT filebuf::int_type filebuf::pbackfail(filebuf::int_type c); - template <> _UCXXEXPORT filebuf * filebuf::open(const char* s, ios_base::openmode mode); - template <> _UCXXEXPORT filebuf * filebuf::close(); - template <> _UCXXEXPORT filebuf::int_type filebuf::overflow(filebuf::int_type c); - template <> _UCXXEXPORT filebuf::int_type filebuf::underflow (); - - template <> _UCXXEXPORT basic_streambuf > * filebuf::setbuf(char * s, streamsize n); - template <> _UCXXEXPORT streamsize filebuf::xsputn(const char* s, streamsize n); - -#endif -#endif - - - template class _UCXXEXPORT basic_ifstream - : public basic_istream - { - public: - typedef charT char_type; - typedef typename traits::int_type int_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; - - _UCXXEXPORT basic_ifstream(): basic_ios(&sb), basic_istream(&sb){ - //Passing the address of sb - } - explicit _UCXXEXPORT basic_ifstream(const char* s, ios_base::openmode mode = ios_base::in) - : basic_ios(&sb), basic_istream(&sb) - { - if(sb.open(s, mode) == 0){ - basic_ios::setstate(ios_base::failbit); - } - } - - virtual _UCXXEXPORT ~basic_ifstream(){ - - } - - _UCXXEXPORT basic_filebuf* rdbuf() const{ - return (basic_filebuf*)&sb; - } - _UCXXEXPORT bool is_open() const{ - return sb.is_open(); - } - _UCXXEXPORT void open(const char* s, ios_base::openmode mode = ios_base::in){ - if(sb.open(s, mode) == 0){ - basic_ios::setstate(ios_base::failbit); - } - } - _UCXXEXPORT void close(){ - sb.close(); - } - private: - basic_filebuf sb; - }; - - - template class _UCXXEXPORT basic_ofstream - : public basic_ostream - { - public: - typedef charT char_type; - typedef typename traits::int_type int_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; - - _UCXXEXPORT basic_ofstream() : basic_ios(&sb), basic_ostream(&sb){ - - } - - virtual _UCXXEXPORT ~basic_ofstream(); - - explicit _UCXXEXPORT basic_ofstream(const char* s, ios_base::openmode mode = ios_base::out | ios_base::trunc) : - basic_ios(&sb), basic_ostream(&sb) - { - if(sb.open(s, mode | ios_base::out ) == 0){ - basic_ios::setstate(ios_base::failbit); - } - } - - _UCXXEXPORT basic_filebuf* rdbuf() const{ - return (basic_filebuf*)&sb; - } - - _UCXXEXPORT bool is_open() const{ - return sb.is_open(); - } - _UCXXEXPORT void open(const char* s, ios_base::openmode mode = ios_base::out | ios_base::trunc){ - if(sb.open(s, mode) == 0){ - basic_ios::setstate(ios_base::failbit); - } - } - _UCXXEXPORT void close(){ - sb.close(); - } - private: - basic_filebuf sb; - }; - - template _UCXXEXPORT basic_ofstream::~basic_ofstream(){ - basic_ostream::flush(); - } - - - template class _UCXXEXPORT basic_fstream - : public basic_iostream - { - public: - typedef charT char_type; - typedef typename traits::int_type ins_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; - - _UCXXEXPORT basic_fstream(): basic_ios(&sb), basic_iostream(&sb){ } - - explicit _UCXXEXPORT basic_fstream(const char* s, ios_base::openmode mode = ios_base::in|ios_base::out): - basic_ios(&sb), basic_iostream(&sb) - { - if(sb.open(s, mode) == 0){ - basic_ios::setstate(ios_base::failbit); - } - } - - _UCXXEXPORT basic_filebuf* rdbuf() const{ - return (basic_filebuf*)&sb; - } - _UCXXEXPORT bool is_open() const{ - return sb.is_open(); - } - _UCXXEXPORT void open(const char* s, ios_base::openmode mode = ios_base::in|ios_base::out){ - if(sb.open(s, mode) == 0){ - basic_ios::setstate(ios_base::failbit); - } - } - _UCXXEXPORT void close(){ - sb.close(); - } - private: - basic_filebuf sb; - }; - - - -#ifdef __UCLIBCXX_EXPAND_FSTREAM_CHAR__ -#ifndef __UCLIBCXX_COMPILE_FSTREAM__ - -#ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - - template <> _UCXXEXPORT basic_ofstream >::basic_ofstream(); - template <> _UCXXEXPORT basic_ofstream >::basic_ofstream(const char* s, ios_base::openmode mode); - template <> _UCXXEXPORT basic_ofstream >::~basic_ofstream(); - - template <> _UCXXEXPORT basic_ifstream >::basic_ifstream(); - template <> _UCXXEXPORT basic_ifstream >::basic_ifstream(const char* s, ios_base::openmode mode); - template <> _UCXXEXPORT basic_ifstream >::~basic_ifstream(); + template <> _UCXXEXPORT basic_ifstream >::basic_ifstream(); + template <> _UCXXEXPORT basic_ifstream >::basic_ifstream(const char* s, ios_base::openmode mode); + template <> _UCXXEXPORT basic_ifstream >::~basic_ifstream(); #endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ #endif #endif - - -} +} // namespace +} // exteren "C++" #pragma GCC visibility pop #endif - diff --git a/misc/uClibc++/include/uClibc++/functional b/misc/uClibc++/include/uClibc++/functional index b7932e2cf9..e11e9f3166 100644 --- a/misc/uClibc++/include/uClibc++/functional +++ b/misc/uClibc++/include/uClibc++/functional @@ -1,20 +1,20 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #ifndef __STD_HEADER_FUNCTIONAL #define __STD_HEADER_FUNCTIONAL 1 @@ -23,414 +23,466 @@ #pragma GCC visibility push(default) -namespace std{ - - template struct unary_function; - template struct binary_function; - - template struct plus; - template struct minus; - template struct multiplies; - template struct divides; - template struct modulus; - template struct negate; - - template struct equal_to; - template struct not_equal_to; - template struct greater; - template struct less; - template struct greater_equal; - template struct less_equal; - - template struct logical_and; - template struct logical_or; - template struct logical_not; - - template struct unary_negate; - template unary_negate not1(const Predicate&); - template struct binary_negate; - template binary_negate not2(const Predicate&); - - - template class binder1st; - template binder1st bind1st(const Operation&, const T&); - template class binder2nd; - template binder2nd bind2nd(const Operation&, const T&); - - template class pointer_to_unary_function; - template pointer_to_unary_function ptr_fun(Result (*)(Arg)); - template class pointer_to_binary_function; - template - pointer_to_binary_function ptr_fun(Result (*)(Arg1,Arg2)); - - template class mem_fun_t; - template class mem_fun1_t; - template class const_mem_fun_t; - template class const_mem_fun1_t; - template mem_fun_t mem_fun(S (T::*f)()); - template mem_fun1_t mem_fun(S (T::*f)(A)); - template class mem_fun_ref_t; - template class mem_fun1_ref_t; - template mem_fun_ref_t mem_fun_ref(S (T::*f)()); - template mem_fun1_ref_t mem_fun1_ref(S (T::*f)(A)); - - //Implementation - - template struct _UCXXEXPORT unary_function{ - typedef Arg argument_type; - typedef Result result_type; - }; - - - template struct _UCXXEXPORT binary_function{ - typedef Arg1 first_argument_type; - typedef Arg2 second_argument_type; - typedef Result result_type; - }; - - template struct _UCXXEXPORT plus : binary_function{ - T operator()(const T& x, const T& y) const{ - return x + y; - } - }; - - template struct _UCXXEXPORT minus : binary_function{ - T operator()(const T& x, const T& y) const{ - return x - y; - } - }; - - template struct _UCXXEXPORT multiplies : binary_function{ - T operator()(const T& x, const T& y) const{ - return x * y; - } - }; - - template struct _UCXXEXPORT divides : binary_function{ - T operator()(const T& x, const T& y) const{ - return x / y; - } - }; - - template struct _UCXXEXPORT modulus : binary_function{ - T operator()(const T& x, const T& y) const{ - return x % y; - } - }; - - template struct _UCXXEXPORT negate : unary_function{ - T operator()(const T& x) const{ - return -x; - } - }; - - template struct _UCXXEXPORT equal_to : binary_function{ - bool operator()(const T& x, const T& y) const{ - return (x == y); - } - }; - - template struct _UCXXEXPORT not_equal_to : binary_function{ - bool operator()(const T& x, const T& y) const{ - return (x != y); - } - }; - - template struct _UCXXEXPORT greater : binary_function{ - bool operator()(const T& x, const T& y) const{ - return (x > y); - } - }; - - template struct _UCXXEXPORT less : binary_function{ - bool operator()(const T& x, const T& y) const{ - return (x < y); - } - }; - - template struct _UCXXEXPORT greater_equal : binary_function{ - bool operator()(const T& x, const T& y) const{ - return (x >= y); - } - }; - - template struct _UCXXEXPORT less_equal : binary_function{ - bool operator()(const T& x, const T& y) const{ - return (x <= y); - } - }; - - template struct _UCXXEXPORT logical_and : binary_function { - bool operator()(const T& x, const T& y) const{ - return (x && y); - } - }; - - template struct _UCXXEXPORT logical_or : binary_function { - bool operator()(const T& x, const T& y) const{ - return (x || y); - } - }; - - template struct _UCXXEXPORT logical_not : unary_function { - bool operator()(const T& x) const{ - return !x; - } - }; - - template class _UCXXEXPORT unary_negate - : public unary_function - { - public: - explicit unary_negate(const Predicate& pred) : p(pred) { } - bool operator()(const typename Predicate::argument_type& x) const{ - return !p(x); - } - private: - Predicate p; - }; - - - template _UCXXEXPORT unary_negate not1(const Predicate& pred){ - return unary_negate(pred); - } - - - template class _UCXXEXPORT binary_negate : public - binary_function - { - public: - explicit binary_negate(const Predicate& pred) : p(pred) { } - bool operator()(const typename Predicate::first_argument_type& x, - const typename Predicate::second_argument_type& y) const - { - return !p(x, y); - } - private: - Predicate p; - }; - - - template _UCXXEXPORT binary_negate not2(const Predicate& pred){ - return binary_negate(pred); - } - - - template class _UCXXEXPORT binder1st - : public unary_function - { - protected: - Operation op; - typename Operation::first_argument_type value; - public: - binder1st(const Operation& x, const typename Operation::first_argument_type& y) : op(x), value(y){ } - typename Operation::result_type operator()(const typename Operation::second_argument_type& x) const{ - return op(value,x); - } - }; - - - template _UCXXEXPORT binder1st bind1st(const Operation& op, const T& x){ - return binder1st(op, typename Operation::first_argument_type(x)); - } - - - template class _UCXXEXPORT binder2nd - : public unary_function - { - protected: - Operation op; - typename Operation::second_argument_type value; - public: - binder2nd(const Operation& x, const typename Operation::second_argument_type& y) : op(x), value(y) { } - typename Operation::result_type operator()(const typename Operation::first_argument_type& x) const{ - return op(x,value); - } - }; - - - template _UCXXEXPORT - binder2nd bind2nd(const Operation& op, const T& x) - { - return binder2nd(op, typename Operation::second_argument_type(x)); - } - - - template class _UCXXEXPORT - pointer_to_unary_function : public unary_function - { - protected: - Result (*func)(Arg); - public: - explicit pointer_to_unary_function(Result (*f)(Arg)) : func(f) { } - Result operator()(Arg x) const{ - return func(x); - } - }; - - - template _UCXXEXPORT pointer_to_unary_function ptr_fun(Result (*f)(Arg)){ - return pointer_to_unary_function(f); - } - - - template class _UCXXEXPORT - pointer_to_binary_function : public binary_function - { - protected: - Result (*func)(Arg1, Arg2); - public: - explicit pointer_to_binary_function(Result (*f)(Arg1, Arg2)) : func(f) { } - Result operator()(Arg1 x, Arg2 y) const{ - return func(x, y); - } - }; - - template _UCXXEXPORT - pointer_to_binary_function ptr_fun(Result (*f)(Arg1, Arg2)) - { - return pointer_to_binary_function(f); - } - - - template class _UCXXEXPORT mem_fun_t - : public unary_function - { - public: - explicit mem_fun_t(S (T::*p)()) : m(p) { } - S operator()(T* p) const { return (p->*m)(); } - private: - S (T::*m)(); - }; - - - template class _UCXXEXPORT mem_fun1_t - : public binary_function - { - public: - explicit mem_fun1_t(S (T::*p)(A)) : m(p) { } - S operator()(T* p, A x) const { return (p->*m)(x); } - private: - S (T::*m)(A); - }; - - - template class _UCXXEXPORT const_mem_fun_t - : public unary_function - { - public: - explicit const_mem_fun_t(S (T::*p)() const) : m(p) { } - S operator()(const T* p) const { return (p->*m)(); } - private: - S (T::*m)() const; - }; - - - template class _UCXXEXPORT const_mem_fun1_t - : public binary_function - { - public: - explicit const_mem_fun1_t(S (T::*p)(A) const) : m(p) { } - S operator()(const T* p, A x) const { return (p->*m)(x); } - private: - S (T::*m)(A) const; - }; - - - template _UCXXEXPORT mem_fun_t mem_fun(S (T::*f)()){ - return mem_fun_t(f); - } - - template _UCXXEXPORT const_mem_fun_t mem_fun(S (T::*f)() const){ - return const_mem_fun_t(f); - } - - template _UCXXEXPORT mem_fun1_t mem_fun(S (T::*f)(A)){ - return mem_fun1_t(f); - } - - template _UCXXEXPORT const_mem_fun1_t mem_fun(S (T::*f)(A) const){ - return const_mem_fun1_t(f); - } - - template class _UCXXEXPORT mem_fun_ref_t - : public unary_function - { - public: - explicit mem_fun_ref_t(S (T::*p)()) : mf(p) { } - S operator()(T& p) { return (p.*mf)(); } - private: - S (T::*mf)(); - }; - - template class _UCXXEXPORT mem_fun1_ref_t - : public binary_function - { - public: - explicit mem_fun1_ref_t(S (T::*p)(A)) : mf(p) { } - S operator()(T& p, A x) { return (p.*mf)(x); } - private: - S (T::*mf)(A); - }; - - template _UCXXEXPORT mem_fun_ref_t mem_fun_ref(S (T::*f)()){ - return mem_fun_ref_t(f); - } - - template _UCXXEXPORT mem_fun1_ref_t mem_fun1_ref(S (T::*f)(A)){ - return mem_fun1_ref_t(f); - } - - -} - - -//These are SGI extensions which are checked for by some conformance checks. They +extern "C++" +{ + +namespace std +{ + + template struct unary_function; + template struct binary_function; + + template struct plus; + template struct minus; + template struct multiplies; + template struct divides; + template struct modulus; + template struct negate; + + template struct equal_to; + template struct not_equal_to; + template struct greater; + template struct less; + template struct greater_equal; + template struct less_equal; + + template struct logical_and; + template struct logical_or; + template struct logical_not; + + template struct unary_negate; + template unary_negate not1(const Predicate&); + template struct binary_negate; + template binary_negate not2(const Predicate&); + + template class binder1st; + template binder1st bind1st(const Operation&, const T&); + template class binder2nd; + template binder2nd bind2nd(const Operation&, const T&); + + template class pointer_to_unary_function; + template pointer_to_unary_function ptr_fun(Result (*)(Arg)); + template class pointer_to_binary_function; + template + pointer_to_binary_function ptr_fun(Result (*)(Arg1,Arg2)); + + template class mem_fun_t; + template class mem_fun1_t; + template class const_mem_fun_t; + template class const_mem_fun1_t; + template mem_fun_t mem_fun(S (T::*f)()); + template mem_fun1_t mem_fun(S (T::*f)(A)); + template class mem_fun_ref_t; + template class mem_fun1_ref_t; + template mem_fun_ref_t mem_fun_ref(S (T::*f)()); + template mem_fun1_ref_t mem_fun1_ref(S (T::*f)(A)); + + // Implementation + + template struct _UCXXEXPORT unary_function + { + typedef Arg argument_type; + typedef Result result_type; + }; + + template struct _UCXXEXPORT binary_function + { + typedef Arg1 first_argument_type; + typedef Arg2 second_argument_type; + typedef Result result_type; + }; + + template struct _UCXXEXPORT plus : binary_function + { + T operator()(const T& x, const T& y) const{ + return x + y; + } + }; + + template struct _UCXXEXPORT minus : binary_function + { + T operator()(const T& x, const T& y) const + { + return x - y; + } + }; + + template struct _UCXXEXPORT multiplies : binary_function + { + T operator()(const T& x, const T& y) const{ + return x * y; + } + }; + + template struct _UCXXEXPORT divides : binary_function + { + T operator()(const T& x, const T& y) const{ + return x / y; + } + }; + + template struct _UCXXEXPORT modulus : binary_function + { + T operator()(const T& x, const T& y) const + { + return x % y; + } + }; + + template struct _UCXXEXPORT negate : unary_function + { + T operator()(const T& x) const{ + return -x; + } + }; + + template struct _UCXXEXPORT equal_to : binary_function + { + bool operator()(const T& x, const T& y) const + { + return (x == y); + } + }; + + template struct _UCXXEXPORT not_equal_to : binary_function + { + bool operator()(const T& x, const T& y) const + { + return (x != y); + } + }; + + template struct _UCXXEXPORT greater : binary_function + { + bool operator()(const T& x, const T& y) const + { + return (x > y); + } + }; + + template struct _UCXXEXPORT less : binary_function + { + bool operator()(const T& x, const T& y) const + { + return (x < y); + } + }; + + template struct _UCXXEXPORT greater_equal : binary_function + { + bool operator()(const T& x, const T& y) const + { + return (x >= y); + } + }; + + template struct _UCXXEXPORT less_equal : binary_function + { + bool operator()(const T& x, const T& y) const + { + return (x <= y); + } + }; + + template struct _UCXXEXPORT logical_and : binary_function + { + bool operator()(const T& x, const T& y) const + { + return (x && y); + } + }; + + template struct _UCXXEXPORT logical_or : binary_function + { + bool operator()(const T& x, const T& y) const + { + return (x || y); + } + }; + + template struct _UCXXEXPORT logical_not : unary_function + { + bool operator()(const T& x) const + { + return !x; + } + }; + + template class _UCXXEXPORT unary_negate + : public unary_function + { + public: + explicit unary_negate(const Predicate& pred) : p(pred) { } + + bool operator()(const typename Predicate::argument_type& x) const + { + return !p(x); + } + + private: + Predicate p; + }; + + template _UCXXEXPORT unary_negate not1(const Predicate& pred) + { + return unary_negate(pred); + } + + template class _UCXXEXPORT binary_negate : public + binary_function + { + public: + explicit binary_negate(const Predicate& pred) : p(pred) { } + + bool operator()(const typename Predicate::first_argument_type& x, + const typename Predicate::second_argument_type& y) const + { + return !p(x, y); + } + + private: + Predicate p; + }; + + template _UCXXEXPORT binary_negate not2(const Predicate& pred){ + return binary_negate(pred); + } + + template class _UCXXEXPORT binder1st + : public unary_function + { + protected: + Operation op; + typename Operation::first_argument_type value; + public: + binder1st(const Operation& x, const typename Operation::first_argument_type& y) : op(x), value(y){ } + + typename Operation::result_type operator()(const typename Operation::second_argument_type& x) const + { + return op(value,x); + } + }; + + template _UCXXEXPORT binder1st bind1st(const Operation& op, const T& x) + { + return binder1st(op, typename Operation::first_argument_type(x)); + } + + template class _UCXXEXPORT binder2nd + : public unary_function + { + protected: + Operation op; + typename Operation::second_argument_type value; + public: + binder2nd(const Operation& x, const typename Operation::second_argument_type& y) : op(x), value(y) { } + + typename Operation::result_type operator()(const typename Operation::first_argument_type& x) const + { + return op(x,value); + } + }; + + template _UCXXEXPORT + binder2nd bind2nd(const Operation& op, const T& x) + { + return binder2nd(op, typename Operation::second_argument_type(x)); + } + + template class _UCXXEXPORT + pointer_to_unary_function : public unary_function + { + protected: + Result (*func)(Arg); + public: + explicit pointer_to_unary_function(Result (*f)(Arg)) : func(f) { } + + Result operator()(Arg x) const + { + return func(x); + } + }; + + template _UCXXEXPORT pointer_to_unary_function ptr_fun(Result (*f)(Arg)) + { + return pointer_to_unary_function(f); + } + + template class _UCXXEXPORT + pointer_to_binary_function : public binary_function + { + protected: + Result (*func)(Arg1, Arg2); + + public: + explicit pointer_to_binary_function(Result (*f)(Arg1, Arg2)) : func(f) { } + + Result operator()(Arg1 x, Arg2 y) const + { + return func(x, y); + } + }; + + template _UCXXEXPORT + pointer_to_binary_function ptr_fun(Result (*f)(Arg1, Arg2)) + { + return pointer_to_binary_function(f); + } + + template class _UCXXEXPORT mem_fun_t + : public unary_function + { + public: + explicit mem_fun_t(S (T::*p)()) : m(p) { } + S operator()(T* p) const { return (p->*m)(); } + + private: + S (T::*m)(); + }; + + template class _UCXXEXPORT mem_fun1_t + : public binary_function + { + public: + explicit mem_fun1_t(S (T::*p)(A)) : m(p) { } + S operator()(T* p, A x) const { return (p->*m)(x); } + private: + S (T::*m)(A); + }; + + template class _UCXXEXPORT const_mem_fun_t + : public unary_function + { + public: + explicit const_mem_fun_t(S (T::*p)() const) : m(p) { } + S operator()(const T* p) const { return (p->*m)(); } + + private: + S (T::*m)() const; + }; + + template class _UCXXEXPORT const_mem_fun1_t + : public binary_function + { + public: + explicit const_mem_fun1_t(S (T::*p)(A) const) : m(p) { } + S operator()(const T* p, A x) const { return (p->*m)(x); } + + private: + S (T::*m)(A) const; + }; + + template _UCXXEXPORT mem_fun_t mem_fun(S (T::*f)()) + { + return mem_fun_t(f); + } + + template _UCXXEXPORT const_mem_fun_t mem_fun(S (T::*f)() const) + { + return const_mem_fun_t(f); + } + + template _UCXXEXPORT mem_fun1_t mem_fun(S (T::*f)(A)) + { + return mem_fun1_t(f); + } + + template _UCXXEXPORT const_mem_fun1_t mem_fun(S (T::*f)(A) const) + { + return const_mem_fun1_t(f); + } + + template class _UCXXEXPORT mem_fun_ref_t + : public unary_function + { + public: + explicit mem_fun_ref_t(S (T::*p)()) : mf(p) { } + S operator()(T& p) { return (p.*mf)(); } + + private: + S (T::*mf)(); + }; + + template class _UCXXEXPORT mem_fun1_ref_t + : public binary_function + { + public: + explicit mem_fun1_ref_t(S (T::*p)(A)) : mf(p) { } + S operator()(T& p, A x) { return (p.*mf)(x); } + + private: + S (T::*mf)(A); + }; + + template _UCXXEXPORT mem_fun_ref_t mem_fun_ref(S (T::*f)()) + { + return mem_fun_ref_t(f); + } + + template _UCXXEXPORT mem_fun1_ref_t mem_fun1_ref(S (T::*f)(A)) + { + return mem_fun1_ref_t(f); + } + +} // namespace + +// These are SGI extensions which are checked for by some conformance checks. They // are *NOT* part of the C++ standard, however template class _UCXXEXPORT unary_compose : - public std::unary_function + public std::unary_function { protected: - Op1 mf1; - Op2 mf2; + Op1 mf1; + Op2 mf2; + public: - unary_compose(const Op1& x, const Op2& y) : mf1(x), mf2(y) { } - typename Op1::result_type operator()(const typename Op2::argument_type& x) const { - return mf1(mf2(x)); - } + unary_compose(const Op1& x, const Op2& y) : mf1(x), mf2(y) { } + + typename Op1::result_type operator()(const typename Op2::argument_type& x) const + { + return mf1(mf2(x)); + } }; template _UCXXEXPORT inline unary_compose -compose1(const Op1& fn1, const Op2& fn2){ - return unary_compose(fn1, fn2); +compose1(const Op1& fn1, const Op2& fn2) +{ + return unary_compose(fn1, fn2); } template class _UCXXEXPORT binary_compose : - public std::unary_function + public std::unary_function { protected: - Op1 mf1; - Op2 mf2; - Op3 mf3; + Op1 mf1; + Op2 mf2; + Op3 mf3; + public: - binary_compose(const Op1 & x, const Op2 & y, const Op3 & z) - : mf1(x), mf2(y), mf3(z){ } - typename Op1::result_type operator()(const typename Op2::argument_type & x) const { - return mf1(mf2(x), mf3(x)); - } + binary_compose(const Op1 & x, const Op2 & y, const Op3 & z) + : mf1(x), mf2(y), mf3(z){ } + + typename Op1::result_type operator()(const typename Op2::argument_type & x) const + { + return mf1(mf2(x), mf3(x)); + } }; template inline _UCXXEXPORT binary_compose -compose2(const Op1 & fn1, const Op2 & fn2, const Op3 & fn3){ - return binary_compose(fn1, fn2, fn3); + +compose2(const Op1 & fn1, const Op2 & fn2, const Op3 & fn3) +{ + return binary_compose(fn1, fn2, fn3); } +} // extern "C++" + #pragma GCC visibility pop #endif diff --git a/misc/uClibc++/include/uClibc++/iomanip b/misc/uClibc++/include/uClibc++/iomanip index 14a82607c1..82125268a6 100644 --- a/misc/uClibc++/include/uClibc++/iomanip +++ b/misc/uClibc++/include/uClibc++/iomanip @@ -1,21 +1,21 @@ -/* Copyright (C) 2005 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2005 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -25,144 +25,157 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ // These are the helper classes which we are going to be using to // hold the required data -class _UCXXEXPORT __resetiosflags{ +class _UCXXEXPORT __resetiosflags +{ public: - ios_base::fmtflags m; - _UCXXEXPORT __resetiosflags(ios_base::fmtflags mask) : m(mask){ } + ios_base::fmtflags m; + _UCXXEXPORT __resetiosflags(ios_base::fmtflags mask) : m(mask){ } }; -class _UCXXEXPORT __setiosflags{ +class _UCXXEXPORT __setiosflags +{ public: - ios_base::fmtflags m; - _UCXXEXPORT __setiosflags(ios_base::fmtflags mask) : m(mask){ } + ios_base::fmtflags m; + _UCXXEXPORT __setiosflags(ios_base::fmtflags mask) : m(mask){ } }; -class _UCXXEXPORT __setbase{ +class _UCXXEXPORT __setbase +{ public: - int base; - _UCXXEXPORT __setbase(int b) : base(b){ } + int base; + _UCXXEXPORT __setbase(int b) : base(b){ } }; -class _UCXXEXPORT __setfill{ +class _UCXXEXPORT __setfill +{ public: - int character; - _UCXXEXPORT __setfill(int c): character(c){ } + int character; + _UCXXEXPORT __setfill(int c): character(c){ } }; -class _UCXXEXPORT __setprecision{ +class _UCXXEXPORT __setprecision +{ public: - int digits; - _UCXXEXPORT __setprecision(int n): digits(n) { } + int digits; + _UCXXEXPORT __setprecision(int n): digits(n) { } }; -class _UCXXEXPORT __setw{ +class _UCXXEXPORT __setw +{ public: - int width; - _UCXXEXPORT __setw(int n): width(n) { } + int width; + _UCXXEXPORT __setw(int n): width(n) { } }; +// Actual manipulator functions -//Actual manipulator functions - -inline __resetiosflags resetiosflags(ios_base::fmtflags mask){ - return __resetiosflags(mask); +inline __resetiosflags resetiosflags(ios_base::fmtflags mask) +{ + return __resetiosflags(mask); } -inline __setiosflags setiosflags(ios_base::fmtflags mask){ - return __setiosflags(mask); +inline __setiosflags setiosflags(ios_base::fmtflags mask) +{ + return __setiosflags(mask); } -inline __setbase setbase(int b){ - return __setbase(b); +inline __setbase setbase(int b) +{ + return __setbase(b); } -inline __setfill setfill(int c){ - return __setfill(c); +inline __setfill setfill(int c) +{ + return __setfill(c); } -inline __setprecision setprecision(int n){ - return __setprecision(n); +inline __setprecision setprecision(int n) +{ + return __setprecision(n); } -inline __setw setw(int n){ - return __setw(n); +inline __setw setw(int n) +{ + return __setw(n); } - -//How to handle interaction with [i|o]stream classes +// How to handle interaction with [i|o]stream classes template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, const __resetiosflags s) + operator<<(basic_ostream& os, const __resetiosflags s) { - os.setf(ios_base::fmtflags(0),s.m); - return os; + os.setf(ios_base::fmtflags(0),s.m); + return os; } template _UCXXEXPORT basic_istream& - operator>>(basic_istream& is, const __resetiosflags s) + operator>>(basic_istream& is, const __resetiosflags s) { - is.setf(ios_base::fmtflags(0),s.m); - return is; + is.setf(ios_base::fmtflags(0),s.m); + return is; } template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, const __setiosflags s) + operator<<(basic_ostream& os, const __setiosflags s) { - os.setf(s.m); - return os; + os.setf(s.m); + return os; } template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, const __setbase s) + operator<<(basic_ostream& os, const __setbase s) { - ios_base::fmtflags f(0); - switch(s.base){ - case 8: - f = ios_base::oct; - break; - case 10: - f = ios_base::dec; - break; - case 16: - f = ios_base::hex; - break; - default: - break; + ios_base::fmtflags f(0); + switch(s.base) + { + case 8: + f = ios_base::oct; + break; + case 10: + f = ios_base::dec; + break; + case 16: + f = ios_base::hex; + break; + default: + break; + } - } - os.setf(f, ios_base::basefield); - return os; + os.setf(f, ios_base::basefield); + return os; } template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, const __setfill s) + operator<<(basic_ostream& os, const __setfill s) { - os.fill(s.character); - return os; + os.fill(s.character); + return os; } template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, const __setprecision s) + operator<<(basic_ostream& os, const __setprecision s) { - os.precision(s.digits); - return os; + os.precision(s.digits); + return os; } template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, const __setw s) + operator<<(basic_ostream& os, const __setw s) { - os.width(s.width); - return os; + os.width(s.width); + return os; } - - -} +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/ios b/misc/uClibc++/include/uClibc++/ios index 2af1a14cb2..6b49921ed8 100644 --- a/misc/uClibc++/include/uClibc++/ios +++ b/misc/uClibc++/include/uClibc++/ios @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -27,472 +27,583 @@ #pragma GCC visibility push(default) -namespace std{ - typedef signed long int streamoff; +extern "C++" +{ +namespace std +{ + typedef signed long int streamoff; - template class fpos; + template class fpos; - class _UCXXEXPORT ios_base { - public: - class failure; + class _UCXXEXPORT ios_base + { + public: + class failure; #ifdef CONFIG_UCLIBCXX_EXCEPTION - class failure : public exception { - public: - explicit failure(const std::string&) { } - explicit failure() { } - virtual const char* what() const throw() { - return "std::ios_base failure exception"; - } - }; + class failure : public exception + { + public: + explicit failure(const std::string&) { } + explicit failure() { } + virtual const char* what() const throw() { + return "std::ios_base failure exception"; + } + }; #endif #ifdef __UCLIBCXX_SUPPORT_CDIR__ - class _UCXXLOCAL Init{ - public: - _UCXXEXPORT Init(); - _UCXXEXPORT ~Init(); - private: - static int init_cnt; - }; + class _UCXXLOCAL Init + { + public: + _UCXXEXPORT Init(); + _UCXXEXPORT ~Init(); + private: + static int init_cnt; + }; #endif - public: + public: - typedef unsigned short int fmtflags; + typedef unsigned short int fmtflags; - static const fmtflags skipws = 0x0001; + static const fmtflags skipws = 0x0001; - static const fmtflags left = 0x0002; - static const fmtflags right = 0x0004; - static const fmtflags internal = 0x0008; + static const fmtflags left = 0x0002; + static const fmtflags right = 0x0004; + static const fmtflags internal = 0x0008; - static const fmtflags boolalpha = 0x0010; + static const fmtflags boolalpha = 0x0010; - static const fmtflags dec = 0x0020; - static const fmtflags oct = 0x0040; - static const fmtflags hex = 0x0080; + static const fmtflags dec = 0x0020; + static const fmtflags oct = 0x0040; + static const fmtflags hex = 0x0080; - static const fmtflags scientific = 0x0100; - static const fmtflags fixed = 0x0200; + static const fmtflags scientific = 0x0100; + static const fmtflags fixed = 0x0200; - static const fmtflags showbase = 0x0400; - static const fmtflags showpoint = 0x0800; - static const fmtflags showpos = 0x1000; - static const fmtflags uppercase = 0x2000; + static const fmtflags showbase = 0x0400; + static const fmtflags showpoint = 0x0800; + static const fmtflags showpos = 0x1000; + static const fmtflags uppercase = 0x2000; - static const fmtflags adjustfield = left | right | internal; - static const fmtflags basefield = dec | oct | hex; - static const fmtflags floatfield = fixed | scientific; + static const fmtflags adjustfield = left | right | internal; + static const fmtflags basefield = dec | oct | hex; + static const fmtflags floatfield = fixed | scientific; - static const fmtflags unitbuf = 0x4000; + static const fmtflags unitbuf = 0x4000; - typedef unsigned char iostate; - static const iostate goodbit = 0x00; - static const iostate badbit = 0x01; - static const iostate eofbit = 0x02; - static const iostate failbit = 0x04; + typedef unsigned char iostate; + static const iostate goodbit = 0x00; + static const iostate badbit = 0x01; + static const iostate eofbit = 0x02; + static const iostate failbit = 0x04; - typedef unsigned char openmode; - static const openmode app = 0x01; - static const openmode ate = 0x02; - static const openmode binary = 0x04; - static const openmode in = 0x08; - static const openmode out = 0x10; - static const openmode trunc = 0x20; + typedef unsigned char openmode; + static const openmode app = 0x01; + static const openmode ate = 0x02; + static const openmode binary = 0x04; + static const openmode in = 0x08; + static const openmode out = 0x10; + static const openmode trunc = 0x20; - typedef unsigned char seekdir; - static const seekdir beg = 0x01; - static const seekdir cur = 0x02; - static const seekdir end = 0x04; + typedef unsigned char seekdir; + static const seekdir beg = 0x01; + static const seekdir cur = 0x02; + static const seekdir end = 0x04; - _UCXXEXPORT fmtflags flags() const{ - return mformat; - } - _UCXXEXPORT fmtflags flags(fmtflags fmtfl); + _UCXXEXPORT fmtflags flags() const + { + return mformat; + } - fmtflags setf(fmtflags fmtfl); - fmtflags setf(fmtflags fmtfl, fmtflags mask ); + _UCXXEXPORT fmtflags flags(fmtflags fmtfl); - _UCXXEXPORT void unsetf(fmtflags mask){ - mformat&= ~mask; - } + fmtflags setf(fmtflags fmtfl); + fmtflags setf(fmtflags fmtfl, fmtflags mask); - _UCXXEXPORT streamsize precision() const{ - return mprecision; - } + _UCXXEXPORT void unsetf(fmtflags mask) + { + mformat&= ~mask; + } - _UCXXEXPORT streamsize precision(streamsize prec); + _UCXXEXPORT streamsize precision() const + { + return mprecision; + } - _UCXXEXPORT streamsize width() const{ - return mwidth; - } + _UCXXEXPORT streamsize precision(streamsize prec); - _UCXXEXPORT streamsize width(streamsize wide); + _UCXXEXPORT streamsize width() const + { + return mwidth; + } - _UCXXEXPORT locale imbue(const locale& loc); + _UCXXEXPORT streamsize width(streamsize wide); - _UCXXEXPORT locale getloc() const{ - return mLocale; - } + _UCXXEXPORT locale imbue(const locale& loc); -// FIXME - These need to be implemented -// static int xalloc(); -// long& iword(int index); -// void*& pword(int index); + _UCXXEXPORT locale getloc() const + { + return mLocale; + } - _UCXXEXPORT ~ios_base() { } +// FIXME - These need to be implemented +// static int xalloc(); +// long& iword(int index); +// void*& pword(int index); - enum event { erase_event, imbue_event, copyfmt_event }; + _UCXXEXPORT ~ios_base() { } - typedef void (*event_callback)(event, ios_base&, int index); -// void register_callback(event_call_back fn, int index); + enum event { erase_event, imbue_event, copyfmt_event }; - //We are going to wrap stdio so we don't need implementation of the following: - inline static bool sync_with_stdio(bool = true) { return true; } + typedef void (*event_callback)(event, ios_base&, int index); +// void register_callback(event_call_back fn, int index); - protected: - _UCXXEXPORT ios_base() : mLocale(), mformat(dec | skipws ), mstate(goodbit), - mmode(), mdir(), mprecision(6), mwidth(0) + //We are going to wrap stdio so we don't need implementation of the following: + inline static bool sync_with_stdio(bool = true) { return true; } + + protected: + _UCXXEXPORT ios_base() : mLocale(), mformat(dec | skipws), mstate(goodbit), + mmode(), mdir(), mprecision(6), mwidth(0) #ifdef __UCLIBCXX_SUPPORT_CDIR__ - ,mInit() + ,mInit() #endif - { + { - } - locale mLocale; - fmtflags mformat; - iostate mstate; - openmode mmode; - seekdir mdir; - streamsize mprecision; - streamsize mwidth; + } + locale mLocale; + fmtflags mformat; + iostate mstate; + openmode mmode; + seekdir mdir; + streamsize mprecision; + streamsize mwidth; #ifdef __UCLIBCXX_SUPPORT_CDIR__ - Init mInit; + Init mInit; #endif - }; + }; + // ios_base manipulators - //ios_base manipulators + inline ios_base& boolalpha(ios_base& str) + { + str.setf(ios_base::boolalpha); + return str; + } + inline ios_base& noboolalpha(ios_base& str) + { + str.unsetf(ios_base::boolalpha); + return str; + } - inline ios_base& boolalpha (ios_base& str){ - str.setf(ios_base::boolalpha); - return str; - } - inline ios_base& noboolalpha(ios_base& str){ - str.unsetf(ios_base::boolalpha); - return str; - } - inline ios_base& showbase (ios_base& str){ - str.setf(ios_base::showbase); - return str; - } - inline ios_base& noshowbase (ios_base& str){ - str.unsetf(ios_base::showbase); - return str; - } - inline ios_base& showpoint (ios_base& str){ - str.setf(ios_base::showpoint); - return str; - } - inline ios_base& noshowpoint(ios_base& str){ - str.unsetf(ios_base::showpoint); - return str; - } - inline ios_base& showpos (ios_base& str){ - str.setf(ios_base::showpos); - return str; - } - inline ios_base& noshowpos (ios_base& str){ - str.unsetf(ios_base::showpos); - return str; - } - inline ios_base& skipws (ios_base& str){ - str.setf(ios_base::skipws); - return str; - } - inline ios_base& noskipws (ios_base& str){ - str.unsetf(ios_base::skipws); - return str; - } - inline ios_base& uppercase (ios_base& str){ - str.setf(ios_base::uppercase); - return str; - } - inline ios_base& nouppercase(ios_base& str){ - str.unsetf(ios_base::uppercase); - return str; - } + inline ios_base& showbase(ios_base& str){ + str.setf(ios_base::showbase); + return str; + } - inline ios_base& unitbuf (ios_base& str){ - str.setf(ios_base::unitbuf); - return str; - } - inline ios_base& nounitbuf (ios_base& str){ - str.unsetf(ios_base::unitbuf); - return str; - } - inline ios_base& internal (ios_base& str){ - str.setf(ios_base::internal, ios_base::adjustfield); - return str; - } - inline ios_base& left (ios_base& str){ - str.setf(ios_base::left, ios_base::adjustfield); - return str; - } - inline ios_base& right (ios_base& str){ - str.setf(ios_base::right, ios_base::adjustfield); - return str; - } + inline ios_base& noshowbase(ios_base& str) + { + str.unsetf(ios_base::showbase); + return str; + } - inline ios_base& dec (ios_base& str){ - str.setf(ios_base::dec, ios_base::basefield); - return str; - } - inline ios_base& hex (ios_base& str){ - str.setf(ios_base::hex, ios_base::basefield); - return str; - } - inline ios_base& oct (ios_base& str){ - str.setf(ios_base::oct, ios_base::basefield); - return str; - } + inline ios_base& showpoint(ios_base& str) + { + str.setf(ios_base::showpoint); + return str; + } - inline ios_base& fixed (ios_base& str){ - str.setf(ios_base::fixed, ios_base::floatfield); - return str; - } - inline ios_base& scientific (ios_base& str){ - str.setf(ios_base::scientific, ios_base::floatfield); - return str; - } + inline ios_base& noshowpoint(ios_base& str) + { + str.unsetf(ios_base::showpoint); + return str; + } + inline ios_base& showpos(ios_base& str) + { + str.setf(ios_base::showpos); + return str; + } - //basic_ios class definition + inline ios_base& noshowpos(ios_base& str) + { + str.unsetf(ios_base::showpos); + return str; + } + inline ios_base& skipws(ios_base& str) + { + str.setf(ios_base::skipws); + return str; + } - template class _UCXXEXPORT basic_ios - : public ios_base - { - public: - // Types: - typedef charT char_type; - typedef typename traits::int_type int_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; - typedef traits traits_type; + inline ios_base& noskipws(ios_base& str) + { + str.unsetf(ios_base::skipws); + return str; + } - _UCXXEXPORT operator void*() const{ - if(fail() ){ - return 0; - } - return (void *)(1); //Must return a non-NULL pointer (though it can be *any* pointer) - } + inline ios_base& uppercase(ios_base& str) + { + str.setf(ios_base::uppercase); + return str; + } - _UCXXEXPORT bool operator!() const{ - return fail(); - } - _UCXXEXPORT iostate rdstate() const{ - return mstate; - } - _UCXXEXPORT void clear(iostate state = goodbit){ - if(rdbuf()!=0){ - mstate = state; - }else{ - mstate = state|ios_base::badbit; - } - } - _UCXXEXPORT void setstate(iostate state) { - clear(rdstate() | state); + inline ios_base& nouppercase(ios_base& str) + { + str.unsetf(ios_base::uppercase); + return str; + } + + inline ios_base& unitbuf(ios_base& str) + { + str.setf(ios_base::unitbuf); + return str; + } + + inline ios_base& nounitbuf(ios_base& str) + { + str.unsetf(ios_base::unitbuf); + return str; + } + + inline ios_base& internal(ios_base& str) + { + str.setf(ios_base::internal, ios_base::adjustfield); + return str; + } + + inline ios_base& left(ios_base& str) + { + str.setf(ios_base::left, ios_base::adjustfield); + return str; + } + + inline ios_base& right(ios_base& str) + { + str.setf(ios_base::right, ios_base::adjustfield); + return str; + } + + inline ios_base& dec(ios_base& str) + { + str.setf(ios_base::dec, ios_base::basefield); + return str; + } + + inline ios_base& hex(ios_base& str) + { + str.setf(ios_base::hex, ios_base::basefield); + return str; + } + + inline ios_base& oct(ios_base& str) + { + str.setf(ios_base::oct, ios_base::basefield); + return str; + } + + inline ios_base& fixed(ios_base& str) + { + str.setf(ios_base::fixed, ios_base::floatfield); + return str; + } + + inline ios_base& scientific(ios_base& str) + { + str.setf(ios_base::scientific, ios_base::floatfield); + return str; + } + + // basic_ios class definition + + template class _UCXXEXPORT basic_ios + : public ios_base + { + public: + // Types: + + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef traits traits_type; + + _UCXXEXPORT operator void*() const + { + if (fail()) + { + return 0; + } + + return (void *)(1); // Must return a non-NULL pointer (though it can be *any* pointer) + } + + _UCXXEXPORT bool operator!() const + { + return fail(); + } + + _UCXXEXPORT iostate rdstate() const + { + return mstate; + } + + _UCXXEXPORT void clear(iostate state = goodbit) + { + if (rdbuf()!=0) + { + mstate = state; + } + else + { + mstate = state|ios_base::badbit; + } + } + + _UCXXEXPORT void setstate(iostate state) + { + clear(rdstate() | state); #ifdef CONFIG_UCLIBCXX_EXCEPTION - if(rdstate() & throw_mask){ - throw failure(); - } + if (rdstate() & throw_mask) + { + throw failure(); + } #endif - } + } - _UCXXEXPORT bool good() const{ - return (rdstate() == 0); - } - _UCXXEXPORT bool eof() const{ - if(rdstate() & eofbit){ - return true; - } - return false; - } - _UCXXEXPORT bool fail() const{ - if( mstate & (failbit | badbit) ){ - return true; - } - return false; - } + _UCXXEXPORT bool good() const + { + return (rdstate() == 0); + } - _UCXXEXPORT bool bad() const{ - if(mstate & badbit){ - return true; - } - return false; - } + _UCXXEXPORT bool eof() const + { + if (rdstate() & eofbit) + { + return true; + } - _UCXXEXPORT iostate exceptions() const{ - return throw_mask; - } - _UCXXEXPORT void exceptions(iostate except){ - throw_mask = except; - } + return false; + } - explicit _UCXXEXPORT basic_ios(basic_streambuf* sb) : fill_char(' '), mtied(0), mstreambuf(0){ - init(sb); - } + _UCXXEXPORT bool fail() const + { + if (mstate & (failbit | badbit)) + { + return true; + } - basic_ios() : mtied(0), mstreambuf(0){ } + return false; + } - virtual _UCXXEXPORT ~basic_ios(){ - } + _UCXXEXPORT bool bad() const + { + if (mstate & badbit) + { + return true; + } - _UCXXEXPORT basic_ostream* tie() const{ - return mtied; - } - _UCXXEXPORT basic_ostream* tie(basic_ostream* tiestr){ - basic_ostream* retval= mtied; - mtied = tiestr; - return retval; - } - _UCXXEXPORT basic_streambuf* rdbuf() const{ - return mstreambuf; - } - _UCXXEXPORT basic_streambuf* rdbuf(basic_streambuf* sb){ - basic_streambuf* retval = mstreambuf; - mstreambuf = sb; - return retval; - } - _UCXXEXPORT basic_ios& copyfmt(const basic_ios& rhs); - _UCXXEXPORT char_type fill() const{ - return fill_char; - } - _UCXXEXPORT char_type fill(char_type ch){ - char_type temp = fill_char; - fill_char = ch; - return temp; - } + return false; + } - _UCXXEXPORT locale imbue(const locale& loc){ - return ios_base::imbue(loc); - } - _UCXXEXPORT char narrow(char_type c, char dfault) const; - _UCXXEXPORT char_type widen(char c) const; + _UCXXEXPORT iostate exceptions() const + { + return throw_mask; + } - protected: - char_type fill_char; - basic_ostream* mtied; - basic_streambuf* mstreambuf; - iostate throw_mask; - _UCXXEXPORT basic_ios(const basic_ios &){ } - _UCXXEXPORT basic_ios & operator=(const basic_ios &){ return *this; } - _UCXXEXPORT void init(basic_streambuf* sb){ - ios_base::mformat = skipws|dec; - mstreambuf = sb; - mstate = goodbit; - throw_mask = goodbit; - } - }; + _UCXXEXPORT void exceptions(iostate except) + { + throw_mask = except; + } + + explicit _UCXXEXPORT basic_ios(basic_streambuf* sb) : fill_char(' '), mtied(0), mstreambuf(0) + { + init(sb); + } + + basic_ios() : mtied(0), mstreambuf(0){ } + + virtual _UCXXEXPORT ~basic_ios() + { + } + + _UCXXEXPORT basic_ostream* tie() const + { + return mtied; + } + + _UCXXEXPORT basic_ostream* tie(basic_ostream* tiestr) + { + basic_ostream* retval= mtied; + mtied = tiestr; + return retval; + } + + _UCXXEXPORT basic_streambuf* rdbuf() const + { + return mstreambuf; + } + + _UCXXEXPORT basic_streambuf* rdbuf(basic_streambuf* sb) + { + basic_streambuf* retval = mstreambuf; + mstreambuf = sb; + return retval; + } + + _UCXXEXPORT basic_ios& copyfmt(const basic_ios& rhs); + + _UCXXEXPORT char_type fill() const + { + return fill_char; + } + + _UCXXEXPORT char_type fill(char_type ch) + { + char_type temp = fill_char; + fill_char = ch; + return temp; + } + + _UCXXEXPORT locale imbue(const locale& loc) + { + return ios_base::imbue(loc); + } + + _UCXXEXPORT char narrow(char_type c, char dfault) const; + _UCXXEXPORT char_type widen(char c) const; + + protected: + char_type fill_char; + basic_ostream* mtied; + basic_streambuf* mstreambuf; + iostate throw_mask; + _UCXXEXPORT basic_ios(const basic_ios &){ } + _UCXXEXPORT basic_ios & operator=(const basic_ios &){ return *this; } + + _UCXXEXPORT void init(basic_streambuf* sb) + { + ios_base::mformat = skipws|dec; + mstreambuf = sb; + mstate = goodbit; + throw_mask = goodbit; + } + }; #ifdef __UCLIBCXX_EXPAND_IOS_CHAR__ #ifndef __UCLIBCXX_COMPILE_IOS__ - template <> _UCXXEXPORT void basic_ios >::clear(iostate state); - template <> _UCXXEXPORT void basic_ios >::setstate(iostate state); + template <> _UCXXEXPORT void basic_ios >::clear(iostate state); + template <> _UCXXEXPORT void basic_ios >::setstate(iostate state); #endif #endif + template + inline char basic_ios::narrow(char_type c, char dfault) const + { + return dfault; + } - template - inline char basic_ios::narrow(char_type c, char dfault) const - { - return dfault; - } - - template <> - inline char basic_ios >::narrow(char_type c, char) const - { - return c; - } + template <> + inline char basic_ios >::narrow(char_type c, char) const + { + return c; + } #ifdef __UCLIBCXX_HAS_WCHAR__ - template <> - inline char basic_ios >::narrow(char_type c, char dfault) const - { - char retval = wctob (c); - if(retval == EOF){ - retval = dfault; - } - return retval; - } + template <> + inline char basic_ios >::narrow(char_type c, char dfault) const + { + char retval = wctob(c); + if (retval == EOF) + { + retval = dfault; + } -#endif //__UCLIBCXX_HAS_WCHAR__ + return retval; + } - template - inline typename basic_ios::char_type - basic_ios::widen(char c) const - { - return c; - } +#endif //__UCLIBCXX_HAS_WCHAR__ - template <> - inline basic_ios >::char_type - basic_ios >::widen(char c) const - { - return c; - } + template + inline typename basic_ios::char_type + basic_ios::widen(char c) const + { + return c; + } + + template <> + inline basic_ios >::char_type + basic_ios >::widen(char c) const + { + return c; + } #ifdef __UCLIBCXX_HAS_WCHAR__ - template <> - inline basic_ios >::char_type - basic_ios >::widen(char c) const - { - return btowc(c); - } + template <> + inline basic_ios >::char_type + basic_ios >::widen(char c) const + { + return btowc(c); + } #endif //__UCLIBCXX_HAS_WCHAR__ - template class _UCXXEXPORT fpos{ - public: - _UCXXEXPORT fpos(stateT s){ - st = s; - } - _UCXXEXPORT stateT state() const{ - return st; - } - _UCXXEXPORT void state(stateT s){ - st = s; - } - _UCXXEXPORT bool operator==(const fpos &rhs){ - return st == rhs.st; - } - _UCXXEXPORT bool operator!=(const fpos &rhs){ - return st != rhs.st; - } - _UCXXEXPORT fpos & operator+(const streamoff & o){ - st += o; - return *this; - } - _UCXXEXPORT fpos & operator-(const streamoff & o){ - st -= o; - return *this; - } - _UCXXEXPORT streamoff operator-(const fpos & rhs){ - return st - rhs.st; - } + template class _UCXXEXPORT fpos{ + public: + _UCXXEXPORT fpos(stateT s) + { + st = s; + } - private: - stateT st; - }; + _UCXXEXPORT stateT state() const + { + return st; + } + _UCXXEXPORT void state(stateT s) + { + st = s; + } -} + _UCXXEXPORT bool operator==(const fpos &rhs) + { + return st == rhs.st; + } + + _UCXXEXPORT bool operator!=(const fpos &rhs) + { + return st != rhs.st; + } + + _UCXXEXPORT fpos & operator+(const streamoff & o) + { + st += o; + return *this; + } + + _UCXXEXPORT fpos & operator-(const streamoff & o) + { + st -= o; + return *this; + } + + _UCXXEXPORT streamoff operator-(const fpos & rhs) + { + return st - rhs.st; + } + + private: + stateT st; + }; + +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/iosfwd b/misc/uClibc++/include/uClibc++/iosfwd index 2c14725e32..c322b64d33 100644 --- a/misc/uClibc++/include/uClibc++/iosfwd +++ b/misc/uClibc++/include/uClibc++/iosfwd @@ -1,114 +1,119 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include #include - #ifndef __HEADER_STD_IOSFWD #define __HEADER_STD_IOSFWD 1 #pragma GCC visibility push(default) -namespace std { - class ios_base; - template<> class char_traits; +extern "C++" +{ + +namespace std +{ + class ios_base; + template<> class char_traits; #ifdef __UCLIBCXX_HAS_WCHAR__ - template<> class char_traits; + template<> class char_traits; #endif - template > class basic_ios; + template > class basic_ios; - template > class basic_streambuf; - template > class basic_istream; - template > class basic_ostream; - template > class basic_iostream; + template > class basic_streambuf; + template > class basic_istream; + template > class basic_ostream; + template > class basic_iostream; - template , - class Allocator = allocator > class basic_stringbuf; + template , + class Allocator = allocator > class basic_stringbuf; - template , - class Allocator = allocator > class basic_istringstream; + template , + class Allocator = allocator > class basic_istringstream; - template , - class Allocator = allocator > class basic_ostringstream; + template , + class Allocator = allocator > class basic_ostringstream; - template , - class Allocator = allocator > class basic_stringstream; + template , + class Allocator = allocator > class basic_stringstream; - template > class basic_filebuf; + template > class basic_filebuf; - template > class basic_ifstream; + template > class basic_ifstream; - template > class basic_ofstream; + template > class basic_ofstream; - template > class basic_fstream; + template > class basic_fstream; - template > class basic_istreambuf_iterator; + template > class basic_istreambuf_iterator; - template > class basic_ostreambuf_iterator; + template > class basic_ostreambuf_iterator; - typedef basic_ios ios; + typedef basic_ios ios; #ifdef __UCLIBCXX_HAS_WCHAR__ - typedef basic_ios wios; + typedef basic_ios wios; #endif - typedef basic_streambuf streambuf; - typedef basic_istream istream; - typedef basic_ostream ostream; - typedef basic_iostream iostream; + typedef basic_streambuf streambuf; + typedef basic_istream istream; + typedef basic_ostream ostream; + typedef basic_iostream iostream; - typedef basic_stringbuf stringbuf; - typedef basic_istringstream istringstream; - typedef basic_ostringstream ostringstream; - typedef basic_stringstream stringstream; + typedef basic_stringbuf stringbuf; + typedef basic_istringstream istringstream; + typedef basic_ostringstream ostringstream; + typedef basic_stringstream stringstream; - typedef basic_filebuf filebuf; - typedef basic_ifstream ifstream; - typedef basic_ofstream ofstream; - typedef basic_fstream fstream; + typedef basic_filebuf filebuf; + typedef basic_ifstream ifstream; + typedef basic_ofstream ofstream; + typedef basic_fstream fstream; #ifdef __UCLIBCXX_HAS_WCHAR__ - typedef basic_streambuf wstreambuf; - typedef basic_istream wistream; - typedef basic_ostream wostream; - typedef basic_iostream wiostream; + typedef basic_streambuf wstreambuf; + typedef basic_istream wistream; + typedef basic_ostream wostream; + typedef basic_iostream wiostream; - typedef basic_stringbuf wstringbuf; - typedef basic_istringstream wistringstream; - typedef basic_ostringstream wostringstream; - typedef basic_stringstream wstringstream; + typedef basic_stringbuf wstringbuf; + typedef basic_istringstream wistringstream; + typedef basic_ostringstream wostringstream; + typedef basic_stringstream wstringstream; - typedef basic_filebuf wfilebuf; - typedef basic_ifstream wifstream; - typedef basic_ofstream wofstream; - typedef basic_fstream wfstream; + typedef basic_filebuf wfilebuf; + typedef basic_ifstream wifstream; + typedef basic_ofstream wofstream; + typedef basic_fstream wfstream; #endif - - template class fpos; - typedef fpos::state_type> streampos; + + template class fpos; + typedef fpos::state_type> streampos; #ifdef __UCLIBCXX_HAS_WCHAR__ - typedef fpos::state_type> wstreampos; + typedef fpos::state_type> wstreampos; #endif -} + +} // namespace +} // extern "C++" #pragma GCC visibility pop -#endif +#endif // __HEADER_STD_IOSFWD diff --git a/misc/uClibc++/include/uClibc++/iostream b/misc/uClibc++/include/uClibc++/iostream index f93987f3bb..3a2f5c09ee 100644 --- a/misc/uClibc++/include/uClibc++/iostream +++ b/misc/uClibc++/include/uClibc++/iostream @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include @@ -31,70 +31,70 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ + #ifdef __UCLIBCXX_SUPPORT_CIN__ - extern istream cin; + extern istream cin; #endif #ifdef __UCLIBCXX_SUPPORT_COUT__ - extern ostream cout; + extern ostream cout; #endif #ifdef __UCLIBCXX_SUPPORT_CERR__ - extern ostream cerr; + extern ostream cerr; #endif #ifdef __UCLIBCXX_SUPPORT_CLOG__ - extern ostream clog; + extern ostream clog; #endif #ifdef __UCLIBCXX_SUPPORT_WCIN__ - extern wistream wcin; + extern wistream wcin; #endif #ifdef __UCLIBCXX_SUPPORT_WCOUT__ - extern wostream wcout; + extern wostream wcout; #endif #ifdef __UCLIBCXX_SUPPORT_WCERR__ - extern wostream wcerr; + extern wostream wcerr; #endif #ifdef __UCLIBCXX_SUPPORT_WCLOG__ - extern wostream wclog; + extern wostream wclog; #endif + template class _UCXXEXPORT basic_iostream : + public basic_istream, public basic_ostream + { + public: + // constructor/destructor + explicit _UCXXEXPORT basic_iostream(basic_streambuf* sb); + virtual _UCXXEXPORT ~basic_iostream(); //Below + }; - template class _UCXXEXPORT basic_iostream : - public basic_istream, public basic_ostream - { - public: - // constructor/destructor - explicit _UCXXEXPORT basic_iostream(basic_streambuf* sb); - virtual _UCXXEXPORT ~basic_iostream(); //Below - }; - - template _UCXXEXPORT - basic_iostream:: basic_iostream(basic_streambuf* sb) - : basic_ios(sb), basic_istream(sb), basic_ostream(sb) - { - return; - } - - - template _UCXXEXPORT basic_iostream::~basic_iostream(){ - return; - } + template _UCXXEXPORT + basic_iostream:: basic_iostream(basic_streambuf* sb) + : basic_ios(sb), basic_istream(sb), basic_ostream(sb) + { + return; + } + template _UCXXEXPORT basic_iostream::~basic_iostream(){ + return; + } #ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ #ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ #ifndef __UCLIBCXX_COMPILE_IOSTREAM__ - template <> _UCXXEXPORT basic_iostream >:: - basic_iostream(basic_streambuf >* sb); - template <> _UCXXEXPORT basic_iostream >::~basic_iostream(); + template <> _UCXXEXPORT basic_iostream >:: + basic_iostream(basic_streambuf >* sb); + template <> _UCXXEXPORT basic_iostream >::~basic_iostream(); #endif #endif #endif - - -} +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/istream b/misc/uClibc++/include/uClibc++/istream index 37ffa127b6..faedcc1c8f 100644 --- a/misc/uClibc++/include/uClibc++/istream +++ b/misc/uClibc++/include/uClibc++/istream @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc C++ Library. This library is free - software; you can redistribute it and/or modify it under the - terms of the GNU General Public License as published by the - Free Software Foundation; either version 2, or (at your option) - any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License along - with this library; see the file COPYING. If not, write to the Free - Software Foundation, 59 Temple Place - Suite 330, Boston, MA 02111-1307, - USA. -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc C++ Library. This library is free + * software; you can redistribute it and/or modify it under the + * terms of the GNU General Public License as published by the + * Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this library; see the file COPYING. If not, write to the Free + * Software Foundation, 59 Temple Place - Suite 330, Boston, MA 02111-1307, + * USA. + */ #include #include @@ -28,572 +28,704 @@ #pragma GCC visibility push(default) -namespace std{ - - typedef basic_istream istream; +extern "C++" +{ +namespace std +{ + typedef basic_istream istream; #ifdef __UCLIBCXX_HAS_WCHAR__ - typedef basic_istream wistream; + typedef basic_istream wistream; #endif - template basic_istream& ws(basic_istream& is); + template basic_istream& ws(basic_istream& is); - template class _UCXXEXPORT basic_istream : - virtual public basic_ios - { - public: + template class _UCXXEXPORT basic_istream : + virtual public basic_ios + { + public: - typedef charT char_type; - typedef typename traits::int_type int_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; - typedef basic_streambuf streambuf_type; - typedef traits traits_type; + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef basic_streambuf streambuf_type; + typedef traits traits_type; - explicit basic_istream(basic_streambuf* sb) - : basic_ios(sb), count_last_ufmt_input(0) - { - basic_ios::init(sb); - } - virtual ~basic_istream() { } + explicit basic_istream(basic_streambuf* sb) + : basic_ios(sb), count_last_ufmt_input(0) + { + basic_ios::init(sb); + } - class sentry; + virtual ~basic_istream() { } - basic_istream& operator>>(basic_istream& (*pf)(basic_istream&)); - basic_istream& operator>>(basic_ios& (*pf)(basic_ios&)); - basic_istream& operator>>(ios_base& (*pf)(ios_base&)); - basic_istream& operator>>(bool& n); - basic_istream& operator>>(short& n); - basic_istream& operator>>(unsigned short& n); - basic_istream& operator>>(int& n); - basic_istream& operator>>(unsigned int& n); - basic_istream& operator>>(long& n); - basic_istream& operator>>(unsigned long& n); - basic_istream& operator>>(void*& p); - basic_istream& operator>>(basic_streambuf* sb); + class sentry; + + basic_istream& operator>>(basic_istream& (*pf)(basic_istream&)); + basic_istream& operator>>(basic_ios& (*pf)(basic_ios&)); + basic_istream& operator>>(ios_base& (*pf)(ios_base&)); + basic_istream& operator>>(bool& n); + basic_istream& operator>>(short& n); + basic_istream& operator>>(unsigned short& n); + basic_istream& operator>>(int& n); + basic_istream& operator>>(unsigned int& n); + basic_istream& operator>>(long& n); + basic_istream& operator>>(unsigned long& n); + basic_istream& operator>>(void*& p); + basic_istream& operator>>(basic_streambuf* sb); #ifdef CONFIG_HAVE_FLOAT - basic_istream& operator>>(float& f); - basic_istream& operator>>(double& f); - basic_istream& operator>>(long double& f); + basic_istream& operator>>(float& f); + basic_istream& operator>>(double& f); + basic_istream& operator>>(long double& f); #endif - _UCXXEXPORT streamsize gcount() const{ - return count_last_ufmt_input; - } + _UCXXEXPORT streamsize gcount() const + { + return count_last_ufmt_input; + } - _UCXXEXPORT int_type get(); //below - _UCXXEXPORT basic_istream& get(char_type& c); //Below + _UCXXEXPORT int_type get(); //below + _UCXXEXPORT basic_istream& get(char_type& c); //Below - _UCXXEXPORT basic_istream& get(char_type* s, streamsize n){ - return get(s, n, basic_ios::widen('\n')); - } + _UCXXEXPORT basic_istream& get(char_type* s, streamsize n) + { + return get(s, n, basic_ios::widen('\n')); + } - _UCXXEXPORT basic_istream& get(char_type* s, streamsize n, char_type delim){ - sentry(*this, true); - streamsize i = 0; - int_type c; - for(i=0;i::mstreambuf->sgetc(); - basic_ios::mstreambuf->sbumpc(); - if(c == traits::eof() ){ - if(i==0){ - basic_ios::setstate(ios_base::failbit); - }else{ - basic_ios::setstate(ios_base::eofbit); - } - break; - } - if(c == delim){ - if(i==0){ - basic_ios::setstate(ios_base::failbit); - } - basic_ios::mstreambuf->sputbackc(c); - break; - } - s[i] = c; - } - s[i] = traits::eos(); - count_last_ufmt_input = i; - return *this; - } + _UCXXEXPORT basic_istream& get(char_type* s, streamsize n, char_type delim) + { + sentry(*this, true); + streamsize i = 0; + int_type c; + for (i = 0; i < n-1; ++i) + { + c = basic_ios::mstreambuf->sgetc(); + basic_ios::mstreambuf->sbumpc(); + if (c == traits::eof()) + { + if (i==0) + { + basic_ios::setstate(ios_base::failbit); + } + else + { + basic_ios::setstate(ios_base::eofbit); + } - _UCXXEXPORT basic_istream& get(basic_streambuf& sb){ - return get(sb, basic_ios::widen('\n')); - } + break; + } - _UCXXEXPORT basic_istream& get(basic_streambuf& sb, char_type delim){ - sentry(*this, true); - streamsize i = 0; - int_type c; - while(1){ //We will exit internally based upon error conditions - c = basic_ios::mstreambuf->sgetc(); - if(c == traits::eof()){ - if(i==0){ - basic_ios::setstate(ios_base::failbit); - }else{ - basic_ios::setstate(ios_base::eofbit); - } - count_last_ufmt_input = i; - return *this; - } - if(c == delim){ - if(i==0){ - basic_ios::setstate(ios_base::failbit); - } - count_last_ufmt_input = i; - return *this; - } - if(sb.sputc(c) != c){ //Error doing output - count_last_ufmt_input = i; - return *this; - } - ++i; - basic_ios::mstreambuf->sbumpc(); - } - } + if (c == delim) + { + if (i==0) + { + basic_ios::setstate(ios_base::failbit); + } - _UCXXEXPORT basic_istream& getline(char_type* s, streamsize n){ - return getline(s, n, basic_ios::widen('\n')); - } + basic_ios::mstreambuf->sputbackc(c); + break; + } - _UCXXEXPORT basic_istream& getline(char_type* s, streamsize n, char_type delim){ - sentry(*this, true); - streamsize i = 0; - int_type c; - for(i=0;i::mstreambuf->sgetc(); - if(c == traits::eof() ){ - if( basic_ios::eof() ){ - basic_ios::setstate(ios_base::failbit); - }else{ - basic_ios::setstate(ios_base::eofbit); - } - count_last_ufmt_input = i; - s[i] = traits::eos(); - return *this; - } - if(basic_ios::mstreambuf->sbumpc()==traits::eof() ){ - basic_ios::setstate(ios_base::eofbit); - } - if(c == delim){ - count_last_ufmt_input = i+1; - s[i] = traits::eos(); - return *this; - } - s[i] = c; - } - s[n-1] = traits::eos(); - return *this; - } + s[i] = c; + } - _UCXXEXPORT basic_istream& ignore (streamsize n = 1, int_type delim = traits::eof()){ - sentry(*this, true); - streamsize i; - int_type c; - for(i=0;i::mstreambuf->sgetc(); - if(c == traits::eof()){ - basic_ios::setstate(ios_base::eofbit); - return *this; - } - basic_ios::mstreambuf->sbumpc(); - if(c == delim){ - return *this; - } - } - return *this; - } + s[i] = traits::eos(); + count_last_ufmt_input = i; + return *this; + } - _UCXXEXPORT int_type peek(){ - if(basic_ios::good() == false){ - return traits::eof(); - }else{ - int_type c = basic_ios::mstreambuf->sgetc(); - if(c == traits::eof()){ - basic_ios::setstate(ios_base::eofbit); - } - return basic_ios::mstreambuf->sgetc(); - } - } + _UCXXEXPORT basic_istream& get(basic_streambuf& sb) + { + return get(sb, basic_ios::widen('\n')); + } - _UCXXEXPORT basic_istream& read (char_type* s, streamsize n){ - sentry(*this, true); - streamsize i; - int_type c; - for(i=0;i::mstreambuf->sgetc(); + _UCXXEXPORT basic_istream& get(basic_streambuf& sb, char_type delim) + { + sentry(*this, true); + streamsize i = 0; + int_type c; + while (1) + { + // We will exit internally based upon error conditions - if(c == traits::eof()){ - basic_ios::setstate(ios_base::failbit); - basic_ios::setstate(ios_base::eofbit); - count_last_ufmt_input = i; - return *this; - } - basic_ios::mstreambuf->sbumpc(); - s[i] = c; - } - count_last_ufmt_input = n; - return *this; - } + c = basic_ios::mstreambuf->sgetc(); + if (c == traits::eof()) + { + if (i==0) + { + basic_ios::setstate(ios_base::failbit); + } + else + { + basic_ios::setstate(ios_base::eofbit); + } - _UCXXEXPORT streamsize readsome(char_type* s, streamsize n){ - sentry(*this, true); - if(!basic_ios::good()){ - count_last_ufmt_input = 0; - basic_ios::setstate(ios_base::failbit); - return 0; - } + count_last_ufmt_input = i; + return *this; + } - if( basic_ios::mstreambuf->in_avail() == -1){ - count_last_ufmt_input=0; - basic_ios::setstate(ios_base::eofbit); - return 0; - } + if (c == delim) + { + if (i == 0) + { + basic_ios::setstate(ios_base::failbit); + } - if(n > basic_ios::mstreambuf->in_avail() ){ - n = basic_ios::mstreambuf->in_avail(); - } + count_last_ufmt_input = i; + return *this; + } - streamsize i; - int_type c; + if (sb.sputc(c) != c) + { + // Error doing output - for(i=0;i::mstreambuf->sgetc(); - basic_ios::mstreambuf->sbumpc(); - s[i] = c; - } - count_last_ufmt_input = n; - return n; - } + count_last_ufmt_input = i; + return *this; + } - _UCXXEXPORT basic_istream& putback(char_type c){ - sentry(*this, true); - if(!basic_ios::good()){ - basic_ios::setstate(ios_base::failbit); - return *this; - } - if(basic_ios::mstreambuf == 0){ - basic_ios::setstate(ios_base::badbit); - return *this; - } - if(basic_ios::mstreambuf->sputbackc(c) == traits::eof()){ - basic_ios::setstate(ios_base::badbit); - return *this; - } - return *this; - } + ++i; + basic_ios::mstreambuf->sbumpc(); + } + } - _UCXXEXPORT basic_istream& unget(){ - sentry(*this, true); - if(!basic_ios::good()){ - basic_ios::setstate(ios_base::failbit); - return *this; - } - if(basic_ios::mstreambuf == 0){ - basic_ios::setstate(ios_base::failbit); - return *this; - } - if(basic_ios::mstreambuf->sungetc() == traits::eof()){ - basic_ios::setstate(ios_base::failbit); - } - return *this; - } + _UCXXEXPORT basic_istream& getline(char_type* s, streamsize n) + { + return getline(s, n, basic_ios::widen('\n')); + } - _UCXXEXPORT int sync(){ - sentry(*this, true); - if(basic_ios::mstreambuf == 0){ - return -1; - } - if(basic_ios::mstreambuf->pubsync() == -1){ - basic_ios::setstate(ios_base::badbit); - return traits::eof(); - } - return 0; - } + _UCXXEXPORT basic_istream& getline(char_type* s, streamsize n, char_type delim) + { + sentry(*this, true); + streamsize i = 0; + int_type c; + for (i = 0; i < n-1; ++i) + { + c = basic_ios::mstreambuf->sgetc(); + if (c == traits::eof()) + { + if (basic_ios::eof()) + { + basic_ios::setstate(ios_base::failbit); + } + else + { + basic_ios::setstate(ios_base::eofbit); + } - _UCXXEXPORT pos_type tellg(){ - if(basic_ios::fail() !=false){ - return pos_type(-1); - } - return basic_ios::mstreambuf->pubseekoff(0, ios_base::cur, ios_base::in); - } + count_last_ufmt_input = i; + s[i] = traits::eos(); + return *this; + } - _UCXXEXPORT basic_istream& seekg(pos_type pos){ - if(basic_ios::fail() !=true){ - basic_ios::mstreambuf->pubseekpos(pos); - } - return *this; - } + if (basic_ios::mstreambuf->sbumpc()==traits::eof()) + { + basic_ios::setstate(ios_base::eofbit); + } - _UCXXEXPORT basic_istream& seekg(off_type off, ios_base::seekdir dir){ - if(basic_ios::fail() !=true){ - basic_ios::mstreambuf->pubseekoff(off, dir); - } - return *this; - } + if (c == delim) + { + count_last_ufmt_input = i+1; + s[i] = traits::eos(); + return *this; + } - protected: - _UCXXEXPORT basic_istream(const basic_istream &): basic_ios() { } - _UCXXEXPORT basic_istream & operator=(const basic_istream &){ return *this; } - streamsize count_last_ufmt_input; + s[i] = c; + } - }; + s[n-1] = traits::eos(); + return *this; + } - template > class _UCXXEXPORT basic_istream::sentry { - bool ok; - public: - explicit _UCXXEXPORT sentry(basic_istream& os, bool noskipws = false){ - if(os.good() !=0){ //Prepare for output - } + _UCXXEXPORT basic_istream& ignore (streamsize n = 1, int_type delim = traits::eof()) + { + sentry(*this, true); + streamsize i; + int_type c; + for (i = 0; i < n; ++i) + { + c = basic_ios::mstreambuf->sgetc(); + if (c == traits::eof()) + { + basic_ios::setstate(ios_base::eofbit); + return *this; + } - //Flush any tied buffer - if(os.tie() != 0){ - os.tie()->flush(); - } - if(!noskipws){ - __skipws(os); - } + basic_ios::mstreambuf->sbumpc(); + if (c == delim) + { + return *this; + } + } - ok = true; - } - _UCXXEXPORT ~sentry() { } - _UCXXEXPORT operator bool() { - return ok; - } - }; + return *this; + } - //Template implementations of basic_istream functions which may be partially specialized - //For code reduction + _UCXXEXPORT int_type peek() + { + if (basic_ios::good() == false) + { + return traits::eof(); + } + else + { + int_type c = basic_ios::mstreambuf->sgetc(); + if (c == traits::eof()) + { + basic_ios::setstate(ios_base::eofbit); + } - template - _UCXXEXPORT typename basic_istream::int_type basic_istream::get(){ - sentry(*this, true); - int_type retval = basic_ios::mstreambuf->sgetc(); - if(retval == traits::eof()){ - count_last_ufmt_input = 0; - basic_ios::setstate(ios_base::eofbit); - }else{ - count_last_ufmt_input = 1; - basic_ios::mstreambuf->sbumpc(); - } - return retval; - } + return basic_ios::mstreambuf->sgetc(); + } + } - template - _UCXXEXPORT basic_istream& basic_istream::get(char_type& c){ - sentry(*this, true); - int_type retval = basic_ios::mstreambuf->sgetc(); - if(retval == traits::eof()){ - count_last_ufmt_input = 0; - basic_ios::setstate(ios_base::eofbit); - basic_ios::setstate(ios_base::failbit); - }else{ - count_last_ufmt_input = 1; - c = traits::to_char_type(retval); - basic_ios::mstreambuf->sbumpc(); - } - return *this; - } + _UCXXEXPORT basic_istream& read (char_type* s, streamsize n) + { + sentry(*this, true); + streamsize i; + int_type c; + for (i = 0; i < n; ++i) + { + c = basic_ios::mstreambuf->sgetc(); + if (c == traits::eof()) + { + basic_ios::setstate(ios_base::failbit); + basic_ios::setstate(ios_base::eofbit); + count_last_ufmt_input = i; + return *this; + } - template _UCXXEXPORT basic_istream& - basic_istream::operator>>(bool& n) - { - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } + basic_ios::mstreambuf->sbumpc(); + s[i] = c; + } - template _UCXXEXPORT basic_istream& - basic_istream::operator>>(short& n) - { - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } + count_last_ufmt_input = n; + return *this; + } - template _UCXXEXPORT basic_istream& - basic_istream::operator>>(unsigned short& n) - { - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } + _UCXXEXPORT streamsize readsome(char_type* s, streamsize n) + { + sentry(*this, true); + if (!basic_ios::good()) + { + count_last_ufmt_input = 0; + basic_ios::setstate(ios_base::failbit); + return 0; + } - template _UCXXEXPORT basic_istream& basic_istream::operator>>(int& n){ - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } + if (basic_ios::mstreambuf->in_avail() == -1) + { + count_last_ufmt_input=0; + basic_ios::setstate(ios_base::eofbit); + return 0; + } - template _UCXXEXPORT basic_istream& basic_istream::operator>>(unsigned int& n){ - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } + if (n > basic_ios::mstreambuf->in_avail()) + { + n = basic_ios::mstreambuf->in_avail(); + } - template _UCXXEXPORT basic_istream& basic_istream::operator>>(long int& n){ - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } + streamsize i; + int_type c; - template _UCXXEXPORT basic_istream& - basic_istream::operator>>(unsigned long int& n) - { - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } + for (i = 0; i < n; ++i) + { + c = basic_ios::mstreambuf->sgetc(); + basic_ios::mstreambuf->sbumpc(); + s[i] = c; + } + + count_last_ufmt_input = n; + return n; + } + + _UCXXEXPORT basic_istream& putback(char_type c) + { + sentry(*this, true); + if (!basic_ios::good()) + { + basic_ios::setstate(ios_base::failbit); + return *this; + } + + if (basic_ios::mstreambuf == 0){ + + basic_ios::setstate(ios_base::badbit); + return *this; + } + + if (basic_ios::mstreambuf->sputbackc(c) == traits::eof()) + { + basic_ios::setstate(ios_base::badbit); + return *this; + } + + return *this; + } + + _UCXXEXPORT basic_istream& unget() + { + sentry(*this, true); + if (!basic_ios::good()) + { + basic_ios::setstate(ios_base::failbit); + return *this; + } + + if (basic_ios::mstreambuf == 0) + { + basic_ios::setstate(ios_base::failbit); + return *this; + } + + if (basic_ios::mstreambuf->sungetc() == traits::eof()) + { + basic_ios::setstate(ios_base::failbit); + } + + return *this; + } + + _UCXXEXPORT int sync() + { + sentry(*this, true); + if (basic_ios::mstreambuf == 0) + { + return -1; + } + + if (basic_ios::mstreambuf->pubsync() == -1) + { + basic_ios::setstate(ios_base::badbit); + return traits::eof(); + } + + return 0; + } + + _UCXXEXPORT pos_type tellg() + { + if (basic_ios::fail() !=false) + { + return pos_type(-1); + } + + return basic_ios::mstreambuf->pubseekoff(0, ios_base::cur, ios_base::in); + } + + _UCXXEXPORT basic_istream& seekg(pos_type pos) + { + if (basic_ios::fail() !=true) + { + basic_ios::mstreambuf->pubseekpos(pos); + } + + return *this; + } + + _UCXXEXPORT basic_istream& seekg(off_type off, ios_base::seekdir dir) + { + if (basic_ios::fail() !=true) + { + basic_ios::mstreambuf->pubseekoff(off, dir); + } + + return *this; + } + + protected: + _UCXXEXPORT basic_istream(const basic_istream &): basic_ios() { } + _UCXXEXPORT basic_istream & operator=(const basic_istream &){ return *this; } + streamsize count_last_ufmt_input; + }; + + template > class _UCXXEXPORT basic_istream::sentry + { + bool ok; + public: + explicit _UCXXEXPORT sentry(basic_istream& os, bool noskipws = false){ + if (os.good() !=0) + { + // Prepare for output + } + + // Flush any tied buffer + + if (os.tie() != 0) + { + os.tie()->flush(); + } + + if (!noskipws) + { + __skipws(os); + } + + ok = true; + } + + _UCXXEXPORT ~sentry() { } + + _UCXXEXPORT operator bool() + { + return ok; + } + }; + + // Template implementations of basic_istream functions which may be partially specialized + // For code reduction + + template + _UCXXEXPORT typename basic_istream::int_type basic_istream::get() + { + sentry(*this, true); + int_type retval = basic_ios::mstreambuf->sgetc(); + if (retval == traits::eof()) + { + count_last_ufmt_input = 0; + basic_ios::setstate(ios_base::eofbit); + } + else + { + count_last_ufmt_input = 1; + basic_ios::mstreambuf->sbumpc(); + } + + return retval; + } + + template + _UCXXEXPORT basic_istream& basic_istream::get(char_type& c) + { + sentry(*this, true); + int_type retval = basic_ios::mstreambuf->sgetc(); + if (retval == traits::eof()) + { + count_last_ufmt_input = 0; + basic_ios::setstate(ios_base::eofbit); + basic_ios::setstate(ios_base::failbit); + } + else + { + count_last_ufmt_input = 1; + c = traits::to_char_type(retval); + basic_ios::mstreambuf->sbumpc(); + } + + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(bool& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(short& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(unsigned short& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& basic_istream::operator>>(int& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& basic_istream::operator>>(unsigned int& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& basic_istream::operator>>(long int& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(unsigned long int& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } #ifdef CONFIG_HAVE_FLOAT - template _UCXXEXPORT basic_istream& - basic_istream::operator>>(float& n) - { - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } - template _UCXXEXPORT basic_istream& - basic_istream::operator>>(double& n) - { - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } - template _UCXXEXPORT basic_istream& - basic_istream::operator>>(long double& n) - { - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(float& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(double& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(long double& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } #endif - template _UCXXEXPORT basic_istream& - basic_istream::operator>>(void *& n) - { - sentry(*this); - __istream_readin::readin(*this, n); - return *this; - } - template _UCXXEXPORT basic_istream& - operator>>(basic_istream& is, charT& c) - { - typename basic_istream::sentry s(is); - is.get(c); - return is; - } + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(void *& n) + { + sentry(*this); + __istream_readin::readin(*this, n); + return *this; + } - template _UCXXEXPORT basic_istream& - operator>>(basic_istream& is, unsigned char& c) - { - typename basic_istream::sentry s(is); - char b; - is.get(b); - c = b; - return is; - } - template _UCXXEXPORT basic_istream& - operator>>(basic_istream& is, signed char& c) - { - typename basic_istream::sentry s(is); - is.get(c); - return is; - } + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, charT& c) + { + typename basic_istream::sentry s(is); + is.get(c); + return is; + } - template _UCXXEXPORT basic_istream& - operator>>(basic_istream& is, charT* c) - { - typename basic_istream::sentry s(is); - int n = is.width(); - if(n == 0){ - n = __STRING_MAX_UNITS; - } - is.get(c, n); - return is; + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, unsigned char& c) + { + typename basic_istream::sentry s(is); + char b; + is.get(b); + c = b; + return is; + } - } - template _UCXXEXPORT basic_istream& - operator>>(basic_istream& is, unsigned char* c) - { - typename basic_istream::sentry s(is); - int n = is.width(); - if(n == 0){ - n = __STRING_MAX_UNITS; - } - is.get(c, n); - return is; - } - template _UCXXEXPORT basic_istream& - operator>>(basic_istream& is, signed char* c) - { - typename basic_istream::sentry s(is); - int n = is.width(); - if(n == 0){ - n = __STRING_MAX_UNITS; - } - is.get(c, n); - return is; - } + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, signed char& c) + { + typename basic_istream::sentry s(is); + is.get(c); + return is; + } - template _UCXXEXPORT basic_istream& - basic_istream::operator>>(basic_istream& (*pf)(basic_istream&)) - { - sentry(*this); - pf(*this); - return *this; - } + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, charT* c) + { + typename basic_istream::sentry s(is); + int n = is.width(); + if (n == 0) + { + n = __STRING_MAX_UNITS; + } - template _UCXXEXPORT basic_istream& - basic_istream::operator>>(basic_ios& (*pf)(basic_ios&)) - { - sentry(*this); - pf(*this); - return *this; - } + is.get(c, n); + return is; - template _UCXXEXPORT basic_istream& - ws(basic_istream& is) - { - __skipws(is); - return is; - } + } + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, unsigned char* c) + { + typename basic_istream::sentry s(is); + int n = is.width(); + if (n == 0) + { + n = __STRING_MAX_UNITS; + } + + is.get(c, n); + return is; + } + + template _UCXXEXPORT basic_istream& + operator>>(basic_istream& is, signed char* c) + { + typename basic_istream::sentry s(is); + int n = is.width(); + if (n == 0) + { + n = __STRING_MAX_UNITS; + } + is.get(c, n); + return is; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(basic_istream& (*pf)(basic_istream&)) + { + sentry(*this); + pf(*this); + return *this; + } + + template _UCXXEXPORT basic_istream& + basic_istream::operator>>(basic_ios& (*pf)(basic_ios&)) + { + sentry(*this); + pf(*this); + return *this; + } + + template _UCXXEXPORT basic_istream& + ws(basic_istream& is) + { + __skipws(is); + return is; + } #ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ #ifndef __UCLIBCXX_COMPILE_ISTREAM__ + template <> _UCXXEXPORT istream & basic_istream >::get(char & c); + template <> _UCXXEXPORT istream::int_type basic_istream >::get(); - template <> _UCXXEXPORT istream & basic_istream >::get(char & c); - template <> _UCXXEXPORT istream::int_type basic_istream >::get(); - - template <> _UCXXEXPORT istream & istream::operator>>(bool &n); - template <> _UCXXEXPORT istream & istream::operator>>(short &n); - template <> _UCXXEXPORT istream & istream::operator>>(unsigned short &n); - template <> _UCXXEXPORT istream & istream::operator>>(int &n); - template <> _UCXXEXPORT istream & istream::operator>>(unsigned int &n); - template <> _UCXXEXPORT istream & istream::operator>>(long unsigned &n); - template <> _UCXXEXPORT istream & istream::operator>>(long int &n); - template <> _UCXXEXPORT istream & istream::operator>>(void *& p); + template <> _UCXXEXPORT istream & istream::operator>>(bool &n); + template <> _UCXXEXPORT istream & istream::operator>>(short &n); + template <> _UCXXEXPORT istream & istream::operator>>(unsigned short &n); + template <> _UCXXEXPORT istream & istream::operator>>(int &n); + template <> _UCXXEXPORT istream & istream::operator>>(unsigned int &n); + template <> _UCXXEXPORT istream & istream::operator>>(long unsigned &n); + template <> _UCXXEXPORT istream & istream::operator>>(long int &n); + template <> _UCXXEXPORT istream & istream::operator>>(void *& p); #ifdef CONFIG_HAVE_FLOAT - template <> _UCXXEXPORT istream & istream::operator>>(float &f); - template <> _UCXXEXPORT istream & istream::operator>>(double &f); - template <> _UCXXEXPORT istream & istream::operator>>(long double &f); + template <> _UCXXEXPORT istream & istream::operator>>(float &f); + template <> _UCXXEXPORT istream & istream::operator>>(double &f); + template <> _UCXXEXPORT istream & istream::operator>>(long double &f); #endif - template <> _UCXXEXPORT istream & operator>>(istream & is, char & c); + template <> _UCXXEXPORT istream & operator>>(istream & is, char & c); - template <> _UCXXEXPORT void __skipws(basic_istream >& is); + template <> _UCXXEXPORT void __skipws(basic_istream >& is); #endif #endif -} +} // namespace +} // extern "C++" #pragma GCC visibility pop #endif - diff --git a/misc/uClibc++/include/uClibc++/istream_helpers b/misc/uClibc++/include/uClibc++/istream_helpers index 36765dd70b..b514f1a1e3 100644 --- a/misc/uClibc++/include/uClibc++/istream_helpers +++ b/misc/uClibc++/include/uClibc++/istream_helpers @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -28,343 +28,452 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ + /* We are making the following template class for serveral reasons. Firstly, + * we want to keep the main istream code neat and tidy. Secondly, we want it + * to be easy to do partial specialization of the istream code so that it can + * be expanded and put into the library. This will allow us to make application + * code smaller at the expense of increased library size. This is a fair + * trade-off when there are multiple applications being compiled. Also, this + * feature will be used optionally via configuration options. It will also + * allow us to keep the code bases in sync, dramatically simplifying the + * maintenance required. We specialized for char because wchar and others + * require different scanf functions + */ + template _UCXXEXPORT + basic_string _readToken(basic_istream& stream) + { + basic_string temp; + typename traits::int_type c; + while (true) + { + c = stream.rdbuf()->sgetc(); + if (c != traits::eof() && isspace(c) == false) + { + stream.rdbuf()->sbumpc(); + temp.append(1, traits::to_char_type(c)); + } + else + { + break; + } + } - /* We are making the following template class for serveral reasons. Firstly, - * we want to keep the main istream code neat and tidy. Secondly, we want it - * to be easy to do partial specialization of the istream code so that it can - * be expanded and put into the library. This will allow us to make application - * code smaller at the expense of increased library size. This is a fair - * trade-off when there are multiple applications being compiled. Also, this - * feature will be used optionally via configuration options. It will also - * allow us to keep the code bases in sync, dramatically simplifying the - * maintenance required. We specialized for char because wchar and others - * require different scanf functions - */ + if (temp.size() == 0) + { + stream.setstate(ios_base::eofbit|ios_base::failbit); + } - template _UCXXEXPORT - basic_string _readToken(basic_istream& stream) - { - basic_string temp; - typename traits::int_type c; - while(true){ - c = stream.rdbuf()->sgetc(); - if(c != traits::eof() && isspace(c) == false){ - stream.rdbuf()->sbumpc(); - temp.append(1, traits::to_char_type(c)); - }else{ - break; - } - } - if (temp.size() == 0) - stream.setstate(ios_base::eofbit|ios_base::failbit); + return temp; + } - return temp; - } + template _UCXXEXPORT + basic_string _readTokenDecimal(basic_istream& stream) + { + basic_string temp; + typename traits::int_type c; + while (true) + { + c = stream.rdbuf()->sgetc(); + if (c != traits::eof() && isspace(c) == false && ( + isdigit(c) || + c == '.' || + c == ',' || + ((c == '-' || c == '+') && temp.size() == 0))) + { + stream.rdbuf()->sbumpc(); + temp.append(1, traits::to_char_type(c)); + } + else + { + break; + } + } - template _UCXXEXPORT - basic_string _readTokenDecimal(basic_istream& stream) - { - basic_string temp; - typename traits::int_type c; - while(true){ - c = stream.rdbuf()->sgetc(); - if(c != traits::eof() && isspace(c) == false && ( - isdigit(c) || - c == '.' || - c == ',' || - ((c == '-' || c == '+') && temp.size() == 0) ) - ){ - stream.rdbuf()->sbumpc(); - temp.append(1, traits::to_char_type(c)); - }else{ - break; - } - } - if (temp.size() == 0) - stream.setstate(ios_base::eofbit|ios_base::failbit); + if (temp.size() == 0) + { + stream.setstate(ios_base::eofbit|ios_base::failbit); + } - return temp; - } + return temp; + } #ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ - - template <> _UCXXEXPORT string _readToken >(istream & stream); - + template <> _UCXXEXPORT string _readToken >(istream & stream); #endif + template class _UCXXEXPORT __istream_readin + { + public: + static void readin(basic_istream& stream, dataType & var); + }; - template class _UCXXEXPORT __istream_readin{ - public: - static void readin(basic_istream& stream, dataType & var); - }; + template class _UCXXEXPORT __istream_readin + { + public: + inline static void readin(basic_istream& stream, bool & var) + { + /* 22.4.2.1.2.4 */ - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, bool & var) - { - /* 22.4.2.1.2.4 */ - basic_string temp; - temp = _readToken( stream); - if (stream.flags() & ios_base::boolalpha) { - if (temp == "true") // truename() - var = true; - else { - var = false; - if (temp != "false") // falsename() - stream.setstate(ios_base::failbit); - } - } else { - long int i = 0; - int ret; - if (stream.flags() & ios_base::dec) { - ret = sscanf(temp.c_str(), "%ld", &i ); - } else { - if (stream.flags() & ios_base::oct) { - ret = sscanf(temp.c_str(), "%lo", (unsigned long int *)(&i)); - } else if (stream.flags() & ios_base::hex) { - if (stream.flags() & ios_base::uppercase) { - ret = sscanf(temp.c_str(), "%lX", (unsigned long int *)(&i)); - } else { - ret = sscanf(temp.c_str(), "%lx", (unsigned long int *)(&i)); - } - } else { - ret = sscanf(temp.c_str(), "%li", &i); - } - } - if (ret != 1 || i >> 1) - stream.setstate(ios_base::failbit); - var = ret == 1 && bool(i); - } - } - }; + basic_string temp; + temp = _readToken(stream); + if (stream.flags() & ios_base::boolalpha) + { + if (temp == "true") // truename() + { + var = true; + } + else + { + var = false; + if (temp != "false") // falsename() + { + stream.setstate(ios_base::failbit); + } + } + } + else + { + long int i = 0; + int ret; + if (stream.flags() & ios_base::dec) + { + ret = sscanf(temp.c_str(), "%ld", &i); + } + else + { + if (stream.flags() & ios_base::oct) + { + ret = sscanf(temp.c_str(), "%lo", (unsigned long int *)(&i)); + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::uppercase) + { + ret = sscanf(temp.c_str(), "%lX", (unsigned long int *)(&i)); + } + else + { + ret = sscanf(temp.c_str(), "%lx", (unsigned long int *)(&i)); + } + } + else + { + ret = sscanf(temp.c_str(), "%li", &i); + } + } + if (ret != 1 || i >> 1) + { + stream.setstate(ios_base::failbit); + } - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, short & var) - { - basic_string temp; + var = ret == 1 && bool(i); + } + } + }; - if(stream.flags() & ios_base::dec){ - temp = _readTokenDecimal( stream); - sscanf(temp.c_str(), "%hd", &var ); - }else{ - temp = _readToken( stream); - if( stream.flags() & ios_base::oct){ - sscanf(temp.c_str(), "%ho", (unsigned short int *)(&var) ); - }else if(stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::uppercase){ - sscanf(temp.c_str(), "%hX", (unsigned short int *)(&var) ); - }else{ - sscanf(temp.c_str(), "%hx", (unsigned short int *)(&var) ); - } - }else{ - sscanf(temp.c_str(), "%hi", &var); - } - } - } - }; + template class _UCXXEXPORT __istream_readin + { + public: + inline static void readin(basic_istream& stream, short & var) + { + basic_string temp; - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, unsigned short & var) - { - basic_string temp; + if (stream.flags() & ios_base::dec) + { + temp = _readTokenDecimal(stream); + sscanf(temp.c_str(), "%hd", &var); + } + else + { + temp = _readToken(stream); + if (stream.flags() & ios_base::oct) + { + sscanf(temp.c_str(), "%ho", (unsigned short int *)(&var)); + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::uppercase) + { + sscanf(temp.c_str(), "%hX", (unsigned short int *)(&var)); + } + else + { + sscanf(temp.c_str(), "%hx", (unsigned short int *)(&var)); + } + } + else + { + sscanf(temp.c_str(), "%hi", &var); + } + } + } + }; - if(stream.flags() & ios_base::dec){ - temp = _readTokenDecimal( stream); - sscanf(temp.c_str(), "%hu", &var ); - }else{ - temp = _readToken( stream); - if( stream.flags() & ios_base::oct){ - sscanf(temp.c_str(), "%ho", &var); - }else if(stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::uppercase){ - sscanf(temp.c_str(), "%hX", &var ); - }else{ - sscanf(temp.c_str(), "%hx", &var); - } - }else{ - sscanf(temp.c_str(), "%hi", (signed short int*)(&var) ); - } - } - } - }; + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, unsigned short & var) + { + basic_string temp; - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, int & var) - { - basic_string temp; + if (stream.flags() & ios_base::dec) + { + temp = _readTokenDecimal(stream); + sscanf(temp.c_str(), "%hu", &var); + } + else + { + temp = _readToken(stream); + if (stream.flags() & ios_base::oct) + { + sscanf(temp.c_str(), "%ho", &var); + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::uppercase) + { + sscanf(temp.c_str(), "%hX", &var); + } + else + { + sscanf(temp.c_str(), "%hx", &var); + } + } + else + { + sscanf(temp.c_str(), "%hi", (signed short int*)(&var)); + } + } + } + }; - if(stream.flags() & ios_base::dec){ - temp = _readTokenDecimal( stream); - sscanf(temp.c_str(), "%d", &var ); - }else{ - temp = _readToken( stream); - if( stream.flags() & ios_base::oct){ - sscanf(temp.c_str(), "%o", (unsigned int *)(&var) ); - }else if(stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::uppercase){ - sscanf(temp.c_str(), "%X", (unsigned int *)(&var) ); - }else{ - sscanf(temp.c_str(), "%x", (unsigned int *)(&var) ); - } - }else{ - sscanf(temp.c_str(), "%i", &var); - } - } - } - }; + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, int & var) + { + basic_string temp; - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, unsigned int & var) - { - basic_string temp; + if (stream.flags() & ios_base::dec) + { + temp = _readTokenDecimal(stream); + sscanf(temp.c_str(), "%d", &var); + } + else + { + temp = _readToken(stream); + if (stream.flags() & ios_base::oct) + { + sscanf(temp.c_str(), "%o", (unsigned int *)(&var)); + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::uppercase) + { + sscanf(temp.c_str(), "%X", (unsigned int *)(&var)); + } + else + { + sscanf(temp.c_str(), "%x", (unsigned int *)(&var)); + } + } + else + { + sscanf(temp.c_str(), "%i", &var); + } + } + } + }; - if(stream.flags() & ios_base::dec){ - temp = _readTokenDecimal( stream); - sscanf(temp.c_str(), "%u", &var ); - }else{ - temp = _readToken( stream); - if( stream.flags() & ios_base::oct){ - sscanf(temp.c_str(), "%o", (unsigned int *)(&var) ); - }else if(stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::uppercase){ - sscanf(temp.c_str(), "%X", (unsigned int *)(&var) ); - }else{ - sscanf(temp.c_str(), "%x", (unsigned int *)(&var) ); - } - }else{ - sscanf(temp.c_str(), "%i", (int *)(&var) ); - } - } + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, unsigned int & var) + { + basic_string temp; - } - }; + if (stream.flags() & ios_base::dec) + { + temp = _readTokenDecimal(stream); + sscanf(temp.c_str(), "%u", &var); + } + else + { + temp = _readToken(stream); + if (stream.flags() & ios_base::oct) + { + sscanf(temp.c_str(), "%o", (unsigned int *)(&var)); + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::uppercase) + { + sscanf(temp.c_str(), "%X", (unsigned int *)(&var)); + } + else + { + sscanf(temp.c_str(), "%x", (unsigned int *)(&var)); + } + } + else + { + sscanf(temp.c_str(), "%i", (int *)(&var)); + } + } + } + }; + template class _UCXXEXPORT __istream_readin{ + public: + inline static void readin(basic_istream& stream, long int & var) + { + basic_string temp; - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, long int & var) - { - basic_string temp; + if (stream.flags() & ios_base::dec) + { + temp = _readTokenDecimal(stream); + sscanf(temp.c_str(), "%ld", &var); + } + else + { + temp = _readToken(stream); + if (stream.flags() & ios_base::oct) + { + sscanf(temp.c_str(), "%lo", (unsigned long int *)(&var)); + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::uppercase) + { + sscanf(temp.c_str(), "%lX", (unsigned long int *)(&var)); + } + else + { + sscanf(temp.c_str(), "%lx", (unsigned long int *)(&var)); + } + } + else + { + sscanf(temp.c_str(), "%li", (long int *)(&var)); + } + } + } + }; - if(stream.flags() & ios_base::dec){ - temp = _readTokenDecimal( stream); - sscanf(temp.c_str(), "%ld", &var ); - }else{ - temp = _readToken( stream); - if( stream.flags() & ios_base::oct){ - sscanf(temp.c_str(), "%lo", (unsigned long int *)(&var) ); - }else if(stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::uppercase){ - sscanf(temp.c_str(), "%lX", (unsigned long int *)(&var) ); - }else{ - sscanf(temp.c_str(), "%lx", (unsigned long int *)(&var) ); - } - }else{ - sscanf(temp.c_str(), "%li", (long int *)(&var) ); - } - } - - } - }; - - - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, unsigned long int & var) - { - basic_string temp; - - if(stream.flags() & ios_base::dec){ - temp = _readTokenDecimal( stream); - sscanf(temp.c_str(), "%lu", &var ); - }else{ - temp = _readToken( stream); - if( stream.flags() & ios_base::oct){ - sscanf(temp.c_str(), "%lo", &var ); - }else if(stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::uppercase){ - sscanf(temp.c_str(), "%lX", &var ); - }else{ - sscanf(temp.c_str(), "%lx", &var); - } - }else{ - sscanf(temp.c_str(), "%li", (long int *)(&var) ); - } - } - } - }; + template class _UCXXEXPORT __istream_readin + { + public: + inline static void readin(basic_istream& stream, unsigned long int & var) + { + basic_string temp; + if (stream.flags() & ios_base::dec) + { + temp = _readTokenDecimal(stream); + sscanf(temp.c_str(), "%lu", &var); + } + else + { + temp = _readToken(stream); + if (stream.flags() & ios_base::oct) + { + sscanf(temp.c_str(), "%lo", &var); + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::uppercase) + { + sscanf(temp.c_str(), "%lX", &var); + } + else + { + sscanf(temp.c_str(), "%lx", &var); + } + } + else + { + sscanf(temp.c_str(), "%li", (long int *)(&var)); + } + } + } + }; #ifdef CONFIG_HAVE_FLOAT - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, float & var) - { - basic_string temp; - temp = _readTokenDecimal( stream); + template class _UCXXEXPORT __istream_readin + { + public: + inline static void readin(basic_istream& stream, float & var) + { + basic_string temp; + temp = _readTokenDecimal(stream); - sscanf(temp.c_str(), "%g", &var); - } - }; + sscanf(temp.c_str(), "%g", &var); + } + }; - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, double & var) - { - basic_string temp; - temp = _readTokenDecimal( stream); - sscanf(temp.c_str(), "%lg", &var); - } - }; + template class _UCXXEXPORT __istream_readin + { + public: + inline static void readin(basic_istream& stream, double & var) + { + basic_string temp; + temp = _readTokenDecimal(stream); + sscanf(temp.c_str(), "%lg", &var); + } + }; - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, long double & var) - { - basic_string temp; - temp = _readTokenDecimal( stream); - sscanf(temp.c_str(), "%Lg", &var); - } - }; + template class _UCXXEXPORT __istream_readin + { + public: + inline static void readin(basic_istream& stream, long double & var) + { + basic_string temp; + temp = _readTokenDecimal(stream); + sscanf(temp.c_str(), "%Lg", &var); + } + }; -#endif // ifdef CONFIG_HAVE_FLOAT +#endif // ifdef CONFIG_HAVE_FLOAT - template class _UCXXEXPORT __istream_readin{ - public: - inline static void readin(basic_istream& stream, void* & var) - { - basic_string temp; - temp = _readToken( stream); - sscanf(temp.c_str(), "%p", &var); - } - }; + template class _UCXXEXPORT __istream_readin + { + public: + inline static void readin(basic_istream& stream, void* & var) + { + basic_string temp; + temp = _readToken(stream); + sscanf(temp.c_str(), "%p", &var); + } + }; + template void __skipws(basic_istream& is) + { + const typename basic_istream::int_type eof = traits::eof(); + typename basic_istream::int_type c; - template void __skipws(basic_istream& is){ - const typename basic_istream::int_type eof = traits::eof(); - typename basic_istream::int_type c; - //While the next character normally read doesn't equal eof - //and that character is a space, advance to the next read position - //Thus itterating through all whitespace until we get to the meaty stuff - while ( - !traits::eq_int_type((c = is.rdbuf()->sgetc()), eof) - && isspace(c) - ) { - is.rdbuf()->sbumpc(); - } - if(traits::eq_int_type(c, eof)){ - is.setstate(ios_base::eofbit); - } - } -} + // While the next character normally read doesn't equal eof + // and that character is a space, advance to the next read position + // Thus itterating through all whitespace until we get to the meaty stuff + + while ( + !traits::eq_int_type((c = is.rdbuf()->sgetc()), eof) + && isspace(c)) + { + is.rdbuf()->sbumpc(); + } + + if (traits::eq_int_type(c, eof)) + { + is.setstate(ios_base::eofbit); + } + } + +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/iterator b/misc/uClibc++/include/uClibc++/iterator index b3d81b2074..9a690d83da 100644 --- a/misc/uClibc++/include/uClibc++/iterator +++ b/misc/uClibc++/include/uClibc++/iterator @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -23,204 +23,250 @@ #include #include - - #ifndef __STD_HEADER_ITERATOR #define __STD_HEADER_ITERATOR 1 #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ - // subclause _lib.stream.iterators_, stream iterators: - template , class Distance = ptrdiff_t> class istream_iterator; - template bool - operator==(const istream_iterator& x, const istream_iterator& y); - template bool - operator!=(const istream_iterator& x, const istream_iterator& y); - template > class ostream_iterator; - template > class istreambuf_iterator; - template bool - operator==(const istreambuf_iterator& a, const istreambuf_iterator& b); - template bool - operator!=(const istreambuf_iterator& a, const istreambuf_iterator& b); - template > class ostreambuf_iterator; +namespace std +{ + // Subclause _lib.stream.iterators_, stream iterators: - template < class T, class charT, class traits, class Distance > class _UCXXEXPORT istream_iterator - : public iterator - { - public: - typedef charT char_type; - typedef traits traits_type; - typedef basic_istream istream_type; - istream_iterator() : in_stream(0), value(0) {} - istream_iterator(istream_type& s) : in_stream(&s), value() { - *in_stream >> value; - } - istream_iterator(const istream_iterator& x) - : in_stream(x.in_stream), value(x.value) - { } - ~istream_iterator() { } - const T& operator*() const{ - return value; - } - const T* operator->() const{ - return &value; - } - istream_iterator& operator++() { - *in_stream >> value; - return *this; - } - istream_iterator operator++(int){ - istream_iterator tmp = *this; - *in_stream >> value; - return (tmp); - } - bool m_equal(const istream_iterator& x) const{ - return (in_stream == x.in_stream); - } - private: - basic_istream* in_stream; - T value; - }; + template , class Distance = ptrdiff_t> class istream_iterator; + template bool + operator==(const istream_iterator& x, const istream_iterator& y); + template bool + operator!=(const istream_iterator& x, const istream_iterator& y); + template > class ostream_iterator; + template > class istreambuf_iterator; + template bool + operator==(const istreambuf_iterator& a, const istreambuf_iterator& b); + template bool + operator!=(const istreambuf_iterator& a, const istreambuf_iterator& b); + template > class ostreambuf_iterator; - template _UCXXEXPORT - bool operator==(const istream_iterator& x, - const istream_iterator& y) - { - return x.m_equal(y); - } + template < class T, class charT, class traits, class Distance > class _UCXXEXPORT istream_iterator + : public iterator + { + public: + typedef charT char_type; + typedef traits traits_type; + typedef basic_istream istream_type; + istream_iterator() : in_stream(0), value(0) {} - template _UCXXEXPORT - bool operator!=(const istream_iterator& x, - const istream_iterator& y) - { - return !(x == y); - } + istream_iterator(istream_type& s) : in_stream(&s), value() + { + *in_stream >> value; + } - template class _UCXXEXPORT ostream_iterator - : public iterator - { - public: - typedef charT char_type; - typedef traits traits_type; - typedef basic_ostream ostream_type; + istream_iterator(const istream_iterator& x) + : in_stream(x.in_stream), value(x.value) + { } - ostream_iterator(ostream_type& s) : out_stream(&s), delim(0) { } - ostream_iterator(ostream_type& s, const charT* delimiter) : out_stream(&s), delim(delimiter) { } - ostream_iterator(const ostream_iterator& x) : out_stream(x.out_stream), delim(x.delim) { } - ~ostream_iterator() { } - ostream_iterator& operator=(const T& value){ - *out_stream << value; - if(delim != 0){ - *out_stream << delim; - } - return (*this); - } - ostream_iterator& operator*(){ return *this; } - ostream_iterator& operator++() { return *this; } - ostream_iterator operator++(int) { return *this; } - private: - basic_ostream* out_stream; - const char* delim; - }; + ~istream_iterator() { } - template class _UCXXEXPORT istreambuf_iterator : - public iterator - { - public: - typedef charT char_type; - typedef traits traits_type; - typedef typename traits::int_type int_type; - typedef basic_streambuf streambuf_type; - typedef basic_istream istream_type; + const T& operator*() const + { + return value; + } - class _UCXXEXPORT proxy{ - charT val; - basic_streambuf * buf; + const T* operator->() const + { + return &value; + } - proxy(charT v, basic_streambuf * b) : val(v), buf(b) { } - public: - charT operator*() { return val; } - }; + istream_iterator& operator++() + { + *in_stream >> value; + return *this; + } - istreambuf_iterator() throw() : sbuf(0) { } - istreambuf_iterator(istream_type& s) throw() : sbuf(s.rdbuf()) { } - istreambuf_iterator(streambuf_type* s) throw() : sbuf(s) { } - istreambuf_iterator(const proxy& p) throw() : sbuf(&p.buf) { } + istream_iterator operator++(int) + { + istream_iterator tmp = *this; + *in_stream >> value; + return (tmp); + } - charT operator*() const{ - return sbuf->sgetc(); - } - istreambuf_iterator& operator++(){ - sbuf->sbumpc(); - return *this; - } - proxy operator++(int){ - istreambuf_iterator tmp = *this; - sbuf->sbumpc(); - return(tmp); - } + bool m_equal(const istream_iterator& x) const + { + return (in_stream == x.in_stream); + } - bool equal(const istreambuf_iterator& b) const{ - return sbuf == b.sbuf || is_eof() && b.is_eof(); - } - private: - streambuf_type* sbuf; - inline bool is_eof() const{ - return sbuf == 0 || sbuf->sgetc() == traits_type::eof(); - } - }; + private: + basic_istream* in_stream; + T value; + }; - template _UCXXEXPORT bool - operator==(const istreambuf_iterator& a, - const istreambuf_iterator& b) - { - return a.equal(b); - } + template _UCXXEXPORT + bool operator==(const istream_iterator& x, + const istream_iterator& y) + { + return x.m_equal(y); + } - template bool _UCXXEXPORT - operator!=(const istreambuf_iterator& a, - const istreambuf_iterator& b) - { - return !a.equal(b); - } + template _UCXXEXPORT + bool operator!=(const istream_iterator& x, + const istream_iterator& y) + { + return !(x == y); + } - template class _UCXXEXPORT ostreambuf_iterator - : iterator - { - public: - typedef charT char_type; - typedef traits traits_type; - typedef basic_streambuf streambuf_type; - typedef basic_ostream ostream_type; - public: - ostreambuf_iterator(ostream_type& s) throw() : sbuf(s.rdbuf()), f(false) { } - ostreambuf_iterator(streambuf_type* s) throw() : sbuf(s), f(false) { } - ostreambuf_iterator& operator=(charT c){ - if(failed() == false){ - if(sbuf->sputc(c) == traits::eof()){ - f = true; - } - } - return *this; - } - ostreambuf_iterator& operator*(){ - return *this; - } - ostreambuf_iterator& operator++() { return *this; } - ostreambuf_iterator operator++(int) { return *this; } - bool failed() const throw(){ - return f; - } + template class _UCXXEXPORT ostream_iterator + : public iterator + { + public: + typedef charT char_type; + typedef traits traits_type; + typedef basic_ostream ostream_type; - private: - streambuf_type* sbuf; - bool f; - }; + ostream_iterator(ostream_type& s) : out_stream(&s), delim(0) { } + ostream_iterator(ostream_type& s, const charT* delimiter) : out_stream(&s), delim(delimiter) { } + ostream_iterator(const ostream_iterator& x) : out_stream(x.out_stream), delim(x.delim) { } -} + ~ostream_iterator() { } + + ostream_iterator& operator=(const T& value) + { + *out_stream << value; + if (delim != 0) + { + *out_stream << delim; + } + + return (*this); + } + + ostream_iterator& operator*(){ return *this; } + ostream_iterator& operator++() { return *this; } + ostream_iterator operator++(int) { return *this; } + + private: + basic_ostream* out_stream; + const char* delim; + }; + + template class _UCXXEXPORT istreambuf_iterator : + public iterator + { + public: + typedef charT char_type; + typedef traits traits_type; + typedef typename traits::int_type int_type; + typedef basic_streambuf streambuf_type; + typedef basic_istream istream_type; + + class _UCXXEXPORT proxy + { + charT val; + basic_streambuf * buf; + + proxy(charT v, basic_streambuf * b) : val(v), buf(b) { } + + public: + charT operator*() { return val; } + }; + + istreambuf_iterator() throw() : sbuf(0) { } + istreambuf_iterator(istream_type& s) throw() : sbuf(s.rdbuf()) { } + istreambuf_iterator(streambuf_type* s) throw() : sbuf(s) { } + istreambuf_iterator(const proxy& p) throw() : sbuf(&p.buf) { } + + charT operator*() const + { + return sbuf->sgetc(); + } + + istreambuf_iterator& operator++() + { + sbuf->sbumpc(); + return *this; + } + + proxy operator++(int) + { + istreambuf_iterator tmp = *this; + sbuf->sbumpc(); + return(tmp); + } + + bool equal(const istreambuf_iterator& b) const + { + return sbuf == b.sbuf || is_eof() && b.is_eof(); + } + + private: + streambuf_type* sbuf; + + inline bool is_eof() const + { + return sbuf == 0 || sbuf->sgetc() == traits_type::eof(); + } + }; + + template _UCXXEXPORT bool + operator==(const istreambuf_iterator& a, + const istreambuf_iterator& b) + { + return a.equal(b); + } + + template bool _UCXXEXPORT + operator!=(const istreambuf_iterator& a, + const istreambuf_iterator& b) + { + return !a.equal(b); + } + + template class _UCXXEXPORT ostreambuf_iterator + : iterator + { + public: + typedef charT char_type; + typedef traits traits_type; + typedef basic_streambuf streambuf_type; + typedef basic_ostream ostream_type; + public: + ostreambuf_iterator(ostream_type& s) throw() : sbuf(s.rdbuf()), f(false) { } + ostreambuf_iterator(streambuf_type* s) throw() : sbuf(s), f(false) { } + + ostreambuf_iterator& operator=(charT c) + { + if (failed() == false) + { + if (sbuf->sputc(c) == traits::eof()) + { + f = true; + } + } + + return *this; + } + + ostreambuf_iterator& operator*() + { + return *this; + } + + ostreambuf_iterator& operator++() { return *this; } + ostreambuf_iterator operator++(int) { return *this; } + + bool failed() const throw() + { + return f; + } + + private: + streambuf_type* sbuf; + bool f; + }; + +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/iterator_base b/misc/uClibc++/include/uClibc++/iterator_base index 1cae589661..307174440e 100644 --- a/misc/uClibc++/include/uClibc++/iterator_base +++ b/misc/uClibc++/include/uClibc++/iterator_base @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include @@ -24,282 +24,320 @@ #pragma GCC visibility push(default) -namespace std{ - template struct iterator_traits; - template struct iterator_traits; +extern "C++" +{ - template struct iterator; +namespace std +{ + template struct iterator_traits; + template struct iterator_traits; - struct _UCXXEXPORT input_iterator_tag {}; - struct _UCXXEXPORT output_iterator_tag {}; - struct _UCXXEXPORT forward_iterator_tag: public input_iterator_tag {}; - struct _UCXXEXPORT bidirectional_iterator_tag: public forward_iterator_tag {}; - struct _UCXXEXPORT random_access_iterator_tag: public bidirectional_iterator_tag {}; + template struct iterator; - template _UCXXEXPORT void advance(InputIterator& i, Distance n){ - while(n > 0){ - --n; - ++i; - } - } + struct _UCXXEXPORT input_iterator_tag {}; + struct _UCXXEXPORT output_iterator_tag {}; + struct _UCXXEXPORT forward_iterator_tag: public input_iterator_tag {}; + struct _UCXXEXPORT bidirectional_iterator_tag: public forward_iterator_tag {}; + struct _UCXXEXPORT random_access_iterator_tag: public bidirectional_iterator_tag {}; - template _UCXXEXPORT typename iterator_traits::difference_type - distance(InputIterator first, InputIterator last) - { - typename iterator_traits::difference_type d = 0; - while(first++ !=last){ - d++; - } - return d; - } + template _UCXXEXPORT void advance(InputIterator& i, Distance n) + { + while (n > 0) + { + --n; + ++i; + } + } + + template _UCXXEXPORT typename iterator_traits::difference_type + distance(InputIterator first, InputIterator last) + { + typename iterator_traits::difference_type d = 0; + while (first++ !=last) + { + d++; + } + return d; + } // subclause _lib.predef.iterators_, predefined iterators: - template class reverse_iterator; - template bool operator==(const reverse_iterator& x, const reverse_iterator& y); - template bool operator<(const reverse_iterator& x, const reverse_iterator& y); - template bool operator!=(const reverse_iterator& x, const reverse_iterator& y); - template bool operator>(const reverse_iterator& x, const reverse_iterator& y); - template bool operator>=(const reverse_iterator& x, const reverse_iterator& y); - template bool operator<=(const reverse_iterator& x, const reverse_iterator& y); - template typename reverse_iterator::difference_type - operator-( const reverse_iterator& x, const reverse_iterator& y); - template reverse_iterator - operator+( typename reverse_iterator::difference_type n, const reverse_iterator& x); - template class back_insert_iterator; - template back_insert_iterator back_inserter(Container& x); - template class front_insert_iterator; - template front_insert_iterator front_inserter(Container& x); - template class insert_iterator; - template - insert_iterator inserter(Container& x, Iterator i); - //Actual Template definitions + template class reverse_iterator; + template bool operator==(const reverse_iterator& x, const reverse_iterator& y); + template bool operator<(const reverse_iterator& x, const reverse_iterator& y); + template bool operator!=(const reverse_iterator& x, const reverse_iterator& y); + template bool operator>(const reverse_iterator& x, const reverse_iterator& y); + template bool operator>=(const reverse_iterator& x, const reverse_iterator& y); + template bool operator<=(const reverse_iterator& x, const reverse_iterator& y); + template typename reverse_iterator::difference_type + operator-( const reverse_iterator& x, const reverse_iterator& y); + template reverse_iterator + operator+( typename reverse_iterator::difference_type n, const reverse_iterator& x); + template class back_insert_iterator; + template back_insert_iterator back_inserter(Container& x); + template class front_insert_iterator; + template front_insert_iterator front_inserter(Container& x); + template class insert_iterator; + template + insert_iterator inserter(Container& x, Iterator i); - template struct _UCXXEXPORT iterator_traits { - typedef typename Iterator::difference_type difference_type; - typedef typename Iterator::value_type value_type; - typedef typename Iterator::pointer pointer; - typedef typename Iterator::reference reference; - typedef typename Iterator::iterator_category iterator_category; - }; + // Actual Template definitions - //Pointer specialization - required by standard - template struct _UCXXEXPORT iterator_traits { - typedef ptrdiff_t difference_type; - typedef T value_type; - typedef T* pointer; - typedef T& reference; - typedef random_access_iterator_tag iterator_category; - }; + template struct _UCXXEXPORT iterator_traits + { + typedef typename Iterator::difference_type difference_type; + typedef typename Iterator::value_type value_type; + typedef typename Iterator::pointer pointer; + typedef typename Iterator::reference reference; + typedef typename Iterator::iterator_category iterator_category; + }; - //Specialization recomended by standard -/* template struct _UCXXEXPORT iterator_traits { - typedef long difference_type; - typedef T value_type; - typedef T __far* pointer; - typedef T __far& reference; - typedef random_access_iterator_tag iterator_category; - };*/ + //Pointer specialization - required by standard -/* template _UCXXEXPORT void - reverse(BidirectionalIterator first, BidirectionalIterator last) - { - typename iterator_traits::difference_type n = distance(first, last); - --n; - while(n > 0){ - typename iterator_traits::value_type tmp = *first; - *first++ = * --last; - *last = tmp; - n -= 2; - } - };*/ + template struct _UCXXEXPORT iterator_traits + { + typedef ptrdiff_t difference_type; + typedef T value_type; + typedef T* pointer; + typedef T& reference; + typedef random_access_iterator_tag iterator_category; + }; + + //Specialization recomended by standard + +/* template struct _UCXXEXPORT iterator_traits + { + typedef long difference_type; + typedef T value_type; + typedef T __far* pointer; + typedef T __far& reference; + typedef random_access_iterator_tag iterator_category; + };*/ + +/* template _UCXXEXPORT void + reverse(BidirectionalIterator first, BidirectionalIterator last) + { + typename iterator_traits::difference_type n = distance(first, last); + --n; + while(n > 0) + { + typename iterator_traits::value_type tmp = *first; + *first++ = * --last; + *last = tmp; + n -= 2; + } + };*/ + + template + struct _UCXXEXPORT iterator + { + typedef T value_type; + typedef Distance difference_type; + typedef Pointer pointer; + typedef Reference reference; + typedef Category iterator_category; + }; - template - struct _UCXXEXPORT iterator - { - typedef T value_type; - typedef Distance difference_type; - typedef Pointer pointer; - typedef Reference reference; - typedef Category iterator_category; - }; + template class _UCXXEXPORT reverse_iterator + : public iterator::iterator_category, + typename iterator_traits::value_type, typename iterator_traits::difference_type, + typename iterator_traits::pointer, typename iterator_traits::reference> + { + protected: + Iterator current; + friend bool operator== (const reverse_iterator& x, const reverse_iterator& y); + friend bool operator< (const reverse_iterator& x, const reverse_iterator& y); + public: + typedef Iterator iterator_type; - template class _UCXXEXPORT reverse_iterator - : public iterator::iterator_category, - typename iterator_traits::value_type, typename iterator_traits::difference_type, - typename iterator_traits::pointer, typename iterator_traits::reference> - { - protected: - Iterator current; - friend bool operator== (const reverse_iterator& x, const reverse_iterator& y); - friend bool operator< (const reverse_iterator& x, const reverse_iterator& y); + reverse_iterator() : current(){}; + explicit reverse_iterator(Iterator x) : current(x) { } + template reverse_iterator(const reverse_iterator &x) : current(x.base()){} - public: - typedef Iterator iterator_type; + Iterator base() const { return current; } // explicit - reverse_iterator() : current(){}; - explicit reverse_iterator(Iterator x) : current(x) { } - template reverse_iterator(const reverse_iterator &x) : current(x.base()){} + typename iterator_traits::reference operator*() const { Iterator tmp = current; return *--tmp; } + typename iterator_traits::pointer operator->() const { return &(operator*()); } + typename iterator_traits::reference operator[](typename iterator_traits::difference_type n) const + { + return current[-n-1]; + } - Iterator base() const { return current; } // explicit + reverse_iterator& operator++(){ --current; return *this; } + reverse_iterator operator++(int) {reverse_iterator tmp = *this; --current; return tmp; } + reverse_iterator& operator--() { ++ current; return *this; } + reverse_iterator operator--(int) {reverse_iterator tmp = *this; ++current; return tmp; } - typename iterator_traits::reference operator*() const { Iterator tmp = current; return *--tmp; } - typename iterator_traits::pointer operator->() const { return &(operator*()); } - typename iterator_traits::reference operator[](typename iterator_traits::difference_type n) const{ - return current[-n-1]; - } + reverse_iterator operator+ (typename iterator_traits::difference_type n) const + { + reverse_iterator retval( *this ); + retval+=n; + return retval; + } - reverse_iterator& operator++(){ --current; return *this; } - reverse_iterator operator++(int) {reverse_iterator tmp = *this; --current; return tmp; } - reverse_iterator& operator--() { ++ current; return *this; } - reverse_iterator operator--(int) {reverse_iterator tmp = *this; ++current; return tmp; } + reverse_iterator& operator+=(typename iterator_traits::difference_type n) + { + current -= n; + return *this; + } - reverse_iterator operator+ (typename iterator_traits::difference_type n) const{ - reverse_iterator retval( *this ); - retval+=n; - return retval; - } - reverse_iterator& operator+=(typename iterator_traits::difference_type n){ - current -= n; - return *this; - } - reverse_iterator operator- (typename iterator_traits::difference_type n) const{ - reverse_iterator retval( *this ); - retval-=n; - return retval; - } - reverse_iterator& operator-=(typename iterator_traits::difference_type n){ - current += n; - return *this; - } - }; + reverse_iterator operator- (typename iterator_traits::difference_type n) const + { + reverse_iterator retval( *this ); + retval-=n; + return retval; + } + reverse_iterator& operator-=(typename iterator_traits::difference_type n) + { + current += n; + return *this; + } + }; - template _UCXXEXPORT bool - operator==(const reverse_iterator& x, const reverse_iterator& y) - { - return x.base() == y.base(); - } - template _UCXXEXPORT bool - operator<(const reverse_iterator& x, const reverse_iterator& y) - { - return x.base() < y.base(); - } - template _UCXXEXPORT bool - operator!=(const reverse_iterator& x, const reverse_iterator& y) - { - return x.base() != y.base(); - } - template _UCXXEXPORT bool - operator>(const reverse_iterator& x, const reverse_iterator& y) - { - return x.base() > y.base(); - } - template _UCXXEXPORT bool - operator>=(const reverse_iterator& x, const reverse_iterator& y) - { - return x.base() >= y.base(); - } - template _UCXXEXPORT bool - operator<=(const reverse_iterator& x, const reverse_iterator& y) - { - return x.base() <= y.base(); - } - template _UCXXEXPORT typename reverse_iterator::difference_type - operator-( const reverse_iterator& x, const reverse_iterator& y) - { - return y.base() - x.base(); - } - template _UCXXEXPORT reverse_iterator - operator+(typename reverse_iterator::difference_type n, const reverse_iterator& x) - { - return reverse_iterator (x.base() - n); - } + template _UCXXEXPORT bool + operator==(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() == y.base(); + } - template class _UCXXEXPORT back_insert_iterator : - public iterator - { - protected: - Container& container; - public: - typedef Container container_type; - explicit back_insert_iterator(Container& x):container(x) {}; - back_insert_iterator& operator=(const typename Container::value_type& value){ - container.push_back(value); - return *this; - } - back_insert_iterator& operator*(){ - return *this; - } - back_insert_iterator& operator++(){ - return *this; - } - back_insert_iterator operator++(int){ - return *this; - } - }; + template _UCXXEXPORT bool + operator<(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() < y.base(); + } - template _UCXXEXPORT back_insert_iterator - back_inserter(Container& x) - { - return back_insert_iterator(x); - } + template _UCXXEXPORT bool + operator!=(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() != y.base(); + } - template class _UCXXEXPORT front_insert_iterator - : public iterator - { - protected: - Container& container; - public: - typedef Container container_type; - explicit front_insert_iterator(Container& x): container(x) {} - front_insert_iterator& operator=(const typename Container::value_type& value){ - container.push_front(value); - return *this; - } + template _UCXXEXPORT bool + operator>(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() > y.base(); + } - front_insert_iterator& operator*() { return *this; } - front_insert_iterator& operator++() { return *this; } - front_insert_iterator operator++(int) { return *this; } - }; + template _UCXXEXPORT bool + operator>=(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() >= y.base(); + } - template _UCXXEXPORT front_insert_iterator - front_inserter(Container& x) - { - return front_insert_iterator(x); - } + template _UCXXEXPORT bool + operator<=(const reverse_iterator& x, const reverse_iterator& y) + { + return x.base() <= y.base(); + } - template class _UCXXEXPORT insert_iterator - : public iterator - { - protected: - Container& container; - typename Container::iterator iter; - public: - typedef Container container_type; - insert_iterator(Container& x, typename Container::iterator i) : container(x), iter(i) {} - insert_iterator& operator=(const typename Container::value_type& value){ - iter = container.insert(iter, value); - ++iter; - return *this; - } - insert_iterator& operator*() { return *this; } - insert_iterator& operator++() { return *this; } - insert_iterator operator++(int) { return *this; } - }; + template _UCXXEXPORT typename reverse_iterator::difference_type + operator-( const reverse_iterator& x, const reverse_iterator& y) + { + return y.base() - x.base(); + } - template _UCXXEXPORT insert_iterator - inserter(Container& x, Iterator i) - { - return insert_iterator(x,typename Container::iterator(i)); - } + template _UCXXEXPORT reverse_iterator + operator+(typename reverse_iterator::difference_type n, const reverse_iterator& x) + { + return reverse_iterator (x.base() - n); + } -} + template class _UCXXEXPORT back_insert_iterator : + public iterator + { + protected: + Container& container; + public: + typedef Container container_type; + explicit back_insert_iterator(Container& x):container(x) {}; + + back_insert_iterator& operator=(const typename Container::value_type& value) + { + container.push_back(value); + return *this; + } + + back_insert_iterator& operator*() + { + return *this; + } + + back_insert_iterator& operator++() + { + return *this; + } + + back_insert_iterator operator++(int) + { + return *this; + } + }; + + template _UCXXEXPORT back_insert_iterator + back_inserter(Container& x) + { + return back_insert_iterator(x); + } + + template class _UCXXEXPORT front_insert_iterator + : public iterator + { + protected: + Container& container; + public: + typedef Container container_type; + explicit front_insert_iterator(Container& x): container(x) {} + + front_insert_iterator& operator=(const typename Container::value_type& value) + { + container.push_front(value); + return *this; + } + + front_insert_iterator& operator*() { return *this; } + front_insert_iterator& operator++() { return *this; } + front_insert_iterator operator++(int) { return *this; } + }; + + template _UCXXEXPORT front_insert_iterator + front_inserter(Container& x) + { + return front_insert_iterator(x); + } + + template class _UCXXEXPORT insert_iterator + : public iterator + { + protected: + Container& container; + typename Container::iterator iter; + public: + typedef Container container_type; + insert_iterator(Container& x, typename Container::iterator i) : container(x), iter(i) {} + + insert_iterator& operator=(const typename Container::value_type& value) + { + iter = container.insert(iter, value); + ++iter; + return *this; + } + + insert_iterator& operator*() { return *this; } + insert_iterator& operator++() { return *this; } + insert_iterator operator++(int) { return *this; } + }; + + template _UCXXEXPORT insert_iterator + inserter(Container& x, Iterator i) + { + return insert_iterator(x,typename Container::iterator(i)); + } + +} // namespace +} // extern "C++" #pragma GCC visibility pop - -#endif - - +#endif // __STD_HEADER_ITERATOR_BASE diff --git a/misc/uClibc++/include/uClibc++/limits b/misc/uClibc++/include/uClibc++/limits index e275eb5ec0..0b5b159e99 100644 --- a/misc/uClibc++/include/uClibc++/limits +++ b/misc/uClibc++/include/uClibc++/limits @@ -1,20 +1,20 @@ -/* Copyright (C) 2006 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2006 Garrett A. Kajmowicz + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include @@ -25,638 +25,795 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ -enum float_round_style{ - round_indeterminate =-1, - round_toward_zero = 0, - round_to_nearest = 1, - round_toward_infinity = 2, - round_toward_neg_infinity = 3 +enum float_round_style +{ + round_indeterminate = -1, + round_toward_zero = 0, + round_to_nearest = 1, + round_toward_infinity = 2, + round_toward_neg_infinity = 3 }; -template struct __bits_to_base_10{ - static const int size = -1; -}; -template <> struct __bits_to_base_10<7>{ - static const int size = 2; -}; -template <> struct __bits_to_base_10<8>{ - static const int size = 2; -}; -template <> struct __bits_to_base_10<9>{ - static const int size = 2; -}; -template <> struct __bits_to_base_10<10>{ - static const int size = 3; -}; -template <> struct __bits_to_base_10<15>{ - static const int size = 4; -}; -template <> struct __bits_to_base_10<16>{ - static const int size = 4; -}; -template <> struct __bits_to_base_10<17>{ - static const int size = 5; -}; -template <> struct __bits_to_base_10<18>{ - static const int size = 5; -}; -template <> struct __bits_to_base_10<31>{ - static const int size = 9; -}; -template <> struct __bits_to_base_10<32>{ - static const int size = 9; -}; -template <> struct __bits_to_base_10<35>{ - static const int size = 10; -}; -template <> struct __bits_to_base_10<36>{ - static const int size = 10; -}; -template <> struct __bits_to_base_10<63>{ - static const int size = 18; -}; -template <> struct __bits_to_base_10<64>{ - static const int size = 19; -}; -template <> struct __bits_to_base_10<71>{ - static const int size = 21; -}; -template <> struct __bits_to_base_10<72>{ - static const int size = 21; -}; -template <> struct __bits_to_base_10<79>{ - static const int size = 23; -}; -template <> struct __bits_to_base_10<80>{ - static const int size = 24; -}; -template <> struct __bits_to_base_10<127>{ - static const int size = 38; -}; -template <> struct __bits_to_base_10<128>{ - static const int size = 38; +template struct __bits_to_base_10 +{ + static const int size = -1; }; +template <> struct __bits_to_base_10<7> +{ + static const int size = 2; +}; +template <> struct __bits_to_base_10<8> +{ + static const int size = 2; +}; +template <> struct __bits_to_base_10<9> +{ + static const int size = 2; +}; +template <> struct __bits_to_base_10<10> +{ + static const int size = 3; +}; +template <> struct __bits_to_base_10<15> +{ + static const int size = 4; +}; -template class numeric_limits { +template <> struct __bits_to_base_10<16> +{ + static const int size = 4; +}; + +template <> struct __bits_to_base_10<17> +{ + static const int size = 5; +}; + +template <> struct __bits_to_base_10<18> +{ + static const int size = 5; +}; + +template <> struct __bits_to_base_10<31> +{ + static const int size = 9; +}; + +template <> struct __bits_to_base_10<32> +{ + static const int size = 9; +}; + +template <> struct __bits_to_base_10<35> +{ + static const int size = 10; +}; + +template <> struct __bits_to_base_10<36> +{ + static const int size = 10; +}; + +template <> struct __bits_to_base_10<63> +{ + static const int size = 18; +}; + +template <> struct __bits_to_base_10<64> +{ + static const int size = 19; +}; + +template <> struct __bits_to_base_10<71> +{ + static const int size = 21; +}; + +template <> struct __bits_to_base_10<72> +{ + static const int size = 21; +}; + +template <> struct __bits_to_base_10<79> +{ + static const int size = 23; +}; + +template <> struct __bits_to_base_10<80> +{ + static const int size = 24; +}; + +template <> struct __bits_to_base_10<127> +{ + static const int size = 38; +}; + +template <> struct __bits_to_base_10<128> +{ + static const int size = 38; +}; + +template class numeric_limits +{ public: - // General -- meaningful for all specializations. + // General -- meaningful for all specializations. - static const bool is_specialized = false; - static T min(); - static T max(); - static const int radix; - static const int digits; - static const int digits10; - static const bool is_signed; - static const bool is_integer; - static const bool is_exact; - static const bool traps; - static const bool is_modulo; - static const bool is_bounded; + static const bool is_specialized = false; + static T min(); + static T max(); + static const int radix; + static const int digits; + static const int digits10; + static const bool is_signed; + static const bool is_integer; + static const bool is_exact; + static const bool traps; + static const bool is_modulo; + static const bool is_bounded; - // Floating point specific. + // Floating point specific. - static T epsilon(); - static T round_error(); - static const int min_exponent10; - static const int max_exponent10; - static const int min_exponent; + static T epsilon(); + static T round_error(); + static const int min_exponent10; + static const int max_exponent10; + static const int min_exponent; - static const int max_exponent; - static const bool has_infinity; - static const bool has_quiet_NaN; - static const bool has_signaling_NaN; - static const bool is_iec559; - static const bool has_denorm; - static const bool tinyness_before; - static const float_round_style round_style; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static const int max_exponent; + static const bool has_infinity; + static const bool has_quiet_NaN; + static const bool has_signaling_NaN; + static const bool is_iec559; + static const bool has_denorm; + static const bool tinyness_before; + static const float_round_style round_style; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef bool T; - // General -- meaningful for all specializations. - static const bool is_specialized = true; - static T min(){ - return false; - } - static T max(){ - return true; - } - static const int radix = 2; - static const int digits = 1; - static const int digits10 = 0; - static const bool is_signed = false; - static const bool is_integer = true; - static const bool is_exact = true; - static const bool traps = false; - static const bool is_modulo = false; - static const bool is_bounded = true; + typedef bool T; - // Floating point specific. + // General -- meaningful for all specializations. - static T epsilon(){ - return 0; - } - static T round_error(){ - return 0; - } - static const int min_exponent10 = 0; - static const int max_exponent10 = 0; - static const int min_exponent = 0; + static const bool is_specialized = true; - static const int max_exponent = 0; - static const bool has_infinity = false; - static const bool has_quiet_NaN = false; - static const bool has_signaling_NaN = false; - static const bool is_iec559 = false; - static const bool has_denorm = false; - static const bool tinyness_before = false; - static const float_round_style round_style = round_indeterminate; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static T min() + { + return false; + } + + static T max() + { + return true; + } + + static const int radix = 2; + static const int digits = 1; + static const int digits10 = 0; + static const bool is_signed = false; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = false; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon() + { + return 0; + } + + static T round_error() + { + return 0; + } + + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef unsigned char T; - // General -- meaningful for all specializations. - static const bool is_specialized = true; - static T min(){ - return 0; - } - static T max(){ - return UCHAR_MAX; - } - static const int radix = 2; - static const int digits = CHAR_BIT; - static const int digits10 = __bits_to_base_10::size; - static const bool is_signed = false; - static const bool is_integer = true; - static const bool is_exact = true; - static const bool traps = false; - static const bool is_modulo = true; - static const bool is_bounded = true; + typedef unsigned char T; - // Floating point specific. + // General -- meaningful for all specializations. - static T epsilon(){ - return 0; - } - static T round_error(){ - return 0; - } - static const int min_exponent10 = 0; - static const int max_exponent10 = 0; - static const int min_exponent = 0; + static const bool is_specialized = true; - static const int max_exponent = 0; - static const bool has_infinity = false; - static const bool has_quiet_NaN = false; - static const bool has_signaling_NaN = false; - static const bool is_iec559 = false; - static const bool has_denorm = false; - static const bool tinyness_before = false; - static const float_round_style round_style = round_indeterminate; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static T min() + { + return 0; + } + + static T max() + { + return UCHAR_MAX; + } + + static const int radix = 2; + static const int digits = CHAR_BIT; + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = false; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon() + { + return 0; + } + + static T round_error() + { + return 0; + } + + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef signed char T; - // General -- meaningful for all specializations. - static const bool is_specialized = true; - static T min(){ - return SCHAR_MIN; - } - static T max(){ - return SCHAR_MAX; - } - static const int radix = 2; - static const int digits = CHAR_BIT - 1; - static const int digits10 = __bits_to_base_10::size; - static const bool is_signed = true; - static const bool is_integer = true; - static const bool is_exact = true; - static const bool traps = false; - static const bool is_modulo = true; - static const bool is_bounded = true; + typedef signed char T; - // Floating point specific. + // General -- meaningful for all specializations. - static T epsilon(){ - return 0; - } - static T round_error(){ - return 0; - } - static const int min_exponent10 = 0; - static const int max_exponent10 = 0; - static const int min_exponent = 0; + static const bool is_specialized = true; - static const int max_exponent = 0; - static const bool has_infinity = false; - static const bool has_quiet_NaN = false; - static const bool has_signaling_NaN = false; - static const bool is_iec559 = false; - static const bool has_denorm = false; - static const bool tinyness_before = false; - static const float_round_style round_style = round_indeterminate; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static T min() + { + return SCHAR_MIN; + } + + static T max() + { + return SCHAR_MAX; + } + + static const int radix = 2; + static const int digits = CHAR_BIT - 1; + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = true; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon() + { + return 0; + } + + static T round_error() + { + return 0; + } + + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef char T; - // General -- meaningful for all specializations. - static const bool is_specialized = true; - static T min(){ - return CHAR_MIN; - } - static T max(){ - return CHAR_MAX; - } - static const int radix = 2; - static const int digits = (CHAR_MIN != 0) ? CHAR_BIT - 1 : CHAR_BIT; - static const int digits10 = __bits_to_base_10::size; - static const bool is_signed = (CHAR_MIN != 0); - static const bool is_integer = true; - static const bool is_exact = true; - static const bool traps = false; - static const bool is_modulo = true; - static const bool is_bounded = true; + typedef char T; - // Floating point specific. + // General -- meaningful for all specializations. - static T epsilon(){ - return 0; - } - static T round_error(){ - return 0; - } - static const int min_exponent10 = 0; - static const int max_exponent10 = 0; - static const int min_exponent = 0; + static const bool is_specialized = true; - static const int max_exponent = 0; - static const bool has_infinity = false; - static const bool has_quiet_NaN = false; - static const bool has_signaling_NaN = false; - static const bool is_iec559 = false; - static const bool has_denorm = false; - static const bool tinyness_before = false; - static const float_round_style round_style = round_indeterminate; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static T min() + { + return CHAR_MIN; + } + + static T max() + { + return CHAR_MAX; + } + + static const int radix = 2; + static const int digits = (CHAR_MIN != 0) ? CHAR_BIT - 1 : CHAR_BIT; + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = (CHAR_MIN != 0); + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon(){ + return 0; + } + + static T round_error(){ + return 0; + } + + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef unsigned short T; - // General -- meaningful for all specializations. - static const bool is_specialized = true; - static T min(){ - return 0; - } - static T max(){ - return USHRT_MAX; - } - static const int radix = 2; - static const int digits = CHAR_BIT * sizeof(T); - static const int digits10 = __bits_to_base_10::size; - static const bool is_signed = false; - static const bool is_integer = true; - static const bool is_exact = true; - static const bool traps = false; - static const bool is_modulo = true; - static const bool is_bounded = true; + typedef unsigned short T; - // Floating point specific. + // General -- meaningful for all specializations. - static T epsilon(){ - return 0; - } - static T round_error(){ - return 0; - } - static const int min_exponent10 = 0; - static const int max_exponent10 = 0; - static const int min_exponent = 0; + static const bool is_specialized = true; - static const int max_exponent = 0; - static const bool has_infinity = false; - static const bool has_quiet_NaN = false; - static const bool has_signaling_NaN = false; - static const bool is_iec559 = false; - static const bool has_denorm = false; - static const bool tinyness_before = false; - static const float_round_style round_style = round_indeterminate; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static T min() + { + return 0; + } + + static T max() + { + return USHRT_MAX; + } + + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = false; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon() + { + return 0; + } + + static T round_error() + { + return 0; + } + + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef signed short T; - // General -- meaningful for all specializations. - static const bool is_specialized = true; - static T min(){ - return SHRT_MIN; - } - static T max(){ - return SHRT_MAX; - } - static const int radix = 2; - static const int digits = CHAR_BIT * sizeof(T); - static const int digits10 = __bits_to_base_10::size; - static const bool is_signed = true; - static const bool is_integer = true; - static const bool is_exact = true; - static const bool traps = false; - static const bool is_modulo = true; - static const bool is_bounded = true; + typedef signed short T; - // Floating point specific. + // General -- meaningful for all specializations. - static T epsilon(){ - return 0; - } - static T round_error(){ - return 0; - } - static const int min_exponent10 = 0; - static const int max_exponent10 = 0; - static const int min_exponent = 0; + static const bool is_specialized = true; - static const int max_exponent = 0; - static const bool has_infinity = false; - static const bool has_quiet_NaN = false; - static const bool has_signaling_NaN = false; - static const bool is_iec559 = false; - static const bool has_denorm = false; - static const bool tinyness_before = false; - static const float_round_style round_style = round_indeterminate; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static T min() + { + return SHRT_MIN; + } + + static T max() + { + return SHRT_MAX; + } + + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = true; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon() + { + return 0; + } + + static T round_error() + { + return 0; + } + + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef unsigned int T; - // General -- meaningful for all specializations. - static const bool is_specialized = true; - static T min(){ - return 0; - } - static T max(){ - return UINT_MAX; - } - static const int radix = 2; - static const int digits = CHAR_BIT * sizeof(T); - static const int digits10 = __bits_to_base_10::size; - static const bool is_signed = false; - static const bool is_integer = true; - static const bool is_exact = true; - static const bool traps = false; - static const bool is_modulo = true; - static const bool is_bounded = true; + typedef unsigned int T; - // Floating point specific. + // General -- meaningful for all specializations. - static T epsilon(){ - return 0; - } - static T round_error(){ - return 0; - } - static const int min_exponent10 = 0; - static const int max_exponent10 = 0; - static const int min_exponent = 0; + static const bool is_specialized = true; - static const int max_exponent = 0; - static const bool has_infinity = false; - static const bool has_quiet_NaN = false; - static const bool has_signaling_NaN = false; - static const bool is_iec559 = false; - static const bool has_denorm = false; - static const bool tinyness_before = false; - static const float_round_style round_style = round_indeterminate; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static T min() + { + return 0; + } + + static T max() + { + return UINT_MAX; + } + + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = false; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon() + { + return 0; + } + + static T round_error() + { + return 0; + } + + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef signed int T; - // General -- meaningful for all specializations. - static const bool is_specialized = true; - static T min(){ - return INT_MIN; - } - static T max(){ - return INT_MAX; - } - static const int radix = 2; - static const int digits = CHAR_BIT * sizeof(T); - static const int digits10 = __bits_to_base_10::size; - static const bool is_signed = true; - static const bool is_integer = true; - static const bool is_exact = true; - static const bool traps = false; - static const bool is_modulo = true; - static const bool is_bounded = true; + typedef signed int T; - // Floating point specific. + // General -- meaningful for all specializations. - static T epsilon(){ - return 0; - } - static T round_error(){ - return 0; - } - static const int min_exponent10 = 0; - static const int max_exponent10 = 0; - static const int min_exponent = 0; + static const bool is_specialized = true; - static const int max_exponent = 0; - static const bool has_infinity = false; - static const bool has_quiet_NaN = false; - static const bool has_signaling_NaN = false; - static const bool is_iec559 = false; - static const bool has_denorm = false; - static const bool tinyness_before = false; - static const float_round_style round_style = round_indeterminate; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static T min() + { + return INT_MIN; + } + + static T max() + { + return INT_MAX; + } + + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = true; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon() + { + return 0; + } + + static T round_error() + { + return 0; + } + + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef unsigned long int T; - // General -- meaningful for all specializations. - static const bool is_specialized = true; - static T min(){ - return 0; - } - static T max(){ - return ULONG_MAX; - } - static const int radix = 2; - static const int digits = CHAR_BIT * sizeof(T); - static const int digits10 = __bits_to_base_10::size; - static const bool is_signed = false; - static const bool is_integer = true; - static const bool is_exact = true; - static const bool traps = false; - static const bool is_modulo = true; - static const bool is_bounded = true; + typedef unsigned long int T; - // Floating point specific. + // General -- meaningful for all specializations. - static T epsilon(){ - return 0; - } - static T round_error(){ - return 0; - } - static const int min_exponent10 = 0; - static const int max_exponent10 = 0; - static const int min_exponent = 0; + static const bool is_specialized = true; - static const int max_exponent = 0; - static const bool has_infinity = false; - static const bool has_quiet_NaN = false; - static const bool has_signaling_NaN = false; - static const bool is_iec559 = false; - static const bool has_denorm = false; - static const bool tinyness_before = false; - static const float_round_style round_style = round_indeterminate; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static T min( + ){ + return 0; + } + + static T max() + { + return ULONG_MAX; + } + + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = false; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon() + { + return 0; + } + + static T round_error() + { + return 0; + } + + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef signed long int T; - // General -- meaningful for all specializations. - static const bool is_specialized = true; - static T min(){ - return LONG_MIN; - } - static T max(){ - return LONG_MAX; - } - static const int radix = 2; - static const int digits = CHAR_BIT * sizeof(T); - static const int digits10 = __bits_to_base_10::size; - static const bool is_signed = true; - static const bool is_integer = true; - static const bool is_exact = true; - static const bool traps = false; - static const bool is_modulo = true; - static const bool is_bounded = true; + typedef signed long int T; - // Floating point specific. + // General -- meaningful for all specializations. - static T epsilon(){ - return 0; - } - static T round_error(){ - return 0; - } - static const int min_exponent10 = 0; - static const int max_exponent10 = 0; - static const int min_exponent = 0; + static const bool is_specialized = true; - static const int max_exponent = 0; - static const bool has_infinity = false; - static const bool has_quiet_NaN = false; - static const bool has_signaling_NaN = false; - static const bool is_iec559 = false; - static const bool has_denorm = false; - static const bool tinyness_before = false; - static const float_round_style round_style = round_indeterminate; - static T denorm_min(); - static T infinity(); - static T quiet_NaN(); - static T signaling_NaN(); + static T min() + { + return LONG_MIN; + } + + static T max() + { + return LONG_MAX; + } + + static const int radix = 2; + static const int digits = CHAR_BIT * sizeof(T); + static const int digits10 = __bits_to_base_10::size; + static const bool is_signed = true; + static const bool is_integer = true; + static const bool is_exact = true; + static const bool traps = false; + static const bool is_modulo = true; + static const bool is_bounded = true; + + // Floating point specific. + + static T epsilon() + { + return 0; + } + + static T round_error() + { + return 0; + } + + static const int min_exponent10 = 0; + static const int max_exponent10 = 0; + static const int min_exponent = 0; + + static const int max_exponent = 0; + static const bool has_infinity = false; + static const bool has_quiet_NaN = false; + static const bool has_signaling_NaN = false; + static const bool is_iec559 = false; + static const bool has_denorm = false; + static const bool tinyness_before = false; + static const float_round_style round_style = round_indeterminate; + static T denorm_min(); + static T infinity(); + static T quiet_NaN(); + static T signaling_NaN(); }; -template <> class numeric_limits { +template <> class numeric_limits +{ public: - typedef double numeric_type; + typedef double numeric_type; - static const bool is_specialized = true; - static numeric_type min () { return __DBL_MIN__; } - static numeric_type max () { return __DBL_MAX__; } - static const int radix = __FLT_RADIX__; - static const int digits = __DBL_MANT_DIG__; - static const int digits10 = __DBL_DIG__; - static const bool is_signed = true; - static const bool is_integer = false; - static const bool is_exact = false; - static const bool traps = false; // this is a guess - static const bool is_modulo = false; - static const bool is_bounded = true; + static const bool is_specialized = true; + static numeric_type min () { return __DBL_MIN__; } + static numeric_type max () { return __DBL_MAX__; } + static const int radix = __FLT_RADIX__; + static const int digits = __DBL_MANT_DIG__; + static const int digits10 = __DBL_DIG__; + static const bool is_signed = true; + static const bool is_integer = false; + static const bool is_exact = false; + static const bool traps = false; // this is a guess + static const bool is_modulo = false; + static const bool is_bounded = true; - // Floating point specific. + // Floating point specific. - static numeric_type epsilon () { return __DBL_EPSILON__; } - static numeric_type round_error () { return 0.5; } - static const int min_exponent10 = -1; //How do I properly get this? - static const int max_exponent10 = -1; //How do I properly get this? - static const int min_exponent = -1; //How do I properly get this? - static const int max_exponent = -1; //How do I properly get this? - static const bool has_infinity = false; //I don't know, so until I can find out, I'm saying no - static const bool has_quiet_NaN = false; //I don't know, so until I can find out, I'm saying no - static const bool has_signaling_NaN = false; //I don't know, so until I can find out, I'm saying no - static const bool has_denorm = false; //I don't know, so until I can find out, I'm saying no + static numeric_type epsilon () { return __DBL_EPSILON__; } + static numeric_type round_error () { return 0.5; } + static const int min_exponent10 = -1; //How do I properly get this? + static const int max_exponent10 = -1; //How do I properly get this? + static const int min_exponent = -1; //How do I properly get this? + static const int max_exponent = -1; //How do I properly get this? + static const bool has_infinity = false; //I don't know, so until I can find out, I'm saying no + static const bool has_quiet_NaN = false; //I don't know, so until I can find out, I'm saying no + static const bool has_signaling_NaN = false; //I don't know, so until I can find out, I'm saying no + static const bool has_denorm = false; //I don't know, so until I can find out, I'm saying no - static const bool is_iec559 = false; //I don't know, so until I can find out, I'm saying no - static const bool tinyness_before = false; // more questions - static const float_round_style round_style = round_to_nearest; // more questions - static numeric_type denorm_min () { return -1; } //How do I properly get this? - static numeric_type infinity () { return -1; } //How do I properly get this? - static numeric_type quiet_NaN () { return -1; } //How do I properly get this? - static numeric_type signaling_NaN () { return -1; } //How do I properly get this? + static const bool is_iec559 = false; //I don't know, so until I can find out, I'm saying no + static const bool tinyness_before = false; // more questions + static const float_round_style round_style = round_to_nearest; // more questions + static numeric_type denorm_min () { return -1; } //How do I properly get this? + static numeric_type infinity () { return -1; } //How do I properly get this? + static numeric_type quiet_NaN () { return -1; } //How do I properly get this? + static numeric_type signaling_NaN () { return -1; } //How do I properly get this? }; - - - - -} +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/list b/misc/uClibc++/include/uClibc++/list index 2fe182c66e..8daf8144d7 100644 --- a/misc/uClibc++/include/uClibc++/list +++ b/misc/uClibc++/include/uClibc++/list @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -26,897 +26,1072 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ - template > class _UCXXEXPORT list { - public: - typedef typename Allocator::reference reference; - typedef typename Allocator::const_reference const_reference; - typedef typename Allocator::size_type size_type; - typedef typename Allocator::difference_type difference_type; - typedef T value_type; - typedef Allocator allocator_type; - typedef typename Allocator::pointer pointer; - typedef typename Allocator::const_pointer const_pointer; +namespace std +{ - protected: - class node; - class iter_list; + template > class _UCXXEXPORT list { + public: + typedef typename Allocator::reference reference; + typedef typename Allocator::const_reference const_reference; + typedef typename Allocator::size_type size_type; + typedef typename Allocator::difference_type difference_type; + typedef T value_type; + typedef Allocator allocator_type; + typedef typename Allocator::pointer pointer; + typedef typename Allocator::const_pointer const_pointer; - node * list_start; - node * list_end; - size_type elements; - Allocator a; + protected: + class node; + class iter_list; - public: + node * list_start; + node * list_end; + size_type elements; + Allocator a; - typedef iter_list iterator; - typedef iter_list const_iterator; - typedef std::reverse_iterator reverse_iterator; - typedef std::reverse_iterator const_reverse_iterator; + public: + typedef iter_list iterator; + typedef iter_list const_iterator; + typedef std::reverse_iterator reverse_iterator; + typedef std::reverse_iterator const_reverse_iterator; - explicit list(const Allocator& = Allocator()); - explicit list(size_type n, const T& value = T(), const Allocator& = Allocator()); - template list(InputIterator first, InputIterator last, - const Allocator& al= Allocator()); - list(const list& x); - ~list(); + explicit list(const Allocator& = Allocator()); + explicit list(size_type n, const T& value = T(), const Allocator& = Allocator()); + template list(InputIterator first, InputIterator last, + const Allocator& al= Allocator()); + list(const list& x); + ~list(); - list& operator=(const list& x){ - if(&x == this){ - return *this; - } - clear(); - iterator i = x.begin(); - while(i != x.end()){ - push_back(*i); - ++i; - } - return *this; - } + list& operator=(const list& x) + { + if (&x == this) + { + return *this; + } - template void assign(InputIterator first, InputIterator last); - template void assign(Size n, const U& u = U()); - allocator_type get_allocator() const; + clear(); + iterator i = x.begin(); + while (i != x.end()) + { + push_back(*i); + ++i; + } - iterator begin(); - const_iterator begin() const; - iterator end(); - const_iterator end() const; - reverse_iterator rbegin(); - const_reverse_iterator rbegin() const; - reverse_iterator rend(); - const_reverse_iterator rend() const; + return *this; + } - bool empty() const; - size_type size() const; - size_type max_size() const; - void resize(size_type sz, T c = T()); + template void assign(InputIterator first, InputIterator last); + template void assign(Size n, const U& u = U()); + allocator_type get_allocator() const; - reference front(); - const_reference front() const; - reference back(); - const_reference back() const; + iterator begin(); + const_iterator begin() const; + iterator end(); + const_iterator end() const; + reverse_iterator rbegin(); + const_reverse_iterator rbegin() const; + reverse_iterator rend(); + const_reverse_iterator rend() const; - void push_front(const T& x); - void pop_front(); - void push_back(const T& x); - void pop_back(); - iterator insert(iterator position, const T& x = T()); - void insert(iterator position, size_type n, const T& x); - template void insert(iterator position, InputIterator first, InputIterator last); - iterator erase(iterator position); - iterator erase(iterator position, iterator last); - void swap(list&); - void clear(); + bool empty() const; + size_type size() const; + size_type max_size() const; + void resize(size_type sz, T c = T()); - void splice(iterator position, list& x); - void splice(iterator position, list& x, iterator i); - void splice(iterator position, list& x, iterator first, iterator last); - void remove(const T& value); - template void remove_if(Predicate pred); - void unique(); - template void unique(BinaryPredicate binary_pred); - void merge(list& x); - template void merge(list& x, Compare comp); - void sort(); - template void sort(Compare comp); - void reverse(); - protected: - void swap_nodes(node * x, node * y); - }; + reference front(); + const_reference front() const; + reference back(); + const_reference back() const; + void push_front(const T& x); + void pop_front(); + void push_back(const T& x); + void pop_back(); + iterator insert(iterator position, const T& x = T()); + void insert(iterator position, size_type n, const T& x); + template void insert(iterator position, InputIterator first, InputIterator last); + iterator erase(iterator position); + iterator erase(iterator position, iterator last); + void swap(list&); + void clear(); - //Implementations of List + void splice(iterator position, list& x); + void splice(iterator position, list& x, iterator i); + void splice(iterator position, list& x, iterator first, iterator last); + void remove(const T& value); + template void remove_if (Predicate pred); + void unique(); + template void unique(BinaryPredicate binary_pred); + void merge(list& x); + template void merge(list& x, Compare comp); + void sort(); + template void sort(Compare comp); + void reverse(); - //List node - template class _UCXXEXPORT list::node{ - public: - node * previous; - node * next; - T * val; + protected: + void swap_nodes(node * x, node * y); + }; - node(): previous(0), next(0), val(0){ } - node(const T & t ): previous(0), next(0), val(0) { - val = new T(t); - //FIXME use allocator somehow but only call constructor once - } - node(const T & t, node * p, node * n): previous(p), next(n), val(0) { - val = new T(t); - } - ~node(){ } - }; + // Implementations of List - //List iterator - template class _UCXXEXPORT list::iter_list - : public std::iterator< - bidirectional_iterator_tag, - T, - typename Allocator::difference_type, - typename Allocator::pointer, - typename Allocator::reference - > - { - private: - node * current; - public: - iter_list():current(0) { } - iter_list( typename list::node * n): current(n) { } - iter_list(const list::iter_list & l): current(l.current) { } - ~iter_list(){ } + // List node - iter_list & operator=(const list::iter_list & right ){ - current = right.current; - return *this; - } + template class _UCXXEXPORT list::node + { + public: + node * previous; + node * next; + T * val; - T & operator*(){ - return *(current->val); - } - T * operator->(){ - return current->val; - } - const T & operator*() const{ - return *current->val; - } - const T * operator->() const{ - return current->val; - } + node(): previous(0), next(0), val(0){ } - bool operator==(const list::iter_list & right) const { - return (current == right.current); - } + node(const T & t): previous(0), next(0), val(0) + { + val = new T(t); + //FIXME use allocator somehow but only call constructor once + } - bool operator!=(const list::iter_list & right) const { - return (current != right.current); - } + node(const T & t, node * p, node * n): previous(p), next(n), val(0) + { + val = new T(t); + } - iter_list & operator++(){ - current = current->next; - return *this; - } + ~node(){ } + }; - iter_list operator++(int){ - iter_list temp(current); - current = current->next; - return temp; - } - iter_list & operator--(){ - current = current->previous; - return *this; - } + // List iterator - iter_list operator--(int){ - iter_list temp(current); - current = current->previous; - return temp; - } - node * link_struct(){ - return current; - } - iter_list & operator+=(unsigned int n){ - for(unsigned int i = 0; i < n; ++i){ - current = current->next; - } - return *this; - } - iter_list & operator-=(unsigned int n){ - for(unsigned int i = 0; i < n; ++i){ - current = current->previous; - } - return *this; - } - }; + template class _UCXXEXPORT list::iter_list + : public std::iterator< + bidirectional_iterator_tag, + T, + typename Allocator::difference_type, + typename Allocator::pointer, + typename Allocator::reference + > + { + private: + node * current; + public: + iter_list():current(0) { } + iter_list(typename list::node * n): current(n) { } + iter_list(const list::iter_list & l): current(l.current) { } + ~iter_list(){ } + iter_list & operator=(const list::iter_list & right) + { + current = right.current; + return *this; + } - template list::list(const Allocator& al) - :list_start(0), list_end(0), elements(0), a(al) - { - //End node - list_start = new node(); - list_end = list_start; - return; - } + T & operator*() + { + return *(current->val); + } - template list::list - (typename Allocator::size_type n, const T& value, const Allocator& al) - :list_start(0), list_end(0), elements(0), a(al) - { - //End node - list_start = new node(); - list_end = list_start; + T * operator->() + { + return current->val; + } - for(typename Allocator::size_type i = 0; i < n ; ++i){ - push_back(value); - } - } + const T & operator*() const + { + return *current->val; + } - template template - list::list - (InputIterator first, InputIterator last, const Allocator& al) - : list_start(0), list_end(0), elements(0), a(al) - { - list_start = new node(); - list_end = list_start; - while(first != last){ - push_back(*first); - ++first; - } - } + const T * operator->() const + { + return current->val; + } - template list::list(const list& x) - : list_start(0), list_end(0), elements(0), a(x.a) - { - list_start = new node(); - list_end = list_start; + bool operator==(const list::iter_list & right) const + { + return (current == right.current); + } - iterator i = x.begin(); - while(i != x.end()){ - push_back( *i); - ++i; - } - } + bool operator!=(const list::iter_list & right) const + { + return (current != right.current); + } - template list::~list(){ - while(elements > 0){ - pop_front(); - } - delete list_start->val; + iter_list & operator++() + { + current = current->next; + return *this; + } + + iter_list operator++(int) + { + iter_list temp(current); + current = current->next; + return temp; + } + + iter_list & operator--() + { + current = current->previous; + return *this; + } + + iter_list operator--(int) + { + iter_list temp(current); + current = current->previous; + return temp; + } + + node *link_struct() + { + return current; + } + + iter_list & operator+=(unsigned int n) + { + for (unsigned int i = 0; i < n; ++i) + { + current = current->next; + } + + return *this; + } + + iter_list & operator-=(unsigned int n) + { + for (unsigned int i = 0; i < n; ++i) + { + current = current->previous; + } + + return *this; + } + }; + + template list::list(const Allocator& al) + :list_start(0), list_end(0), elements(0), a(al) + { + // End node + + list_start = new node(); + list_end = list_start; + return; + } + + template list::list + (typename Allocator::size_type n, const T& value, const Allocator& al) + :list_start(0), list_end(0), elements(0), a(al) + { + // End node + + list_start = new node(); + list_end = list_start; + + for (typename Allocator::size_type i = 0; i < n ; ++i) + { + push_back(value); + } + } + + template template + list::list + (InputIterator first, InputIterator last, const Allocator& al) + : list_start(0), list_end(0), elements(0), a(al) + { + list_start = new node(); + list_end = list_start; + while (first != last) + { + push_back(*first); + ++first; + } + } + + template list::list(const list& x) + : list_start(0), list_end(0), elements(0), a(x.a) + { + list_start = new node(); + list_end = list_start; + + iterator i = x.begin(); + while (i != x.end()) + { + push_back(*i); + ++i; + } + } + + template list::~list(){ + while (elements > 0) + { + pop_front(); + } + + delete list_start->val; #ifdef CONFIG_DEBUG_LIB - list_start->val = 0; + list_start->val = 0; #endif - delete list_start; + delete list_start; #ifdef CONFIG_DEBUG_LIB - list_start = 0; - list_end = 0; + list_start = 0; + list_end = 0; #endif - } + } - template void list::swap_nodes(node * x, node * y){ - T * v = x->val; - x->val = y->val; - y->val = v; - } + template void list::swap_nodes(node * x, node * y) + { + T * v = x->val; + x->val = y->val; + y->val = v; + } - template typename list::iterator - list::begin() - { - return iterator(list_start); - } + template typename list::iterator + list::begin() + { + return iterator(list_start); + } + template typename list::const_iterator + list::begin() const + { + return const_iterator(list_start); + } - template typename list::const_iterator - list::begin() const - { - return const_iterator(list_start); - } + template typename list::iterator + list::end() + { + return iterator(list_end); + } + template typename list::const_iterator + list::end() const + { + return const_iterator(list_end); + } - template typename list::iterator - list::end() - { - return iterator(list_end); - } + template typename list::reverse_iterator + list::rbegin() + { + return reverse_iterator(end()); + } - template typename list::const_iterator - list::end() const - { - return const_iterator(list_end); - } + template typename list::const_reverse_iterator + list::rbegin() const + { + return const_reverse_iterator(end()); + } - template typename list::reverse_iterator - list::rbegin() - { - return reverse_iterator(end()); - } + template typename list::reverse_iterator + list::rend() + { + return reverse_iterator(begin()); + } - template typename list::const_reverse_iterator - list::rbegin() const - { - return const_reverse_iterator(end()); - } + template typename list::const_reverse_iterator + list::rend() const + { + return const_reverse_iterator(begin()); + } - template typename list::reverse_iterator - list::rend() - { - return reverse_iterator(begin()); - } + template bool list::empty() const{ + return (elements == 0); + } - template typename list::const_reverse_iterator - list::rend() const - { - return const_reverse_iterator(begin()); - } + template typename list::size_type list::size() const{ + return elements; + } - template bool list::empty() const{ - return (elements == 0); - } - template typename list::size_type list::size() const{ - return elements; - } - template typename list::size_type list::max_size() const{ - return ((size_type)(-1)) / (sizeof(T) + sizeof(node)); - } - template void list::resize(typename Allocator::size_type sz, T c){ -// if(sz > elements){ - for(typename Allocator::size_type i = elements; i < sz; ++i){ - push_back(c); - } -// } -// if(sz < elements){ - for(typename Allocator::size_type i = elements; i > sz; --i){ - pop_back(); - } -// } - } + template typename list::size_type list::max_size() const + { + return ((size_type)(-1)) / (sizeof(T) + sizeof(node)); + } - template typename list::reference list::front(){ - return *(list_start->val); - } - template typename list::const_reference list::front() const{ - return *(list_start->val); - } - template typename list::reference list::back(){ - return *(list_end->previous->val); - } - template typename list::const_reference list::back() const{ - return *(list_end->previous->val); - } + template void list::resize(typename Allocator::size_type sz, T c) + { +// if (sz > elements) +// { + for (typename Allocator::size_type i = elements; i < sz; ++i) + { + push_back(c); + } +// } +// if (sz < elements) +// { + for (typename Allocator::size_type i = elements; i > sz; --i) + { + pop_back(); + } +// } + } + template typename list::reference list::front(){ + return *(list_start->val); + } - template void list::push_front(const T& x){ - node * temp = new node(x); - list_start->previous = temp; - temp->previous = 0; - temp->next = list_start; - list_start = temp; - ++elements; - } + template typename list::const_reference list::front() const + { + return *(list_start->val); + } - template void list::pop_front(){ - if(elements > 0){ - list_start = list_start->next; - delete list_start->previous->val; + template typename list::reference list::back() + { + return *(list_end->previous->val); + } + + template typename list::const_reference list::back() const + { + return *(list_end->previous->val); + } + + template void list::push_front(const T& x) + { + node * temp = new node(x); + list_start->previous = temp; + temp->previous = 0; + temp->next = list_start; + list_start = temp; + ++elements; + } + + template void list::pop_front() + { + if (elements > 0) + { + list_start = list_start->next; + delete list_start->previous->val; #ifdef CONFIG_DEBUG_LIB - list_start->previous->val = 0; - list_start->previous->next = 0; - list_start->previous->previous = 0; + list_start->previous->val = 0; + list_start->previous->next = 0; + list_start->previous->previous = 0; #endif - delete list_start->previous; - list_start->previous = 0; - --elements; - } - } + delete list_start->previous; + list_start->previous = 0; + --elements; + } + } - template void list::push_back(const T& x){ - if(elements == 0){ - //The list is completely empty - list_start = new node(x); - list_end->previous = list_start; - list_start->previous = 0; - list_start->next = list_end; - elements = 1; - }else{ - node * temp = new node(x); - temp->previous = list_end->previous; - temp->next = list_end; - list_end->previous->next = temp; - list_end->previous = temp; - ++elements; - } - } + template void list::push_back(const T& x) + { + if (elements == 0) + { + // The list is completely empty - template void list::pop_back(){ - if(elements > 0){ - node * temp = list_end->previous; - if(temp == list_start){ - list_end->previous = 0; - list_start = list_end; - }else{ - temp->previous->next = temp->next; - list_end->previous = temp->previous; - } - delete temp->val; + list_start = new node(x); + list_end->previous = list_start; + list_start->previous = 0; + list_start->next = list_end; + elements = 1; + } + else + { + node * temp = new node(x); + temp->previous = list_end->previous; + temp->next = list_end; + list_end->previous->next = temp; + list_end->previous = temp; + ++elements; + } + } + + template void list::pop_back() + { + if (elements > 0) + { + node * temp = list_end->previous; + if (temp == list_start) + { + list_end->previous = 0; + list_start = list_end; + } + else + { + temp->previous->next = temp->next; + list_end->previous = temp->previous; + } + + delete temp->val; #ifdef CONFIG_DEBUG_LIB - temp->val = 0; - temp->next = 0; - temp->previous = 0; + temp->val = 0; + temp->next = 0; + temp->previous = 0; #endif - delete temp; + delete temp; #ifdef CONFIG_DEBUG_LIB - temp = 0; + temp = 0; #endif - --elements; - } - } + --elements; + } + } - template typename list::iterator - list::insert(iterator position, const T& x) - { - node * temp = new node(x); + template typename list::iterator + list::insert(iterator position, const T& x) + { + node * temp = new node(x); - temp->previous = position.link_struct()->previous; - temp->next = position.link_struct(); + temp->previous = position.link_struct()->previous; + temp->next = position.link_struct(); - if(temp->previous == 0){ - list_start = temp; - }else{ - position.link_struct()->previous->next = temp; - } + if (temp->previous == 0) + { + list_start = temp; + } + else + { + position.link_struct()->previous->next = temp; + } - position.link_struct()->previous = temp; + position.link_struct()->previous = temp; - ++elements; - --position; - return position; - } + ++elements; + --position; + return position; + } - template void list::insert(iterator position, size_type n, const T& x){ - for(typename list::size_type i = 0; i < n; ++i){ - position = insert(position, x); - } - } + template void list::insert(iterator position, size_type n, const T& x) + { + for (typename list::size_type i = 0; i < n; ++i) + { + position = insert(position, x); + } + } - template template void - list::insert(iterator position, InputIterator first, InputIterator last) - { - while(first !=last){ - insert(position, *first); - ++first; - } - } - template typename list::iterator - list::erase(iterator position) - { - if(position != end() ){ - node * temp = position.link_struct(); - if(temp == list_start){ - ++position; - temp->next->previous = 0; - list_start = temp->next; - }else{ - --position; - temp->next->previous = temp->previous; - temp->previous->next = temp->next; - ++position; - } - delete temp->val; + template template void + list::insert(iterator position, InputIterator first, InputIterator last) + { + while (first !=last) + { + insert(position, *first); + ++first; + } + } + + template typename list::iterator + list::erase(iterator position) + { + if (position != end()) + { + node * temp = position.link_struct(); + if (temp == list_start) + { + ++position; + temp->next->previous = 0; + list_start = temp->next; + } + else + { + --position; + temp->next->previous = temp->previous; + temp->previous->next = temp->next; + ++position; + } + + delete temp->val; #ifdef CONFIG_DEBUG_LIB - temp->next = 0; - temp->previous = 0; - temp->val = 0; + temp->next = 0; + temp->previous = 0; + temp->val = 0; #endif - delete temp; + delete temp; #ifdef CONFIG_DEBUG_LIB - temp = 0; + temp = 0; #endif - --elements; - } - return position; - } - template typename list::iterator - list::erase(iterator position, iterator last) - { - iterator temp = position; - while(position !=last){ - position = erase(position); - } - return position; - } - template void list::swap(list& l){ - node * temp; - size_type tempel; - - temp = list_start; - list_start = l.list_start; - l.list_start = temp; - - temp = list_end; - list_end = l.list_end; - l.list_end = temp; - - tempel = elements; - elements = l.elements; - l.elements = tempel; - } - template void list::clear(){ - while(elements > 0){ - pop_front(); - } - } - - template - void list::splice(iterator position, list& x) - { - - //Can't add non-existant elements - if(x.elements == 0){ - return; - } - - elements += x.elements; - x.elements = 0; - - - //Chaining to the begining - if(position == begin()){ - x.list_end->previous->next = list_start; - list_start->previous = x.list_end->previous; - - list_start = x.list_start; - - x.list_start = x.list_end; - x.list_end->previous = 0; - - return; - } - - //Link everything we need - x.list_start->previous = position.link_struct()->previous; - position.link_struct()->previous->next = x.list_start; - - position.link_struct()->previous = x.list_end->previous; - x.list_end->previous->next = position.link_struct(); - - //Clean up the other list - - x.list_start = x.list_end; - x.list_end->previous=0; - - } - - template - void list::splice(iterator position, list& x, iterator i) - { - //Invalid conditions - if( x.elements == 0 || i == position || position.link_struct() == i.link_struct()->next ){ - return; - } - - //Do we need to adjust the begining pointer? - if(i == x.begin()){ - x.list_start = x.list_start->next; - x.list_start->previous = 0; - } - - - //Insert at begining special case - if(position == begin()){ - - i.link_struct()->previous->next = i.link_struct()->next; - i.link_struct()->next->previous = i.link_struct()->previous; - - i.link_struct()->previous = 0; - i.link_struct()->next = position.link_struct(); - position.link_struct()->previous = i.link_struct(); - - list_start = i.link_struct(); - - --x.elements; - ++elements; - return; - } - - if( i.link_struct()->previous != 0){ - i.link_struct()->previous->next = i.link_struct()->next; - i.link_struct()->next->previous = i.link_struct()->previous; - }else{ - i.link_struct()->next->previous = 0; - x.list_start = i.link_struct()->next; - } - - i.link_struct()->previous = position.link_struct()->previous; - position.link_struct()->previous->next = i.link_struct(); - - i.link_struct()->next = position.link_struct(); - position.link_struct()->previous = i.link_struct(); - - --x.elements; - ++elements; - } - - template - void list::splice(iterator position, list& x, - iterator first, iterator last) - { - if(x.elements == 0){ - return; - } - - iterator temp; - while(first != last){ - temp = first; - ++first; - splice(position, x, temp); - } - } - - - template void list::remove(const T& value){ - iterator temp = begin(); - while( temp != end() ){ - if(*temp == value){ - temp = erase(temp); - }else{ - ++temp; - } - } - } - - - template template void list::remove_if(Predicate pred){ - iterator temp = begin(); - while( temp != end() ){ - if( pred(*temp) ){ - temp = erase(temp); - }else{ - ++temp; - } - } - } - - - template void list::unique(){ - equal_to::value_type> p; - unique(p); - } - - template template - void list::unique(BinaryPredicate binary_pred) - { - iterator temp1 = begin(); - iterator temp2; - ++temp1; - while( temp1 != end() ){ - temp2 = temp1; - --temp2; - if( binary_pred(*temp1, *temp2) ){ - erase(temp1); - temp1 = temp2; - } - ++temp1; - } - } - - template void list::merge(list& x){ - less::iterator>::value_type> c; - merge(x, c); - } - - template template - void list::merge(list& x, Compare comp) - { - iterator source = x.begin(); - iterator temp; - iterator dest = begin(); - - while(source != x.end()){ - while( dest != end() && comp (*dest, *source) ){ - ++dest; - } - ++elements; - --x.elements; - - temp = source; - ++temp; - - if(dest == begin()){ - dest.link_struct()->previous = source.link_struct(); - source.link_struct()->next = dest.link_struct(); - source.link_struct()->previous = 0; - list_start = source.link_struct(); - }else{ - source.link_struct()->previous = dest.link_struct()->previous; - dest.link_struct()->previous->next = source.link_struct(); - source.link_struct()->next = dest.link_struct(); - dest.link_struct()->previous = source.link_struct(); - } - source = temp; - } - - //Fix up x; - x.list_start = x.list_end; - x.list_start->previous = 0; - } - - template void list::sort(){ - less::iterator>::value_type> c; - sort(c); - } - - template template - void list::sort(Compare comp) - { - typename list::iterator i, j, k; - - //FIXME - bubble sort - - if(elements == 0){ - return; - } - - i = end(); - --i; - while(i != begin()){ - j = begin(); - k = j; - ++k; - while(j != i){ - if( comp(*k, *j) ){ - swap_nodes(k.link_struct(), j.link_struct()); - } - ++j; - ++k; - } - --i; - } - } - - - template void list::reverse(){ - if(elements == 0){ - return; - } - - node * current; - node * following; - node * temp; - - //Need to move the list_end element to the begining - - temp = list_end; - list_end = temp->previous; - list_end->next = 0; - - list_start->previous = temp; - temp->previous = 0; - temp->next = list_start; - list_start = temp; - - current = list_start; - - while( current != list_end ){ - following = current->next; - - //Swap the values pointed to/at with the current node - temp = current->next; - current->next = current->previous; - current->previous = temp; - - current = following; - } - - //Swap pointers on the end node - temp = list_end->next; - list_end->next = list_end->previous; - list_end->previous = temp; - - - //Swap the fixed pointers - temp = list_start; - list_start = list_end; - list_end = temp; - - } - - template - bool operator==(const list& x, const list& y){ - if(x.size() != y.size()){ - return false; - } - typename list::const_iterator i = x.begin(); - typename list::const_iterator j = y.begin(); - - while(i != x.end()){ - if( *i != *j){ - return false; - } - ++i; - ++j; - } - return true; - } - - template - bool operator< (const list& x, const list& y){ - typename list::const_iterator i = x.begin(); - typename list::const_iterator j = y.begin(); - while(i != x.end() && j != y.end()){ - if( *i < *j){ - return true; - } - if(*j < *i){ - return false; - } - ++i; - ++j; - } - return (i == x.end() && j != y.end()); - } - - template - bool operator!=(const list& x, const list& y){ - return !(x == y); - } - - template - bool operator> (const list& x, const list& y){ - typename list::const_iterator i = x.begin(); - typename list::const_iterator j = y.begin(); - while(i != x.end() && j != y.end()){ - if( *i > *j){ - return true; - } - if( *j > *i){ - return false; - } - ++i; - ++j; - } - return (i != x.end() && j == y.end()); - } - - template - bool operator>=(const list& x, const list& y){ - typename list::const_iterator i = x.begin(); - typename list::const_iterator j = y.begin(); - while(i != x.end() && j != y.end()){ - if( *i >= *j){ - return true; - } - if(*j >= *i){ - return false; - } - ++i; - ++j; - } - return (i != x.end() && j == y.end()); - } - - template - bool operator<=(const list& x, const list& y){ - typename list::const_iterator i = x.begin(); - typename list::const_iterator j = y.begin(); - while(i != x.end() && j != y.end()){ - if( *i <= *j){ - return true; - } - if(*j <= *i){ - return false; - } - ++i; - ++j; - } - return (i == x.end()); - } - - template - void swap(list& x, list& y){ - x.swap(y); - } - -} + --elements; + } + + return position; + } + + template typename list::iterator + list::erase(iterator position, iterator last) + { + iterator temp = position; + while (position !=last) + { + position = erase(position); + } + + return position; + } + + template void list::swap(list& l) + { + node * temp; + size_type tempel; + + temp = list_start; + list_start = l.list_start; + l.list_start = temp; + + temp = list_end; + list_end = l.list_end; + l.list_end = temp; + + tempel = elements; + elements = l.elements; + l.elements = tempel; + } + + template void list::clear() + { + while (elements > 0) + { + pop_front(); + } + } + + template + void list::splice(iterator position, list& x) + { + // Can't add non-existant elements + + if (x.elements == 0) + { + return; + } + + elements += x.elements; + x.elements = 0; + + // Chaining to the begining + + if (position == begin()) + { + x.list_end->previous->next = list_start; + list_start->previous = x.list_end->previous; + + list_start = x.list_start; + + x.list_start = x.list_end; + x.list_end->previous = 0; + + return; + } + + // Link everything we need + + x.list_start->previous = position.link_struct()->previous; + position.link_struct()->previous->next = x.list_start; + + position.link_struct()->previous = x.list_end->previous; + x.list_end->previous->next = position.link_struct(); + + // Clean up the other list + + x.list_start = x.list_end; + x.list_end->previous=0; + } + + template + void list::splice(iterator position, list& x, iterator i) + { + // Invalid conditions + + if (x.elements == 0 || i == position || position.link_struct() == i.link_struct()->next) + { + return; + } + + // Do we need to adjust the begining pointer? + + if (i == x.begin()) + { + x.list_start = x.list_start->next; + x.list_start->previous = 0; + } + + // Insert at begining special case + + if (position == begin()) + { + i.link_struct()->previous->next = i.link_struct()->next; + i.link_struct()->next->previous = i.link_struct()->previous; + + i.link_struct()->previous = 0; + i.link_struct()->next = position.link_struct(); + position.link_struct()->previous = i.link_struct(); + + list_start = i.link_struct(); + + --x.elements; + ++elements; + return; + } + + if (i.link_struct()->previous != 0) + { + i.link_struct()->previous->next = i.link_struct()->next; + i.link_struct()->next->previous = i.link_struct()->previous; + } + else + { + i.link_struct()->next->previous = 0; + x.list_start = i.link_struct()->next; + } + + i.link_struct()->previous = position.link_struct()->previous; + position.link_struct()->previous->next = i.link_struct(); + + i.link_struct()->next = position.link_struct(); + position.link_struct()->previous = i.link_struct(); + + --x.elements; + ++elements; + } + + template + void list::splice(iterator position, list& x, + iterator first, iterator last) + { + if (x.elements == 0) + { + return; + } + + iterator temp; + while (first != last) + { + temp = first; + ++first; + splice(position, x, temp); + } + } + + template void list::remove(const T& value) + { + iterator temp = begin(); + while (temp != end()) + { + if (*temp == value) + { + temp = erase(temp); + } + else + { + ++temp; + } + } + } + + template template void list::remove_if (Predicate pred) + { + iterator temp = begin(); + while (temp != end()) + { + if (pred(*temp)) + { + temp = erase(temp); + } + else + { + ++temp; + } + } + } + + template void list::unique() + { + equal_to::value_type> p; + unique(p); + } + + template template + void list::unique(BinaryPredicate binary_pred) + { + iterator temp1 = begin(); + iterator temp2; + ++temp1; + while (temp1 != end()) + { + temp2 = temp1; + --temp2; + if (binary_pred(*temp1, *temp2)) + { + erase(temp1); + temp1 = temp2; + } + + ++temp1; + } + } + + template void list::merge(list& x) + { + less::iterator>::value_type> c; + merge(x, c); + } + + template template + void list::merge(list& x, Compare comp) + { + iterator source = x.begin(); + iterator temp; + iterator dest = begin(); + + while (source != x.end()) + { + while (dest != end() && comp (*dest, *source)) + { + ++dest; + } + + ++elements; + --x.elements; + + temp = source; + ++temp; + + if (dest == begin()) + { + dest.link_struct()->previous = source.link_struct(); + source.link_struct()->next = dest.link_struct(); + source.link_struct()->previous = 0; + list_start = source.link_struct(); + } + else + { + source.link_struct()->previous = dest.link_struct()->previous; + dest.link_struct()->previous->next = source.link_struct(); + source.link_struct()->next = dest.link_struct(); + dest.link_struct()->previous = source.link_struct(); + } + + source = temp; + } + + // Fix up x; + + x.list_start = x.list_end; + x.list_start->previous = 0; + } + + template void list::sort() + { + less::iterator>::value_type> c; + sort(c); + } + + template template + void list::sort(Compare comp) + { + typename list::iterator i, j, k; + + // FIXME - bubble sort + + if (elements == 0) + { + return; + } + + i = end(); + --i; + while (i != begin()) + { + j = begin(); + k = j; + ++k; + while (j != i) + { + if (comp(*k, *j)) + { + swap_nodes(k.link_struct(), j.link_struct()); + } + + ++j; + ++k; + } + + --i; + } + } + + + template void list::reverse() + { + if (elements == 0) + { + return; + } + + node * current; + node * following; + node * temp; + + // Need to move the list_end element to the begining + + temp = list_end; + list_end = temp->previous; + list_end->next = 0; + + list_start->previous = temp; + temp->previous = 0; + temp->next = list_start; + list_start = temp; + + current = list_start; + + while (current != list_end) + { + following = current->next; + + // Swap the values pointed to/at with the current node + + temp = current->next; + current->next = current->previous; + current->previous = temp; + + current = following; + } + + // Swap pointers on the end node + + temp = list_end->next; + list_end->next = list_end->previous; + list_end->previous = temp; + + //Swap the fixed pointers + + temp = list_start; + list_start = list_end; + list_end = temp; + } + + template + bool operator==(const list& x, const list& y) + { + if (x.size() != y.size()) + { + return false; + } + + typename list::const_iterator i = x.begin(); + typename list::const_iterator j = y.begin(); + + while (i != x.end()) + { + if (*i != *j) + { + return false; + } + + ++i; + ++j; + } + + return true; + } + + template + bool operator< (const list& x, const list& y) + { + typename list::const_iterator i = x.begin(); + typename list::const_iterator j = y.begin(); + while (i != x.end() && j != y.end()) + { + if (*i < *j) + { + return true; + } + + if (*j < *i) + { + return false; + } + + ++i; + ++j; + } + + return (i == x.end() && j != y.end()); + } + + template + bool operator!=(const list& x, const list& y) + { + return !(x == y); + } + + template + bool operator> (const list& x, const list& y) + { + typename list::const_iterator i = x.begin(); + typename list::const_iterator j = y.begin(); + while (i != x.end() && j != y.end()) + { + if (*i > *j) + { + return true; + } + + if (*j > *i) + { + return false; + } + + ++i; + ++j; + } + + return (i != x.end() && j == y.end()); + } + + template + bool operator>=(const list& x, const list& y) + { + typename list::const_iterator i = x.begin(); + typename list::const_iterator j = y.begin(); + while (i != x.end() && j != y.end()) + { + if (*i >= *j) + { + return true; + } + + if (*j >= *i) + { + return false; + } + + ++i; + ++j; + } + + return (i != x.end() && j == y.end()); + } + + template + bool operator<=(const list& x, const list& y) + { + typename list::const_iterator i = x.begin(); + typename list::const_iterator j = y.begin(); + while (i != x.end() && j != y.end()) + { + if (*i <= *j) + { + return true; + } + + if (*j <= *i) + { + return false; + } + + ++i; + ++j; + } + + return (i == x.end()); + } + + template + void swap(list& x, list& y) + { + x.swap(y); + } + +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/map b/misc/uClibc++/include/uClibc++/map index 038191af7c..6816116bbb 100644 --- a/misc/uClibc++/include/uClibc++/map +++ b/misc/uClibc++/include/uClibc++/map @@ -1,63 +1,60 @@ -/* Copyright (C) 2004-2007 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - - +/* Copyright (C) 2004-2007 Garrett A. Kajmowicz + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + *Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include #include #include - - #ifndef __STD_HEADER_MAP #define __STD_HEADER_MAP #pragma GCC visibility push(default) -namespace std{ - +extern "C++" +{ +namespace std +{ template, class Allocator = allocator > class map; template, class Allocator = allocator > class multimap; + //Compare the keys of the two items - //Compare the keys of the two items -/* template class _UCXXEXPORT - __base_map::value_compare : public binary_function< - typename map::value_type, - typename map::value_type, - bool> - { - friend class __base_map; - protected: - Compare comp; - value_compare(Compare c) : comp(c) { } - ~value_compare() { } - public: - bool operator()(const value_type& x, const value_type& y) const { - return comp(x.first, y.first); - } - }; + /* template class _UCXXEXPORT + __base_map::value_compare : public binary_function< + typename map::value_type, + typename map::value_type, + bool> +{ + friend class __base_map; + protected: + Compare comp; + value_compare(Compare c) : comp(c) { } + ~value_compare() { } + public: + bool operator()(const value_type& x, const value_type& y) const + { + return comp(x.first, y.first); + } + }; */ -// value_compare value_comp() const; - - +// value_compare value_comp() const; /* This is the implementation for the map container. As noted above, it deviates * from ISO spec by deriving from a base class in order to reduce code redundancy. @@ -66,199 +63,207 @@ template, class Allocator = alloca * the specifications too much to be worth the risk. */ - - //Implementation of map - template class _UCXXEXPORT map - : public __single_associative, Compare, Allocator> + : public __single_associative, Compare, Allocator> { - //Default value of allocator does not meet C++ standard specs, but it works for this library - //Deal with it + // Default value of allocator does not meet C++ standard specs, but it works for this library + // Deal with it public: - typedef __single_associative, Compare, Allocator> base; - typedef T mapped_type; - typedef typename base::key_type key_type; - typedef typename base::value_type value_type; - typedef typename base::key_compare key_compare; - typedef typename base::allocator_type allocator_type; - typedef typename base::reference reference; - typedef typename base::const_reference const_reference; - typedef typename base::iterator iterator; - typedef typename base::const_iterator const_iterator; - typedef typename base::size_type size_type; - typedef typename base::difference_type difference_type; - typedef typename base::pointer pointer; - typedef typename base::const_pointer const_pointer; - typedef typename base::reverse_iterator reverse_iterator; - typedef typename base::const_reverse_iterator const_reverse_iterator; + typedef __single_associative, Compare, Allocator> base; + typedef T mapped_type; + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; - static const key_type v_t_k(const value_type v){ - return v.first; - } + static const key_type v_t_k(const value_type v) + { + return v.first; + } -// using base::value_compare; +// using base::value_compare; - explicit map(const Compare& comp = Compare(), const Allocator& al = Allocator()) - : base(comp, al, v_t_k) { } + explicit map(const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(comp, al, v_t_k) { } - template map(InputIterator first, InputIterator last, - const Compare& comp = Compare(), const Allocator& al = Allocator()) - : base(first, last, comp, al, v_t_k) { } + template map(InputIterator first, InputIterator last, + const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(first, last, comp, al, v_t_k) { } - map(const map& x) : base(x) { } - ~map() { } + map(const map& x) : base(x) { } + ~map() { } - using base::operator=; - using base::operator==; - using base::operator!=; + using base::operator=; + using base::operator==; + using base::operator!=; - using base::insert; - using base::erase; + using base::insert; + using base::erase; - using base::begin; - using base::end; - using base::rbegin; - using base::rend; + using base::begin; + using base::end; + using base::rbegin; + using base::rend; - using base::empty; - using base::size; - using base::max_size; + using base::empty; + using base::size; + using base::max_size; - using base::find; - using base::count; - using base::lower_bound; - using base::upper_bound; - using base::equal_range; - using base::swap; + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; + using base::swap; - reference operator[](const key_type& k){ - iterator i = lower_bound(k); - if (i == end() || base::c(k, i->first)) { - i = insert(make_pair(k, T())).first; - } - return i->second; - } + reference operator[](const key_type& k) + { + iterator i = lower_bound(k); + if (i == end() || base::c(k, i->first)) + { + i = insert(make_pair(k, T())).first; + } + + return i->second; + } protected: - using base::backing; + using base::backing; }; - -//Implementation of multimap - +// Implementation of multimap template class _UCXXEXPORT multimap - : public __multi_associative, Compare, Allocator> - + : public __multi_associative, Compare, Allocator> { - //Default value of allocator does not meet C++ standard specs, but it works for this library - //Deal with it + // Default value of allocator does not meet C++ standard specs, but it works for this library + // Deal with it + public: - typedef __multi_associative, Compare, Allocator> base; - typedef T mapped_type; - typedef typename base::key_type key_type; - typedef typename base::value_type value_type; - typedef typename base::key_compare key_compare; - typedef typename base::allocator_type allocator_type; - typedef typename base::reference reference; - typedef typename base::const_reference const_reference; - typedef typename base::iterator iterator; - typedef typename base::const_iterator const_iterator; - typedef typename base::size_type size_type; - typedef typename base::difference_type difference_type; - typedef typename base::pointer pointer; - typedef typename base::const_pointer const_pointer; - typedef typename base::reverse_iterator reverse_iterator; - typedef typename base::const_reverse_iterator const_reverse_iterator; + typedef __multi_associative, Compare, Allocator> base; + typedef T mapped_type; + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; - static const key_type v_t_k(const value_type v){ - return v.first; - } + static const key_type v_t_k(const value_type v) + { + return v.first; + } - explicit multimap(const Compare& comp = Compare(), const Allocator& al = Allocator()) - : base(comp, al, v_t_k) { } + explicit multimap(const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(comp, al, v_t_k) { } - template multimap(InputIterator first, InputIterator last, - const Compare& comp = Compare(), const Allocator& al = Allocator()) - : base(first, last, comp, al, v_t_k) { } + template multimap(InputIterator first, InputIterator last, + const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(first, last, comp, al, v_t_k) { } + multimap(const multimap& x) : base(x) { } + ~multimap() { } - multimap(const multimap& x) : base(x) { } - ~multimap() { } + using base::operator=; + using base::operator==; + using base::operator!=; - using base::operator=; - using base::operator==; - using base::operator!=; + using base::insert; + using base::erase; - using base::insert; - using base::erase; + using base::begin; + using base::end; + using base::rbegin; + using base::rend; - using base::begin; - using base::end; - using base::rbegin; - using base::rend; + using base::empty; + using base::size; + using base::max_size; - using base::empty; - using base::size; - using base::max_size; - - using base::find; - using base::count; - using base::lower_bound; - using base::upper_bound; - using base::equal_range; - using base::swap; + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; + using base::swap; protected: - using base::c; - + using base::c; }; - /* Non-member functions. These are at the end because they are not associated with any - particular class. These will be implemented as I figure out exactly what all of - them are supposed to do, and I have time. + * particular class. These will be implemented as I figure out exactly what all of + * them are supposed to do, and I have time. */ - template _UCXXEXPORT bool operator< - (const map& x, const map& y); - template _UCXXEXPORT bool operator!= - (const map& x, const map& y); - template _UCXXEXPORT bool operator> - (const map& x, const map& y); - template _UCXXEXPORT bool operator>= - (const map& x, const map& y); - template _UCXXEXPORT bool operator<= - (const map& x, const map& y); - template _UCXXEXPORT void swap - (map& x, map& y); + template _UCXXEXPORT bool operator< + (const map& x, const map& y); + template _UCXXEXPORT bool operator!= + (const map& x, const map& y); - template _UCXXEXPORT bool operator== - (const multimap& x, const multimap& y); - template _UCXXEXPORT bool operator< - (const multimap& x, const multimap& y); - template _UCXXEXPORT bool operator!= - (const multimap& x, const multimap& y); - template _UCXXEXPORT bool operator> - (const multimap& x, const multimap& y); - template _UCXXEXPORT bool operator>= - (const multimap& x, const multimap& y); - template _UCXXEXPORT bool operator<= - (const multimap& x, const multimap& y); - template _UCXXEXPORT void swap - (multimap& x, multimap& y); + template _UCXXEXPORT bool operator> + (const map& x, const map& y); -} + template _UCXXEXPORT bool operator>= + (const map& x, const map& y); + + template _UCXXEXPORT bool operator<= + (const map& x, const map& y); + + template _UCXXEXPORT void swap + (map& x, map& y); + + template _UCXXEXPORT bool operator== + (const multimap& x, const multimap& y); + + template _UCXXEXPORT bool operator< + (const multimap& x, const multimap& y); + + template _UCXXEXPORT bool operator!= + (const multimap& x, const multimap& y); + + template _UCXXEXPORT bool operator> + (const multimap& x, const multimap& y); + + template _UCXXEXPORT bool operator>= + (const multimap& x, const multimap& y); + + template _UCXXEXPORT bool operator<= + (const multimap& x, const multimap& y); + + template _UCXXEXPORT void swap + (multimap& x, multimap& y); + +} // namespace +} // extern "C++" #pragma GCC visibility pop #endif - + diff --git a/misc/uClibc++/include/uClibc++/memory b/misc/uClibc++/include/uClibc++/memory index 2a7ce8c152..cd3956f185 100644 --- a/misc/uClibc++/include/uClibc++/memory +++ b/misc/uClibc++/include/uClibc++/memory @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -29,166 +29,214 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ + +namespace std +{ template class allocator; - // Specialize for void: + // Specialize for void: -template <> class _UCXXEXPORT allocator { +template <> class _UCXXEXPORT allocator +{ public: - typedef void* pointer; - typedef const void* const_pointer; - typedef void value_type; - template struct rebind { typedef allocator other; }; + typedef void* pointer; + typedef const void* const_pointer; + typedef void value_type; + template struct rebind { typedef allocator other; }; }; -template class _UCXXEXPORT allocator{ +template class _UCXXEXPORT allocator +{ public: - typedef T value_type; - typedef size_t size_type; - typedef ptrdiff_t difference_type; - - typedef T* pointer; - typedef const T* const_pointer; + typedef T value_type; + typedef size_t size_type; + typedef ptrdiff_t difference_type; + + typedef T* pointer; + typedef const T* const_pointer; - typedef T& reference; - typedef const T& const_reference; + typedef T& reference; + typedef const T& const_reference; - pointer address(reference r) const { return &r; } - const_pointer address(const_reference r) const { return &r; } - - allocator() throw(){} - template allocator(const allocator& ) throw(); - ~allocator() throw(){} + pointer address(reference r) const { return &r; } + const_pointer address(const_reference r) const { return &r; } + + allocator() throw(){} + template allocator(const allocator& ) throw(); + ~allocator() throw(){} - //Space for n Ts - pointer allocate(size_type n, typename allocator::const_pointer = 0){ - return (T*)(::operator new( n * sizeof(T) )); - } - void deallocate(pointer p, size_type){ - ::operator delete(p); - } + // Space for n Ts - //Use placement new to engage the constructor - void construct(pointer p, const T& val) { new((void*)p) T(val); } - void destroy(pointer p){ ((T*)p)->~T(); } //Call destructor + pointer allocate(size_type n, typename allocator::const_pointer = 0) + { + return (T*)(::operator new( n * sizeof(T) )); + } - size_type max_size() const throw(); - template struct rebind { typedef allocator other; }; + void deallocate(pointer p, size_type) + { + ::operator delete(p); + } + // Use placement new to engage the constructor + + void construct(pointer p, const T& val) { new((void*)p) T(val); } + void destroy(pointer p){ ((T*)p)->~T(); } //Call destructor + + size_type max_size() const throw(); + template struct rebind { typedef allocator other; }; }; template class _UCXXEXPORT raw_storage_iterator - : public iterator + : public iterator { - Out p; + Out p; public: - explicit raw_storage_iterator(Out pp) : p (pp) { } - raw_storage_iterator & operator*() { return *this; } - raw_storage_iterator & operator=(const T& val) { - T* pp = &*p; - new(pp) T(val); - return *this; - } + explicit raw_storage_iterator(Out pp) : p (pp) { } + raw_storage_iterator & operator*() { return *this; } - raw_storage_iterator & operator++() { ++p; return *this; } - raw_storage_iterator operator++(int) { - raw_storage_iterator t = *this; - ++p; - return t; - } + raw_storage_iterator & operator=(const T& val) + { + T* pp = &*p; + new(pp) T(val); + return *this; + } + + raw_storage_iterator & operator++() { ++p; return *this; } + + raw_storage_iterator operator++(int) + { + raw_storage_iterator t = *this; + ++p; + return t; + } }; -template _UCXXEXPORT pair get_temporary_buffer(ptrdiff_t n){ - pair retval; - retval.first = static_cast(malloc(n * sizeof(T))); - if(retval.first == 0){ - retval.second = 0; - }else{ - retval.second = n; - } - return retval; +template _UCXXEXPORT pair get_temporary_buffer(ptrdiff_t n) +{ + pair retval; + retval.first = static_cast(malloc(n * sizeof(T))); + if (retval.first == 0) + { + retval.second = 0; + } + else + { + retval.second = n; + } + + return retval; } -template _UCXXEXPORT void return_temporary_buffer(T* p){ - free(p); +template _UCXXEXPORT void return_temporary_buffer(T* p) +{ + free(p); } -template class _UCXXEXPORT auto_ptr{ - +template class _UCXXEXPORT auto_ptr +{ private: - T * object; - template struct auto_ptr_ref{ - Y * p; - }; + T * object; + template struct auto_ptr_ref + { + Y * p; + }; public: - typedef T element_type; + typedef T element_type; - explicit auto_ptr(T* p =0) throw() : object(p){ } - auto_ptr(auto_ptr& p) throw() : object(p.release()){ } - auto_ptr(auto_ptr_ref r) throw() : object(r.p){ - r.p = 0; - } - template auto_ptr(auto_ptr& p) throw() : object(p.release()){ } - auto_ptr& operator=(auto_ptr& p) throw(){ - if(&p == this){ - return *this; - } - delete object; - object = p.release(); - return *this; - } - template auto_ptr& operator=(auto_ptr& p) throw(){ - if(&p == this){ - return *this; - } - delete object; - object = p.release(); - return *this; - } - ~auto_ptr(){ - delete object; - } + explicit auto_ptr(T* p =0) throw() : object(p){ } + auto_ptr(auto_ptr& p) throw() : object(p.release()){ } - T& operator*() const throw(){ - return *object; - } - T* operator->() const throw(){ - return object; - } - T* get() const throw(){ - return object; - } - T* release() throw(){ - T * temp(object); - object = 0; - return temp; - } - void reset(T * p=0) throw(){ - if(p != object){ - delete object; - object = p; - } - } - template operator auto_ptr_ref() throw(){ - auto_ptr_ref retval; - retval.p = object; - object = 0; - return retval; - } - template operator auto_ptr() throw(){ - auto_ptr retval(object); - object = 0; - return retval; - } - + auto_ptr(auto_ptr_ref r) throw() : object(r.p) + { + r.p = 0; + } + + template auto_ptr(auto_ptr& p) throw() : object(p.release()){ } + + auto_ptr& operator=(auto_ptr& p) throw() + { + if (&p == this) + { + return *this; + } + + delete object; + object = p.release(); + return *this; + } + + template auto_ptr& operator=(auto_ptr& p) throw() + { + if (&p == this) + { + return *this; + } + + delete object; + object = p.release(); + return *this; + } + + ~auto_ptr() + { + delete object; + } + + T& operator*() const throw() + { + return *object; + } + + T* operator->() const throw() + { + return object; + } + + T* get() const throw() + { + return object; + } + + T* release() throw() + { + T * temp(object); + object = 0; + return temp; + } + + void reset(T * p=0) throw() + { + if(p != object) + { + delete object; + object = p; + } + } + + template operator auto_ptr_ref() throw() + { + auto_ptr_ref retval; + retval.p = object; + object = 0; + return retval; + } + + template operator auto_ptr() throw() + { + auto_ptr retval(object); + object = 0; + return retval; + } }; -} //namespace std +} // namespace std +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/new b/misc/uClibc++/include/uClibc++/new index 665e783952..29baba6afd 100644 --- a/misc/uClibc++/include/uClibc++/new +++ b/misc/uClibc++/include/uClibc++/new @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* * Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + **/ #include #include @@ -26,16 +26,19 @@ #pragma GCC visibility push(default) -namespace std{ - class _UCXXEXPORT bad_alloc : public exception {}; +extern "C++" +{ - struct _UCXXEXPORT nothrow_t {}; - extern const nothrow_t nothrow; +namespace std +{ + class _UCXXEXPORT bad_alloc : public exception {}; - typedef void (*new_handler)(); - _UCXXEXPORT new_handler set_new_handler(new_handler new_p) throw(); -} + struct _UCXXEXPORT nothrow_t {}; + extern const nothrow_t nothrow; + typedef void (*new_handler)(); + _UCXXEXPORT new_handler set_new_handler(new_handler new_p) throw(); +} // namespace _UCXXEXPORT void* operator new(std::size_t numBytes) throw(std::bad_alloc); _UCXXEXPORT void operator delete(void* ptr) throw(); @@ -51,14 +54,16 @@ _UCXXEXPORT void* operator new[](std::size_t numBytes, const std::nothrow_t& ) t _UCXXEXPORT void operator delete[](void* ptr, const std::nothrow_t& ) throw(); #endif - /* Placement operators */ +/* Placement operators */ + inline void* operator new(std::size_t, void* ptr) throw() {return ptr; } inline void operator delete(void* , void *) throw() { } - + inline void* operator new[](std::size_t, void *p) throw() { return p; } inline void operator delete[](void* , void *) throw() {} +} // extern "C++" + #pragma GCC visibility pop -#endif - +#endif // __STD_NEW_OPERATOR diff --git a/misc/uClibc++/include/uClibc++/numeric b/misc/uClibc++/include/uClibc++/numeric index 25d1b27468..880eb79f7a 100644 --- a/misc/uClibc++/include/uClibc++/numeric +++ b/misc/uClibc++/include/uClibc++/numeric @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -25,135 +25,150 @@ #pragma GCC visibility push(default) -namespace std{ - template _UCXXEXPORT - T accumulate(InputIterator first, InputIterator last, T init) - { - while(first != last){ - init = init + *first; - ++first; - } - return init; - } +extern "C++" +{ +namespace std +{ + template _UCXXEXPORT + T accumulate(InputIterator first, InputIterator last, T init) + { + while (first != last) + { + init = init + *first; + ++first; + } - template _UCXXEXPORT - T accumulate(InputIterator first, InputIterator last, T init, BinaryOperation binary_op) - { - while(first != last){ - init = binary_op(init, *first); - ++first; - } - return init; - } + return init; + } + + template _UCXXEXPORT + T accumulate(InputIterator first, InputIterator last, T init, BinaryOperation binary_op) + { + while (first != last) + { + init = binary_op(init, *first); + ++first; + } + + return init; + } + + template _UCXXEXPORT + T inner_product(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, T init) + { + while (first1 != last1) + { + init = init + *first1 * *first2; + ++first1; + ++first2; + } + + return init; + } + + template _UCXXEXPORT + T inner_product(InputIterator1 first1, InputIterator1 last1, + InputIterator2 first2, T init, + BinaryOperation1 binary_op1, + BinaryOperation2 binary_op2) + { + while (first1 != last1) + { + init = binary_op1(init, binary_op2(*first1, *first2)); + ++first1; + ++first2; + } + + return init; + } + + template _UCXXEXPORT + OutputIterator partial_sum(InputIterator first, InputIterator last, + OutputIterator result) + { + OutputIterator temp(result); + *result = *first; + ++first; + ++result; + + while (first != last) + { + *result = *first + *temp; + temp = result; + ++first; + ++result; + } + + return result; + } + + template _UCXXEXPORT + OutputIterator partial_sum(InputIterator first, InputIterator last, + OutputIterator result, BinaryOperation binary_op) + { + OutputIterator temp(result); + *result = *first; + ++first; + ++result; + + while(first != last) + { + *result = binary_op(*first, *temp); + temp = result; + ++first; + ++result; + } + + return result; + } + + template _UCXXEXPORT + OutputIterator + adjacent_difference(InputIterator first, InputIterator last, + OutputIterator result) + { + OutputIterator temp(first); + *result = *first; + ++first; + ++result; + + while(first != last) + { + *result = *first - *temp; + temp = first; + ++first; + ++result; + } + + return result; + } - template _UCXXEXPORT - T inner_product(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, T init) - { - while(first1 != last1){ - init = init + *first1 * *first2; - ++first1; - ++first2; - } - return init; - } + template _UCXXEXPORT + OutputIterator + adjacent_difference(InputIterator first, InputIterator last, + OutputIterator result, BinaryOperation binary_op) + { + OutputIterator temp(first); + *result = *first; + ++first; + ++result; - template _UCXXEXPORT - T inner_product(InputIterator1 first1, InputIterator1 last1, - InputIterator2 first2, T init, - BinaryOperation1 binary_op1, - BinaryOperation2 binary_op2) - { - while(first1 != last1){ - init = binary_op1(init, binary_op2(*first1, *first2)); - ++first1; - ++first2; - } - return init; - } + while(first != last) + { + *result = binary_op(*first, *temp); + temp = first; + ++first; + ++result; + } - template _UCXXEXPORT - OutputIterator partial_sum(InputIterator first, InputIterator last, - OutputIterator result) - { - OutputIterator temp(result); - *result = *first; - ++first; - ++result; + return result; + } - while(first != last){ - *result = *first + *temp; - temp = result; - ++first; - ++result; - } - return result; - } - - - template _UCXXEXPORT - OutputIterator partial_sum(InputIterator first, InputIterator last, - OutputIterator result, BinaryOperation binary_op) - { - OutputIterator temp(result); - *result = *first; - ++first; - ++result; - - while(first != last){ - *result = binary_op(*first, *temp); - temp = result; - ++first; - ++result; - } - return result; - } - - - template _UCXXEXPORT - OutputIterator - adjacent_difference(InputIterator first, InputIterator last, - OutputIterator result) - { - OutputIterator temp(first); - *result = *first; - ++first; - ++result; - - while(first != last){ - *result = *first - *temp; - temp = first; - ++first; - ++result; - } - - return result; - } - - - template _UCXXEXPORT - OutputIterator - adjacent_difference(InputIterator first, InputIterator last, - OutputIterator result, BinaryOperation binary_op) - { - OutputIterator temp(first); - *result = *first; - ++first; - ++result; - - while(first != last){ - *result = binary_op(*first, *temp); - temp = first; - ++first; - ++result; - } - - return result; - } - -} +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/ostream b/misc/uClibc++/include/uClibc++/ostream index 55bace3a0e..c62b4c92d9 100644 --- a/misc/uClibc++/include/uClibc++/ostream +++ b/misc/uClibc++/include/uClibc++/ostream @@ -1,20 +1,20 @@ -/* Copyright (C) 2004-2008 Garrett A. Kajmowicz +/* Copyright (C) 2004-2008 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. + This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include @@ -30,479 +30,542 @@ #pragma GCC visibility push(default) -namespace std { - template class basic_ostream; - typedef basic_ostream ostream; +extern "C++" +{ +namespace std +{ + template class basic_ostream; + typedef basic_ostream ostream; #ifdef __UCLIBCXX_HAS_WCHAR__ - typedef basic_ostream wostream; + typedef basic_ostream wostream; #endif - template basic_ostream& endl(basic_ostream& os); - template basic_ostream& ends(basic_ostream& os); - template basic_ostream& flush(basic_ostream& os); + template basic_ostream& endl(basic_ostream& os); + template basic_ostream& ends(basic_ostream& os); + template basic_ostream& flush(basic_ostream& os); - template class _UCXXEXPORT basic_ostream - : virtual public basic_ios - { - public: + template class _UCXXEXPORT basic_ostream + : virtual public basic_ios + { + public: - typedef charT char_type; - typedef typename traits::int_type int_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; - typedef traits traits_type; + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef traits traits_type; + _UCXXEXPORT basic_ostream(basic_streambuf* sb) + : basic_ios(sb) + { + basic_ios::init(sb); + } - _UCXXEXPORT basic_ostream(basic_streambuf* sb) - : basic_ios(sb) - { - basic_ios::init(sb); - } - virtual _UCXXEXPORT ~basic_ostream(); + virtual _UCXXEXPORT ~basic_ostream(); - class sentry; + class sentry; - _UCXXEXPORT basic_ostream& operator<<(basic_ostream& (*pf)(basic_ostream&)){ - return pf(*this); - } - _UCXXEXPORT basic_ostream& operator<<(basic_ios& (*pf)(basic_ios&)){ - pf(*this); - return *this; - } - _UCXXEXPORT basic_ostream& operator<<(ios_base& (*pf)(ios_base&)){ - pf(*this); - return *this; - } - basic_ostream& operator<<(bool n); - basic_ostream& operator<<(short n); - basic_ostream& operator<<(unsigned short n); - basic_ostream& operator<<(int n); - basic_ostream& operator<<(unsigned int n); - basic_ostream& operator<<(long n); - basic_ostream& operator<<(unsigned long n); - basic_ostream& operator<<(float f); - basic_ostream& operator<<(double f); - basic_ostream& operator<<(long double f); - basic_ostream& operator<<(void* p); - basic_ostream& operator<<(basic_streambuf* sb); + _UCXXEXPORT basic_ostream& operator<<(basic_ostream& (*pf)(basic_ostream&)) + { + return pf(*this); + } - _UCXXEXPORT basic_ostream& put(char_type c){ - if(basic_ostream::traits_type::eq_int_type( - basic_ios::mstreambuf->sputc(c), - basic_ostream::traits_type::eof())) - { - basic_ios::setstate(ios_base::eofbit); - } - return *this; - } - _UCXXEXPORT basic_ostream& write(const char_type* s, streamsize n){ - if(basic_ostream::traits_type::eq_int_type( - basic_ios::mstreambuf->sputn(s, n), - basic_ostream::traits_type::eof()) - ){ - basic_ios::setstate(ios_base::eofbit); - } - return *this; - } - _UCXXEXPORT basic_ostream& flush(){ - if(basic_ios::mstreambuf->pubsync() == -1){ - basic_ios::setstate(ios_base::badbit); - } - return *this; - } - _UCXXEXPORT pos_type tellp(){ - if(basic_ios::fail() != false){ - return pos_type(-1); - } - return basic_ios::rdbuf()->pubseekoff(0, ios_base::cur, ios_base::out); - } - _UCXXEXPORT basic_ostream& seekp(pos_type pos){ - if( basic_ios::fail() != true ){ - basic_ios::rdbuf()->pubseekpos(pos); - } - return *this; - } - _UCXXEXPORT basic_ostream& seekp(off_type off, ios_base::seekdir dir){ - if( basic_ios::fail() != true){ - basic_ios::rdbuf()->pubseekoff(off, dir); - } - return *this; - } + _UCXXEXPORT basic_ostream& operator<<(basic_ios& (*pf)(basic_ios&)) + { + pf(*this); + return *this; + } - _UCXXEXPORT void printout(const char_type* s, streamsize n){ + _UCXXEXPORT basic_ostream& operator<<(ios_base& (*pf)(ios_base&)) + { + pf(*this); + return *this; + } + + basic_ostream& operator<<(bool n); + basic_ostream& operator<<(short n); + basic_ostream& operator<<(unsigned short n); + basic_ostream& operator<<(int n); + basic_ostream& operator<<(unsigned int n); + basic_ostream& operator<<(long n); + basic_ostream& operator<<(unsigned long n); + basic_ostream& operator<<(float f); + basic_ostream& operator<<(double f); + basic_ostream& operator<<(long double f); + basic_ostream& operator<<(void* p); + basic_ostream& operator<<(basic_streambuf* sb); + + _UCXXEXPORT basic_ostream& put(char_type c) + { + if (basic_ostream::traits_type::eq_int_type( + basic_ios::mstreambuf->sputc(c), + basic_ostream::traits_type::eof())) + { + basic_ios::setstate(ios_base::eofbit); + } + + return *this; + } + + _UCXXEXPORT basic_ostream& write(const char_type* s, streamsize n) + { + if (basic_ostream::traits_type::eq_int_type( + basic_ios::mstreambuf->sputn(s, n), + basic_ostream::traits_type::eof()) + ) + { + basic_ios::setstate(ios_base::eofbit); + } + + return *this; + } + + _UCXXEXPORT basic_ostream& flush() + { + if (basic_ios::mstreambuf->pubsync() == -1) + { + basic_ios::setstate(ios_base::badbit); + } + + return *this; + } + + _UCXXEXPORT pos_type tellp() + { + if (basic_ios::fail() != false) + { + return pos_type(-1); + } + + return basic_ios::rdbuf()->pubseekoff(0, ios_base::cur, ios_base::out); + } + + _UCXXEXPORT basic_ostream& seekp(pos_type pos) + { + if (basic_ios::fail() != true) + { + basic_ios::rdbuf()->pubseekpos(pos); + } + + return *this; + } + + _UCXXEXPORT basic_ostream& seekp(off_type off, ios_base::seekdir dir) + { + if (basic_ios::fail() != true) + { + basic_ios::rdbuf()->pubseekoff(off, dir); + } + + return *this; + } + + _UCXXEXPORT void printout(const char_type* s, streamsize n) + { //david - streamsize extra = ios::width() - n; - if ((ios::flags()&ios::adjustfield) == ios::right){ - while (extra > 0) { - --extra; - put(ios::fill()); - } - } - write(s, n); - if ((ios::flags()&ios::adjustfield) == ios::left) { - while (extra > 0) { - --extra; - put(ios::fill()); - } - } - // Width value only applies for the next output operation. Reset to zero. - ios::width(0); - } + streamsize extra = ios::width() - n; + if ((ios::flags()&ios::adjustfield) == ios::right) + { + while (extra > 0) + { + --extra; + put(ios::fill()); + } + } - protected: - basic_ostream(const basic_ostream &){ } - basic_ostream & operator=(const basic_ostream &){ return *this; } - }; + write(s, n); + if ((ios::flags()&ios::adjustfield) == ios::left) + { + while (extra > 0) + { + --extra; + put(ios::fill()); + } + } - //Implementations of template functions. To allow for partial specialization + // Width value only applies for the next output operation. Reset to zero. - template _UCXXEXPORT basic_ostream::~basic_ostream(){ } - - template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(bool n){ - sentry s(*this); - if( basic_ios::flags() & ios_base::boolalpha){ - if(n){ - printout("true", 4); - }else{ - printout("false", 5); - } - }else{ - if(n){ - printout("1", 1); - }else{ - printout("0", 1); - } - } - if(basic_ios::flags() & ios_base::unitbuf){ - flush(); - } - return *this; - } + ios::width(0); + } - template _UCXXEXPORT basic_ostream& - basic_ostream::operator<<(unsigned short n){ - sentry s(*this); - __ostream_printout::printout(*this, n); - return *this; - } + protected: + basic_ostream(const basic_ostream &){ } + basic_ostream & operator=(const basic_ostream &){ return *this; } + }; - template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(short n){ - sentry s(*this); - __ostream_printout::printout(*this, n); - return *this; - } + // Implementations of template functions. To allow for partial specialization - template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(int n){ - sentry s(*this); - __ostream_printout::printout(*this, n); - return *this; - } + template _UCXXEXPORT basic_ostream::~basic_ostream(){ } + + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(bool n) + { + sentry s(*this); + if (basic_ios::flags() & ios_base::boolalpha) + { + if (n) + { + printout("true", 4); + } + else + { + printout("false", 5); + } + } + else + { + if (n) + { + printout("1", 1); + } + else + { + printout("0", 1); + } + } - template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(unsigned int n){ - sentry s(*this); - __ostream_printout::printout(*this, n); - return *this; - } + if (basic_ios::flags() & ios_base::unitbuf) + { + flush(); + } - template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(long n){ - sentry s(*this); - __ostream_printout::printout(*this, n); - return *this; - } + return *this; + } - template _UCXXEXPORT basic_ostream& - basic_ostream::operator<<(unsigned long n) - { - sentry s(*this); - __ostream_printout::printout(*this, n); - return *this; - } + template _UCXXEXPORT basic_ostream& + basic_ostream::operator<<(unsigned short n) + { + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } - template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(float f){ - sentry s(*this); - __ostream_printout::printout(*this, f); - return *this; - } + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(short n) + { + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } - template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(double f){ - sentry s(*this); - __ostream_printout::printout(*this, f); - return *this; - } + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(int n) + { + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } - template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(long double f){ - sentry s(*this); - __ostream_printout::printout(*this, f); - return *this; - } + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(unsigned int n) + { + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } - template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(void* p){ - sentry s(*this); - char buffer[20]; - printout(buffer, snprintf(buffer, 20, "%p", p) ); - if(basic_ios::flags() & ios_base::unitbuf){ - flush(); - } - return *this; - } + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(long n) + { + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } - template _UCXXEXPORT basic_ostream& - basic_ostream::operator<<(basic_streambuf* sb) - { - sentry s(*this); - if(sb == 0){ - basic_ios::setstate(ios_base::badbit); - return *this; - } + template _UCXXEXPORT basic_ostream& + basic_ostream::operator<<(unsigned long n) + { + sentry s(*this); + __ostream_printout::printout(*this, n); + return *this; + } - typename traits::int_type c; + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(float f) + { + sentry s(*this); + __ostream_printout::printout(*this, f); + return *this; + } - while(basic_ios::good() && (c = sb->sbumpc()) != traits::eof() ){ - put(c); - } + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(double f) + { + sentry s(*this); + __ostream_printout::printout(*this, f); + return *this; + } - if(basic_ios::flags() & ios_base::unitbuf){ - flush(); - } - return *this; - } + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(long double f) + { + sentry s(*this); + __ostream_printout::printout(*this, f); + return *this; + } - /*Template Specializations*/ + template _UCXXEXPORT basic_ostream& basic_ostream::operator<<(void* p) + { + sentry s(*this); + char buffer[20]; + printout(buffer, snprintf(buffer, 20, "%p", p)); + if (basic_ios::flags() & ios_base::unitbuf) + { + flush(); + } + + return *this; + } + + template _UCXXEXPORT basic_ostream& + basic_ostream::operator<<(basic_streambuf* sb) + { + sentry s(*this); + if (sb == 0) + { + basic_ios::setstate(ios_base::badbit); + return *this; + } + + typename traits::int_type c; + + while (basic_ios::good() && (c = sb->sbumpc()) != traits::eof()) + { + put(c); + } + + if (basic_ios::flags() & ios_base::unitbuf) + { + flush(); + } + + return *this; + } + + /* Template Specializations */ #ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ #ifndef __UCLIBCXX_COMPILE_OSTREAM__ #ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template <> _UCXXEXPORT ostream::~basic_ostream(); + template <> _UCXXEXPORT ostream::~basic_ostream(); #endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template <> _UCXXEXPORT ostream & ostream::flush(); + template <> _UCXXEXPORT ostream & ostream::flush(); - template <> _UCXXEXPORT ostream & ostream::operator<<(bool n); - template <> _UCXXEXPORT ostream & ostream::operator<<(short int n); - template <> _UCXXEXPORT ostream & ostream::operator<<(unsigned short int n); - template <> _UCXXEXPORT ostream & ostream::operator<<(int n); - template <> _UCXXEXPORT ostream & ostream::operator<<(unsigned int n); - template <> _UCXXEXPORT ostream & ostream::operator<<(long n); - template <> _UCXXEXPORT ostream & ostream::operator<<(unsigned long n); - template <> _UCXXEXPORT ostream & ostream::operator<<(float f); - template <> _UCXXEXPORT ostream & ostream::operator<<(double f); - template <> _UCXXEXPORT ostream & ostream::operator<<(long double f); - template <> _UCXXEXPORT ostream & ostream::operator<<(void* p); - template <> _UCXXEXPORT ostream & ostream::operator<<(basic_streambuf >* sb); + template <> _UCXXEXPORT ostream & ostream::operator<<(bool n); + template <> _UCXXEXPORT ostream & ostream::operator<<(short int n); + template <> _UCXXEXPORT ostream & ostream::operator<<(unsigned short int n); + template <> _UCXXEXPORT ostream & ostream::operator<<(int n); + template <> _UCXXEXPORT ostream & ostream::operator<<(unsigned int n); + template <> _UCXXEXPORT ostream & ostream::operator<<(long n); + template <> _UCXXEXPORT ostream & ostream::operator<<(unsigned long n); + template <> _UCXXEXPORT ostream & ostream::operator<<(float f); + template <> _UCXXEXPORT ostream & ostream::operator<<(double f); + template <> _UCXXEXPORT ostream & ostream::operator<<(long double f); + template <> _UCXXEXPORT ostream & ostream::operator<<(void* p); + template <> _UCXXEXPORT ostream & ostream::operator<<(basic_streambuf >* sb); #endif #endif - template > - class _UCXXEXPORT basic_ostream::sentry - { - bool ok; - public: - explicit _UCXXEXPORT sentry(basic_ostream& os): ok(true){ + template > + class _UCXXEXPORT basic_ostream::sentry + { + bool ok; + public: + explicit _UCXXEXPORT sentry(basic_ostream& os): ok(true){ //david - if(os.good() !=0){ //Prepare for output - } - //Flush any tied buffer - if(os.tie() !=0 ){ - os.tie()->flush(); - } - } - _UCXXEXPORT ~sentry() { } - _UCXXEXPORT operator bool() { - return ok; - } - }; + if (os.good() !=0) + { + // Prepare for output + } + // Flush any tied buffer + + if (os.tie() !=0) + { + os.tie()->flush(); + } + } + + _UCXXEXPORT ~sentry() { } + + _UCXXEXPORT operator bool() + { + return ok; + } + }; #ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ #ifndef __UCLIBCXX_COMPILE_OSTREAM__ #ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template <> _UCXXEXPORT ostream::sentry::sentry(ostream & os); - template <> _UCXXEXPORT ostream::sentry::~sentry(); + template <> _UCXXEXPORT ostream::sentry::sentry(ostream & os); + template <> _UCXXEXPORT ostream::sentry::~sentry(); #endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ #endif #endif + // Non - class functions - //Non - class functions - - - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, charT c) - { - typename basic_ostream::sentry s(out); - out.put(c); - return out; - } - - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, char c) - { - typename basic_ostream::sentry s(out); - out.put(c); - return out; - } + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, charT c) + { + typename basic_ostream::sentry s(out); + out.put(c); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, char c) + { + typename basic_ostream::sentry s(out); + out.put(c); + return out; + } - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, char c) - { - typename basic_ostream::sentry s(out); - out.put(c); - return out; - } + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, char c) + { + typename basic_ostream::sentry s(out); + out.put(c); + return out; + } // signed and unsigned - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, signed char c) - { - typename basic_ostream::sentry s(out); - out.put(c); - return out; - } - - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, unsigned char c) - { - typename basic_ostream::sentry s(out); - out.put(c); - return out; - } - - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, const charT* c) - { - typename basic_ostream::sentry s(out); - out.printout(c, traits::length(c) ); - return out; - } - - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, const char* c) - { - typename basic_ostream::sentry s(out); - out.printout(c, char_traits::length(c) ); - return out; - } -//david - // partial specializations - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, const char* c) - { -//add by david - /* printf("hello\n"); - int i; - for(i=0;i::sentry s(out); - out.printout(c, traits::length(c)); - return out; - } + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, signed char c) + { + typename basic_ostream::sentry s(out); + out.put(c); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, unsigned char c) + { + typename basic_ostream::sentry s(out); + out.put(c); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const charT* c) + { + typename basic_ostream::sentry s(out); + out.printout(c, traits::length(c)); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const char* c) + { + typename basic_ostream::sentry s(out); + out.printout(c, char_traits::length(c)); + return out; + } + + // partial specializations + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const char* c) + { + typename basic_ostream::sentry s(out); + out.printout(c, traits::length(c)); + return out; + } #ifdef __UCLIBCXX_HAS_WCHAR__ - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, const char* c) - { - typename basic_ostream::sentry s(out); - size_t numChars = char_traits::length(c); - wchar_t * temp = new wchar_t[numChars]; + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const char* c) + { + typename basic_ostream::sentry s(out); + size_t numChars = char_traits::length(c); + wchar_t * temp = new wchar_t[numChars]; - for(size_t i=0; i < numChars; ++i){ - temp[i] = out.widen(c[i]); - } + for (size_t i=0; i < numChars; ++i) + { + temp[i] = out.widen(c[i]); + } - out.printout(temp, numChars); - return out; - } + out.printout(temp, numChars); + return out; + } #endif - // signed and unsigned - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, const signed char* c) - { - typename basic_ostream::sentry s(out); - out.printout(reinterpret_cast(c), traits::length( reinterpret_cast(c))); - return out; - } - - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& out, const unsigned char* c) - { - typename basic_ostream::sentry s(out); - out.printout(reinterpret_cast(c), traits::length( reinterpret_cast(c))); - return out; - } + // Signed and unsigned - template _UCXXEXPORT basic_ostream& - endl(basic_ostream& os) - { - typename basic_ostream::sentry s(os); - os.put('\n'); - os.flush(); - return os; - } + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const signed char* c) + { + typename basic_ostream::sentry s(out); + out.printout(reinterpret_cast(c), traits::length(reinterpret_cast(c))); + return out; + } + + template _UCXXEXPORT basic_ostream& + operator<<(basic_ostream& out, const unsigned char* c) + { + typename basic_ostream::sentry s(out); + out.printout(reinterpret_cast(c), traits::length(reinterpret_cast(c))); + return out; + } - template _UCXXEXPORT basic_ostream& - ends(basic_ostream& os) - { - typename basic_ostream::sentry s(os); - os.put(traits::eos()); - return os; - } + template _UCXXEXPORT basic_ostream& + endl(basic_ostream& os) + { + typename basic_ostream::sentry s(os); + os.put('\n'); + os.flush(); + return os; + } - template _UCXXEXPORT basic_ostream& flush(basic_ostream& os){ - typename basic_ostream::sentry s(os); - os.flush(); - return os; - } + template _UCXXEXPORT basic_ostream& + ends(basic_ostream& os) + { + typename basic_ostream::sentry s(os); + os.put(traits::eos()); + return os; + } + template _UCXXEXPORT basic_ostream& flush(basic_ostream& os){ + typename basic_ostream::sentry s(os); + os.flush(); + return os; + } #ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ #ifndef __UCLIBCXX_COMPILE_OSTREAM__ - template <> _UCXXEXPORT ostream & endl(ostream & os); - template <> _UCXXEXPORT ostream & flush(ostream & os); - template <> _UCXXEXPORT ostream & operator<<(ostream & out, char c); - template <> _UCXXEXPORT ostream & operator<<(ostream & out, const char* c); - template <> _UCXXEXPORT ostream & operator<<(ostream & out, unsigned char c); - template <> _UCXXEXPORT ostream & operator<<(ostream & out, unsigned const char* c); + template <> _UCXXEXPORT ostream & endl(ostream & os); + template <> _UCXXEXPORT ostream & flush(ostream & os); + template <> _UCXXEXPORT ostream & operator<<(ostream & out, char c); + template <> _UCXXEXPORT ostream & operator<<(ostream & out, const char* c); + template <> _UCXXEXPORT ostream & operator<<(ostream & out, unsigned char c); + template <> _UCXXEXPORT ostream & operator<<(ostream & out, unsigned const char* c); #endif #endif - #ifndef __STRICT_ANSI__ -//Support for output of long long data types +// Support for output of long long data types template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, signed long long int i) + operator<<(basic_ostream& os, signed long long int i) { - typename basic_ostream::sentry s(os); - __ostream_printout::printout(os, i); - return os; + typename basic_ostream::sentry s(os); + __ostream_printout::printout(os, i); + return os; } - template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, unsigned long long int i) + operator<<(basic_ostream& os, unsigned long long int i) { - typename basic_ostream::sentry s(os); - __ostream_printout::printout(os, i); - return os; + typename basic_ostream::sentry s(os); + __ostream_printout::printout(os, i); + return os; } +#endif //__STRICT_ANSI__ -#endif //__STRICT_ANSI__ - - - - -} +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/ostream_helpers b/misc/uClibc++/include/uClibc++/ostream_helpers index 6c3f9fc69c..214ec259d6 100644 --- a/misc/uClibc++/include/uClibc++/ostream_helpers +++ b/misc/uClibc++/include/uClibc++/ostream_helpers @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -29,459 +29,663 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ + /* We are making the following template class for serveral reasons. Firstly, + * we want to keep the main ostream code neat and tidy. Secondly, we want it + * to be easy to do partial specialization of the ostream code so that it can + * be expanded and put into the library. This will allow us to make application + * code smaller at the expense of increased library size. This is a fair + * trade-off when there are multiple applications being compiled. Also, this + * feature will be used optionally via configuration options. It will also + * allow us to keep the code bases in sync, dramatically simplifying the + * maintenance required. We specialized for char because wchar and others + * require different scanf functions + */ - /* We are making the following template class for serveral reasons. Firstly, - * we want to keep the main ostream code neat and tidy. Secondly, we want it - * to be easy to do partial specialization of the ostream code so that it can - * be expanded and put into the library. This will allow us to make application - * code smaller at the expense of increased library size. This is a fair - * trade-off when there are multiple applications being compiled. Also, this - * feature will be used optionally via configuration options. It will also - * allow us to keep the code bases in sync, dramatically simplifying the - * maintenance required. We specialized for char because wchar and others - * require different scanf functions - */ + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const dataType n); + }; + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const signed long int n) + { + char buffer[20]; + const char * c_ld = "%ld"; + const char * c_lo = "%lo"; + const char * c_lX = "%lX"; + const char * c_lx = "%lx"; + const char * c_hashlo = "%#lo"; + const char * c_hashlX = "%#lX"; + const char * c_hashlx = "%#lx"; + const char * formatString=0; - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const dataType n); - }; + if (stream.flags() & ios_base::dec) + { + formatString = c_ld; + } + else if (stream.flags() & ios_base::oct) + { + if (stream.flags() & ios_base::showbase) + { + formatString = c_hashlo; + } + else + { + formatString = c_lo; + } + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::showbase) + { + if (stream.flags() & ios_base::uppercase) + { + formatString = c_hashlX; + } + else + { + formatString = c_hashlx; + } + } + else + { + if (stream.flags() & ios_base::uppercase) + { + formatString = c_lX; + } + else + { + formatString = c_lx; + } + } + } - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const signed long int n) - { - char buffer[20]; - const char * c_ld = "%ld"; - const char * c_lo = "%lo"; - const char * c_lX = "%lX"; - const char * c_lx = "%lx"; - const char * c_hashlo = "%#lo"; - const char * c_hashlX = "%#lX"; - const char * c_hashlx = "%#lx"; + stream.printout(buffer, snprintf(buffer, 20, formatString, n)); - const char * formatString=0; + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; - if( stream.flags() & ios_base::dec){ - formatString = c_ld; - }else if( stream.flags() & ios_base::oct){ - if( stream.flags() & ios_base::showbase){ - formatString = c_hashlo; - }else{ - formatString = c_lo; - } - }else if (stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::showbase){ - if(stream.flags() & ios_base::uppercase){ - formatString = c_hashlX; - }else{ - formatString = c_hashlx; - } - }else{ - if(stream.flags() & ios_base::uppercase){ - formatString = c_lX; - }else{ - formatString = c_lx; - } - } - } + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const unsigned long int n) + { + char buffer[20]; + const char * c_lo = "%lo"; + const char * c_lu = "%lu"; + const char * c_lX = "%lX"; + const char * c_lx = "%lx"; + const char * c_hashlo = "%#lo"; + const char * c_hashlX = "%#lX"; + const char * c_hashlx = "%#lx"; + const char * formatString=0; - stream.printout(buffer, snprintf(buffer, 20, formatString, n) ); + if (stream.flags() & ios_base::dec) + { + formatString = c_lu; + } + else if (stream.flags() & ios_base::oct) + { + if (stream.flags() & ios_base::showbase) + { + formatString = c_hashlo; + } + else + { + formatString = c_lo; + } + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::showbase) + { + if (stream.flags() & ios_base::uppercase) + { + formatString = c_hashlX; + } + else + { + formatString = c_hashlx; + } + } + else + { + if (stream.flags() & ios_base::uppercase) + { + formatString = c_lX; + } + else + { + formatString = c_lx; + } + } + } - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - - } - }; - - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const unsigned long int n) - { - char buffer[20]; - const char * c_lo = "%lo"; - const char * c_lu = "%lu"; - const char * c_lX = "%lX"; - const char * c_lx = "%lx"; - const char * c_hashlo = "%#lo"; - const char * c_hashlX = "%#lX"; - const char * c_hashlx = "%#lx"; - const char * formatString=0; - - if( stream.flags() & ios_base::dec){ - formatString = c_lu; - }else if( stream.flags() & ios_base::oct){ - if( stream.flags() & ios_base::showbase){ - formatString = c_hashlo; - }else{ - formatString = c_lo; - } - }else if (stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::showbase){ - if(stream.flags() & ios_base::uppercase){ - formatString = c_hashlX; - }else{ - formatString = c_hashlx; - } - }else{ - if(stream.flags() & ios_base::uppercase){ - formatString = c_lX; - }else{ - formatString = c_lx; - } - } - } - - stream.printout(buffer, snprintf(buffer, 20, formatString, n)); - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - } - }; + stream.printout(buffer, snprintf(buffer, 20, formatString, n)); + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; #ifndef __STRICT_ANSI__ - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const signed long long int n) - { - char buffer[28]; - const char * lld = "%lld"; - const char * llo = "%llo"; - const char * llX = "%llX"; - const char * llx = "%llx"; - const char * hashllo = "%#llo"; - const char * hashllX = "%#llX"; - const char * hashllx = "%#llx"; - const char * formatString=0; + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const signed long long int n) + { + char buffer[28]; + const char * lld = "%lld"; + const char * llo = "%llo"; + const char * llX = "%llX"; + const char * llx = "%llx"; + const char * hashllo = "%#llo"; + const char * hashllX = "%#llX"; + const char * hashllx = "%#llx"; + const char * formatString=0; - if( stream.flags() & ios_base::dec){ - formatString = lld; - }else if( stream.flags() & ios_base::oct){ - if( stream.flags() & ios_base::showbase){ - formatString = hashllo; - }else{ - formatString = llo; - } - }else if (stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::showbase){ - if(stream.flags() & ios_base::uppercase){ - formatString = hashllX; - }else{ - formatString = hashllx; - } - }else{ - if(stream.flags() & ios_base::uppercase){ - formatString = llX; - }else{ - formatString = llx; - } - } - } + if (stream.flags() & ios_base::dec) + { + formatString = lld; + } + else if (stream.flags() & ios_base::oct) + { + if (stream.flags() & ios_base::showbase) + { + formatString = hashllo; + } + else + { + formatString = llo; + } + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::showbase) + { + if (stream.flags() & ios_base::uppercase) + { + formatString = hashllX; + } + else + { + formatString = hashllx; + } + } + else + { + if (stream.flags() & ios_base::uppercase) + { + formatString = llX; + } + else + { + formatString = llx; + } + } + } - stream.printout(buffer, snprintf(buffer, 27, formatString, n) ); + stream.printout(buffer, snprintf(buffer, 27, formatString, n)); - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - } - }; + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const unsigned long long int n) - { - char buffer[28]; - const char * llo = "%llo"; - const char * llu = "%llu"; - const char * llX = "%llX"; - const char * llx = "%llx"; - const char * hashllo = "%#llo"; - const char * hashllX = "%#llX"; - const char * hashllx = "%#llx"; - const char * formatString=0; + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const unsigned long long int n) + { + char buffer[28]; + const char * llo = "%llo"; + const char * llu = "%llu"; + const char * llX = "%llX"; + const char * llx = "%llx"; + const char * hashllo = "%#llo"; + const char * hashllX = "%#llX"; + const char * hashllx = "%#llx"; + const char * formatString=0; - if( stream.flags() & ios_base::dec){ - formatString = llu; - }else if( stream.flags() & ios_base::oct){ - if( stream.flags() & ios_base::showbase){ - formatString = hashllo; - }else{ - formatString = llo; - } - }else if (stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::showbase){ - if(stream.flags() & ios_base::uppercase){ - formatString = hashllX; - }else{ - formatString = hashllx; - } - }else{ - if(stream.flags() & ios_base::uppercase){ - formatString = llX; - }else{ - formatString = llx; - } - } - } + if (stream.flags() & ios_base::dec) + { + formatString = llu; + } + else if (stream.flags() & ios_base::oct) + { + if (stream.flags() & ios_base::showbase) + { + formatString = hashllo; + } + else + { + formatString = llo; + } + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::showbase) + { + if (stream.flags() & ios_base::uppercase) + { + formatString = hashllX; + } + else + { + formatString = hashllx; + } + } + else + { + if (stream.flags() & ios_base::uppercase) + { + formatString = llX; + } + else + { + formatString = llx; + } + } + } - stream.printout(buffer, snprintf(buffer, 27, formatString, n) ); + stream.printout(buffer, snprintf(buffer, 27, formatString, n)); - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - } - }; + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; -#endif //__STRICT_ANSI__ +#endif //__STRICT_ANSI__ - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const double f) - { - char buffer[32]; - int length; - if(stream.flags() & ios_base::scientific){ - if(stream.flags() & ios_base::uppercase){ - length = snprintf(buffer, 32, "%*.*E", static_cast(stream.width()),static_cast(stream.precision()), f); - }else{ - length = snprintf(buffer, 32, "%*.*e", static_cast(stream.width()),static_cast(stream.precision()), f); - } - } else if(stream.flags() & ios_base::fixed){ - length = snprintf(buffer, 32, "%*.*f",static_cast(stream.width()),static_cast(stream.precision()), f); - } else { - length = snprintf(buffer, 32, "%*.*g",static_cast(stream.width()),static_cast(stream.precision()), f); - } - stream.printout(buffer, length); - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - } - }; + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const double f) + { + char buffer[32]; + int length; - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const long double f) - { - char buffer[32]; - int length; - if(stream.flags() & ios_base::scientific){ - if(stream.flags() & ios_base::uppercase){ - length = snprintf(buffer, 32, "%*.*LE", static_cast(stream.width()), static_cast(stream.precision()), f); - }else{ - length = snprintf(buffer, 32, "%*.*Le", static_cast(stream.width()), static_cast(stream.precision()), f); - } - } else if(stream.flags() & ios_base::fixed){ - length = snprintf(buffer, 32, "%*.*Lf", static_cast(stream.width()), static_cast(stream.precision()), f); - } else { - length = snprintf(buffer, 32, "%*.*Lg", static_cast(stream.width()), static_cast(stream.precision()), f); - } - stream.printout(buffer, length); - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } + if (stream.flags() & ios_base::scientific) + { + if (stream.flags() & ios_base::uppercase) + { + length = snprintf(buffer, 32, "%*.*E", static_cast(stream.width()),static_cast(stream.precision()), f); + } + else + { + length = snprintf(buffer, 32, "%*.*e", static_cast(stream.width()),static_cast(stream.precision()), f); + } + } else if (stream.flags() & ios_base::fixed) + { + length = snprintf(buffer, 32, "%*.*f",static_cast(stream.width()),static_cast(stream.precision()), f); + } + else + { + length = snprintf(buffer, 32, "%*.*g",static_cast(stream.width()),static_cast(stream.precision()), f); + } - } - }; + stream.printout(buffer, length); + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; + + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const long double f) + { + char buffer[32]; + int length; + if (stream.flags() & ios_base::scientific) + { + if (stream.flags() & ios_base::uppercase) + { + length = snprintf(buffer, 32, "%*.*LE", static_cast(stream.width()), static_cast(stream.precision()), f); + } + else + { + length = snprintf(buffer, 32, "%*.*Le", static_cast(stream.width()), static_cast(stream.precision()), f); + } + } + else if (stream.flags() & ios_base::fixed) + { + length = snprintf(buffer, 32, "%*.*Lf", static_cast(stream.width()), static_cast(stream.precision()), f); + } + else + { + length = snprintf(buffer, 32, "%*.*Lg", static_cast(stream.width()), static_cast(stream.precision()), f); + } + + stream.printout(buffer, length); + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; #ifdef __UCLIBCXX_HAS_WCHAR__ - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const signed long int n) - { - wchar_t buffer[20]; - if( stream.flags() & ios_base::dec){ - stream.printout(buffer, swprintf(buffer, 20, L"%ld", n)); - }else if( stream.flags() & ios_base::oct){ - if( stream.flags() & ios_base::showbase){ - stream.printout(buffer, swprintf(buffer, 20, L"%#lo", n)); - }else{ - stream.printout(buffer, swprintf(buffer, 20, L"%lo", n) ); - } - }else if (stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::showbase){ - if(stream.flags() & ios_base::uppercase){ - stream.printout(buffer, swprintf(buffer, 20, L"%#lX", n) ); - }else{ - stream.printout(buffer, swprintf(buffer, 20, L"%#lx", n) ); - } - }else{ - if(stream.flags() & ios_base::uppercase){ - stream.printout(buffer, swprintf(buffer, 20, L"%lX", n) ); - }else{ - stream.printout(buffer, swprintf(buffer, 20, L"%lx", n) ); - } - } - } - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - } - }; + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const signed long int n) + { + wchar_t buffer[20]; + if (stream.flags() & ios_base::dec) + { + stream.printout(buffer, swprintf(buffer, 20, L"%ld", n)); + } + else if (stream.flags() & ios_base::oct) + { + if (stream.flags() & ios_base::showbase) + { + stream.printout(buffer, swprintf(buffer, 20, L"%#lo", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 20, L"%lo", n)); + } + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::showbase) + { + if (stream.flags() & ios_base::uppercase) + { + stream.printout(buffer, swprintf(buffer, 20, L"%#lX", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 20, L"%#lx", n)); + } + } + else + { + if (stream.flags() & ios_base::uppercase) + { + stream.printout(buffer, swprintf(buffer, 20, L"%lX", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 20, L"%lx", n)); + } + } + } - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const unsigned long int n) - { - wchar_t buffer[20]; - if( stream.flags() & ios_base::dec){ - stream.printout(buffer, swprintf(buffer, 20, L"%lu", n)); - }else if( stream.flags() & ios_base::oct){ - if( stream.flags() & ios_base::showbase){ - stream.printout(buffer, swprintf(buffer, 20, L"%#lo", n)); - }else{ - stream.printout(buffer, swprintf(buffer, 20, L"%lo", n) ); - } - }else if (stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::showbase){ - if(stream.flags() & ios_base::uppercase){ - stream.printout(buffer, swprintf(buffer, 20, L"%#lX", n) ); - }else{ - stream.printout(buffer, swprintf(buffer, 20, L"%#lx", n) ); - } - }else{ - if(stream.flags() & ios_base::uppercase){ - stream.printout(buffer, swprintf(buffer, 20, L"%lX", n) ); - }else{ - stream.printout(buffer, swprintf(buffer, 20, L"%lx", n) ); - } - } - } - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - } - }; + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; + + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const unsigned long int n) + { + wchar_t buffer[20]; + + if (stream.flags() & ios_base::dec) + { + stream.printout(buffer, swprintf(buffer, 20, L"%lu", n)); + } + else if (stream.flags() & ios_base::oct) + { + if (stream.flags() & ios_base::showbase) + { + stream.printout(buffer, swprintf(buffer, 20, L"%#lo", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 20, L"%lo", n)); + } + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::showbase) + { + if (stream.flags() & ios_base::uppercase) + { + stream.printout(buffer, swprintf(buffer, 20, L"%#lX", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 20, L"%#lx", n)); + } + } + else + { + if (stream.flags() & ios_base::uppercase) + { + stream.printout(buffer, swprintf(buffer, 20, L"%lX", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 20, L"%lx", n)); + } + } + } + + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; #ifndef __STRICT_ANSI__ - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const signed long long int n) - { - wchar_t buffer[28]; - if( stream.flags() & ios_base::dec){ - stream.printout(buffer, swprintf(buffer, 27, L"%lld", n)); - }else if( stream.flags() & ios_base::oct){ - if( stream.flags() & ios_base::showbase){ - stream.printout(buffer, swprintf(buffer, 27, L"%#llo", n)); - }else{ - stream.printout(buffer, swprintf(buffer, 27, L"%llo", n) ); - } - }else if (stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::showbase){ - if(stream.flags() & ios_base::uppercase){ - stream.printout(buffer, swprintf(buffer, 27, L"%#llX", n) ); - }else{ - stream.printout(buffer, swprintf(buffer, 27, L"%#llx", n) ); - } - }else{ - if(stream.flags() & ios_base::uppercase){ - stream.printout(buffer, swprintf(buffer, 27, L"%llX", n) ); - }else{ - stream.printout(buffer, swprintf(buffer, 27, L"%llx", n) ); - } - } - } - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - } - }; + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const signed long long int n) + { + wchar_t buffer[28]; + if (stream.flags() & ios_base::dec) + { + stream.printout(buffer, swprintf(buffer, 27, L"%lld", n)); + } + else if (stream.flags() & ios_base::oct) + { + if (stream.flags() & ios_base::showbase) + { + stream.printout(buffer, swprintf(buffer, 27, L"%#llo", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 27, L"%llo", n)); + } + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::showbase) + { + if (stream.flags() & ios_base::uppercase) + { + stream.printout(buffer, swprintf(buffer, 27, L"%#llX", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 27, L"%#llx", n)); + } + } + else + { + if (stream.flags() & ios_base::uppercase) + { + stream.printout(buffer, swprintf(buffer, 27, L"%llX", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 27, L"%llx", n)); + } + } + } - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const unsigned long long int n) - { - wchar_t buffer[28]; - if( stream.flags() & ios_base::dec){ - stream.printout(buffer, swprintf(buffer, 27, L"%llu", n)); - }else if( stream.flags() & ios_base::oct){ - if( stream.flags() & ios_base::showbase){ - stream.printout(buffer, swprintf(buffer, 27, L"%#llo", n)); - }else{ - stream.printout(buffer, swprintf(buffer, 27, L"%llo", n) ); - } - }else if (stream.flags() & ios_base::hex){ - if(stream.flags() & ios_base::showbase){ - if(stream.flags() & ios_base::uppercase){ - stream.printout(buffer, swprintf(buffer, 27, L"%#llX", n) ); - }else{ - stream.printout(buffer, swprintf(buffer, 27, L"%#llx", n) ); - } - }else{ - if(stream.flags() & ios_base::uppercase){ - stream.printout(buffer, swprintf(buffer, 27, L"%llX", n) ); - }else{ - stream.printout(buffer, swprintf(buffer, 27, L"%llx", n) ); - } - } - } - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - } - }; + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; + + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const unsigned long long int n) + { + wchar_t buffer[28]; + + if (stream.flags() & ios_base::dec) + { + stream.printout(buffer, swprintf(buffer, 27, L"%llu", n)); + } + else if (stream.flags() & ios_base::oct) + { + if (stream.flags() & ios_base::showbase) + { + stream.printout(buffer, swprintf(buffer, 27, L"%#llo", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 27, L"%llo", n)); + } + } + else if (stream.flags() & ios_base::hex) + { + if (stream.flags() & ios_base::showbase) + { + if (stream.flags() & ios_base::uppercase) + { + stream.printout(buffer, swprintf(buffer, 27, L"%#llX", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 27, L"%#llx", n)); + } + } + else + { + if (stream.flags() & ios_base::uppercase) + { + stream.printout(buffer, swprintf(buffer, 27, L"%llX", n)); + } + else + { + stream.printout(buffer, swprintf(buffer, 27, L"%llx", n)); + } + } + } + + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; -#endif //__STRICT_ANSI__ +#endif //__STRICT_ANSI__ - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const double f) - { - wchar_t buffer[32]; - wchar_t format_string[32]; - if(stream.flags() & ios_base::scientific){ - if(stream.flags() & ios_base::uppercase){ - swprintf(format_string, 32, L"%%%u.%uE", static_cast(stream.width()), static_cast(stream.precision())); - }else{ - swprintf(format_string, 32, L"%%%u.%ue", static_cast(stream.width()), static_cast(stream.precision())); - } - } else if(stream.flags() & ios_base::fixed){ - swprintf(format_string, 32, L"%%%u.%uf", static_cast(stream.width()), static_cast(stream.precision())); - } else { - swprintf(format_string, 32, L"%%%u.%ug", static_cast(stream.width()), static_cast(stream.precision())); - } - stream.printout(buffer, swprintf(buffer, 32, format_string, f) ); - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - } - }; + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const double f) + { + wchar_t buffer[32]; + wchar_t format_string[32]; - template class _UCXXEXPORT __ostream_printout{ - public: - static void printout(basic_ostream& stream, const long double f) - { - wchar_t buffer[32]; - wchar_t format_string[32]; - if(stream.flags() & ios_base::scientific){ - if(stream.flags() & ios_base::uppercase){ - swprintf(format_string, 32, L"%%%u.%uLE", static_cast(stream.width()), static_cast(stream.precision())); - }else{ - swprintf(format_string, 32, L"%%%u.%uLe", static_cast(stream.width()), static_cast(stream.precision())); - } - } else if(stream.flags() & ios_base::fixed){ - swprintf(format_string, 32, L"%%%u.%uLf", static_cast(stream.width()), static_cast(stream.precision())); - } else { - swprintf(format_string, 32, L"%%%u.%uLg", static_cast(stream.width()), static_cast(stream.precision())); - } - stream.printout(buffer, swprintf(buffer, 32, format_string, f) ); - if(stream.flags() & ios_base::unitbuf){ - stream.flush(); - } - } - }; + if (stream.flags() & ios_base::scientific) + { + if (stream.flags() & ios_base::uppercase) + { + swprintf(format_string, 32, L"%%%u.%uE", static_cast(stream.width()), static_cast(stream.precision())); + } + else + { + swprintf(format_string, 32, L"%%%u.%ue", static_cast(stream.width()), static_cast(stream.precision())); + } + } + else if (stream.flags() & ios_base::fixed) + { + swprintf(format_string, 32, L"%%%u.%uf", static_cast(stream.width()), static_cast(stream.precision())); + } + else + { + swprintf(format_string, 32, L"%%%u.%ug", static_cast(stream.width()), static_cast(stream.precision())); + } + + stream.printout(buffer, swprintf(buffer, 32, format_string, f)); + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; + + template class _UCXXEXPORT __ostream_printout + { + public: + static void printout(basic_ostream& stream, const long double f) + { + wchar_t buffer[32]; + wchar_t format_string[32]; + + if (stream.flags() & ios_base::scientific) + { + if (stream.flags() & ios_base::uppercase) + { + swprintf(format_string, 32, L"%%%u.%uLE", static_cast(stream.width()), static_cast(stream.precision())); + } + else + { + swprintf(format_string, 32, L"%%%u.%uLe", static_cast(stream.width()), static_cast(stream.precision())); + } + } + else if (stream.flags() & ios_base::fixed) + { + swprintf(format_string, 32, L"%%%u.%uLf", static_cast(stream.width()), static_cast(stream.precision())); + } + else + { + swprintf(format_string, 32, L"%%%u.%uLg", static_cast(stream.width()), static_cast(stream.precision())); + } + + stream.printout(buffer, swprintf(buffer, 32, format_string, f)); + if (stream.flags() & ios_base::unitbuf) + { + stream.flush(); + } + } + }; #endif //__UCLIBCXX_HAS_WCHAR__ -} +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/queue b/misc/uClibc++/include/uClibc++/queue index b817b1dfe7..51fe35cbe0 100644 --- a/misc/uClibc++/include/uClibc++/queue +++ b/misc/uClibc++/include/uClibc++/queue @@ -1,19 +1,20 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -25,102 +26,114 @@ #pragma GCC visibility push(default) -namespace std{ - - template > class _UCXXEXPORT queue{ - protected: - Container c; - public: - typedef typename Container::value_type value_type; - typedef typename Container::size_type size_type; - typedef Container container_type; +extern "C++" +{ +namespace std +{ + template > class _UCXXEXPORT queue + { + protected: + Container c; - explicit queue(const Container& a = Container()) : c(a) { } + public: + typedef typename Container::value_type value_type; + typedef typename Container::size_type size_type; + typedef Container container_type; - bool empty() const { return c.empty(); } - size_type size() const { return c.size(); } - value_type& front() { return c.front(); } - const value_type& front() const { return c.front(); } - value_type& back() { return c.back(); } - const value_type& back() const { return c.back(); } - void push(const value_type& x) { c.push_back(x); } - void pop() { c.pop_front(); } - }; + explicit queue(const Container& a = Container()) : c(a) { } + bool empty() const { return c.empty(); } + size_type size() const { return c.size(); } + value_type& front() { return c.front(); } + const value_type& front() const { return c.front(); } + value_type& back() { return c.back(); } + const value_type& back() const { return c.back(); } + void push(const value_type& x) { c.push_back(x); } + void pop() { c.pop_front(); } + }; - template _UCXXEXPORT bool - operator==(const queue& x, const queue& y) - { - return (x.c == y.c); - } - template _UCXXEXPORT bool - operator< (const queue& x, const queue& y) - { - return (x.c < y.c); - } - template _UCXXEXPORT bool - operator!=(const queue& x, const queue& y) - { - return (x.c != y.c); - } - template _UCXXEXPORT bool - operator> (const queue& x, const queue& y) - { - return (x.c > y.c); - } - template _UCXXEXPORT bool - operator>=(const queue& x, const queue& y) - { - return (x.c >= y.c); - } - template _UCXXEXPORT bool - operator<=(const queue& x, const queue& y) - { - return (x.c <= y.c); - } + template _UCXXEXPORT bool + operator==(const queue& x, const queue& y) + { + return (x.c == y.c); + } + template _UCXXEXPORT bool + operator< (const queue& x, const queue& y) + { + return (x.c < y.c); + } - template , - class Compare = less - > class _UCXXEXPORT priority_queue { - protected: - Container c; - Compare comp; - public: - typedef typename Container::value_type value_type; - typedef typename Container::size_type size_type; - typedef Container container_type; + template _UCXXEXPORT bool + operator!=(const queue& x, const queue& y) + { + return (x.c != y.c); + } - explicit priority_queue(const Compare& x = Compare(), const Container& a = Container()) - : c(a), comp(x) { make_heap(c.begin(), c.end(), comp) ; } - template priority_queue(InputIterator first, - InputIterator last, - const Compare& x = Compare(), - const Container& y= Container()) - : c(y), comp(c) - { - c.insert(c.end(), first, last); - make_heap(c.begin(), c.end(), comp); - } + template _UCXXEXPORT bool + operator> (const queue& x, const queue& y) + { + return (x.c > y.c); + } - bool empty() const { return c.empty(); } - size_type size() const { return c.size(); } - const value_type& top() const { return c.front(); } - void push(const value_type& x){ - c.push_back(x); - push_heap(c.begin(), c.end(), comp); - } - void pop(){ - pop_heap(c.begin(), c.end(), comp); - c.pop_back(); - } - }; + template _UCXXEXPORT bool + operator>=(const queue& x, const queue& y) + { + return (x.c >= y.c); + } -} + template _UCXXEXPORT bool + operator<=(const queue& x, const queue& y) + { + return (x.c <= y.c); + } + + template , + class Compare = less + > class _UCXXEXPORT priority_queue + { + protected: + Container c; + Compare comp; + + public: + typedef typename Container::value_type value_type; + typedef typename Container::size_type size_type; + typedef Container container_type; + + explicit priority_queue(const Compare& x = Compare(), const Container& a = Container()) + : c(a), comp(x) { make_heap(c.begin(), c.end(), comp) ; } + template priority_queue(InputIterator first, + InputIterator last, + const Compare& x = Compare(), + const Container& y= Container()) + : c(y), comp(c) + { + c.insert(c.end(), first, last); + make_heap(c.begin(), c.end(), comp); + } + + bool empty() const { return c.empty(); } + size_type size() const { return c.size(); } + const value_type& top() const { return c.front(); } + + void push(const value_type& x) + { + c.push_back(x); + push_heap(c.begin(), c.end(), comp); + } + + void pop() + { + pop_heap(c.begin(), c.end(), comp); + c.pop_back(); + } + }; + +} // namespace +} // extern "C++" #pragma GCC visibility pop #endif - - diff --git a/misc/uClibc++/include/uClibc++/set b/misc/uClibc++/include/uClibc++/set index f376e47008..02f9251ccc 100644 --- a/misc/uClibc++/include/uClibc++/set +++ b/misc/uClibc++/include/uClibc++/set @@ -1,22 +1,20 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - - +/* Copyright (C) 2004 Garrett A. Kajmowicz + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -30,13 +28,14 @@ #pragma GCC visibility push(default) -namespace std{ - +extern "C++" +{ +namespace std +{ template, class Allocator = allocator > class set; template, class Allocator = allocator > class multiset; - /* This is the implementation for the set container. As noted above, it deviates * from ISO spec by deriving from a base class in order to reduce code redundancy. * More code could be reduced by convirting to virtual functions (thus allowing @@ -44,361 +43,405 @@ template, class Allocator = allocator * the specifications too much to be worth the risk. */ - -//Implementation of set - +// Implementation of set template class _UCXXEXPORT set - : public __single_associative + : public __single_associative { - //Default value of allocator does not meet C++ standard specs, but it works for this library - //Deal with it + //Default value of allocator does not meet C++ standard specs, but it works for this library + //Deal with it + public: + typedef __single_associative base; + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; - typedef __single_associative base; - typedef typename base::key_type key_type; - typedef typename base::value_type value_type; - typedef typename base::key_compare key_compare; - typedef typename base::allocator_type allocator_type; - typedef typename base::reference reference; - typedef typename base::const_reference const_reference; - typedef typename base::iterator iterator; - typedef typename base::const_iterator const_iterator; - typedef typename base::size_type size_type; - typedef typename base::difference_type difference_type; - typedef typename base::pointer pointer; - typedef typename base::const_pointer const_pointer; - typedef typename base::reverse_iterator reverse_iterator; - typedef typename base::const_reverse_iterator const_reverse_iterator; +// using base::value_compare; -// using base::value_compare; + static const key_type v_t_k(const value_type v) + { + return v; + } - static const key_type v_t_k(const value_type v){ - return v; - } + explicit set(const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(comp, al, v_t_k) { } - explicit set(const Compare& comp = Compare(), const Allocator& al = Allocator()) - : base(comp, al, v_t_k) { } + template set(InputIterator first, InputIterator last, + const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(first, last, comp, al, v_t_k) { } - template set(InputIterator first, InputIterator last, - const Compare& comp = Compare(), const Allocator& al = Allocator()) - : base(first, last, comp, al, v_t_k) { } + set(const set& x) : base(x) { } + ~set() { } - set(const set& x) : base(x) { } - ~set() { } + using base::operator=; + using base::operator==; + using base::operator!=; - using base::operator=; - using base::operator==; - using base::operator!=; + using base::insert; + using base::erase; - using base::insert; - using base::erase; + using base::begin; + using base::end; + using base::rbegin; + using base::rend; - using base::begin; - using base::end; - using base::rbegin; - using base::rend; + using base::empty; + using base::size; + using base::max_size; - using base::empty; - using base::size; - using base::max_size; - - - using base::find; - using base::count; - using base::lower_bound; - using base::upper_bound; - using base::equal_range; + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; protected: - }; - -//Implementation of multiset - +// Implementation of multiset template class _UCXXEXPORT multiset - : public __multi_associative + : public __multi_associative { - //Default value of allocator does not meet C++ standard specs, but it works for this library - //Deal with it + //Default value of allocator does not meet C++ standard specs, but it works for this library + //Deal with it + public: + typedef __multi_associative base; + typedef typename base::key_type key_type; + typedef typename base::value_type value_type; + typedef typename base::key_compare key_compare; + typedef typename base::allocator_type allocator_type; + typedef typename base::reference reference; + typedef typename base::const_reference const_reference; + typedef typename base::iterator iterator; + typedef typename base::const_iterator const_iterator; + typedef typename base::size_type size_type; + typedef typename base::difference_type difference_type; + typedef typename base::pointer pointer; + typedef typename base::const_pointer const_pointer; + typedef typename base::reverse_iterator reverse_iterator; + typedef typename base::const_reverse_iterator const_reverse_iterator; - typedef __multi_associative base; - typedef typename base::key_type key_type; - typedef typename base::value_type value_type; - typedef typename base::key_compare key_compare; - typedef typename base::allocator_type allocator_type; - typedef typename base::reference reference; - typedef typename base::const_reference const_reference; - typedef typename base::iterator iterator; - typedef typename base::const_iterator const_iterator; - typedef typename base::size_type size_type; - typedef typename base::difference_type difference_type; - typedef typename base::pointer pointer; - typedef typename base::const_pointer const_pointer; - typedef typename base::reverse_iterator reverse_iterator; - typedef typename base::const_reverse_iterator const_reverse_iterator; + static const key_type v_t_k(const value_type v) + { + return v; + } - static const key_type v_t_k(const value_type v){ - return v; - } + explicit multiset(const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(comp, al, v_t_k) { } - explicit multiset(const Compare& comp = Compare(), const Allocator& al = Allocator()) - : base(comp, al, v_t_k) { } + template multiset(InputIterator first, InputIterator last, + const Compare& comp = Compare(), const Allocator& al = Allocator()) + : base(first, last, comp, al, v_t_k) { } - template multiset(InputIterator first, InputIterator last, - const Compare& comp = Compare(), const Allocator& al = Allocator()) - : base(first, last, comp, al, v_t_k) { } + multiset(const multiset& x) : base(x) { } + ~multiset() { } + using base::operator=; + using base::operator==; + using base::operator!=; - multiset(const multiset& x) : base(x) { } - ~multiset() { } + using base::insert; + using base::erase; - using base::operator=; - using base::operator==; - using base::operator!=; + using base::begin; + using base::end; + using base::rbegin; + using base::rend; - using base::insert; - using base::erase; - - using base::begin; - using base::end; - using base::rbegin; - using base::rend; - - using base::empty; - using base::size; - using base::max_size; - - using base::find; - using base::count; - using base::lower_bound; - using base::upper_bound; - using base::equal_range; + using base::empty; + using base::size; + using base::max_size; + using base::find; + using base::count; + using base::lower_bound; + using base::upper_bound; + using base::equal_range; protected: - }; - /* Non-member functions. These are at the end because they are not associated with any - particular class. These will be implemented as I figure out exactly what all of - them are supposed to do, and I have time. + * particular class. These will be implemented as I figure out exactly what all of + * them are supposed to do, and I have time. */ - template _UCXXEXPORT bool operator< - (const set& x, const set& y) - { - typename set::const_iterator first1 = x.begin(); - typename set::const_iterator first2 = y.begin(); - typename set::const_iterator last1 = x.end(); - typename set::const_iterator last2 = y.end(); + template _UCXXEXPORT bool operator< + (const set& x, const set& y) + { + typename set::const_iterator first1 = x.begin(); + typename set::const_iterator first2 = y.begin(); + typename set::const_iterator last1 = x.end(); + typename set::const_iterator last2 = y.end(); - while(first1 != last1 && first2 != last2){ - if( *first1 < *first2 ){ - return true; - } - if( *first2 < *first1 ){ - return false; - } - ++first1; - ++first2; - } - return first1==last1 && first2 != last2; - } + while (first1 != last1 && first2 != last2) + { + if (*first1 < *first2) + { + return true; + } - template _UCXXEXPORT bool operator> - (const set& x, const set& y) - { - typename set::const_iterator first1 = x.begin(); - typename set::const_iterator first2 = y.begin(); - typename set::const_iterator last1 = x.end(); - typename set::const_iterator last2 = y.end(); + if (*first2 < *first1) + { + return false; + } - while(first1 != last1 && first2 != last2){ - if( *first1 > *first2 ){ - return true; - } - if( *first2 > *first1 ){ - return false; - } - ++first1; - ++first2; - } - return first1!=last1 && first2 == last2; - } + ++first1; + ++first2; + } - template _UCXXEXPORT bool operator>= - (const set& x, const set& y) - { - typename set::const_iterator first1 = x.begin(); - typename set::const_iterator first2 = y.begin(); - typename set::const_iterator last1 = x.end(); - typename set::const_iterator last2 = y.end(); + return first1==last1 && first2 != last2; + } - while(first1 != last1 && first2 != last2){ - if( *first1 > *first2 ){ - return true; - } - if( *first2 > *first1 ){ - return false; - } - ++first1; - ++first2; - } - return first1!=last1; - } + template _UCXXEXPORT bool operator> + (const set& x, const set& y) + { + typename set::const_iterator first1 = x.begin(); + typename set::const_iterator first2 = y.begin(); + typename set::const_iterator last1 = x.end(); + typename set::const_iterator last2 = y.end(); - template _UCXXEXPORT bool operator<= - (const set& x, const set& y) - { - typename set::const_iterator first1 = x.begin(); - typename set::const_iterator first2 = y.begin(); - typename set::const_iterator last1 = x.end(); - typename set::const_iterator last2 = y.end(); + while (first1 != last1 && first2 != last2) + { + if (*first1 > *first2) + { + return true; + } - while(first1 != last1 && first2 != last2){ - if( *first1 < *first2 ){ - return true; - } - if( *first2 < *first1 ){ - return false; - } - ++first1; - ++first2; - } - return first2!=last2; - } - template _UCXXEXPORT void swap - (set& x, set& y) - { - x.swap(y); - } + if (*first2 > *first1) + { + return false; + } + ++first1; + ++first2; + } - template _UCXXEXPORT bool operator== - (const multiset& x, const multiset& y) - { - if(x.data == y.data){ - return true; - } - return false; - } + return first1!=last1 && first2 == last2; + } - template _UCXXEXPORT bool operator< - (const multiset& x, const multiset& y) - { - typename multiset::const_iterator first1 = x.begin(); - typename multiset::const_iterator first2 = y.begin(); - typename multiset::const_iterator last1 = x.end(); - typename multiset::const_iterator last2 = y.end(); + template _UCXXEXPORT bool operator>= + (const set& x, const set& y) + { + typename set::const_iterator first1 = x.begin(); + typename set::const_iterator first2 = y.begin(); + typename set::const_iterator last1 = x.end(); + typename set::const_iterator last2 = y.end(); - while(first1 != last1 && first2 != last2){ - if( *first1 < *first2 ){ - return true; - } - if( *first2 < *first1 ){ - return false; - } - ++first1; - ++first2; - } - return first1==last1 && first2 != last2; - } + while (first1 != last1 && first2 != last2) + { + if (*first1 > *first2) + { + return true; + } - template _UCXXEXPORT bool operator!= - (const multiset& x, const multiset& y) - { - typename multiset::const_iterator first1 = x.begin(); - typename multiset::const_iterator first2 = y.begin(); - typename multiset::const_iterator last1 = x.end(); - typename multiset::const_iterator last2 = y.end(); + if (*first2 > *first1) + { + return false; + } - while(first1 != last1 && first2 != last2){ - if( *first1 != *first2 ){ - return true; - } - ++first1; - ++first2; - } - return first1!=last1 || first2 != last2; - } + ++first1; + ++first2; + } + return first1!=last1; + } - template _UCXXEXPORT bool operator> - (const multiset& x, const multiset& y) - { - typename multiset::const_iterator first1 = x.begin(); - typename multiset::const_iterator first2 = y.begin(); - typename multiset::const_iterator last1 = x.end(); - typename multiset::const_iterator last2 = y.end(); + template _UCXXEXPORT bool operator<= + (const set& x, const set& y) + { + typename set::const_iterator first1 = x.begin(); + typename set::const_iterator first2 = y.begin(); + typename set::const_iterator last1 = x.end(); + typename set::const_iterator last2 = y.end(); - while(first1 != last1 && first2 != last2){ - if( *first1 > *first2 ){ - return true; - } - if( *first2 > *first1 ){ - return false; - } - ++first1; - ++first2; - } - return first1!=last1 && first2 == last2; - } + while (first1 != last1 && first2 != last2) + { + if (*first1 < *first2) + { + return true; + } - template _UCXXEXPORT bool operator>= - (const multiset& x, const multiset& y) - { - typename multiset::const_iterator first1 = x.begin(); - typename multiset::const_iterator first2 = y.begin(); - typename multiset::const_iterator last1 = x.end(); - typename multiset::const_iterator last2 = y.end(); + if (*first2 < *first1) + { + return false; + } - while(first1 != last1 && first2 != last2){ - if( *first1 > *first2 ){ - return true; - } - if( *first2 > *first1 ){ - return false; - } - ++first1; - ++first2; - } - return first1!=last1; - } + ++first1; + ++first2; + } - template _UCXXEXPORT bool operator<= - (const multiset& x, const multiset& y) - { - typename multiset::const_iterator first1 = x.begin(); - typename multiset::const_iterator first2 = y.begin(); - typename multiset::const_iterator last1 = x.end(); - typename multiset::const_iterator last2 = y.end(); + return first2!=last2; + } - while(first1 != last1 && first2 != last2){ - if( *first1 < *first2 ){ - return true; - } - if( *first2 < *first1 ){ - return false; - } - ++first1; - ++first2; - } - return first2!=last2; - } + template _UCXXEXPORT void swap + (set& x, set& y) + { + x.swap(y); + } - template _UCXXEXPORT void swap - (multiset& x, multiset& y) - { - x.swap(y); - } + template _UCXXEXPORT bool operator== + (const multiset& x, const multiset& y) + { + if (x.data == y.data) + { + return true; + } + return false; + } + template _UCXXEXPORT bool operator< + (const multiset& x, const multiset& y) + { + typename multiset::const_iterator first1 = x.begin(); + typename multiset::const_iterator first2 = y.begin(); + typename multiset::const_iterator last1 = x.end(); + typename multiset::const_iterator last2 = y.end(); -} + while (first1 != last1 && first2 != last2) + { + if (*first1 < *first2) + { + return true; + } + + if (*first2 < *first1) + { + return false; + } + + ++first1; + ++first2; + } + + return first1==last1 && first2 != last2; + } + + template _UCXXEXPORT bool operator!= + (const multiset& x, const multiset& y) + { + typename multiset::const_iterator first1 = x.begin(); + typename multiset::const_iterator first2 = y.begin(); + typename multiset::const_iterator last1 = x.end(); + typename multiset::const_iterator last2 = y.end(); + + while (first1 != last1 && first2 != last2) + { + if (*first1 != *first2) + { + return true; + } + + ++first1; + ++first2; + } + + return first1!=last1 || first2 != last2; + } + + template _UCXXEXPORT bool operator> + (const multiset& x, const multiset& y) + { + typename multiset::const_iterator first1 = x.begin(); + typename multiset::const_iterator first2 = y.begin(); + typename multiset::const_iterator last1 = x.end(); + typename multiset::const_iterator last2 = y.end(); + + while (first1 != last1 && first2 != last2) + { + if (*first1 > *first2) + { + return true; + } + + if (*first2 > *first1) + { + return false; + } + + ++first1; + ++first2; + } + + return first1!=last1 && first2 == last2; + } + + template _UCXXEXPORT bool operator>= + (const multiset& x, const multiset& y) + { + typename multiset::const_iterator first1 = x.begin(); + typename multiset::const_iterator first2 = y.begin(); + typename multiset::const_iterator last1 = x.end(); + typename multiset::const_iterator last2 = y.end(); + + while (first1 != last1 && first2 != last2) + { + if (*first1 > *first2) + { + return true; + } + + if (*first2 > *first1) + { + return false; + } + + ++first1; + ++first2; + } + + return first1!=last1; + } + + template _UCXXEXPORT bool operator<= + (const multiset& x, const multiset& y) + { + typename multiset::const_iterator first1 = x.begin(); + typename multiset::const_iterator first2 = y.begin(); + typename multiset::const_iterator last1 = x.end(); + typename multiset::const_iterator last2 = y.end(); + + while (first1 != last1 && first2 != last2) + { + if (*first1 < *first2) + { + return true; + } + + if (*first2 < *first1) + { + return false; + } + + ++first1; + ++first2; + } + + return first2!=last2; + } + + template _UCXXEXPORT void swap + (multiset& x, multiset& y) + { + x.swap(y); + } + +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/sstream b/misc/uClibc++/include/uClibc++/sstream index 296985374c..d06d1874f8 100644 --- a/misc/uClibc++/include/uClibc++/sstream +++ b/misc/uClibc++/include/uClibc++/sstream @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include @@ -31,345 +31,431 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ + template + class _UCXXEXPORT basic_stringbuf : public basic_streambuf + { + public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef typename Allocator::size_type size_type; - template - class _UCXXEXPORT basic_stringbuf : public basic_streambuf - { - public: - typedef charT char_type; - typedef typename traits::int_type int_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; - typedef typename Allocator::size_type size_type; + explicit _UCXXEXPORT basic_stringbuf(ios_base::openmode which = ios_base::in | ios_base::out) + : data(), ielement(0), oelement(0) + { + basic_streambuf::openedFor = which; + } - explicit _UCXXEXPORT basic_stringbuf(ios_base::openmode which = ios_base::in | ios_base::out) - : data(), ielement(0), oelement(0) - { - basic_streambuf::openedFor = which; - } + explicit _UCXXEXPORT basic_stringbuf(const basic_string& str, + ios_base::openmode which = ios_base::in | ios_base::out) + : data(str), ielement(0), oelement(0) + { + if (which & ios_base::ate) + { + oelement = data.length(); + } - explicit _UCXXEXPORT basic_stringbuf(const basic_string& str, - ios_base::openmode which = ios_base::in | ios_base::out) - : data(str), ielement(0), oelement(0) - { - if(which & ios_base::ate){ - oelement = data.length(); - } - basic_streambuf::openedFor = which; - } + basic_streambuf::openedFor = which; + } - virtual _UCXXEXPORT ~basic_stringbuf() { } + virtual _UCXXEXPORT ~basic_stringbuf() { } - _UCXXEXPORT basic_string str() const{ - return data; - } + _UCXXEXPORT basic_string str() const + { + return data; + } - _UCXXEXPORT void str(const basic_string& s){ - data = s; - ielement = 0; - if(basic_streambuf::openedFor & ios_base::ate){ - oelement = data.length(); - }else{ - oelement = 0; - } - } + _UCXXEXPORT void str(const basic_string& s) + { + data = s; + ielement = 0; + if (basic_streambuf::openedFor & ios_base::ate) + { + oelement = data.length(); + } + else + { + oelement = 0; + } + } - protected: - virtual _UCXXEXPORT int sync(){ - return 0; - } - virtual _UCXXEXPORT int_type underflow(){ - if(ielement >= data.length()){ - return traits::eof(); - } - return traits::to_int_type(data[ielement]); - } + protected: + virtual _UCXXEXPORT int sync() + { + return 0; + } - virtual _UCXXEXPORT int_type uflow(){ - int_type retval = underflow(); - if(retval != traits::eof()){ - ++ielement; - } - return retval; - } + virtual _UCXXEXPORT int_type underflow() + { + if (ielement >= data.length()) + { + return traits::eof(); + } - virtual _UCXXEXPORT int_type pbackfail(int_type c = traits::eof()){ - //Error possibilities - if(ielement == 0){ - return traits::eof(); - } - if(ielement > data.length()){ - ielement = data.length(); - return traits::eof(); - } - //eof passed in - if(traits::eq_int_type(c,traits::eof())==true){ - --ielement; - return traits::not_eof(c); - } - if(traits::eq(traits::to_char_type(c),data[ielement-1]) == true){ - --ielement; - return c; - } - if(basic_streambuf::openedFor & ios_base::out){ - --ielement; - data[ielement] = c; - return c; - } - return traits::eof(); - } + return traits::to_int_type(data[ielement]); + } - virtual _UCXXEXPORT int showmanyc(){ - return data.length() - ielement; - } - virtual _UCXXEXPORT streamsize xsgetn(char_type* c, streamsize n){ - streamsize i = 0; - while(ielement < data.length() && i < n ){ - c[i] = data[ielement]; - ++i; - ++ielement; - } - return i; - } + virtual _UCXXEXPORT int_type uflow() + { + int_type retval = underflow(); + if (retval != traits::eof()) + { + ++ielement; + } - virtual _UCXXEXPORT int_type overflow (int_type c = traits::eof()){ - //Nothing to do - if(traits::eq_int_type(c,traits::eof())){ - return traits::not_eof(c); - } + return retval; + } - //Actually add character, if possible - if(basic_streambuf::openedFor & ios_base::out){ - if(oelement >= data.length()){ - data.push_back(c); - }else{ - data[oelement] = c; - } - ++oelement; - return c; - } - //Not possible - return traits::eof(); - } + virtual _UCXXEXPORT int_type pbackfail(int_type c = traits::eof()) + { + // Error possibilities - virtual _UCXXEXPORT basic_streambuf* setbuf(charT*, streamsize){ - //This function does nothing - return this; - } + if (ielement == 0) + { + return traits::eof(); + } - virtual _UCXXEXPORT streamsize xsputn(const char_type* s, streamsize n){ - data.replace(oelement, n, s, n); - oelement += n; - return n; - } + if (ielement > data.length()) + { + ielement = data.length(); + return traits::eof(); + } - virtual _UCXXEXPORT pos_type seekoff(off_type off, ios_base::seekdir way, - ios_base::openmode which = ios_base::in | ios_base::out) - { - //Test for invalid option - if( (which & ios_base::in) && (which & ios_base::out) && (way == ios_base::cur)){ - return -1; - } + // eof passed in - //Calculate new location - size_type newpos = 0; + if (traits::eq_int_type(c,traits::eof())==true) + { + --ielement; + return traits::not_eof(c); + } - if(way == ios_base::beg){ - newpos = off; - }else if(way == ios_base::cur){ - if(which & ios_base::out){ - newpos = data.length() + off; - } - if(which & ios_base::in){ - newpos = ielement + off; - } - - }else{ - newpos = data.length() + off; - } + if (traits::eq(traits::to_char_type(c),data[ielement-1]) == true) + { + --ielement; + return c; + } - //Test for error conditions - if(newpos > data.length()){ - return -1; - } + if (basic_streambuf::openedFor & ios_base::out) + { + --ielement; + data[ielement] = c; + return c; + } - //Shuffle pointers + return traits::eof(); + } - if(which & ios_base::in){ - ielement = newpos; - } - if(which & ios_base::out){ - data.resize(newpos); - if(ielement > data.length()){ - ielement = data.length(); - } - } + virtual _UCXXEXPORT int showmanyc() + { + return data.length() - ielement; + } - return newpos; - } - - virtual _UCXXEXPORT pos_type seekpos(pos_type sp, - ios_base::openmode which = ios_base::in | ios_base::out) - { - return seekoff(sp, ios_base::beg, which); - } + virtual _UCXXEXPORT streamsize xsgetn(char_type* c, streamsize n) + { + streamsize i = 0; + while (ielement < data.length() && i < n) + { + c[i] = data[ielement]; + ++i; + ++ielement; + } - basic_string data; - size_type ielement; - size_type oelement; - }; + return i; + } + + virtual _UCXXEXPORT int_type overflow (int_type c = traits::eof()) + { + // Nothing to do + + if (traits::eq_int_type(c,traits::eof())) + { + return traits::not_eof(c); + } + + // Actually add character, if possible + + if (basic_streambuf::openedFor & ios_base::out) + { + if (oelement >= data.length()) + { + data.push_back(c); + } + else + { + data[oelement] = c; + } + + ++oelement; + return c; + } + + // Not possible + + return traits::eof(); + } + + virtual _UCXXEXPORT basic_streambuf* setbuf(charT*, streamsize) + { + //This function does nothing + + return this; + } + + virtual _UCXXEXPORT streamsize xsputn(const char_type* s, streamsize n) + { + data.replace(oelement, n, s, n); + oelement += n; + return n; + } + + virtual _UCXXEXPORT pos_type seekoff(off_type off, ios_base::seekdir way, + ios_base::openmode which = ios_base::in | ios_base::out) + { + // Test for invalid option + + if ((which & ios_base::in) && (which & ios_base::out) && (way == ios_base::cur)) + { + return -1; + } + + // Calculate new location + + size_type newpos = 0; + + if (way == ios_base::beg) + { + newpos = off; + } + else if (way == ios_base::cur) + { + if (which & ios_base::out) + { + newpos = data.length() + off; + } + + if (which & ios_base::in) + { + newpos = ielement + off; + } + } + else + { + newpos = data.length() + off; + } + + // Test for error conditions + + if (newpos > data.length()) + { + return -1; + } + + // Shuffle pointers - template class _UCXXEXPORT basic_istringstream - : public basic_istream - { - public: - typedef charT char_type; - typedef typename traits::int_type int_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; + if (which & ios_base::in) + { + ielement = newpos; + } + + if (which & ios_base::out) + { + data.resize(newpos); + if (ielement > data.length()) + { + ielement = data.length(); + } + } + + return newpos; + } + + virtual _UCXXEXPORT pos_type seekpos(pos_type sp, + ios_base::openmode which = ios_base::in | ios_base::out) + { + return seekoff(sp, ios_base::beg, which); + } + + basic_string data; + size_type ielement; + size_type oelement; + }; + + template class _UCXXEXPORT basic_istringstream + : public basic_istream + { + public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + explicit _UCXXEXPORT basic_istringstream(ios_base::openmode m = ios_base::in) + : basic_ios(&sb), basic_istream(&sb), sb(m) + { + } + + explicit _UCXXEXPORT basic_istringstream(const basic_string& str, + ios_base::openmode which = ios_base::in) + : basic_ios(&sb), basic_istream(&sb), sb(str, which) + { + } + + virtual _UCXXEXPORT ~basic_istringstream() { } + + _UCXXEXPORT basic_stringbuf* rdbuf() const + { + return &sb; + } + + _UCXXEXPORT basic_string str() const + { + return sb.str(); + } + + _UCXXEXPORT void str(const basic_string& s){ + sb.str(s); + basic_istream::clear(); + } + + private: + basic_stringbuf sb; + }; + + template class _UCXXEXPORT basic_ostringstream + : public basic_ostream + { + public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + + explicit _UCXXEXPORT basic_ostringstream(ios_base::openmode m = ios_base::out) + : basic_ios(&sb), basic_ostream(&sb), sb(m) + { + } + + explicit _UCXXEXPORT basic_ostringstream(const basic_string& str, + ios_base::openmode which = ios_base::out) + : basic_ios(&sb), basic_ostream(&sb), sb(str, which) + { + } + + virtual _UCXXEXPORT ~basic_ostringstream() { } + + _UCXXEXPORT basic_stringbuf* rdbuf() const + { + return &sb; + } + + _UCXXEXPORT basic_string str() const + { + return sb.str(); + } + + _UCXXEXPORT void str(const basic_string& s) + { + sb.str(s); + basic_ostream::clear(); + } + + private: + basic_stringbuf sb; + }; - explicit _UCXXEXPORT basic_istringstream(ios_base::openmode m = ios_base::in) - : basic_ios(&sb), basic_istream(&sb), sb(m) - { - } - explicit _UCXXEXPORT basic_istringstream( const basic_string& str, - ios_base::openmode which = ios_base::in) - : basic_ios(&sb), basic_istream(&sb), sb(str, which) - { - } - virtual _UCXXEXPORT ~basic_istringstream() { } - _UCXXEXPORT basic_stringbuf* rdbuf() const{ - return &sb; - } - _UCXXEXPORT basic_string str() const{ - return sb.str(); - } - _UCXXEXPORT void str(const basic_string& s){ - sb.str(s); - basic_istream::clear(); - } - private: - basic_stringbuf sb; - }; + template class _UCXXEXPORT basic_stringstream + : public basic_iostream + { + public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + explicit _UCXXEXPORT basic_stringstream(ios_base::openmode which = ios_base::out|ios_base::in) + : basic_ios(&sb), basic_iostream(&sb), sb(which) + { + } - template class _UCXXEXPORT basic_ostringstream - : public basic_ostream - { - public: + explicit _UCXXEXPORT basic_stringstream(const basic_string& str, + ios_base::openmode which = ios_base::out|ios_base::in) + : basic_ios(&sb), basic_iostream(&sb), sb(str, which) + { + } - typedef charT char_type; - typedef typename traits::int_type int_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; + virtual _UCXXEXPORT ~basic_stringstream(){ } - explicit _UCXXEXPORT basic_ostringstream(ios_base::openmode m = ios_base::out) - : basic_ios(&sb), basic_ostream(&sb), sb(m) - { - } - explicit _UCXXEXPORT basic_ostringstream(const basic_string& str, - ios_base::openmode which = ios_base::out) - : basic_ios(&sb), basic_ostream(&sb), sb(str, which) - { - } - virtual _UCXXEXPORT ~basic_ostringstream() { } + _UCXXEXPORT basic_stringbuf* rdbuf() + { + return &sb; + } - _UCXXEXPORT basic_stringbuf* rdbuf() const{ - return &sb; - } - _UCXXEXPORT basic_string str() const{ - return sb.str(); - } - _UCXXEXPORT void str(const basic_string& s){ - sb.str(s); - basic_ostream::clear(); - } - private: - basic_stringbuf sb; - }; + _UCXXEXPORT basic_string str() const + { + return sb.str(); + } + _UCXXEXPORT void str(const basic_string& s) + { + sb.str(s); + basic_iostream::clear(); + } - template class _UCXXEXPORT basic_stringstream - : public basic_iostream - { - public: - - typedef charT char_type; - typedef typename traits::int_type int_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; - - explicit _UCXXEXPORT basic_stringstream(ios_base::openmode which = ios_base::out|ios_base::in) - : basic_ios(&sb), basic_iostream(&sb), sb(which) - { - } - - explicit _UCXXEXPORT basic_stringstream(const basic_string& str, - ios_base::openmode which = ios_base::out|ios_base::in) - : basic_ios(&sb), basic_iostream(&sb), sb(str, which) - { - } - virtual _UCXXEXPORT ~basic_stringstream(){ } - - _UCXXEXPORT basic_stringbuf* rdbuf(){ - return &sb; - } - _UCXXEXPORT basic_string str() const{ - return sb.str(); - } - _UCXXEXPORT void str(const basic_string& s){ - sb.str(s); - basic_iostream::clear(); - } - private: - basic_stringbuf sb; - }; + private: + basic_stringbuf sb; + }; #ifdef __UCLIBCXX_EXPAND_SSTREAM_CHAR__ #ifndef __UCLIBCXX_COMPILE_SSTREAM__ #ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template <> _UCXXEXPORT basic_stringbuf, allocator >:: - basic_stringbuf(ios_base::openmode which); - template <> _UCXXEXPORT basic_stringbuf, allocator >::~basic_stringbuf(); + template <> _UCXXEXPORT basic_stringbuf, allocator >:: + basic_stringbuf(ios_base::openmode which); + template <> _UCXXEXPORT basic_stringbuf, allocator >::~basic_stringbuf(); #endif // __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template <> _UCXXEXPORT basic_string, allocator > - basic_stringbuf, allocator >::str() const; + template <> _UCXXEXPORT basic_string, allocator > + basic_stringbuf, allocator >::str() const; - template <> _UCXXEXPORT basic_stringbuf, allocator >::int_type - basic_stringbuf, allocator >:: - pbackfail(basic_stringbuf, allocator >::int_type c); + template <> _UCXXEXPORT basic_stringbuf, allocator >::int_type + basic_stringbuf, allocator >:: + pbackfail(basic_stringbuf, allocator >::int_type c); - template <> _UCXXEXPORT basic_stringbuf, allocator >::pos_type - basic_stringbuf, allocator >:: - seekoff (basic_stringbuf, allocator >::off_type off, - ios_base::seekdir way, - ios_base::openmode which - ); + template <> _UCXXEXPORT basic_stringbuf, allocator >::pos_type + basic_stringbuf, allocator >:: + seekoff (basic_stringbuf, allocator >::off_type off, + ios_base::seekdir way, + ios_base::openmode which); - template <> _UCXXEXPORT basic_stringbuf, allocator >::int_type - basic_stringbuf, allocator >:: - overflow (basic_stringbuf, allocator >::int_type c); + template <> _UCXXEXPORT basic_stringbuf, allocator >::int_type + basic_stringbuf, allocator >:: + overflow (basic_stringbuf, allocator >::int_type c); - template <> _UCXXEXPORT basic_stringbuf, allocator >::int_type - basic_stringbuf, allocator >::underflow (); + template <> _UCXXEXPORT basic_stringbuf, allocator >::int_type + basic_stringbuf, allocator >::underflow (); - template <> _UCXXEXPORT streamsize basic_stringbuf, allocator >:: - xsputn(const char* s, streamsize n); + template <> _UCXXEXPORT streamsize basic_stringbuf, allocator >:: + xsputn(const char* s, streamsize n); #ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template <> _UCXXEXPORT basic_stringstream, allocator >:: - basic_stringstream(ios_base::openmode which); - template <> _UCXXEXPORT basic_stringstream, allocator >::~basic_stringstream(); - template <> _UCXXEXPORT basic_istringstream, allocator >::~basic_istringstream(); - template <> _UCXXEXPORT basic_ostringstream, allocator >::~basic_ostringstream(); + template <> _UCXXEXPORT basic_stringstream, allocator >:: + basic_stringstream(ios_base::openmode which); + + template <> _UCXXEXPORT basic_stringstream, allocator >::~basic_stringstream(); + + template <> _UCXXEXPORT basic_istringstream, allocator >::~basic_istringstream(); + + template <> _UCXXEXPORT basic_ostringstream, allocator >::~basic_ostringstream(); #endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ @@ -378,7 +464,7 @@ namespace std{ #pragma GCC visibility pop -} - +} // namespace +} // extern "C++" #endif diff --git a/misc/uClibc++/include/uClibc++/stack b/misc/uClibc++/include/uClibc++/stack index d4861b3a42..2321831ba4 100644 --- a/misc/uClibc++/include/uClibc++/stack +++ b/misc/uClibc++/include/uClibc++/stack @@ -1,19 +1,20 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -23,59 +24,66 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ + template > class _UCXXEXPORT stack + { + protected: + Container c; - template > class _UCXXEXPORT stack{ - protected: - Container c; + public: + typedef typename Container::value_type value_type; + typedef typename Container::size_type size_type; + typedef Container container_type; - public: - typedef typename Container::value_type value_type; - typedef typename Container::size_type size_type; - typedef Container container_type; + explicit stack(const Container& a = Container()) : c(a) { }; + bool empty() const { return c.empty(); } + size_type size() const { return c.size(); } + value_type& top() { return c.back(); } + const value_type& top() const { return c.back(); } + void push(const value_type& x) { c.push_back(x); } + void pop() { c.pop_back(); } - explicit stack(const Container& a = Container()) : c(a) { }; - bool empty() const { return c.empty(); } - size_type size() const { return c.size(); } - value_type& top() { return c.back(); } - const value_type& top() const { return c.back(); } - void push(const value_type& x) { c.push_back(x); } - void pop() { c.pop_back(); } + bool operator==(const stack &x) const + { + return x.c == c; + } + }; - bool operator==(const stack &x) const{ - return x.c == c; - } + template _UCXXEXPORT bool + operator< (const stack& x, const stack& y) + { + return (x.c < y.c); + } - }; + template _UCXXEXPORT bool + operator!=(const stack& x, const stack& y) + { + return (x.c != y.c); + } + template _UCXXEXPORT bool + operator> (const stack& x, const stack& y) + { + return (x.c > y.c); + } - template _UCXXEXPORT bool - operator< (const stack& x, const stack& y) - { - return (x.c < y.c); - } - template _UCXXEXPORT bool - operator!=(const stack& x, const stack& y) - { - return (x.c != y.c); - } - template _UCXXEXPORT bool - operator> (const stack& x, const stack& y) - { - return (x.c > y.c); - } - template _UCXXEXPORT bool - operator>=(const stack& x, const stack& y) - { - return (x.c >= y.c); - } - template _UCXXEXPORT bool - operator<=(const stack& x, const stack& y) - { - return (x.c <= y.c); - } + template _UCXXEXPORT bool + operator>=(const stack& x, const stack& y) + { + return (x.c >= y.c); + } -} + template _UCXXEXPORT bool + operator<=(const stack& x, const stack& y) + { + return (x.c <= y.c); + } + +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/streambuf b/misc/uClibc++/include/uClibc++/streambuf index 0daa388f06..2dfa213d0c 100644 --- a/misc/uClibc++/include/uClibc++/streambuf +++ b/misc/uClibc++/include/uClibc++/streambuf @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -29,300 +29,379 @@ #pragma GCC visibility push(default) -namespace std{ - - template class _UCXXEXPORT basic_streambuf{ - public: +extern "C++" +{ +namespace std +{ + template class _UCXXEXPORT basic_streambuf{ + public: #ifdef __UCLIBCXX_SUPPORT_CDIR__ - friend ios_base::Init::Init(); + friend ios_base::Init::Init(); #endif - // Types: - typedef charT char_type; - typedef typename traits::int_type int_type; - typedef typename traits::pos_type pos_type; - typedef typename traits::off_type off_type; - typedef traits traits_type; + // Types: - virtual ~basic_streambuf(); + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef traits traits_type; - locale pubimbue(const locale &loc); + virtual ~basic_streambuf(); - locale getloc() const{ - return myLocale; - } + locale pubimbue(const locale &loc); - basic_streambuf* pubsetbuf(char_type* s, streamsize n){ - return setbuf(s,n); - } - pos_type pubseekoff(off_type off, - typename ios_base::seekdir way, - ios_base::openmode which = ios_base::in | - ios_base::out - ) - { - return seekoff(off,way,which); - } - pos_type pubseekpos(pos_type sp, ios_base::openmode which = ios_base::in | ios_base::out){ - return seekpos(sp,which); - } - int pubsync(){ - return sync(); - } + locale getloc() const + { + return myLocale; + } - streamsize in_avail(); + basic_streambuf* pubsetbuf(char_type* s, streamsize n) + { + return setbuf(s,n); + } - int_type snextc(); + pos_type pubseekoff(off_type off, + typename ios_base::seekdir way, + ios_base::openmode which = ios_base::in | + ios_base::out) + { + return seekoff(off,way,which); + } - int_type sbumpc(); + pos_type pubseekpos(pos_type sp, ios_base::openmode which = ios_base::in | ios_base::out) + { + return seekpos(sp,which); + } - int_type sgetc(); + int pubsync() + { + return sync(); + } - streamsize sgetn(char_type* s, streamsize n){ - return xsgetn(s,n); - } + streamsize in_avail(); - int_type sputbackc(char_type c); + int_type snextc(); - int_type sungetc(); + int_type sbumpc(); - int_type sputc(char_type c); + int_type sgetc(); - streamsize sputn(const char_type* s, streamsize n){ - if(openedFor & ios_base::app){ - seekoff(0, ios_base::end, ios_base::out); - } - return xsputn(s, n); - } + streamsize sgetn(char_type* s, streamsize n) + { + return xsgetn(s,n); + } - protected: - locale myLocale; - //Pointers for the "get" buffers - charT * mgbeg; - charT * mgnext; - charT * mgend; + int_type sputbackc(char_type c); - //Pointers for the "put" buffers - charT * mpbeg; - charT * mpnext; - charT * mpend; + int_type sungetc(); - //In the event of null buffers Lets us know what the buffer is opened for - ios_base::openmode openedFor; - - basic_streambuf(); + int_type sputc(char_type c); - basic_streambuf(const basic_streambuf > &) - : myLocale(), - mgbeg(0), mgnext(0), mgend(0), mpbeg(0), mpnext(0), mpend(0), - openedFor(0) - { } - basic_streambuf > & operator=(const basic_streambuf > &){ - return *this; - } - - char_type* eback() const{ - return mgbeg; - } - char_type* gptr() const{ - return mgnext; - } - char_type* egptr() const{ - return mgend; - } - void gbump(int n){ - mgnext+=n; - } - void setg(char_type* gbeg, char_type* gnext, char_type* gend){ - mgbeg = gbeg; - mgnext = gnext; - mgend = gend; - } + streamsize sputn(const char_type* s, streamsize n) + { + if (openedFor & ios_base::app) + { + seekoff(0, ios_base::end, ios_base::out); + } - char_type* pbase() const{ - return mpbeg; - } - char_type* pptr() const{ - return mpnext; - } - char_type* epptr() const{ - return mpend; - } - void pbump(int n){ - mpnext+=n; - } - void setp(char_type* pbeg, char_type* pend){ - mpbeg = pbeg; - mpnext = pbeg; - mpend = pend; - } + return xsputn(s, n); + } - virtual void imbue(const locale &loc){ - myLocale = loc; - } + protected: + locale myLocale; - //Virtual functions which we will not implement + // Pointers for the "get" buffers - virtual basic_streambuf* setbuf(char_type* , streamsize){ - return 0; - } - virtual pos_type seekoff(off_type , ios_base::seekdir, - ios_base::openmode = ios_base::in | ios_base::out) - { - return 0; - } - virtual pos_type seekpos(pos_type , ios_base::openmode = ios_base::in | ios_base::out){ - return 0; - } - virtual int sync(){ - return 0; - } + charT * mgbeg; + charT * mgnext; + charT * mgend; - virtual int showmanyc(){ - return 0; - } - virtual streamsize xsgetn(char_type* , streamsize ){ - return 0; - } - virtual int_type underflow(){ - return traits_type::eof(); - } - virtual int_type uflow(){ - int_type ret = underflow(); - if (!traits_type::eq_int_type(ret, traits_type::eof())) - gbump(1); - return ret; - } + // Pointers for the "put" buffers - virtual int_type pbackfail(int_type c = traits::eof()){ - return c; - } - virtual streamsize xsputn(const char_type* c, streamsize n){ - //This function is designed to be replaced by subclasses - for(streamsize i = 0; i< n; ++i){ - if(sputc(c[i]) == traits::eof()){ - return i; - } - } - return n; - } - virtual int_type overflow (int_type c = traits::eof()){ - return c; - } - }; + charT * mpbeg; + charT * mpnext; + charT * mpend; - typedef basic_streambuf streambuf; + // In the event of null buffers Lets us know what the buffer is opened for + + ios_base::openmode openedFor; + + basic_streambuf(); + + basic_streambuf(const basic_streambuf > &) + : myLocale(), + mgbeg(0), mgnext(0), mgend(0), mpbeg(0), mpnext(0), mpend(0), + openedFor(0) + { } + + basic_streambuf > & operator=(const basic_streambuf > &) + { + return *this; + } + + char_type* eback() const + { + return mgbeg; + } + + char_type* gptr() const + { + return mgnext; + } + char_type* egptr() const + { + return mgend; + } + + void gbump(int n) + { + mgnext+=n; + } + + void setg(char_type* gbeg, char_type* gnext, char_type* gend) + { + mgbeg = gbeg; + mgnext = gnext; + mgend = gend; + } + + char_type* pbase() const + { + return mpbeg; + } + + char_type* pptr() const + { + return mpnext; + } + + char_type* epptr() const + { + return mpend; + } + + void pbump(int n) + { + mpnext+=n; + } + + void setp(char_type* pbeg, char_type* pend) + { + mpbeg = pbeg; + mpnext = pbeg; + mpend = pend; + } + + virtual void imbue(const locale &loc) + { + myLocale = loc; + } + + // Virtual functions which we will not implement + + virtual basic_streambuf* setbuf(char_type* , streamsize) + { + return 0; + } + + virtual pos_type seekoff(off_type , ios_base::seekdir, + ios_base::openmode = ios_base::in | ios_base::out) + { + return 0; + } + + virtual pos_type seekpos(pos_type , ios_base::openmode = ios_base::in | ios_base::out) + { + return 0; + } + + virtual int sync() + { + return 0; + } + + virtual int showmanyc() + { + return 0; + } + + virtual streamsize xsgetn(char_type* , streamsize) + { + return 0; + } + + virtual int_type underflow() + { + return traits_type::eof(); + } + + virtual int_type uflow() + { + int_type ret = underflow(); + if (!traits_type::eq_int_type(ret, traits_type::eof())) + { + gbump(1); + } + + return ret; + } + + virtual int_type pbackfail(int_type c = traits::eof()) + { + return c; + } + + virtual streamsize xsputn(const char_type* c, streamsize n) + { + // This function is designed to be replaced by subclasses + + for (streamsize i = 0; i< n; ++i) + { + if (sputc(c[i]) == traits::eof()) + { + return i; + } + } + + return n; + } + + virtual int_type overflow (int_type c = traits::eof()) + { + return c; + } + }; + + typedef basic_streambuf streambuf; #ifdef __UCLIBCXX_HAS_WCHAR__ - typedef basic_streambuf wstreambuf; + typedef basic_streambuf wstreambuf; #endif +// Definitions put below to allow for easy expansion of code -//Definitions put below to allow for easy expansion of code + template basic_streambuf::~basic_streambuf(){ } - template basic_streambuf::~basic_streambuf(){ } + template locale basic_streambuf::pubimbue(const locale &loc) + { + locale temp = myLocale; + myLocale = loc; + return temp; + } - template locale basic_streambuf::pubimbue(const locale &loc){ - locale temp = myLocale; - myLocale = loc; - return temp; - } + template streamsize basic_streambuf::in_avail() + { + if (mgend !=0 && mgnext !=0) + { + return mgend - mgnext; + } - template streamsize basic_streambuf::in_avail(){ - if(mgend !=0 && mgnext !=0){ - return mgend - mgnext; - } - return showmanyc(); - } + return showmanyc(); + } - template typename basic_streambuf::int_type basic_streambuf::sbumpc(){ - if(mgbeg == 0 || mgnext == mgend){ - return uflow(); - } - int_type retval = T::to_int_type(*gptr()); - gbump(1); - return retval; - } + template typename basic_streambuf::int_type basic_streambuf::sbumpc() + { + if (mgbeg == 0 || mgnext == mgend) + { + return uflow(); + } - template typename basic_streambuf::int_type basic_streambuf::snextc(){ - if(sbumpc() == T::eof() ){ - return T::eof() ; - } - return sgetc(); - } + int_type retval = T::to_int_type(*gptr()); + gbump(1); + return retval; + } - template typename basic_streambuf::int_type basic_streambuf::sgetc(){ - if(mgbeg == 0 || mgnext == mgend){ - return underflow(); - } - return T::to_int_type(*gptr()); - } + template typename basic_streambuf::int_type basic_streambuf::snextc() + { + if (sbumpc() == T::eof()) + { + return T::eof() ; + } - template typename basic_streambuf::int_type basic_streambuf::sputbackc(char_type c){ - if(mgbeg == 0 || mgnext == mgbeg || !T::eq(c, gptr()[-1] )){ - return pbackfail(T::to_int_type(c)); - } - gbump(-1); - return T::to_int_type(*gptr()); - } + return sgetc(); + } - template typename basic_streambuf::int_type basic_streambuf::sungetc(){ - if(mgbeg == 0 || mgnext == mgbeg){ - return ios_base::failbit; - } - gbump(-1); - return T::to_int_type(*gptr()); - } + template typename basic_streambuf::int_type basic_streambuf::sgetc() + { + if (mgbeg == 0 || mgnext == mgend) + { + return underflow(); + } - template typename basic_streambuf::int_type basic_streambuf::sputc(char_type c){ - if(openedFor & ios_base::app){ - seekoff(0, ios_base::end, ios_base::out); - } - if(mpnext < mpend){ - *mpnext = c; - ++mpnext; - }else{ - return overflow( T::to_int_type(c) ); - } - return T::to_int_type(c); - } + return T::to_int_type(*gptr()); + } - template basic_streambuf::basic_streambuf() - : myLocale(), - mgbeg(0), mgnext(0), mgend(0), mpbeg(0), mpnext(0), mpend(0), - openedFor(0) - { } + template typename basic_streambuf::int_type basic_streambuf::sputbackc(char_type c) + { + if (mgbeg == 0 || mgnext == mgbeg || !T::eq(c, gptr()[-1])) + { + return pbackfail(T::to_int_type(c)); + } + gbump(-1); + return T::to_int_type(*gptr()); + } + template typename basic_streambuf::int_type basic_streambuf::sungetc() + { + if (mgbeg == 0 || mgnext == mgbeg) + { + return ios_base::failbit; + } + gbump(-1); + return T::to_int_type(*gptr()); + } + template typename basic_streambuf::int_type basic_streambuf::sputc(char_type c) + { + if (openedFor & ios_base::app) + { + seekoff(0, ios_base::end, ios_base::out); + } + if (mpnext < mpend) + { + *mpnext = c; + ++mpnext; + } + else + { + return overflow(T::to_int_type(c)); + } + + return T::to_int_type(c); + } + + template basic_streambuf::basic_streambuf() + : myLocale(), + mgbeg(0), mgnext(0), mgend(0), mpbeg(0), mpnext(0), mpend(0), + openedFor(0) + { } #ifdef __UCLIBCXX_EXPAND_STREAMBUF_CHAR__ #ifndef __UCLIBCXX_COMPILE_STREAMBUF__ #ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template <> _UCXXEXPORT streambuf::basic_streambuf(); - template <> _UCXXEXPORT streambuf::~basic_streambuf(); + template <> _UCXXEXPORT streambuf::basic_streambuf(); + template <> _UCXXEXPORT streambuf::~basic_streambuf(); #endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template <> _UCXXEXPORT locale streambuf::pubimbue(const locale &loc); - template <> _UCXXEXPORT streamsize streambuf::in_avail(); - template <> _UCXXEXPORT streambuf::int_type streambuf::sbumpc(); - template <> _UCXXEXPORT streambuf::int_type streambuf::snextc(); - template <> _UCXXEXPORT streambuf::int_type streambuf::sgetc(); - template <> _UCXXEXPORT streambuf::int_type streambuf::sputbackc(char_type c); - template <> _UCXXEXPORT streambuf::int_type streambuf::sungetc(); - template <> _UCXXEXPORT streambuf::int_type streambuf::sputc(char_type c); + template <> _UCXXEXPORT locale streambuf::pubimbue(const locale &loc); + template <> _UCXXEXPORT streamsize streambuf::in_avail(); + template <> _UCXXEXPORT streambuf::int_type streambuf::sbumpc(); + template <> _UCXXEXPORT streambuf::int_type streambuf::snextc(); + template <> _UCXXEXPORT streambuf::int_type streambuf::sgetc(); + template <> _UCXXEXPORT streambuf::int_type streambuf::sputbackc(char_type c); + template <> _UCXXEXPORT streambuf::int_type streambuf::sungetc(); + template <> _UCXXEXPORT streambuf::int_type streambuf::sputc(char_type c); #endif #endif - - - - -} +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/string b/misc/uClibc++/include/uClibc++/string index f128e7e5ad..47c2a9d517 100644 --- a/misc/uClibc++/include/uClibc++/string +++ b/misc/uClibc++/include/uClibc++/string @@ -35,6 +35,8 @@ #pragma GCC visibility push(default) +extern "C++" +{ namespace std { // Basic basic_string @@ -1331,7 +1333,9 @@ template <> _UCXXEXPORT bool operator< (const string & lhs, const string & rhs); #endif #endif + } // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/string_iostream b/misc/uClibc++/include/uClibc++/string_iostream index 4ef3b600c5..46a9893c17 100644 --- a/misc/uClibc++/include/uClibc++/string_iostream +++ b/misc/uClibc++/include/uClibc++/string_iostream @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -31,114 +31,124 @@ #pragma GCC visibility push(default) -namespace std{ - - +extern "C++" +{ +namespace std +{ template _UCXXEXPORT basic_ostream& - operator<<(basic_ostream& os, const basic_string& str) + operator<<(basic_ostream& os, const basic_string& str) { - return os.write(str.data(), str.length()); + return os.write(str.data(), str.length()); } template _UCXXEXPORT basic_istream& - operator>>(basic_istream& is, basic_string& str) + operator>>(basic_istream& is, basic_string& str) { + typename basic_istream::sentry s(is); + if(s == false) + { + return is; + } - typename basic_istream::sentry s(is); - if(s == false){ - return is; - } + str.clear(); - str.clear(); + typename basic_istream::int_type c; + typename Allocator::size_type n = is.width(); + bool exitnow = false; + if (n == 0) + { + n = str.max_size(); + } - typename basic_istream::int_type c; - typename Allocator::size_type n = is.width(); - bool exitnow = false; - if(n == 0){ - n = str.max_size(); - } - -// //Clear out preliminary spaces first -// c = is.get(); -// while(isspace(c)){ -// c = is.get(); -// } +// //Clear out preliminary spaces first +// c = is.get(); +// while(isspace(c)){ +// c = is.get(); +// } // -// is.putback(c); +// is.putback(c); - do{ - c = is.get(); - if(c == traits::eof() || isspace(c) || n == 0){ - is.putback(c); - exitnow = true; - }else{ - str.append(1, traits::to_char_type(c) ); - --n; - } - }while(exitnow == false); - return is; + do + { + c = is.get(); + if(c == traits::eof() || isspace(c) || n == 0) + { + is.putback(c); + exitnow = true; + } + else + { + str.append(1, traits::to_char_type(c) ); + --n; + } + } + while(exitnow == false); + + return is; } template _UCXXEXPORT basic_istream& - getline(basic_istream& is, basic_string& str, charT delim) + getline(basic_istream& is, basic_string& str, charT delim) { - typename basic_istream::sentry s(is); - if(s == false){ - return is; - } + typename basic_istream::sentry s(is); + if (s == false) + { + return is; + } - str.erase(); + str.erase(); - streamsize i = 0; - typename basic_istream::int_type c_i; - charT c; - unsigned int n = str.max_size(); - for(i=0;i::int_type c_i; + charT c; + unsigned int n = str.max_size(); + for (i = 0; i < n; ++i) + { + c_i=is.get(); + if (c_i == traits::eof() ) + { + return is; + } + + c = traits::to_char_type(c_i); + if (c == delim) + { + return is; + } + + str.append(1, c); + } + return is; } template _UCXXEXPORT basic_istream& - getline(basic_istream& is, basic_string& str) + getline(basic_istream& is, basic_string& str) { - return getline(is, str, '\n'); + return getline(is, str, '\n'); } - #ifdef __UCLIBCXX_EXPAND_STRING_CHAR__ #ifndef __UCLIBCXX_COMPILE_STRING__ - #ifdef __UCLIBCXX_EXPAND_ISTREAM_CHAR__ template<> _UCXXEXPORT basic_istream >& operator>>( - basic_istream >& is, - basic_string, allocator >& str); + basic_istream >& is, + basic_string, allocator >& str); #endif - #ifdef __UCLIBCXX_EXPAND_OSTREAM_CHAR__ template<> _UCXXEXPORT basic_ostream >& - operator<<(basic_ostream >& os, - const basic_string, std::allocator >& str); + operator<<(basic_ostream >& os, + const basic_string, std::allocator >& str); #endif - #endif #endif - -} +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/type_traits b/misc/uClibc++/include/uClibc++/type_traits index fa1de40cee..2a599f78b4 100644 --- a/misc/uClibc++/include/uClibc++/type_traits +++ b/misc/uClibc++/include/uClibc++/type_traits @@ -1,20 +1,20 @@ -/* Copyright (C) 2005 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2005 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -27,64 +27,75 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ + struct _UCXXEXPORT __true_type{}; + struct _UCXXEXPORT __false_type{}; - struct _UCXXEXPORT __true_type{}; - struct _UCXXEXPORT __false_type{}; + template class _UCXXEXPORT __is_integer + { + public: + typedef __false_type value; + }; - template class _UCXXEXPORT __is_integer{ - public: - typedef __false_type value; - }; + template <> class _UCXXEXPORT __is_integer + { + public: + typedef __true_type value; + }; - template <> class _UCXXEXPORT __is_integer { - public: - typedef __true_type value; - }; + template <> class _UCXXEXPORT __is_integer + { + public: + typedef __true_type value; + }; - template <> class _UCXXEXPORT __is_integer { - public: - typedef __true_type value; - }; + template <> class _UCXXEXPORT __is_integer + { + public: + typedef __true_type value; + }; - template <> class _UCXXEXPORT __is_integer { - public: - typedef __true_type value; - }; + template <> class _UCXXEXPORT __is_integer + { + public: + typedef __true_type value; + }; - template <> class _UCXXEXPORT __is_integer { - public: - typedef __true_type value; - }; + template <> class _UCXXEXPORT __is_integer + { + public: + typedef __true_type value; + }; - template <> class _UCXXEXPORT __is_integer { - public: - typedef __true_type value; - }; + template <> class _UCXXEXPORT __is_integer + { + public: + typedef __true_type value; + }; - template <> class _UCXXEXPORT __is_integer { - public: - typedef __true_type value; - }; + template <> class _UCXXEXPORT __is_integer + { + public: + typedef __true_type value; + }; - template <> class _UCXXEXPORT __is_integer { - public: - typedef __true_type value; - }; + template <> class _UCXXEXPORT __is_integer + { + public: + typedef __true_type value; + }; - template <> class _UCXXEXPORT __is_integer { - public: - typedef __true_type value; - }; + template <> class _UCXXEXPORT __is_integer + { + public: + typedef __true_type value; + }; - template <> class _UCXXEXPORT __is_integer { - public: - typedef __true_type value; - }; - - - -} +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/utility b/misc/uClibc++/include/uClibc++/utility index b654679248..f5cb59f2f7 100644 --- a/misc/uClibc++/include/uClibc++/utility +++ b/misc/uClibc++/include/uClibc++/utility @@ -1,88 +1,107 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - -*/ - +/* Copyright (C) 2004 Garrett A. Kajmowicz + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include - #ifndef __STD_HEADER_UTILITY #define __STD_HEADER_UTILITY 1 #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ - namespace rel_ops { - template inline bool operator!=(const T& x, const T& y){ - return !(x == y); - } +namespace std +{ + namespace rel_ops + { + template inline bool operator!=(const T& x, const T& y) + { + return !(x == y); + } - template inline bool operator> (const T& x, const T& y){ - return ( y < x); - } + template inline bool operator> (const T& x, const T& y) + { + return ( y < x); + } - template inline bool operator<=(const T& x, const T& y){ - return !( y < x ); - } + template inline bool operator<=(const T& x, const T& y) + { + return !( y < x ); + } - template inline bool operator>=(const T& x, const T& y){ - return !(x < y); - } - } + template inline bool operator>=(const T& x, const T& y) + { + return !(x < y); + } + } // namespace - template struct _UCXXEXPORT pair { - typedef T1 first_type; - typedef T2 second_type; + template struct _UCXXEXPORT pair + { + typedef T1 first_type; + typedef T2 second_type; - T1 first; - T2 second; - pair() : first(), second() { } - pair(const T1& x, const T2& y) : first(x), second(y) { } - template pair(const pair &p) : first(p.first), second(p.second) { } - }; - - template bool operator==(const pair& x, const pair& y){ - using namespace rel_ops; - return (x.first == y.first && x.second==y.second); - } - template bool operator< (const pair& x, const pair& y){ - return x.first < y.first || (!(y.first < x.first) && x.second < y.second); - } - template bool operator!=(const pair& x, const pair& y){ - return !(x == y); - } - template bool operator> (const pair& x, const pair& y){ - return y < x; - } - template bool operator>=(const pair& x, const pair& y){ - return !(x < y); - } - template bool operator<=(const pair& x, const pair& y){ - return !(y < x); - } - template pair make_pair(const T1& x, const T2& y){ - return pair(x, y); - } + T1 first; + T2 second; + pair() : first(), second() { } + pair(const T1& x, const T2& y) : first(x), second(y) { } + template pair(const pair &p) : first(p.first), second(p.second) { } + }; + + template bool operator==(const pair& x, const pair& y) + { + using namespace rel_ops; + return (x.first == y.first && x.second==y.second); + } + template bool operator< (const pair& x, const pair& y) + { + return x.first < y.first || (!(y.first < x.first) && x.second < y.second); + } -} + template bool operator!=(const pair& x, const pair& y) + { + return !(x == y); + } + + template bool operator> (const pair& x, const pair& y) + { + return y < x; + } + + template bool operator>=(const pair& x, const pair& y) + { + return !(x < y); + } + + template bool operator<=(const pair& x, const pair& y) + { + return !(y < x); + } + + template pair make_pair(const T1& x, const T2& y) + { + return pair(x, y); + } + +} // namespace +} // extern "C++" #pragma GCC visibility pop -#endif //__STD_HEADER_UTILITY +#endif //__STD_HEADER_UTILITY diff --git a/misc/uClibc++/include/uClibc++/valarray b/misc/uClibc++/include/uClibc++/valarray index 09d929c49e..f28ad58745 100644 --- a/misc/uClibc++/include/uClibc++/valarray +++ b/misc/uClibc++/include/uClibc++/valarray @@ -1,21 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include @@ -27,1015 +27,1550 @@ #pragma GCC visibility push(default) -namespace std{ +extern "C++" +{ +namespace std +{ + template class valarray; + class slice; + template class slice_array; + class gslice; + template class gslice_array; + template class mask_array; + template class indirect_array; - template class valarray; - class slice; - template class slice_array; - class gslice; - template class gslice_array; - template class mask_array; - template class indirect_array; + // Actual class definitions - //Actual class definitions + class _UCXXEXPORT slice{ + protected: + size_t sta; + size_t siz; + size_t str; + public: + slice() : sta(0), siz(0), str(0){ } + slice(size_t a, size_t b, size_t c) : sta(a), siz(b), str(c) { } + slice(const slice& s) : sta(s.sta), siz(s.siz), str(s.str) { } + ~slice() { } - class _UCXXEXPORT slice { - protected: - size_t sta; - size_t siz; - size_t str; + size_t start() const + { + return sta; + } - public: - slice() : sta(0), siz(0), str(0){ } - slice(size_t a, size_t b, size_t c) : sta(a), siz(b), str(c) { } - slice(const slice& s) : sta(s.sta), siz(s.siz), str(s.str) { } - ~slice() { } - size_t start() const{ - return sta; - } - size_t size() const{ - return siz; - } - size_t stride() const{ - return str; - } - }; + size_t size() const + { + return siz; + } + size_t stride() const + { + return str; + } + }; + template class _UCXXEXPORT valarray + { + friend class slice_array; + protected: + T * data; + size_t length; - template class _UCXXEXPORT valarray { - friend class slice_array; - protected: - T * data; - size_t length; + public: + typedef T value_type; - public: - typedef T value_type; + valarray() : data(0), length(0) { } - valarray() : data(0), length(0) { } + explicit valarray(size_t t) : data(0), length(t) + { + data = new T[length]; + } - explicit valarray(size_t t) : data(0), length(t){ - data = new T[length]; - } + valarray(const T& v, size_t t) : data(0), length(t) + { + data = new T[length]; + for (size_t i = 0; i < length; ++i) + { + data[i] = v; + } + } - valarray(const T& v, size_t t) : data(0), length(t){ - data = new T[length]; - for(size_t i = 0; i < length; ++i){ - data[i] = v; - } - } - valarray(const T* p, size_t t) : data(0), length(t) { - data = new T[length]; - for(size_t i = 0; i < length; ++i){ - data[i] = p[i]; - } - } - valarray(const valarray& v) : data(0), length(v.length){ - data = new T[length]; - for(size_t i = 0; i < length; ++i){ - data[i] = v.data[i]; - } - } - valarray(const slice_array & sa) : data(0), length(sa.s.size()){ - data = new T[length]; - for(unsigned int i = 0; i < length; ++i){ - data[i] = sa.array->data[sa.s.start() + i * sa.s.stride()]; - } - } - valarray(const gslice_array&); - valarray(const mask_array&); - valarray(const indirect_array&); - ~valarray(){ - delete [] data; - data = 0; - length = 0; - } + valarray(const T* p, size_t t) : data(0), length(t) + { + data = new T[length]; + for (size_t i = 0; i < length; ++i){ + data[i] = p[i]; + } + } - valarray& operator=(const valarray& v){ - if (length != v.length) { // DR 630 - delete [] data; - length = v.length; - data = new T[length]; - } - for (size_t i = 0; i < length; ++i) { - data[i] = v.data[i]; - } - return *this; - } - valarray& operator=(const T& t){ - for(size_t i = 0; i < length; ++i){ - data[i] = t; - } - return *this; - } - valarray& operator=(const slice_array& sa){ - for(size_t i =0; i < length; ++i){ - data[i] = sa.data[sa.s.start() + i * sa.s.stride()]; - } - return *this; - } - valarray& operator=(const gslice_array&); - valarray& operator=(const mask_array&); - valarray& operator=(const indirect_array&); + valarray(const valarray& v) : data(0), length(v.length) + { + data = new T[length]; + for (size_t i = 0; i < length; ++i) + { + data[i] = v.data[i]; + } + } - const T& operator[](size_t t) const{ - return data[t]; - } - T& operator[](size_t t){ - return data[t]; - } + valarray(const slice_array & sa) : data(0), length(sa.s.size()) + { + data = new T[length]; + for (unsigned int i = 0; i < length; ++i) + { + data[i] = sa.array->data[sa.s.start() + i * sa.s.stride()]; + } + } - valarray operator[](slice s) const{ - valarray retval(s.size()); - for(unsigned int i = 0; i< s.size(); ++i){ - retval.data[i] = data[s.start() + i * s.stride()]; - } - return retval; - } + valarray(const gslice_array&); + valarray(const mask_array&); + valarray(const indirect_array&); - slice_array operator[](slice sl){ - slice_array retval; - retval.s = sl; - retval.array = this; - return retval; - } + ~valarray() + { + delete [] data; + data = 0; + length = 0; + } - valarray operator[](const gslice&) const; - gslice_array operator[](const gslice&); - valarray operator[](const valarray&) const; - mask_array operator[](const valarray&); - valarray operator[](const valarray&) const; - indirect_array operator[](const valarray&); + valarray& operator=(const valarray& v) + { + if (length != v.length) + { + // DR 630 + + delete [] data; + length = v.length; + data = new T[length]; + } + + for (size_t i = 0; i < length; ++i) + { + data[i] = v.data[i]; + } + + return *this; + } + + valarray& operator=(const T& t) + { + for (size_t i = 0; i < length; ++i) + { + data[i] = t; + } + + return *this; + } + + valarray& operator=(const slice_array& sa) + { + for (size_t i =0; i < length; ++i) + { + data[i] = sa.data[sa.s.start() + i * sa.s.stride()]; + } + + return *this; + } + + valarray& operator=(const gslice_array&); + valarray& operator=(const mask_array&); + valarray& operator=(const indirect_array&); + + const T& operator[](size_t t) const + { + return data[t]; + } + + T& operator[](size_t t) + { + return data[t]; + } + + valarray operator[](slice s) const + { + valarray retval(s.size()); + for (unsigned int i = 0; i< s.size(); ++i) + { + retval.data[i] = data[s.start() + i * s.stride()]; + } + + return retval; + } + + slice_array operator[](slice sl) + { + slice_array retval; + retval.s = sl; + retval.array = this; + return retval; + } + + valarray operator[](const gslice&) const; + gslice_array operator[](const gslice&); + valarray operator[](const valarray&) const; + mask_array operator[](const valarray&); + valarray operator[](const valarray&) const; + indirect_array operator[](const valarray&); + + valarray operator+() const + { + valarray retval(length); + for (size_t i = 0; i< length ; ++i) + { + retval.data[i] = +data[i]; + } + + return retval; + } + + valarray operator-() const + { + valarray retval(length); + for (size_t i = 0; i< length; ++i) + { + retval.data[i] = -data[i]; + } + + return retval; + } + + valarray operator~() const + { + valarray retval(length); + for (size_t i = 0; i< length ; ++i) + { + retval.data[i] = ~data[i]; + } + + return retval; + } + + valarray operator!() const + { + valarray retval(length); + for (size_t i = 0; i < length ; ++i) + { + retval[i] = !data[i]; + } + + return retval; + } + + valarray& operator*= (const T& t) + { + for (size_t i=0;i& operator/= (const T& t) + { + for (size_t i=0; i& operator%= (const T& t) + { + for (size_t i=0; i& operator+= (const T& t + ){ + for (size_t i=0; i& operator-= (const T& t) + { + for (size_t i=0; i& operator^= (const T& t) + { + for (size_t i=0; i& operator&= (const T& t) + { + for (size_t i=0; i& operator|= (const T& t) + { + for (size_t i=0; i& operator<<=(const T& t) + { + for (size_t i=0; i& operator>>=(const T& t) + { + for (size_t i=0; i>= t; + } + + return *this; + } + + valarray& operator*= (const valarray& a) + { + for (size_t i=0; i& operator/= (const valarray& a) + { + for (size_t i=0; i& operator%= (const valarray& a) + { + for (size_t i=0; i& operator+= (const valarray& a) + { + for (size_t i=0; i& operator-= (const valarray& a) + { + for (size_t i=0; i& operator^= (const valarray& a) + { + for (size_t i=0; i& operator|= (const valarray& a) + { + for (size_t i=0; i& operator&= (const valarray& a) + { + for (size_t i=0; i& operator<<=(const valarray& a) + { + for (size_t i=0; i& operator>>=(const valarray& a) + { + for (size_t i=0; i>= a.data[i]; + } + + return *this; + } - valarray operator+() const{ - valarray retval(length); - for(size_t i = 0; i< length ; ++i){ - retval.data[i] = +data[i]; - } - return retval; - } - valarray operator-() const{ - valarray retval(length); - for(size_t i = 0; i< length; ++i){ - retval.data[i] = -data[i]; - } - return retval; - } - valarray operator~() const{ - valarray retval(length); - for(size_t i = 0; i< length ; ++i){ - retval.data[i] = ~data[i]; - } - return retval; - } - valarray operator!() const{ - valarray retval(length); - for (size_t i = 0; i < length ; ++i){ - retval[i] = !data[i]; - } - return retval; - } - valarray& operator*= (const T& t){ - for(size_t i=0;i& operator/= (const T& t){ - for(size_t i=0;i& operator%= (const T& t){ - for(size_t i=0;i& operator+= (const T& t){ - for(size_t i=0;i& operator-= (const T& t){ - for(size_t i=0;i& operator^= (const T& t){ - for(size_t i=0;i& operator&= (const T& t){ - for(size_t i=0;i& operator|= (const T& t){ - for(size_t i=0;i& operator<<=(const T& t){ - for(size_t i=0;i& operator>>=(const T& t){ - for(size_t i=0;i>= t; - } - return *this; - } - valarray& operator*= (const valarray& a){ - for(size_t i=0;i& operator/= (const valarray& a){ - for(size_t i=0;i& operator%= (const valarray& a){ - for(size_t i=0;i& operator+= (const valarray& a){ - for(size_t i=0;i& operator-= (const valarray& a){ - for(size_t i=0;i& operator^= (const valarray& a){ - for(size_t i=0;i& operator|= (const valarray& a){ - for(size_t i=0;i& operator&= (const valarray& a){ - for(size_t i=0;i& operator<<=(const valarray& a){ - for(size_t i=0;i& operator>>=(const valarray& a){ - for(size_t i=0;i>= a.data[i]; - } - return *this; - } #if 0 - void swap(valarray& other) noexcept { - std::swap(length, other.length); - std::swap(data, other.data); - } + void swap(valarray& other) noexcept + { + std::swap(length, other.length); + std::swap(data, other.data); + } #endif - size_t size() const{ - return length; - } - T sum() const{ - T retval(data[0]); - for(size_t i = 1; i< length; ++i){ - retval += data[i]; - } - return retval; - } + size_t size() const + { + return length; + } - T min() const{ - T retval(data[0]); - for(size_t i = 1; i< length; ++i){ - if(data[i] < retval){ - retval = data[i]; - } - } - return retval; - } + T sum() const + { + T retval(data[0]); - T max() const{ - T retval(data[0]); - for(size_t i = 1; i< length; ++i){ - if(retval < data[i]){ - retval = data[i]; - } - } - return retval; - } + for (size_t i = 1; i< length; ++i) + { + retval += data[i]; + } - valarray shift (int n) const{ - valarray retval(length); - if (n < 0) { - if (-size_t(n) > length) - n = -int(length); - } else { - if (size_t(n) > length) - n = int(length); - } - for (size_t i = 0; i < length ; ++i) { - if ((n + i) < length) - retval.data[i] = data[n + i]; - } - return retval; - } - valarray cshift(int n) const{ - valarray retval(length); - if (length == 0) - return retval; - if (n < 0) { - if (-size_t(n) > length) - n = -int(-size_t(n) % length); - n = length + n; - } else { - if (size_t(n) > length) - n = int(size_t(n) % length); - } - for (size_t i = 0; i < length ; ++i){ - retval.data[i] = data[(n + i) % length]; - } - return retval; - } - valarray apply(T func(T) ) const{ - valarray retval(length); - for(size_t i = 0; i< length; ++i){ - retval.data[i] = func(data[i]); - } - return retval; - } - valarray apply(T func(const T&)) const{ - valarray retval(length); - for(size_t i = 0; i< length; ++i){ - retval.data[i] = func(data[i]); - } - return retval; - } - void resize(size_t sz, T c = T()){ - delete [] data; - data = 0; - if(sz > 0){ - data = new T[sz]; - for(size_t i = 0; i < sz; ++i){ - data[i] = c; - } - } - length = sz; - } - }; + return retval; + } + T min() const + { + T retval(data[0]); + for (size_t i = 1; i< length; ++i) + { + if (data[i] < retval) + { + retval = data[i]; + } + } - template class _UCXXEXPORT slice_array { - friend class valarray; - public: - typedef T value_type; + return retval; + } - void operator= (const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] = v[i]; - } - } - void operator= (const T & v){ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] = v; - } - } - void fill(const T & v){ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] = v; - } - } - void operator*= (const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] *= v[i]; - } - } - void operator/= (const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] /= v[i]; - } - } - void operator%= (const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] %= v[i]; - } - } - void operator+= (const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] += v[i]; - } - } - void operator-= (const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] -= v[i]; - } - } - void operator^= (const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] ^= v[i]; - } - } - void operator&= (const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] &= v[i]; - } - } - void operator|= (const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] |= v[i]; - } - } - void operator<<=(const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] <<= v[i]; - } - } - void operator>>=(const valarray& v) const{ - for(unsigned int i = 0; i < s.size(); ++i){ - array->data[s.start() + i * s.stride()] >>= v[i]; - } - } - ~slice_array(){ - array = 0; - } + T max() const + { + T retval(data[0]); - private: - slice_array() : array(0){ } + for (size_t i = 1; i< length; ++i) + { + if (retval < data[i]) + { + retval = data[i]; + } + } - public: - slice_array(const slice_array& sa) : array(sa.array), s(sa.s){ } - slice_array& operator=(const slice_array& sa){ - array = sa.array; - s = sa.s; - return *this; - } + return retval; + } - private: - valarray * array; - slice s; - }; + valarray shift (int n) const + { + valarray retval(length); + if (n < 0) + { + if (-size_t(n) > length) + { + n = -int(length); + } + } + else + { + if (size_t(n) > length) + { + n = int(length); + } + } - class _UCXXEXPORT gslice { - private: - size_t sta; - valarray siz; - valarray str; + for (size_t i = 0; i < length ; ++i) + { + if ((n + i) < length) + { + retval.data[i] = data[n + i]; + } + } - public: - gslice() : sta(0), siz(), str() { } // DR 543 - gslice(size_t s, const valarray& l, const valarray& d) - : sta(s), siz(l), str(d) { } + return retval; + } - size_t start() const{ - return sta; - } - valarray size() const{ - return siz; - } - valarray stride() const{ - return str; - } - }; + valarray cshift(int n) const + { + valarray retval(length); - template class gslice_array { - private: - friend class valarray; + if (length == 0) + { + return retval; + } - public: - ~gslice_array(); + if (n < 0) + { + if (-size_t(n) > length) + { + n = -int(-size_t(n) % length); + } - void operator=(const valarray& array) const; - void operator*=(const valarray& array) const; - void operator/=(const valarray& array) const; - void operator%=(const valarray& array) const; - void operator+=(const valarray& array) const; - void operator-=(const valarray& array) const; - void operator^=(const valarray& array) const; - void operator&=(const valarray& array) const; - void operator|=(const valarray& array) const; - void operator<<=(const valarray& array) const; - void operator>>=(const valarray& array) const; + n = length + n; + } + else + { + if (size_t(n) > length) + { + n = int(size_t(n) % length); + } + } + + for (size_t i = 0; i < length ; ++i) + { + retval.data[i] = data[(n + i) % length]; + } + + return retval; + } + + valarray apply(T func(T)) const + { + valarray retval(length); + + for (size_t i = 0; i< length; ++i) + { + retval.data[i] = func(data[i]); + } + + return retval; + } + + valarray apply(T func(const T&)) const + { + valarray retval(length); + + for (size_t i = 0; i< length; ++i) + { + retval.data[i] = func(data[i]); + } + + return retval; + } + + void resize(size_t sz, T c = T()) + { + delete [] data; + + data = 0; + if (sz > 0) + { + data = new T[sz]; + + for (size_t i = 0; i < sz; ++i) + { + data[i] = c; + } + } + + length = sz; + } + }; + + template class _UCXXEXPORT slice_array + { + friend class valarray; + public: + typedef T value_type; + + void operator= (const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] = v[i]; + } + } + + void operator= (const T & v) + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] = v; + } + } + + void fill(const T & v) + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] = v; + } + } + + void operator*= (const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] *= v[i]; + } + } + + void operator/= (const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] /= v[i]; + } + } + + void operator%= (const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] %= v[i]; + } + } + + void operator+= (const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] += v[i]; + } + } + + void operator-= (const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] -= v[i]; + } + } + + void operator^= (const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] ^= v[i]; + } + } + + void operator&= (const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] &= v[i]; + } + } + + void operator|= (const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] |= v[i]; + } + } + + void operator<<=(const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] <<= v[i]; + } + } + + void operator>>=(const valarray& v) const + { + for (unsigned int i = 0; i < s.size(); ++i) + { + array->data[s.start() + i * s.stride()] >>= v[i]; + } + } + + ~slice_array() + { + array = 0; + } + + private: + slice_array() : array(0){ } + + public: + slice_array(const slice_array& sa) : array(sa.array), s(sa.s){ } + + slice_array& operator=(const slice_array& sa) + { + array = sa.array; + s = sa.s; + return *this; + } + + private: + valarray * array; + slice s; + }; + + class _UCXXEXPORT gslice + { + private: + size_t sta; + valarray siz; + valarray str; + + public: + gslice() : sta(0), siz(), str() { } // DR 543 + gslice(size_t s, const valarray& l, const valarray& d) + : sta(s), siz(l), str(d) { } + + size_t start() const + { + return sta; + } + + valarray size() const + { + return siz; + } + + valarray stride() const + { + return str; + } + }; + + template class gslice_array + { + private: + friend class valarray; + + public: + ~gslice_array(); + + void operator=(const valarray& array) const; + void operator*=(const valarray& array) const; + void operator/=(const valarray& array) const; + void operator%=(const valarray& array) const; + void operator+=(const valarray& array) const; + void operator-=(const valarray& array) const; + void operator^=(const valarray& array) const; + void operator&=(const valarray& array) const; + void operator|=(const valarray& array) const; + void operator<<=(const valarray& array) const; + void operator>>=(const valarray& array) const; - void operator=(const T&); + void operator=(const T&); - private: - gslice_array(); - gslice_array(const gslice_array&); - gslice_array& operator= (const gslice_array& array); - }; + private: + gslice_array(); + gslice_array(const gslice_array&); + gslice_array& operator= (const gslice_array& array); + }; + template valarray operator* (const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs); + retval *= rhs; + return retval; + } + template valarray operator* (const valarray& lhs, const T& rhs) + { + valarray retval(lhs); + retval *= rhs; + return retval; + } - template valarray operator* (const valarray& lhs, const valarray& rhs){ - valarray retval(lhs); - retval *= rhs; - return retval; - } + template valarray operator* (const T& lhs, const valarray& rhs) + { + valarray retval(rhs); + retval *= lhs; + return retval; + } - template valarray operator* (const valarray& lhs, const T& rhs){ - valarray retval(lhs); - retval *= rhs; - return retval; - } - template valarray operator* (const T& lhs, const valarray& rhs){ - valarray retval(rhs); - retval *= lhs; - return retval; - } - template valarray operator/ (const valarray& lhs, const valarray& rhs){ - valarray retval(lhs); - retval /= rhs; - return retval; - } - template valarray operator/ (const valarray& lhs, const T& rhs){ - valarray retval(lhs); - retval /= rhs; - return retval; - } - template valarray operator/ (const T& lhs, const valarray& rhs){ - valarray retval(lhs, rhs.size()); - retval /= rhs; - return retval; - } - template valarray operator% (const valarray& lhs, const valarray& rhs){ - valarray retval(lhs); - retval %= rhs; - return retval; - } - template valarray operator% (const valarray& lhs, const T& rhs){ - valarray retval(lhs); - retval %= rhs; - return retval; - } - template valarray operator% (const T& lhs, const valarray& rhs){ - valarray retval(lhs, rhs.size()); - retval %= rhs; - return retval; - } - template valarray operator+ (const valarray& lhs, const valarray& rhs){ - valarray retval(lhs); - retval += rhs; - return retval; - } - template valarray operator+ (const valarray& lhs, const T& rhs){ - valarray retval(lhs); - retval += rhs; - return retval; - } - template valarray operator+ (const T& lhs, const valarray& rhs){ - valarray retval(lhs, rhs.size()); - retval += rhs; - return retval; - } - template valarray operator- (const valarray& lhs, const valarray& rhs){ - valarray retval(lhs); - retval -= rhs; - return retval; - } - template valarray operator- (const valarray& lhs, const T& rhs){ - valarray retval(lhs); - retval -= rhs; - return retval; - } - template valarray operator- (const T& lhs, const valarray& rhs){ - valarray retval(lhs, rhs.size()); - retval -= rhs; - return retval; - } - template valarray operator^ (const valarray& lhs, const valarray& rhs){ - valarray retval(lhs); - retval ^= rhs; - return retval; - } - template valarray operator^ (const valarray& lhs, const T& rhs){ - valarray retval(lhs); - retval ^= rhs; - return retval; - } - template valarray operator^ (const T& lhs, const valarray& rhs){ - valarray retval(lhs, rhs.size()); - retval ^= rhs; - return retval; - } - template valarray operator& (const valarray& lhs, const valarray& rhs){ - valarray retval(lhs); - retval &= rhs; - return retval; - } - template valarray operator& (const valarray& lhs, const T& rhs){ - valarray retval(lhs); - retval &= rhs; - return retval; - } - template valarray operator& (const T& lhs, const valarray& rhs){ - valarray retval(lhs, rhs.size()); - retval &= rhs; - return retval; - } - template valarray operator| (const valarray& lhs, const valarray& rhs){ - valarray retval(lhs); - retval |= rhs; - return retval; - } - template valarray operator| (const valarray& lhs, const T& rhs){ - valarray retval(lhs); - retval |= rhs; - return retval; - } - template valarray operator| (const T& lhs, const valarray& rhs){ - valarray retval(lhs, rhs.size()); - retval |= rhs; - return retval; - } - template valarray operator<<(const valarray& lhs, const valarray& rhs){ - valarray retval(lhs); - retval <<= rhs; - return retval; - } - template valarray operator<<(const valarray& lhs, const T& rhs){ - valarray retval(lhs); - retval <<= rhs; - return retval; - } - template valarray operator<<(const T& lhs, const valarray& rhs){ - valarray retval(lhs, rhs.size()); - retval <<= rhs; - return retval; - } - template valarray operator>>(const valarray& lhs, const valarray& rhs){ - valarray retval(lhs); - retval >>= rhs; - return retval; - } - template valarray operator>>(const valarray& lhs, const T& rhs){ - valarray retval(lhs); - retval >>= rhs; - return retval; - } - template valarray operator>>(const T& lhs, const valarray& rhs){ - valarray retval(lhs, rhs.size()); - retval >>= rhs; - return retval; - } + template valarray operator/ (const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs); + retval /= rhs; + return retval; + } - template valarray operator&&(const valarray& lhs, const valarray& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = lhs[i] && rhs[i]; - } - return retval; - } - template valarray operator&&(const valarray& lhs, const T& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i valarray operator&&(const T& lhs, const valarray& rhs){ - valarray retval(rhs.size()); - for(size_t i = 0; i valarray operator||(const valarray&lhs, const valarray& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i valarray operator||(const valarray& lhs, const T& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i valarray operator||(const T& lhs, const valarray& rhs){ - valarray retval(rhs.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = lhs || rhs[i]; - } - return retval; - } + template valarray operator/ (const valarray& lhs, const T& rhs) + { + valarray retval(lhs); + retval /= rhs; + return retval; + } - template valarray operator==(const valarray& lhs, const valarray& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i valarray operator==(const valarray& lhs, const T& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = lhs[i] == rhs; - } - return retval; - } - template valarray operator==(const T& lhs, const valarray& rhs){ - valarray retval(rhs.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = lhs == rhs[i]; - } - return retval; - } - template valarray operator!=(const valarray& lhs, const valarray& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i valarray operator!=(const valarray& lhs, const T& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i valarray operator!=(const T& lhs, const valarray& rhs){ - valarray retval(rhs.size()); - for(size_t i = 0; i valarray operator< (const valarray& lhs, const valarray& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i valarray operator< (const valarray& lhs, const T& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i valarray operator< (const T& lhs, const valarray& rhs){ - valarray retval(rhs.size()); - for(size_t i = 0; i valarray operator> (const valarray& lhs, const valarray& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i rhs[i]; - } - return retval; - } - template valarray operator> (const valarray& lhs, const T& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i rhs; - } - return retval; - } - template valarray operator> (const T& lhs, const valarray& rhs){ - valarray retval(rhs.size()); - for(size_t i = 0; i rhs[i]; - } - return retval; - } - template valarray operator<=(const valarray& lhs, const valarray& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i valarray operator<=(const valarray& lhs, const T& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i valarray operator<=(const T& lhs, const valarray& rhs){ - valarray retval(rhs.size()); - for(size_t i = 0; i valarray operator>=(const valarray& lhs, const valarray& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i = rhs[i]; - } - return retval; - } - template valarray operator>=(const valarray& lhs, const T& rhs){ - valarray retval(lhs.size()); - for(size_t i = 0; i = rhs; - } - return retval; - } - template valarray operator>=(const T& lhs, const valarray& rhs){ - valarray retval(rhs.size()); - for(size_t i = 0; i = rhs[i]; - } - return retval; - } - template T min(const valarray& x){ - T retval(x[0]); - for(size_t i = 1; i < x.size(); ++i){ - if(x[i] < retval){ - retval = x[i]; - } - } - } - template T max(const valarray& x){ - T retval(x[0]); - for(size_t i = 1; i < x.size(); ++i){ - if(x[i] > retval){ - retval = x[i]; - } - } - } + template valarray operator/ (const T& lhs, const valarray& rhs) + { + valarray retval(lhs, rhs.size()); + retval /= rhs; + return retval; + } - template valarray abs (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = abs(x[i]); - } - return retval; - } - template valarray acos (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = acos(x[i]); - } - return retval; - } - template valarray asin (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = asin(x[i]); - } - return retval; - } - template valarray atan (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = atan(x[i]); - } - return retval; - } - template valarray atan2(const valarray& y, const valarray& x){ - valarray retval(y.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = atan2(y[i], x[i]); - } - return retval; - } - template valarray atan2(const valarray& y, const T& x){ - valarray retval(y.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = atan2(y[i], x); - } - return retval; - } - template valarray atan2(const T& y, const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = atan2(y, x[i]); - } - return retval; - } - template valarray cos (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = cos(x[i]); - } - return retval; - } - template valarray cosh (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = cosh(x[i]); - } - return retval; - } - template valarray exp (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = exp(x[i]); - } - return retval; - } - template valarray log (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = log(x[i]); - } - return retval; - } - template valarray log10(const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = log10(x[i]); - } - return retval; - } - template valarray pow (const valarray& x, const valarray& y){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = pow(x[i], y[i]); - } - return retval; - } - template valarray pow (const valarray& x, const T& y){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = pow(x[i], y); - } - return retval; - } - template valarray pow (const T& x, const valarray& y){ - valarray retval(y.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = pow(x, y[i]); - } - return retval; - } - template valarray sin (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = sin(x[i]); - } - return retval; - } - template valarray sinh (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = sinh(x[i]); - } - return retval; - } - template valarray sqrt (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = sqrt(x[i]); - } - return retval; - } - template valarray tan (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = tan(x[i]); - } - return retval; - } - template valarray tanh (const valarray& x){ - valarray retval(x.size()); - for(size_t i = 0; i < retval.size(); ++i){ - retval[i] = tanh(x[i]); - } - return retval; - } -} + template valarray operator% (const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs); + retval %= rhs; + return retval; + } + + template valarray operator% (const valarray& lhs, const T& rhs) + { + valarray retval(lhs); + retval %= rhs; + return retval; + } + + template valarray operator% (const T& lhs, const valarray& rhs) + { + valarray retval(lhs, rhs.size()); + retval %= rhs; + return retval; + } + + template valarray operator+ (const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs); + retval += rhs; + return retval; + } + + template valarray operator+ (const valarray& lhs, const T& rhs) + { + valarray retval(lhs); + retval += rhs; + return retval; + } + + template valarray operator+ (const T& lhs, const valarray& rhs) + { + valarray retval(lhs, rhs.size()); + retval += rhs; + return retval; + } + + template valarray operator- (const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs); + retval -= rhs; + return retval; + } + + template valarray operator- (const valarray& lhs, const T& rhs) + { + valarray retval(lhs); + retval -= rhs; + return retval; + } + + template valarray operator- (const T& lhs, const valarray& rhs) + { + valarray retval(lhs, rhs.size()); + retval -= rhs; + return retval; + } + + template valarray operator^ (const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs); + retval ^= rhs; + return retval; + } + + template valarray operator^ (const valarray& lhs, const T& rhs) + { + valarray retval(lhs); + retval ^= rhs; + return retval; + } + + template valarray operator^ (const T& lhs, const valarray& rhs) + { + valarray retval(lhs, rhs.size()); + retval ^= rhs; + return retval; + } + + template valarray operator& (const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs); + retval &= rhs; + return retval; + } + + template valarray operator& (const valarray& lhs, const T& rhs) + { + valarray retval(lhs); + retval &= rhs; + return retval; + } + + template valarray operator& (const T& lhs, const valarray& rhs) + { + valarray retval(lhs, rhs.size()); + retval &= rhs; + return retval; + } + + template valarray operator| (const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs); + retval |= rhs; + return retval; + } + + template valarray operator| (const valarray& lhs, const T& rhs) + { + valarray retval(lhs); + retval |= rhs; + return retval; + } + + template valarray operator| (const T& lhs, const valarray& rhs) + { + valarray retval(lhs, rhs.size()); + retval |= rhs; + return retval; + } + + template valarray operator<<(const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs); + retval <<= rhs; + return retval; + } + + template valarray operator<<(const valarray& lhs, const T& rhs) + { + valarray retval(lhs); + retval <<= rhs; + return retval; + } + + template valarray operator<<(const T& lhs, const valarray& rhs) + { + valarray retval(lhs, rhs.size()); + retval <<= rhs; + return retval; + } + + template valarray operator>>(const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs); + retval >>= rhs; + return retval; + } + + template valarray operator>>(const valarray& lhs, const T& rhs) + { + valarray retval(lhs); + retval >>= rhs; + return retval; + } + + template valarray operator>>(const T& lhs, const valarray& rhs) + { + valarray retval(lhs, rhs.size()); + retval >>= rhs; + return retval; + } + + template valarray operator&&(const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = lhs[i] && rhs[i]; + } + + return retval; + } + + template valarray operator&&(const valarray& lhs, const T& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i valarray operator&&(const T& lhs, const valarray& rhs) + { + valarray retval(rhs.size()); + + for (size_t i = 0; i valarray operator||(const valarray&lhs, const valarray& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i valarray operator||(const valarray& lhs, const T& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i valarray operator||(const T& lhs, const valarray& rhs) + { + valarray retval(rhs.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = lhs || rhs[i]; + } + + return retval; + } + + template valarray operator==(const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i valarray operator==(const valarray& lhs, const T& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = lhs[i] == rhs; + } + + return retval; + } + + template valarray operator==(const T& lhs, const valarray& rhs) + { + valarray retval(rhs.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = lhs == rhs[i]; + } + + return retval; + } + + template valarray operator!=(const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i valarray operator!=(const valarray& lhs, const T& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i valarray operator!=(const T& lhs, const valarray& rhs) + { + valarray retval(rhs.size()); + + for (size_t i = 0; i valarray operator< (const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i valarray operator< (const valarray& lhs, const T& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i valarray operator< (const T& lhs, const valarray& rhs) + { + valarray retval(rhs.size()); + + for (size_t i = 0; i valarray operator> (const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i rhs[i]; + } + + return retval; + } + + template valarray operator> (const valarray& lhs, const T& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i rhs; + } + + return retval; + } + + template valarray operator> (const T& lhs, const valarray& rhs) + { + valarray retval(rhs.size()); + + for (size_t i = 0; i rhs[i]; + } + + return retval; + } + + template valarray operator<=(const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i valarray operator<=(const valarray& lhs, const T& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i valarray operator<=(const T& lhs, const valarray& rhs) + { + valarray retval(rhs.size()); + + for (size_t i = 0; i valarray operator>=(const valarray& lhs, const valarray& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i = rhs[i]; + } + + return retval; + } + + template valarray operator>=(const valarray& lhs, const T& rhs) + { + valarray retval(lhs.size()); + + for (size_t i = 0; i = rhs; + } + + return retval; + } + + template valarray operator>=(const T& lhs, const valarray& rhs) + { + valarray retval(rhs.size()); + + for (size_t i = 0; i = rhs[i]; + } + + return retval; + } + + template T min(const valarray& x) + { + T retval(x[0]); + + for (size_t i = 1; i < x.size(); ++i) + { + if (x[i] < retval) + { + retval = x[i]; + } + } + } + + template T max(const valarray& x) + { + T retval(x[0]); + + for (size_t i = 1; i < x.size(); ++i) + { + if (x[i] > retval) + { + retval = x[i]; + } + } + } + + template valarray abs (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = abs(x[i]); + } + + return retval; + } + + template valarray acos (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = acos(x[i]); + } + + return retval; + } + + template valarray asin (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = asin(x[i]); + } + + return retval; + } + + template valarray atan (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = atan(x[i]); + } + + return retval; + } + + template valarray atan2(const valarray& y, const valarray& x) + { + valarray retval(y.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = atan2(y[i], x[i]); + } + + return retval; + } + + template valarray atan2(const valarray& y, const T& x) + { + valarray retval(y.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = atan2(y[i], x); + } + + return retval; + } + + template valarray atan2(const T& y, const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = atan2(y, x[i]); + } + + return retval; + } + + template valarray cos (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = cos(x[i]); + } + + return retval; + } + + template valarray cosh (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = cosh(x[i]); + } + + return retval; + } + + template valarray exp (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = exp(x[i]); + } + + return retval; + } + + template valarray log (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = log(x[i]); + } + + return retval; + } + + template valarray log10(const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = log10(x[i]); + } + + return retval; + } + + template valarray pow (const valarray& x, const valarray& y) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = pow(x[i], y[i]); + } + + return retval; + } + + template valarray pow (const valarray& x, const T& y) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = pow(x[i], y); + } + + return retval; + } + + template valarray pow (const T& x, const valarray& y) + { + valarray retval(y.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = pow(x, y[i]); + } + + return retval; + } + + template valarray sin (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = sin(x[i]); + } + + return retval; + } + + template valarray sinh (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = sinh(x[i]); + } + + return retval; + } + + template valarray sqrt (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = sqrt(x[i]); + } + + return retval; + } + + template valarray tan (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i){ + retval[i] = tan(x[i]); + } + + return retval; + } + + template valarray tanh (const valarray& x) + { + valarray retval(x.size()); + + for (size_t i = 0; i < retval.size(); ++i) + { + retval[i] = tanh(x[i]); + } + + return retval; + } + +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/include/uClibc++/vector b/misc/uClibc++/include/uClibc++/vector index 8310bc14e3..88adbd0117 100644 --- a/misc/uClibc++/include/uClibc++/vector +++ b/misc/uClibc++/include/uClibc++/vector @@ -1,22 +1,21 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include #include @@ -25,491 +24,582 @@ #include #include - #ifndef __STD_HEADER_VECTOR #define __STD_HEADER_VECTOR #pragma GCC visibility push(default) -namespace std{ - - template > class vector; - template bool operator==(const vector& x, const vector& y); - template bool operator< (const vector& x, const vector& y); - template bool operator!=(const vector& x, const vector& y); - template bool operator> (const vector& x, const vector& y); - template bool operator>=(const vector& x, const vector& y); - template bool operator<=(const vector& x, const vector& y); - template void swap(vector& x, vector& y); - - template class _UCXXEXPORT vector { - public: - - typedef typename Allocator::reference reference; - typedef typename Allocator::const_reference const_reference; - typedef typename Allocator::size_type size_type; - typedef typename Allocator::difference_type difference_type; - typedef typename Allocator::pointer pointer; - typedef typename Allocator::const_pointer const_pointer; - - typedef T* iterator; - typedef const T* const_iterator; - typedef T value_type; - typedef Allocator allocator_type; - typedef std::reverse_iterator reverse_iterator; - typedef std::reverse_iterator const_reverse_iterator; - - explicit _UCXXEXPORT vector(const Allocator& al= Allocator()): data(0), //defaultValue(T()), - data_size(__UCLIBCXX_STL_BUFFER_SIZE__), elements(0), a(al) - { - data = a.allocate(data_size); - } - - explicit _UCXXEXPORT vector(size_type n, const T& value = T(), const Allocator& al= Allocator()) : - data(0), data_size(0), elements(0), a(al) - { - data_size = n + __UCLIBCXX_STL_BUFFER_SIZE__; - data = a.allocate(data_size); - - resize(n, value); - } - - template _UCXXEXPORT - vector(InputIterator first, InputIterator last, const Allocator& al = Allocator()): - data(0), data_size(__UCLIBCXX_STL_BUFFER_SIZE__), elements(0), a(al) - { - data = a.allocate(data_size); - assign(first, last); - } - - _UCXXEXPORT vector(const vector& x){ - a = x.a; - - elements = x.elements; - data_size = elements + __UCLIBCXX_STL_BUFFER_SIZE__; - data = a.allocate(data_size); - - for(size_type i = 0; i < elements; i++){ - a.construct(data+i, x.data[i]); - } - } - - _UCXXEXPORT ~vector(); //Below - - _UCXXEXPORT vector& operator=(const vector& x){ - if(&x == this){ - return *this; - } - - reserve(x.elements); //Make sure that we have enough actual memory - - - //Copy as many elements as possible - - size_t minElements = elements; - if(minElements > x.elements){ - minElements = x.elements; - } - for(size_t i = 0; i < minElements; ++i){ - data[i] = x.data[i]; - } - - //If we need to add new elements - if(elements < x.elements){ - for(size_t i = elements; i< x.elements; ++i){ - a.construct(data+i, x.data[i]); - ++elements; - } - } - - if(elements > x.elements){ - downsize(x.elements); - } - - return *this; - } - - template _UCXXEXPORT void assign(InputIterator first, InputIterator last){ - clear(); - insert(begin(), first, last); - } - - template _UCXXEXPORT void assign(Size n, const U& u = U()){ - clear(); - resize(n, u); - } - - inline allocator_type get_allocator() const{ - return a; - } - - inline iterator begin(){ - return data; - } - - inline const_iterator begin() const{ - return data; - } - - inline iterator end(){ - return (data + elements); - } - - inline const_iterator end() const{ - return (data + elements); - } - - inline reverse_iterator rbegin(){ - return reverse_iterator(end()); - } - - inline const_reverse_iterator rbegin() const{ - return const_reverse_iterator(end()); - } - - inline reverse_iterator rend(){ - return reverse_iterator(begin()); - } - - inline const_reverse_iterator rend() const{ - return const_reverse_iterator(begin()); - } - - inline size_type size() const{ - return elements; - } - - _UCXXEXPORT size_type max_size() const{ - return ((size_type)(-1)) / sizeof(T); - } - - void downsize(size_type sz); - void resize(size_type sz, const T & c = T()); - - inline size_type capacity() const{ - return data_size; - } - - inline bool empty() const{ - return (size() == 0); - } - - void reserve(size_type n); - - inline reference operator[](size_type n){ - return data[n]; - } - - inline const_reference operator[](size_type n) const{ - return data[n]; - } - - _UCXXEXPORT const_reference at(size_type n) const{ - if(n >= elements){ - __throw_out_of_range("Invalid subscript"); - } - return data[n]; - } - - _UCXXEXPORT reference at(size_type n){ - if(n >= elements){ - __throw_out_of_range("Invalid subscript"); - } - return data[n]; - } - - inline reference front(){ - return data[0]; - } - - inline const_reference front() const{ - return data[0]; - } - - inline reference back(){ - return data[ size() - 1]; - } - - inline const_reference back() const{ - return data[ size() - 1 ]; - } - - inline void push_back(const T& x){ - resize( size() + 1, x); - } - - inline void pop_back(){ - downsize(size() - 1); - } - - _UCXXEXPORT iterator insert(iterator position, const T& x = T()){ - size_type index = position - data; - resize(size() + 1, x); - for(size_type i = elements - 1; i > index; --i){ - data[i] = data[i-1]; - } - data[index] = x; - return (data + index); - } - - _UCXXEXPORT void _insert_fill(iterator position, size_type n, const T & x){ - size_type index = position - data; - resize(size() + n, x); - - for(size_type i = elements -1; (i > (index+n-1)); --i){ - data[i] = data[i-n]; - } - for(size_type i = 0; i < n; i++){ - data[i + index] = x; - } - } - - template _UCXXEXPORT - void _insert_from_iterator(iterator position, InputIterator first, InputIterator last) - { - T temp; - while(first !=last){ - temp = *first; - position = insert(position, temp); - ++position; - ++first; - } - } - - template - inline void _dispatch_insert(iterator position, InputIterator first, InputIterator last, __true_type) - { - _insert_fill(position, first, last); - } - - template - inline void _dispatch_insert(iterator position, InputIterator first, InputIterator last, __false_type) - { - _insert_from_iterator(position, first, last); - } - - inline void insert(iterator position, size_type n, const T& x ){ - _insert_fill(position, n, x); - } - - template inline void insert(iterator position, InputIterator first, InputIterator last){ - typedef typename __is_integer::value __some_type; - _dispatch_insert(position, first, last, __some_type()); - } - - _UCXXEXPORT iterator erase(iterator position){ - size_type index = position - data; - for(size_type i = index; i < (elements - 1); ++i){ - data[i] = data[i+1]; - } - downsize(size() - 1); - return (data + index); - } - - _UCXXEXPORT iterator erase(iterator first, iterator last){ - size_type index = first - data; - size_type width = last - first; - for(size_type i = index; i < (elements - width) ;++i){ - data[i] = data[i+width]; - } - downsize(size() - width); - return (data + index); - } - - _UCXXEXPORT void swap(vector& v){ - if(this == &v){ //Avoid dv.swap(v) - return; - } - T* ptr; - size_type temp; - - //Swap pointers first - ptr = data; - data = v.data; - v.data = ptr; - - //Swap element counts - temp = elements; - elements = v.elements; - v.elements = temp; - - //Swap data size - temp = data_size; - data_size = v.data_size; - v.data_size = temp; - } - - _UCXXEXPORT void clear(){ - downsize(0); - } - - protected: - T* data; - size_type data_size; - size_type elements; - Allocator a; - }; - - - - //Here go template instantiations - - template _UCXXEXPORT vector::~vector(){ - for(size_t i = 0; i < elements; ++i){ - a.destroy(data + i); - } - a.deallocate(data, data_size); - } - - - template _UCXXEXPORT void vector::reserve(size_type n){ - if(n > data_size){ //We never shrink... - T * temp_ptr = data; - size_type temp_size = data_size; - - data_size = n; - data = a.allocate(data_size); - - for(size_type i = 0; i _UCXXEXPORT void vector::resize(size_type sz, const T & c){ - if(sz > elements){ //Need to actually call constructor - if(sz > data_size){ - reserve(sz + __UCLIBCXX_STL_BUFFER_SIZE__); - } - - for(size_type i = elements; i _UCXXEXPORT void vector::downsize(size_type sz){ - if(sz < elements){ //Actually are downsizing - for(size_t i = sz; i< elements; ++i){ - a.destroy(data+i); - } - elements = sz; - } - } - +extern "C++" +{ +namespace std +{ + template > class vector; + template bool operator==(const vector& x, const vector& y); + template bool operator< (const vector& x, const vector& y); + template bool operator!=(const vector& x, const vector& y); + template bool operator> (const vector& x, const vector& y); + template bool operator>=(const vector& x, const vector& y); + template bool operator<=(const vector& x, const vector& y); + template void swap(vector& x, vector& y); + + template class _UCXXEXPORT vector + { + public: + + typedef typename Allocator::reference reference; + typedef typename Allocator::const_reference const_reference; + typedef typename Allocator::size_type size_type; + typedef typename Allocator::difference_type difference_type; + typedef typename Allocator::pointer pointer; + typedef typename Allocator::const_pointer const_pointer; + + typedef T* iterator; + typedef const T* const_iterator; + typedef T value_type; + typedef Allocator allocator_type; + typedef std::reverse_iterator reverse_iterator; + typedef std::reverse_iterator const_reverse_iterator; + + explicit _UCXXEXPORT vector(const Allocator& al= Allocator()): data(0), //defaultValue(T()), + data_size(__UCLIBCXX_STL_BUFFER_SIZE__), elements(0), a(al) + { + data = a.allocate(data_size); + } + + explicit _UCXXEXPORT vector(size_type n, const T& value = T(), const Allocator& al= Allocator()) : + data(0), data_size(0), elements(0), a(al) + { + data_size = n + __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + + resize(n, value); + } + + template _UCXXEXPORT + vector(InputIterator first, InputIterator last, const Allocator& al = Allocator()): + data(0), data_size(__UCLIBCXX_STL_BUFFER_SIZE__), elements(0), a(al) + { + data = a.allocate(data_size); + assign(first, last); + } + + _UCXXEXPORT vector(const vector& x) + { + a = x.a; + + elements = x.elements; + data_size = elements + __UCLIBCXX_STL_BUFFER_SIZE__; + data = a.allocate(data_size); + + for (size_type i = 0; i < elements; i++) + { + a.construct(data+i, x.data[i]); + } + } + + _UCXXEXPORT ~vector(); // Below + + _UCXXEXPORT vector& operator=(const vector& x) + { + if (&x == this) + { + return *this; + } + + reserve(x.elements); // Make sure that we have enough actual memory + + // Copy as many elements as possible + + size_t minElements = elements; + if (minElements > x.elements) + { + minElements = x.elements; + } + + for (size_t i = 0; i < minElements; ++i) + { + data[i] = x.data[i]; + } + + // If we need to add new elements + + if (elements < x.elements) + { + for (size_t i = elements; i< x.elements; ++i) + { + a.construct(data+i, x.data[i]); + ++elements; + } + } + + if (elements > x.elements) + { + downsize(x.elements); + } + + return *this; + } + + template _UCXXEXPORT void assign(InputIterator first, InputIterator last) + { + clear(); + insert(begin(), first, last); + } + + template _UCXXEXPORT void assign(Size n, const U& u = U()) + { + clear(); + resize(n, u); + } + + inline allocator_type get_allocator() const + { + return a; + } + + inline iterator begin() + { + return data; + } + + inline const_iterator begin() const + { + return data; + } + + inline iterator end() + { + return (data + elements); + } + + inline const_iterator end() const + { + return (data + elements); + } + + inline reverse_iterator rbegin() + { + return reverse_iterator(end()); + } + + inline const_reverse_iterator rbegin() const + { + return const_reverse_iterator(end()); + } + + inline reverse_iterator rend() + { + return reverse_iterator(begin()); + } + + inline const_reverse_iterator rend() const + { + return const_reverse_iterator(begin()); + } + + inline size_type size() const + { + return elements; + } + + _UCXXEXPORT size_type max_size() const + { + return ((size_type)(-1)) / sizeof(T); + } + + void downsize(size_type sz); + void resize(size_type sz, const T & c = T()); + + inline size_type capacity() const + { + return data_size; + } + + inline bool empty() const + { + return (size() == 0); + } + + void reserve(size_type n); + + inline reference operator[](size_type n) + { + return data[n]; + } + + inline const_reference operator[](size_type n) const + { + return data[n]; + } + + _UCXXEXPORT const_reference at(size_type n) const + { + if (n >= elements) + { + __throw_out_of_range("Invalid subscript"); + } + + return data[n]; + } + + _UCXXEXPORT reference at(size_type n) + { + if (n >= elements) + { + __throw_out_of_range("Invalid subscript"); + } + + return data[n]; + } + + inline reference front() + { + return data[0]; + } + + inline const_reference front() const + { + return data[0]; + } + + inline reference back() + { + return data[ size() - 1]; + } + + inline const_reference back() const + { + return data[ size() - 1 ]; + } + + inline void push_back(const T& x) + { + resize(size() + 1, x); + } + + inline void pop_back() + { + downsize(size() - 1); + } + + _UCXXEXPORT iterator insert(iterator position, const T& x = T()) + { + size_type index = position - data; + resize(size() + 1, x); + for (size_type i = elements - 1; i > index; --i) + { + data[i] = data[i-1]; + } + + data[index] = x; + return (data + index); + } + + _UCXXEXPORT void _insert_fill(iterator position, size_type n, const T & x) + { + size_type index = position - data; + resize(size() + n, x); + + for (size_type i = elements -1; (i > (index+n-1)); --i) + { + data[i] = data[i-n]; + } + + for (size_type i = 0; i < n; i++) + { + data[i + index] = x; + } + } + + template _UCXXEXPORT + void _insert_from_iterator(iterator position, InputIterator first, InputIterator last) + { + T temp; + while (first !=last) + { + temp = *first; + position = insert(position, temp); + ++position; + ++first; + } + } + + template + inline void _dispatch_insert(iterator position, InputIterator first, InputIterator last, __true_type) + { + _insert_fill(position, first, last); + } + + template + inline void _dispatch_insert(iterator position, InputIterator first, InputIterator last, __false_type) + { + _insert_from_iterator(position, first, last); + } + + inline void insert(iterator position, size_type n, const T& x) + { + _insert_fill(position, n, x); + } + + template inline void insert(iterator position, InputIterator first, InputIterator last) + { + typedef typename __is_integer::value __some_type; + _dispatch_insert(position, first, last, __some_type()); + } + + _UCXXEXPORT iterator erase(iterator position) + { + size_type index = position - data; + for (size_type i = index; i < (elements - 1); ++i) + { + data[i] = data[i+1]; + } + + downsize(size() - 1); + return (data + index); + } + + _UCXXEXPORT iterator erase(iterator first, iterator last) + { + size_type index = first - data; + size_type width = last - first; + for (size_type i = index; i < (elements - width) ;++i) + { + data[i] = data[i+width]; + } + + downsize(size() - width); + return (data + index); + } + + _UCXXEXPORT void swap(vector& v) + { + if (this == &v) + { + // Avoid dv.swap(v) + + return; + } + + T* ptr; + size_type temp; + + // Swap pointers first + + ptr = data; + data = v.data; + v.data = ptr; + + // Swap element counts + + temp = elements; + elements = v.elements; + v.elements = temp; + + // Swap data size + + temp = data_size; + data_size = v.data_size; + v.data_size = temp; + } + + _UCXXEXPORT void clear() + { + downsize(0); + } + + protected: + T* data; + size_type data_size; + size_type elements; + Allocator a; + }; + + // Here go template instantiations + + template _UCXXEXPORT vector::~vector() + { + for (size_t i = 0; i < elements; ++i) + { + a.destroy(data + i); + } + + a.deallocate(data, data_size); + } + + template _UCXXEXPORT void vector::reserve(size_type n) + { + if (n > data_size) + { + // We never shrink... + + T * temp_ptr = data; + size_type temp_size = data_size; + + data_size = n; + data = a.allocate(data_size); + + for (size_type i = 0; i _UCXXEXPORT void vector::resize(size_type sz, const T & c) + { + if (sz > elements) + { + // Need to actually call constructor + + if (sz > data_size) + { + reserve(sz + __UCLIBCXX_STL_BUFFER_SIZE__); + } + + for (size_type i = elements; i _UCXXEXPORT void vector::downsize(size_type sz) + { + if (sz < elements) + { + // Actually are downsizing + + for (size_t i = sz; i< elements; ++i) + { + a.destroy(data+i); + } + + elements = sz; + } + } #ifndef __UCLIBCXX_COMPILE_VECTOR__ #ifdef __UCLIBCXX_EXPAND_VECTOR_BASIC__ - #ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template<> _UCXXEXPORT vector >::vector(const allocator& al); - template<> _UCXXEXPORT vector >::vector(size_type n, const char & value, const allocator & al); - - template<> _UCXXEXPORT vector >::~vector(); - template<> _UCXXEXPORT vector >::~vector(); + template<> _UCXXEXPORT vector >::vector(const allocator& al); + template<> _UCXXEXPORT vector >::vector(size_type n, const char & value, const allocator & al); + template<> _UCXXEXPORT vector >::~vector(); + template<> _UCXXEXPORT vector >::~vector(); #endif //__UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::resize(size_type sz, const char & c); - template<> _UCXXEXPORT void - vector >::resize(size_type sz, const unsigned char & c); - template<> _UCXXEXPORT void vector >::resize(size_type sz, const short & c); - template<> _UCXXEXPORT void - vector >::resize(size_type sz, const unsigned short int & c); - template<> _UCXXEXPORT void vector >::resize(size_type sz, const int & c); - template<> _UCXXEXPORT void vector >::resize(size_type sz, const unsigned int & c); - template<> _UCXXEXPORT void vector >::resize(size_type sz, const long int & c); - template<> _UCXXEXPORT void - vector >::resize(size_type sz, const unsigned long int & c); - template<> _UCXXEXPORT void vector >::resize(size_type sz, const float & c); - template<> _UCXXEXPORT void vector >::resize(size_type sz, const double & c); - template<> _UCXXEXPORT void vector >::resize(size_type sz, const bool & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const char & c); + template<> _UCXXEXPORT void + vector >::resize(size_type sz, const unsigned char & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const short & c); + template<> _UCXXEXPORT void + vector >::resize(size_type sz, const unsigned short int & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const int & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const unsigned int & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const long int & c); + template<> _UCXXEXPORT void + vector >::resize(size_type sz, const unsigned long int & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const float & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const double & c); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const bool & c); #elif defined __UCLIBCXX_EXPAND_STRING_CHAR__ #ifdef __UCLIBCXX_EXPAND_CONSTRUCTORS_DESTRUCTORS__ - - template<> _UCXXEXPORT vector >::vector(const allocator& al); - template<> _UCXXEXPORT vector >::vector(size_type n, const char & value, const allocator & al); - template<> _UCXXEXPORT vector >::~vector(); - + template<> _UCXXEXPORT vector >::vector(const allocator& al); + template<> _UCXXEXPORT vector >::vector(size_type n, const char & value, const allocator & al); + template<> _UCXXEXPORT vector >::~vector(); #endif - template<> _UCXXEXPORT void vector >::reserve(size_type n); - template<> _UCXXEXPORT void vector >::resize(size_type sz, const char & c); + template<> _UCXXEXPORT void vector >::reserve(size_type n); + template<> _UCXXEXPORT void vector >::resize(size_type sz, const char & c); #endif #endif + template _UCXXEXPORT bool + operator==(const vector& x, const vector& y) + { + if (x.size() !=y.size()) + { + return false; + } + for (size_t i = 0; i < x.size(); ++i) + { + if (x[i] != y[i]) + { + return false; + } + } - template _UCXXEXPORT bool - operator==(const vector& x, const vector& y) - { - if(x.size() !=y.size() ){ - return false; - } - for(size_t i = 0; i < x.size(); ++i){ - if(x[i] != y[i]){ - return false; - } - } - return true; - } + return true; + } - template _UCXXEXPORT bool - operator< (const vector& x, const vector& y) - { - less::iterator >::value_type> c; - return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); - } - template _UCXXEXPORT bool - operator!=(const vector& x, const vector& y) - { - return !(x == y); - } - template _UCXXEXPORT bool - operator> (const vector& x, const vector& y) - { - greater::iterator >::value_type> c; - return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); - } - template _UCXXEXPORT bool - operator>=(const vector& x, const vector& y) - { - greater_equal::iterator >::value_type> c; - return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); - } - template _UCXXEXPORT bool - operator<=(const vector& x, const vector& y) - { - less_equal::iterator >::value_type> c; - return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); - } + template _UCXXEXPORT bool + operator< (const vector& x, const vector& y) + { + less::iterator >::value_type> c; + return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); + } - template _UCXXEXPORT void swap(vector& x, vector& y){ - x.swap(y); - } + template _UCXXEXPORT bool + operator!=(const vector& x, const vector& y) + { + return !(x == y); + } -} + template _UCXXEXPORT bool + operator> (const vector& x, const vector& y) + { + greater::iterator >::value_type> c; + return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); + } + + template _UCXXEXPORT bool + operator>=(const vector& x, const vector& y) + { + greater_equal::iterator >::value_type> c; + return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); + } + + template _UCXXEXPORT bool + operator<=(const vector& x, const vector& y) + { + less_equal::iterator >::value_type> c; + return lexicographical_compare(x.begin(), x.end(), y.begin(), y.end(), c); + } + + template _UCXXEXPORT void swap(vector& x, vector& y) + { + x.swap(y); + } + +} // namespace +} // extern "C++" #pragma GCC visibility pop diff --git a/misc/uClibc++/libxx/uClibc++/associative_base.cxx b/misc/uClibc++/libxx/uClibc++/associative_base.cxx index cc2d20e549..6a7d786e4d 100644 --- a/misc/uClibc++/libxx/uClibc++/associative_base.cxx +++ b/misc/uClibc++/libxx/uClibc++/associative_base.cxx @@ -1,26 +1,24 @@ -/* Copyright (C) 2007 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - -*/ +/* Copyright (C) 2007 Garrett A. Kajmowicz + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ #include -namespace std{ - - - -} +namespace std +{ +} // namespace diff --git a/misc/uClibc++/libxx/uClibc++/bitset.cxx b/misc/uClibc++/libxx/uClibc++/bitset.cxx index f1ece31f9f..735d863fdf 100644 --- a/misc/uClibc++/libxx/uClibc++/bitset.cxx +++ b/misc/uClibc++/libxx/uClibc++/bitset.cxx @@ -1,26 +1,24 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ #include -namespace std{ - - - -} +namespace std +{ +} // namespace diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 6fa9ffbfed..b357a629d2 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3554,3 +3554,11 @@ expects. That is usually the case if parameters are passed in registers. * libxx/libxx_cxa_atexit(): Implements __cxa_atexit() + * configs/stm32f4discovery/cxxtest: New test that will be used to + verify the uClibc++ port (eventually). The sim platform turned not + to be a good platform for testing uClibc++. The sim example will not + run because the simulator will attempt to execute the static + constructors before main() starts. BUT... NuttX is not initialized + and this results in a crash. On the STM324Discovery, I will have + better control over when the static constructors run. + diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index 49a651c4eb..7bba7315fc 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -36,58 +36,61 @@ -include $(TOPDIR)/Make.defs -include chip/Make.defs -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(CONFIG_ARCH_CORTEXM3),y) # Cortex-M3 is ARMv7-M -ARCH_SUBDIR = armv7-m +ARCH_SUBDIR = armv7-m else ifeq ($(CONFIG_ARCH_CORTEXM4),y) # Cortex-M4 is ARMv7E-M -ARCH_SUBDIR = armv7-m +ARCH_SUBDIR = armv7-m else -ARCH_SUBDIR = arm +ARCH_SUBDIR = arm endif endif ifeq ($(WINTOOL),y) - NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}" - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \ - -I "${shell cygpath -w $(TOPDIR)/sched}" + NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \ + -I "${shell cygpath -w $(TOPDIR)/sched}" else - NUTTX = $(TOPDIR)/nuttx - CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \ - -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched + NUTTX = $(TOPDIR)/nuttx + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \ + -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched endif -HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT)) +HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT)) -ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS) -AOBJS = $(ASRCS:.S=$(OBJEXT)) +ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS) +AOBJS = $(ASRCS:.S=$(OBJEXT)) -CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS) -COBJS = $(CSRCS:.c=$(OBJEXT)) +CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS) +COBJS = $(CSRCS:.c=$(OBJEXT)) -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) -LDFLAGS = $(ARCHSCRIPT) -EXTRA_LIBS ?= +LDFLAGS = $(ARCHSCRIPT) -LINKLIBS = +EXTRA_LIBS ?= +EXTRA_LIBPATHS ?= + +LINKLIBS = ifeq ($(WINTOOL),y) - LIBPATHS = ${shell for path in $(LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done} - LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}" + LIBPATHS = ${shell for path in $(LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done} + LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}" else - LIBPATHS = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS))) - LIBPATHS += -L"$(BOARDDIR)" + LIBPATHS = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS))) + LIBPATHS += -L"$(BOARDDIR)" endif -LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS)))) +LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS)))) -BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board +BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board -LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}" +LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}" +GCC_LIBDIR := ${shell dirname $(LIBGCC)} -VPATH = chip:common:$(ARCH_SUBDIR) +VPATH = chip:common:$(ARCH_SUBDIR) all: $(HEAD_OBJ) libarch$(LIBEXT) @@ -101,7 +104,7 @@ $(COBJS): %$(OBJEXT): %.c libarch$(LIBEXT): $(OBJS) $(Q) ( for obj in $(OBJS) ; do \ - $(call ARCHIVE, $@, $${obj}); \ + $(call ARCHIVE, $@, $${obj}); \ done ; ) board/libboard$(LIBEXT): @@ -109,7 +112,8 @@ board/libboard$(LIBEXT): nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT) $(Q) echo "LD: nuttx" - $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ + $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) $(EXTRA_LIBPATHS) \ + -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ --start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group $(Q) $(NM) $(NUTTX)$(EXEEXT) | \ grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \ @@ -122,10 +126,10 @@ nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT) export_head: board/libboard$(LIBEXT) $(HEAD_OBJ) ifneq ($(HEAD_OBJ),) $(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \ - cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \ + cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \ else \ - echo "$(EXPORT_DIR)/startup does not exist"; \ - exit 1; \ + echo "$(EXPORT_DIR)/startup does not exist"; \ + exit 1; \ fi endif @@ -133,7 +137,7 @@ endif .depend: Makefile chip/Make.defs $(SRCS) $(Q) if [ -e board/Makefile ]; then \ - $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \ + $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \ fi $(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \ $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @@ -143,14 +147,14 @@ depend: .depend clean: $(Q) if [ -e board/Makefile ]; then \ - $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ + $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi $(Q) rm -f libarch$(LIBEXT) *~ .*.swp $(call CLEAN) distclean: clean $(Q) if [ -e board/Makefile ]; then \ - $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ + $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi $(Q) rm -f Make.dep .depend diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile index cf8008b16b..1e4d08736b 100644 --- a/nuttx/arch/sim/src/Makefile +++ b/nuttx/arch/sim/src/Makefile @@ -101,6 +101,7 @@ endif endif EXTRA_LIBS ?= +EXTRA_LIBPATHS ?= ifeq ($(CONFIG_FS_FAT),y) STDLIBS += -lz @@ -108,9 +109,6 @@ endif STDLIBS += -lc -LIBGCC := "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}" -GCC_LIBDIR := ${shell dirname $(LIBGCC)} - # Determine which objects are required in the link. The # up_head object normally draws in all that is needed, but # there are a fews that must be included because they @@ -134,7 +132,7 @@ LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS)))) # Add the board-specific library and directory -LDPATHS += -L board -L $(GCC_LIBDIR) +LDPATHS += -L board LDLIBS += -lboard # Make targets begin here @@ -181,7 +179,7 @@ Cygwin-names.dat: nuttx-names.dat nuttx.rel : libarch$(LIBEXT) board/libboard$(LIBEXT) $(HOSTOS)-names.dat $(LINKOBJS) $(Q) echo "LD: nuttx.rel" - $(Q) $(LD) -r $(LDLINKFLAGS) $(LDPATHS) -o $@ $(REQUIREDOBJS) --start-group $(LDLIBS) $(EXTRA_LIBS) --end-group + $(Q) $(LD) -r $(LDLINKFLAGS) $(LDPATHS) $(EXTRA_LIBPATHS) -o $@ $(REQUIREDOBJS) --start-group $(LDLIBS) $(EXTRA_LIBS) --end-group $(Q) $(OBJCOPY) --redefine-syms=$(HOSTOS)-names.dat $@ # Generate the final NuttX binary by linking the host-specific objects with the NuttX diff --git a/nuttx/configs/sim/README.txt b/nuttx/configs/sim/README.txt index 654ce93146..39ace5495e 100644 --- a/nuttx/configs/sim/README.txt +++ b/nuttx/configs/sim/README.txt @@ -215,18 +215,18 @@ cxxtest b. Execute 'make menuconfig' in nuttx/ in order to start the reconfiguration process. - 3. At presenet (2012/11/02), this example builds only with exceptions + 3. At present (2012/11/02), this example builds only with exceptions disabled (CONFIG_UCLIBCXX_EXCEPTIONS=n). And even then, it will not run. - The reason that the example will will not run on the simulator has + The reason that the example will not run on the simulator has to do with when static constructors are enabled: In the simulator - it will attempt to execute the static constructros before main() + it will attempt to execute the static constructors before main() starts. BUT... NuttX is not initialized and this results in a crash. To really use this example, I will have to think of some way to postpone running C++ static initializers until NuttX has been - initialied. + initialized. mount diff --git a/nuttx/configs/sim/cxxtest/Make.defs b/nuttx/configs/sim/cxxtest/Make.defs index 7b0c524b4f..6f945cc519 100644 --- a/nuttx/configs/sim/cxxtest/Make.defs +++ b/nuttx/configs/sim/cxxtest/Make.defs @@ -93,6 +93,10 @@ LDLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(LD) CCLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(CC) LDFLAGS = $(ARCHSCRIPT) # For backward compatibility, same as CCLINKFLAGS +LIBSUPXX = ${shell $(CC) --print-file-name=libsupc++.a} +EXTRA_LIBPATHS = -L "${shell dirname "$(LIBSUPXX)"}" +EXTRA_LIBS = -lsupc++ + ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDLINKFLAGS += -g CCLINKFLAGS += -g @@ -105,8 +109,6 @@ ifeq ($(CONFIG_SIM_M32),y) LDFLAGS += -m32 endif -EXTRA_LIBS = -lsupc++ - MKDEP = $(TOPDIR)/tools/mkdeps.sh HOSTCC = gcc diff --git a/nuttx/configs/sim/cxxtest/defconfig b/nuttx/configs/sim/cxxtest/defconfig index d2fef0a554..1f99a63338 100644 --- a/nuttx/configs/sim/cxxtest/defconfig +++ b/nuttx/configs/sim/cxxtest/defconfig @@ -288,7 +288,7 @@ CONFIG_HAVE_CXX=y # uClibc++ Standard C++ Library # CONFIG_UCLIBCXX=y -CONFIG_UCLIBCXX_EXCEPTION=y +# CONFIG_UCLIBCXX_EXCEPTION is not set CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE=32 CONFIG_UCLIBCXX_HAVE_LIBSUPCXX=y diff --git a/nuttx/configs/sim/ostest/Make.defs b/nuttx/configs/sim/ostest/Make.defs index 201ff7a94f..975d59338e 100644 --- a/nuttx/configs/sim/ostest/Make.defs +++ b/nuttx/configs/sim/ostest/Make.defs @@ -36,76 +36,76 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -HOSTOS = ${shell uname -o 2>/dev/null || echo "Other"} +HOSTOS = ${shell uname -o 2>/dev/null || echo "Other"} ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - ARCHOPTIMIZATION = -g + ARCHOPTIMIZATION = -g else - ARCHOPTIMIZATION = -O2 + ARCHOPTIMIZATION = -O2 endif -ARCHCPUFLAGS = -fno-builtin -ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions -fno-rtti -ARCHPICFLAGS = -fpic -ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -ARCHWARNINGSXX = -Wall -Wshadow -ARCHDEFINES = -ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx -ARCHSCRIPT = +ARCHCPUFLAGS = -fno-builtin +ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions -fno-rtti +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +ARCHDEFINES = +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include +ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx +ARCHSCRIPT = ifeq ($(CONFIG_SIM_M32),y) - ARCHCPUFLAGS += -m32 - ARCHCPUFLAGSXX += -m32 + ARCHCPUFLAGS += -m32 + ARCHCPUFLAGSXX += -m32 endif -CROSSDEV = -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 = +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 -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -CXXFLAGS = $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGSXX) $(ARCHINCLUDESXX) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -AFLAGS = $(CFLAGS) -D__ASSEMBLY__ +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXFLAGS = $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGSXX) $(ARCHINCLUDESXX) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ -OBJEXT = .o -LIBEXT = .a +OBJEXT = .o +LIBEXT = .a ifeq ($(HOSTOS),Cygwin) - EXEEXT = .exe + EXEEXT = .exe else - EXEEXT = + EXEEXT = endif -LDLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(LD) -CCLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(CC) -LDFLAGS = $(ARCHSCRIPT) # For backward compatibility, same as CCLINKFLAGS +LDLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(LD) +CCLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(CC) +LDFLAGS = $(ARCHSCRIPT) # For backward compatibility, same as CCLINKFLAGS ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - LDLINKFLAGS += -g - CCLINKFLAGS += -g - LDFLAGS += -g + LDLINKFLAGS += -g + CCLINKFLAGS += -g + LDFLAGS += -g endif ifeq ($(CONFIG_SIM_M32),y) - LDLINKFLAGS += -melf_i386 - CCLINKFLAGS += -m32 - LDFLAGS += -m32 + LDLINKFLAGS += -melf_i386 + CCLINKFLAGS += -m32 + LDFLAGS += -m32 endif -MKDEP = $(TOPDIR)/tools/mkdeps.sh +MKDEP = $(TOPDIR)/tools/mkdeps.sh -HOSTCC = gcc -HOSTINCLUDES = -I. -HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -HOSTLDFLAGS = +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index 57db94e1e6..730bf66ef2 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -982,6 +982,35 @@ can be selected as follow: Where is one of the following: + cxxtest: + ------- + + The C++ standard libary test at apps/examples/cxxtest configuration. This + test is used to verify the uClibc++ port to NuttX. This configuration may + be selected as follows: + + cd /tools + ./configure.sh sim/cxxtest + + NOTES: + + 1. Before you can use this example, you must first install the uClibc++ + C++ library. This is located outside of the NuttX source tree at + misc/uClibc++ in SVN. See the README.txt file for instructions on + how to install uClibc++ + + 2. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 3. At present (2012/11/02), this example builds only with exceptions + disabled (CONFIG_UCLIBCXX_EXCEPTIONS=n). + elf: --- diff --git a/nuttx/configs/stm32f4discovery/cxxtest/Make.defs b/nuttx/configs/stm32f4discovery/cxxtest/Make.defs new file mode 100644 index 0000000000..f81d6ec2c1 --- /dev/null +++ b/nuttx/configs/stm32f4discovery/cxxtest/Make.defs @@ -0,0 +1,184 @@ +############################################################################ +# configs/stm32f4discovery/cxxtest/Make.defs +# +# 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk + +# Setup for the selected toolchain + +ifeq ($(CONFIG_STM32_CODESOURCERYW),y) + # CodeSourcery under Windows + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_CODESOURCERYL),y) + # CodeSourcery under Linux + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -O2 +endif +ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) + # Atollic toolchain under Windows + CROSSDEV = arm-atollic-eabi- + ARCROSSDEV = + WINTOOL = y +ifeq ($(CONFIG_ARCH_FPU),y) + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard +else + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +endif +ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) + # Atollic toolchain under Windows + CROSSDEV = arm-atollic-eabi- + ARCROSSDEV = arm-atollic-eabi- + WINTOOL = y +ifeq ($(CONFIG_ARCH_FPU),y) + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard +else + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +endif +ifeq ($(CONFIG_STM32_DEVKITARM),y) + # devkitARM under Windows + CROSSDEV = arm-eabi- + ARCROSSDEV = arm-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_RAISONANCE),y) + # Raisonance RIDE7 under Windows + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -Os +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +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} + +LDSCRIPT = ld.script +LIBSUPXX = ${shell $(CC) --print-file-name=libsupc++.a} +EXTRA_LIBPATHS = -L "${shell dirname "$(LIBSUPXX)"}" +EXTRA_LIBS = -lsupc++ + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/winlink.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" \ + -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" \ + -isystem "${shell cygpath -w $(TOPDIR)/include/uClibc++}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" + MAXOPTIMIZATION = -O2 +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include \ + -isystem $(TOPDIR)/include/cxx -isystem $(TOPDIR)/include/uClibc++ + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ifeq ($(CONFIG_UCLIBCXX_EXCEPTION),y) + ARCHCPUFLAGSXX = -fno-builtin +else + ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions +endif +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +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__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx/configs/stm32f4discovery/cxxtest/defconfig b/nuttx/configs/stm32f4discovery/cxxtest/defconfig new file mode 100644 index 0000000000..85b04c0ff9 --- /dev/null +++ b/nuttx/configs/stm32f4discovery/cxxtest/defconfig @@ -0,0 +1,573 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +CONFIG_ARCH_FLOAT_H=y +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM3S is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM4=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARCH_FPU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set +CONFIG_ARCH_IRQPRIO=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +CONFIG_ARCH_CHIP_STM32F407VG=y +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +CONFIG_STM32_STM32F40XX=y +CONFIG_STM32_CODESOURCERYW=y +# CONFIG_STM32_CODESOURCERYL is not set +# CONFIG_STM32_ATOLLIC_LITE is not set +# CONFIG_STM32_ATOLLIC_PRO is not set +# CONFIG_STM32_DEVKITARM is not set +# CONFIG_STM32_RAISONANCE is not set +# CONFIG_STM32_BUILDROOT is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_BKPSRAM is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CCMDATARAM is not set +# CONFIG_STM32_CRYP is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_IWDG is not set +# CONFIG_STM32_OTGFS is not set +# CONFIG_STM32_OTGHS is not set +# CONFIG_STM32_PWR is not set +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_USART1 is not set +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +# CONFIG_STM32_WWDG is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +# CONFIG_STM32_CCMEXCLUDE is not set + +# +# USB Host Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_STACKDUMP=y + +# +# Board Settings +# +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=114688 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="stm32f4discovery" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2012 +CONFIG_START_MONTH=11 +CONFIG_START_DAY=2 +CONFIG_DEV_CONSOLE=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_WAITPID is not set +# CONFIG_SCHED_ATEXIT is not set +CONFIG_SCHED_ONEXIT=y +CONFIG_SCHED_ONEXIT_MAX=4 +CONFIG_USER_ENTRYPOINT="cxxtest_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_POLL=y + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Stack and heap information +# +# CONFIG_CUSTOM_STACK is not set +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_SPI is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_USART2=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_FS_RAMMAP is not set + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_SYMTAB_ORDEREDBYNAME=y + +# +# Library Routines +# +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIBM=y +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set + +# +# Basic CXX Support +# +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# uClibc++ Standard C++ Library +# +CONFIG_UCLIBCXX=y +# CONFIG_UCLIBCXX_EXCEPTION is not set +CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE=32 +CONFIG_UCLIBCXX_HAVE_LIBSUPCXX=y + +# +# Application Configuration +# + +# +# Named Applications +# +# CONFIG_NAMEDAPP is not set + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +CONFIG_EXAMPLES_CXXTEST=y +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_NETTEST is not set +# CONFIG_EXAMPLES_NSH is not set +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WLAN is not set + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +# CONFIG_NSH_LIBRARY is not set + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +# CONFIG_SYSTEM_READLINE is not set + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# 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/stm32f4discovery/cxxtest/setenv.sh b/nuttx/configs/stm32f4discovery/cxxtest/setenv.sh new file mode 100755 index 0000000000..a3c297c766 --- /dev/null +++ b/nuttx/configs/stm32f4discovery/cxxtest/setenv.sh @@ -0,0 +1,75 @@ +#!/bin/bash +# configs/stm32f4discovery/cxxtest/setenv.sh +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +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" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm32f4discovery/ostest/defconfig b/nuttx/configs/stm32f4discovery/ostest/defconfig index 29d6b30eba..a644b42eca 100644 --- a/nuttx/configs/stm32f4discovery/ostest/defconfig +++ b/nuttx/configs/stm32f4discovery/ostest/defconfig @@ -251,7 +251,7 @@ CONFIG_SDCLONE_DISABLE=y # CONFIG_SCHED_WAITPID is not set # CONFIG_SCHED_ATEXIT is not set # CONFIG_SCHED_ONEXIT is not set -CONFIG_USER_ENTRYPOINT="elf_main" +CONFIG_USER_ENTRYPOINT="ostest_main" CONFIG_DISABLE_OS_API=y # CONFIG_DISABLE_CLOCK is not set # CONFIG_DISABLE_POSIX_TIMERS is not set From df77815b8b94d487809e1b2786bbe729de4bfbb8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 3 Nov 2012 00:00:56 +0000 Subject: [PATCH 070/206] Add support for wget POST interface; from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5301 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 2 + apps/examples/wgetjson/Kconfig | 4 + .../wgetjson/webserver/wgetjson/post_cmd.php | 3 + apps/examples/wgetjson/wgetjson_main.c | 124 ++++++++- apps/include/netutils/urldecode.h | 150 +++++------ apps/include/netutils/webclient.h | 12 + apps/netutils/codecs/urldecode.c | 67 +++++ apps/netutils/webclient/Kconfig | 5 + apps/netutils/webclient/webclient.c | 243 ++++++++++++++++-- apps/nshlib/nsh_netinit.c | 4 +- 10 files changed, 508 insertions(+), 106 deletions(-) create mode 100644 apps/examples/wgetjson/webserver/wgetjson/post_cmd.php diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 0b8b3cde74..ff90d50dd8 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -397,3 +397,5 @@ * apps/examples/wgetjson: Test example contributed by Darcy Gong * apps/examples/cxxtest: A test for the uClibc++ library provided by Qiang Yu and the RGMP team. + * apps/netutils/webclient, apps/netutils.codes, and apps/examples/wgetjson: + Add support for wget POST interface. Contributed by Darcy Gong. diff --git a/apps/examples/wgetjson/Kconfig b/apps/examples/wgetjson/Kconfig index f7f4f236cf..f7f9096902 100644 --- a/apps/examples/wgetjson/Kconfig +++ b/apps/examples/wgetjson/Kconfig @@ -20,4 +20,8 @@ config EXAMPLES_WGETJSON_URL string "wget URL" default "http://10.0.0.1/wgetjson/json_cmd.php" +config EXAMPLES_WGETPOST_URL + string "wget_post URL" + default "http://10.0.0.1/wgetjson/post_cmd.php" + endif diff --git a/apps/examples/wgetjson/webserver/wgetjson/post_cmd.php b/apps/examples/wgetjson/webserver/wgetjson/post_cmd.php new file mode 100644 index 0000000000..a352300754 --- /dev/null +++ b/apps/examples/wgetjson/webserver/wgetjson/post_cmd.php @@ -0,0 +1,3 @@ + \ No newline at end of file diff --git a/apps/examples/wgetjson/wgetjson_main.c b/apps/examples/wgetjson/wgetjson_main.c index a137af438c..8f82d1fcaa 100644 --- a/apps/examples/wgetjson/wgetjson_main.c +++ b/apps/examples/wgetjson/wgetjson_main.c @@ -58,13 +58,19 @@ ****************************************************************************/ #ifndef CONFIG_EXAMPLES_WGETJSON_MAXSIZE -# define CONFIG_EXAMPLES_WGETJSON_MAXSIZE 1024 +# define CONFIG_EXAMPLES_WGETJSON_MAXSIZE 1024 #endif -#ifndef CONFIG_EXAMPLES_EXAMPLES_WGETJSON_URL -# define CONFIG_EXAMPLES_EXAMPLES_WGETJSON_URL "http://10.0.0.1/wgetjson/json_cmd.php" +#ifndef CONFIG_EXAMPLES_WGETJSON_URL +# define CONFIG_EXAMPLES_WGETJSON_URL "http://10.0.0.1/wgetjson/json_cmd.php" #endif +#ifndef CONFIG_EXAMPLES_WGETPOST_URL +# define CONFIG_EXAMPLES_WGETPOST_URL "http://10.0.0.1/wgetjson/post_cmd.php" +#endif + +#define MULTI_POST_NDATA 3 + /**************************************************************************** * Private Types ****************************************************************************/ @@ -85,6 +91,21 @@ static bool g_has_json = false; * Private Functions ****************************************************************************/ +static void wgetjson_postdebug_callback(FAR char **buffer, int offset, + int datend, FAR int *buflen, + FAR void *arg) +{ + int len = datend - offset; + if (len <= 0) + { + printf("Callback No Data!\n"); + return; + } + + ((*buffer)[datend]) = '\0'; + printf("Callback Data(Length:%d):\n%s\n", len, &((*buffer)[offset])); +} + /**************************************************************************** * Name: wgetjson_callback ****************************************************************************/ @@ -271,20 +292,102 @@ static int wgetjson_json_parse(char *text) int wgetjson_main(int argc, char *argv[]) { char *buffer = NULL; - char *url = CONFIG_EXAMPLES_EXAMPLES_WGETJSON_URL; - int ret; + int buffer_len = 512; + char *url = CONFIG_EXAMPLES_WGETJSON_URL; + int ret = -1; + int option; + bool is_post = false; + bool is_post_multi = false; + bool badarg=false; + bool is_debug=false; + char *post_buff = NULL; + int post_buff_len = 0; + char *post_single_name = "type"; + char *post_single_value = "string"; + char *post_multi_names[MULTI_POST_NDATA] = {"name", "gender", "country"}; + char *post_multi_values[MULTI_POST_NDATA] = {"darcy", "man", "china"}; + wget_callback_t wget_cb = wgetjson_callback; - buffer = malloc(512); + while ((option = getopt(argc, argv, ":pPD")) != ERROR) + { + switch (option) + { + case 'p': + is_post = true; + break; + + case 'P': + is_post = true; + is_post_multi = true; + break; + + case 'D': + is_debug = true; + break; + + case ':': + badarg = true; + break; + + case '?': + default: + badarg = true; + break; + } + } + + if (badarg) + { + printf("usage: wgetjson -p(single post) -P(multi post) -D(debug wget callback)\n"); + return -1; + } + + if (is_debug) + { + wget_cb = wgetjson_postdebug_callback; + } + + if (is_post) + { + buffer_len = 512*2; + } + + buffer = malloc(buffer_len); wgetjson_json_release(); printf("URL: %s\n", url); - ret = wget(url, buffer, 512, wgetjson_callback, NULL); + if (is_post) + { + url = CONFIG_EXAMPLES_WGETPOST_URL; + if (is_post_multi) + { + post_buff_len = web_posts_strlen(post_multi_names, post_multi_values, MULTI_POST_NDATA); + post_buff = malloc(post_buff_len); + web_posts_str(post_buff, &post_buff_len, post_multi_names, post_multi_values, MULTI_POST_NDATA); + } + else + { + post_buff_len = web_post_strlen(post_single_name, post_single_value); + post_buff = malloc(post_buff_len); + web_post_str(post_buff, &post_buff_len, post_single_name, post_single_value); + } + + if (post_buff) + { + ret = wget_post(url, post_buff, buffer, buffer_len, wget_cb, NULL); + } + } + else + { + ret = wget(url, buffer, buffer_len, wget_cb , NULL); + } + if (ret < 0) { printf("get json size: %d\n",g_json_bufflen); } - else + else if (!is_debug) { g_has_json = false; if (wgetjson_json_parse(g_json_buff) == OK && g_has_json) @@ -301,5 +404,10 @@ int wgetjson_main(int argc, char *argv[]) wgetjson_json_release(); free(buffer); + if (post_buff) + { + free(post_buff); + } + return 0; } diff --git a/apps/include/netutils/urldecode.h b/apps/include/netutils/urldecode.h index 136d33041a..e3c726be09 100644 --- a/apps/include/netutils/urldecode.h +++ b/apps/include/netutils/urldecode.h @@ -1,74 +1,76 @@ -/**************************************************************************** - * apps/include/netutils/urldecode.h - * - * This file is part of the NuttX RTOS: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 __APPS_INCLUDE_NETUTILS_URLDECODE_H -#define __APPS_INCLUDE_NETUTILS_URLDECODE_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#ifdef __cplusplus -extern "C" -{ -#endif - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#ifdef CONFIG_CODECS_URLCODE_NEWMEMORY -char *url_encode(char *str); -char *url_decode(char *str); -#endif /* CONFIG_CODECS_URLCODE_NEWMEMORY */ - -#ifdef CONFIG_CODECS_URLCODE -char *urlencode(const char *src, const int src_len, char *dest, int *dest_len); -char *urldecode(const char *src, const int src_len, char *dest, int *dest_len); -#endif /* CONFIG_CODECS_URLCODE */ - -#ifdef CONFIG_CODECS_AVR_URLCODE -void urlrawdecode(char *urlbuf); -void urlrawencode(char *str,char *urlbuf); -#endif /* CONFIG_CODECS_AVR_URLCODE */ - -#ifdef __cplusplus -} -#endif - -#endif /* __APPS_INCLUDE_NETUTILS_URLDECODE_H */ - +/**************************************************************************** + * apps/include/netutils/urldecode.h + * + * This file is part of the NuttX RTOS: + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 __APPS_INCLUDE_NETUTILS_URLDECODE_H +#define __APPS_INCLUDE_NETUTILS_URLDECODE_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef __cplusplus +extern "C" +{ +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE_NEWMEMORY +char *url_encode(char *str); +char *url_decode(char *str); +#endif /* CONFIG_CODECS_URLCODE_NEWMEMORY */ + +#ifdef CONFIG_CODECS_URLCODE +char *urlencode(const char *src, const int src_len, char *dest, int *dest_len); +char *urldecode(const char *src, const int src_len, char *dest, int *dest_len); +int urlencode_len(const char *src, const int src_len); +int urldecode_len(const char *src, const int src_len); +#endif /* CONFIG_CODECS_URLCODE */ + +#ifdef CONFIG_CODECS_AVR_URLCODE +void urlrawdecode(char *urlbuf); +void urlrawencode(char *str,char *urlbuf); +#endif /* CONFIG_CODECS_AVR_URLCODE */ + +#ifdef __cplusplus +} +#endif + +#endif /* __APPS_INCLUDE_NETUTILS_URLDECODE_H */ + diff --git a/apps/include/netutils/webclient.h b/apps/include/netutils/webclient.h index 5c07f20ab6..3a4c4ea909 100644 --- a/apps/include/netutils/webclient.h +++ b/apps/include/netutils/webclient.h @@ -109,6 +109,13 @@ extern "C" { #define EXTERN extern #endif +EXTERN char *web_post_str(FAR char *buffer, int *size, FAR char *name, + FAR char *value); +EXTERN char *web_posts_str(FAR char *buffer, int *size, FAR char **name, + FAR char **value, int len); +EXTERN int web_post_strlen(FAR char *name, FAR char *value); +EXTERN int web_posts_strlen(FAR char **name, FAR char **value, int len); + /**************************************************************************** * Name: wget * @@ -141,6 +148,11 @@ extern "C" { EXTERN int wget(FAR const char *url, FAR char *buffer, int buflen, wget_callback_t callback, FAR void *arg); + +EXTERN int wget_post(FAR const char *url, FAR const char *posts, + FAR char *buffer, int buflen, wget_callback_t callback, + FAR void *arg); + #undef EXTERN #ifdef __cplusplus } diff --git a/apps/netutils/codecs/urldecode.c b/apps/netutils/codecs/urldecode.c index 9b3b609550..90cc3301bf 100644 --- a/apps/netutils/codecs/urldecode.c +++ b/apps/netutils/codecs/urldecode.c @@ -350,6 +350,73 @@ char *urldecode(const char *src, const int src_len, char *dest, int *dest_len) } #endif +/**************************************************************************** + * Name: urlencode_len + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE +int urlencode_len(const char *src, const int src_len) +{ + const unsigned char *pSrc; + const unsigned char *pEnd; + int len = 0; + + pEnd = (unsigned char *)src + src_len; + for (pSrc = (unsigned char *)src; pSrc < pEnd; pSrc++) + { + if ((*pSrc >= '0' && *pSrc <= '9') || + (*pSrc >= 'a' && *pSrc <= 'z') || + (*pSrc >= 'A' && *pSrc <= 'Z') || + (*pSrc == '_' || *pSrc == '-' || *pSrc == '.' || *pSrc == '~' || *pSrc == ' ')) + { + len++; + } + else + { + len+=3; + } + } + + return len; +} +#endif + +/**************************************************************************** + * Name: urldecode_len + ****************************************************************************/ + +#ifdef CONFIG_CODECS_URLCODE +int urldecode_len(const char *src, const int src_len) +{ + const unsigned char *pSrc; + const unsigned char *pEnd; + int len = 0; + unsigned char cHigh; + unsigned char cLow; + + pSrc = (unsigned char *)src; + pEnd = (unsigned char *)src + src_len; + while (pSrc < pEnd) + { + if (*pSrc == '%' && pSrc + 2 < pEnd) + { + cHigh = *(pSrc + 1); + cLow = *(pSrc + 2); + + if (IS_HEX_CHAR(cHigh) && IS_HEX_CHAR(cLow)) + { + pSrc += 2; + } + } + + len++; + pSrc++; + } + + return len; +} +#endif + /**************************************************************************** * Name: urlrawdecode * diff --git a/apps/netutils/webclient/Kconfig b/apps/netutils/webclient/Kconfig index c53195d483..68b13ce926 100644 --- a/apps/netutils/webclient/Kconfig +++ b/apps/netutils/webclient/Kconfig @@ -10,4 +10,9 @@ config NETUTILS_WEBCLIENT Enable support for the uIP web client. if NETUTILS_WEBCLIENT + +config NSH_WGET_USERAGENT + string "wget Usert Agent" + default "NuttX/6.xx.x (; http://www.nuttx.org/)" + endif diff --git a/apps/netutils/webclient/webclient.c b/apps/netutils/webclient/webclient.c index 8ce7b93a07..4dbd130ec5 100644 --- a/apps/netutils/webclient/webclient.c +++ b/apps/netutils/webclient/webclient.c @@ -69,9 +69,31 @@ #include #include + +#include #include #include +#if defined(CONFIG_NETUTILS_CODECS) +# if defined(CONFIG_CODECS_URLCODE) +# define WGET_USE_URLENCODE 1 +# include +# endif +# if defined(CONFIG_CODECS_BASE64) +# include +# endif +#endif + +#ifndef CONFIG_NSH_WGET_USERAGENT +# if CONFIG_VERSION_MAJOR != 0 || CONFIG_VERSION_MINOR != 0 +# define CONFIG_NSH_WGET_USERAGENT \ + "NuttX/" CONFIG_VERSION_STRING " (; http://www.nuttx.org/)" +# else +# define CONFIG_NSH_WGET_USERAGENT \ + "NuttX/6.xx.x (; http://www.nuttx.org/)" +# endif +#endif + /**************************************************************************** * Definitions ****************************************************************************/ @@ -92,6 +114,9 @@ #define ISO_cr 0x0d #define ISO_space 0x20 +#define WGET_MODE_GET 0 +#define WGET_MODE_POST 1 + /**************************************************************************** * Private Types ****************************************************************************/ @@ -136,10 +161,13 @@ static const char g_httpcontenttype[] = "content-type: "; static const char g_httphost[] = "host: "; static const char g_httplocation[] = "location: "; static const char g_httpget[] = "GET "; +static const char g_httppost[] = "POST "; static const char g_httpuseragentfields[] = "Connection: close\r\n" - "User-Agent: NuttX/0.4.x (; http://www.nuttx.org/)\r\n\r\n"; + "User-Agent: " + CONFIG_NSH_WGET_USERAGENT + "\r\n\r\n"; static const char g_http200[] = "200 "; static const char g_http301[] = "301 "; @@ -147,6 +175,11 @@ static const char g_http302[] = "302 "; static const char g_httpcrnl[] = "\r\n"; +static const char g_httpform[] = "Content-Type: application/x-www-form-urlencoded"; +static const char g_httpcontsize[] = "Content-Length: "; +//static const char g_httpconn[] = "Connection: Keep-Alive"; +//static const char g_httpcache[] = "Cache-Control: no-cache"; + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -162,11 +195,28 @@ static const char g_httpcrnl[] = "\r\n"; static char *wget_strcpy(char *dest, const char *src) { int len = strlen(src); + memcpy(dest, src, len); dest[len] = '\0'; return dest + len; } +/**************************************************************************** + * Name: wget_urlencode_strcpy + ****************************************************************************/ + +#ifdef WGET_USE_URLENCODE +static char *wget_urlencode_strcpy(char *dest, const char *src) +{ + int len = strlen(src); + int d_len; + + d_len = urlencode_len(src, len); + urlencode(src, len, dest, &d_len); + return dest + d_len; +} +#endif + /**************************************************************************** * Name: wget_parsestatus ****************************************************************************/ @@ -320,11 +370,7 @@ exit: } /**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: wget + * Name: wget_base * * Description: * Obtain the requested file from an HTTP server using the GET method. @@ -344,6 +390,7 @@ exit: * buflen - The size of the user provided buffer * callback - As data is obtained from the host, this function is * to dispose of each block of file data as it is received. + * mode - Indicates GET or POST modes * * Returned Value: * 0: if the GET operation completed successfully; @@ -351,15 +398,16 @@ exit: * ****************************************************************************/ -int wget(FAR const char *url, FAR char *buffer, int buflen, - wget_callback_t callback, FAR void *arg) +static int wget_base(FAR const char *url, FAR char *buffer, int buflen, + wget_callback_t callback, FAR void *arg, + FAR const char *posts, uint8_t mode) { struct sockaddr_in server; struct wget_s ws; bool redirected; - char *dest; + char *dest,post_size[8]; int sockfd; - int len; + int len,post_len; int ret = OK; /* Initialize the state structure */ @@ -380,6 +428,7 @@ int wget(FAR const char *url, FAR char *buffer, int buflen, set_errno(-ret); return ERROR; } + nvdbg("hostname='%s' filename='%s'\n", ws.hostname, ws.filename); /* The following sequence may repeat indefinitely if we are redirected */ @@ -435,19 +484,53 @@ int wget(FAR const char *url, FAR char *buffer, int buflen, /* Send the GET request */ - dest = ws.buffer; - dest = wget_strcpy(dest, g_httpget); - dest = wget_strcpy(dest, ws.filename); - *dest++ = ISO_space; - dest = wget_strcpy(dest, g_http10); - dest = wget_strcpy(dest, g_httpcrnl); - dest = wget_strcpy(dest, g_httphost); - dest = wget_strcpy(dest, ws.hostname); - dest = wget_strcpy(dest, g_httpcrnl); - dest = wget_strcpy(dest, g_httpuseragentfields); - len = dest - buffer; + dest = ws.buffer; + if (mode == WGET_MODE_POST) + { + dest = wget_strcpy(dest, g_httppost); + } + else + { + dest = wget_strcpy(dest, g_httpget); + } - ret = send(sockfd, buffer, len, 0); +#ifndef WGET_USE_URLENCODE + dest = wget_strcpy(dest, ws.filename); +#else + //dest = wget_urlencode_strcpy(dest, ws.filename); + dest = wget_strcpy(dest, ws.filename); +#endif + + *dest++ = ISO_space; + dest = wget_strcpy(dest, g_http10); + dest = wget_strcpy(dest, g_httpcrnl); + dest = wget_strcpy(dest, g_httphost); + dest = wget_strcpy(dest, ws.hostname); + dest = wget_strcpy(dest, g_httpcrnl); + + if (mode == WGET_MODE_POST) + { + dest = wget_strcpy(dest, g_httpform); + dest = wget_strcpy(dest, g_httpcrnl); + dest = wget_strcpy(dest, g_httpcontsize); + + /* Post content size */ + + post_len = strlen((char *)posts); + sprintf(post_size,"%d", post_len); + dest = wget_strcpy(dest, post_size); + dest = wget_strcpy(dest, g_httpcrnl); + } + + dest = wget_strcpy(dest, g_httpuseragentfields); + if (mode == WGET_MODE_POST) + { + dest = wget_strcpy(dest, (char *)posts); + } + + len = dest - buffer; + + ret = send(sockfd, buffer, len, 0); if (ret < 0) { ndbg("send failed: %d\n", errno); @@ -528,3 +611,119 @@ errout: close(sockfd); return ERROR; } + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: web_post_str + ****************************************************************************/ + +char *web_post_str(FAR char *buffer, int *size, FAR char *name, + FAR char *value) +{ + char *dst=buffer; + buffer = wget_strcpy(buffer,name); + buffer = wget_strcpy(buffer, "="); + buffer = wget_urlencode_strcpy(buffer,value); + *size = buffer - dst; + return dst; +} + +/**************************************************************************** + * Name: web_post_strlen + ****************************************************************************/ + +int web_post_strlen(FAR char *name, FAR char *value) +{ + return strlen(name) + urlencode_len(value,strlen(value)) + 1; +} + +/**************************************************************************** + * Name: web_posts_str + ****************************************************************************/ + +char *web_posts_str(FAR char *buffer, int *size, FAR char **name, + FAR char **value, int len) +{ + char *dst=buffer; + int wlen; + int i; + + for (i = 0; i < len; i++) + { + if (i > 0) + { + buffer = wget_strcpy(buffer,"&"); + } + + wlen = *size; + buffer = web_post_str(buffer, &wlen, name[i], value[i]); + buffer += wlen; + } + + *size=buffer-dst; + return dst; +} + +/**************************************************************************** + * Name: web_posts_strlen + ****************************************************************************/ + +int web_posts_strlen(FAR char **name, FAR char **value, int len) +{ + int wlen = 0; + int i; + + for (i = 0; i < len; i++) + { + wlen += web_post_strlen(name[i], value[i]); + } + + return wlen + len - 1; +} + +/**************************************************************************** + * Name: wget + * + * Description: + * Obtain the requested file from an HTTP server using the GET method. + * + * Note: If the function is passed a host name, it must already be in + * the resolver cache in order for the function to connect to the web + * server. It is therefore up to the calling module to implement the + * resolver calls and the signal handler used for reporting a resolv + * query answer. + * + * Input Parameters + * url - A pointer to a string containing either the full URL to + * the file to get (e.g., http://www.nutt.org/index.html, or + * http://192.168.23.1:80/index.html). + * buffer - A user provided buffer to receive the file data (also + * used for the outgoing GET request + * buflen - The size of the user provided buffer + * callback - As data is obtained from the host, this function is + * to dispose of each block of file data as it is received. + * + * Returned Value: + * 0: if the GET operation completed successfully; + * -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) +{ + return wget_base(url, buffer, buflen, callback, arg, NULL, WGET_MODE_GET); +} + +/**************************************************************************** + * Name: web_posts_strlen + ****************************************************************************/ + +int wget_post(FAR const char *url, FAR const char *posts, FAR char *buffer, + int buflen, wget_callback_t callback, FAR void *arg) +{ + return wget_base(url, buffer, buflen, callback, arg, posts, WGET_MODE_POST); +} diff --git a/apps/nshlib/nsh_netinit.c b/apps/nshlib/nsh_netinit.c index 535efd6a3c..bb1c73dffe 100644 --- a/apps/nshlib/nsh_netinit.c +++ b/apps/nshlib/nsh_netinit.c @@ -47,7 +47,7 @@ #include #include -#if defined(CONFIG_NSH_DHCPC) +#if defined(CONFIG_NSH_DHCPC) || defined(CONFIG_NSH_DNS) # include # include #endif @@ -135,7 +135,7 @@ int nsh_netinit(void) resolv_init(); #if defined(CONFIG_NSH_DNS) addr.s_addr = HTONL(CONFIG_NSH_DNSIPADDR); - resolv_conf(&addr.s_addr); + resolv_conf(&addr); #endif #endif From 1336ed8637d05a59271077e48501e44ef6150463 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 3 Nov 2012 13:02:31 +0000 Subject: [PATCH 071/206] uClibc++ updates git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5302 42af7a65-404d-4744-a932-0658087f49c3 --- misc/uClibc++/README.txt | 70 +++++++++++++++-- .../include/uClibc++/basic_definitions | 37 +++++---- misc/uClibc++/include/uClibc++/func_exception | 49 ++++++------ misc/uClibc++/libxx/uClibc++/new_opv.cxx | 77 ++++++++++++------- nuttx/libxx/Makefile | 11 ++- 5 files changed, 165 insertions(+), 79 deletions(-) diff --git a/misc/uClibc++/README.txt b/misc/uClibc++/README.txt index 6fedcb67fa..751f235878 100755 --- a/misc/uClibc++/README.txt +++ b/misc/uClibc++/README.txt @@ -6,9 +6,20 @@ originates from http://cxx.uclibc.org/ and has been adapted for NuttX by the RGMP team (http://rgmp.sourceforge.net/wiki/index.php/Main_Page). uClibc++ resides in the misc/ directory rather than in the main NuttX source -tree due to licensing issues: NuttX is licensed under the permissiv - modified BSD License; uClibc, on the other hand, islicensed under the - stricter GNU LGPL Version 3 license. +tree due to licensing issues: NuttX is licensed under the permissive +modified BSD License; uClibc, on the other hand, is licensed under the +stricter GNU LGPL Version 3 license. + +Contents: +^^^^^^^^^ + + o Installation of uClibc++ + o Dependencies + o NuttX Configuration File Changes + o Make.defs File Changes + o Building NuttX with uClibc++ + o Callbacks + o RGMP Installation of uClibc++ ^^^^^^^^^^^^^^^^^^^^^^^^ @@ -50,7 +61,6 @@ enabled. The following must be defined in your NuttX configuration file. There are many ways to provide math library support (see nuttx/README.txt). If you choose to use the NuttX math library, that is enabled as follows: - CONFIG_LIBM=y The math libraries depend on the float.h header file that is normally @@ -59,6 +69,10 @@ can be installed by setting: CONFIG_ARCH_FLOAT_H=y +Exception support can be enabled with: + + CONFIG_UCLIBCXX_EXCEPTION=y + Make.defs File Changes ^^^^^^^^^^^^^^^^^^^^^^ @@ -74,9 +88,25 @@ And, of course, you no long need to suppress exceptions or run-time typing: -ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions -fno-rtti +ARCHCPUFLAGSXX = -fno-builtin +If exceptions are disabled via CONFIG_UCLIBCXX_EXCEPTION=n, then -fno-exceptions +is still required. This logic would handle both cases: -I create the nuttx/configs/rgmp/x86/cxxtest/Make.def, add the two libs to EXTRA_LIBS to be linked -to NUTTX. The code. + ifeq ($(CONFIG_UCLIBCXX_EXCEPTION),y) + ARCHCPUFLAGSXX = -fno-builtin + else + ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions + endif + +To get the required libraries into to the NuttX build, it is necessary to add +them to EXTRA_LIBS and to EXTRA_LIBPATHS. + + LIBSUPXX = ${shell $(CC) --print-file-name=libsupc++.a} + EXTRA_LIBPATHS = -L "${shell dirname "$(LIBSUPXX)"}" + EXTRA_LIBS = -lsupc++ + +NOTE: This assumes that support for these options has been incorporated into +arch//src/Makefile. As of this writing that is true only for +the ARM and simulation platforms. Building NuttX with uClibc++ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -101,6 +131,34 @@ build, add the uClibc++ subdirectory to the dependency list, and add the uClibc++ subdirectory to the VPATH. That should, in principle, be all it takes. +Callbacks +^^^^^^^^^ + +The runtime will call this function if exception handling must be abandoned +for any reason. + + void std::terminate(void) throw(); + +NOTE: If exception handling is disabled via CONFIG_UCLIBCXX_EXCEPTION, then +this function is always called when an exception would have been thrown. + +By default, std::terminate() just calls abort(), but that can be changed +with std:terminate(). std::set_terminated takes a new handler function +as an argument and returns the old handler: + + typedef CODE void (*terminate_handler)(void); + terminate_handler std::set_terminate(std::terminate_handler func) throw(); + +The runtime will call this function if an exception is thrown which violates +the function's %exception specification: + + void std::unexpected(void) throw() + +This handler defaults to std::terminate but can be re-directed with: + + typedef CODE void (*unexpected_handler)(void); + unexpected_handler set_unexpected(unexpected_handler) throw(); + RGMP ^^^^ diff --git a/misc/uClibc++/include/uClibc++/basic_definitions b/misc/uClibc++/include/uClibc++/basic_definitions index ff2b29054e..dc4d531211 100644 --- a/misc/uClibc++/include/uClibc++/basic_definitions +++ b/misc/uClibc++/include/uClibc++/basic_definitions @@ -1,26 +1,31 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - This file is part of the uClibc++ Library. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ +/* Copyright (C) 2004 Garrett A. Kajmowicz + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #ifndef __BASIC_DEFINITIONS #define __BASIC_DEFINITIONS 1 +// NuttX Configuration + #include #include +// Deprecated + #include #pragma GCC visibility push(default) diff --git a/misc/uClibc++/include/uClibc++/func_exception b/misc/uClibc++/include/uClibc++/func_exception index 1b7bdd8c50..ecf446e6e4 100644 --- a/misc/uClibc++/include/uClibc++/func_exception +++ b/misc/uClibc++/include/uClibc++/func_exception @@ -1,38 +1,37 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include #include - #ifndef HEADER_IMPLEMENTATION_FUNC_EXCEPTION #define HEADER_IMPLEMENTATION_FUNC_EXCEPTION #pragma GCC visibility push(default) -namespace std{ - - _UCXXEXPORT void __throw_bad_alloc(); - _UCXXEXPORT void __throw_out_of_range(const char * message = 0); - _UCXXEXPORT void __throw_overflow_error(const char * message = 0); - _UCXXEXPORT void __throw_length_error(const char * message = 0); - _UCXXEXPORT void __throw_invalid_argument(const char * message = 0); +namespace std +{ + _UCXXEXPORT void __throw_bad_alloc(); + _UCXXEXPORT void __throw_out_of_range(const char *message = 0); + _UCXXEXPORT void __throw_overflow_error(const char *message = 0); + _UCXXEXPORT void __throw_length_error(const char *message = 0); + _UCXXEXPORT void __throw_invalid_argument(const char *message = 0); } #pragma GCC visibility pop diff --git a/misc/uClibc++/libxx/uClibc++/new_opv.cxx b/misc/uClibc++/libxx/uClibc++/new_opv.cxx index ef416e07b7..312d5adb31 100644 --- a/misc/uClibc++/libxx/uClibc++/new_opv.cxx +++ b/misc/uClibc++/libxx/uClibc++/new_opv.cxx @@ -1,35 +1,54 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz - - This file is part of the uClibc++ Library. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +/* Copyright (C) 2004 Garrett A. Kajmowicz + * + * This file is part of the uClibc++ Library. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include #include -#include -_UCXXEXPORT void* operator new[](std::size_t numBytes) throw(std::bad_alloc){ - //C++ stardard 5.3.4.8 requires that a valid pointer be returned for - //a call to new(0). Thus: - if(numBytes == 0){ - numBytes = 1; - } - void * p = malloc(numBytes); - if(p == 0){ - std::__throw_bad_alloc(); - } - return p; +#include + +#ifdef CONFIG_UCLIBCXX_EXCEPTION +# include +#else +# include +#endif + +_UCXXEXPORT void *operator new[](std::size_t numBytes) throw(std::bad_alloc) +{ + // C++ stardard 5.3.4.8 requires that a valid pointer be returned for + // a call to new(0). Thus: + + if (numBytes == 0) + { + numBytes = 1; + } + + // Allocate the memory + + void *p = malloc(numBytes); + if (p == 0) + { +#ifdef CONFIG_UCLIBCXX_EXCEPTION + std::__throw_bad_alloc(); +#else + std::terminate(); +#endif + } + + return p; } diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile index e563b9647e..a749269b09 100644 --- a/nuttx/libxx/Makefile +++ b/nuttx/libxx/Makefile @@ -40,9 +40,14 @@ ASRCS = CSRCS = -CXXSRCS = libxx_cxapurevirtual.cxx libxx_delete.cxx libxx_deletea.cxx -CXXSRCS += libxx_eabi_atexit.cxx libxx_cxa_atexit.cxx libxx_new.cxx -CXXSRCS += libxx_newa.cxx +CXXSRCS = libxx_cxapurevirtual.cxx libxx_eabi_atexit.cxx libxx_cxa_atexit.cxx + +# Some of the libxx/ files are not need if uClibc++ is installed because +# uClibx++ replaces them + +ifneq ($(CONFIG_UCLIBCXX),y) +CXXSRCS += libxx_delete.cxx libxx_deletea.cxx libxx_new.cxx libxx_newa.cxx +endif # Paths From bae3b4f9545636e5b933d6839ae3c936489feed8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 3 Nov 2012 15:48:03 +0000 Subject: [PATCH 072/206] Several small things git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5303 42af7a65-404d-4744-a932-0658087f49c3 --- misc/uClibc++/libxx/uClibc++/Make.defs | 4 ++ misc/uClibc++/libxx/uClibc++/eh_terminate.cxx | 2 +- nuttx/arch/arm/Kconfig | 3 + nuttx/include/cxx/cmath | 59 +++++++++++++++++++ 4 files changed, 67 insertions(+), 1 deletion(-) diff --git a/misc/uClibc++/libxx/uClibc++/Make.defs b/misc/uClibc++/libxx/uClibc++/Make.defs index b8f7a70920..335ae8db1b 100644 --- a/misc/uClibc++/libxx/uClibc++/Make.defs +++ b/misc/uClibc++/libxx/uClibc++/Make.defs @@ -44,10 +44,14 @@ CXXSRCS += new_opvnt.cxx numeric.cxx ostream.cxx queue.cxx set.cxx CXXSRCS += sstream.cxx stack.cxx streambuf.cxx string.cxx typeinfo.cxx CXXSRCS += utility.cxx valarray.cxx vector.cxx +# Exception handling logic + ifeq ($(CONFIG_UCLIBCXX_EXCEPTION),y) CXXSRCS += exception.cxx func_exception.cxx stdexcept.cxx endif +# libsupc++ replacement + ifneq ($(CONFIG_UCLIBCXX_HAVE_LIBSUPCXX),y) CXXSRCS += eh_alloc.cxx eh_globals.cxx eh_terminate.cxx endif diff --git a/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx b/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx index 1d1aa9eb7a..5b9e1aa2e0 100644 --- a/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx +++ b/misc/uClibc++/libxx/uClibc++/eh_terminate.cxx @@ -1,4 +1,4 @@ -/* Copyright (C) 2004 Garrett A. Kajmowicz +/* Copyright (C) 2004 Garrett A. Kajmowicz * * This file is part of the uClibc++ Library. * diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig index 02a8719943..9bec34ff1e 100644 --- a/nuttx/arch/arm/Kconfig +++ b/nuttx/arch/arm/Kconfig @@ -155,6 +155,9 @@ config ARCH_CHIP default "stm32" if ARCH_CHIP_STM32 default "str71x" if ARCH_CHIP_STR71X +config ARCH_HAVE_CMNVECTOR + bool + config ARMV7M_CMNVECTOR bool "Use common ARMv7-M vectors" default n diff --git a/nuttx/include/cxx/cmath b/nuttx/include/cxx/cmath index 7cb3a2109a..55c7c1dcc7 100644 --- a/nuttx/include/cxx/cmath +++ b/nuttx/include/cxx/cmath @@ -40,6 +40,9 @@ // Included Files //*************************************************************************** +#include +#include + #include //*************************************************************************** @@ -48,6 +51,33 @@ namespace std { +#if CONFIG_HAVE_FLOAT + using ::acosf; + using ::asinf; + using ::atanf; + using ::atan2f; + using ::ceilf; + using ::cosf; + using ::coshf; + using ::expf; + using ::fabsf; + using ::floorf; + using ::fmodf; + using ::frexpf; + using ::ldexpf; + using ::logf; + using ::log10f; + using ::log2f; + using ::modff; + using ::powf; + using ::sinf; + using ::sinhf; + using ::sqrtf; + using ::tanf; + using ::tanhf; +#endif + +#if CONFIG_HAVE_DOUBLE using ::acos; using ::asin; using ::atan; @@ -63,6 +93,7 @@ namespace std using ::ldexp; using ::log; using ::log10; + using ::log2; using ::modf; using ::pow; using ::sin; @@ -70,6 +101,34 @@ namespace std using ::sqrt; using ::tan; using ::tanh; +#endif + +#ifdef CONFIG_HAVE_LONG_DOUBLE + using ::acosl; + using ::asinl; + using ::atanl; + using ::atan2l; + using ::ceill; + using ::cosl; + using ::coshl; + using ::expl; + using ::fabsl; + using ::floorl; + using ::fmodl; + using ::frexpl; + using ::ldexpl; + using ::logl; + using ::log10l; + using ::log2l; + using ::modfl; + using ::powl; + using ::sinl; + using ::sinhl; + using ::sqrtl; + using ::tanl; + using ::tanhl; +#endif + } #endif // __INCLUDE_CXX_CMATH From 0062c0322665d7e117d4c86b0daec806e893e62a Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 3 Nov 2012 16:14:40 +0000 Subject: [PATCH 073/206] More STM32 Value Line updates from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5304 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/stm32/Kconfig | 1 + .../arm/src/stm32/chip/stm32f10xxx_gpio.h | 23 ++++++ .../src/stm32/chip/stm32f10xxx_memorymap.h | 28 ++----- .../arch/arm/src/stm32/chip/stm32f10xxx_rcc.h | 78 +++++++++++++++---- nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c | 6 +- 5 files changed, 99 insertions(+), 37 deletions(-) diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index acfac81aa0..4fcaa756f2 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -138,6 +138,7 @@ config STM32_STM32F10XX config STM32_VALUELINE bool + select ARMV7M_CMNVECTOR config STM32_HIGHDENSITY bool diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h index a95d13100e..fa0969601f 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h @@ -59,6 +59,7 @@ #define STM32_AFIO_EXTICR2_OFFSET 0x000c /* External interrupt configuration register 2 */ #define STM32_AFIO_EXTICR3_OFFSET 0x0010 /* External interrupt configuration register 3 */ #define STM32_AFIO_EXTICR4_OFFSET 0x0014 /* External interrupt configuration register 4 */ +#define STM32_AFIO_MAPR2_OFFSET 0x001c /* AF remap and debug I/O configuration register 2 */ /* Register Addresses ***************************************************************/ @@ -373,5 +374,27 @@ #define AFIO_EXTICR4_EXTI15_SHIFT (12) /* Bits 15-12: EXTI 15 configuration */ #define AFIO_EXTICR4_EXTI15_MASK (AFIO_EXTICR_PORT_MASK << AFIO_EXTICR4_EXTI15_SHIFT) +/* AF remap and debug I/O configuration register 2 */ + +#ifdef CONFIG_STM32_VALUELINE +# define AFIO_MAPR2_TIM15_REMAP (1 << 0) /* Bit 0: TIM15 remapping */ +# define AFIO_MAPR2_TIM16_REMAP (1 << 1) /* Bit 1: TIM16 remapping */ +# define AFIO_MAPR2_TIM17_REMAP (1 << 2) /* Bit 2: TIM17 remapping */ +# define AFIO_MAPR2_CEC_REMAP (1 << 3) /* Bit 3: CEC remapping */ +# define AFIO_MAPR2_TIM1_DMA_REMAP (1 << 4) /* Bit 4: TIM1 DMA remapping */ +#else +# define AFIO_MAPR2_TIM9_REMAP (1 << 5) /* Bit 5: TIM9 remapping */ +# define AFIO_MAPR2_TIM10_REMAP (1 << 6) /* Bit 6: TIM10 remapping */ +# define AFIO_MAPR2_TIM11_REMAP (1 << 7) /* Bit 7: TIM11 remapping */ +#endif +#define AFIO_MAPR2_TIM13_REMAP (1 << 8) /* Bit 8: TIM13 remapping */ +#define AFIO_MAPR2_TIM14_REMAP (1 << 9) /* Bit 9: TIM14 remapping */ +#define AFIO_MAPR2_FSMC_NADV (1 << 10) /* Bit 10: NADV connect/disconnect */ +#ifdef CONFIG_STM32_VALUELINE +# define AFIO_MAPR2_TIM76_DAC_DMA_REMAP (1 << 11) /* Bit 11: TIM67_DAC DMA remapping */ +# define AFIO_MAPR2_TIM12_REMAP (1 << 12) /* Bit 12: TIM12 remapping */ +# define AFIO_MAPR2_MISC_REMAP (1 << 13) /* Bit 13: Miscellaneous features remapping */ +#endif + #endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F10XXX_GPIO_H */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h index e38414f311..a1d2e26d30 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h @@ -60,14 +60,9 @@ #define STM32_TIM5_BASE 0x40000c00 /* 0x40000c00 - 0x40000fff: TIM5 timer */ #define STM32_TIM6_BASE 0x40001000 /* 0x40001000 - 0x400013ff: TIM6 timer */ #define STM32_TIM7_BASE 0x40001400 /* 0x40001400 - 0x400007ff: TIM7 timer */ -#if defined(CONFIG_STM32_VALUELINE) -# define STM32_TIM12_BASE 0x40001800 /* 0x40001800 - 0x40001bff: TIM12 timer */ -# define STM32_TIM13_BASE 0x40001c00 /* 0x40001c00 - 0x40001fff: TIM13 timer */ -# define STM32_TIM14_BASE 0x40002000 /* 0x40002000 - 0x400023ff: TIM14 timer */ - /* 0x40002400 - 0x400027ff: Reserved */ -#else - /* 0x40001800 - 0x40027fff: Reserved */ -#endif +#define STM32_TIM12_BASE 0x40001800 /* 0x40001800 - 0x40001bff: TIM12 timer */ +#define STM32_TIM13_BASE 0x40001c00 /* 0x40001c00 - 0x40001fff: TIM13 timer */ +#define STM32_TIM14_BASE 0x40002000 /* 0x40002000 - 0x400023ff: TIM14 timer */ #define STM32_RTC_BASE 0x40002800 /* 0x40002800 - 0x40002bff: RTC */ #define STM32_WWDG_BASE 0x40002c00 /* 0x40002C00 - 0x40002fff: Window watchdog (WWDG) */ #define STM32_IWDG_BASE 0x40003000 /* 0x40003000 - 0x400033ff: Independent watchdog (IWDG) */ @@ -90,13 +85,8 @@ #define STM32_BKP_BASE 0x40006c00 /* 0x40006c00 - 0x40006fff: Backup registers (BKP) */ #define STM32_PWR_BASE 0x40007000 /* 0x40007000 - 0x400073ff: Power control PWR */ #define STM32_DAC_BASE 0x40007400 /* 0x40007400 - 0x400077ff: DAC */ -#if defined(CONFIG_STM32_VALUELINE) -# define STM32_CEC_BASE 0x40007800 /* 0x40007800 - 0x40007bff: CEC */ +#define STM32_CEC_BASE 0x40007800 /* 0x40007800 - 0x40007bff: CEC */ /* 0x40007c00 - 0x4000ffff: Reserved */ -#else - /* 0x40007800 - 0x4000ffff: Reserved */ -#endif - /* APB2 bus */ #define STM32_AFIO_BASE 0x40010000 /* 0x40010000 - 0x400103ff: AFIO */ @@ -115,15 +105,11 @@ #define STM32_TIM8_BASE 0x40013400 /* 0x40013400 - 0x400137ff: TIM8 timer */ #define STM32_USART1_BASE 0x40013800 /* 0x40013800 - 0x40013bff: USART1 */ #define STM32_ADC3_BASE 0x40012800 /* 0x40012800 - 0x40013c00: ADC3 */ -#if defined(CONFIG_STM32_VALUELINE) /* 0x40013c00 - 0x40013fff: Reserved */ -# define STM32_TIM15_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM15 */ -# define STM32_TIM16_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM16 */ -# define STM32_TIM17_BASE 0x40014800 /* 0x40014800 - 0x40014bff: TIM17 */ +#define STM32_TIM15_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM15 */ +#define STM32_TIM16_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM16 */ +#define STM32_TIM17_BASE 0x40014800 /* 0x40014800 - 0x40014bff: TIM17 */ /* 0x40014c00 - 0x4001ffff: Reserved */ -#else - /* 0x40013c00 - 0x4001ffff: Reserved */ -#endif /* AHB bus */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h index 60365b9218..1a792b7ebc 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h @@ -163,7 +163,9 @@ # define RCC_CFGR_PLLMUL_CLKx14 (12 << RCC_CFGR_PLLMUL_SHIFT) /* 1100: PLL input clock x 14 */ # define RCC_CFGR_PLLMUL_CLKx15 (13 << RCC_CFGR_PLLMUL_SHIFT) /* 1101: PLL input clock x 15 */ # define RCC_CFGR_PLLMUL_CLKx16 (14 << RCC_CFGR_PLLMUL_SHIFT) /* 111x: PLL input clock x 16 */ -#define RCC_CFGR_USBPRE (1 << 22) /* Bit 22: USB prescaler */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_CFGR_USBPRE (1 << 22) /* Bit 22: USB prescaler */ +#endif #define RCC_CFGR_MCO_SHIFT (24) /* Bits 26-24: Microcontroller Clock Output */ #define RCC_CFGR_MCO_MASK (0x0f << RCC_CFGR_MCO_SHIFT) # define RCC_CFGR_NOCLK (0 << RCC_CFGR_MCO_SHIFT) /* 0xx: No clock */ @@ -207,12 +209,22 @@ #define TCC_APB2RSTR_IOPFRST (1 << 7) /* Bit 7: IO port F reset */ #define TCC_APB2RSTR_IOPGRST (1 << 8) /* Bit 8: IO port G reset */ #define RCC_APB2RSTR_ADC1RST (1 << 9) /* Bit 9: ADC 1 interface reset */ -#define RCC_APB2RSTR_ADC2RST (1 << 10) /* Bit 10: ADC 2 interface reset */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2RSTR_ADC2RST (1 << 10) /* Bit 10: ADC 2 interface reset */ +#endif #define RCC_APB2RSTR_TIM1RST (1 << 11) /* Bit 11: TIM1 Timer reset */ #define RCC_APB2RSTR_SPI1RST (1 << 12) /* Bit 12: SPI 1 reset */ -#define RCC_APB2RSTR_TIM8RST (1 << 13) /* Bit 13: TIM8 Timer reset */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2RSTR_TIM8RST (1 << 13) /* Bit 13: TIM8 Timer reset */ +#endif #define RCC_APB2RSTR_USART1RST (1 << 14) /* Bit 14: USART1 reset */ -#define RCC_APB2RSTR_ADC3RST (1 << 15) /* Bit 15: ADC3 interface reset */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2RSTR_ADC3RST (1 << 15) /* Bit 15: ADC3 interface reset */ +#else +# define RCC_APB2RSTR_TIM15RST (1 << 16) /* Bit 16: TIM15 reset */ +# define RCC_APB2RSTR_TIM16RST (1 << 17) /* Bit 17: TIM16 reset */ +# define RCC_APB2RSTR_TIM17RST (1 << 18) /* Bit 18: TIM17 reset */ +#endif /* APB1 Peripheral reset register */ @@ -222,6 +234,11 @@ #define RCC_APB1RSTR_TIM5RST (1 << 3) /* Bit 3: Timer 5 reset */ #define RCC_APB1RSTR_TIM6RST (1 << 4) /* Bit 4: Timer 6 reset */ #define RCC_APB1RSTR_TIM7RST (1 << 5) /* Bit 5: Timer 7 reset */ +#ifdef CONFIG_STM32_VALUELINE +# define RCC_APB1RSTR_TIM12RST (1 << 6) /* Bit 6: TIM12 reset */ +# define RCC_APB1RSTR_TIM13RST (1 << 7) /* Bit 7: TIM13 reset */ +# define RCC_APB1RSTR_TIM14RST (1 << 8) /* Bit 8: TIM14 reset */ +#endif #define RCC_APB1RSTR_WWDGRST (1 << 11) /* Bit 11: Window Watchdog reset */ #define RCC_APB1RSTR_SPI2RST (1 << 14) /* Bit 14: SPI 2 reset */ #define RCC_APB1RSTR_SPI3RST (1 << 15) /* Bit 15: SPI 3 reset */ @@ -231,12 +248,17 @@ #define RCC_APB1RSTR_UART5RST (1 << 20) /* Bit 18: UART 5 reset */ #define RCC_APB1RSTR_I2C1RST (1 << 21) /* Bit 21: I2C 1 reset */ #define RCC_APB1RSTR_I2C2RST (1 << 22) /* Bit 22: I2C 2 reset */ -#define RCC_APB1RSTR_USBRST (1 << 23) /* Bit 23: USB reset */ -#define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ -#define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB1RSTR_USBRST (1 << 23) /* Bit 23: USB reset */ +# define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ +# define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */ +#endif #define RCC_APB1RSTR_BKPRST (1 << 27) /* Bit 27: Backup interface reset */ #define RCC_APB1RSTR_PWRRST (1 << 28) /* Bit 28: Power interface reset */ #define RCC_APB1RSTR_DACRST (1 << 29) /* Bit 29: DAC interface reset */ +#ifdef CONFIG_STM32_VALUELINE +# define RCC_APB1RSTR_CECRST (1 << 30) /* Bit 30: CEC reset */ +#endif /* AHB Peripheral Clock enable register */ @@ -246,7 +268,9 @@ #define RCC_AHBENR_FLITFEN (1 << 4) /* Bit 4: FLITF clock enable */ #define RCC_AHBENR_CRCEN (1 << 6) /* Bit 6: CRC clock enable */ #define RCC_AHBENR_FSMCEN (1 << 8) /* Bit 8: FSMC clock enable */ -#define RCC_AHBENR_SDIOEN (1 << 10) /* Bit 10: SDIO clock enable */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_AHBENR_SDIOEN (1 << 10) /* Bit 10: SDIO clock enable */ +#endif #ifdef CONFIG_STM32_CONNECTIVITYLINE # define RCC_AHBENR_ETHMACEN (1 << 14) /* Bit 14: Ethernet MAC clock enable */ # define RCC_AHBENR_ETHMACTXEN (1 << 15) /* Bit 15: Ethernet MAC TX clock enable */ @@ -272,12 +296,22 @@ #define RCC_APB2ENR_IOPFEN (1 << 7) /* Bit 7: I/O port F clock enable */ #define RCC_APB2ENR_IOPGEN (1 << 8) /* Bit 8: I/O port G clock enable */ #define RCC_APB2ENR_ADC1EN (1 << 9) /* Bit 9: ADC 1 interface clock enable */ -#define RCC_APB2ENR_ADC2EN (1 << 10) /* Bit 10: ADC 2 interface clock enable */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2ENR_ADC2EN (1 << 10) /* Bit 10: ADC 2 interface clock enable */ +#endif #define RCC_APB2ENR_TIM1EN (1 << 11) /* Bit 11: TIM1 Timer clock enable */ #define RCC_APB2ENR_SPI1EN (1 << 12) /* Bit 12: SPI 1 clock enable */ -#define RCC_APB2ENR_TIM8EN (1 << 13) /* Bit 13: TIM8 Timer clock enable */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2ENR_TIM8EN (1 << 13) /* Bit 13: TIM8 Timer clock enable */ +#endif #define RCC_APB2ENR_USART1EN (1 << 14) /* Bit 14: USART1 clock enable */ -#define RCC_APB2ENR_ADC3EN (1 << 15) /* Bit 14: ADC3 interface clock enable */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2ENR_ADC3EN (1 << 15) /* Bit 14: ADC3 interface clock enable */ +#else +# define RCC_APB2ENR_TIM15EN (1 << 16) /* Bit 16: TIM15 clock enable */ +# define RCC_APB2ENR_TIM16EN (1 << 17) /* Bit 17: TIM16 clock enable */ +# define RCC_APB2ENR_TIM17EN (1 << 18) /* Bit 18: TIM17 clock enable */ +#endif /* APB1 Peripheral Clock enable register */ @@ -287,6 +321,11 @@ #define RCC_APB1ENR_TIM5EN (1 << 3) /* Bit 3: Timer 5 clock enable */ #define RCC_APB1ENR_TIM6EN (1 << 4) /* Bit 4: Timer 6 clock enable */ #define RCC_APB1ENR_TIM7EN (1 << 5) /* Bit 5: Timer 7 clock enable */ +#ifdef CONFIG_STM32_VALUELINE +# define RCC_APB1ENR_TIM12EN (1 << 6) /* Bit 6: Timer 12 clock enable */ +# define RCC_APB1ENR_TIM13EN (1 << 7) /* Bit 7: Timer 13 clock enable */ +# define RCC_APB1ENR_TIM14EN (1 << 8) /* Bit 8: Timer 14 clock enable */ +#endif #define RCC_APB1ENR_WWDGEN (1 << 11) /* Bit 11: Window Watchdog clock enable */ #define RCC_APB1ENR_SPI2EN (1 << 14) /* Bit 14: SPI 2 clock enable */ #define RCC_APB1ENR_SPI3EN (1 << 15) /* Bit 15: SPI 3 clock enable */ @@ -296,12 +335,17 @@ #define RCC_APB1ENR_UART5EN (1 << 20) /* Bit 20: UART 5 clock enable */ #define RCC_APB1ENR_I2C1EN (1 << 21) /* Bit 21: I2C 1 clock enable */ #define RCC_APB1ENR_I2C2EN (1 << 22) /* Bit 22: I2C 2 clock enable */ -#define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */ -#define RCC_APB1ENR_CAN1EN (1 << 25) /* Bit 25: CAN1 clock enable */ -#define RCC_APB1ENR_CAN2EN (1 << 26) /* Bit 25: CAN2 clock enable */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */ +# define RCC_APB1ENR_CAN1EN (1 << 25) /* Bit 25: CAN1 clock enable */ +# define RCC_APB1ENR_CAN2EN (1 << 26) /* Bit 25: CAN2 clock enable */ +#endif #define RCC_APB1ENR_BKPEN (1 << 27) /* Bit 27: Backup interface clock enable */ #define RCC_APB1ENR_PWREN (1 << 28) /* Bit 28: Power interface clock enable */ #define RCC_APB1ENR_DACEN (1 << 29) /* Bit 29: DAC interface clock enable */ +#ifdef CONFIG_STM32_VALUELINE +# define RCC_APB1ENR_CECEN (1 << 30) /* Bit 30: CEC clock enable */ +#endif /* Backup domain control register */ @@ -331,7 +375,7 @@ #if defined(CONFIG_STM32_VALUELINE) || defined(CONFIG_STM32_CONNECTIVITYLINE) -/* Clock configuration register 2 (For connectivity line only) */ +/* Clock configuration register 2 (For value line and connectivity line only) */ #define RCC_CFGR2_PREDIV1_SHIFT (0) #define RCC_CFGR2_PREDIV1_MASK (0x0f << RCC_CFGR2_PREDIV1_SHIFT) @@ -352,6 +396,10 @@ # define RCC_CFGR2_PREDIV1d15 (14 << RCC_CFGR2_PREDIV1_SHIFT) # define RCC_CFGR2_PREDIV1d16 (15 << RCC_CFGR2_PREDIV1_SHIFT) +#endif + +#ifdef CONFIG_STM32_CONNECTIVITYLINE + #define RCC_CFGR2_PREDIV2_SHIFT (4) #define RCC_CFGR2_PREDIV2_MASK (0x0f << RCC_CFGR2_PREDIV2_SHIFT) # define RCC_CFGR2_PREDIV2d1 (0 << RCC_CFGR2_PREDIV2_SHIFT) diff --git a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c index 47ed5e016b..ed767db77f 100644 --- a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c +++ b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c @@ -92,7 +92,11 @@ static inline void rcc_reset(void) putreg32(regval, STM32_RCC_CR); regval = getreg32(STM32_RCC_CFGR); /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */ - regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK|RCC_CFGR_USBPRE); + regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK +#ifndef CONFIG_STM32_VALUELINE + |RCC_CFGR_USBPRE +#endif + ); putreg32(regval, STM32_RCC_CFGR); putreg32(0, STM32_RCC_CIR); /* Disable all interrupts */ From f561a5ab0302e260c2df461cc9c32c9b1535c243 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 4 Nov 2012 15:12:55 +0000 Subject: [PATCH 074/206] RGMP 4.0 update from Qiang Yu git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5305 42af7a65-404d-4744-a932-0658087f49c3 --- misc/tools/README.txt | 7 + misc/uClibc++/libxx/uClibc++/Make.defs | 1 + misc/uClibc++/libxx/uClibc++/vterminate.cxx | 22 + nuttx/ChangeLog | 1 + .../arm/src/stm32/chip/stm32f10xxx_gpio.h | 2 +- nuttx/arch/rgmp/include/arch.h | 1 - nuttx/arch/rgmp/include/irq.h | 11 +- nuttx/arch/rgmp/include/math.h | 194 ++++++++ nuttx/arch/rgmp/include/stdbool.h | 5 - .../arch/rgmp/include/x86/arch/subarch/arch.h | 11 +- nuttx/arch/rgmp/src/Makefile | 18 +- nuttx/arch/rgmp/src/bridge.c | 59 ++- nuttx/arch/rgmp/src/cxx.c | 19 + nuttx/arch/rgmp/src/nuttx.c | 299 ++++++------ nuttx/arch/rgmp/src/rgmp.c | 93 ++-- nuttx/arch/rgmp/src/x86/arch_nuttx.c | 29 +- nuttx/arch/rgmp/src/x86/com.c | 6 +- nuttx/arch/rgmp/src/x86/sigentry.S | 4 +- nuttx/configs/rgmp/x86/cxxtest/Make.defs | 134 ++++++ nuttx/configs/rgmp/x86/cxxtest/appconfig | 39 ++ nuttx/configs/rgmp/x86/cxxtest/defconfig | 428 ++++++++++++++++++ nuttx/configs/rgmp/x86/cxxtest/setenv.sh | 47 ++ nuttx/configs/rgmp/x86/default/Make.defs | 2 +- nuttx/configs/rgmp/x86/default/defconfig | 5 +- nuttx/configs/rgmp/x86/helloxx/Make.defs | 132 ++++++ nuttx/configs/rgmp/x86/helloxx/appconfig | 51 +++ nuttx/configs/rgmp/x86/helloxx/defconfig | 428 ++++++++++++++++++ nuttx/configs/rgmp/x86/helloxx/setenv.sh | 47 ++ nuttx/configs/rgmp/x86/nsh/Make.defs | 2 +- nuttx/configs/rgmp/x86/nsh/appconfig | 1 + nuttx/configs/rgmp/x86/nsh/defconfig | 9 + nuttx/drivers/net/e1000.c | 297 ++++++------ nuttx/drivers/net/e1000.h | 4 +- nuttx/drivers/net/vnet.c | 327 +++++++------ nuttx/lib/Kconfig | 7 + nuttx/lib/string/lib_strchr.c | 2 + 36 files changed, 2171 insertions(+), 573 deletions(-) create mode 100644 misc/uClibc++/libxx/uClibc++/vterminate.cxx create mode 100644 nuttx/arch/rgmp/src/cxx.c create mode 100644 nuttx/configs/rgmp/x86/cxxtest/Make.defs create mode 100644 nuttx/configs/rgmp/x86/cxxtest/appconfig create mode 100644 nuttx/configs/rgmp/x86/cxxtest/defconfig create mode 100644 nuttx/configs/rgmp/x86/cxxtest/setenv.sh create mode 100644 nuttx/configs/rgmp/x86/helloxx/Make.defs create mode 100644 nuttx/configs/rgmp/x86/helloxx/appconfig create mode 100644 nuttx/configs/rgmp/x86/helloxx/defconfig create mode 100644 nuttx/configs/rgmp/x86/helloxx/setenv.sh diff --git a/misc/tools/README.txt b/misc/tools/README.txt index ebda8b160a..4a141cb941 100644 --- a/misc/tools/README.txt +++ b/misc/tools/README.txt @@ -41,6 +41,13 @@ kconfig-frontends-3.3.0-1-libintl.patch make make install + See: http://ymorin.is-a-geek.org/hg/kconfig-frontends/file/tip/docs/known-issues.txt + + Update: According to the release notes, version 3.6.0 (and above) + will build on Cygwin with not patches: + + http://ymorin.is-a-geek.org/download/kconfig-frontends/ + kconfig-macos.path This is a patch to make the kconfig-frontends build on Mac OS X. diff --git a/misc/uClibc++/libxx/uClibc++/Make.defs b/misc/uClibc++/libxx/uClibc++/Make.defs index 335ae8db1b..40aee6e473 100644 --- a/misc/uClibc++/libxx/uClibc++/Make.defs +++ b/misc/uClibc++/libxx/uClibc++/Make.defs @@ -52,6 +52,7 @@ endif # libsupc++ replacement +# CXXSRCS += vterminate.C ifneq ($(CONFIG_UCLIBCXX_HAVE_LIBSUPCXX),y) CXXSRCS += eh_alloc.cxx eh_globals.cxx eh_terminate.cxx endif diff --git a/misc/uClibc++/libxx/uClibc++/vterminate.cxx b/misc/uClibc++/libxx/uClibc++/vterminate.cxx new file mode 100644 index 0000000000..09d19b19ff --- /dev/null +++ b/misc/uClibc++/libxx/uClibc++/vterminate.cxx @@ -0,0 +1,22 @@ +/* Copyright (C) 2012 Gregory Nutt + * + * This file is part of the uClibc++ Library. + * + * A replacement for __gnu_cxx::terminate + */ + +#include +#include +#include +#include + +// This is a brain-dead replacement for __gnu_cxx::__verbose_terminate_handler + +namespace __gnu_cxx +{ + void __verbose_terminate_handler() + { + ldbg("PID %d: Terminating...\n", getpid()); + abort(); + } +} diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index b357a629d2..06bc13fd6e 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3561,4 +3561,5 @@ constructors before main() starts. BUT... NuttX is not initialized and this results in a crash. On the STM324Discovery, I will have better control over when the static constructors run. + * RGMP 4.0 updated from Qiany Yu. diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h index fa0969601f..d339fc15ef 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h @@ -391,7 +391,7 @@ #define AFIO_MAPR2_TIM14_REMAP (1 << 9) /* Bit 9: TIM14 remapping */ #define AFIO_MAPR2_FSMC_NADV (1 << 10) /* Bit 10: NADV connect/disconnect */ #ifdef CONFIG_STM32_VALUELINE -# define AFIO_MAPR2_TIM76_DAC_DMA_REMAP (1 << 11) /* Bit 11: TIM67_DAC DMA remapping */ +# define AFIO_MAPR2_TIM67_DAC_DMA_REMAP (1 << 11) /* Bit 11: TIM67_DAC DMA remapping */ # define AFIO_MAPR2_TIM12_REMAP (1 << 12) /* Bit 12: TIM12 remapping */ # define AFIO_MAPR2_MISC_REMAP (1 << 13) /* Bit 13: Miscellaneous features remapping */ #endif diff --git a/nuttx/arch/rgmp/include/arch.h b/nuttx/arch/rgmp/include/arch.h index c93397baa4..32eb16ee36 100644 --- a/nuttx/arch/rgmp/include/arch.h +++ b/nuttx/arch/rgmp/include/arch.h @@ -46,7 +46,6 @@ #include - struct up_wait { struct up_wait *next; _TCB *task; diff --git a/nuttx/arch/rgmp/include/irq.h b/nuttx/arch/rgmp/include/irq.h index 00c9775609..b0411b2ab4 100644 --- a/nuttx/arch/rgmp/include/irq.h +++ b/nuttx/arch/rgmp/include/irq.h @@ -44,12 +44,13 @@ #ifndef __ASSEMBLY__ -#include #include + #include +#include struct xcptcontext { - struct Trapframe *tf; + struct rgmp_context ctx; // for signal using unsigned int save_eip; unsigned int save_eflags; @@ -63,12 +64,14 @@ extern int nest_irq; static inline irqstate_t irqsave(void) { - return pushcli(); + unsigned long flags; + local_irq_save(flags); + return flags; } static inline void irqrestore(irqstate_t flags) { - popcli(flags); + local_irq_restore(flags); } #endif /* !__ASSEMBLY__ */ diff --git a/nuttx/arch/rgmp/include/math.h b/nuttx/arch/rgmp/include/math.h index 16992d63c6..24a68ee132 100644 --- a/nuttx/arch/rgmp/include/math.h +++ b/nuttx/arch/rgmp/include/math.h @@ -57,6 +57,200 @@ extern "C" { #include +// following functions are not implemented by RGMP math library +// don't use them +// declared here for cmath + +/* General Functions ********************************************************/ + +float ceilf (float x); +#if CONFIG_HAVE_DOUBLE +//double ceil (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double ceill (long double x); +#endif + +float floorf(float x); +#if CONFIG_HAVE_DOUBLE +//double floor (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double floorl(long double x); +#endif + +float fabsf (float x); +#if CONFIG_HAVE_DOUBLE +//double fabs (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double fabsl (long double x); +#endif + +float modff (float x, float *iptr); +#if CONFIG_HAVE_DOUBLE +//double modf (double x, double *iptr); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double modfl (long double x, long double *iptr); +#endif + +float fmodf (float x, float div); +#if CONFIG_HAVE_DOUBLE +//double fmod (double x, double div); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double fmodl (long double x, long double div); +#endif + +/* Exponential and Logarithmic Functions ************************************/ + +float powf (float b, float e); +#if CONFIG_HAVE_DOUBLE +//double pow (double b, double e); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double powl (long double b, long double e); +#endif + +float expf (float x); +#if CONFIG_HAVE_DOUBLE +//double exp (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double expl (long double x); +#endif + +float logf (float x); +#if CONFIG_HAVE_DOUBLE +//double log (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double logl (long double x); +#endif + +float log10f(float x); +#if CONFIG_HAVE_DOUBLE +//double log10 (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double log10l(long double x); +#endif + +float log2f (float x); +#if CONFIG_HAVE_DOUBLE +//double log2 (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double log2l (long double x); +#endif + +float sqrtf (float x); +#if CONFIG_HAVE_DOUBLE +//double sqrt (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double sqrtl (long double x); +#endif + +float ldexpf(float x, int n); +#if CONFIG_HAVE_DOUBLE +double ldexp (double x, int n); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double ldexpl(long double x, int n); +#endif + +float frexpf(float x, int *exp); +#if CONFIG_HAVE_DOUBLE +double frexp (double x, int *exp); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double frexpl(long double x, int *exp); +#endif + +/* Trigonometric Functions **************************************************/ + +float sinf (float x); +#if CONFIG_HAVE_DOUBLE +//double sin (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double sinl (long double x); +#endif + +float cosf (float x); +#if CONFIG_HAVE_DOUBLE +//double cos (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double cosl (long double x); +#endif + +float tanf (float x); +#if CONFIG_HAVE_DOUBLE +//double tan (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double tanl (long double x); +#endif + +float asinf (float x); +#if CONFIG_HAVE_DOUBLE +//double asin (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double asinl (long double x); +#endif + +float acosf (float x); +#if CONFIG_HAVE_DOUBLE +//double acos (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double acosl (long double x); +#endif + +float atanf (float x); +#if CONFIG_HAVE_DOUBLE +//double atan (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double atanl (long double x); +#endif + +float atan2f(float y, float x); +#if CONFIG_HAVE_DOUBLE +//double atan2 (double y, double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double atan2l(long double y, long double x); +#endif + +float sinhf (float x); +#if CONFIG_HAVE_DOUBLE +//double sinh (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double sinhl (long double x); +#endif + +float coshf (float x); +#if CONFIG_HAVE_DOUBLE +//double cosh (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double coshl (long double x); +#endif + +float tanhf (float x); +#if CONFIG_HAVE_DOUBLE +//double tanh (double x); +#endif +#ifdef CONFIG_HAVE_LONG_DOUBLE +long double tanhl (long double x); +#endif + #undef EXTERN #ifdef __cplusplus } diff --git a/nuttx/arch/rgmp/include/stdbool.h b/nuttx/arch/rgmp/include/stdbool.h index 993e0f7361..eb1bee1adb 100644 --- a/nuttx/arch/rgmp/include/stdbool.h +++ b/nuttx/arch/rgmp/include/stdbool.h @@ -58,9 +58,6 @@ * use _Bool8 as the underlying type. */ -#ifndef CONFIG_ARCH_RGMP -#define bool _Bool8 -#endif #define true 1 #define false 0 @@ -82,8 +79,6 @@ * as the underlying type. */ -#ifndef CONFIG_ARCH_RGMP typedef uint8_t _Bool8; -#endif #endif /* __ARCH_RGMP_INCLUDE_STDBOOL_H */ diff --git a/nuttx/arch/rgmp/include/x86/arch/subarch/arch.h b/nuttx/arch/rgmp/include/x86/arch/subarch/arch.h index 2f401c03b9..0637dbd39f 100644 --- a/nuttx/arch/rgmp/include/x86/arch/subarch/arch.h +++ b/nuttx/arch/rgmp/include/x86/arch/subarch/arch.h @@ -42,8 +42,11 @@ #ifndef __ASSEMBLY__ -#include +#ifdef __cplusplus +extern "C" { +#endif +#include static inline void up_mdelay(uint32_t msec) { @@ -52,9 +55,13 @@ static inline void up_mdelay(uint32_t msec) static inline void up_udelay(uint32_t usec) { - hpet_udelay(usec*1000); + hpet_ndelay(usec*1000); } +#ifdef __cplusplus +} +#endif + #endif /* !__ASSEMBLY__ */ #endif diff --git a/nuttx/arch/rgmp/src/Makefile b/nuttx/arch/rgmp/src/Makefile index 4f5d87ad63..80ad78b379 100644 --- a/nuttx/arch/rgmp/src/Makefile +++ b/nuttx/arch/rgmp/src/Makefile @@ -42,18 +42,21 @@ RGMP_ARCH_CSRCS := $(addprefix $(CONFIG_RGMP_SUBARCH)/,$(RGMP_ARCH_CSRCS)) CFLAGS += -I$(TOPDIR)/sched -I$(TOPDIR)/fs ASRCS = $(RGMP_ARCH_ASRCS) -CSRCS = nuttx.c rgmp.c bridge.c $(RGMP_ARCH_CSRCS) +CSRCS = nuttx.c cxx.c $(RGMP_ARCH_CSRCS) AOBJS = $(ASRCS:.S=$(OBJEXT)) COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) +LINKSRCS = rgmp.c bridge.c +LINKOBJS = $(LINKSRCS:.c=$(OBJEXT)) + LDFLAGS += -T$(RGMPLKSCPT) LDPATHS = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS))) LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS)))) LDPATHS += -L$(RGMPLIBDIR) -LDLIBS += -lrgmp -lm -ltest $(shell gcc -print-libgcc-file-name) +LDLIBS += -lrgmp $(shell $(CC) -print-libgcc-file-name) all: libarch$(LIBEXT) @@ -74,9 +77,9 @@ libarch$(LIBEXT): $(OBJS) # Generate the final NuttX binary by linking the host-specific objects with the NuttX # specific objects (with munged names) -nuttx$(EXEEXT): +nuttx$(EXEEXT): $(LINKOBJS) @echo "LD: nuttx$(EXEEXT)" - @$(LD) $(LDFLAGS) $(LDPATHS) --start-group $(LDLIBS) --end-group -o $(TOPDIR)/$@ + @$(LD) $(LDFLAGS) $(LDPATHS) $(LINKOBJS) --start-group $(LDLIBS) $(EXTRA_LIBS) --end-group -o $(TOPDIR)/$@ @$(OBJDUMP) -S $(TOPDIR)/$@ > $(TOPDIR)/nuttx.asm @$(NM) -n $(TOPDIR)/$@ > $(TOPDIR)/nuttx.sym @$(OBJCOPY) -S -O binary $(TOPDIR)/$@ nuttx.img @@ -88,14 +91,15 @@ export_head: # Dependencies -.depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep +.depend: Makefile $(SRCS) $(LINKSRCS) + @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) $(LINKSRCS) >Make.dep @touch $@ depend: .depend clean: - @rm $(TOPDIR)/kernel.img nuttx.img + @rm -f $(TOPDIR)/arch/rgmp/src/x86/*.o + @rm -f $(TOPDIR)/kernel.img nuttx.img @rm -f libarch$(LIBEXT) *~ .*.swp $(call CLEAN) diff --git a/nuttx/arch/rgmp/src/bridge.c b/nuttx/arch/rgmp/src/bridge.c index 96280a7bf6..2d09448316 100644 --- a/nuttx/arch/rgmp/src/bridge.c +++ b/nuttx/arch/rgmp/src/bridge.c @@ -44,25 +44,37 @@ #include #include #include +#include #include #include #include +struct bridge { + struct rgmp_bridge *b; + sem_t rd_lock; + sem_t wr_lock; +}; static ssize_t up_bridge_read(struct file *filp, char *buffer, size_t len) { - struct rgmp_bridge *b; + ssize_t ret; + struct bridge *b = filp->f_inode->i_private; - b = filp->f_inode->i_private; - return rgmp_bridge_read(b, buffer, len); + sem_wait(&b->rd_lock); + ret = rgmp_bridge_read(b->b, buffer, len, 0); + sem_post(&b->rd_lock); + return ret; } static ssize_t up_bridge_write(struct file *filp, const char *buffer, size_t len) { - struct rgmp_bridge *b; + ssize_t ret; + struct bridge *b = filp->f_inode->i_private; - b = filp->f_inode->i_private; - return rgmp_bridge_write(b, (char *)buffer, len); + sem_wait(&b->wr_lock); + ret = rgmp_bridge_write(b->b, (char *)buffer, len, 0); + sem_post(&b->wr_lock); + return ret; } static int up_bridge_open(struct file *filp) @@ -75,30 +87,45 @@ static int up_bridge_close(struct file *filp) return 0; } -static const struct file_operations up_bridge_fops = -{ +static const struct file_operations up_bridge_fops = { .read = up_bridge_read, .write = up_bridge_write, .open = up_bridge_open, .close = up_bridge_close, }; -void up_register_bridges(void) +int rtos_bridge_init(struct rgmp_bridge *b) { int err; + struct bridge *bridge; char path[30] = {'/', 'd', 'e', 'v', '/'}; - struct rgmp_bridge *b; - for (b=bridge_list.next; b!=NULL; b=b->next) { + if ((bridge = kmalloc(sizeof(*bridge))) == NULL) + goto err0; + + bridge->b = b; + if ((err = sem_init(&bridge->rd_lock, 0, 1)) == ERROR) + goto err1; + if ((err = sem_init(&bridge->wr_lock, 0, 1)) == ERROR) + goto err1; + // make rgmp_bridge0 to be the console if (strcmp(b->vdev->name, "rgmp_bridge0") == 0) - strlcpy(path+5, "console", 25); + strlcpy(path + 5, "console", 25); else - strlcpy(path+5, b->vdev->name, 25); - err = register_driver(path, &up_bridge_fops, 0666, b); - if (err == ERROR) + strlcpy(path + 5, b->vdev->name, 25); + + if ((err = register_driver(path, &up_bridge_fops, 0666, bridge)) == ERROR) { cprintf("NuttX: register bridge %s fail\n", b->vdev->name); - } + goto err1; + } + + return 0; + +err1: + kfree(bridge); +err0: + return -1; } diff --git a/nuttx/arch/rgmp/src/cxx.c b/nuttx/arch/rgmp/src/cxx.c new file mode 100644 index 0000000000..99f42dfd27 --- /dev/null +++ b/nuttx/arch/rgmp/src/cxx.c @@ -0,0 +1,19 @@ +#include +#include + +int stderr = 2; + +void __stack_chk_fail_local(void) +{ + panic("stack check fail\n"); +} + +int __sprintf_chk(char *str, int flag, size_t strlen, const char *format) +{ + return snprintf(str, strlen, format); +} + +int dl_iterate_phdr(void* arg1, void* arg2) +{ + return -1; +} diff --git a/nuttx/arch/rgmp/src/nuttx.c b/nuttx/arch/rgmp/src/nuttx.c index 14b3e6d1d4..7deb959a28 100644 --- a/nuttx/arch/rgmp/src/nuttx.c +++ b/nuttx/arch/rgmp/src/nuttx.c @@ -38,13 +38,12 @@ ****************************************************************************/ #include -#include +#include +#include +#include #include -#include #include - #include -#include #include #include @@ -67,37 +66,34 @@ static inline void up_switchcontext(_TCB *ctcb, _TCB *ntcb) { // do nothing if two tasks are the same if (ctcb == ntcb) - return; + return; // this function can not be called in interrupt if (up_interrupt_context()) { - panic("%s: try to switch context in interrupt\n", __func__); + panic("%s: try to switch context in interrupt\n", __func__); } // start switch current_task = ntcb; - rgmp_context_switch(ctcb?&ctcb->xcp.tf:NULL, ntcb->xcp.tf); + rgmp_context_switch(ctcb ? &ctcb->xcp.ctx : NULL, &ntcb->xcp.ctx); } void up_initialize(void) { extern pidhash_t g_pidhash[]; - extern void up_register_bridges(void); - extern void vnet_initialize(void); + extern void vdev_init(void); extern void nuttx_arch_init(void); // intialize the current_task to g_idletcb current_task = g_pidhash[PIDHASH(0)].tcb; - // setup console - up_register_bridges(); + // OS memory alloc system is ready + use_os_kmalloc = 1; -#ifdef CONFIG_NET_VNET - // setup vnet device - vnet_initialize(); -#endif + // rgmp vdev init + vdev_init(); - nuttx_arch_init(); + nuttx_arch_init(); // enable interrupt local_irq_enable(); @@ -110,8 +106,9 @@ void up_idle(void) void up_allocate_heap(void **heap_start, size_t *heap_size) { + void *boot_freemem = boot_alloc(0, sizeof(int)); *heap_start = boot_freemem; - *heap_size = KERNBASE + boot_param.mem_size - (uint32_t)boot_freemem; + *heap_size = KERNBASE + kmem_size - (uint32_t)boot_freemem; } int up_create_stack(_TCB *tcb, size_t stack_size) @@ -128,16 +125,16 @@ int up_create_stack(_TCB *tcb, size_t stack_size) uint32_t *stack_alloc_ptr = (uint32_t*)kmalloc(adj_stack_size); if (stack_alloc_ptr) { - /* This is the address of the last word in the allocation */ + /* This is the address of the last word in the allocation */ - adj_stack_ptr = &stack_alloc_ptr[adj_stack_words - 1]; + adj_stack_ptr = &stack_alloc_ptr[adj_stack_words - 1]; - /* Save the values in the TCB */ + /* Save the values in the TCB */ - tcb->adj_stack_size = adj_stack_size; - tcb->stack_alloc_ptr = stack_alloc_ptr; - tcb->adj_stack_ptr = (void *)((unsigned int)adj_stack_ptr & ~7); - ret = OK; + tcb->adj_stack_size = adj_stack_size; + tcb->stack_alloc_ptr = stack_alloc_ptr; + tcb->adj_stack_ptr = (void *)((unsigned int)adj_stack_ptr & ~7); + ret = OK; } return ret; } @@ -164,7 +161,7 @@ int up_use_stack(_TCB *tcb, void *stack, size_t stack_size) void up_release_stack(_TCB *dtcb) { if (dtcb->stack_alloc_ptr) { - free(dtcb->stack_alloc_ptr); + free(dtcb->stack_alloc_ptr); } dtcb->stack_alloc_ptr = NULL; @@ -199,43 +196,43 @@ void up_block_task(_TCB *tcb, tstate_t task_state) { /* Verify that the context switch can be performed */ if ((tcb->task_state < FIRST_READY_TO_RUN_STATE) || - (tcb->task_state > LAST_READY_TO_RUN_STATE)) { - warn("%s: task sched error\n", __func__); - return; + (tcb->task_state > LAST_READY_TO_RUN_STATE)) { + warn("%s: task sched error\n", __func__); + return; } else { - _TCB *rtcb = current_task; - bool switch_needed; + _TCB *rtcb = current_task; + bool switch_needed; - /* Remove the tcb task from the ready-to-run list. If we - * are blocking the task at the head of the task list (the - * most likely case), then a context switch to the next - * ready-to-run task is needed. In this case, it should - * also be true that rtcb == tcb. - */ - switch_needed = sched_removereadytorun(tcb); + /* Remove the tcb task from the ready-to-run list. If we + * are blocking the task at the head of the task list (the + * most likely case), then a context switch to the next + * ready-to-run task is needed. In this case, it should + * also be true that rtcb == tcb. + */ + switch_needed = sched_removereadytorun(tcb); - /* Add the task to the specified blocked task list */ - sched_addblocked(tcb, (tstate_t)task_state); + /* Add the task to the specified blocked task list */ + sched_addblocked(tcb, (tstate_t)task_state); - /* Now, perform the context switch if one is needed */ - if (switch_needed) { - _TCB *nexttcb; - // this part should not be executed in interrupt context - if (up_interrupt_context()) { - panic("%s: %d\n", __func__, __LINE__); - } - // If there are any pending tasks, then add them to the g_readytorun - // task list now. It should be the up_realease_pending() called from - // sched_unlock() to do this for disable preemption. But it block - // itself, so it's OK. - if (g_pendingtasks.head) { - warn("Disable preemption failed for task block itself\n"); - sched_mergepending(); - } - nexttcb = (_TCB*)g_readytorun.head; - // context switch - up_switchcontext(rtcb, nexttcb); + /* Now, perform the context switch if one is needed */ + if (switch_needed) { + _TCB *nexttcb; + // this part should not be executed in interrupt context + if (up_interrupt_context()) { + panic("%s: %d\n", __func__, __LINE__); + } + // If there are any pending tasks, then add them to the g_readytorun + // task list now. It should be the up_realease_pending() called from + // sched_unlock() to do this for disable preemption. But it block + // itself, so it's OK. + if (g_pendingtasks.head) { + warn("Disable preemption failed for task block itself\n"); + sched_mergepending(); + } + nexttcb = (_TCB*)g_readytorun.head; + // context switch + up_switchcontext(rtcb, nexttcb); } } } @@ -259,31 +256,31 @@ void up_unblock_task(_TCB *tcb) { /* Verify that the context switch can be performed */ if ((tcb->task_state < FIRST_BLOCKED_STATE) || - (tcb->task_state > LAST_BLOCKED_STATE)) { - warn("%s: task sched error\n", __func__); - return; + (tcb->task_state > LAST_BLOCKED_STATE)) { + warn("%s: task sched error\n", __func__); + return; } else { - _TCB *rtcb = current_task; + _TCB *rtcb = current_task; - /* Remove the task from the blocked task list */ - sched_removeblocked(tcb); + /* Remove the task from the blocked task list */ + sched_removeblocked(tcb); - /* Reset its timeslice. This is only meaningful for round - * robin tasks but it doesn't here to do it for everything - */ + /* Reset its timeslice. This is only meaningful for round + * robin tasks but it doesn't here to do it for everything + */ #if CONFIG_RR_INTERVAL > 0 - tcb->timeslice = CONFIG_RR_INTERVAL / MSEC_PER_TICK; + tcb->timeslice = CONFIG_RR_INTERVAL / MSEC_PER_TICK; #endif - // Add the task in the correct location in the prioritized - // g_readytorun task list. - if (sched_addreadytorun(tcb) && !up_interrupt_context()) { - /* The currently active task has changed! */ - _TCB *nexttcb = (_TCB*)g_readytorun.head; - // context switch - up_switchcontext(rtcb, nexttcb); - } + // Add the task in the correct location in the prioritized + // g_readytorun task list. + if (sched_addreadytorun(tcb) && !up_interrupt_context()) { + /* The currently active task has changed! */ + _TCB *nexttcb = (_TCB*)g_readytorun.head; + // context switch + up_switchcontext(rtcb, nexttcb); + } } } @@ -298,11 +295,11 @@ void up_release_pending(void) /* Merge the g_pendingtasks list into the g_readytorun task list */ if (sched_mergepending()) { - /* The currently active task has changed! */ - _TCB *nexttcb = (_TCB*)g_readytorun.head; + /* The currently active task has changed! */ + _TCB *nexttcb = (_TCB*)g_readytorun.head; - // context switch - up_switchcontext(rtcb, nexttcb); + // context switch + up_switchcontext(rtcb, nexttcb); } } @@ -311,54 +308,54 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE + tcb->task_state > LAST_READY_TO_RUN_STATE #if SCHED_PRIORITY_MIN > UINT8_MIN - || priority < SCHED_PRIORITY_MIN + || priority < SCHED_PRIORITY_MIN #endif #if SCHED_PRIORITY_MAX < UINT8_MAX - || priority > SCHED_PRIORITY_MAX + || priority > SCHED_PRIORITY_MAX #endif - ) { - warn("%s: task sched error\n", __func__); - return; + ) { + warn("%s: task sched error\n", __func__); + return; } else { - _TCB *rtcb = current_task; - bool switch_needed; + _TCB *rtcb = current_task; + bool switch_needed; - /* Remove the tcb task from the ready-to-run list. - * sched_removereadytorun will return true if we just - * remove the head of the ready to run list. - */ - switch_needed = sched_removereadytorun(tcb); + /* Remove the tcb task from the ready-to-run list. + * sched_removereadytorun will return true if we just + * remove the head of the ready to run list. + */ + switch_needed = sched_removereadytorun(tcb); - /* Setup up the new task priority */ - tcb->sched_priority = (uint8_t)priority; + /* Setup up the new task priority */ + tcb->sched_priority = (uint8_t)priority; - /* Return the task to the specified blocked task list. - * sched_addreadytorun will return true if the task was - * added to the new list. We will need to perform a context - * switch only if the EXCLUSIVE or of the two calls is non-zero - * (i.e., one and only one the calls changes the head of the - * ready-to-run list). - */ - switch_needed ^= sched_addreadytorun(tcb); + /* Return the task to the specified blocked task list. + * sched_addreadytorun will return true if the task was + * added to the new list. We will need to perform a context + * switch only if the EXCLUSIVE or of the two calls is non-zero + * (i.e., one and only one the calls changes the head of the + * ready-to-run list). + */ + switch_needed ^= sched_addreadytorun(tcb); - /* Now, perform the context switch if one is needed */ - if (switch_needed && !up_interrupt_context()) { - _TCB *nexttcb; - // If there are any pending tasks, then add them to the g_readytorun - // task list now. It should be the up_realease_pending() called from - // sched_unlock() to do this for disable preemption. But it block - // itself, so it's OK. - if (g_pendingtasks.head) { - warn("Disable preemption failed for reprioritize task\n"); - sched_mergepending(); + /* Now, perform the context switch if one is needed */ + if (switch_needed && !up_interrupt_context()) { + _TCB *nexttcb; + // If there are any pending tasks, then add them to the g_readytorun + // task list now. It should be the up_realease_pending() called from + // sched_unlock() to do this for disable preemption. But it block + // itself, so it's OK. + if (g_pendingtasks.head) { + warn("Disable preemption failed for reprioritize task\n"); + sched_mergepending(); } - nexttcb = (_TCB*)g_readytorun.head; - // context switch - up_switchcontext(rtcb, nexttcb); + nexttcb = (_TCB*)g_readytorun.head; + // context switch + up_switchcontext(rtcb, nexttcb); } } } @@ -390,26 +387,26 @@ void up_assert(const uint8_t *filename, int line) // which will stop the OS // if in user space just terminate the task if (up_interrupt_context() || current_task->pid == 0) { - panic("%s: %d\n", __func__, __LINE__); + panic("%s: %d\n", __func__, __LINE__); } else { - exit(EXIT_FAILURE); + exit(EXIT_FAILURE); } } void up_assert_code(const uint8_t *filename, int line, int code) { fprintf(stderr, "Assertion failed at file:%s line: %d error code: %d\n", - filename, line, code); + filename, line, code); // in interrupt context or idle task means kernel error // which will stop the OS // if in user space just terminate the task if (up_interrupt_context() || current_task->pid == 0) { - panic("%s: %d\n", __func__, __LINE__); + panic("%s: %d\n", __func__, __LINE__); } else { - exit(EXIT_FAILURE); + exit(EXIT_FAILURE); } } @@ -420,38 +417,38 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver) { /* Refuse to handle nested signal actions */ if (!tcb->xcp.sigdeliver) { - int flags; + int flags; - /* Make sure that interrupts are disabled */ - flags = pushcli(); + /* Make sure that interrupts are disabled */ + local_irq_save(flags); - // First, handle some special cases when the signal is - // being delivered to the currently executing task. - if (tcb == current_task) { - // CASE 1: We are not in an interrupt handler and - // a task is signalling itself for some reason. - if (!up_interrupt_context()) { - // In this case just deliver the signal now. - sigdeliver(tcb); - } - // CASE 2: We are in an interrupt handler AND the - // interrupted task is the same as the one that - // must receive the signal. - else { - tcb->xcp.sigdeliver = sigdeliver; + // First, handle some special cases when the signal is + // being delivered to the currently executing task. + if (tcb == current_task) { + // CASE 1: We are not in an interrupt handler and + // a task is signalling itself for some reason. + if (!up_interrupt_context()) { + // In this case just deliver the signal now. + sigdeliver(tcb); + } + // CASE 2: We are in an interrupt handler AND the + // interrupted task is the same as the one that + // must receive the signal. + else { + tcb->xcp.sigdeliver = sigdeliver; } } - // Otherwise, we are (1) signaling a task is not running - // from an interrupt handler or (2) we are not in an - // interrupt handler and the running task is signalling - // some non-running task. - else { - tcb->xcp.sigdeliver = sigdeliver; - push_xcptcontext(&tcb->xcp); + // Otherwise, we are (1) signaling a task is not running + // from an interrupt handler or (2) we are not in an + // interrupt handler and the running task is signalling + // some non-running task. + else { + tcb->xcp.sigdeliver = sigdeliver; + push_xcptcontext(&tcb->xcp); } - popcli(flags); + local_irq_restore(flags); } } @@ -461,7 +458,7 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver) bool up_interrupt_context(void) { if (nest_irq) - return true; + return true; return false; } @@ -496,6 +493,16 @@ void up_sigdeliver(struct Trapframe *tf) local_irq_disable(); } +#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE) + +void up_cxxinitialize(void) +{ + rgmp_cxx_init(); +} + +#endif + + diff --git a/nuttx/arch/rgmp/src/rgmp.c b/nuttx/arch/rgmp/src/rgmp.c index 40fad1f87a..479696fb5e 100644 --- a/nuttx/arch/rgmp/src/rgmp.c +++ b/nuttx/arch/rgmp/src/rgmp.c @@ -38,7 +38,7 @@ ****************************************************************************/ #include -#include +#include #include #include @@ -56,9 +56,9 @@ int nest_irq = 0; // the default time is 10ms #ifdef CONFIG_MSEC_PER_TICK -unsigned int rtos_tick_time = CONFIG_MSEC_PER_TICK; +const unsigned int rtos_tick_time = CONFIG_MSEC_PER_TICK; #else -unsigned int rtos_tick_time = 10; +const unsigned int rtos_tick_time = 10; #endif void rtos_entry(void) @@ -76,80 +76,71 @@ void rtos_free_page(void *page) free(page); } +void *rtos_kmalloc(int size) +{ + return kmalloc(size); +} + +void rtos_kfree(void *addr) +{ + kfree(addr); +} + /** * The interrupt can be nested. The pair of rtos_enter_interrupt() * and rtos_exit_interrupt() make sure the context switch is * performed only in the last IRQ exit. */ -void rtos_enter_interrupt(struct Trapframe *tf) +void rtos_enter_interrupt(void) { nest_irq++; } -void rtos_exit_interrupt(struct Trapframe *tf) +void rtos_exit_interrupt(void) { local_irq_disable(); nest_irq--; if (!nest_irq) { - _TCB *rtcb = current_task; - _TCB *ntcb; + _TCB *rtcb = current_task; + _TCB *ntcb; - if (rtcb->xcp.sigdeliver) { - rtcb->xcp.tf = tf; - push_xcptcontext(&rtcb->xcp); - } - ntcb = (_TCB*)g_readytorun.head; - // switch needed - if (rtcb != ntcb) { - rtcb->xcp.tf = tf; - current_task = ntcb; - rgmp_pop_tf(ntcb->xcp.tf); - } + if (rtcb->xcp.sigdeliver) { + rtcb->xcp.ctx.tf = current_regs; + push_xcptcontext(&rtcb->xcp); + } + ntcb = (_TCB*)g_readytorun.head; + // switch needed + if (rtcb != ntcb) { + rtcb->xcp.ctx.tf = current_regs; + current_task = ntcb; + rgmp_switch_to(&ntcb->xcp.ctx); + } } } -void rtos_timer_isr(struct Trapframe *tf) +void rtos_timer_isr(void *data) { sched_process_timer(); } -/** - * RTOS mutex operation - */ -const int rtos_mutex_size = sizeof(sem_t); -void rtos_mutex_init(void *lock) -{ - sem_init(lock, 0, 1); -} - -int rtos_mutex_lock(void *lock) -{ - return sem_wait(lock); -} - -int rtos_mutex_unlock(void *lock) -{ - return sem_post(lock); -} - /** * RTOS semaphore operation */ -const int rtos_semaphore_size = sizeof(sem_t); - -void rtos_sem_init(void *sem, int val) +int rtos_sem_init(struct semaphore *sem, int val) { - sem_init(sem, 0, val); + if ((sem->sem = kmalloc(sizeof(sem_t))) == NULL) + return -1; + return sem_init(sem->sem, 0, val); } -int rtos_sem_up(void *sem) +int rtos_sem_up(struct semaphore *sem) { - return sem_post(sem); + return sem_post(sem->sem); } -int rtos_sem_down(void *sem) +int rtos_sem_down(struct semaphore *sem) { - return sem_wait(sem); + return sem_wait(sem->sem); } void rtos_stop_running(void) @@ -161,8 +152,16 @@ void rtos_stop_running(void) nuttx_arch_exit(); while(1) { - arch_hlt(); + arch_hlt(); } } +int rtos_vnet_init(struct rgmp_vnet *vnet) +{ + extern int vnet_init(struct rgmp_vnet *vnet); + + return vnet_init(vnet); +} + + diff --git a/nuttx/arch/rgmp/src/x86/arch_nuttx.c b/nuttx/arch/rgmp/src/x86/arch_nuttx.c index c7b7577f36..04b8fa8c82 100644 --- a/nuttx/arch/rgmp/src/x86/arch_nuttx.c +++ b/nuttx/arch/rgmp/src/x86/arch_nuttx.c @@ -37,7 +37,7 @@ * ****************************************************************************/ -#include +#include #include #include @@ -75,32 +75,27 @@ void up_initial_state(_TCB *tcb) { struct Trapframe *tf; - if (tcb->pid != 0) { - tf = (struct Trapframe *)tcb->adj_stack_ptr-1; - memset(tf, 0, sizeof(struct Trapframe)); - tf->tf_fpu = rgmp_fpu_init_regs; - tf->tf_eflags = 0x00000202; - tf->tf_cs = GD_KT; - tf->tf_ds = GD_KD; - tf->tf_es = GD_KD; - tf->tf_eip = (uint32_t)tcb->start; - tcb->xcp.tf = tf; + if (tcb->pid) { + tf = (struct Trapframe *)tcb->adj_stack_ptr - 1; + rgmp_setup_context(&tcb->xcp.ctx, tf, tcb->start, 1); } + else + rgmp_setup_context(&tcb->xcp.ctx, NULL, NULL, 0); } void push_xcptcontext(struct xcptcontext *xcp) { - xcp->save_eip = xcp->tf->tf_eip; - xcp->save_eflags = xcp->tf->tf_eflags; + xcp->save_eip = xcp->ctx.tf->tf_eip; + xcp->save_eflags = xcp->ctx.tf->tf_eflags; // set up signal entry with interrupts disabled - xcp->tf->tf_eip = (uint32_t)up_sigentry; - xcp->tf->tf_eflags = 0; + xcp->ctx.tf->tf_eip = (uint32_t)up_sigentry; + xcp->ctx.tf->tf_eflags = 0; } void pop_xcptcontext(struct xcptcontext *xcp) { - xcp->tf->tf_eip = xcp->save_eip; - xcp->tf->tf_eflags = xcp->save_eflags; + xcp->ctx.tf->tf_eip = xcp->save_eip; + xcp->ctx.tf->tf_eflags = xcp->save_eflags; } diff --git a/nuttx/arch/rgmp/src/x86/com.c b/nuttx/arch/rgmp/src/x86/com.c index 6a136ac7d7..7983bb1bcd 100644 --- a/nuttx/arch/rgmp/src/x86/com.c +++ b/nuttx/arch/rgmp/src/x86/com.c @@ -57,7 +57,6 @@ #include #include -#include /**************************************************************************** * Pre-processor Definitions @@ -129,7 +128,7 @@ static int up_setup(struct uart_dev_s *dev); static void up_shutdown(struct uart_dev_s *dev); static int up_attach(struct uart_dev_s *dev); static void up_detach(struct uart_dev_s *dev); -static irqreturn_t up_com_int_handler(struct Trapframe *tf, void *dev_id); +static irqreturn_t up_com_int_handler(int irq, void *dev_id); static int up_ioctl(struct file *filep, int cmd, unsigned long arg); static int up_receive(struct uart_dev_s *dev, unsigned int *status); static void up_rxint(struct uart_dev_s *dev, bool enable); @@ -345,7 +344,7 @@ static void up_detach(struct uart_dev_s *dev) * ****************************************************************************/ -static irqreturn_t up_com_int_handler(struct Trapframe *tf, void *dev_id) +static irqreturn_t up_com_int_handler(int irq, void *dev_id) { struct uart_dev_s *dev = dev_id; struct up_dev_s *priv = dev->priv; @@ -622,6 +621,7 @@ void up_serialinit(void) * writes * ****************************************************************************/ +extern void cons_putc(int c); int up_putc(int ch) { diff --git a/nuttx/arch/rgmp/src/x86/sigentry.S b/nuttx/arch/rgmp/src/x86/sigentry.S index 98891c0268..77214e8114 100644 --- a/nuttx/arch/rgmp/src/x86/sigentry.S +++ b/nuttx/arch/rgmp/src/x86/sigentry.S @@ -39,11 +39,11 @@ .globl up_sigentry up_sigentry: - subl $172, %esp # 172 is the size of TrapFrame + subl $172, %esp # 172 is the size of Trapframe without cross ring part pushl %esp movl %esp, %eax call up_sigdeliver - addl $8, %esp # skip parameter and current_task + addl $8, %esp # skip parameter and tf_curregs frstor 0(%esp) addl $108, %esp popal diff --git a/nuttx/configs/rgmp/x86/cxxtest/Make.defs b/nuttx/configs/rgmp/x86/cxxtest/Make.defs new file mode 100644 index 0000000000..858ecbae1e --- /dev/null +++ b/nuttx/configs/rgmp/x86/cxxtest/Make.defs @@ -0,0 +1,134 @@ +#################################################################################### +# configs/rgmp/default/Make.defs +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# 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 + +RGMPLIBDIR := $(RGMP_INST_DIR)/lib +RGMPINCDIR := $(RGMP_INST_DIR)/include +RGMPLKSCPT := $(RGMP_INST_DIR)/etc/rgmp.ld + +HOSTOS = ${shell uname -o} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -O2 -gstabs +else + ARCHOPTIMIZATION = -O2 +endif + +#ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti +ARCHCXXFLAGS = -fno-builtin +ARCHCPUFLAGS = -fno-builtin -nostdinc -fno-stack-protector +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +ARCHDEFINES = -D__RGMP_KERNEL__ -D__RTOS_KERNEL__ -D__SHARE_KERNEL__ +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ + -I$(TOPDIR)/configs/rgmp/include -I$(TOPDIR)/arch/rgmp/include/x86 + +ARCHXXDEFINES = +ARCHXXINCLUDES = -I$(TOPDIR)/include/cxx -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ + -I$(TOPDIR)/configs/rgmp/include -I$(TOPDIR)/arch/rgmp/include/x86 \ + -I$(TOPDIR)/include/uClibc++ + +CROSSDEV = +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 + +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) \ + $(ARCHXXDEFINES) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) \ + -pipe -nodefaultlibs -nostdinc++ +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +OBJEXT = .o +LIBEXT = .a + +ifeq ($(HOSTOS),Cygwin) + EXEEXT = .exe +else + EXEEXT = +endif + +LDFLAGS += -nostdlib +EXTRA_LIBS = $(shell $(CC) -print-file-name=libsupc++.a) \ + $(shell $(CC) -print-file-name=libgcc_eh.a) + +define PREPROCESS + @echo "CPP: $1->$2" + @$(CPP) $(CPPFLAGS) $1 -o $2 +endef + +define COMPILE + @echo "CC: $1" + @$(CC) -c $(CFLAGS) $1 -o $2 +endef + +define COMPILEXX + @echo "CXX: $1" + @$(CXX) -c $(CXXFLAGS) $1 -o $2 +endef + +define ASSEMBLE + @echo "AS: $1" + @$(CC) -c $(AFLAGS) $1 -o $2 +endef + +define ARCHIVE + echo "AR: $2"; \ + $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; } +endef + +define CLEAN + @rm -f *.o *.a +endef + +MKDEP = $(TOPDIR)/tools/mkdeps.sh + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/rgmp/x86/cxxtest/appconfig b/nuttx/configs/rgmp/x86/cxxtest/appconfig new file mode 100644 index 0000000000..e1273af268 --- /dev/null +++ b/nuttx/configs/rgmp/x86/cxxtest/appconfig @@ -0,0 +1,39 @@ +############################################################################ +# configs/sim/default/appconfig +# +# Copyright (C) 2011 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. +# +############################################################################ + +# Path to example in apps/examples containing the user_start entry point + +CONFIGURED_APPS += examples/cxxtest + diff --git a/nuttx/configs/rgmp/x86/cxxtest/defconfig b/nuttx/configs/rgmp/x86/cxxtest/defconfig new file mode 100644 index 0000000000..34430ae86a --- /dev/null +++ b/nuttx/configs/rgmp/x86/cxxtest/defconfig @@ -0,0 +1,428 @@ +############################################################################ +# configs/rgmp/default/defconfig +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# 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. +# +############################################################################ +# +# Architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_name - for use in C code. This identifies the particular +# processor architecture (CONFIG_ARCH_SIM). +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# +CONFIG_ARCH="rgmp" +CONFIG_ARCH_RGMP=y +CONFIG_ARCH_BOARD="rgmp" +CONFIG_ARCH_BOARD_RGMP=y + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_DEBUG_SYMBOLS - build without optimization and with +# debug symbols (needed for use with a debugger). +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_JULIAN_TIME - Enables Julian time conversions +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket +# desciptors by task_create() when a new task is started. If +# set, all sockets will appear to be closed in the new task. +# +#CONFIG_APPS_DIR= +CONFIG_DEBUG=y +CONFIG_DEBUG_VERBOSE=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_MM_REGIONS=1 +CONFIG_ARCH_LOWPUTC=y +CONFIG_MSEC_PER_TICK=1 +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=32 +CONFIG_START_YEAR=2007 +CONFIG_START_MONTH=2 +CONFIG_START_DAY=27 +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=n +CONFIG_FDCLONE_STDIO=n +CONFIG_SDCLONE_DISABLE=y + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=n +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=n +CONFIG_DISABLE_MOUNTPOINT=n +CONFIG_DISABLE_ENVIRON=n +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve sysem performance +# +CONFIG_ARCH_MEMCPY=y +CONFIG_ARCH_MEMCMP=y +CONFIG_ARCH_MEMMOVE=y +CONFIG_ARCH_MEMSET=y +CONFIG_ARCH_STRCMP=y +CONFIG_ARCH_STRCPY=y +CONFIG_ARCH_STRNCPY=y +CONFIG_ARCH_STRLEN=y +CONFIG_ARCH_STRNLEN=y +CONFIG_ARCH_STRCHR=y +CONFIG_ARCH_BZERO=n +CONFIG_ARCH_MATH_H=y +CONFIG_ARCH_STDINT_H=y +CONFIG_ARCH_STDBOOL_H=y + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_RAW_BINARY=n +CONFIG_HAVE_LIBM=n +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=64 +CONFIG_MAX_TASK_ARGS=10 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=16 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=32 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=4 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_PREALLOC_TIMERS=8 +CONFIG_STDIO_LINEBUFFER=y + +# +# FAT filesystem configuration +# CONFIG_FS_FAT - Enable FAT filesystem support +# CONFIG_FAT_SECTORSIZE - Max supported sector size +# CONFIG_FS_ROMFS - Enable ROMFS filesystem support +CONFIG_FS_FAT=n +CONFIG_FS_ROMFS=n + +# +# TCP/IP and UDP support via uIP +# CONFIG_NET - Enable or disable all network features +# CONFIG_NET_IPv6 - Build in support for IPv6 +# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread. +# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options +# CONFIG_NET_BUFSIZE - uIP buffer size +# CONFIG_NET_TCP - TCP support on or off +# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks) +# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers +# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero) +# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until +# accept() is called. The size of the backlog is selected when listen() is called. +# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks) +# CONFIG_NET_UDP - UDP support on or off +# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off +# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections +# CONFIG_NET_ICMP - ICMP ping response support on or off +# CONFIG_NET_ICMP_PING - ICMP ping request support on or off +# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address +# CONFIG_NET_STATISTICS - uIP statistics on or off +# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window +# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table +# CONFIG_NET_BROADCAST - Broadcast support +# CONFIG_NET_LLH_LEN - The link level header length +# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates +CONFIG_NET=y +CONFIG_NET_IPv6=n +CONFIG_NSOCKET_DESCRIPTORS=5 +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_BUFSIZE=1514 +CONFIG_NET_TCP=y +CONFIG_NET_TCP_CONNS=40 +CONFIG_NET_MAX_LISTENPORTS=40 +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +#CONFIG_NET_UDP_CONNS=10 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_PING=y +#CONFIG_NET_PINGADDRCONF=0 +CONFIG_NET_STATISTICS=y +#CONFIG_NET_RECEIVE_WINDOW=128 +#CONFIG_NET_ARPTAB_SIZE=8 +CONFIG_NET_BROADCAST=n +#CONFIG_NET_LLH_LEN=14 +#CONFIG_NET_FWCACHE_SIZE=2 + +# +# UIP Network Utilities +# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP +# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries +CONFIG_NET_DHCP_LIGHT=n +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 + +# +# 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 + +# +# Settings for examples/nsh +CONFIG_NSH_CONSOLE=y +CONFIG_NSH_TELNET=n +CONFIG_NSH_IOBUFFER_SIZE=512 +CONFIG_NSH_CMD_SIZE=40 +CONFIG_NSH_DHCPC=n +CONFIG_NSH_NOMAC=n +CONFIG_NSH_IPADDR=0x0a000002 +CONFIG_NSH_DRIPADDR=0x0a000001 +CONFIG_NSH_NETMASK=0xffffff00 + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2 after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=8192 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= +CONFIG_USER_ENTRYPOINT="cxxtest_main" + +# +# uClibc++ Standard C++ Library +# +CONFIG_UCLIBCXX=y +CONFIG_UCLIBCXX_EXCEPTION=y +CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE=32 +CONFIG_UCLIBCXX_HAVE_LIBSUPCXX=y + +########################################## +# RGMP specific configuration +########################################## + +# +# arch +# +CONFIG_RGMP_SUBARCH=x86 + +# +# VNET +# +CONFIG_NET_VNET=y +CONFIG_VNET_NINTERFACES=1 + +# +# Serial port +# +CONFIG_COM1=y +CONFIG_COM2=y +CONFIG_COM3=n +CONFIG_COM4=n + +# +# E1000 +# +CONFIG_NET_E1000=n +CONFIG_E1000_N_TX_DESC=128 +CONFIG_E1000_N_RX_DESC=128 +CONFIG_E1000_BUFF_SIZE=0x800 diff --git a/nuttx/configs/rgmp/x86/cxxtest/setenv.sh b/nuttx/configs/rgmp/x86/cxxtest/setenv.sh new file mode 100644 index 0000000000..a6a533e477 --- /dev/null +++ b/nuttx/configs/rgmp/x86/cxxtest/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# config/rgmp/default/setenv.sh +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; 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 + +#export NUTTX_BIN= +#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/rgmp/x86/default/Make.defs b/nuttx/configs/rgmp/x86/default/Make.defs index 676087809d..53853838de 100644 --- a/nuttx/configs/rgmp/x86/default/Make.defs +++ b/nuttx/configs/rgmp/x86/default/Make.defs @@ -53,7 +53,7 @@ endif ARCHCPUFLAGS = -fno-builtin -nostdinc -fno-stack-protector ARCHPICFLAGS = -fpic ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -ARCHDEFINES = +ARCHDEFINES = -D__RGMP_KERNEL__ -D__RTOS_KERNEL__ -D__SHARE_KERNEL__ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ -I$(TOPDIR)/configs/rgmp/include -I$(TOPDIR)/arch/rgmp/include/x86 ARCHSCRIPT = diff --git a/nuttx/configs/rgmp/x86/default/defconfig b/nuttx/configs/rgmp/x86/default/defconfig index e36c397661..30b27c4a13 100644 --- a/nuttx/configs/rgmp/x86/default/defconfig +++ b/nuttx/configs/rgmp/x86/default/defconfig @@ -48,7 +48,7 @@ CONFIG_ARCH_BOARD_RGMP=y CONFIG_USER_ENTRYPOINT="rgmp_main" CONFIG_DEBUG=n CONFIG_DEBUG_VERBOSE=n -CONFIG_DEBUG_SYMBOLS=n +CONFIG_DEBUG_SYMBOLS=y CONFIG_MM_REGIONS=1 CONFIG_ARCH_LOWPUTC=y CONFIG_MSEC_PER_TICK=1 @@ -96,6 +96,7 @@ CONFIG_DISABLE_POLL=y # # Misc libc settings # +CONFIG_LIBC_FLOATINGPOINT=y CONFIG_NOPRINTF_FIELDWIDTH=n # @@ -113,6 +114,7 @@ CONFIG_ARCH_STRCPY=y CONFIG_ARCH_STRNCPY=y CONFIG_ARCH_STRLEN=y CONFIG_ARCH_STRNLEN=y +CONFIG_ARCH_STRCHR=y CONFIG_ARCH_BZERO=n CONFIG_ARCH_MATH_H=y CONFIG_ARCH_STDINT_H=y @@ -124,6 +126,7 @@ CONFIG_ARCH_STDBOOL_H=y CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n +CONFIG_HAVE_LIBM=n # # Sizes of configurable things (0 disables) diff --git a/nuttx/configs/rgmp/x86/helloxx/Make.defs b/nuttx/configs/rgmp/x86/helloxx/Make.defs new file mode 100644 index 0000000000..d2d0e83ea9 --- /dev/null +++ b/nuttx/configs/rgmp/x86/helloxx/Make.defs @@ -0,0 +1,132 @@ +#################################################################################### +# configs/rgmp/default/Make.defs +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# 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 + +RGMPLIBDIR := $(RGMP_INST_DIR)/lib +RGMPINCDIR := $(RGMP_INST_DIR)/include +RGMPLKSCPT := $(RGMP_INST_DIR)/etc/rgmp.ld + +HOSTOS = ${shell uname -o} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -O2 -gstabs +else + ARCHOPTIMIZATION = -O2 +endif + +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti +ARCHCPUFLAGS = -fno-builtin -nostdinc -fno-stack-protector +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +ARCHDEFINES = -D__RGMP_KERNEL__ -D__RTOS_KERNEL__ -D__SHARE_KERNEL__ +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ + -I$(TOPDIR)/configs/rgmp/include -I$(TOPDIR)/arch/rgmp/include/x86 + +ARCHXXINCLUDES = -I$(TOPDIR)/include/cxx -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ + -I$(TOPDIR)/configs/rgmp/include -I$(TOPDIR)/arch/rgmp/include/x86 \ + -I$(TOPDIR)/include/uClibc++ + +CROSSDEV = +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 + +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) \ + $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -nodefaultlibs \ + -nostdinc++ +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +OBJEXT = .o +LIBEXT = .a + +ifeq ($(HOSTOS),Cygwin) + EXEEXT = .exe +else + EXEEXT = +endif + +LDFLAGS += -nostdlib +EXTRA_LIBS = $(shell $(CC) -print-file-name=libsupc++.a) \ + $(shell $(CC) -print-file-name=libgcc_eh.a) + +define PREPROCESS + @echo "CPP: $1->$2" + @$(CPP) $(CPPFLAGS) $1 -o $2 +endef + +define COMPILE + @echo "CC: $1" + @$(CC) -c $(CFLAGS) $1 -o $2 +endef + +define COMPILEXX + @echo "CXX: $1" + @$(CXX) -c $(CXXFLAGS) $1 -o $2 +endef + +define ASSEMBLE + @echo "AS: $1" + @$(CC) -c $(AFLAGS) $1 -o $2 +endef + +define ARCHIVE + echo "AR: $2"; \ + $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; } +endef + +define CLEAN + @rm -f *.o *.a +endef + +MKDEP = $(TOPDIR)/tools/mkdeps.sh + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/rgmp/x86/helloxx/appconfig b/nuttx/configs/rgmp/x86/helloxx/appconfig new file mode 100644 index 0000000000..58c9dad588 --- /dev/null +++ b/nuttx/configs/rgmp/x86/helloxx/appconfig @@ -0,0 +1,51 @@ +############################################################################ +# configs/sim/default/appconfig +# +# Copyright (C) 2011 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 +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dyAR 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. +# +############################################################################ + +# Path to example in apps/examples containing the user_start entry point + +CONFIGURED_APPS += examples/helloxx + diff --git a/nuttx/configs/rgmp/x86/helloxx/defconfig b/nuttx/configs/rgmp/x86/helloxx/defconfig new file mode 100644 index 0000000000..ed7d5d8b99 --- /dev/null +++ b/nuttx/configs/rgmp/x86/helloxx/defconfig @@ -0,0 +1,428 @@ +############################################################################ +# configs/rgmp/default/defconfig +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# 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. +# +############################################################################ +# +# Architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_name - for use in C code. This identifies the particular +# processor architecture (CONFIG_ARCH_SIM). +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# +CONFIG_ARCH="rgmp" +CONFIG_ARCH_RGMP=y +CONFIG_ARCH_BOARD="rgmp" +CONFIG_ARCH_BOARD_RGMP=y + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_DEBUG_SYMBOLS - build without optimization and with +# debug symbols (needed for use with a debugger). +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_JULIAN_TIME - Enables Julian time conversions +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket +# desciptors by task_create() when a new task is started. If +# set, all sockets will appear to be closed in the new task. +# +#CONFIG_APPS_DIR= +CONFIG_DEBUG=y +CONFIG_DEBUG_VERBOSE=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_MM_REGIONS=1 +CONFIG_ARCH_LOWPUTC=y +CONFIG_MSEC_PER_TICK=1 +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=32 +CONFIG_START_YEAR=2007 +CONFIG_START_MONTH=2 +CONFIG_START_DAY=27 +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=n +CONFIG_FDCLONE_STDIO=n +CONFIG_SDCLONE_DISABLE=y + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=n +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=n +CONFIG_DISABLE_MOUNTPOINT=n +CONFIG_DISABLE_ENVIRON=n +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve sysem performance +# +CONFIG_ARCH_MEMCPY=y +CONFIG_ARCH_MEMCMP=y +CONFIG_ARCH_MEMMOVE=y +CONFIG_ARCH_MEMSET=y +CONFIG_ARCH_STRCMP=y +CONFIG_ARCH_STRCPY=y +CONFIG_ARCH_STRNCPY=y +CONFIG_ARCH_STRLEN=y +CONFIG_ARCH_STRNLEN=y +CONFIG_ARCH_STRCHR=y +CONFIG_ARCH_BZERO=n +CONFIG_ARCH_MATH_H=y +CONFIG_ARCH_STDINT_H=y +CONFIG_ARCH_STDBOOL_H=y + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_RAW_BINARY=n +CONFIG_HAVE_LIBM=n +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=64 +CONFIG_MAX_TASK_ARGS=10 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=16 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=32 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=4 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_PREALLOC_TIMERS=8 +CONFIG_STDIO_LINEBUFFER=y + +# +# FAT filesystem configuration +# CONFIG_FS_FAT - Enable FAT filesystem support +# CONFIG_FAT_SECTORSIZE - Max supported sector size +# CONFIG_FS_ROMFS - Enable ROMFS filesystem support +CONFIG_FS_FAT=n +CONFIG_FS_ROMFS=n + +# +# TCP/IP and UDP support via uIP +# CONFIG_NET - Enable or disable all network features +# CONFIG_NET_IPv6 - Build in support for IPv6 +# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread. +# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options +# CONFIG_NET_BUFSIZE - uIP buffer size +# CONFIG_NET_TCP - TCP support on or off +# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks) +# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers +# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero) +# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until +# accept() is called. The size of the backlog is selected when listen() is called. +# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks) +# CONFIG_NET_UDP - UDP support on or off +# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off +# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections +# CONFIG_NET_ICMP - ICMP ping response support on or off +# CONFIG_NET_ICMP_PING - ICMP ping request support on or off +# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address +# CONFIG_NET_STATISTICS - uIP statistics on or off +# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window +# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table +# CONFIG_NET_BROADCAST - Broadcast support +# CONFIG_NET_LLH_LEN - The link level header length +# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates +CONFIG_NET=y +CONFIG_NET_IPv6=n +CONFIG_NSOCKET_DESCRIPTORS=5 +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_BUFSIZE=1514 +CONFIG_NET_TCP=y +CONFIG_NET_TCP_CONNS=40 +CONFIG_NET_MAX_LISTENPORTS=40 +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +#CONFIG_NET_UDP_CONNS=10 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_PING=y +#CONFIG_NET_PINGADDRCONF=0 +CONFIG_NET_STATISTICS=y +#CONFIG_NET_RECEIVE_WINDOW=128 +#CONFIG_NET_ARPTAB_SIZE=8 +CONFIG_NET_BROADCAST=n +#CONFIG_NET_LLH_LEN=14 +#CONFIG_NET_FWCACHE_SIZE=2 + +# +# UIP Network Utilities +# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP +# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries +CONFIG_NET_DHCP_LIGHT=n +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 + +# +# 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 + +# +# Settings for examples/nsh +CONFIG_NSH_CONSOLE=y +CONFIG_NSH_TELNET=n +CONFIG_NSH_IOBUFFER_SIZE=512 +CONFIG_NSH_CMD_SIZE=40 +CONFIG_NSH_DHCPC=n +CONFIG_NSH_NOMAC=n +CONFIG_NSH_IPADDR=0x0a000002 +CONFIG_NSH_DRIPADDR=0x0a000001 +CONFIG_NSH_NETMASK=0xffffff00 + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2 after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=8192 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= +CONFIG_USER_ENTRYPOINT="helloxx_main" + +# +# uClibc++ Standard C++ Library +# +#CONFIG_UCLIBCXX=y +#CONFIG_UCLIBCXX_EXCEPTION=y +#CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE=32 +#CONFIG_UCLIBCXX_HAVE_LIBSUPCXX=y + +########################################## +# RGMP specific configuration +########################################## + +# +# arch +# +CONFIG_RGMP_SUBARCH=x86 + +# +# VNET +# +CONFIG_NET_VNET=y +CONFIG_VNET_NINTERFACES=1 + +# +# Serial port +# +CONFIG_COM1=y +CONFIG_COM2=y +CONFIG_COM3=n +CONFIG_COM4=n + +# +# E1000 +# +CONFIG_NET_E1000=n +CONFIG_E1000_N_TX_DESC=128 +CONFIG_E1000_N_RX_DESC=128 +CONFIG_E1000_BUFF_SIZE=0x800 diff --git a/nuttx/configs/rgmp/x86/helloxx/setenv.sh b/nuttx/configs/rgmp/x86/helloxx/setenv.sh new file mode 100644 index 0000000000..a6a533e477 --- /dev/null +++ b/nuttx/configs/rgmp/x86/helloxx/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# config/rgmp/default/setenv.sh +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; 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 + +#export NUTTX_BIN= +#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/rgmp/x86/nsh/Make.defs b/nuttx/configs/rgmp/x86/nsh/Make.defs index 1ef857efed..cc9c3a8c4e 100644 --- a/nuttx/configs/rgmp/x86/nsh/Make.defs +++ b/nuttx/configs/rgmp/x86/nsh/Make.defs @@ -53,7 +53,7 @@ endif ARCHCPUFLAGS = -fno-builtin -nostdinc -fno-stack-protector ARCHPICFLAGS = -fpic ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -ARCHDEFINES = +ARCHDEFINES = -D__RGMP_KERNEL__ -D__RTOS_KERNEL__ -D__SHARE_KERNEL__ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ -I$(TOPDIR)/configs/rgmp/include -I$(TOPDIR)/arch/rgmp/include/x86 ARCHSCRIPT = diff --git a/nuttx/configs/rgmp/x86/nsh/appconfig b/nuttx/configs/rgmp/x86/nsh/appconfig index b5e5d0203f..b9c5fe65a0 100644 --- a/nuttx/configs/rgmp/x86/nsh/appconfig +++ b/nuttx/configs/rgmp/x86/nsh/appconfig @@ -49,6 +49,7 @@ CONFIGURED_APPS += netutils/uiplib CONFIGURED_APPS += netutils/dhcpc CONFIGURED_APPS += netutils/resolv CONFIGURED_APPS += netutils/tftpc +CONFIGURED_APPS += netutils/codecs CONFIGURED_APPS += netutils/webclient endif diff --git a/nuttx/configs/rgmp/x86/nsh/defconfig b/nuttx/configs/rgmp/x86/nsh/defconfig index 6afe9c9a9e..90797a20b2 100644 --- a/nuttx/configs/rgmp/x86/nsh/defconfig +++ b/nuttx/configs/rgmp/x86/nsh/defconfig @@ -96,6 +96,7 @@ CONFIG_DISABLE_POLL=y # # Misc libc settings # +CONFIG_LIBC_FLOATINGPOINT=y CONFIG_NOPRINTF_FIELDWIDTH=n # @@ -113,6 +114,7 @@ CONFIG_ARCH_STRCPY=y CONFIG_ARCH_STRNCPY=y CONFIG_ARCH_STRLEN=y CONFIG_ARCH_STRNLEN=y +CONFIG_ARCH_STRCHR=y CONFIG_ARCH_BZERO=n CONFIG_ARCH_MATH_H=y CONFIG_ARCH_STDINT_H=y @@ -124,6 +126,7 @@ CONFIG_ARCH_STDBOOL_H=y CONFIG_RRLOAD_BINARY=n CONFIG_INTELHEX_BINARY=n CONFIG_RAW_BINARY=n +CONFIG_HAVE_LIBM=n # # Sizes of configurable things (0 disables) @@ -208,6 +211,12 @@ CONFIG_NSH_IPADDR=0xc0a80a02 CONFIG_NSH_DRIPADDR=0xc0a80a01 CONFIG_NSH_NETMASK=0xffffff00 +# +# settings for apps/netutils +# +CONFIG_NETUTILS_CODECS=y +CONFIG_CODECS_URLCODE=y + # # Stack and heap information # diff --git a/nuttx/drivers/net/e1000.c b/nuttx/drivers/net/e1000.c index ec2b29b6ad..cae6f39b40 100644 --- a/nuttx/drivers/net/e1000.c +++ b/nuttx/drivers/net/e1000.c @@ -60,6 +60,7 @@ #include #include #include +#include #include #include #include "e1000.h" @@ -104,9 +105,9 @@ struct e1000_dev { uint32_t io_mem_base; uint32_t mem_size; int pci_dev_id; + uint16_t pci_addr; unsigned char src_mac[6]; unsigned char dst_mac[6]; - int irq; struct irq_action int_desc; struct tx_ring tx_ring; struct rx_ring rx_ring; @@ -308,16 +309,16 @@ void e1000_init(struct e1000_dev *dev) e1000_outl(dev, E1000_FCRTH, pba*9/10); // setup tx rings - txd_phys = PADDR(dev->tx_ring.desc); - kmem_phys = PADDR(dev->tx_ring.buf); + txd_phys = PADDR((uintptr_t)dev->tx_ring.desc); + kmem_phys = PADDR((uintptr_t)dev->tx_ring.buf); for (i=0; itx_ring.desc[i].base_address = kmem_phys; - dev->tx_ring.desc[i].packet_length = 0; - dev->tx_ring.desc[i].cksum_offset = 0; - dev->tx_ring.desc[i].cksum_origin = 0; - dev->tx_ring.desc[i].desc_status = 1; - dev->tx_ring.desc[i].desc_command = (1<<0)|(1<<1)|(1<<3); - dev->tx_ring.desc[i].special_info = 0; + dev->tx_ring.desc[i].base_address = kmem_phys; + dev->tx_ring.desc[i].packet_length = 0; + dev->tx_ring.desc[i].cksum_offset = 0; + dev->tx_ring.desc[i].cksum_origin = 0; + dev->tx_ring.desc[i].desc_status = 1; + dev->tx_ring.desc[i].desc_command = (1<<0)|(1<<1)|(1<<3); + dev->tx_ring.desc[i].special_info = 0; } dev->tx_ring.tail = 0; e1000_outl(dev, E1000_TDT, 0); @@ -329,15 +330,15 @@ void e1000_init(struct e1000_dev *dev) e1000_outl(dev, E1000_TXDCTL, 0x01010000); // setup rx rings - rxd_phys = PADDR(dev->rx_ring.desc); - kmem_phys = PADDR(dev->rx_ring.buf); + rxd_phys = PADDR((uintptr_t)dev->rx_ring.desc); + kmem_phys = PADDR((uintptr_t)dev->rx_ring.buf); for (i=0; irx_ring.desc[i].base_address = kmem_phys; - dev->rx_ring.desc[i].packet_length = 0; - dev->rx_ring.desc[i].packet_cksum = 0; - dev->rx_ring.desc[i].desc_status = 0; - dev->rx_ring.desc[i].desc_errors = 0; - dev->rx_ring.desc[i].vlan_tag = 0; + dev->rx_ring.desc[i].base_address = kmem_phys; + dev->rx_ring.desc[i].packet_length = 0; + dev->rx_ring.desc[i].packet_cksum = 0; + dev->rx_ring.desc[i].desc_status = 0; + dev->rx_ring.desc[i].desc_errors = 0; + dev->rx_ring.desc[i].vlan_tag = 0; } dev->rx_ring.head = 0; dev->rx_ring.tail = CONFIG_E1000_N_RX_DESC-1; @@ -378,7 +379,7 @@ static int e1000_transmit(struct e1000_dev *e1000) { int tail = e1000->tx_ring.tail; unsigned char *cp = (unsigned char *) - (e1000->tx_ring.buf + tail * CONFIG_E1000_BUFF_SIZE); + (e1000->tx_ring.buf + tail * CONFIG_E1000_BUFF_SIZE); int count = e1000->uip_dev.d_len; /* Verify that the hardware is ready to send another packet. If we get @@ -387,7 +388,7 @@ static int e1000_transmit(struct e1000_dev *e1000) */ if (!e1000->tx_ring.desc[tail].desc_status) - return -1; + return -1; /* Increment statistics */ @@ -445,14 +446,14 @@ static int e1000_uiptxpoll(struct uip_driver_s *dev) */ if (e1000->uip_dev.d_len > 0) { - uip_arp_out(&e1000->uip_dev); - e1000_transmit(e1000); + uip_arp_out(&e1000->uip_dev); + e1000_transmit(e1000); - /* Check if there is room in the device to hold another packet. If not, - * return a non-zero value to terminate the poll. - */ - if (!e1000->tx_ring.desc[tail].desc_status) - return -1; + /* Check if there is room in the device to hold another packet. If not, + * return a non-zero value to terminate the poll. + */ + if (!e1000->tx_ring.desc[tail].desc_status) + return -1; } /* If zero is returned, the polling will continue until all connections have @@ -483,75 +484,75 @@ static void e1000_receive(struct e1000_dev *e1000) { int head = e1000->rx_ring.head; unsigned char *cp = (unsigned char *) - (e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); + (e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); int cnt; while (e1000->rx_ring.desc[head].desc_status) { - /* Check for errors and update statistics */ + /* Check for errors and update statistics */ - // Here we do not handle packets that exceed packet-buffer size - if ((e1000->rx_ring.desc[head].desc_status & 3) == 1) { - cprintf("NIC READ: Oversized packet\n"); - goto next; - } + // Here we do not handle packets that exceed packet-buffer size + if ((e1000->rx_ring.desc[head].desc_status & 3) == 1) { + cprintf("NIC READ: Oversized packet\n"); + goto next; + } - /* Check if the packet is a valid size for the uIP buffer configuration */ + /* Check if the packet is a valid size for the uIP buffer configuration */ - // get the number of actual data-bytes in this packet - cnt = e1000->rx_ring.desc[head].packet_length; + // get the number of actual data-bytes in this packet + cnt = e1000->rx_ring.desc[head].packet_length; - if (cnt > CONFIG_NET_BUFSIZE || cnt < 14) { - cprintf("NIC READ: invalid package size\n"); - goto next; - } + if (cnt > CONFIG_NET_BUFSIZE || cnt < 14) { + cprintf("NIC READ: invalid package size\n"); + goto next; + } - /* Copy the data data from the hardware to e1000->uip_dev.d_buf. Set - * amount of data in e1000->uip_dev.d_len - */ + /* Copy the data data from the hardware to e1000->uip_dev.d_buf. Set + * amount of data in e1000->uip_dev.d_len + */ - // now we try to copy these data-bytes to the UIP buffer - memcpy(e1000->uip_dev.d_buf, cp, cnt); - e1000->uip_dev.d_len = cnt; + // now we try to copy these data-bytes to the UIP buffer + memcpy(e1000->uip_dev.d_buf, cp, cnt); + e1000->uip_dev.d_len = cnt; - /* We only accept IP packets of the configured type and ARP packets */ + /* We only accept IP packets of the configured type and ARP packets */ #ifdef CONFIG_NET_IPv6 - if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) #else - if (BUF->type == HTONS(UIP_ETHTYPE_IP)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP)) #endif - { - uip_arp_ipin(&e1000->uip_dev); - uip_input(&e1000->uip_dev); + { + uip_arp_ipin(&e1000->uip_dev); + uip_input(&e1000->uip_dev); - /* If the above function invocation resulted in data that should be - * sent out on the network, the field d_len will set to a value > 0. - */ + /* If the above function invocation resulted in data that should be + * sent out on the network, the field d_len will set to a value > 0. + */ - if (e1000->uip_dev.d_len > 0) { - uip_arp_out(&e1000->uip_dev); - e1000_transmit(e1000); - } - } - else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { - uip_arp_arpin(&e1000->uip_dev); + if (e1000->uip_dev.d_len > 0) { + uip_arp_out(&e1000->uip_dev); + e1000_transmit(e1000); + } + } + else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { + uip_arp_arpin(&e1000->uip_dev); - /* If the above function invocation resulted in data that should be - * sent out on the network, the field d_len will set to a value > 0. - */ + /* If the above function invocation resulted in data that should be + * sent out on the network, the field d_len will set to a value > 0. + */ - if (e1000->uip_dev.d_len > 0) { - e1000_transmit(e1000); - } - } + if (e1000->uip_dev.d_len > 0) { + e1000_transmit(e1000); + } + } next: - e1000->rx_ring.desc[head].desc_status = 0; - e1000->rx_ring.head = (head + 1) % CONFIG_E1000_N_RX_DESC; - e1000->rx_ring.free++; - head = e1000->rx_ring.head; - cp = (unsigned char *)(e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); + e1000->rx_ring.desc[head].desc_status = 0; + e1000->rx_ring.head = (head + 1) % CONFIG_E1000_N_RX_DESC; + e1000->rx_ring.free++; + head = e1000->rx_ring.head; + cp = (unsigned char *)(e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); } } @@ -615,7 +616,7 @@ static void e1000_polltimer(int argc, uint32_t arg, ...) * the TX poll if he are unable to accept another packet for transmission. */ if (!e1000->tx_ring.desc[tail].desc_status) - return; + return; /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm.. * might be bug here. Does this mean if there is a transmit in progress, @@ -651,8 +652,8 @@ static int e1000_ifup(struct uip_driver_s *dev) struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; ndbg("Bringing up: %d.%d.%d.%d\n", - dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, - (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); + dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, + (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ e1000_init(e1000); @@ -662,9 +663,9 @@ static int e1000_ifup(struct uip_driver_s *dev) (void)wd_start(e1000->txpoll, E1000_WDDELAY, e1000_polltimer, 1, (uint32_t)e1000); if (e1000_inl(e1000, E1000_STATUS) & 2) - e1000->bifup = true; + e1000->bifup = true; else - e1000->bifup = false; + e1000->bifup = false; return OK; } @@ -749,9 +750,9 @@ static int e1000_txavail(struct uip_driver_s *dev) /* Ignore the notification if the interface is not yet up */ if (e1000->bifup) { - /* Check if there is room in the hardware to hold another outgoing packet. */ - if (e1000->tx_ring.desc[tail].desc_status) - (void)uip_poll(&e1000->uip_dev, e1000_uiptxpoll); + /* Check if there is room in the hardware to hold another outgoing packet. */ + if (e1000->tx_ring.desc[tail].desc_status) + (void)uip_poll(&e1000->uip_dev, e1000_uiptxpoll); } irqrestore(flags); @@ -779,11 +780,11 @@ static int e1000_txavail(struct uip_driver_s *dev) #ifdef CONFIG_NET_IGMP static int e1000_addmac(struct uip_driver_s *dev, const uint8_t *mac) { - struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; + struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif @@ -808,15 +809,15 @@ static int e1000_addmac(struct uip_driver_s *dev, const uint8_t *mac) #ifdef CONFIG_NET_IGMP static int e1000_rmmac(struct uip_driver_s *dev, const uint8_t *mac) { - struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; + struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif -irqreturn_t e1000_interrupt_handler(struct Trapframe *tf, void *dev_id) +static irqreturn_t e1000_interrupt_handler(int irq, void *dev_id) { struct e1000_dev *e1000 = (struct e1000_dev *)dev_id; @@ -826,27 +827,27 @@ irqreturn_t e1000_interrupt_handler(struct Trapframe *tf, void *dev_id) // not for me if (intr_cause == 0) - return IRQ_NONE; + return IRQ_NONE; /* Handle interrupts according to status bit settings */ // Link status change if (intr_cause & (1<<2)) { - if (e1000_inl(e1000, E1000_STATUS) & 2) - e1000->bifup = true; - else - e1000->bifup = false; + if (e1000_inl(e1000, E1000_STATUS) & 2) + e1000->bifup = true; + else + e1000->bifup = false; } /* Check if we received an incoming packet, if so, call skel_receive() */ // Rx-descriptor Timer expired if (intr_cause & (1<<7)) - e1000_receive(e1000); + e1000_receive(e1000); // Tx queue empty if (intr_cause & (1<<1)) - wd_cancel(e1000->txtimeout); + wd_cancel(e1000->txtimeout); /* Check is a packet transmission just completed. If so, call skel_txdone. * This may disable further Tx interrupts if there are no pending @@ -855,17 +856,17 @@ irqreturn_t e1000_interrupt_handler(struct Trapframe *tf, void *dev_id) // Tx-descriptor Written back if (intr_cause & (1<<0)) - uip_poll(&e1000->uip_dev, e1000_uiptxpoll); + uip_poll(&e1000->uip_dev, e1000_uiptxpoll); // Rx-Descriptors Low if (intr_cause & (1<<4)) { - int tail; - tail = e1000->rx_ring.tail + e1000->rx_ring.free; - tail %= CONFIG_E1000_N_RX_DESC; - e1000->rx_ring.tail = tail; - e1000->rx_ring.free = 0; - e1000_outl(e1000, E1000_RDT, tail); + int tail; + tail = e1000->rx_ring.tail + e1000->rx_ring.free; + tail %= CONFIG_E1000_N_RX_DESC; + e1000->rx_ring.tail = tail; + e1000->rx_ring.free = 0; + e1000_outl(e1000, E1000_RDT, tail); } return IRQ_HANDLED; @@ -885,20 +886,21 @@ static pci_id_t e1000_id_table[] = { static int e1000_probe(uint16_t addr, pci_id_t id) { uint32_t mmio_base, mmio_size; - uint32_t pci_cmd, size; - int err, irq, flags; + uint32_t size; + int err; void *kmem, *omem; struct e1000_dev *dev; // alloc e1000_dev memory - dev = kzalloc(sizeof(struct e1000_dev)); - if (dev == NULL) - return -1; + if ((dev = kzalloc(sizeof(struct e1000_dev))) == NULL) + return -1; + + // save pci addr + dev->pci_addr = addr; // enable device - err = pci_enable_device(addr, PCI_RESOURCE_MEM); - if (err) - goto error; + if ((err = pci_enable_device(addr, PCI_BUS_MASTER)) < 0) + goto error; // get e1000 device type dev->pci_dev_id = id.join; @@ -908,33 +910,20 @@ static int e1000_probe(uint16_t addr, pci_id_t id) mmio_size = pci_resource_len(addr, 0); err = rgmp_memmap_nocache(mmio_base, mmio_size, mmio_base); if (err) - goto error; + goto error; dev->phy_mem_base = mmio_base; dev->io_mem_base = mmio_base; dev->mem_size = mmio_size; - // make sure the controller's Bus Master capability is enabled - pci_cmd = pci_config_readl(addr, PCI_COMMAND); - pci_cmd |= (1<<2); - pci_config_writel(addr, PCI_COMMAND, pci_cmd); - // MAC address memset(dev->dst_mac, 0xFF, 6); memcpy(dev->src_mac, (void *)(dev->io_mem_base+E1000_RA), 6); - // get e1000 IRQ - flags = 0; - irq = pci_enable_msi(addr); - if (irq == 0) { - irq = pci_read_irq(addr); - flags |= IDC_SHARE; - } - dev->irq = irq; + // IRQ setup dev->int_desc.handler = e1000_interrupt_handler; dev->int_desc.dev_id = dev; - err = rgmp_request_irq(irq, &dev->int_desc, flags); - if (err) - goto err0; + if ((err = pci_request_irq(addr, &dev->int_desc, 0)) < 0) + goto err0; // Here we alloc a big block of memory once and make it // aligned to page boundary and multiple of page size. This @@ -942,15 +931,19 @@ static int e1000_probe(uint16_t addr, pci_id_t id) // should be mapped no-cache which will hugely reduce memory // access performance. The page size alloc will restrict // this bad effect only within the memory we alloc here. + // + // NEED FIX: the memalign may alloc memory continous in + // virtual address but dis-continous in physical address + // due to RGMP memory setup. size = CONFIG_E1000_N_TX_DESC * sizeof(struct tx_desc) + - CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + - CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + - CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; + CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + + CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + + CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; size = ROUNDUP(size, PGSIZE); omem = kmem = memalign(PGSIZE, size); if (kmem == NULL) { - err = -ENOMEM; - goto err1; + err = -ENOMEM; + goto err1; } rgmp_memremap_nocache((uintptr_t)kmem, size); @@ -991,7 +984,7 @@ static int e1000_probe(uint16_t addr, pci_id_t id) /* Register the device with the OS so that socket IOCTLs can be performed */ err = netdev_register(&dev->uip_dev); if (err) - goto err2; + goto err2; // insert into e1000_list dev->next = e1000_list.next; @@ -1000,14 +993,14 @@ static int e1000_probe(uint16_t addr, pci_id_t id) return 0; - err2: +err2: rgmp_memremap((uintptr_t)omem, size); free(omem); - err1: - rgmp_free_irq(irq, &dev->int_desc); - err0: +err1: + pci_free_irq(addr); +err0: rgmp_memunmap(mmio_base, mmio_size); - error: +error: kfree(dev); cprintf("e1000 device probe fail: %d\n", err); return err; @@ -1028,21 +1021,21 @@ void e1000_mod_exit(void) struct e1000_dev *dev; size = CONFIG_E1000_N_TX_DESC * sizeof(struct tx_desc) + - CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + - CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + - CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; + CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + + CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + + CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; size = ROUNDUP(size, PGSIZE); for (dev=e1000_list.next; dev!=NULL; dev=dev->next) { - netdev_unregister(&dev->uip_dev); - e1000_reset(dev); - wd_delete(dev->txpoll); - wd_delete(dev->txtimeout); - rgmp_memremap((uintptr_t)dev->tx_ring.desc, size); - free(dev->tx_ring.desc); - rgmp_free_irq(dev->irq, &dev->int_desc); - rgmp_memunmap((uintptr_t)dev->io_mem_base, dev->mem_size); - kfree(dev); + netdev_unregister(&dev->uip_dev); + e1000_reset(dev); + wd_delete(dev->txpoll); + wd_delete(dev->txtimeout); + rgmp_memremap((uintptr_t)dev->tx_ring.desc, size); + free(dev->tx_ring.desc); + pci_free_irq(dev->pci_addr); + rgmp_memunmap((uintptr_t)dev->io_mem_base, dev->mem_size); + kfree(dev); } e1000_list.next = NULL; diff --git a/nuttx/drivers/net/e1000.h b/nuttx/drivers/net/e1000.h index 6614ad77ec..63ff53e3c3 100644 --- a/nuttx/drivers/net/e1000.h +++ b/nuttx/drivers/net/e1000.h @@ -44,9 +44,7 @@ * Included Files ****************************************************************************/ -#include -#include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/drivers/net/vnet.c b/nuttx/drivers/net/vnet.c index f1e2465b96..e05a39675c 100644 --- a/nuttx/drivers/net/vnet.c +++ b/nuttx/drivers/net/vnet.c @@ -168,30 +168,30 @@ static int vnet_transmit(FAR struct vnet_driver_s *vnet) { int err; - /* Verify that the hardware is ready to send another packet. If we get - * here, then we are committed to sending a packet; Higher level logic - * must have assured that there is not transmission in progress. - */ + /* Verify that the hardware is ready to send another packet. If we get + * here, then we are committed to sending a packet; Higher level logic + * must have assured that there is not transmission in progress. + */ - /* Increment statistics */ + /* Increment statistics */ - /* Send the packet: address=vnet->sk_dev.d_buf, length=vnet->sk_dev.d_len */ + /* Send the packet: address=vnet->sk_dev.d_buf, length=vnet->sk_dev.d_len */ err = vnet_xmit(vnet->vnet, (char *)vnet->sk_dev.d_buf, vnet->sk_dev.d_len); if (err) { - /* Setup the TX timeout watchdog (perhaps restarting the timer) */ - //(void)wd_start(vnet->sk_txtimeout, VNET_TXTIMEOUT, vnet_txtimeout, 1, (uint32_t)vnet); + /* Setup the TX timeout watchdog (perhaps restarting the timer) */ + //(void)wd_start(vnet->sk_txtimeout, VNET_TXTIMEOUT, vnet_txtimeout, 1, (uint32_t)vnet); - // When vnet_xmit fail, it means TX buffer is full. Watchdog - // is of no use here because no TX done INT will happen. So - // we reset the TX buffer directly. + // When vnet_xmit fail, it means TX buffer is full. Watchdog + // is of no use here because no TX done INT will happen. So + // we reset the TX buffer directly. #ifdef CONFIG_DEBUG - cprintf("VNET: TX buffer is full\n"); + cprintf("VNET: TX buffer is full\n"); #endif - return ERROR; + return ERROR; } else { - // this step may be unnecessary here - vnet_txdone(vnet); + // this step may be unnecessary here + vnet_txdone(vnet); } return OK; @@ -223,29 +223,29 @@ static int vnet_transmit(FAR struct vnet_driver_s *vnet) static int vnet_uiptxpoll(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - /* If the polling resulted in data that should be sent out on the network, - * the field d_len is set to a value > 0. - */ + /* If the polling resulted in data that should be sent out on the network, + * the field d_len is set to a value > 0. + */ - if (vnet->sk_dev.d_len > 0) + if (vnet->sk_dev.d_len > 0) { - uip_arp_out(&vnet->sk_dev); - vnet_transmit(vnet); + uip_arp_out(&vnet->sk_dev); + vnet_transmit(vnet); - /* Check if there is room in the device to hold another packet. If not, - * return a non-zero value to terminate the poll. - */ - if (vnet_is_txbuff_full(vnet->vnet)) - return 1; + /* Check if there is room in the device to hold another packet. If not, + * return a non-zero value to terminate the poll. + */ + if (vnet_is_txbuff_full(vnet->vnet)) + return 1; } - /* If zero is returned, the polling will continue until all connections have - * been examined. - */ + /* If zero is returned, the polling will continue until all connections have + * been examined. + */ - return 0; + return 0; } /**************************************************************************** @@ -265,54 +265,53 @@ static int vnet_uiptxpoll(struct uip_driver_s *dev) * ****************************************************************************/ -void rtos_vnet_recv(struct rgmp_vnet *vnet_dummy, char *data, int len) +void rtos_vnet_recv(struct rgmp_vnet *rgmp_vnet, char *data, int len) { - // now only support 1 vnet - struct vnet_driver_s *vnet = &g_vnet[0]; + struct vnet_driver_s *vnet = rgmp_vnet->priv; do { - /* Check for errors and update statistics */ + /* Check for errors and update statistics */ - /* Check if the packet is a valid size for the uIP buffer configuration */ - if (len > CONFIG_NET_BUFSIZE || len < 14) { + /* Check if the packet is a valid size for the uIP buffer configuration */ + if (len > CONFIG_NET_BUFSIZE || len < 14) { #ifdef CONFIG_DEBUG - cprintf("VNET: receive invalid packet of size %d\n", len); + cprintf("VNET: receive invalid packet of size %d\n", len); #endif - return; - } + return; + } - // Copy the data data from the hardware to vnet->sk_dev.d_buf. Set - // amount of data in vnet->sk_dev.d_len - memcpy(vnet->sk_dev.d_buf, data, len); - vnet->sk_dev.d_len = len; + // Copy the data data from the hardware to vnet->sk_dev.d_buf. Set + // amount of data in vnet->sk_dev.d_len + memcpy(vnet->sk_dev.d_buf, data, len); + vnet->sk_dev.d_len = len; - /* We only accept IP packets of the configured type and ARP packets */ + /* We only accept IP packets of the configured type and ARP packets */ #ifdef CONFIG_NET_IPv6 - if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) #else - if (BUF->type == HTONS(UIP_ETHTYPE_IP)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP)) #endif - { - uip_arp_ipin(&vnet->sk_dev); - uip_input(&vnet->sk_dev); + { + uip_arp_ipin(&vnet->sk_dev); + uip_input(&vnet->sk_dev); - // If the above function invocation resulted in data that should be - // sent out on the network, the field d_len will set to a value > 0. - if (vnet->sk_dev.d_len > 0) { - uip_arp_out(&vnet->sk_dev); - vnet_transmit(vnet); - } - } - else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { - uip_arp_arpin(&vnet->sk_dev); + // If the above function invocation resulted in data that should be + // sent out on the network, the field d_len will set to a value > 0. + if (vnet->sk_dev.d_len > 0) { + uip_arp_out(&vnet->sk_dev); + vnet_transmit(vnet); + } + } + else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { + uip_arp_arpin(&vnet->sk_dev); - // If the above function invocation resulted in data that should be - // sent out on the network, the field d_len will set to a value > 0. - if (vnet->sk_dev.d_len > 0) { - vnet_transmit(vnet); - } - } + // If the above function invocation resulted in data that should be + // sent out on the network, the field d_len will set to a value > 0. + if (vnet->sk_dev.d_len > 0) { + vnet_transmit(vnet); + } + } } while (0); /* While there are more packets to be processed */ } @@ -336,17 +335,17 @@ void rtos_vnet_recv(struct rgmp_vnet *vnet_dummy, char *data, int len) static void vnet_txdone(FAR struct vnet_driver_s *vnet) { - /* Check for errors and update statistics */ + /* Check for errors and update statistics */ - /* If no further xmits are pending, then cancel the TX timeout and - * disable further Tx interrupts. - */ + /* If no further xmits are pending, then cancel the TX timeout and + * disable further Tx interrupts. + */ - //wd_cancel(vnet->sk_txtimeout); + //wd_cancel(vnet->sk_txtimeout); - /* Then poll uIP for new XMIT data */ + /* Then poll uIP for new XMIT data */ - (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); + (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); } /**************************************************************************** @@ -370,15 +369,15 @@ static void vnet_txdone(FAR struct vnet_driver_s *vnet) static void vnet_txtimeout(int argc, uint32_t arg, ...) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; - /* Increment statistics and dump debug info */ + /* Increment statistics and dump debug info */ - /* Then reset the hardware */ + /* Then reset the hardware */ - /* Then poll uIP for new XMIT data */ + /* Then poll uIP for new XMIT data */ - (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); + (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); } /**************************************************************************** @@ -401,28 +400,28 @@ static void vnet_txtimeout(int argc, uint32_t arg, ...) static void vnet_polltimer(int argc, uint32_t arg, ...) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; - /* Check if there is room in the send another TX packet. We cannot perform - * the TX poll if he are unable to accept another packet for transmission. - */ - if (vnet_is_txbuff_full(vnet->vnet)) { + /* Check if there is room in the send another TX packet. We cannot perform + * the TX poll if he are unable to accept another packet for transmission. + */ + if (vnet_is_txbuff_full(vnet->vnet)) { #ifdef CONFIG_DEBUG - cprintf("VNET: TX buffer is full\n"); + cprintf("VNET: TX buffer is full\n"); #endif - return; - } + return; + } - /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm.. - * might be bug here. Does this mean if there is a transmit in progress, - * we will missing TCP time state updates? - */ + /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm.. + * might be bug here. Does this mean if there is a transmit in progress, + * we will missing TCP time state updates? + */ - (void)uip_timer(&vnet->sk_dev, vnet_uiptxpoll, VNET_POLLHSEC); + (void)uip_timer(&vnet->sk_dev, vnet_uiptxpoll, VNET_POLLHSEC); - /* Setup the watchdog poll timer again */ + /* Setup the watchdog poll timer again */ - (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, arg); + (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, arg); } /**************************************************************************** @@ -444,20 +443,20 @@ static void vnet_polltimer(int argc, uint32_t arg, ...) static int vnet_ifup(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - ndbg("Bringing up: %d.%d.%d.%d\n", - dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, - (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); + ndbg("Bringing up: %d.%d.%d.%d\n", + dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, + (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); - /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ + /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ - /* Set and activate a timer process */ + /* Set and activate a timer process */ - (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, (uint32_t)vnet); + (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, (uint32_t)vnet); - vnet->sk_bifup = true; - return OK; + vnet->sk_bifup = true; + return OK; } /**************************************************************************** @@ -478,28 +477,28 @@ static int vnet_ifup(struct uip_driver_s *dev) static int vnet_ifdown(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - irqstate_t flags; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + irqstate_t flags; - /* Disable the Ethernet interrupt */ + /* Disable the Ethernet interrupt */ - flags = irqsave(); + flags = irqsave(); - /* Cancel the TX poll timer and TX timeout timers */ + /* Cancel the TX poll timer and TX timeout timers */ - wd_cancel(vnet->sk_txpoll); - //wd_cancel(vnet->sk_txtimeout); + wd_cancel(vnet->sk_txpoll); + //wd_cancel(vnet->sk_txtimeout); - /* Put the the EMAC is its reset, non-operational state. This should be - * a known configuration that will guarantee the vnet_ifup() always - * successfully brings the interface back up. - */ + /* Put the the EMAC is its reset, non-operational state. This should be + * a known configuration that will guarantee the vnet_ifup() always + * successfully brings the interface back up. + */ - /* Mark the device "down" */ + /* Mark the device "down" */ - vnet->sk_bifup = false; - irqrestore(flags); - return OK; + vnet->sk_bifup = false; + irqrestore(flags); + return OK; } /**************************************************************************** @@ -523,35 +522,35 @@ static int vnet_ifdown(struct uip_driver_s *dev) static int vnet_txavail(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - irqstate_t flags; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + irqstate_t flags; - /* Disable interrupts because this function may be called from interrupt - * level processing. - */ + /* Disable interrupts because this function may be called from interrupt + * level processing. + */ - flags = irqsave(); + flags = irqsave(); - /* Ignore the notification if the interface is not yet up */ + /* Ignore the notification if the interface is not yet up */ - if (vnet->sk_bifup) + if (vnet->sk_bifup) { - /* Check if there is room in the hardware to hold another outgoing packet. */ - if (vnet_is_txbuff_full(vnet->vnet)) { + /* Check if there is room in the hardware to hold another outgoing packet. */ + if (vnet_is_txbuff_full(vnet->vnet)) { #ifdef CONFIG_DEBUG - cprintf("VNET: TX buffer is full\n"); + cprintf("VNET: TX buffer is full\n"); #endif - goto out; - } + goto out; + } - /* If so, then poll uIP for new XMIT data */ + /* If so, then poll uIP for new XMIT data */ - (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); + (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); } - out: - irqrestore(flags); - return OK; +out: + irqrestore(flags); + return OK; } /**************************************************************************** @@ -575,11 +574,11 @@ static int vnet_txavail(struct uip_driver_s *dev) #ifdef CONFIG_NET_IGMP static int vnet_addmac(struct uip_driver_s *dev, FAR const uint8_t *mac) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif @@ -604,11 +603,11 @@ static int vnet_addmac(struct uip_driver_s *dev, FAR const uint8_t *mac) #ifdef CONFIG_NET_IGMP static int vnet_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif @@ -633,41 +632,41 @@ static int vnet_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac) * ****************************************************************************/ -void vnet_initialize(void) +int vnet_init(struct rgmp_vnet *vnet) { - struct vnet_driver_s *priv; - struct rgmp_vnet *vnet = vnet_list.next; - int i; + struct vnet_driver_s *priv; + static int i = 0; - for (i=0; i= CONFIG_VNET_NINTERFACES) + return -1; - /* Initialize the driver structure */ + priv = &g_vnet[i++]; - memset(priv, 0, sizeof(struct vnet_driver_s)); - priv->sk_dev.d_ifup = vnet_ifup; /* I/F down callback */ - priv->sk_dev.d_ifdown = vnet_ifdown; /* I/F up (new IP address) callback */ - priv->sk_dev.d_txavail = vnet_txavail; /* New TX data callback */ + /* Initialize the driver structure */ + + memset(priv, 0, sizeof(struct vnet_driver_s)); + priv->sk_dev.d_ifup = vnet_ifup; /* I/F down callback */ + priv->sk_dev.d_ifdown = vnet_ifdown; /* I/F up (new IP address) callback */ + priv->sk_dev.d_txavail = vnet_txavail; /* New TX data callback */ #ifdef CONFIG_NET_IGMP - priv->sk_dev.d_addmac = vnet_addmac; /* Add multicast MAC address */ - priv->sk_dev.d_rmmac = vnet_rmmac; /* Remove multicast MAC address */ + priv->sk_dev.d_addmac = vnet_addmac; /* Add multicast MAC address */ + priv->sk_dev.d_rmmac = vnet_rmmac; /* Remove multicast MAC address */ #endif - priv->sk_dev.d_private = (void*)g_vnet; /* Used to recover private state from dev */ + priv->sk_dev.d_private = (void*)priv; /* Used to recover private state from dev */ - /* Create a watchdog for timing polling for and timing of transmisstions */ + /* Create a watchdog for timing polling for and timing of transmisstions */ - priv->sk_txpoll = wd_create(); /* Create periodic poll timer */ - //priv->sk_txtimeout = wd_create(); /* Create TX timeout timer */ + priv->sk_txpoll = wd_create(); /* Create periodic poll timer */ + //priv->sk_txtimeout = wd_create(); /* Create TX timeout timer */ - priv->vnet = vnet; + priv->vnet = vnet; + vnet->priv = priv; - /* Register the device with the OS */ + /* Register the device with the OS */ - (void)netdev_register(&priv->sk_dev); - vnet = vnet->next; - } + (void)netdev_register(&priv->sk_dev); + + return 0; } #endif /* CONFIG_NET && CONFIG_NET_VNET */ diff --git a/nuttx/lib/Kconfig b/nuttx/lib/Kconfig index 440e9c3e25..1c93bb0475 100644 --- a/nuttx/lib/Kconfig +++ b/nuttx/lib/Kconfig @@ -223,6 +223,13 @@ config MEMSET_64BIT Compiles memset() for architectures that suppport 64-bit operations efficiently. +config ARCH_STRCHR + bool "strchr()" + default n + ---help--- + Select this option if the architecture provides an optimized version + of strchr(). + config ARCH_STRCMP bool "strcmp()" default n diff --git a/nuttx/lib/string/lib_strchr.c b/nuttx/lib/string/lib_strchr.c index ad72738620..d0bd22a0ea 100644 --- a/nuttx/lib/string/lib_strchr.c +++ b/nuttx/lib/string/lib_strchr.c @@ -59,6 +59,7 @@ * ****************************************************************************/ +#ifndef CONFIG_ARCH_STRCHR FAR char *strchr(FAR const char *s, int c) { if (s) @@ -74,3 +75,4 @@ FAR char *strchr(FAR const char *s, int c) return NULL; } +#endif From 9583fa1abd79dfcc8610d8dbb4cc6c4d91c3bb5f Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 4 Nov 2012 16:08:02 +0000 Subject: [PATCH 075/206] Relay example from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5306 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 1 + apps/examples/Kconfig | 1 + apps/examples/Make.defs | 4 + apps/examples/Makefile | 8 +- apps/examples/README.txt | 28 ++-- apps/examples/relays/Kconfig | 20 +++ apps/examples/relays/Makefile | 105 ++++++++++++ apps/examples/relays/relays_main.c | 154 ++++++++++++++++++ nuttx/configs/shenzhou/include/board.h | 16 +- .../configs/shenzhou/src/shenzhou-internal.h | 4 +- nuttx/configs/shenzhou/src/up_relays.c | 17 +- nuttx/include/nuttx/arch.h | 22 +++ 12 files changed, 357 insertions(+), 23 deletions(-) create mode 100644 apps/examples/relays/Kconfig create mode 100644 apps/examples/relays/Makefile create mode 100644 apps/examples/relays/relays_main.c diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index ff90d50dd8..0c4e94fd93 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -399,3 +399,4 @@ Qiang Yu and the RGMP team. * apps/netutils/webclient, apps/netutils.codes, and apps/examples/wgetjson: Add support for wget POST interface. Contributed by Darcy Gong. + * apps/examples/relays: A relay example contributed by Darcy Gong. diff --git a/apps/examples/Kconfig b/apps/examples/Kconfig index f7a923b944..c0d126ad47 100644 --- a/apps/examples/Kconfig +++ b/apps/examples/Kconfig @@ -39,6 +39,7 @@ source "$APPSDIR/examples/pipe/Kconfig" source "$APPSDIR/examples/poll/Kconfig" source "$APPSDIR/examples/pwm/Kconfig" source "$APPSDIR/examples/qencoder/Kconfig" +source "$APPSDIR/examples/relays/Kconfig" source "$APPSDIR/examples/rgmp/Kconfig" source "$APPSDIR/examples/romfs/Kconfig" source "$APPSDIR/examples/sendmail/Kconfig" diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index 8d36aaa409..1c61513844 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -178,6 +178,10 @@ ifeq ($(CONFIG_EXAMPLES_QENCODER),y) CONFIGURED_APPS += examples/qencoder endif +ifeq ($(CONFIG_EXAMPLES_RELAYS),y) +CONFIGURED_APPS += examples/relays +endif + ifeq ($(CONFIG_EXAMPLES_RGMP),y) CONFIGURED_APPS += examples/rgmp endif diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 0eaffbc15e..8e058998f2 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -40,9 +40,9 @@ SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf ftpc SUBDIRS += ftpd hello helloxx hidkbd igmp json lcdrw mm modbus mount SUBDIRS += nettest nsh null nx nxconsole nxffs nxflat nxhello nximage -SUBDIRS += nxlines nxtext ostest pashello pipe poll pwm qencoder rgmp -SUBDIRS += romfs serloop telnetd thttpd tiff touchscreen udp uip usbserial -SUBDIRS += sendmail usbstorage usbterm watchdog wget wgetjson wlan +SUBDIRS += nxlines nxtext ostest pashello pipe poll pwm qencoder relays +SUBDIRS += rgmp romfs serloop telnetd thttpd tiff touchscreen udp uip +SUBDIRS += usbserial sendmail usbstorage usbterm watchdog wget wgetjson wlan # Sub-directories that might need context setup. Directories may need # context setup for a variety of reasons, but the most common is because @@ -58,7 +58,7 @@ CNTXTDIRS = pwm ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) CNTXTDIRS += adc can cdcacm composite cxxtestdhcpd discover ftpd json -CNTXTDIRS += modbus nettest qencoder telnetd watchdog wgetjson +CNTXTDIRS += modbus nettest relays qencoder telnetd watchdog wgetjson endif ifeq ($(CONFIG_EXAMPLES_HELLO_BUILTIN),y) diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 3f24ec4e29..fd0dcf5c50 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -1208,17 +1208,23 @@ examples/qencoder Specific configuration options for this example include: - CONFIG_EXAMPLES_QENCODER_DEVPATH - The path to the QE device. Default: - /dev/qe0 - CONFIG_EXAMPLES_QENCODER_NSAMPLES - If CONFIG_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: Samples are collected - indefinitely. - CONFIG_EXAMPLES_QENCODER_DELAY - This value provides the delay (in - milliseonds) between each sample. If CONFIG_NSH_BUILTIN_APPS - is defined, then this value is the default delay if no other delay is - provided on the command line. Default: 100 milliseconds + CONFIG_EXAMPLES_QENCODER_DEVPATH - The path to the QE device. Default: + /dev/qe0 + CONFIG_EXAMPLES_QENCODER_NSAMPLES - If CONFIG_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: Samples are collected + indefinitely. + CONFIG_EXAMPLES_QENCODER_DELAY - This value provides the delay (in + milliseonds) between each sample. If CONFIG_NSH_BUILTIN_APPS + is defined, then this value is the default delay if no other delay is + provided on the command line. Default: 100 milliseconds + +examples/relays +^^^^^^^^^^^^^^^ + + Requires CONFIG_ARCH_RELAYS. + Contributed by Darcy Gong. examples/rgmp ^^^^^^^^^^^^^ diff --git a/apps/examples/relays/Kconfig b/apps/examples/relays/Kconfig new file mode 100644 index 0000000000..1e1f9aa5b6 --- /dev/null +++ b/apps/examples/relays/Kconfig @@ -0,0 +1,20 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config EXAMPLES_RELAYS + bool "wget JSON Example" + default n + depends on NETUTILS_JSON + ---help--- + Enable the wget JSON example + +if EXAMPLES_RELAYS + +config EXAMPLES_RELAYS_NRELAYS + int "Number of Relays" + default 2 + depends on ARCH_RELAYS + +endif diff --git a/apps/examples/relays/Makefile b/apps/examples/relays/Makefile new file mode 100644 index 0000000000..6641c94b4a --- /dev/null +++ b/apps/examples/relays/Makefile @@ -0,0 +1,105 @@ +############################################################################ +# apps/examples/relays/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +# relays Example + +ASRC = +CSRC = relays_main.c + +AOBJ = $(ASRCS:.S=$(OBJEXT)) +COBJ = $(CSRCS:.c=$(OBJEXT)) + +SRC = $(ASRCS) $(CSRCS) +OBJ = $(AOBJS) $(COBJS) + +ifeq ($(WINTOOL),y) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" +else + BIN = "$(APPDIR)/libapps$(LIBEXT)" +endif + +ROOTDEPPATH = --dep-path . + +# Buttons built-in application info + +APPNAME = relays +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +# Common build + +VPATH = + +all: .built +.PHONY: context clean depend 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 + +.context: +ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) + $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) + @touch $@ +endif + +context: .context + +.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 Make.dep .depend + +-include Make.dep diff --git a/apps/examples/relays/relays_main.c b/apps/examples/relays/relays_main.c new file mode 100644 index 0000000000..c7ad6db0fd --- /dev/null +++ b/apps/examples/relays/relays_main.c @@ -0,0 +1,154 @@ +/**************************************************************************** + * examples/relays/relays_main.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: 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 +#include +#include +#include +#include +#include +#include +#include + +#include + +#ifdef CONFIG_ARCH_RELAYS + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#ifndef CONFIG_EXAMPLES_RELAYS_NRELAYS +# define CONFIG_EXAMPLES_RELAYS_NRELAYS 2 +#endif + + /**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: relays_main + ****************************************************************************/ + +int relays_main(int argc, char *argv[]) +{ + char *stat = NULL; + char *no = NULL; + bool badarg = false; + bool set_stat = false; + uint32_t r_stat; + int option; + int n = -1; + int ret = -1; + int i; + + while ((option = getopt(argc, argv, ":n:")) != ERROR) + { + switch (option) + { + case 'n': + no = optarg; + n = atoi(no); + break; + + case ':': + badarg = true; + break; + + case '?': + default: + badarg = true; + break; + } + } + + if (badarg) + { + printf("usage: relays [ -n ] \n"); + return -1; + } + + if (optind == argc - 1) + { + stat = argv[optind]; + set_stat = (!strcmp(stat,"on") || !strcmp(stat,"ON")) ? true : false ; + } + + up_relaysinit(); + + if (n >= 0) + { + printf("set RELAY ID %d to %s\n", n , set_stat ? "ON" : "OFF"); + relays_setstat(n,set_stat); + } + else + { + r_stat = 0; + for (i = 0; i < CONFIG_EXAMPLES_RELAYS_NRELAYS; i++) + { + printf("set RELAY ID %d to %s\n", i , set_stat ? "ON" : "OFF"); + r_stat |= (set_stat ? 1 : 0) << i; + } + + relays_setstats(r_stat); + } + + return 0; +} + +#endif /* CONFIG_ARCH_RELAYS */ diff --git a/nuttx/configs/shenzhou/include/board.h b/nuttx/configs/shenzhou/include/board.h index b0fc1b52d5..efc15c73d4 100644 --- a/nuttx/configs/shenzhou/include/board.h +++ b/nuttx/configs/shenzhou/include/board.h @@ -49,6 +49,8 @@ #include "stm32_sdio.h" #include "stm32_internal.h" +#include + /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ @@ -174,6 +176,10 @@ #define BUTTON_TAMPER_BIT BUTTON_KEY3_BIT #define BUTTON_WAKEUP_BIT BUTTON_KEY4_BIT +/* Relays */ + +#define NUM_RELAYS 2 + /* Pin selections ******************************************************************/ /* Ethernet * @@ -426,18 +432,20 @@ EXTERN void stm32_lcdclear(uint16_t color); * Relay control functions * * Description: - * Non-standard fucntions for relay control from the Shenzhou board. + * Non-standard functions for relay control from the Shenzhou board. + * + * NOTE: These must match the prototypes in include/nuttx/arch.h * ************************************************************************************/ #ifdef CONFIG_ARCH_RELAYS EXTERN void up_relaysinit(void); -EXTERN void relays_setstat(int relays,bool stat); +EXTERN void relays_setstat(int relays, bool stat); EXTERN bool relays_getstat(int relays); EXTERN void relays_setstats(uint32_t relays_stat); EXTERN uint32_t relays_getstats(void); -EXTERN void relays_onoff(int relays,uint32_t mdelay); -EXTERN void relays_onoffs(uint32_t relays_stat,uint32_t mdelay); +EXTERN void relays_onoff(int relays, uint32_t mdelay); +EXTERN void relays_onoffs(uint32_t relays_stat, uint32_t mdelay); EXTERN void relays_resetmode(int relays); EXTERN void relays_powermode(int relays); EXTERN void relays_resetmodes(uint32_t relays_stat); diff --git a/nuttx/configs/shenzhou/src/shenzhou-internal.h b/nuttx/configs/shenzhou/src/shenzhou-internal.h index 862a0250dc..f28abcf602 100644 --- a/nuttx/configs/shenzhou/src/shenzhou-internal.h +++ b/nuttx/configs/shenzhou/src/shenzhou-internal.h @@ -393,9 +393,11 @@ /* Relays */ -#define NUM_RELAYS 1 +#define NUM_RELAYS 2 #define GPIO_RELAYS_R00 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN0) +#define GPIO_RELAYS_R01 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN1) /**************************************************************************************************** * Public Types diff --git a/nuttx/configs/shenzhou/src/up_relays.c b/nuttx/configs/shenzhou/src/up_relays.c index 075c7d5903..6916ee455f 100644 --- a/nuttx/configs/shenzhou/src/up_relays.c +++ b/nuttx/configs/shenzhou/src/up_relays.c @@ -42,11 +42,13 @@ #include #include - -#include -#include "shenzhou-internal.h" #include +#include +#include + +#include "shenzhou-internal.h" + #ifdef CONFIG_ARCH_RELAYS /**************************************************************************** @@ -62,6 +64,7 @@ ****************************************************************************/ static uint32_t g_relays_stat = 0; +static bool g_relays_init = false; static const uint16_t g_relays[NUM_RELAYS] = { @@ -173,6 +176,11 @@ void up_relaysinit(void) { int i; + if (g_relays_init) + { + return; + } + /* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are * configured for some pins but NOT used in this file */ @@ -180,7 +188,10 @@ void up_relaysinit(void) for (i = 0; i < NUM_RELAYS; i++) { stm32_configgpio(g_relays[i]); + stm32_gpiowrite(g_relays[i], false); } + + g_relays_init = true; } void relays_setstat(int relays,bool stat) diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h index bf6be1ce08..c836a75573 100644 --- a/nuttx/include/nuttx/arch.h +++ b/nuttx/include/nuttx/arch.h @@ -616,6 +616,28 @@ EXTERN uint8_t up_buttons(void); EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler); #endif +/************************************************************************************ + * Relay control functions + * + * Description: + * Non-standard functions for relay control. + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_RELAYS +EXTERN void up_relaysinit(void); +EXTERN void relays_setstat(int relays, bool stat); +EXTERN bool relays_getstat(int relays); +EXTERN void relays_setstats(uint32_t relays_stat); +EXTERN uint32_t relays_getstats(void); +EXTERN void relays_onoff(int relays, uint32_t mdelay); +EXTERN void relays_onoffs(uint32_t relays_stat, uint32_t mdelay); +EXTERN void relays_resetmode(int relays); +EXTERN void relays_powermode(int relays); +EXTERN void relays_resetmodes(uint32_t relays_stat); +EXTERN void relays_powermodes(uint32_t relays_stat); +#endif + /**************************************************************************** * Debug interfaces exported by the architecture-specific logic ****************************************************************************/ From baeabacae3435daefab7ae41ab4e69cf96c613ca Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 4 Nov 2012 17:18:25 +0000 Subject: [PATCH 076/206] Massive clean-up of linker scripts from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5307 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/README.txt | 10 ++ nuttx/ChangeLog | 2 + nuttx/configs/avr32dev1/nsh/ld.script | 4 +- nuttx/configs/avr32dev1/ostest/ld.script | 4 +- .../demo9s12ne64/ostest/ld.script.banked | 4 +- .../demo9s12ne64/ostest/ld.script.nonbanked | 4 +- nuttx/configs/ea3131/locked/ld-locked.script | 4 +- nuttx/configs/ea3131/scripts/ld.script | 30 ++-- nuttx/configs/ea3131/scripts/pg-ld.script | 36 ++-- nuttx/configs/ea3152/scripts/ld.script | 30 ++-- nuttx/configs/eagle100/README.txt | 2 +- nuttx/configs/eagle100/httpd/Make.defs | 4 +- nuttx/configs/eagle100/nettest/Make.defs | 4 +- nuttx/configs/eagle100/nettest/ld.script | 112 ------------ nuttx/configs/eagle100/nsh/Make.defs | 4 +- nuttx/configs/eagle100/nsh/ld.script | 112 ------------ nuttx/configs/eagle100/nxflat/Make.defs | 4 +- nuttx/configs/eagle100/nxflat/ld.script | 112 ------------ nuttx/configs/eagle100/ostest/Make.defs | 4 +- nuttx/configs/eagle100/ostest/ld.script | 112 ------------ .../eagle100/{httpd => scripts}/ld.script | 20 ++- nuttx/configs/eagle100/thttpd/Make.defs | 4 +- nuttx/configs/eagle100/thttpd/ld.script | 112 ------------ nuttx/configs/ekk-lm3s9b96/scripts/ld.script | 30 ++-- nuttx/configs/fire-stm32v2/scripts/ld.script | 30 ++-- .../fire-stm32v2/scripts/ld.script.dfu | 30 ++-- nuttx/configs/hymini-stm32v/scripts/ld.script | 30 ++-- .../hymini-stm32v/scripts/ld.script.dfu | 30 ++-- nuttx/configs/kwikstik-k40/ostest/Make.defs | 4 +- nuttx/configs/kwikstik-k40/ostest/ld.script | 32 ++-- nuttx/configs/lincoln60/scripts/ld.script | 32 ++-- nuttx/configs/lm3s6432-s2e/nsh/Make.defs | 4 +- nuttx/configs/lm3s6432-s2e/ostest/Make.defs | 4 +- nuttx/configs/lm3s6432-s2e/ostest/ld.script | 108 ------------ .../lm3s6432-s2e/{nsh => scripts}/ld.script | 34 ++-- nuttx/configs/lm3s6965-ek/nsh/Make.defs | 4 +- nuttx/configs/lm3s6965-ek/nx/Make.defs | 4 +- nuttx/configs/lm3s6965-ek/nx/ld.script | 108 ------------ nuttx/configs/lm3s6965-ek/ostest/Make.defs | 4 +- nuttx/configs/lm3s6965-ek/ostest/ld.script | 108 ------------ .../lm3s6965-ek/{nsh => scripts}/ld.script | 34 ++-- nuttx/configs/lm3s8962-ek/nsh/Make.defs | 4 +- nuttx/configs/lm3s8962-ek/nsh/ld.script | 108 ------------ nuttx/configs/lm3s8962-ek/nx/Make.defs | 4 +- nuttx/configs/lm3s8962-ek/ostest/Make.defs | 4 +- nuttx/configs/lm3s8962-ek/ostest/ld.script | 108 ------------ .../lm3s8962-ek/{nx => scripts}/ld.script | 34 ++-- .../lpc4330-xplorer/scripts/ramconfig.ld | 32 ++-- .../lpc4330-xplorer/scripts/spificonfig.ld | 32 ++-- .../lpcxpresso-lpc1768/scripts/ld.script | 30 ++-- nuttx/configs/mbed/hidkbd/Make.defs | 4 +- nuttx/configs/mbed/hidkbd/ld.script | 109 ------------ nuttx/configs/mbed/nsh/Make.defs | 4 +- .../usbserial => mbed/scripts}/ld.script | 34 ++-- .../mcu123-lpc214x/composite/Make.defs | 4 +- .../mcu123-lpc214x/composite/ld.script | 120 ------------- nuttx/configs/mcu123-lpc214x/nsh/Make.defs | 4 +- nuttx/configs/mcu123-lpc214x/ostest/Make.defs | 4 +- nuttx/configs/mcu123-lpc214x/ostest/ld.script | 119 ------------- .../mcu123-lpc214x/{nsh => scripts}/ld.script | 35 ++-- .../mcu123-lpc214x/usbserial/Make.defs | 4 +- .../mcu123-lpc214x/usbserial/ld.script | 119 ------------- .../mcu123-lpc214x/usbstorage/Make.defs | 4 +- .../mcu123-lpc214x/usbstorage/ld.script | 119 ------------- nuttx/configs/mirtoo/scripts/c32-debug.ld | 4 +- nuttx/configs/mirtoo/scripts/c32-release.ld | 10 +- .../configs/mirtoo/scripts/mips-elf-debug.ld | 4 +- .../mirtoo/scripts/mips-elf-release.ld | 10 +- nuttx/configs/mirtoo/scripts/xc32-debug.ld | 4 +- nuttx/configs/mirtoo/scripts/xc32-release.ld | 10 +- .../configs/ne64badge/ostest/ld.script.banked | 4 +- .../ne64badge/ostest/ld.script.nonbanked | 4 +- nuttx/configs/nucleus2g/nsh/Make.defs | 4 +- nuttx/configs/nucleus2g/nsh/ld.script | 109 ------------ nuttx/configs/nucleus2g/ostest/Make.defs | 4 +- nuttx/configs/nucleus2g/ostest/ld.script | 109 ------------ .../{mbed/nsh => nucleus2g/scripts}/ld.script | 34 ++-- nuttx/configs/nucleus2g/usbserial/Make.defs | 4 +- nuttx/configs/nucleus2g/usbstorage/Make.defs | 4 +- nuttx/configs/nucleus2g/usbstorage/ld.script | 109 ------------ .../olimex-lpc1766stk/scripts/ld.script | 30 ++-- nuttx/configs/olimex-lpc2378/nsh/Make.defs | 4 +- nuttx/configs/olimex-lpc2378/ostest/Make.defs | 4 +- nuttx/configs/olimex-lpc2378/ostest/ld.script | 166 ------------------ .../olimex-lpc2378/{nsh => scripts}/ld.script | 42 ++--- .../olimex-stm32-p107/scripts/ld.script | 30 ++-- .../olimex-stm32-p107/scripts/ld.script.dfu | 30 ++-- .../configs/olimex-strp711/nettest/Make.defs | 4 +- nuttx/configs/olimex-strp711/nsh/Make.defs | 4 +- nuttx/configs/olimex-strp711/nsh/ld.script | 122 ------------- nuttx/configs/olimex-strp711/ostest/Make.defs | 4 +- nuttx/configs/olimex-strp711/ostest/ld.script | 122 ------------- .../{nettest => scripts}/ld.script | 35 ++-- nuttx/configs/pcblogic-pic32mx/nsh/ld.script | 10 +- .../configs/pcblogic-pic32mx/ostest/ld.script | 10 +- nuttx/configs/pic32-starterkit/nsh/ld.script | 10 +- nuttx/configs/pic32-starterkit/nsh2/ld.script | 10 +- .../configs/pic32-starterkit/ostest/ld.script | 10 +- nuttx/configs/pic32mx7mmb/nsh/ld.script | 10 +- nuttx/configs/pic32mx7mmb/ostest/ld.script | 10 +- nuttx/configs/qemu-i486/nsh/ld.script | 4 +- nuttx/configs/qemu-i486/ostest/ld.script | 4 +- nuttx/configs/sam3u-ek/kernel/kernel.ld | 32 ++-- nuttx/configs/sam3u-ek/knsh/ld.script | 32 ++-- nuttx/configs/sam3u-ek/nsh/Make.defs | 4 +- nuttx/configs/sam3u-ek/nsh/ld.script | 111 ------------ nuttx/configs/sam3u-ek/nx/Make.defs | 4 +- nuttx/configs/sam3u-ek/ostest/Make.defs | 4 +- nuttx/configs/sam3u-ek/ostest/ld.script | 111 ------------ .../sam3u-ek/{nx => scripts}/ld.script | 8 +- nuttx/configs/sam3u-ek/touchscreen/Make.defs | 4 +- nuttx/configs/sam3u-ek/touchscreen/ld.script | 111 ------------ nuttx/configs/shenzhou/scripts/ld.script | 12 +- nuttx/configs/shenzhou/scripts/ld.script.dfu | 12 +- nuttx/configs/stm3210e-eval/RIDE/README.txt | 76 ++++---- nuttx/configs/stm3210e-eval/RIDE/nuttx.elf.ld | 4 +- nuttx/configs/stm3210e-eval/RIDE/nuttx.rapp | 2 +- .../configs/stm3210e-eval/RIDE/stm32-nuttx.ld | 111 ------------ nuttx/configs/stm3210e-eval/scripts/ld.script | 30 ++-- .../stm3210e-eval/scripts/ld.script.dfu | 30 ++-- nuttx/configs/stm3220g-eval/scripts/ld.script | 12 +- nuttx/configs/stm3240g-eval/scripts/ld.script | 12 +- .../stm32f4discovery/scripts/ld.script | 12 +- nuttx/configs/sure-pic32mx/nsh/ld.script | 10 +- nuttx/configs/sure-pic32mx/ostest/ld.script | 10 +- nuttx/configs/sure-pic32mx/usbnsh/ld.script | 10 +- nuttx/configs/twr-k60n512/nsh/Make.defs | 4 +- nuttx/configs/twr-k60n512/ostest/Make.defs | 4 +- nuttx/configs/twr-k60n512/ostest/ld.script | 135 -------------- .../twr-k60n512/{nsh => scripts}/ld.script | 34 ++-- nuttx/configs/ubw32/nsh/ld.script | 10 +- nuttx/configs/ubw32/ostest/ld.script | 10 +- nuttx/configs/vsn/nsh/Make.defs | 4 +- nuttx/configs/vsn/nsh/ld.script | 34 ++-- nuttx/configs/vsn/nsh/ld.script.dfu | 34 ++-- 135 files changed, 862 insertions(+), 3676 deletions(-) delete mode 100644 nuttx/configs/eagle100/nettest/ld.script delete mode 100644 nuttx/configs/eagle100/nsh/ld.script delete mode 100644 nuttx/configs/eagle100/nxflat/ld.script delete mode 100644 nuttx/configs/eagle100/ostest/ld.script rename nuttx/configs/eagle100/{httpd => scripts}/ld.script (94%) delete mode 100644 nuttx/configs/eagle100/thttpd/ld.script delete mode 100644 nuttx/configs/lm3s6432-s2e/ostest/ld.script rename nuttx/configs/lm3s6432-s2e/{nsh => scripts}/ld.script (91%) delete mode 100755 nuttx/configs/lm3s6965-ek/nx/ld.script delete mode 100755 nuttx/configs/lm3s6965-ek/ostest/ld.script rename nuttx/configs/lm3s6965-ek/{nsh => scripts}/ld.script (91%) delete mode 100755 nuttx/configs/lm3s8962-ek/nsh/ld.script delete mode 100755 nuttx/configs/lm3s8962-ek/ostest/ld.script rename nuttx/configs/lm3s8962-ek/{nx => scripts}/ld.script (91%) delete mode 100644 nuttx/configs/mbed/hidkbd/ld.script rename nuttx/configs/{nucleus2g/usbserial => mbed/scripts}/ld.script (91%) delete mode 100644 nuttx/configs/mcu123-lpc214x/composite/ld.script delete mode 100644 nuttx/configs/mcu123-lpc214x/ostest/ld.script rename nuttx/configs/mcu123-lpc214x/{nsh => scripts}/ld.script (93%) delete mode 100644 nuttx/configs/mcu123-lpc214x/usbserial/ld.script delete mode 100644 nuttx/configs/mcu123-lpc214x/usbstorage/ld.script delete mode 100755 nuttx/configs/nucleus2g/nsh/ld.script delete mode 100755 nuttx/configs/nucleus2g/ostest/ld.script rename nuttx/configs/{mbed/nsh => nucleus2g/scripts}/ld.script (91%) delete mode 100755 nuttx/configs/nucleus2g/usbstorage/ld.script delete mode 100755 nuttx/configs/olimex-lpc2378/ostest/ld.script rename nuttx/configs/olimex-lpc2378/{nsh => scripts}/ld.script (92%) delete mode 100644 nuttx/configs/olimex-strp711/nsh/ld.script delete mode 100644 nuttx/configs/olimex-strp711/ostest/ld.script rename nuttx/configs/olimex-strp711/{nettest => scripts}/ld.script (91%) delete mode 100755 nuttx/configs/sam3u-ek/nsh/ld.script delete mode 100755 nuttx/configs/sam3u-ek/ostest/ld.script rename nuttx/configs/sam3u-ek/{nx => scripts}/ld.script (97%) delete mode 100755 nuttx/configs/sam3u-ek/touchscreen/ld.script delete mode 100755 nuttx/configs/stm3210e-eval/RIDE/stm32-nuttx.ld delete mode 100644 nuttx/configs/twr-k60n512/ostest/ld.script rename nuttx/configs/twr-k60n512/{nsh => scripts}/ld.script (92%) diff --git a/apps/examples/README.txt b/apps/examples/README.txt index fd0dcf5c50..3bc6e50b5f 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -594,6 +594,11 @@ examples/lcdrw * CONFIG_EXAMPLES_LDCRW_YRES LCD Y resolution. Default: 320 + NOTE: This test exercises internal lcd driver interfaces. As such, it + relies on internal OS interfaces that are not normally available to a + user-space program. As a result, this example cannot be used if a + NuttX is built as a protected, supervisor kernel (CONFIG_NUTTX_KERNEL). + examples/mm ^^^^^^^^^^^ @@ -1226,6 +1231,11 @@ examples/relays Requires CONFIG_ARCH_RELAYS. Contributed by Darcy Gong. + NOTE: This test exercises internal relay driver interfaces. As such, it + relies on internal OS interfaces that are not normally available to a + user-space program. As a result, this example cannot be used if a + NuttX is built as a protected, supervisor kernel (CONFIG_NUTTX_KERNEL). + examples/rgmp ^^^^^^^^^^^^^ diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 06bc13fd6e..3b60fc8128 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3562,4 +3562,6 @@ and this results in a crash. On the STM324Discovery, I will have better control over when the static constructors run. * RGMP 4.0 updated from Qiany Yu. + * configs/*/Make.defs and configs/*/ld.script: Massive clean-up + and standardization of linker scripts from Freddie Chopin. diff --git a/nuttx/configs/avr32dev1/nsh/ld.script b/nuttx/configs/avr32dev1/nsh/ld.script index 1a7035a739..5f661ca446 100755 --- a/nuttx/configs/avr32dev1/nsh/ld.script +++ b/nuttx/configs/avr32dev1/nsh/ld.script @@ -58,10 +58,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) diff --git a/nuttx/configs/avr32dev1/ostest/ld.script b/nuttx/configs/avr32dev1/ostest/ld.script index 189a9ebe34..f878abef8c 100755 --- a/nuttx/configs/avr32dev1/ostest/ld.script +++ b/nuttx/configs/avr32dev1/ostest/ld.script @@ -58,10 +58,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) diff --git a/nuttx/configs/demo9s12ne64/ostest/ld.script.banked b/nuttx/configs/demo9s12ne64/ostest/ld.script.banked index 798658f39e..812f5f19ca 100755 --- a/nuttx/configs/demo9s12ne64/ostest/ld.script.banked +++ b/nuttx/configs/demo9s12ne64/ostest/ld.script.banked @@ -90,10 +90,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) diff --git a/nuttx/configs/demo9s12ne64/ostest/ld.script.nonbanked b/nuttx/configs/demo9s12ne64/ostest/ld.script.nonbanked index ab36d1c4e2..fae728f629 100755 --- a/nuttx/configs/demo9s12ne64/ostest/ld.script.nonbanked +++ b/nuttx/configs/demo9s12ne64/ostest/ld.script.nonbanked @@ -63,10 +63,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) diff --git a/nuttx/configs/ea3131/locked/ld-locked.script b/nuttx/configs/ea3131/locked/ld-locked.script index 955505364f..334c328c07 100644 --- a/nuttx/configs/ea3131/locked/ld-locked.script +++ b/nuttx/configs/ea3131/locked/ld-locked.script @@ -38,6 +38,6 @@ OUTPUT_ARCH(arm) SECTIONS { .text.locked : { *(.text .text.*) } - .data : { *(.data) } - .bss : { *(.bss) *(COMMON) } + .data : { *(.data) } + .bss : { *(.bss) *(COMMON) } } diff --git a/nuttx/configs/ea3131/scripts/ld.script b/nuttx/configs/ea3131/scripts/ld.script index 333117c198..72a3d9f97d 100644 --- a/nuttx/configs/ea3131/scripts/ld.script +++ b/nuttx/configs/ea3131/scripts/ld.script @@ -51,10 +51,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -64,6 +64,22 @@ SECTIONS _etext = ABSOLUTE(.); } > isram + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > isram + + .ARM.extab : { + *(.ARM.extab*) + } > isram + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > isram + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); .data : { @@ -74,16 +90,6 @@ SECTIONS _edata = ABSOLUTE(.); } > isram - .ARM.extab : { - *(.ARM.extab*) - } >isram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > isram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/ea3131/scripts/pg-ld.script b/nuttx/configs/ea3131/scripts/pg-ld.script index 90a713c7de..d7c1f1d4d1 100644 --- a/nuttx/configs/ea3131/scripts/pg-ld.script +++ b/nuttx/configs/ea3131/scripts/pg-ld.script @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. * ****************************************************************************/ - + /* The LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. * LPC31xx boot ROM expects the boot image be compiled with entry point at * 0x1102:9000. A 128b header will appear at this address (applied by @@ -80,10 +80,10 @@ SECTIONS .locked : { _slocked = ABSOLUTE(.); *(.vectors) - up_head.o locked.r (.text .text.*) + up_head.o locked.r (.text .text.*) up_head.o locked.r (.fixup) up_head.o locked.r (.gnu.warning) - up_head.o locked.r (.rodata .rodata.*) + up_head.o locked.r (.rodata .rodata.*) up_head.o locked.r (.gnu.linkonce.t.*) up_head.o locked.r (.glue_7) up_head.o locked.r (.glue_7t) @@ -93,14 +93,30 @@ SECTIONS _elocked = ABSOLUTE(.); } >locked + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > locked + + .ARM.extab : { + *(.ARM.extab*) + } > locked + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > locked + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); .paged : { _spaged = ABSOLUTE(.); - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -118,16 +134,6 @@ SECTIONS _edata = ABSOLUTE(.); } > data AT > locked - .ARM.extab : { - *(.ARM.extab*) - } >data - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } > data - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/ea3152/scripts/ld.script b/nuttx/configs/ea3152/scripts/ld.script index cf5b5d5196..ff1578df2a 100644 --- a/nuttx/configs/ea3152/scripts/ld.script +++ b/nuttx/configs/ea3152/scripts/ld.script @@ -51,10 +51,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -64,6 +64,22 @@ SECTIONS _etext = ABSOLUTE(.); } > isram + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > isram + + .ARM.extab : { + *(.ARM.extab*) + } > isram + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > isram + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); .data : { @@ -74,16 +90,6 @@ SECTIONS _edata = ABSOLUTE(.); } > isram - .ARM.extab : { - *(.ARM.extab*) - } >isram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } > isram - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt index c9253960a2..ce607c7647 100644 --- a/nuttx/configs/eagle100/README.txt +++ b/nuttx/configs/eagle100/README.txt @@ -100,7 +100,7 @@ CodeSourcery on Linux ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx - ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -O2 The values for TOPDIR is provided by the make system; the value for CONFIG_ARCH_BOARD diff --git a/nuttx/configs/eagle100/httpd/Make.defs b/nuttx/configs/eagle100/httpd/Make.defs index dc252dfb3a..4d5024d247 100644 --- a/nuttx/configs/eagle100/httpd/Make.defs +++ b/nuttx/configs/eagle100/httpd/Make.defs @@ -60,7 +60,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/httpd/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -70,7 +70,7 @@ else 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}" - ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/httpd/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/eagle100/nettest/Make.defs b/nuttx/configs/eagle100/nettest/Make.defs index 3de14846e6..98b544ed9b 100644 --- a/nuttx/configs/eagle100/nettest/Make.defs +++ b/nuttx/configs/eagle100/nettest/Make.defs @@ -60,7 +60,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/nettest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -70,7 +70,7 @@ else 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}" - ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nettest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/eagle100/nettest/ld.script b/nuttx/configs/eagle100/nettest/ld.script deleted file mode 100644 index 4997200af6..0000000000 --- a/nuttx/configs/eagle100/nettest/ld.script +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * configs/eagle100/nettest/ld.script - * - * Copyright (C) 2009, 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. - * - ****************************************************************************/ - -/* The LM3S6918 has 256Kb of FLASH beginning at address 0x0000:0000. However, - * if the Eagle100 Ethernet bootloader is used, then the entry point must - * be at the following offset in FLASH (and the size of the FLASH must be - * reduced to 248Kb): - */ - -MEMORY -{ -/* flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K */ - flash (rx) : ORIGIN = 0x00002000, LENGTH = 248K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/eagle100/nsh/Make.defs b/nuttx/configs/eagle100/nsh/Make.defs index ff66759339..efd473f7ab 100644 --- a/nuttx/configs/eagle100/nsh/Make.defs +++ b/nuttx/configs/eagle100/nsh/Make.defs @@ -60,7 +60,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -70,7 +70,7 @@ else 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}" - ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/eagle100/nsh/ld.script b/nuttx/configs/eagle100/nsh/ld.script deleted file mode 100644 index cdf1a4110d..0000000000 --- a/nuttx/configs/eagle100/nsh/ld.script +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * configs/eagle100/nsh/ld.script - * - * Copyright (C) 2009, 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. - * - ****************************************************************************/ - -/* The LM3S6918 has 256Kb of FLASH beginning at address 0x0000:0000. However, - * if the Eagle100 Ethernet bootloader is used, then the entry point must - * be at the following offset in FLASH (and the size of the FLASH must be - * reduced to 248Kb): - */ - -MEMORY -{ -/* flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K */ - flash (rx) : ORIGIN = 0x00002000, LENGTH = 248K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/eagle100/nxflat/Make.defs b/nuttx/configs/eagle100/nxflat/Make.defs index 780e858504..6c6965d202 100644 --- a/nuttx/configs/eagle100/nxflat/Make.defs +++ b/nuttx/configs/eagle100/nxflat/Make.defs @@ -63,7 +63,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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 + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -73,7 +73,7 @@ else 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}" - ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nxflat/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/eagle100/nxflat/ld.script b/nuttx/configs/eagle100/nxflat/ld.script deleted file mode 100644 index 153e777b5f..0000000000 --- a/nuttx/configs/eagle100/nxflat/ld.script +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * configs/eagle100/nxflat/ld.script - * - * Copyright (C) 2009, 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. - * - ****************************************************************************/ - -/* The LM3S6918 has 256Kb of FLASH beginning at address 0x0000:0000. However, - * if the Eagle100 Ethernet bootloader is used, then the entry point must - * be at the following offset in FLASH (and the size of the FLASH must be - * reduced to 248Kb): - */ - -MEMORY -{ -/* flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K */ - flash (rx) : ORIGIN = 0x00002000, LENGTH = 248K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/eagle100/ostest/Make.defs b/nuttx/configs/eagle100/ostest/Make.defs index 78db5644e4..f28f6d90be 100644 --- a/nuttx/configs/eagle100/ostest/Make.defs +++ b/nuttx/configs/eagle100/ostest/Make.defs @@ -60,7 +60,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -70,7 +70,7 @@ else 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}" - ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/eagle100/ostest/ld.script b/nuttx/configs/eagle100/ostest/ld.script deleted file mode 100644 index 10c2f0cfad..0000000000 --- a/nuttx/configs/eagle100/ostest/ld.script +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * configs/eagle100/ostest/ld.script - * - * Copyright (C) 2009, 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. - * - ****************************************************************************/ - -/* The LM3S6918 has 256Kb of FLASH beginning at address 0x0000:0000. However, - * if the Eagle100 Ethernet bootloader is used, then the entry point must - * be at the following offset in FLASH (and the size of the FLASH must be - * reduced to 248Kb): - */ - -MEMORY -{ -/* flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K */ - flash (rx) : ORIGIN = 0x00002000, LENGTH = 248K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/eagle100/httpd/ld.script b/nuttx/configs/eagle100/scripts/ld.script similarity index 94% rename from nuttx/configs/eagle100/httpd/ld.script rename to nuttx/configs/eagle100/scripts/ld.script index 24e9c90b72..0382307696 100644 --- a/nuttx/configs/eagle100/httpd/ld.script +++ b/nuttx/configs/eagle100/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/eagle100/httpd/ld.script + * configs/eagle100/scripts/ld.script * * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -53,10 +53,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -66,6 +66,16 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + __exidx_start = ABSOLUTE(.); .ARM.exidx : { *(.ARM.exidx*) @@ -84,10 +94,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/eagle100/thttpd/Make.defs b/nuttx/configs/eagle100/thttpd/Make.defs index 87157525b3..83abbe411a 100644 --- a/nuttx/configs/eagle100/thttpd/Make.defs +++ b/nuttx/configs/eagle100/thttpd/Make.defs @@ -63,7 +63,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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 + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -73,7 +73,7 @@ else 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}" - ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/thttpd/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/eagle100/thttpd/ld.script b/nuttx/configs/eagle100/thttpd/ld.script deleted file mode 100644 index 7a1d7c75d8..0000000000 --- a/nuttx/configs/eagle100/thttpd/ld.script +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * configs/eagle100/thttpd/ld.script - * - * Copyright (C) 2009, 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. - * - ****************************************************************************/ - -/* The LM3S6918 has 256Kb of FLASH beginning at address 0x0000:0000. However, - * if the Eagle100 Ethernet bootloader is used, then the entry point must - * be at the following offset in FLASH (and the size of the FLASH must be - * reduced to 248Kb): - */ - -MEMORY -{ -/* flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K */ - flash (rx) : ORIGIN = 0x00002000, LENGTH = 248K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/ekk-lm3s9b96/scripts/ld.script b/nuttx/configs/ekk-lm3s9b96/scripts/ld.script index 22d2edfdb9..a85999f6e6 100644 --- a/nuttx/configs/ekk-lm3s9b96/scripts/ld.script +++ b/nuttx/configs/ekk-lm3s9b96/scripts/ld.script @@ -51,10 +51,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -64,6 +64,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); .data : { @@ -74,16 +90,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/fire-stm32v2/scripts/ld.script b/nuttx/configs/fire-stm32v2/scripts/ld.script index 443dec50d8..225af3834b 100644 --- a/nuttx/configs/fire-stm32v2/scripts/ld.script +++ b/nuttx/configs/fire-stm32v2/scripts/ld.script @@ -53,10 +53,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -66,6 +66,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); /* The STM32F103Z has 64Kb of SRAM beginning at the following address */ @@ -78,16 +94,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/fire-stm32v2/scripts/ld.script.dfu b/nuttx/configs/fire-stm32v2/scripts/ld.script.dfu index c7add1422c..fd6576cc31 100644 --- a/nuttx/configs/fire-stm32v2/scripts/ld.script.dfu +++ b/nuttx/configs/fire-stm32v2/scripts/ld.script.dfu @@ -52,10 +52,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -65,6 +65,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); /* The STM32F103Z has 64Kb of SRAM beginning at the following address */ @@ -77,16 +93,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/hymini-stm32v/scripts/ld.script b/nuttx/configs/hymini-stm32v/scripts/ld.script index cef391bf42..15370f39a2 100644 --- a/nuttx/configs/hymini-stm32v/scripts/ld.script +++ b/nuttx/configs/hymini-stm32v/scripts/ld.script @@ -54,10 +54,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -67,6 +67,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ @@ -79,16 +95,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/hymini-stm32v/scripts/ld.script.dfu b/nuttx/configs/hymini-stm32v/scripts/ld.script.dfu index 1f51a9fc3f..23ab5e196b 100644 --- a/nuttx/configs/hymini-stm32v/scripts/ld.script.dfu +++ b/nuttx/configs/hymini-stm32v/scripts/ld.script.dfu @@ -52,10 +52,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -65,6 +65,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */ @@ -77,16 +93,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/kwikstik-k40/ostest/Make.defs b/nuttx/configs/kwikstik-k40/ostest/Make.defs index a51f37e94f..f239d872d4 100644 --- a/nuttx/configs/kwikstik-k40/ostest/Make.defs +++ b/nuttx/configs/kwikstik-k40/ostest/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/kwikstik-k40/ostest/ld.script b/nuttx/configs/kwikstik-k40/ostest/ld.script index 2b7b517fa3..97ac473caa 100755 --- a/nuttx/configs/kwikstik-k40/ostest/ld.script +++ b/nuttx/configs/kwikstik-k40/ostest/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/kwikstik-k40/ostest/ld.script + * configs/kwikstik-k40/scripts/ld.script * * Copyright (C) 2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -70,10 +70,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -83,6 +83,22 @@ SECTIONS _etext = ABSOLUTE(.); } > progflash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > progflash + + .ARM.extab : { + *(.ARM.extab*) + } > progflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > progflash + __exidx_end = ABSOLUTE(.); + .data : { _sdata = ABSOLUTE(.); *(.data .data.*) @@ -101,16 +117,6 @@ SECTIONS _framfuncs = LOADADDR(.ramfunc); - .ARM.extab : { - *(.ARM.extab*) - } > datasram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > datasram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/lincoln60/scripts/ld.script b/nuttx/configs/lincoln60/scripts/ld.script index 262e62df86..ece01a00a1 100644 --- a/nuttx/configs/lincoln60/scripts/ld.script +++ b/nuttx/configs/lincoln60/scripts/ld.script @@ -53,10 +53,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -66,7 +66,23 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - _eronly = ABSOLUTE(.); /* See below */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); .data : { _sdata = ABSOLUTE(.); @@ -76,16 +92,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs index c9ade8028a..795d928d2e 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs index 5f48145bfd..8a0fc03175 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lm3s6432-s2e/ostest/ld.script b/nuttx/configs/lm3s6432-s2e/ostest/ld.script deleted file mode 100644 index bfbf8d3024..0000000000 --- a/nuttx/configs/lm3s6432-s2e/ostest/ld.script +++ /dev/null @@ -1,108 +0,0 @@ -/**************************************************************************** - * configs/lm3s6432-s2e/ostest/ld.script - * - * Copyright (C) 2010 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. - * - ****************************************************************************/ - -/* The LM3S6432 has 96Kb of FLASH beginning at address 0x0000:0000 and 32Kb - * of SRAM beginning at 0x2000:0000. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 96K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - /* The LM3S6432 has 32Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/lm3s6432-s2e/nsh/ld.script b/nuttx/configs/lm3s6432-s2e/scripts/ld.script similarity index 91% rename from nuttx/configs/lm3s6432-s2e/nsh/ld.script rename to nuttx/configs/lm3s6432-s2e/scripts/ld.script index 0701841c5a..555eb77ba9 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/ld.script +++ b/nuttx/configs/lm3s6432-s2e/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/lm3s6432-s2e/nsh/ld.script + * configs/lm3s6432-s2e/scripts/ld.script * * Copyright (C) 2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -50,10 +50,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -63,7 +63,23 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - _eronly = ABSOLUTE(.); /* See below */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); /* The LM3S6432 has 32Kb of SRAM beginning at the following address */ @@ -75,16 +91,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - .bss : { /* BSS */ _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/lm3s6965-ek/nsh/Make.defs b/nuttx/configs/lm3s6965-ek/nsh/Make.defs index 6fc8616aab..72ea6b151e 100644 --- a/nuttx/configs/lm3s6965-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nsh/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lm3s6965-ek/nx/Make.defs b/nuttx/configs/lm3s6965-ek/nx/Make.defs index 887bb823a3..2a409101bb 100644 --- a/nuttx/configs/lm3s6965-ek/nx/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nx/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nx/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nx/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lm3s6965-ek/nx/ld.script b/nuttx/configs/lm3s6965-ek/nx/ld.script deleted file mode 100755 index dcb12fa99a..0000000000 --- a/nuttx/configs/lm3s6965-ek/nx/ld.script +++ /dev/null @@ -1,108 +0,0 @@ -/**************************************************************************** - * configs/lm3s6965-ek/nx/ld.script - * - * Copyright (C) 2010 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. - * - ****************************************************************************/ - -/* The LM3S6965 has 256Kb of FLASH beginning at address 0x0000:0000 and 64Kb - * of SRAM beginning at 0x2000:0000. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/lm3s6965-ek/ostest/Make.defs b/nuttx/configs/lm3s6965-ek/ostest/Make.defs index 0c02e22bb0..ae376da0c5 100644 --- a/nuttx/configs/lm3s6965-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s6965-ek/ostest/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lm3s6965-ek/ostest/ld.script b/nuttx/configs/lm3s6965-ek/ostest/ld.script deleted file mode 100755 index e330f35ae4..0000000000 --- a/nuttx/configs/lm3s6965-ek/ostest/ld.script +++ /dev/null @@ -1,108 +0,0 @@ -/**************************************************************************** - * configs/lm3s6965-ek/ostest/ld.script - * - * Copyright (C) 2010 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. - * - ****************************************************************************/ - -/* The LM3S6965 has 256Kb of FLASH beginning at address 0x0000:0000 and 64Kb - * of SRAM beginning at 0x2000:0000. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/lm3s6965-ek/nsh/ld.script b/nuttx/configs/lm3s6965-ek/scripts/ld.script similarity index 91% rename from nuttx/configs/lm3s6965-ek/nsh/ld.script rename to nuttx/configs/lm3s6965-ek/scripts/ld.script index d3a0d668e4..7350cf5ee5 100755 --- a/nuttx/configs/lm3s6965-ek/nsh/ld.script +++ b/nuttx/configs/lm3s6965-ek/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/lm3s6965-ek/nsh/ld.script + * configs/lm3s6965-ek/scripts/ld.script * * Copyright (C) 2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -50,10 +50,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -63,7 +63,23 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - _eronly = ABSOLUTE(.); /* See below */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ @@ -75,16 +91,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - .bss : { /* BSS */ _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/lm3s8962-ek/nsh/Make.defs b/nuttx/configs/lm3s8962-ek/nsh/Make.defs index 671ccec32b..b0b57559c0 100644 --- a/nuttx/configs/lm3s8962-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nsh/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lm3s8962-ek/nsh/ld.script b/nuttx/configs/lm3s8962-ek/nsh/ld.script deleted file mode 100755 index fdf7c89689..0000000000 --- a/nuttx/configs/lm3s8962-ek/nsh/ld.script +++ /dev/null @@ -1,108 +0,0 @@ -/**************************************************************************** - * configs/lm3s8962-ek/nsh/ld.script - * - * Copyright (C) 2010 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. - * - ****************************************************************************/ - -/* The LM3S8962 has 256Kb of FLASH beginning at address 0x0000:0000 and 64Kb - * of SRAM beginning at 0x2000:0000. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/lm3s8962-ek/nx/Make.defs b/nuttx/configs/lm3s8962-ek/nx/Make.defs index 2563c58dd9..7d0d0aa55b 100644 --- a/nuttx/configs/lm3s8962-ek/nx/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nx/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nx/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nx/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lm3s8962-ek/ostest/Make.defs b/nuttx/configs/lm3s8962-ek/ostest/Make.defs index 2559ed89a1..50368f34f2 100644 --- a/nuttx/configs/lm3s8962-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s8962-ek/ostest/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/lm3s8962-ek/ostest/ld.script b/nuttx/configs/lm3s8962-ek/ostest/ld.script deleted file mode 100755 index 6aa9f5f374..0000000000 --- a/nuttx/configs/lm3s8962-ek/ostest/ld.script +++ /dev/null @@ -1,108 +0,0 @@ -/**************************************************************************** - * configs/lm3s8962-ek/ostest/ld.script - * - * Copyright (C) 2010 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. - * - ****************************************************************************/ - -/* The LM3S8962 has 256Kb of FLASH beginning at address 0x0000:0000 and 64Kb - * of SRAM beginning at 0x2000:0000. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/lm3s8962-ek/nx/ld.script b/nuttx/configs/lm3s8962-ek/scripts/ld.script similarity index 91% rename from nuttx/configs/lm3s8962-ek/nx/ld.script rename to nuttx/configs/lm3s8962-ek/scripts/ld.script index 71f0be6c51..ccb22ddfae 100755 --- a/nuttx/configs/lm3s8962-ek/nx/ld.script +++ b/nuttx/configs/lm3s8962-ek/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/lm3s8962-ek/nx/ld.script + * configs/lm3s8962-ek/scripts/ld.script * * Copyright (C) 2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -50,10 +50,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -63,7 +63,23 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - _eronly = ABSOLUTE(.); /* See below */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); /* The LM3S6918 has 64Kb of SRAM beginning at the following address */ @@ -75,16 +91,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - .bss : { /* BSS */ _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/lpc4330-xplorer/scripts/ramconfig.ld b/nuttx/configs/lpc4330-xplorer/scripts/ramconfig.ld index f44d6181e2..d956120203 100644 --- a/nuttx/configs/lpc4330-xplorer/scripts/ramconfig.ld +++ b/nuttx/configs/lpc4330-xplorer/scripts/ramconfig.ld @@ -88,10 +88,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -101,7 +101,23 @@ SECTIONS _etext = ABSOLUTE(.); } > progmem - _eronly = ABSOLUTE(.); /* See below */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > progmem + + .ARM.extab : { + *(.ARM.extab*) + } > progmem + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > progmem + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); .data : { _sdata = ABSOLUTE(.); @@ -111,16 +127,6 @@ SECTIONS _edata = ABSOLUTE(.); } > datamem AT > progmem - .ARM.extab : { - *(.ARM.extab*) - } >datamem - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >datamem - .bss : { /* BSS */ _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/lpc4330-xplorer/scripts/spificonfig.ld b/nuttx/configs/lpc4330-xplorer/scripts/spificonfig.ld index 1b8df48b2e..8ed668beec 100644 --- a/nuttx/configs/lpc4330-xplorer/scripts/spificonfig.ld +++ b/nuttx/configs/lpc4330-xplorer/scripts/spificonfig.ld @@ -84,10 +84,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -97,7 +97,23 @@ SECTIONS _etext = ABSOLUTE(.); } > progmem - _eronly = ABSOLUTE(.); /* See below */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > progmem + + .ARM.extab : { + *(.ARM.extab*) + } > progmem + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > progmem + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); .data : { _sdata = ABSOLUTE(.); @@ -107,16 +123,6 @@ SECTIONS _edata = ABSOLUTE(.); } > datamem AT > progmem - .ARM.extab : { - *(.ARM.extab*) - } >datamem - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >datamem - .bss : { /* BSS */ _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/lpcxpresso-lpc1768/scripts/ld.script b/nuttx/configs/lpcxpresso-lpc1768/scripts/ld.script index bdfa155476..67e3a4f15a 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/scripts/ld.script +++ b/nuttx/configs/lpcxpresso-lpc1768/scripts/ld.script @@ -53,10 +53,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -66,6 +66,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); .data : { @@ -76,16 +92,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/mbed/hidkbd/Make.defs b/nuttx/configs/mbed/hidkbd/Make.defs index b1dfb73e12..92c6c7ceaa 100644 --- a/nuttx/configs/mbed/hidkbd/Make.defs +++ b/nuttx/configs/mbed/hidkbd/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/hidkbd/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/hidkbd/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/mbed/hidkbd/ld.script b/nuttx/configs/mbed/hidkbd/ld.script deleted file mode 100644 index 152f8bc2a8..0000000000 --- a/nuttx/configs/mbed/hidkbd/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc1766stk/hidkbd/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/mbed/nsh/Make.defs b/nuttx/configs/mbed/nsh/Make.defs index f1983a7b7c..9a72736d26 100644 --- a/nuttx/configs/mbed/nsh/Make.defs +++ b/nuttx/configs/mbed/nsh/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/nucleus2g/usbserial/ld.script b/nuttx/configs/mbed/scripts/ld.script similarity index 91% rename from nuttx/configs/nucleus2g/usbserial/ld.script rename to nuttx/configs/mbed/scripts/ld.script index 2fa9249ff7..2d90a7608f 100755 --- a/nuttx/configs/nucleus2g/usbserial/ld.script +++ b/nuttx/configs/mbed/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/nucleus2g/usbserial/ld.script + * configs/nucleus2g/mbed/ld.script * * Copyright (C) 2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -53,10 +53,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -66,7 +66,23 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - _eronly = ABSOLUTE(.); /* See below */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); .data : { _sdata = ABSOLUTE(.); @@ -76,16 +92,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - .bss : { /* BSS */ _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/mcu123-lpc214x/composite/Make.defs b/nuttx/configs/mcu123-lpc214x/composite/Make.defs index fcbc0b8090..7b9b8f22ff 100644 --- a/nuttx/configs/mcu123-lpc214x/composite/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/composite/Make.defs @@ -67,7 +67,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/composite/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -76,7 +76,7 @@ else MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/composite/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/mcu123-lpc214x/composite/ld.script b/nuttx/configs/mcu123-lpc214x/composite/ld.script deleted file mode 100644 index 4065f29916..0000000000 --- a/nuttx/configs/mcu123-lpc214x/composite/ld.script +++ /dev/null @@ -1,120 +0,0 @@ -/**************************************************************************** - * configs/mcu123-lpc214x/composite/ld.script - * - * 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. - * - ****************************************************************************/ - -/* FLASH: - * The lpc2148 has 512Kb of non-volatile memory beginning at address - * 0x00000000. The OS entry point is via the reset vector at address - * 0x00000000 (default MEMMAP mode assumed) - * - * SRAM: - * The lpc2148 has 32Kb of on-chip static RAM beginning at address - * 0x40000000. The first 512 bytes of RAM are reserved for used by - * the bootloader. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 500K - sram (rw) : ORIGIN = 0x40000200, LENGTH = 32K - 512 - 32 -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - /* This is where the .data section is relocated for execution out - * FLASH. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/mcu123-lpc214x/nsh/Make.defs b/nuttx/configs/mcu123-lpc214x/nsh/Make.defs index eed15974a1..ddccbb4734 100644 --- a/nuttx/configs/mcu123-lpc214x/nsh/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/nsh/Make.defs @@ -67,7 +67,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -76,7 +76,7 @@ else MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/mcu123-lpc214x/ostest/Make.defs b/nuttx/configs/mcu123-lpc214x/ostest/Make.defs index 46beab5265..255515a42e 100644 --- a/nuttx/configs/mcu123-lpc214x/ostest/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/ostest/Make.defs @@ -67,7 +67,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -76,7 +76,7 @@ else MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/mcu123-lpc214x/ostest/ld.script b/nuttx/configs/mcu123-lpc214x/ostest/ld.script deleted file mode 100644 index 590e490eb8..0000000000 --- a/nuttx/configs/mcu123-lpc214x/ostest/ld.script +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * configs/mcu123-lpc214x/ostest/ld.script - * - * Copyright (C) 2007-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. - * - ****************************************************************************/ - -/* FLASH: - * The lpc2148 has 512Kb of non-volatile memory beginning at address - * 0x00000000. The OS entry point is via the reset vector at address - * 0x00000000 (default MEMMAP mode assumed) - * - * SRAM: - * The lpc2148 has 32Kb of on-chip static RAM beginning at address - * 0x40000000. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 500K - sram (rw) : ORIGIN = 0x40000000, LENGTH = 32K - 32 -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - /* This is where the .data section is relocated for execution out - * FLASH. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/mcu123-lpc214x/nsh/ld.script b/nuttx/configs/mcu123-lpc214x/scripts/ld.script similarity index 93% rename from nuttx/configs/mcu123-lpc214x/nsh/ld.script rename to nuttx/configs/mcu123-lpc214x/scripts/ld.script index d6128621b4..8ce83748f9 100644 --- a/nuttx/configs/mcu123-lpc214x/nsh/ld.script +++ b/nuttx/configs/mcu123-lpc214x/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/mcu123-lpc214x/nsh/ld.script + * configs/mcu123-lpc214x/scripts/ld.script * * Copyright (C) 2008-2009, 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -70,13 +70,24 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - /* This is where the .data section is relocated for execution out - * FLASH. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); - _eronly = ABSOLUTE(.); - .data : { _sdata = ABSOLUTE(.); *(.data .data.*) @@ -85,16 +96,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs b/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs index 377c39b1d4..6f05d79f73 100644 --- a/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs @@ -67,7 +67,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/usbserial/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -76,7 +76,7 @@ else MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/usbserial/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/mcu123-lpc214x/usbserial/ld.script b/nuttx/configs/mcu123-lpc214x/usbserial/ld.script deleted file mode 100644 index c73d9bda57..0000000000 --- a/nuttx/configs/mcu123-lpc214x/usbserial/ld.script +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * configs/mcu123-lpc214x/usbserial/ld.script - * - * Copyright (C) 2008-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. - * - ****************************************************************************/ - -/* FLASH: - * The lpc2148 has 512Kb of non-volatile memory beginning at address - * 0x00000000. The OS entry point is via the reset vector at address - * 0x00000000 (default MEMMAP mode assumed) - * - * SRAM: - * The lpc2148 has 32Kb of on-chip static RAM beginning at address - * 0x40000000. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 500K - sram (rw) : ORIGIN = 0x40000000, LENGTH = 32K - 32 -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - /* This is where the .data section is relocated for execution out - * FLASH. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/mcu123-lpc214x/usbstorage/Make.defs b/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs index d26a22d6fc..35ea7af7ab 100644 --- a/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs @@ -67,7 +67,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/usbstorage/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -76,7 +76,7 @@ else MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/usbstorage/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/mcu123-lpc214x/usbstorage/ld.script b/nuttx/configs/mcu123-lpc214x/usbstorage/ld.script deleted file mode 100644 index 41404fa6e3..0000000000 --- a/nuttx/configs/mcu123-lpc214x/usbstorage/ld.script +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * configs/mcu123-lpc214x/usbstorage/ld.script - * - * Copyright (C) 2008-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. - * - ****************************************************************************/ - -/* FLASH: - * The lpc2148 has 512Kb of non-volatile memory beginning at address - * 0x00000000. The OS entry point is via the reset vector at address - * 0x00000000 (default MEMMAP mode assumed) - * - * SRAM: - * The lpc2148 has 32Kb of on-chip static RAM beginning at address - * 0x40000000. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 500K - sram (rw) : ORIGIN = 0x40000000, LENGTH = 32K - 32 -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - /* This is where the .data section is relocated for execution out - * FLASH. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/mirtoo/scripts/c32-debug.ld b/nuttx/configs/mirtoo/scripts/c32-debug.ld index d91aa5e723..161c5b81ea 100644 --- a/nuttx/configs/mirtoo/scripts/c32-debug.ld +++ b/nuttx/configs/mirtoo/scripts/c32-debug.ld @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX250F128D has 128Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 128K /* The PIC32MX250F128D has 3Kb of boot FLASH at physical addresses @@ -179,7 +179,7 @@ SECTIONS *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/mirtoo/scripts/c32-release.ld b/nuttx/configs/mirtoo/scripts/c32-release.ld index 05f0ecc062..e34a3b8e12 100644 --- a/nuttx/configs/mirtoo/scripts/c32-release.ld +++ b/nuttx/configs/mirtoo/scripts/c32-release.ld @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX250F128D has 128Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 128K /* The PIC32MX250F128D has 3Kb of boot FLASH at physical addresses @@ -166,8 +166,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -176,12 +176,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/mirtoo/scripts/mips-elf-debug.ld b/nuttx/configs/mirtoo/scripts/mips-elf-debug.ld index c08ba13c8a..990bc154b6 100644 --- a/nuttx/configs/mirtoo/scripts/mips-elf-debug.ld +++ b/nuttx/configs/mirtoo/scripts/mips-elf-debug.ld @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX250F128D has 128Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 128K /* The PIC32MX250F128D has 3Kb of boot FLASH at physical addresses @@ -179,7 +179,7 @@ SECTIONS *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/mirtoo/scripts/mips-elf-release.ld b/nuttx/configs/mirtoo/scripts/mips-elf-release.ld index ce64e67a55..2c3ee892fc 100644 --- a/nuttx/configs/mirtoo/scripts/mips-elf-release.ld +++ b/nuttx/configs/mirtoo/scripts/mips-elf-release.ld @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX250F128D has 128Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 128K /* The PIC32MX250F128D has 3Kb of boot FLASH at physical addresses @@ -166,8 +166,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -176,12 +176,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/mirtoo/scripts/xc32-debug.ld b/nuttx/configs/mirtoo/scripts/xc32-debug.ld index 7582dcaab8..3c5cc949df 100644 --- a/nuttx/configs/mirtoo/scripts/xc32-debug.ld +++ b/nuttx/configs/mirtoo/scripts/xc32-debug.ld @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX250F128D has 128Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_program_mem (rx) : ORIGIN = 0x9d000000, LENGTH = 128K /* The PIC32MX250F128D has 3Kb of boot FLASH at physical addresses @@ -179,7 +179,7 @@ SECTIONS *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/mirtoo/scripts/xc32-release.ld b/nuttx/configs/mirtoo/scripts/xc32-release.ld index 2c8471ad80..b6b24cc718 100644 --- a/nuttx/configs/mirtoo/scripts/xc32-release.ld +++ b/nuttx/configs/mirtoo/scripts/xc32-release.ld @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX250F128D has 128Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_program_mem (rx) : ORIGIN = 0x9d000000, LENGTH = 128K /* The PIC32MX250F128D has 3Kb of boot FLASH at physical addresses @@ -166,8 +166,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -176,12 +176,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/ne64badge/ostest/ld.script.banked b/nuttx/configs/ne64badge/ostest/ld.script.banked index 5f466e6491..9ec5f75516 100755 --- a/nuttx/configs/ne64badge/ostest/ld.script.banked +++ b/nuttx/configs/ne64badge/ostest/ld.script.banked @@ -94,10 +94,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(nonbanked) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) diff --git a/nuttx/configs/ne64badge/ostest/ld.script.nonbanked b/nuttx/configs/ne64badge/ostest/ld.script.nonbanked index dfa8b15b21..f0577a06be 100755 --- a/nuttx/configs/ne64badge/ostest/ld.script.nonbanked +++ b/nuttx/configs/ne64badge/ostest/ld.script.nonbanked @@ -67,10 +67,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(nonbanked) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) diff --git a/nuttx/configs/nucleus2g/nsh/Make.defs b/nuttx/configs/nucleus2g/nsh/Make.defs index 85e175df0d..aed194e104 100644 --- a/nuttx/configs/nucleus2g/nsh/Make.defs +++ b/nuttx/configs/nucleus2g/nsh/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/nucleus2g/nsh/ld.script b/nuttx/configs/nucleus2g/nsh/ld.script deleted file mode 100755 index bc4d89cf17..0000000000 --- a/nuttx/configs/nucleus2g/nsh/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/nucleus2g/nsh/ld.script - * - * Copyright (C) 2010 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. - * - ****************************************************************************/ - -/* The LPC1768 has 512Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/nucleus2g/ostest/Make.defs b/nuttx/configs/nucleus2g/ostest/Make.defs index fc12eccad0..239424083b 100644 --- a/nuttx/configs/nucleus2g/ostest/Make.defs +++ b/nuttx/configs/nucleus2g/ostest/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/nucleus2g/ostest/ld.script b/nuttx/configs/nucleus2g/ostest/ld.script deleted file mode 100755 index 5d3b874af2..0000000000 --- a/nuttx/configs/nucleus2g/ostest/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/nucleus2g/ostest/ld.script - * - * Copyright (C) 2010 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. - * - ****************************************************************************/ - -/* The LPC1768 has 512Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/mbed/nsh/ld.script b/nuttx/configs/nucleus2g/scripts/ld.script similarity index 91% rename from nuttx/configs/mbed/nsh/ld.script rename to nuttx/configs/nucleus2g/scripts/ld.script index d96d51dd9d..3d6fcb1d2a 100755 --- a/nuttx/configs/mbed/nsh/ld.script +++ b/nuttx/configs/nucleus2g/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/mbed/nsh/ld.script + * configs/nucleus2g/scripts/ld.script * * Copyright (C) 2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -53,10 +53,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -66,7 +66,23 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - _eronly = ABSOLUTE(.); /* See below */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); .data : { _sdata = ABSOLUTE(.); @@ -76,16 +92,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - .bss : { /* BSS */ _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/nucleus2g/usbserial/Make.defs b/nuttx/configs/nucleus2g/usbserial/Make.defs index d82b5d1bcc..81f17e86d2 100644 --- a/nuttx/configs/nucleus2g/usbserial/Make.defs +++ b/nuttx/configs/nucleus2g/usbserial/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/usbserial/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/usbserial/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/nucleus2g/usbstorage/Make.defs b/nuttx/configs/nucleus2g/usbstorage/Make.defs index d5819e82a7..06af74d397 100644 --- a/nuttx/configs/nucleus2g/usbstorage/Make.defs +++ b/nuttx/configs/nucleus2g/usbstorage/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/usbstorage/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/usbstorage/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/nucleus2g/usbstorage/ld.script b/nuttx/configs/nucleus2g/usbstorage/ld.script deleted file mode 100755 index a1056f8a7c..0000000000 --- a/nuttx/configs/nucleus2g/usbstorage/ld.script +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * configs/nucleus2g/usbstorage/ld.script - * - * Copyright (C) 2010 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. - * - ****************************************************************************/ - -/* The LPC1768 has 512Kb of FLASH beginning at address 0x0000:0000 and - * 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address - * 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses - * 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit - * into the 32Kb CPU SRAM address range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/olimex-lpc1766stk/scripts/ld.script b/nuttx/configs/olimex-lpc1766stk/scripts/ld.script index 76da776894..51615624e1 100755 --- a/nuttx/configs/olimex-lpc1766stk/scripts/ld.script +++ b/nuttx/configs/olimex-lpc1766stk/scripts/ld.script @@ -53,10 +53,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -66,6 +66,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); .data : { @@ -76,16 +92,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/olimex-lpc2378/nsh/Make.defs b/nuttx/configs/olimex-lpc2378/nsh/Make.defs index 022f3670b7..5fba7e2142 100644 --- a/nuttx/configs/olimex-lpc2378/nsh/Make.defs +++ b/nuttx/configs/olimex-lpc2378/nsh/Make.defs @@ -72,13 +72,13 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc2378/ostest/Make.defs b/nuttx/configs/olimex-lpc2378/ostest/Make.defs index 043f7ad8e9..2c007cd390 100644 --- a/nuttx/configs/olimex-lpc2378/ostest/Make.defs +++ b/nuttx/configs/olimex-lpc2378/ostest/Make.defs @@ -72,13 +72,13 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/olimex-lpc2378/ostest/ld.script b/nuttx/configs/olimex-lpc2378/ostest/ld.script deleted file mode 100755 index e9ffbb4508..0000000000 --- a/nuttx/configs/olimex-lpc2378/ostest/ld.script +++ /dev/null @@ -1,166 +0,0 @@ -/**************************************************************************** - * configs/olimex-lpc2378/ostest/ld.script - * - * Copyright (C) 2010 Rommel Marcelo. All rights reserved. - * Author: Rommel Marcelo - * - * This is part of the NuttX RTOS and based on the LPC2148 port: - * - * Copyright (C) 2010, 2011 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 -{ - ROM (rx) : ORIGIN = 0x00000000, LENGTH = (512k-8k) /* Flash: 512k - boot code */ - RAM (rw) : ORIGIN = 0x40000000, LENGTH = (32k-32) /* SRAM: 32k - IAP work */ - URAM (rw) : ORIGIN = 0x7FD00000, LENGTH = (8k) /* USB RAM: 8k */ - ERAM (rw) : ORIGIN = 0x7FE00000, LENGTH = (16k) /* Ethernet RAM: 16k */ - BRAM (rw) : ORIGIN = 0xE0084000, LENGTH = (2k) /* Battery RAM: 2k */ -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) /* Startup code */ - *(.text .text.*) /* remaining code */ - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) /* read-only data (constants) */ - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - . = ALIGN(4); - } > ROM - - /* This is where the .data section is relocated for execution out - * FLASH. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - . = ALIGN(4); - _eronly = ABSOLUTE(.); - - .data : - { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > RAM AT > ROM - - .ARM.extab : { - *(.ARM.extab*) - } > RAM - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > RAM - __exidx_end = ABSOLUTE(.); - - -/* .bss section which is initialized by 0 */ - /* This section will be filled with zero by startup code */ - .bss (NOLOAD) : - { - _sbss = ABSOLUTE(.) ; - *(.bss) - *(.bss.*) - *(.gnu.linkonce.b*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > RAM - - .usbram (NOLOAD) : - { - __usbram_start = . ; - __usbram_start__ = . ; - *(.usbram) - . = ALIGN(4); - } > URAM - - .etherram (NOLOAD) : - { - __etherram_start = . ; - __etherram_start__ = . ; - *(.etherram) - . = ALIGN(4); - } > ERAM - - .batteryram (NOLOAD) : - { - __batteryram_start = . ; - __batteryram_start__ = . ; - *(.batteryram) - . = ALIGN(4); - } > BRAM - - /* 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) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } -} diff --git a/nuttx/configs/olimex-lpc2378/nsh/ld.script b/nuttx/configs/olimex-lpc2378/scripts/ld.script similarity index 92% rename from nuttx/configs/olimex-lpc2378/nsh/ld.script rename to nuttx/configs/olimex-lpc2378/scripts/ld.script index d591fcd663..8434249b6e 100755 --- a/nuttx/configs/olimex-lpc2378/nsh/ld.script +++ b/nuttx/configs/olimex-lpc2378/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/olimex-lpc2378/nsh/ld.script + * configs/olimex-lpc2378/scripts/ld.script * * Copyright (C) 2010 Rommel Marcelo. All rights reserved. * Author: Rommel Marcelo @@ -52,11 +52,11 @@ SECTIONS { .text : { _stext = ABSOLUTE(.); - *(.vectors) /* Startup code */ - *(.text .text.*) /* remaining code */ + *(.vectors) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) /* read-only data (constants) */ + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -64,16 +64,26 @@ SECTIONS *(.gcc_except_table) *(.gnu.linkonce.r.*) _etext = ABSOLUTE(.); - . = ALIGN(4); } > ROM - /* This is where the .data section is relocated for execution out - * FLASH. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - . = ALIGN(4); + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > ROM + + .ARM.extab : { + *(.ARM.extab*) + } > ROM + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > ROM + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); - + .data : { _sdata = ABSOLUTE(.); @@ -83,16 +93,6 @@ SECTIONS _edata = ABSOLUTE(.); } > RAM AT > ROM - .ARM.extab : { - *(.ARM.extab*) - } > RAM - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > RAM - __exidx_end = ABSOLUTE(.); - /* .bss section which is initialized by 0 */ /* This section will be filled with zero by startup code */ .bss (NOLOAD) : diff --git a/nuttx/configs/olimex-stm32-p107/scripts/ld.script b/nuttx/configs/olimex-stm32-p107/scripts/ld.script index 5037954bae..651848df71 100644 --- a/nuttx/configs/olimex-stm32-p107/scripts/ld.script +++ b/nuttx/configs/olimex-stm32-p107/scripts/ld.script @@ -47,10 +47,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -60,6 +60,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); /* The STM32F107VC has 64Kb of SRAM beginning at the following address */ @@ -72,16 +88,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/olimex-stm32-p107/scripts/ld.script.dfu b/nuttx/configs/olimex-stm32-p107/scripts/ld.script.dfu index 87acb12f90..c20a6224fa 100644 --- a/nuttx/configs/olimex-stm32-p107/scripts/ld.script.dfu +++ b/nuttx/configs/olimex-stm32-p107/scripts/ld.script.dfu @@ -47,10 +47,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -60,6 +60,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); /* The STM32F103Z has 64Kb of SRAM beginning at the following address */ @@ -72,16 +88,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/olimex-strp711/nettest/Make.defs b/nuttx/configs/olimex-strp711/nettest/Make.defs index 1c751be09d..64259e9199 100644 --- a/nuttx/configs/olimex-strp711/nettest/Make.defs +++ b/nuttx/configs/olimex-strp711/nettest/Make.defs @@ -67,7 +67,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/nettest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -76,7 +76,7 @@ else MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nettest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/olimex-strp711/nsh/Make.defs b/nuttx/configs/olimex-strp711/nsh/Make.defs index d2c674d3a5..69c6b4c277 100644 --- a/nuttx/configs/olimex-strp711/nsh/Make.defs +++ b/nuttx/configs/olimex-strp711/nsh/Make.defs @@ -67,7 +67,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -76,7 +76,7 @@ else MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/olimex-strp711/nsh/ld.script b/nuttx/configs/olimex-strp711/nsh/ld.script deleted file mode 100644 index 7a95410f47..0000000000 --- a/nuttx/configs/olimex-strp711/nsh/ld.script +++ /dev/null @@ -1,122 +0,0 @@ -/**************************************************************************** - * configs/olimex-strp711/nsh/ld.script - * - * Copyright (C) 2008-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. - * - ****************************************************************************/ - -/* The str71x has 256Kb of non-volatile memory beginning at address - * 0x4000:0000 for program storage (Bank0, an addition 16Kb is available - * for data storage in Bank1). The OS entry point is via the reset vector - * at address 0x00000000 where the FLASH is remapped at reset. - * - * The str71x has 64Kb of on-chip static RAM beginning at address - * 0x2000:0000. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - -/* The STR711 has 256Kb of FLASH beginning at address 0x4000:0000 and 64Kb - * of SRAM beginning at address 0x2000:0000 - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x40000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - /* This is where the .data section is relocated for execution out - * FLASH. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/olimex-strp711/ostest/Make.defs b/nuttx/configs/olimex-strp711/ostest/Make.defs index 37adf602a4..722a45951e 100644 --- a/nuttx/configs/olimex-strp711/ostest/Make.defs +++ b/nuttx/configs/olimex-strp711/ostest/Make.defs @@ -67,7 +67,7 @@ ifeq ($(CROSSDEV),arm-nuttx-elf-) 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script MAXOPTIMIZATION = -Os else WINTOOL = y @@ -76,7 +76,7 @@ else MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 endif diff --git a/nuttx/configs/olimex-strp711/ostest/ld.script b/nuttx/configs/olimex-strp711/ostest/ld.script deleted file mode 100644 index 9a5c457453..0000000000 --- a/nuttx/configs/olimex-strp711/ostest/ld.script +++ /dev/null @@ -1,122 +0,0 @@ -/**************************************************************************** - * configs/olimex-strp711/ostest/ld.script - * - * Copyright (C) 2008-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. - * - ****************************************************************************/ - -/* The str71x has 256Kb of non-volatile memory beginning at address - * 0x4000:0000 for program storage (Bank0, an addition 16Kb is available - * for data storage in Bank1). The OS entry point is via the reset vector - * at address 0x00000000 where the FLASH is remapped at reset. - * - * The str71x has 64Kb of on-chip static RAM beginning at address - * 0x2000:0000. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - -/* The STR711 has 256Kb of FLASH beginning at address 0x4000:0000 and 64Kb - * of SRAM beginning at address 0x2000:0000 - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x40000000, LENGTH = 256K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - /* This is where the .data section is relocated for execution out - * FLASH. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* 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/olimex-strp711/nettest/ld.script b/nuttx/configs/olimex-strp711/scripts/ld.script similarity index 91% rename from nuttx/configs/olimex-strp711/nettest/ld.script rename to nuttx/configs/olimex-strp711/scripts/ld.script index b3b5c6ff87..2717592dc7 100755 --- a/nuttx/configs/olimex-strp711/nettest/ld.script +++ b/nuttx/configs/olimex-strp711/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/olimex-strp711/nettest/ld.script + * configs/olimex-strp711/scripts/ld.script * * Copyright (C) 2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -73,13 +73,24 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - /* This is where the .data section is relocated for execution out - * FLASH. The .data section will be relocated from _eronly - * to _sdata at boot time. - */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); - _eronly = ABSOLUTE(.); - .data : { _sdata = ABSOLUTE(.); *(.data .data.*) @@ -88,16 +99,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/pcblogic-pic32mx/nsh/ld.script b/nuttx/configs/pcblogic-pic32mx/nsh/ld.script index ff1618acfb..f80cc04365 100644 --- a/nuttx/configs/pcblogic-pic32mx/nsh/ld.script +++ b/nuttx/configs/pcblogic-pic32mx/nsh/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX460F512L has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX460F512L has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/pcblogic-pic32mx/ostest/ld.script b/nuttx/configs/pcblogic-pic32mx/ostest/ld.script index dd181b4d98..93e9320658 100644 --- a/nuttx/configs/pcblogic-pic32mx/ostest/ld.script +++ b/nuttx/configs/pcblogic-pic32mx/ostest/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX460F512L has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX460F512L has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/pic32-starterkit/nsh/ld.script b/nuttx/configs/pic32-starterkit/nsh/ld.script index 88f722064a..3e5ea6e039 100644 --- a/nuttx/configs/pic32-starterkit/nsh/ld.script +++ b/nuttx/configs/pic32-starterkit/nsh/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX795F512L has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX795F512L has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/pic32-starterkit/nsh2/ld.script b/nuttx/configs/pic32-starterkit/nsh2/ld.script index 1f07ee6514..1c9511cc45 100644 --- a/nuttx/configs/pic32-starterkit/nsh2/ld.script +++ b/nuttx/configs/pic32-starterkit/nsh2/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX795F512L has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX795F512L has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/pic32-starterkit/ostest/ld.script b/nuttx/configs/pic32-starterkit/ostest/ld.script index d2c1f162b5..45712df4d4 100644 --- a/nuttx/configs/pic32-starterkit/ostest/ld.script +++ b/nuttx/configs/pic32-starterkit/ostest/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX795F512L has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX795F512L has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/pic32mx7mmb/nsh/ld.script b/nuttx/configs/pic32mx7mmb/nsh/ld.script index a3ffbe91a7..f6ec304c3e 100644 --- a/nuttx/configs/pic32mx7mmb/nsh/ld.script +++ b/nuttx/configs/pic32mx7mmb/nsh/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX795F512L has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX795F512L has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/pic32mx7mmb/ostest/ld.script b/nuttx/configs/pic32mx7mmb/ostest/ld.script index a01074d21c..7f27c6adcf 100644 --- a/nuttx/configs/pic32mx7mmb/ostest/ld.script +++ b/nuttx/configs/pic32mx7mmb/ostest/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX795F512L has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX795F512L has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/qemu-i486/nsh/ld.script b/nuttx/configs/qemu-i486/nsh/ld.script index 3fffc84592..ddab1327e9 100755 --- a/nuttx/configs/qemu-i486/nsh/ld.script +++ b/nuttx/configs/qemu-i486/nsh/ld.script @@ -41,14 +41,14 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) + *(.text .text.*) *(.gnu.linkonce.t.*) _etext = ABSOLUTE(.); } .text ALIGN (0x1000) : { _srodata = ABSOLUTE(.); - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.fixup) *(.gnu.warning) *(.glue_7) diff --git a/nuttx/configs/qemu-i486/ostest/ld.script b/nuttx/configs/qemu-i486/ostest/ld.script index d597710783..e6e1c90e7b 100755 --- a/nuttx/configs/qemu-i486/ostest/ld.script +++ b/nuttx/configs/qemu-i486/ostest/ld.script @@ -41,14 +41,14 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) + *(.text .text.*) *(.gnu.linkonce.t.*) _etext = ABSOLUTE(.); } .text ALIGN (0x1000) : { _srodata = ABSOLUTE(.); - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.fixup) *(.gnu.warning) *(.glue_7) diff --git a/nuttx/configs/sam3u-ek/kernel/kernel.ld b/nuttx/configs/sam3u-ek/kernel/kernel.ld index 9388bf88c2..93d16124a6 100644 --- a/nuttx/configs/sam3u-ek/kernel/kernel.ld +++ b/nuttx/configs/sam3u-ek/kernel/kernel.ld @@ -33,7 +33,7 @@ * ****************************************************************************/ -/* The AT91SAM3U-4 has 256Kb of FLASH beginning at address 0x0008:0000, +/* The AT91SAM3U-4 has 256Kb of FLASH beginning at address 0x0008:0000, * 32Kb of SRAM beginning at address 0x2000:0000, and 16Kb of SRAM beginning * at address 0x2008:000 (used only for heap). When booting from FLASH, * FLASH memory is aliased to address 0x0000:0000 where the code expects to @@ -89,10 +89,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -102,6 +102,22 @@ SECTIONS _etext = ABSOLUTE(.); } > uflash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > uflash + + .ARM.extab : { + *(.ARM.extab*) + } > uflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > uflash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); .data : { @@ -112,16 +128,6 @@ SECTIONS _edata = ABSOLUTE(.); } > usram1 AT > uflash - .ARM.extab : { - *(.ARM.extab*) - } >usram1 - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >usram1 - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/sam3u-ek/knsh/ld.script b/nuttx/configs/sam3u-ek/knsh/ld.script index 34c4fbb322..e24a5bcbf8 100755 --- a/nuttx/configs/sam3u-ek/knsh/ld.script +++ b/nuttx/configs/sam3u-ek/knsh/ld.script @@ -33,7 +33,7 @@ * ****************************************************************************/ -/* The AT91SAM3U-4 has 256Kb of FLASH beginning at address 0x0008:0000, +/* The AT91SAM3U-4 has 256Kb of FLASH beginning at address 0x0008:0000, * 32Kb of SRAM beginning at address 0x2000:0000, and 16Kb of SRAM beginning * at address 0x2008:000 (used only for heap). When booting from FLASH, * FLASH memory is aliased to address 0x0000:0000 where the code expects to @@ -69,10 +69,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -82,6 +82,22 @@ SECTIONS _etext = ABSOLUTE(.); } > kflash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > kflash + + .ARM.extab : { + *(.ARM.extab*) + } > kflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > kflash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); .data : { @@ -92,16 +108,6 @@ SECTIONS _edata = ABSOLUTE(.); } > ksram1 AT > kflash - .ARM.extab : { - *(.ARM.extab*) - } >ksram1 - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >ksram1 - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/sam3u-ek/nsh/Make.defs b/nuttx/configs/sam3u-ek/nsh/Make.defs index 5bf989aad8..337b98df84 100644 --- a/nuttx/configs/sam3u-ek/nsh/Make.defs +++ b/nuttx/configs/sam3u-ek/nsh/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/sam3u-ek/nsh/ld.script b/nuttx/configs/sam3u-ek/nsh/ld.script deleted file mode 100755 index 94ae474033..0000000000 --- a/nuttx/configs/sam3u-ek/nsh/ld.script +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/sam3u-ek/nsh/ld.script - * - * Copyright (C) 2010 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. - * - ****************************************************************************/ - -/* The AT91SAM3U-4 has 256Kb of FLASH beginning at address 0x0008:0000, - * 32Kb of SRAM beginning at address 0x2000:0000, and 16Kb of SRAM beginning - * at address 0x2008:000 (used only for heap). When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00080000, LENGTH = 256K - sram1 (rwx) : ORIGIN = 0x20000000, LENGTH = 32K - sram2 (rwx) : ORIGIN = 0x20080000, LENGTH = 16K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram1 AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram1 - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram1 - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram1 - /* 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/sam3u-ek/nx/Make.defs b/nuttx/configs/sam3u-ek/nx/Make.defs index e4140a1103..86a1c5c38e 100644 --- a/nuttx/configs/sam3u-ek/nx/Make.defs +++ b/nuttx/configs/sam3u-ek/nx/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nx/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nx/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/sam3u-ek/ostest/Make.defs b/nuttx/configs/sam3u-ek/ostest/Make.defs index 8c765976b1..25f386df75 100644 --- a/nuttx/configs/sam3u-ek/ostest/Make.defs +++ b/nuttx/configs/sam3u-ek/ostest/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/sam3u-ek/ostest/ld.script b/nuttx/configs/sam3u-ek/ostest/ld.script deleted file mode 100755 index 70fd611e74..0000000000 --- a/nuttx/configs/sam3u-ek/ostest/ld.script +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/sam3u-ek/ostest/ld.script - * - * Copyright (C) 2009-2010 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. - * - ****************************************************************************/ - -/* The AT91SAM3U-4 has 256Kb of FLASH beginning at address 0x0008:0000, - * 32Kb of SRAM beginning at address 0x2000:0000, and 16Kb of SRAM beginning - * at address 0x2008:000 (used only for heap). When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00080000, LENGTH = 256K - sram1 (rwx) : ORIGIN = 0x20000000, LENGTH = 32K - sram2 (rwx) : ORIGIN = 0x20080000, LENGTH = 16K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram1 AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram1 - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram1 - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram1 - /* 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/sam3u-ek/nx/ld.script b/nuttx/configs/sam3u-ek/scripts/ld.script similarity index 97% rename from nuttx/configs/sam3u-ek/nx/ld.script rename to nuttx/configs/sam3u-ek/scripts/ld.script index 56ae5d6a4e..e382165836 100755 --- a/nuttx/configs/sam3u-ek/nx/ld.script +++ b/nuttx/configs/sam3u-ek/scripts/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/sam3u-ek/nx/ld.script + * configs/sam3u-ek/scripts/ld.script * * Copyright (C) 2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -33,7 +33,7 @@ * ****************************************************************************/ -/* The AT91SAM3U-4 has 256Kb of FLASH beginning at address 0x0008:0000, +/* The AT91SAM3U-4 has 256Kb of FLASH beginning at address 0x0008:0000, * 32Kb of SRAM beginning at address 0x2000:0000, and 16Kb of SRAM beginning * at address 0x2008:000 (used only for heap). When booting from FLASH, * FLASH memory is aliased to address 0x0000:0000 where the code expects to @@ -55,10 +55,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) diff --git a/nuttx/configs/sam3u-ek/touchscreen/Make.defs b/nuttx/configs/sam3u-ek/touchscreen/Make.defs index 99410a652c..fce80ec256 100644 --- a/nuttx/configs/sam3u-ek/touchscreen/Make.defs +++ b/nuttx/configs/sam3u-ek/touchscreen/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/touchscreen/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/touchscreen/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/sam3u-ek/touchscreen/ld.script b/nuttx/configs/sam3u-ek/touchscreen/ld.script deleted file mode 100755 index dd30648a28..0000000000 --- a/nuttx/configs/sam3u-ek/touchscreen/ld.script +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/sam3u-ek/touchscreen/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The AT91SAM3U-4 has 256Kb of FLASH beginning at address 0x0008:0000, - * 32Kb of SRAM beginning at address 0x2000:0000, and 16Kb of SRAM beginning - * at address 0x2008:000 (used only for heap). When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x00080000, LENGTH = 256K - sram1 (rwx) : ORIGIN = 0x20000000, LENGTH = 32K - sram2 (rwx) : ORIGIN = 0x20080000, LENGTH = 16K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram1 AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram1 - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram1 - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram1 - /* 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/shenzhou/scripts/ld.script b/nuttx/configs/shenzhou/scripts/ld.script index d167cc49d7..1a23385f70 100644 --- a/nuttx/configs/shenzhou/scripts/ld.script +++ b/nuttx/configs/shenzhou/scripts/ld.script @@ -50,10 +50,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -69,15 +69,15 @@ SECTIONS _einit = ABSOLUTE(.); } > flash + .ARM.extab : { + *(.ARM.extab*) + } > flash + __exidx_start = ABSOLUTE(.); .ARM.exidx : { *(.ARM.exidx*) } > flash __exidx_end = ABSOLUTE(.); - - .ARM.extab : { - *(.ARM.extab*) - } > flash _eronly = ABSOLUTE(.); diff --git a/nuttx/configs/shenzhou/scripts/ld.script.dfu b/nuttx/configs/shenzhou/scripts/ld.script.dfu index c6d0d76b8e..dcf57b9b0b 100644 --- a/nuttx/configs/shenzhou/scripts/ld.script.dfu +++ b/nuttx/configs/shenzhou/scripts/ld.script.dfu @@ -52,10 +52,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -71,6 +71,10 @@ SECTIONS _einit = ABSOLUTE(.); } > flash + .ARM.extab : { + *(.ARM.extab*) + } > flash + __exidx_start = ABSOLUTE(.); .ARM.exidx : { *(.ARM.exidx*) @@ -89,10 +93,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/stm3210e-eval/RIDE/README.txt b/nuttx/configs/stm3210e-eval/RIDE/README.txt index 8da1c38c98..b8f40e4004 100644 --- a/nuttx/configs/stm3210e-eval/RIDE/README.txt +++ b/nuttx/configs/stm3210e-eval/RIDE/README.txt @@ -1,38 +1,38 @@ -README ------- - -This directory contains a simple RIDE7 project used to bring up the -STM3210E-EVAL board. This project includes only the STM32 boot-up -code under arch/arm/src and configs/stm3210e-eval/src plus as little -additional environmental support as necessary. - -bigfatstub.c - - The NuttX OS is not included in this project. This file contains - stubs for all of the NuttX entry points and this replaces NuttX - -Make.defs, defconfig, setenv.h - - The first step to using this RIDE project is to build a compatible - cygwin project. This will set up of the directories and produce - all of the necessary autogenerated files. - - cd tools - ./configure.sh stm3210e-eva/RIDE - cd .. - . ./setenv.sh - make - -nuttx.* - - RIDE7 project files - -stm32-nuttx.ld - - This is the linker script that replaces the RIDE7 linker script. - -stm32-ld.sh - - This is a shell script that will use the RIDE7 tools to relink the - NuttX binaries. Useful because RIDE7 does not provide much linker - output to see what is going on. +README +------ + +This directory contains a simple RIDE7 project used to bring up the +STM3210E-EVAL board. This project includes only the STM32 boot-up +code under arch/arm/src and configs/stm3210e-eval/src plus as little +additional environmental support as necessary. + +bigfatstub.c + + The NuttX OS is not included in this project. This file contains + stubs for all of the NuttX entry points and this replaces NuttX + +Make.defs, defconfig, setenv.h + + The first step to using this RIDE project is to build a compatible + cygwin project. This will set up of the directories and produce + all of the necessary autogenerated files. + + cd tools + ./configure.sh stm3210e-eva/RIDE + cd .. + . ./setenv.sh + make + +nuttx.* + + RIDE7 project files + +../scripts/ld.scrip + + This is the linker script that replaces the RIDE7 linker script. + +stm32-ld.sh + + This is a shell script that will use the RIDE7 tools to relink the + NuttX binaries. Useful because RIDE7 does not provide much linker + output to see what is going on. diff --git a/nuttx/configs/stm3210e-eval/RIDE/nuttx.elf.ld b/nuttx/configs/stm3210e-eval/RIDE/nuttx.elf.ld index f4d3a6ca1c..515f91cc29 100755 --- a/nuttx/configs/stm3210e-eval/RIDE/nuttx.elf.ld +++ b/nuttx/configs/stm3210e-eval/RIDE/nuttx.elf.ld @@ -1,4 +1,4 @@ - + SEARCH_DIR(".") SEARCH_DIR("C:\Program Files\Raisonance\Ride\Lib\ARM") STARTUP("C:\cygwin\home\Owner\projects\nuttx\nuttx\arch\arm\src\stm32_vectors.o") @@ -16,4 +16,4 @@ INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\up_b INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\irq_unexpectedisr.o") INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\lib_memcpy.o") OUTPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\nuttx.elf") -INCLUDE "C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\stm32-nuttx.ld" +INCLUDE "C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\scripts\ld.script" diff --git a/nuttx/configs/stm3210e-eval/RIDE/nuttx.rapp b/nuttx/configs/stm3210e-eval/RIDE/nuttx.rapp index 4ab167792f..ce9ffc81e2 100755 --- a/nuttx/configs/stm3210e-eval/RIDE/nuttx.rapp +++ b/nuttx/configs/stm3210e-eval/RIDE/nuttx.rapp @@ -62,7 +62,7 @@
    - +
    diff --git a/nuttx/configs/stm3210e-eval/RIDE/stm32-nuttx.ld b/nuttx/configs/stm3210e-eval/RIDE/stm32-nuttx.ld deleted file mode 100755 index 704960ad9f..0000000000 --- a/nuttx/configs/stm3210e-eval/RIDE/stm32-nuttx.ld +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * configs/stm3210e-eval/RIDE/stm32-nuttx.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. - * - ****************************************************************************/ - -/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and - * 64Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - _eronly = ABSOLUTE(.); /* See below */ - - /* The STM32F103Z has 64Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - - .bss : { /* BSS */ - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - /* 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/stm3210e-eval/scripts/ld.script b/nuttx/configs/stm3210e-eval/scripts/ld.script index 5504f0f612..0f0e017aa8 100644 --- a/nuttx/configs/stm3210e-eval/scripts/ld.script +++ b/nuttx/configs/stm3210e-eval/scripts/ld.script @@ -53,10 +53,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -66,6 +66,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); /* The STM32F103Z has 64Kb of SRAM beginning at the following address */ @@ -78,16 +94,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/stm3210e-eval/scripts/ld.script.dfu b/nuttx/configs/stm3210e-eval/scripts/ld.script.dfu index 8f879983a0..8669a0f021 100644 --- a/nuttx/configs/stm3210e-eval/scripts/ld.script.dfu +++ b/nuttx/configs/stm3210e-eval/scripts/ld.script.dfu @@ -52,10 +52,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -65,6 +65,22 @@ SECTIONS _etext = ABSOLUTE(.); } > flash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + _eronly = ABSOLUTE(.); /* The STM32F103Z has 64Kb of SRAM beginning at the following address */ @@ -77,16 +93,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } >sram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/stm3220g-eval/scripts/ld.script b/nuttx/configs/stm3220g-eval/scripts/ld.script index 1c9f12bba1..1b88091666 100644 --- a/nuttx/configs/stm3220g-eval/scripts/ld.script +++ b/nuttx/configs/stm3220g-eval/scripts/ld.script @@ -58,10 +58,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -77,6 +77,10 @@ SECTIONS _einit = ABSOLUTE(.); } > flash + .ARM.extab : { + *(.ARM.extab*) + } > flash + __exidx_start = ABSOLUTE(.); .ARM.exidx : { *(.ARM.exidx*) @@ -93,10 +97,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/stm3240g-eval/scripts/ld.script b/nuttx/configs/stm3240g-eval/scripts/ld.script index 078f2890f4..e319a896a9 100644 --- a/nuttx/configs/stm3240g-eval/scripts/ld.script +++ b/nuttx/configs/stm3240g-eval/scripts/ld.script @@ -59,10 +59,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -78,6 +78,10 @@ SECTIONS _einit = ABSOLUTE(.); } > flash + .ARM.extab : { + *(.ARM.extab*) + } > flash + __exidx_start = ABSOLUTE(.); .ARM.exidx : { *(.ARM.exidx*) @@ -94,10 +98,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/stm32f4discovery/scripts/ld.script b/nuttx/configs/stm32f4discovery/scripts/ld.script index 67879e8d1d..edc4a70910 100644 --- a/nuttx/configs/stm32f4discovery/scripts/ld.script +++ b/nuttx/configs/stm32f4discovery/scripts/ld.script @@ -59,10 +59,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -78,6 +78,10 @@ SECTIONS _einit = ABSOLUTE(.); } > flash + .ARM.extab : { + *(.ARM.extab*) + } > flash + __exidx_start = ABSOLUTE(.); .ARM.exidx : { *(.ARM.exidx*) @@ -94,10 +98,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/sure-pic32mx/nsh/ld.script b/nuttx/configs/sure-pic32mx/nsh/ld.script index a88bdc2c8f..0975477cce 100644 --- a/nuttx/configs/sure-pic32mx/nsh/ld.script +++ b/nuttx/configs/sure-pic32mx/nsh/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX440F512H has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX440F512H has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/sure-pic32mx/ostest/ld.script b/nuttx/configs/sure-pic32mx/ostest/ld.script index 7b5ffa3c4a..01d97ad552 100644 --- a/nuttx/configs/sure-pic32mx/ostest/ld.script +++ b/nuttx/configs/sure-pic32mx/ostest/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX440F512H has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX440F512H has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/sure-pic32mx/usbnsh/ld.script b/nuttx/configs/sure-pic32mx/usbnsh/ld.script index 5bdc5af6f6..088f812d8d 100644 --- a/nuttx/configs/sure-pic32mx/usbnsh/ld.script +++ b/nuttx/configs/sure-pic32mx/usbnsh/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX440F512H has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX440F512H has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/twr-k60n512/nsh/Make.defs b/nuttx/configs/twr-k60n512/nsh/Make.defs index f2922c575b..a558cc0109 100644 --- a/nuttx/configs/twr-k60n512/nsh/Make.defs +++ b/nuttx/configs/twr-k60n512/nsh/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/twr-k60n512/ostest/Make.defs b/nuttx/configs/twr-k60n512/ostest/Make.defs index 871141640d..6d49455215 100644 --- a/nuttx/configs/twr-k60n512/ostest/Make.defs +++ b/nuttx/configs/twr-k60n512/ostest/Make.defs @@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/ostest/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}" MAXOPTIMIZATION = -O2 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)/ostest/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/twr-k60n512/ostest/ld.script b/nuttx/configs/twr-k60n512/ostest/ld.script deleted file mode 100644 index 717a457474..0000000000 --- a/nuttx/configs/twr-k60n512/ostest/ld.script +++ /dev/null @@ -1,135 +0,0 @@ -/**************************************************************************** - * configs/twr-k60n512/ostest/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The K60N512VMD100 has 512Kb of FLASH beginning at address 0x0000:0000 and - * 128Kb of SRAM beginning at address 0x1800:0000 (SRAM_L) and 0x2000:000 - * (SRAM_U). - * - * NOTE: that the first part of the K40 FLASH region is reserved for - * interrupt vectflash and, following that, is a region from 0x0000:0400 - * to 0x0000:040f that is reserved for the FLASH control fields (FCF). - * - * NOTE: The on-chip RAM is split evenly among SRAM_L and SRAM_U. The RAM is - * also implemented such that the SRAM_L and SRAM_U ranges form a - * contiguous block in the memory map. - */ - -MEMORY -{ - vectflash (rx) : ORIGIN = 0x00000000, LENGTH = 1K - 16 - cfmprotect (rx) : ORIGIN = 0x00000400, LENGTH = 16 - progflash (rx) : ORIGIN = 0x00000800, LENGTH = 512K - 2K - datasram (rwx) : ORIGIN = 0x1fff0000, LENGTH = 128K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .vectors : { - _svectors = ABSOLUTE(.); - *(.vectors) - _evectors = ABSOLUTE(.); - } > vectflash - - .cfmprotect : { - *(.cfmconfig) - } > cfmprotect - - .text : { - _stext = ABSOLUTE(.); - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > progflash - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > datasram AT > progflash - - _eronly = LOADADDR(.data); - - .ramfunc ALIGN(4): { - _sramfuncs = ABSOLUTE(.); - *(.ramfunc .ramfunc.*) - _eramfuncs = ABSOLUTE(.); - } > datasram AT > progflash - - _framfuncs = LOADADDR(.ramfunc); - - .ARM.extab : { - *(.ARM.extab*) - } > datasram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > datasram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > datasram - - /* 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/twr-k60n512/nsh/ld.script b/nuttx/configs/twr-k60n512/scripts/ld.script similarity index 92% rename from nuttx/configs/twr-k60n512/nsh/ld.script rename to nuttx/configs/twr-k60n512/scripts/ld.script index e8e5e7de15..26410e6d86 100644 --- a/nuttx/configs/twr-k60n512/nsh/ld.script +++ b/nuttx/configs/twr-k60n512/scripts/ld.script @@ -1,5 +1,5 @@ -/**************************************************************************** - * configs/twr-k60n512/nsh/ld.script + /**************************************************************************** + * configs/twr-k60n512/scripts/ld.script * * Copyright (C) 2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -70,10 +70,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -83,6 +83,22 @@ SECTIONS _etext = ABSOLUTE(.); } > progflash + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > progflash + + .ARM.extab : { + *(.ARM.extab*) + } > progflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > progflash + __exidx_end = ABSOLUTE(.); + .data : { _sdata = ABSOLUTE(.); *(.data .data.*) @@ -101,16 +117,6 @@ SECTIONS _framfuncs = LOADADDR(.ramfunc); - .ARM.extab : { - *(.ARM.extab*) - } > datasram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > datasram - __exidx_end = ABSOLUTE(.); - .bss : { _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/ubw32/nsh/ld.script b/nuttx/configs/ubw32/nsh/ld.script index b053aebe62..43e64a51be 100644 --- a/nuttx/configs/ubw32/nsh/ld.script +++ b/nuttx/configs/ubw32/nsh/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX460F512L has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX460F512L has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/ubw32/ostest/ld.script b/nuttx/configs/ubw32/ostest/ld.script index ff4d1c79f2..3a64fff23a 100644 --- a/nuttx/configs/ubw32/ostest/ld.script +++ b/nuttx/configs/ubw32/ostest/ld.script @@ -39,7 +39,7 @@ MEMORY /* The PIC32MX460F512L has 512Kb of program FLASH at physical address * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 */ - + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K /* The PIC32MX460F512L has 12Kb of boot FLASH at physical address @@ -168,8 +168,8 @@ SECTIONS .text : { _stext = ABSOLUTE(.); - *(.text .text.*) - *(.stub) + *(.text .text.*) + *(.stub) KEEP (*(.text.*personality*)) *(.gnu.linkonce.t.*) *(.gnu.warning) @@ -178,12 +178,12 @@ SECTIONS /* Read-only data is included in the text section */ - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.rodata1) *(.gnu.linkonce.r.*) /* Small initialized constant global and static data */ - + *(.sdata2 .sdata2.*) *(.gnu.linkonce.s2.*) diff --git a/nuttx/configs/vsn/nsh/Make.defs b/nuttx/configs/vsn/nsh/Make.defs index 64b972ee27..c6ab376dec 100644 --- a/nuttx/configs/vsn/nsh/Make.defs +++ b/nuttx/configs/vsn/nsh/Make.defs @@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/nsh/$(LDSCRIPT)}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 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)/nsh/$(LDSCRIPT) + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/nuttx/configs/vsn/nsh/ld.script b/nuttx/configs/vsn/nsh/ld.script index 63c8585ebf..1ee155fb59 100755 --- a/nuttx/configs/vsn/nsh/ld.script +++ b/nuttx/configs/vsn/nsh/ld.script @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/stm3210e-eval/nsh/ld.script + * configs/stm3210e-eval/scripts/ld.script * * Copyright (C) 2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -53,10 +53,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -66,7 +66,23 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - _eronly = ABSOLUTE(.); /* See below */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); /* The STM32F103Z has 64Kb of SRAM beginning at the following address */ @@ -78,16 +94,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - .bss : { /* BSS */ _sbss = ABSOLUTE(.); *(.bss .bss.*) diff --git a/nuttx/configs/vsn/nsh/ld.script.dfu b/nuttx/configs/vsn/nsh/ld.script.dfu index aa077ba3b7..3f5e2a06a6 100755 --- a/nuttx/configs/vsn/nsh/ld.script.dfu +++ b/nuttx/configs/vsn/nsh/ld.script.dfu @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/stm3210e-eval/nsh/ld.script.dfu + * configs/stm3210e-eval/scripts/ld.script.dfu * * Copyright (C) 2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -52,10 +52,10 @@ SECTIONS .text : { _stext = ABSOLUTE(.); *(.vectors) - *(.text .text.*) + *(.text .text.*) *(.fixup) *(.gnu.warning) - *(.rodata .rodata.*) + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) *(.glue_7t) @@ -65,7 +65,23 @@ SECTIONS _etext = ABSOLUTE(.); } > flash - _eronly = ABSOLUTE(.); /* See below */ + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); /* The STM32F103Z has 64Kb of SRAM beginning at the following address */ @@ -77,16 +93,6 @@ SECTIONS _edata = ABSOLUTE(.); } > sram AT > flash - .ARM.extab : { - *(.ARM.extab*) - } >sram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } >sram - .bss : { /* BSS */ _sbss = ABSOLUTE(.); *(.bss .bss.*) From f6de06f9f9959027ee598c0177f676aa4f2ca627 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 4 Nov 2012 18:54:04 +0000 Subject: [PATCH 077/206] Add interfaces flags, extend ifconfig, add ifup and ifdown commands (Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5308 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 6 + apps/include/netutils/uiplib.h | 5 + apps/netutils/uiplib/Makefile | 3 +- apps/netutils/uiplib/uip_gethostaddr.c | 2 + apps/netutils/uiplib/uip_getifflag.c | 118 +++++++++++++ apps/netutils/uiplib/uip_getmacaddr.c | 2 + apps/netutils/uiplib/uip_setifflag.c | 141 ++++++++++++++++ apps/netutils/uiplib/uiplib.c | 57 +++++++ apps/netutils/webclient/webclient.c | 1 + apps/nshlib/README.txt | 43 +++-- apps/nshlib/nsh.h | 34 +++- apps/nshlib/nsh_netcmds.c | 222 +++++++++++++++++++++++-- apps/nshlib/nsh_parse.c | 32 ++-- nuttx/ChangeLog | 2 + nuttx/Documentation/NuttShell.html | 199 +++++++++++++++------- nuttx/include/net/if.h | 9 + nuttx/include/nuttx/net/ioctl.h | 6 + nuttx/include/nuttx/net/uip/uip-arch.h | 4 + nuttx/net/netdev_ioctl.c | 151 ++++++++++++++--- 19 files changed, 905 insertions(+), 132 deletions(-) create mode 100644 apps/netutils/uiplib/uip_getifflag.c create mode 100644 apps/netutils/uiplib/uip_setifflag.c diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 0c4e94fd93..cd1b4eb53a 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -400,3 +400,9 @@ * apps/netutils/webclient, apps/netutils.codes, and apps/examples/wgetjson: Add support for wget POST interface. Contributed by Darcy Gong. * apps/examples/relays: A relay example contributed by Darcy Gong. + * apps/nshlib/nsh_netcmds: Add ifup and ifdown commands (from Darcy + Gong). + * apps/nshlib/nsh_netcmds: Extend the ifconfig command so that it + supports setting IP addresses, network masks, name server addresses, + and hardware address (from Darcy Gong). + diff --git a/apps/include/netutils/uiplib.h b/apps/include/netutils/uiplib.h index b994173621..8e66fb9709 100644 --- a/apps/include/netutils/uiplib.h +++ b/apps/include/netutils/uiplib.h @@ -102,6 +102,7 @@ extern "C" { */ EXTERN bool uiplib_ipaddrconv(const char *addrstr, uint8_t *addr); +EXTERN bool uiplib_hwmacconv(const char *hwstr, uint8_t *hw); /* Get and set IP/MAC addresses (Ethernet L2 only) */ @@ -135,6 +136,10 @@ EXTERN int uip_parsehttpurl(const char *url, uint16_t *port, EXTERN int uip_listenon(uint16_t portno); EXTERN void uip_server(uint16_t portno, pthread_startroutine_t handler, int stacksize); +EXTERN int uip_getifstatus(const char *ifname, bool *status); +EXTERN int uip_ifup(const char *ifname); +EXTERN int uip_ifdown(const char *ifname); + #undef EXTERN #ifdef __cplusplus } diff --git a/apps/netutils/uiplib/Makefile b/apps/netutils/uiplib/Makefile index 189b32acc2..c1b128c26d 100644 --- a/apps/netutils/uiplib/Makefile +++ b/apps/netutils/uiplib/Makefile @@ -41,7 +41,8 @@ include $(APPDIR)/Make.defs ASRCS = CSRCS = uiplib.c uip_sethostaddr.c uip_gethostaddr.c uip_setdraddr.c \ - uip_setnetmask.c uip_parsehttpurl.c + uip_setnetmask.c uip_parsehttpurl.c uip_setifflag.c \ + uip_getifflag.c # These require TCP support diff --git a/apps/netutils/uiplib/uip_gethostaddr.c b/apps/netutils/uiplib/uip_gethostaddr.c index c5c70b1be5..0b2b5dd28c 100644 --- a/apps/netutils/uiplib/uip_gethostaddr.c +++ b/apps/netutils/uiplib/uip_gethostaddr.c @@ -45,6 +45,7 @@ #include #include +#include #include #include @@ -97,6 +98,7 @@ int uip_gethostaddr(const char *ifname, struct in_addr *addr) memcpy(addr, &req.ifr_addr, sizeof(struct in_addr)); #endif } + close(sockfd); } } return ret; diff --git a/apps/netutils/uiplib/uip_getifflag.c b/apps/netutils/uiplib/uip_getifflag.c new file mode 100644 index 0000000000..8574d331ae --- /dev/null +++ b/apps/netutils/uiplib/uip_getifflag.c @@ -0,0 +1,118 @@ +/**************************************************************************** + * netutils/uiplib/uip_getifflag.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: uip_getifstatus + * + * Description: + * Get the network driver ifup/ifdown status + * + * Parameters: + * ifname The name of the interface to use + * status interface flag ifup or ifdown status + * + * Return: + * 0 on sucess; -1 on failure + * + ****************************************************************************/ + +int uip_getifstatus(const char *ifname, bool *status) +{ + int ret = ERROR; + if (ifname) + { + /* Get a socket (only so that we get access to the INET subsystem) */ + + int sockfd = socket(PF_INET, UIPLIB_SOCK_IOCTL, 0); + if (sockfd >= 0) + { + struct ifreq req; + memset (&req, 0, sizeof(struct ifreq)); + + /* Put the driver name into the request */ + + strncpy(req.ifr_name, ifname, IFNAMSIZ); + + /* Perform the ioctl to ifup or ifdown status */ + + ret = ioctl(sockfd, SIOCGIFFLAGS, (unsigned long)&req); + if (!ret) + { + /* Return the ifup or ifdown status */ + + if ((req.ifr_flags & IF_FLAG_IFUP) == (req.ifr_flags & IF_FLAG_IFDOWN)) + { + ret = ERROR; + } + else if(req.ifr_flags & IF_FLAG_IFUP) + { + *status = true; + } + else + { + *status = false; + } + } + close(sockfd); + } + } + return ret; +} + +#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/apps/netutils/uiplib/uip_getmacaddr.c b/apps/netutils/uiplib/uip_getmacaddr.c index f4f01a7f30..e0f72f4a78 100644 --- a/apps/netutils/uiplib/uip_getmacaddr.c +++ b/apps/netutils/uiplib/uip_getmacaddr.c @@ -44,6 +44,7 @@ #include #include #include +#include #include #include @@ -96,6 +97,7 @@ int uip_getmacaddr(const char *ifname, uint8_t *macaddr) memcpy(macaddr, &req.ifr_hwaddr.sa_data, IFHWADDRLEN); } + close(sockfd); } } return ret; diff --git a/apps/netutils/uiplib/uip_setifflag.c b/apps/netutils/uiplib/uip_setifflag.c new file mode 100644 index 0000000000..317ddcce15 --- /dev/null +++ b/apps/netutils/uiplib/uip_setifflag.c @@ -0,0 +1,141 @@ +/**************************************************************************** + * netutils/uiplib/uip_setifflag.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: uip_ifup + * + * Description: + * Set the network interface UP + * + * Parameters: + * ifname The name of the interface to use + * + * Return: + * 0 on sucess; -1 on failure + * + ****************************************************************************/ + +int uip_ifup(const char *ifname) +{ + int ret = ERROR; + if (ifname) + { + /* Get a socket (only so that we get access to the INET subsystem) */ + + int sockfd = socket(PF_INET, UIPLIB_SOCK_IOCTL, 0); + if (sockfd >= 0) + { + struct ifreq req; + memset (&req, 0, sizeof(struct ifreq)); + + /* Put the driver name into the request */ + + strncpy(req.ifr_name, ifname, IFNAMSIZ); + + /* Perform the ioctl to ifup flag */ + req.ifr_flags |= IF_FLAG_IFUP; + + ret = ioctl(sockfd, SIOCSIFFLAGS, (unsigned long)&req); + close(sockfd); + } + } + return ret; +} + +/**************************************************************************** + * Name: uip_ifdown + * + * Description: + * Set the network interface DOWN + * + * Parameters: + * ifname The name of the interface to use + * + * Return: + * 0 on sucess; -1 on failure + * + ****************************************************************************/ + +int uip_ifdown(const char *ifname) +{ + int ret = ERROR; + if (ifname) + { + /* Get a socket (only so that we get access to the INET subsystem) */ + + int sockfd = socket(PF_INET, UIPLIB_SOCK_IOCTL, 0); + if (sockfd >= 0) + { + struct ifreq req; + memset (&req, 0, sizeof(struct ifreq)); + + /* Put the driver name into the request */ + + strncpy(req.ifr_name, ifname, IFNAMSIZ); + + /* Perform the ioctl to ifup flag */ + req.ifr_flags |= IF_FLAG_IFDOWN; + + ret = ioctl(sockfd, SIOCSIFFLAGS, (unsigned long)&req); + close(sockfd); + } + } + return ret; +} + +#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/apps/netutils/uiplib/uiplib.c b/apps/netutils/uiplib/uiplib.c index f863b7343f..32ffaeb06d 100644 --- a/apps/netutils/uiplib/uiplib.c +++ b/apps/netutils/uiplib/uiplib.c @@ -45,10 +45,12 @@ #include #include +#include #include #include + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -93,3 +95,58 @@ bool uiplib_ipaddrconv(const char *addrstr, uint8_t *ipaddr) } return true; } + +bool uiplib_hwmacconv(const char *hwstr, uint8_t *hw) +{ + unsigned char tmp; + char c; + unsigned char i; + unsigned char j; + + if (strlen(hwstr)!=17) + { + return false; + } + + tmp = 0; + + for (i = 0; i < 6; ++i) + { + j = 0; + do + { + c = *hwstr; + ++j; + if (j > 3) + { + return false; + } + if (c == ':' || c == 0) + { + *hw = tmp; + nvdbg("HWMAC[%d]%0.2X\n",i,tmp); + ++hw; + tmp = 0; + } + else if(c >= '0' && c <= '9') + { + tmp = (tmp << 4) + (c - '0'); + } + else if(c >= 'a' && c <= 'f') + { + tmp = (tmp << 4) + (c - 'a' + 10); + } + else if(c >= 'A' && c <= 'F') + { + tmp = (tmp << 4) + (c - 'A' + 10); + } + else + { + return false; + } + ++hwstr; + } + while(c != ':' && c != 0); + } + return true; +} diff --git a/apps/netutils/webclient/webclient.c b/apps/netutils/webclient/webclient.c index 4dbd130ec5..2604ce020c 100644 --- a/apps/netutils/webclient/webclient.c +++ b/apps/netutils/webclient/webclient.c @@ -56,6 +56,7 @@ #include #include +#include #include #include #include diff --git a/apps/nshlib/README.txt b/apps/nshlib/README.txt index 9f371678ee..227f01c0a0 100644 --- a/apps/nshlib/README.txt +++ b/apps/nshlib/README.txt @@ -385,7 +385,7 @@ o help [-v] [] Show full command usage only for this command -o ifconfig +o ifconfig [nic_name [ip]] [dr|gw|gateway ] [netmask ] [dns ] [hw ] Show the current configuration of the network, for example: @@ -396,6 +396,22 @@ o ifconfig if uIP statistics are enabled (CONFIG_NET_STATISTICS), then this command will also show the detailed state of uIP. +o ifdown + + Take down the interface identified by the name . + + Example: + + ifdown eth0 + +o ifup + + Bring up down the interface identified by the name . + + Example: + + ifup eth0 + o kill - Send the to the task identified by . @@ -850,6 +866,8 @@ Command Dependencies on Configuration Settings get CONFIG_NET && CONFIG_NET_UDP && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NET_BUFSIZE >= 558 (see note 1) help -- ifconfig CONFIG_NET + ifdown CONFIG_NET + ifup CONFIG_NET kill !CONFIG_DISABLE_SIGNALS losetup !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 ls CONFIG_NFILE_DESCRIPTORS > 0 @@ -899,17 +917,18 @@ also allow it to squeeze into very small memory footprints. CONFIG_NSH_DISABLE_CD, CONFIG_NSH_DISABLE_CP, CONFIG_NSH_DISABLE_DD, CONFIG_NSH_DISABLE_DF, CONFIG_NSH_DISABLE_ECHO, CONFIG_NSH_DISABLE_EXEC, CONFIG_NSH_DISABLE_EXIT, CONFIG_NSH_DISABLE_FREE, CONFIG_NSH_DISABLE_GET, - CONFIG_NSH_DISABLE_HELP, CONFIG_NSH_DISABLE_IFCONFIG, CONFIG_NSH_DISABLE_KILL, - CONFIG_NSH_DISABLE_LOSETUP, CONFIG_NSH_DISABLE_LS, CONFIG_NSH_DISABLE_MD5 - CONFIG_NSH_DISABLE_MB, CONFIG_NSH_DISABLE_MKDIR, CONFIG_NSH_DISABLE_MKFATFS, - CONFIG_NSH_DISABLE_MKFIFO, CONFIG_NSH_DISABLE_MKRD, CONFIG_NSH_DISABLE_MH, - CONFIG_NSH_DISABLE_MOUNT, CONFIG_NSH_DISABLE_MW, CONFIG_NSH_DISABLE_MV, - CONFIG_NSH_DISABLE_NFSMOUNT, CONFIG_NSH_DISABLE_PS, CONFIG_NSH_DISABLE_PING, - CONFIG_NSH_DISABLE_PUT, CONFIG_NSH_DISABLE_PWD, CONFIG_NSH_DISABLE_RM, - CONFIG_NSH_DISABLE_RMDIR, CONFIG_NSH_DISABLE_SET, CONFIG_NSH_DISABLE_SH, - CONFIG_NSH_DISABLE_SLEEP, CONFIG_NSH_DISABLE_TEST, CONFIG_NSH_DISABLE_UMOUNT, - CONFIG_NSH_DISABLE_UNSET, CONFIG_NSH_DISABLE_URLDECODE, CONFIG_NSH_DISABLE_URLENCODE, - CONFIG_NSH_DISABLE_USLEEP, CONFIG_NSH_DISABLE_WGET, CONFIG_NSH_DISABLE_XD + CONFIG_NSH_DISABLE_HELP, CONFIG_NSH_DISABLE_IFCONFIG, CONFIG_NSH_DISABLE_IFUPDOWN, + CONFIG_NSH_DISABLE_KILL, CONFIG_NSH_DISABLE_LOSETUP, CONFIG_NSH_DISABLE_LS, + CONFIG_NSH_DISABLE_MD5 CONFIG_NSH_DISABLE_MB, CONFIG_NSH_DISABLE_MKDIR, + CONFIG_NSH_DISABLE_MKFATFS, CONFIG_NSH_DISABLE_MKFIFO, CONFIG_NSH_DISABLE_MKRD, + CONFIG_NSH_DISABLE_MH, CONFIG_NSH_DISABLE_MOUNT, CONFIG_NSH_DISABLE_MW, + CONFIG_NSH_DISABLE_MV, CONFIG_NSH_DISABLE_NFSMOUNT, CONFIG_NSH_DISABLE_PS, + CONFIG_NSH_DISABLE_PING, CONFIG_NSH_DISABLE_PUT, CONFIG_NSH_DISABLE_PWD, + CONFIG_NSH_DISABLE_RM, CONFIG_NSH_DISABLE_RMDIR, CONFIG_NSH_DISABLE_SET, + CONFIG_NSH_DISABLE_SH, CONFIG_NSH_DISABLE_SLEEP, CONFIG_NSH_DISABLE_TEST, + CONFIG_NSH_DISABLE_UMOUNT, CONFIG_NSH_DISABLE_UNSET, CONFIG_NSH_DISABLE_URLDECODE, + CONFIG_NSH_DISABLE_URLENCODE, CONFIG_NSH_DISABLE_USLEEP, CONFIG_NSH_DISABLE_WGET, + CONFIG_NSH_DISABLE_XD Verbose help output can be suppressed by defining CONFIG_NSH_HELP_TERSE. In that case, the help command is still available but will be slightly smaller. diff --git a/apps/nshlib/nsh.h b/apps/nshlib/nsh.h index 9f36b1d1f0..ac75cf2e1d 100644 --- a/apps/nshlib/nsh.h +++ b/apps/nshlib/nsh.h @@ -267,9 +267,35 @@ # undef CONFIG_NSH_ROMFSSECTSIZE #endif -/* This is the maximum number of arguments that will be accepted for a command */ +/* This is the maximum number of arguments that will be accepted for a + * command. Here we attempt to select the smallest number possible depending + * upon the of commands that are available. Most commands use six or fewer + * arguments, but there are a few that require more. + * + * This value is also configurable with CONFIG_NSH_MAXARGUMENTS. This + * configurability is necessary since there may also be external, "built-in" + * commands that require more commands than NSH is aware of. + */ -#define NSH_MAX_ARGUMENTS 6 +#ifndef CONFIG_NSH_MAXARGUMENTS +# define CONFIG_NSH_MAXARGUMENTS 6 +#endif + +#if CONFIG_NSH_MAXARGUMENTS < 11 +# if defined(CONFIG_NET) && !defined(CONFIG_NSH_DISABLE_IFCONFIG) +# undef CONFIG_NSH_MAXARGUMENTS +# define CONFIG_NSH_MAXARGUMENTS 11 +# endif +#endif + +#if CONFIG_NSH_MAXARGUMENTS < 7 +# if defined(CONFIG_NET_UDP) && CONFIG_NFILE_DESCRIPTORS > 0 +# if !defined(CONFIG_NSH_DISABLE_GET) || !defined(CONFIG_NSH_DISABLE_PUT) +# undef CONFIG_NSH_MAXARGUMENTS +# define CONFIG_NSH_MAXARGUMENTS 7 +# endif +# endif +#endif /* strerror() produces much nicer output but is, however, quite large and * will only be used if CONFIG_NSH_STRERROR is defined. Note that the strerror @@ -602,6 +628,10 @@ void nsh_usbtrace(void); # ifndef CONFIG_NSH_DISABLE_IFCONFIG int cmd_ifconfig(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); # endif +# ifndef CONFIG_NSH_DISABLE_IFUPDOWN + int cmd_ifup(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); + int cmd_ifdown(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); +# endif #if defined(CONFIG_NET_UDP) && CONFIG_NFILE_DESCRIPTORS > 0 # ifndef CONFIG_NSH_DISABLE_GET int cmd_get(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); diff --git a/apps/nshlib/nsh_netcmds.c b/apps/nshlib/nsh_netcmds.c index f3457a809d..d28fe873d0 100644 --- a/apps/nshlib/nsh_netcmds.c +++ b/apps/nshlib/nsh_netcmds.c @@ -277,14 +277,34 @@ int ifconfig_callback(FAR struct uip_driver_s *dev, void *arg) { struct nsh_vtbl_s *vtbl = (struct nsh_vtbl_s*)arg; struct in_addr addr; + bool is_running = false; + int ret; + + ret = uip_getifstatus(dev->d_ifname,&is_running); + if (ret != OK) + { + nsh_output(vtbl, "\tGet %s interface flags error: %d\n", + dev->d_ifname, ret); + } + + nsh_output(vtbl, "%s\tHWaddr %s at %s\n", + dev->d_ifname, ether_ntoa(&dev->d_mac), (is_running)?"UP":"DOWN"); - nsh_output(vtbl, "%s\tHWaddr %s\n", dev->d_ifname, ether_ntoa(&dev->d_mac)); addr.s_addr = dev->d_ipaddr; nsh_output(vtbl, "\tIPaddr:%s ", inet_ntoa(addr)); + addr.s_addr = dev->d_draddr; nsh_output(vtbl, "DRaddr:%s ", inet_ntoa(addr)); + addr.s_addr = dev->d_netmask; - nsh_output(vtbl, "Mask:%s\n\n", inet_ntoa(addr)); + nsh_output(vtbl, "Mask:%s\n", inet_ntoa(addr)); + +#if defined(CONFIG_NSH_DHCPC) || defined(CONFIG_NSH_DNS) + resolv_getserver(&addr); + nsh_output(vtbl, "\tDNSaddr:%s\n", inet_ntoa(addr)); +#endif + + nsh_output(vtbl, "\n"); return OK; } @@ -483,6 +503,54 @@ int cmd_get(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) #endif #endif +/**************************************************************************** + * Name: cmd_ifup + ****************************************************************************/ + +#ifndef CONFIG_NSH_DISABLE_IFUPDOWN +int cmd_ifup(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + FAR char *intf = NULL; + int ret; + + if (argc != 2) + { + nsh_output(vtbl, "Please select nic_name:\n"); + netdev_foreach(ifconfig_callback, vtbl); + return OK; + } + + intf = argv[1]; + ret = uip_ifup(intf); + nsh_output(vtbl, "ifup %s...%s\n", intf, (ret == OK) ? "OK" : "Failed"); + return ret; +} +#endif + +/**************************************************************************** + * Name: cmd_ifdown + ****************************************************************************/ + +#ifndef CONFIG_NSH_DISABLE_IFUPDOWN +int cmd_ifdown(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + FAR char *intf = NULL; + int ret; + + if (argc != 2) + { + nsh_output(vtbl, "Please select nic_name:\n"); + netdev_foreach(ifconfig_callback, vtbl); + return OK; + } + + intf = argv[1]; + ret = uip_ifdown(intf); + nsh_output(vtbl, "ifdown %s...%s\n", intf, (ret == OK) ? "OK" : "Failed"); + return ret; +} +#endif + /**************************************************************************** * Name: cmd_ifconfig ****************************************************************************/ @@ -491,7 +559,17 @@ int cmd_get(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) int cmd_ifconfig(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) { struct in_addr addr; - in_addr_t ip; + in_addr_t gip; + int i; + FAR char *intf = NULL; + FAR char *hostip = NULL; + FAR char *gwip = NULL; + FAR char *mask = NULL; + FAR char *tmp = NULL; + FAR char *hw = NULL; + FAR char *dns = NULL; + bool badarg=false; + uint8_t mac[6]; /* With one or no arguments, ifconfig simply shows the status of ethernet * device: @@ -513,24 +591,142 @@ int cmd_ifconfig(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) * ifconfig nic_name ip_address */ + if (argc > 2) + { + for(i = 0; i < argc; i++) + { + if (i == 1) + { + intf = argv[i]; + } + else if (i == 2) + { + hostip = argv[i]; + } + else + { + tmp = argv[i]; + if (!strcmp(tmp, "dr") || !strcmp(tmp, "gw") || !strcmp(tmp, "gateway")) + { + if (argc-1 >= i+1) + { + gwip = argv[i+1]; + i++; + } + else + { + badarg = true; + } + } + else if(!strcmp(tmp, "netmask")) + { + if (argc-1 >= i+1) + { + mask = argv[i+1]; + i++; + } + else + { + badarg = true; + } + } + else if(!strcmp(tmp, "hw")) + { + if (argc-1>=i+1) + { + hw = argv[i+1]; + i++; + badarg = !uiplib_hwmacconv(hw, mac); + } + else + { + badarg = true; + } + } + else if(!strcmp(tmp, "dns")) + { + if (argc-1 >= i+1) + { + dns = argv[i+1]; + i++; + } + else + { + badarg = true; + } + } + } + } + } + + if (badarg) + { + nsh_output(vtbl, g_fmtargrequired, argv[0]); + return ERROR; + } + + /* Set Hardware ethernet MAC addr */ + + if (hw) + { + ndbg("HW MAC: %s\n", hw); + uip_setmacaddr(intf, mac); + } + /* Set host ip address */ - ip = addr.s_addr = inet_addr(argv[2]); - uip_sethostaddr(argv[1], &addr); + ndbg("Host IP: %s\n", hostip); + gip = addr.s_addr = inet_addr(hostip); + uip_sethostaddr(intf, &addr); /* Set gateway */ - ip = NTOHL(ip); - ip &= ~0x000000ff; - ip |= 0x00000001; + if (gwip) + { + ndbg("Gateway: %s\n", gwip); + gip = addr.s_addr = inet_addr(gwip); + } + else + { + ndbg("Gateway: default\n"); + gip = NTOHL(gip); + gip &= ~0x000000ff; + gip |= 0x00000001; + gip = HTONL(gip); + addr.s_addr = gip; + } - addr.s_addr = HTONL(ip); - uip_setdraddr(argv[1], &addr); + uip_setdraddr(intf, &addr); - /* Set netmask */ + /* Set network mask */ - addr.s_addr = inet_addr("255.255.255.0"); - uip_setnetmask(argv[1], &addr); + if (mask) + { + ndbg("Netmask: %s\n",mask); + addr.s_addr = inet_addr(mask); + } + else + { + ndbg("Netmask: Default\n"); + addr.s_addr = inet_addr("255.255.255.0"); + } + + uip_setnetmask(intf, &addr); + +#if defined(CONFIG_NSH_DHCPC) || defined(CONFIG_NSH_DNS) + if (dns) + { + ndbg("DNS: %s\n", dns); + addr.s_addr = inet_addr(dns); + } + else + { + ndbg("DNS: Default\n"); + addr.s_addr = gip; + } + + resolv_conf(&addr); +#endif return OK; } diff --git a/apps/nshlib/nsh_parse.c b/apps/nshlib/nsh_parse.c index f9642809fc..bf2b8a4a47 100644 --- a/apps/nshlib/nsh_parse.c +++ b/apps/nshlib/nsh_parse.c @@ -73,19 +73,19 @@ /* Argument list size * * argv[0]: The command name. - * argv[1]: The beginning of argument (up to NSH_MAX_ARGUMENTS) + * argv[1]: The beginning of argument (up to CONFIG_NSH_MAXARGUMENTS) * argv[argc-3]: Possibly '>' or '>>' * argv[argc-2]: Possibly * argv[argc-1]: Possibly '&' (if pthreads are enabled) * argv[argc]: NULL terminating pointer * - * Maximum size is NSH_MAX_ARGUMENTS+5 + * Maximum size is CONFIG_NSH_MAXARGUMENTS+5 */ #ifndef CONFIG_NSH_DISABLEBG -# define MAX_ARGV_ENTRIES (NSH_MAX_ARGUMENTS+5) +# define MAX_ARGV_ENTRIES (CONFIG_NSH_MAXARGUMENTS+5) #else -# define MAX_ARGV_ENTRIES (NSH_MAX_ARGUMENTS+4) +# define MAX_ARGV_ENTRIES (CONFIG_NSH_MAXARGUMENTS+4) #endif /* Help command summary layout */ @@ -146,7 +146,7 @@ static const char g_failure[] = "1"; static const struct cmdmap_s g_cmdmap[] = { #if !defined(CONFIG_NSH_DISABLESCRIPT) && !defined(CONFIG_NSH_DISABLE_TEST) - { "[", cmd_lbracket, 4, NSH_MAX_ARGUMENTS, " ]" }, + { "[", cmd_lbracket, 4, CONFIG_NSH_MAXARGUMENTS, " ]" }, #endif #ifndef CONFIG_NSH_DISABLE_HELP @@ -164,7 +164,7 @@ static const struct cmdmap_s g_cmdmap[] = #if CONFIG_NFILE_DESCRIPTORS > 0 # ifndef CONFIG_NSH_DISABLE_CAT - { "cat", cmd_cat, 2, NSH_MAX_ARGUMENTS, " [ [ ...]]" }, + { "cat", cmd_cat, 2, CONFIG_NSH_MAXARGUMENTS, " [ [ ...]]" }, # endif #ifndef CONFIG_DISABLE_ENVIRON # ifndef CONFIG_NSH_DISABLE_CD @@ -196,9 +196,9 @@ static const struct cmdmap_s g_cmdmap[] = #ifndef CONFIG_NSH_DISABLE_ECHO # ifndef CONFIG_DISABLE_ENVIRON - { "echo", cmd_echo, 0, NSH_MAX_ARGUMENTS, "[ [...]]" }, + { "echo", cmd_echo, 0, CONFIG_NSH_MAXARGUMENTS, "[ [...]]" }, # else - { "echo", cmd_echo, 0, NSH_MAX_ARGUMENTS, "[ [...]]" }, + { "echo", cmd_echo, 0, CONFIG_NSH_MAXARGUMENTS, "[ [...]]" }, # endif #endif @@ -229,7 +229,11 @@ static const struct cmdmap_s g_cmdmap[] = #ifdef CONFIG_NET # ifndef CONFIG_NSH_DISABLE_IFCONFIG - { "ifconfig", cmd_ifconfig, 1, 3, "[nic_name [ip]]" }, + { "ifconfig", cmd_ifconfig, 1, 11, "[nic_name [ip]] [dr|gw|gateway ] [netmask ] [dns ] [hw ]" }, +# endif +# ifndef CONFIG_NSH_DISABLE_IFUPDOWN + { "ifdown", cmd_ifdown, 2, 2, "" }, + { "ifup", cmd_ifup, 2, 2, "" }, # endif #endif @@ -363,7 +367,7 @@ static const struct cmdmap_s g_cmdmap[] = #endif #if !defined(CONFIG_NSH_DISABLESCRIPT) && !defined(CONFIG_NSH_DISABLE_TEST) - { "test", cmd_test, 3, NSH_MAX_ARGUMENTS, "" }, + { "test", cmd_test, 3, CONFIG_NSH_MAXARGUMENTS, "" }, #endif #if !defined(CONFIG_DISABLE_MOUNTPOINT) && CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_FS_READABLE) @@ -736,7 +740,7 @@ static int nsh_execute(FAR struct nsh_vtbl_s *vtbl, int argc, char *argv[]) * * argv[0]: The command name. This is argv[0] when the arguments * are, finally, received by the command vtblr - * argv[1]: The beginning of argument (up to NSH_MAX_ARGUMENTS) + * argv[1]: The beginning of argument (up to CONFIG_NSH_MAXARGUMENTS) * argv[argc]: NULL terminating pointer */ @@ -1343,13 +1347,13 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline) * of argv is: * * argv[0]: The command name. - * argv[1]: The beginning of argument (up to NSH_MAX_ARGUMENTS) + * argv[1]: The beginning of argument (up to CONFIG_NSH_MAXARGUMENTS) * argv[argc-3]: Possibly '>' or '>>' * argv[argc-2]: Possibly * argv[argc-1]: Possibly '&' * argv[argc]: NULL terminating pointer * - * Maximum size is NSH_MAX_ARGUMENTS+5 + * Maximum size is CONFIG_NSH_MAXARGUMENTS+5 */ argv[0] = cmd; @@ -1423,7 +1427,7 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline) /* Check if the maximum number of arguments was exceeded */ - if (argc > NSH_MAX_ARGUMENTS) + if (argc > CONFIG_NSH_MAXARGUMENTS) { nsh_output(vtbl, g_fmttoomanyargs, cmd); } diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 3b60fc8128..f4bdc7ed01 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3564,4 +3564,6 @@ * RGMP 4.0 updated from Qiany Yu. * configs/*/Make.defs and configs/*/ld.script: Massive clean-up and standardization of linker scripts from Freddie Chopin. + * net/netdev_ioctl.c: Add interface state flags and ioctl calls + to bring network interfaces up and down (from Darcy Gong). diff --git a/nuttx/Documentation/NuttShell.html b/nuttx/Documentation/NuttShell.html index f8ef41fb96..31546a100c 100644 --- a/nuttx/Documentation/NuttShell.html +++ b/nuttx/Documentation/NuttShell.html @@ -8,7 +8,7 @@

    NuttShell (NSH)

    -

    Last Updated: October 31, 2012

    +

    Last Updated: November 4, 2012

    @@ -173,175 +173,187 @@
    - 2.16 Show Network Configuration (ifconfig) + 2.16 Manage Network Configuration (ifconfig)
    - 2.17 Send a signal to a task (kill) + 2.17 Take a network down (ifdown)
    - 2.18 Setup/teardown the Loop Device (losetup) + 2.18 Bring a network up (ifup)
    - 2.19 List Directory Contents (ls) + 2.19 Send a signal to a task (kill)
    - 2.20 Calculate MD5 (md5) + 2.20 Setup/teardown the Loop Device (losetup)
    - 2.21 Access Memory (mb, mh, and mw) + 2.21 List Directory Contents (ls)
    - 2.22 Show Current Tasks and Threads (ps) + 2.22 Calculate MD5 (md5)
    - 2.23 Create a Directory (mkdir) + 2.23 Access Memory (mb, mh, and mw)
    - 2.24 Create a FAT Filesystem (mkfatfs) + 2.24 Show Current Tasks and Threads (ps)
    - 2.25 Create a FIFO (mkfifo) + 2.25 Create a Directory (mkdir)
    - 2.26 Create a RAMDISK (mkrd) + 2.26 Create a FAT Filesystem (mkfatfs)
    - 2.27 Mount a File System (mount) + 2.27 Create a FIFO (mkfifo)
    - 2.28 Rename a File (mv) + 2.28 Create a RAMDISK (mkrd)
    - 2.29 Mount an NFS file system (nfsmount) + 2.29 Mount a File System (mount)
    - 2.30 Check Network Peer (ping) + 2.30 Rename a File (mv)
    - 2.31 Send File Via TFTP (put) + 2.31 Mount an NFS file system (nfsmount)
    - 2.32 Show Current Working Directory (pwd) + 2.32 Check Network Peer (ping)
    - 2.33 Remove a File (rm) + 2.33 Send File Via TFTP (put)
    - 2.34 Remove a Directory (rmdir) + 2.34 Show Current Working Directory (pwd)
    - 2.35 Set an Environment Variable (set) + 2.35 Remove a File (rm)
    - 2.36 Execute an NSH Script (sh) + 2.36 Remove a Directory (rmdir)
    - 2.37 Wait for Seconds (sleep) + 2.37 Set an Environment Variable (set)
    - 2.38 Unmount a File System (umount) + 2.38 Execute an NSH Script (sh)
    - 2.39 Unset an Environment Variable (unset) + 2.39 Wait for Seconds (sleep)
    - 2.40 URL Decode (urldecode) + 2.40 Unmount a File System (umount)
    - 2.41 URL Encode (urlencode) + 2.41 Unset an Environment Variable (unset)
    - 2.42 Wait for Microseconds (usleep) + 2.42 URL Decode (urldecode)
    - 2.43 Get File Via HTTP (wget) + 2.43 URL Encode (urlencode)
    - 2.44 Hexadecimal Dump (xd) + 2.44 Wait for Microseconds (usleep) + + + +
    + + 2.45 Get File Via HTTP (wget) + + + +
    + + 2.46 Hexadecimal Dump (xd) @@ -1170,18 +1182,18 @@ help [-v] [<cmd>]
    -

    2.16 Show Network Configuration (ifconfig)

    +

    2.16 Manage Network Configuration (ifconfig)

    Command Syntax:

      -ifconfig [nic_name [ip_address]]
      +ifconfig [nic_name [ip]] [dr|gw|gateway <dr-address>] [netmask <net-mask>] [dns <dns-address>] [hw <hw-mac>]]
       

    Synopsis. - Two forms of the ifconfigcommand are supported: + Multiple forms of the ifconfigcommand are supported:

    1. @@ -1214,14 +1226,63 @@ eth0 HWaddr 00:18:11:80:10:06

         ifconfig nic_name ip_address
        -
          +
        + +
      • + Other forms to be provided
    + +
    -

    2.17 Send a signal to a task (kill)

    +

    2.17 Take a network down (ifdown)

    +
    + +

    Command Syntax:

    +
      +ifdown <nic-name>
      +
    +

    + Synopsis. + Take down the interface identified by the name <nic-name>. +

    +

    + Example: +

    +
      +ifdown eth0
      +
    + + + + + +
    +

    2.18 Bring a network up (ifup)

    +
    + +

    Command Syntax:

    +
      +ifup <nic-name>
      +
    +

    + Synopsis. + Bring up down the interface identified by the name <nic-name>. +

    +

    + Example: +

    +
      +ifup eth0
      +
    + + + +
    +

    2.19 Send a signal to a task (kill)

    @@ -1262,7 +1323,7 @@ nsh>
    -

    2.18 Setup/teardown the Loop Device (losetup)

    +

    2.20 Setup/teardown the Loop Device (losetup)

    @@ -1315,7 +1376,7 @@ losetup d <dev-path>
    -

    2.19 List Directory Contents (ls)

    +

    2.21 List Directory Contents (ls)

    @@ -1352,7 +1413,7 @@ ls [-lRs] <dir-path>
    -

    2.20 Calculate MD5 (md5)

    +

    2.22 Calculate MD5 (md5)

    @@ -1369,7 +1430,7 @@ md5 [-f] <string or filepath>
    -

    2.21 Access Memory (mb, mh, and mw)

    +

    2.23 Access Memory (mb, mh, and mw)

    @@ -1423,7 +1484,7 @@ nsh>
    -

    2.22 Show Current Tasks and Threads (ps)

    +

    2.24 Show Current Tasks and Threads (ps)

    @@ -1449,7 +1510,7 @@ nsh>
    -

    2.23 Create a Directory (mkdir)

    +

    2.25 Create a Directory (mkdir)

    @@ -1484,7 +1545,7 @@ nsh>
    -

    2.24 Create a FAT Filesystem (mkfatfs)

    +

    2.26 Create a FAT Filesystem (mkfatfs)

    @@ -1504,7 +1565,7 @@ mkfatfs <path>
    -

    2.25 Create a FIFO (mkfifo)

    +

    2.27 Create a FIFO (mkfifo)

    @@ -1542,7 +1603,7 @@ nsh>
    -

    2.26 Create a RAMDISK (mkrd)

    +

    2.28 Create a RAMDISK (mkrd)

    @@ -1593,7 +1654,7 @@ nsh>
    -

    2.27 Mount a File System (mount)

    +

    2.29 Mount a File System (mount)

    @@ -1672,7 +1733,7 @@ nsh> mount
    -

    2.28 Rename a File (mv)

    +

    2.30 Rename a File (mv)

    @@ -1690,7 +1751,7 @@ mv <old-path> <new-path>
    -

    2.29 Mount an NFS file system (nfsmount)

    +

    2.31 Mount an NFS file system (nfsmount)

    @@ -1709,7 +1770,7 @@ nfsmount <server-address> <mount-point> <remote-path>
    -

    2.30 Check Network Peer (ping)

    +

    2.32 Check Network Peer (ping)

    @@ -1742,7 +1803,7 @@ nsh>
    -

    2.31 Send File Via TFTP (put)

    +

    2.33 Send File Via TFTP (put)

    @@ -1777,7 +1838,7 @@ put [-b|-n] [-f <remote-path>] -h <ip-address> <local-path>
    -

    2.32 Show Current Working Directory (pwd)

    +

    2.34 Show Current Working Directory (pwd)

    @@ -1807,7 +1868,7 @@ nsh>
    -

    2.33 Remove a File (rm)

    +

    2.35 Remove a File (rm)

    @@ -1841,7 +1902,7 @@ nsh>
    -

    2.34 Remove a Directory (rmdir)

    +

    2.36 Remove a Directory (rmdir)

    @@ -1876,7 +1937,7 @@ nsh>
    -

    2.35 Set an Environment Variable (set)

    +

    2.37 Set an Environment Variable (set)

    @@ -1902,7 +1963,7 @@ nsh>
    -

    2.36 Execute an NSH Script (sh)

    +

    2.38 Execute an NSH Script (sh)

    @@ -1920,7 +1981,7 @@ sh <script-path>
    -

    2.37 Wait for Seconds (sleep)

    +

    2.39 Wait for Seconds (sleep)

    @@ -1937,7 +1998,7 @@ sleep <sec>
    -

    2.38 Unmount a File System (umount)

    +

    2.40 Unmount a File System (umount)

    @@ -1967,7 +2028,7 @@ nsh>
    -

    2.39 Unset an Environment Variable (unset)

    +

    2.41 Unset an Environment Variable (unset)

    @@ -1993,7 +2054,7 @@ nsh>
    -

    2.40 URL Decode (urldecode)

    +

    2.42 URL Decode (urldecode)

    @@ -2010,7 +2071,7 @@ urldecode [-f] <string or filepath>
    -

    2.41 URL Encode (urlencode)

    +

    2.43 URL Encode (urlencode)

    @@ -2027,7 +2088,7 @@ urlencode [-f] <string or filepath>
    -

    2.42 Wait for Microseconds (usleep)

    +

    2.44 Wait for Microseconds (usleep)

    @@ -2044,7 +2105,7 @@ usleep <usec>
    - 2.43 Get File Via HTTP (wget) + 2.45 Get File Via HTTP (wget)
    @@ -2071,7 +2132,7 @@ wget [-o <local-path>] <url>
    -

    2.44 Hexadecimal dump (xd)

    +

    2.46 Hexadecimal dump (xd)

    @@ -2215,6 +2276,16 @@ nsh> CONFIG_NET CONFIG_NSH_DISABLE_IFCONFIG + + ifdown + CONFIG_NET + CONFIG_NSH_DISABLE_IFUPDOWN + + + ifup + CONFIG_NET + CONFIG_NSH_DISABLE_IFUPDOWN + kill !CONFIG_DISABLE_SIGNALS @@ -3723,9 +3794,9 @@ mount -t vfat /dev/ram1 /tmp
  • /etc/init.d/rcS
  • exec
  • exec_namedapp()
  • +
  • exit
  • -
  • exit
  • free
  • g_cmdmap
  • genromfs
  • @@ -3734,6 +3805,8 @@ mount -t vfat /dev/ram1 /tmp
  • help
  • if-then[-else]-fi
  • ifconfig
  • +
  • ifdown
  • +
  • ifup
  • Initialization sequence
  • kill
  • losetup
  • diff --git a/nuttx/include/net/if.h b/nuttx/include/net/if.h index e64b58563f..1ff8ebc383 100644 --- a/nuttx/include/net/if.h +++ b/nuttx/include/net/if.h @@ -52,6 +52,10 @@ #define IF_NAMESIZE 6 /* Newer naming standard */ #define IFHWADDRLEN 6 +#define IFF_RUNNING (1 << 0) +#define IF_FLAG_IFUP (1 << 0) +#define IF_FLAG_IFDOWN (2 << 0) + /******************************************************************************************* * Public Type Definitions *******************************************************************************************/ @@ -72,6 +76,7 @@ struct lifreq struct sockaddr lifru_hwaddr; /* MAC address */ int lifru_count; /* Number of devices */ int lifru_mtu; /* MTU size */ + uint8_t lifru_flags; /* Interface flags */ } lifr_ifru; }; @@ -82,6 +87,7 @@ struct lifreq #define lifr_hwaddr lifr_ifru.lifru_hwaddr /* MAC address */ #define lifr_mtu lifr_ifru.lifru_mtu /* MTU */ #define lifr_count lifr_ifru.lifru_count /* Number of devices */ +#define lifr_flags lifr_ifru.lifru_flags /* interface flags */ /* This is the older I/F request that should only be used with IPv4. However, since * NuttX only supports IPv4 or 6 (not both), we can force the older structure to @@ -101,6 +107,7 @@ struct ifreq struct sockaddr ifru_hwaddr; /* MAC address */ int ifru_count; /* Number of devices */ int ifru_mtu; /* MTU size */ + uint8_t ifru_flags; /* Interface flags */ } ifr_ifru; }; @@ -111,6 +118,7 @@ struct ifreq #define ifr_hwaddr ifr_ifru.ifru_hwaddr /* MAC address */ #define ifr_mtu ifr_ifru.ifru_mtu /* MTU */ #define ifr_count ifr_ifru.ifru_count /* Number of devices */ +#define ifr_flags ifr_ifru.ifru_flags /* interface flags */ #else /* CONFIG_NET_IPv6 */ @@ -123,6 +131,7 @@ struct ifreq #define ifr_hwaddr lifr_ifru.lifru_hwaddr /* MAC address */ #define ifr_mtu lifr_ifru.lifru_mtu /* MTU */ #define ifr_count lifr_ifru.lifru_count /* Number of devices */ +#define ifr_flags lifr_ifru.lifru_flags /* interface flags */ #endif /* CONFIG_NET_IPv6 */ diff --git a/nuttx/include/nuttx/net/ioctl.h b/nuttx/include/nuttx/net/ioctl.h index be3f597f47..d5d1a001c8 100644 --- a/nuttx/include/nuttx/net/ioctl.h +++ b/nuttx/include/nuttx/net/ioctl.h @@ -146,9 +146,15 @@ #define SIOCSIWPMKSA _SIOC(0x0036) /* PMKSA cache operation */ +/* Interface flags */ + +#define SIOCSIFFLAGS _SIOC(0x0037) /* Sets the interface flags */ +#define SIOCGIFFLAGS _SIOC(0x0038) /* Gets the interface flags */ + /**************************************************************************** * Type Definitions ****************************************************************************/ + /* See include/net/if.h */ /**************************************************************************** diff --git a/nuttx/include/nuttx/net/uip/uip-arch.h b/nuttx/include/nuttx/net/uip/uip-arch.h index 9546de04eb..73805c6fb1 100644 --- a/nuttx/include/nuttx/net/uip/uip-arch.h +++ b/nuttx/include/nuttx/net/uip/uip-arch.h @@ -90,6 +90,10 @@ struct uip_driver_s char d_ifname[IFNAMSIZ]; #endif + /* Drivers interface flags. See IFF_* definitions in include/net/if.h */ + + uint8_t d_flags; + /* Ethernet device identity */ #ifdef CONFIG_NET_ETHERNET diff --git a/nuttx/net/netdev_ioctl.c b/nuttx/net/netdev_ioctl.c index 4b5876efa0..ea5c0e4362 100644 --- a/nuttx/net/netdev_ioctl.c +++ b/nuttx/net/netdev_ioctl.c @@ -138,19 +138,47 @@ static void ioctl_setipaddr(FAR uip_ipaddr_t *outaddr, FAR const void *inaddr) * ****************************************************************************/ -static inline void ioctl_ifup(FAR struct uip_driver_s *dev) +static void ioctl_ifup(FAR struct uip_driver_s *dev) { + /* Make sure that the device supports the d_ifup() method */ + if (dev->d_ifup) { - dev->d_ifup(dev); + /* Is the interface already up? */ + + if ((dev->d_flags & IFF_RUNNING) == 0) + { + /* No, bring the interface up now */ + + if (dev->d_ifup(dev) == OK) + { + /* Mark the interface as up */ + + dev->d_flags |= IFF_RUNNING; + } + } } } -static inline void ioctl_ifdown(FAR struct uip_driver_s *dev) +static void ioctl_ifdown(FAR struct uip_driver_s *dev) { + /* Make sure that the device supports the d_ifdown() method */ + if (dev->d_ifdown) { - dev->d_ifdown(dev); + /* Is the interface already down? */ + + if ((dev->d_flags & IFF_RUNNING) != 0) + { + /* No, take the interface down now */ + + if (dev->d_ifdown(dev) == OK) + { + /* Mark the interface as down */ + + dev->d_flags &= ~IFF_RUNNING; + } + } } } @@ -194,63 +222,130 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, struct ifreq *req) switch (cmd) { - case SIOCGIFADDR: /* Get IP address */ - ioctl_getipaddr(&req->ifr_addr, &dev->d_ipaddr); + case SIOCGIFADDR: /* Get IP address */ + { + ioctl_getipaddr(&req->ifr_addr, &dev->d_ipaddr); + } break; - case SIOCSIFADDR: /* Set IP address */ - ioctl_ifdown(dev); - ioctl_setipaddr(&dev->d_ipaddr, &req->ifr_addr); - ioctl_ifup(dev); + case SIOCSIFADDR: /* Set IP address */ + { + ioctl_ifdown(dev); + ioctl_setipaddr(&dev->d_ipaddr, &req->ifr_addr); + ioctl_ifup(dev); + } break; case SIOCGIFDSTADDR: /* Get P-to-P address */ - ioctl_getipaddr(&req->ifr_dstaddr, &dev->d_draddr); + { + ioctl_getipaddr(&req->ifr_dstaddr, &dev->d_draddr); + } break; case SIOCSIFDSTADDR: /* Set P-to-P address */ - ioctl_setipaddr(&dev->d_draddr, &req->ifr_dstaddr); + { + ioctl_setipaddr(&dev->d_draddr, &req->ifr_dstaddr); + } break; case SIOCGIFNETMASK: /* Get network mask */ - ioctl_getipaddr(&req->ifr_addr, &dev->d_netmask); + { + ioctl_getipaddr(&req->ifr_addr, &dev->d_netmask); + } break; case SIOCSIFNETMASK: /* Set network mask */ - ioctl_setipaddr(&dev->d_netmask, &req->ifr_addr); + { + ioctl_setipaddr(&dev->d_netmask, &req->ifr_addr); + } break; case SIOCGIFMTU: /* Get MTU size */ - req->ifr_mtu = CONFIG_NET_BUFSIZE; + { + req->ifr_mtu = CONFIG_NET_BUFSIZE; + } + break; + + case SIOCSIFFLAGS: /* Sets the interface flags */ + { + /* Is this a request to bring the interface up? */ + + if (req->ifr_flags & IF_FLAG_IFUP) + { + /* Yes.. bring the interface up */ + + ioctl_ifup(dev); + } + + /* Is this a request to take the interface down? */ + + else if (req->ifr_flags & IF_FLAG_IFDOWN) + { + /* Yes.. take the interface down */ + + ioctl_ifdown(dev); + } + } + break; + + case SIOCGIFFLAGS: /* Gets the interface flags */ + { + req->ifr_flags = 0; + + /* Is the interface running? */ + + if (dev->d_flags & IFF_RUNNING) + { + /* Yes.. report interface up */ + + req->ifr_flags |= IF_FLAG_IFUP; + } + else + { + /* No.. report interface down */ + + req->ifr_flags |= IF_FLAG_IFDOWN; + } + } break; /* MAC address operations only make sense if Ethernet is supported */ #ifdef CONFIG_NET_ETHERNET case SIOCGIFHWADDR: /* Get hardware address */ - req->ifr_hwaddr.sa_family = AF_INETX; - memcpy(req->ifr_hwaddr.sa_data, dev->d_mac.ether_addr_octet, IFHWADDRLEN); + { + req->ifr_hwaddr.sa_family = AF_INETX; + memcpy(req->ifr_hwaddr.sa_data, dev->d_mac.ether_addr_octet, IFHWADDRLEN); + } break; case SIOCSIFHWADDR: /* Set hardware address -- will not take effect until ifup */ - req->ifr_hwaddr.sa_family = AF_INETX; - memcpy(dev->d_mac.ether_addr_octet, req->ifr_hwaddr.sa_data, IFHWADDRLEN); + { + req->ifr_hwaddr.sa_family = AF_INETX; + memcpy(dev->d_mac.ether_addr_octet, req->ifr_hwaddr.sa_data, IFHWADDRLEN); + } break; #endif case SIOCDIFADDR: /* Delete IP address */ - ioctl_ifdown(dev); - memset(&dev->d_ipaddr, 0, sizeof(uip_ipaddr_t)); + { + ioctl_ifdown(dev); + memset(&dev->d_ipaddr, 0, sizeof(uip_ipaddr_t)); + } break; case SIOCGIFCOUNT: /* Get number of devices */ - req->ifr_count = netdev_count(); - ret = -ENOSYS; + { + req->ifr_count = netdev_count(); + ret = -ENOSYS; + } break; - case SIOCGIFBRDADDR: /* Get broadcast IP address */ - case SIOCSIFBRDADDR: /* Set broadcast IP address */ - ret = -ENOSYS; + case SIOCGIFBRDADDR: /* Get broadcast IP address */ + case SIOCSIFBRDADDR: /* Set broadcast IP address */ + { + ret = -ENOSYS; + } break; #ifdef CONFIG_NET_ARPIOCTLS @@ -261,7 +356,9 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, struct ifreq *req) #endif default: - ret = -EINVAL; + { + ret = -EINVAL; + } break;; } From 396d6787a7bb0532a7c21b3a5482054e664a9bc4 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 4 Nov 2012 19:12:12 +0000 Subject: [PATCH 078/206] Missed a few ld.script files in Freddie Chopin's last big change git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5309 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/kwikstik-k40/{ostest => scripts}/ld.script | 0 nuttx/configs/vsn/{nsh => scripts}/ld.script | 0 nuttx/configs/vsn/{nsh => scripts}/ld.script.dfu | 0 3 files changed, 0 insertions(+), 0 deletions(-) rename nuttx/configs/kwikstik-k40/{ostest => scripts}/ld.script (100%) rename nuttx/configs/vsn/{nsh => scripts}/ld.script (100%) rename nuttx/configs/vsn/{nsh => scripts}/ld.script.dfu (100%) diff --git a/nuttx/configs/kwikstik-k40/ostest/ld.script b/nuttx/configs/kwikstik-k40/scripts/ld.script similarity index 100% rename from nuttx/configs/kwikstik-k40/ostest/ld.script rename to nuttx/configs/kwikstik-k40/scripts/ld.script diff --git a/nuttx/configs/vsn/nsh/ld.script b/nuttx/configs/vsn/scripts/ld.script similarity index 100% rename from nuttx/configs/vsn/nsh/ld.script rename to nuttx/configs/vsn/scripts/ld.script diff --git a/nuttx/configs/vsn/nsh/ld.script.dfu b/nuttx/configs/vsn/scripts/ld.script.dfu similarity index 100% rename from nuttx/configs/vsn/nsh/ld.script.dfu rename to nuttx/configs/vsn/scripts/ld.script.dfu From bb96124a20a22f34eb8e6f35dbcdef10c5b84808 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 4 Nov 2012 20:29:04 +0000 Subject: [PATCH 079/206] Changes to get a clean build of apps/examples/cxxtest with the STM32 and uClibc++ git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5310 42af7a65-404d-4744-a932-0658087f49c3 --- misc/uClibc++/libxx/uClibc++/Make.defs | 3 +- nuttx/configs/sim/cxxtest/Make.defs | 2 +- nuttx/configs/stm32f4discovery/README.txt | 29 ++++++++++++++++++- .../stm32f4discovery/cxxtest/Make.defs | 2 +- nuttx/configs/twr-k60n512/scripts/ld.script | 2 +- 5 files changed, 33 insertions(+), 5 deletions(-) diff --git a/misc/uClibc++/libxx/uClibc++/Make.defs b/misc/uClibc++/libxx/uClibc++/Make.defs index 40aee6e473..cf2089f700 100644 --- a/misc/uClibc++/libxx/uClibc++/Make.defs +++ b/misc/uClibc++/libxx/uClibc++/Make.defs @@ -52,7 +52,8 @@ endif # libsupc++ replacement -# CXXSRCS += vterminate.C +CXXSRCS += vterminate.cxx + ifneq ($(CONFIG_UCLIBCXX_HAVE_LIBSUPCXX),y) CXXSRCS += eh_alloc.cxx eh_globals.cxx eh_terminate.cxx endif diff --git a/nuttx/configs/sim/cxxtest/Make.defs b/nuttx/configs/sim/cxxtest/Make.defs index 6f945cc519..9c7c3d46ba 100644 --- a/nuttx/configs/sim/cxxtest/Make.defs +++ b/nuttx/configs/sim/cxxtest/Make.defs @@ -93,7 +93,7 @@ LDLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(LD) CCLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(CC) LDFLAGS = $(ARCHSCRIPT) # For backward compatibility, same as CCLINKFLAGS -LIBSUPXX = ${shell $(CC) --print-file-name=libsupc++.a} +LIBSUPXX = ${shell $(CC) $(CXXFLAGS) --print-file-name=libsupc++.a} EXTRA_LIBPATHS = -L "${shell dirname "$(LIBSUPXX)"}" EXTRA_LIBS = -lsupc++ diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index 730bf66ef2..02fdbb07a0 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -1008,7 +1008,34 @@ Where is one of the following: b. Execute 'make menuconfig' in nuttx/ in order to start the reconfiguration process. - 3. At present (2012/11/02), this example builds only with exceptions + 3. Ideally, you should build with a toolchain based on GLIBC or + uClibc++. It you use a toolchain based on newlib, you may see + an error like the following: + + .../lib/libsupc++.a(vterminate.o): In function `__gnu_cxx::__verbose_terminate_handler()': + vterminate.cc:(....): undefined reference to `_impure_ptr' + + Here is a quick'n'dirty fix: + + 1. Get the directory where you can find libsupc++: + + arm-none-eabi-gcc -mcpu=cortex-m4 -mthumb -print-file-name=libsupc++.a + + 2. Go to that directory and save a copy of vterminate.o (in case you + want to restore it later: + + cd + arm-none-eabi-ar.exe -x libsupc++.a vterminate.o + + 3. Then remove vterminate.o from the library. At build time, the + uClibc++ package will provide a usable replacement vterminate.o. + + Now NuttX should link with no problem. If you want to restore the + vterminate.o that you removed from libsupc++, you can do that with: + + arm-none-eabi-ar.exe rcs libsupc++.a vterminate.o + + 4. At present (2012/11/02), this example builds only with exceptions disabled (CONFIG_UCLIBCXX_EXCEPTIONS=n). elf: diff --git a/nuttx/configs/stm32f4discovery/cxxtest/Make.defs b/nuttx/configs/stm32f4discovery/cxxtest/Make.defs index f81d6ec2c1..004643950b 100644 --- a/nuttx/configs/stm32f4discovery/cxxtest/Make.defs +++ b/nuttx/configs/stm32f4discovery/cxxtest/Make.defs @@ -114,7 +114,7 @@ ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gc ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} LDSCRIPT = ld.script -LIBSUPXX = ${shell $(CC) --print-file-name=libsupc++.a} +LIBSUPXX = ${shell $(CC) $(CXXFLAGS) --print-file-name=libsupc++.a} EXTRA_LIBPATHS = -L "${shell dirname "$(LIBSUPXX)"}" EXTRA_LIBS = -lsupc++ diff --git a/nuttx/configs/twr-k60n512/scripts/ld.script b/nuttx/configs/twr-k60n512/scripts/ld.script index 26410e6d86..34f1527eb9 100644 --- a/nuttx/configs/twr-k60n512/scripts/ld.script +++ b/nuttx/configs/twr-k60n512/scripts/ld.script @@ -1,4 +1,4 @@ - /**************************************************************************** +/**************************************************************************** * configs/twr-k60n512/scripts/ld.script * * Copyright (C) 2011 Gregory Nutt. All rights reserved. From 516633dcd78590b94595bacda8929628b3834357 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 4 Nov 2012 21:04:30 +0000 Subject: [PATCH 080/206] Change = to += in setting of LDFLAGS in all architecture Makefiles git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5311 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/8051/src/Makefile | 2 +- nuttx/arch/arm/src/Makefile | 2 +- nuttx/arch/avr/src/Makefile | 2 +- nuttx/arch/hc/src/Makefile | 2 +- nuttx/arch/mips/src/Makefile | 2 +- nuttx/arch/sh/src/Makefile | 2 +- nuttx/arch/x86/src/Makefile | 2 +- nuttx/arch/z16/src/Makefile | 2 +- nuttx/arch/z80/src/Makefile.zdsii | 2 +- 9 files changed, 9 insertions(+), 9 deletions(-) diff --git a/nuttx/arch/8051/src/Makefile b/nuttx/arch/8051/src/Makefile index fe1995fd04..83c796119f 100644 --- a/nuttx/arch/8051/src/Makefile +++ b/nuttx/arch/8051/src/Makefile @@ -72,7 +72,7 @@ BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board IRAM_SIZE = 0x100 DEF_STACK_BASE = 0x24 -LDFLAGS = --model-large --nostdlib \ +LDFLAGS += --model-large --nostdlib \ --data-loc $(DEF_STACK_BASE) --iram-size $(IRAM_SIZE) \ --code-loc 0x2100 --code-size 0x5f40 \ --xram-loc $(IRAM_SIZE) --xram-size 0x1f00 diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index 7bba7315fc..f356f4d02a 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -70,7 +70,7 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -LDFLAGS = $(ARCHSCRIPT) +LDFLAGS += $(ARCHSCRIPT) EXTRA_LIBS ?= EXTRA_LIBPATHS ?= diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile index b72a6c8a8d..bbfc4dd4f9 100644 --- a/nuttx/arch/avr/src/Makefile +++ b/nuttx/arch/avr/src/Makefile @@ -74,7 +74,7 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -LDFLAGS = $(ARCHSCRIPT) +LDFLAGS += $(ARCHSCRIPT) EXTRA_LIBS ?= LINKLIBS = diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile index 36fc9bf723..ff19ce6fe6 100644 --- a/nuttx/arch/hc/src/Makefile +++ b/nuttx/arch/hc/src/Makefile @@ -67,7 +67,7 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -LDFLAGS = $(ARCHSCRIPT) +LDFLAGS += $(ARCHSCRIPT) EXTRA_LIBS ?= LINKLIBS = diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile index 8d7b940c6f..8769f35eca 100644 --- a/nuttx/arch/mips/src/Makefile +++ b/nuttx/arch/mips/src/Makefile @@ -64,7 +64,7 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -LDFLAGS = $(ARCHSCRIPT) +LDFLAGS += $(ARCHSCRIPT) EXTRA_LIBS ?= LINKLIBS = diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile index 7ec8c9f80f..3008983966 100644 --- a/nuttx/arch/sh/src/Makefile +++ b/nuttx/arch/sh/src/Makefile @@ -50,7 +50,7 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -LDFLAGS = $(ARCHSCRIPT) +LDFLAGS += $(ARCHSCRIPT) EXTRA_LIBS ?= LINKLIBS = diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile index 9c35e98092..7225f31cf0 100644 --- a/nuttx/arch/x86/src/Makefile +++ b/nuttx/arch/x86/src/Makefile @@ -64,7 +64,7 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -LDFLAGS = $(ARCHSCRIPT) +LDFLAGS += $(ARCHSCRIPT) EXTRA_LIBS ?= LINKLIBS = diff --git a/nuttx/arch/z16/src/Makefile b/nuttx/arch/z16/src/Makefile index 40dc73c5e1..088aeebd2e 100644 --- a/nuttx/arch/z16/src/Makefile +++ b/nuttx/arch/z16/src/Makefile @@ -49,7 +49,7 @@ INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) CPPFLAGS += -I$(ARCHSRCDIR) ifeq ($(COMPILER),zneocc.exe) -LDFLAGS = @"${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}" +LDFLAGS += @"${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}" endif HEAD_ASRC = $(HEAD_SSRC:.S=$(ASMEXT)) diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii index a105597a92..e749bddd32 100644 --- a/nuttx/arch/z80/src/Makefile.zdsii +++ b/nuttx/arch/z80/src/Makefile.zdsii @@ -41,7 +41,7 @@ USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common' INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) CPPFLAGS += -I$(ARCHSRCDIR) -I$(ZDSSTDINCDIR) -I$(ZDSZILOGINCDIR) -LDFLAGS = @"${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}" +LDFLAGS += @"${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}" ############################################################################ # Files and directories From e67d8af63605388899f94ef3ecd281d259c8682b Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 5 Nov 2012 13:30:00 +0000 Subject: [PATCH 081/206] uClibc++ exceptions are working git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5312 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/sim/README.txt | 8 +++++--- nuttx/configs/stm32f4discovery/README.txt | 3 +-- nuttx/configs/stm32f4discovery/cxxtest/defconfig | 4 +++- 3 files changed, 9 insertions(+), 6 deletions(-) diff --git a/nuttx/configs/sim/README.txt b/nuttx/configs/sim/README.txt index 39ace5495e..c8bcb2cd7a 100644 --- a/nuttx/configs/sim/README.txt +++ b/nuttx/configs/sim/README.txt @@ -215,9 +215,11 @@ cxxtest b. Execute 'make menuconfig' in nuttx/ in order to start the reconfiguration process. - 3. At present (2012/11/02), this example builds only with exceptions - disabled (CONFIG_UCLIBCXX_EXCEPTIONS=n). And even then, it will - not run. + 3. At present (2012/11/02), exceptions are disabled in this example + CONFIG_UCLIBCXX_EXCEPTIONS=n). It is probably not necessary to + disable exceptions. + + 4. Unfortunately, this example will not run now. The reason that the example will not run on the simulator has to do with when static constructors are enabled: In the simulator diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index 02fdbb07a0..db423d65b4 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -1035,8 +1035,7 @@ Where is one of the following: arm-none-eabi-ar.exe rcs libsupc++.a vterminate.o - 4. At present (2012/11/02), this example builds only with exceptions - disabled (CONFIG_UCLIBCXX_EXCEPTIONS=n). + 4. Exceptions are enabled and workking (CONFIG_UCLIBCXX_EXCEPTIONS=y) elf: --- diff --git a/nuttx/configs/stm32f4discovery/cxxtest/defconfig b/nuttx/configs/stm32f4discovery/cxxtest/defconfig index 85b04c0ff9..6648d3b132 100644 --- a/nuttx/configs/stm32f4discovery/cxxtest/defconfig +++ b/nuttx/configs/stm32f4discovery/cxxtest/defconfig @@ -73,6 +73,8 @@ CONFIG_ARCH_CHIP_STM32=y CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARCH_FPU is not set CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARMV7M_MPU is not set @@ -414,7 +416,7 @@ CONFIG_HAVE_CXXINITIALIZE=y # uClibc++ Standard C++ Library # CONFIG_UCLIBCXX=y -# CONFIG_UCLIBCXX_EXCEPTION is not set +CONFIG_UCLIBCXX_EXCEPTION=y CONFIG_UCLIBCXX_IOSTREAM_BUFSIZE=32 CONFIG_UCLIBCXX_HAVE_LIBSUPCXX=y From 5d0999c8595e5b99f57ae62fd57c0def41539407 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 5 Nov 2012 15:42:58 +0000 Subject: [PATCH 082/206] Prep for 6.23 release git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5313 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 3 +- misc/buildroot/ChangeLog | 3 +- misc/buildroot/ReleaseNotes | 43 +- misc/uClibc++/ChangeLog.txt | 7 + misc/uClibc++/README.txt | 4 +- misc/uClibc++/ReleaseNotes.txt | 32 + misc/uClibc++/zipme.sh | 80 +++ nuttx/ChangeLog | 10 +- nuttx/Documentation/NuttX.html | 743 ++++++++-------------- nuttx/ReleaseNotes | 78 +++ nuttx/configs/stm32f4discovery/README.txt | 2 + 11 files changed, 506 insertions(+), 499 deletions(-) create mode 100644 misc/uClibc++/ChangeLog.txt create mode 100644 misc/uClibc++/ReleaseNotes.txt create mode 100755 misc/uClibc++/zipme.sh diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index cd1b4eb53a..8a168588bd 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -349,7 +349,7 @@ * 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 +6.23 2012-11-05 Gregory Nutt * vsn: Moved all NSH commands from vsn/ to system/. Deleted the vsn/ directory. @@ -406,3 +406,4 @@ supports setting IP addresses, network masks, name server addresses, and hardware address (from Darcy Gong). +6.24 2012-xx-xx Gregory Nutt diff --git a/misc/buildroot/ChangeLog b/misc/buildroot/ChangeLog index cdbef5da14..6b09b8b949 100644 --- a/misc/buildroot/ChangeLog +++ b/misc/buildroot/ChangeLog @@ -101,7 +101,7 @@ buildroot-1.10 2011-05-06 * configs/arm920t-eabi-defconfig-4.5.2 - Add a configuration to build a GCC 4.5.2 EABI ARM toolchain for the ARM920t. -buildroot-1.11 2011-xx-xx +buildroot-1.11 2011-11-05 * configs/avr-defconfig-4.3.3 - Added --enable-long-long as a GCC option. @@ -127,3 +127,4 @@ buildroot-1.11 2011-xx-xx 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. +buildroot-1.12 2011-xx-xx diff --git a/misc/buildroot/ReleaseNotes b/misc/buildroot/ReleaseNotes index 889b97073a..266354e631 100644 --- a/misc/buildroot/ReleaseNotes +++ b/misc/buildroot/ReleaseNotes @@ -1,5 +1,8 @@ -ReleaseNotes v0.1.10: -^^^^^^^^^^^^^^^^^^^^^ +ReleaseNotes v0.1.11 +==================== + +Supported Toolchains +-------------------- This is a highly hacked up version of the buildroot (see http://buildroot.uclibc.org/). It has been hacked so that it @@ -13,7 +16,7 @@ can be used to build the following NuttX-compatible toolchains: NXFLAT toolchain for use with the ARM7 and ARM9. o arm-elf ARM Cortex-M3 (thumb2) toolchain needed for use with - the Luminary LM3Sxxx, NXP 17xxxx, Atmel SAM3u, and STMicor + the Luminary LM3Sxxx, NXP 17xxxx, Atmel SAM3u, and STMicro STM32 ports provided with the NuttX releases. NXFLAT toolchain for use with the ARM Cortex-M3. @@ -26,11 +29,11 @@ can be used to build the following NuttX-compatible toolchains: o i486-elf toochain. Why would you want such a thing? On Linux, of course, such a thing is not needed because you can use the installed GCC - to build 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 - under Cygwin. + to build 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 + under Cygwin. o bfin-elf toolchain not currently used in any NuttX configuration). @@ -59,8 +62,9 @@ Supported tool versions include: o gcc-4.2.4 + binutils-2.19 o gcc-4.3.3 + binutils-2.19.1 o gcc-4.5.2 + binutils-2.21 + o gcc-4.6.3 + binutils-2.22 -See the ChangeLog of features/architectures added in v0.1.9. +See the ChangeLog of features/architectures added in v0.1.11. Installation instructions: @@ -79,11 +83,30 @@ then: And set the "Path to the NuttX root directory" appropriately. +Version Information +------------------- + +buildroot release 1.11 corresponds to SVN revision r5313. + +Note that all SVN information has been stripped from the tarball. If you +need the SVN configuration, you should check out directly from SVN. Revision +r5313 should equivalent to release 1.0 of NuttX buildroot: + + svn checkout -r5313 svn://svn.code.sf.net/p/nuttx/code/trunk nuttx-code + +Or + + svn checkout -r5313 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code + NXFLAT Toolchain Build +---------------------- You can select to build the NXFLAT toolchain with GCC by selecting the NXFLAT toolchin during the configuration process(you can also select omit building GCC with and only build the NXFLAT toolchain for use with your own GCC toolchain. -NFFLAT is only available for ARM and Cortex-M3 architectures. +NOTES: + - NFFLAT is only available for ARM and Cortex-M3 architectures. + - The GCC 4.6.3 will not work with NXFLAT. See "Toolchain Compatibility + Problem" at http://www.nuttx.org/doku.php?id=wiki:vfs:nxflat for details. diff --git a/misc/uClibc++/ChangeLog.txt b/misc/uClibc++/ChangeLog.txt new file mode 100644 index 0000000000..8c680392c7 --- /dev/null +++ b/misc/uClibc++/ChangeLog.txt @@ -0,0 +1,7 @@ +uClibc++-1.0 2011-11-05 + + * The initial release of the uClibc++ implementation of the standard + C++ library for NuttX. This package was contributed ay Qiang Yu and + David for the RGMP team. + +uClibc++-1.1 2011-xx-xx diff --git a/misc/uClibc++/README.txt b/misc/uClibc++/README.txt index 751f235878..8d306fd5ae 100755 --- a/misc/uClibc++/README.txt +++ b/misc/uClibc++/README.txt @@ -48,7 +48,7 @@ Dependencies libraries. 2. NuttX C++ support 3. Math library -4. TLS support is currenly provided only under RGMP +4. TLS support is currently provided only under RGMP NuttX Configuration File Changes ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -64,7 +64,7 @@ If you choose to use the NuttX math library, that is enabled as follows: CONFIG_LIBM=y The math libraries depend on the float.h header file that is normally -provided by your tooltchain. A dummy (and probably wrong) fload.h file +provided by your toolchain. A dummy (and probably wrong) fload.h file can be installed by setting: CONFIG_ARCH_FLOAT_H=y diff --git a/misc/uClibc++/ReleaseNotes.txt b/misc/uClibc++/ReleaseNotes.txt new file mode 100644 index 0000000000..63e4b7583c --- /dev/null +++ b/misc/uClibc++/ReleaseNotes.txt @@ -0,0 +1,32 @@ +uClibc++-1.0 +============ + +This package is a version of the uClibc++ C++ library customized to work +with NuttX. This code originates from http://cxx.uclibc.org/ and has been +adapted for NuttX by the RGMP team (http://rgmp.sourceforge.net/wiki/index.php/Main_Page). +Thanks go to Qiang Yu and David. + +uClibc++ is released as a separate packet rather than being integrated with +the core NuttX source code. This separation is due to differences in +licensing betweein uClibc++ and NuttX: NuttX is licensed under the +permissive modified BSD License; uClibc, on the other hand, is licensed +under the stricter GNU LGPL Version 3 license. + +A simple installation script is provided at misc/uClibc++/install.sh that +can be used to install the uClibc++ components into the NuttX source tree. +See the README file in the top-level uClibc++ directory for instructions on +using the installation script. If you wish to use uClibc++ with NuttX, you +will be required to comply with the licensing requires of the GNU LGPL +Version 3 license. + +uClibc++ release 1.0 corresponds to SVN revision r5313. + +Note that all SVN information has been stripped from the tarball. If you +need the SVN configuration, you should check out directly from SVN. Revision +r5313 should equivalent to release 1.0 of NuttX uClibc++: + + svn checkout -r5313 svn://svn.code.sf.net/p/nuttx/code/trunk nuttx-code + +Or + + svn checkout -r5313 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code diff --git a/misc/uClibc++/zipme.sh b/misc/uClibc++/zipme.sh new file mode 100755 index 0000000000..d20a784634 --- /dev/null +++ b/misc/uClibc++/zipme.sh @@ -0,0 +1,80 @@ +#!/bin/sh +#set -x + +WD=`pwd` +VERSION=$1 + +TAR="tar cvf" +ZIP=gzip + +# Make sure we know what is going on + +if [ -z ${VERSION} ] ; then + echo "You must supply a version like xx.yy.zz as a parameter" + exit 1; +fi + +# Find the directory we were executed from and where we expect to +# see the directory to tar up + +MYNAME=`basename $0` +UCLIBCXX_DIR=uClibc++-${VERSION} + +if [ -x ${WD}/${MYNAME} ] ; then + MISCDIR=`dirname ${WD}` +else + if [ -x ${WD}/${UCLIBCXX_DIR}/${MYNAME} ] ; then + MISCDIR=${WD} + else + echo "You must cd into the misc/ or misc/${UCLIBCXX_DIR}/ directory to execute this script." + exit 1 + fi +fi + +# Get the path to the parent directory + +SUBDIR=`basename ${MISCDIR}`/${UCLIBCXX_DIR} +PARENT=`dirname ${MISCDIR}` + +# The name of the directory must match the version number + +cd ${PARENT} || \ + { echo "Failed to cd to ${PARENT}" ; exit 1 ; } + +if [ ! -d ${SUBDIR} ] ; then + echo "${PARENT}/${SUBDIR} does not exist!" + exit 1 +fi + +TAR_NAME=${UCLIBCXX_DIR}.tar +ZIP_NAME=${TAR_NAME}.gz + +# Prepare the uClibc++ directory -- Remove editor garbage + +find ${SUBDIR} -name '*~' -exec rm -f '{}' ';' || \ + { echo "Removal of emacs garbage failed!" ; exit 1 ; } +find ${SUBDIR} -name '*.swp' -exec rm -f '{}' ';' || \ + { echo "Removal of VI garbage failed!" ; exit 1 ; } + +# Remove any previous tarballs + +if [ -f ${TAR_NAME} ] ; then + echo "Removing ${TAR_NAME}" + rm -f ${TAR_NAME} || \ + { echo "rm ${TAR_NAME} failed!" ; exit 1 ; } +fi + +if [ -f ${ZIP_NAME} ] ; then + echo "Removing ${ZIP_NAME}" + rm -f ${ZIP_NAME} || \ + { echo "rm ${ZIP_NAME} failed!" ; exit 1 ; } +fi + +# Then zip it + +${TAR} ${TAR_NAME} ${SUBDIR} || \ + { echo "tar of ${TAR_NAME} failed!" ; exit 1 ; } +${ZIP} ${TAR_NAME} || \ + { echo "zip of ${TAR_NAME} failed!" ; exit 1 ; } + +cd ${WD} diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f4bdc7ed01..e131d26b24 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3453,7 +3453,7 @@ * 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 +6.23 2012-11-05 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 @@ -3480,7 +3480,7 @@ * drivers/input/max11802.c/h, and include/nuttx/input max11802.h: Adds support for the Maxim MAX11802 touchscreen controller (contributed by Petteri Aimonen). - * graphics/nxtk/nxtk_events.c: Missing implementatin of the blocked + * graphics/nxtk/nxtk_events.c: Missing implementation of the blocked method. This is a critical bugfix for graphics support (contributed by Petteri Aimonen). * drivers/usbdev/pl2303.c, drivers/usbdev/usbmsc.h, and @@ -3537,7 +3537,7 @@ they don't draw in so much un-necessary code when doing a dumb link. * binfmt/libelf: The ELF loader is working correctly with C++ static constructors and destructors and all. - * Documentation/NuttXBinfmt.html: Add documentionof the binary loader. + * Documentation/NuttXBinfmt.html: Add documentation of the binary loader. * configs/sim/ostest: Converted to use the mconfig configuration tool. * configs/sim/cxxtest: New test that will be used to verify the uClibc++ port (eventually). @@ -3566,4 +3566,8 @@ and standardization of linker scripts from Freddie Chopin. * net/netdev_ioctl.c: Add interface state flags and ioctl calls to bring network interfaces up and down (from Darcy Gong). + * config/stm32f4discovery: Enable C++ exceptions. Now the entire + apps/examples/cxxtest works -- meaning the the uClibc++ is + complete and verified for the STM32 platform. +6.24 2012-xx-xx Gregory Nutt diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index be23be91d2..af81335349 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -8,7 +8,7 @@

    NuttX RTOS

    -

    Last Updated: October 29, 2012

    +

    Last Updated: November 5, 2012

    @@ -537,14 +537,14 @@ - C Library + C/C++ Libraries

    -

  • Fully integrated into the OS.
  • +
  • Standard C Library Fully integrated into the OS.
  • @@ -552,7 +552,7 @@

    -

  • Includes floating point math library.
  • +
  • Includes floating point support via a Standard Math Library.
  • @@ -560,7 +560,7 @@

    -

  • Add-on uClibc++ C++ Library is available (LGPL).
  • +
  • Add-on uClibc++ module provides Standard C++ Library(LGPL).
  • @@ -1039,200 +1039,143 @@ -

    NuttX-6.22 Release Notes

    +

    NuttX-6.23 Release Notes

    - The 89th release of NuttX, Version 6.22, was made on September 29, 2012, and is available for download from the + The 90th release of NuttX, Version 6.23, was made on November 5, 2012, and is available for download from the SourceForge website. - Note that the release consists of two tarballs: nuttx-6.22.tar.gz and apps-6.22.tar.gz. + Note that the release consists of two tarballs: nuttx-6.23.tar.gz and apps-6.23.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: r5206, + This release corresponds with SVN release number: r5313, 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: + Revision r5313 should equivalent to release 6.23 of NuttX:

      -svn checkout -r5206 svn://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
      +svn checkout -r5313 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
      +svn checkout -r5313 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). + If both atexit() and on_exit() are enabled, use on_exit() to implement atexit(). + Updates for RGMP 4.0.

    • - 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. + Binfmt: + Add support for loading and executing ELF binary modules from a file system.

    • 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. + Maxim MAX11802 touchscreen controller (Petteri Aimonen)

    • - ARMv7-M: - Added logic to reset the MCU using the NVIC. + STM32 Driver: + Implementation of /dev/random using the STM32 Random Number Generator (RNG).

    • - STM32: - Add support for STM32F103VET6. + STM32 Boards: + ADC support for the Shenzhou IV board. + Relay support for the Shenzhou IV board (both by Darcy Gong).

    • - STM32 Drivers: - Add logic to re-initialize UARTs a second time to enable DMA (Mike Smith). - I2C driver error recovery (Mike Smith). + C++ Standard Library: + Support is now included for the add-on uClibc++ C++ standard library support. + This includes support for iostreams, strings, STL, RTTI, exceptions -- the complete C++ environment. + uClibc++ is provided as a separate add-on package due to licensing issues. + Contributed by Qiang Yu and David of the RGMP team. +

      +

      + Add support for __cxa_atexit().

    • - 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). + C Standard Library: +

      + Optimized generic and ARM-specific memcpy() function. + Optimized memset() function. +

      +

      + Add support for ferror()), feof()), and clearerror()).

    • - 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). -

      -
    • -
    • + Standard Math Library:

      - Library: - Configurable terse output from strerror(). - Added perror() (Kate). - Add %n format to sscanf() (Kate). + Port of the math library from Rhombus OS by Nick Johnson (Darcy Gong).

    • 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). + New NSH commands: ifup, ifdown, urlencode, urldecode, base64enc, bas64dec, and md5 (Darcy Gong). + Extensions to the ifconfig command (Darcy Gong), + Add support for NSH telnet login (Darcy Gong). + Enancements to NSH ping command to support pinging hosts with very long round-trip times. +

      +

      + Many extensions to the webclient/wget and DNS resolver logic from Darcy Gong. + SON, Base64, URL encoding, and MD5 libraries contributed by Darcy Gong. +

      +

      + New examples: ELF loader, JSON, wgetjson, cxxtest, relays.

    +

    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. + W25 SPI FLASH

    • 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. + ADC reset

    • - Applications: - THTTPD (Kate). - NSH ping when IP address is on a different network (Darcy Gong). + Fraphics: + Missing implementation of the blocked method (*critical*, Petteri Aimonen).

    • - Library: - fread(), fflush(), fdopen(): Fix error handling logic (Ronen Vainish). - Fix some field-width handling issues in sscanf() + C Library: + Floating point numbers in printf and related formatting functions (Mike Smith), + cf[get|set]speed() (Mike Smith)

    @@ -3238,351 +3181,179 @@ Other memory:
      -nuttx-6.22 2012-09-29 Gregory Nutt <gnutt@nuttx.org>
      +nuttx-6.23 2012-11-05 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
      +    * 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.
      +    * 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.
      +    * 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.
      +    * lib/stdio/lib_libdtoa.c:  Another dtoa() fix from Mike Smith.
      +    * configs/shenzhou/src/up_adc.c:  Add ADC support for the Shenzhou
      +      board (Darcy Gong).
      +    * configs/shenzhou/thttpd:  Add a THTTPD configuration for the
      +      Shenzhou board (Darcy Gong).
      +    * include/termios.h and lib/termios/libcf*speed.c: The non-standard,
      +      "hidden" c_speed cannot be type const or else static instantiations
      +      of termios will be required to initialize it (Mike Smith).
      +    * drivers/input/max11802.c/h, and include/nuttx/input max11802.h:  Adds
      +      support for the Maxim MAX11802 touchscreen controller (contributed by
      +      Petteri Aimonen).
      +    * graphics/nxtk/nxtk_events.c:  Missing implementatin of the blocked
      +      method.  This is a critical bugfix for graphics support (contributed
      +      by Petteri Aimonen).
      +    * drivers/usbdev/pl2303.c, drivers/usbdev/usbmsc.h, and
      +      include/nuttx/usb/cdcacm.h: USB_CONFIG_ATTR_SELFPOWER vs.
      +      USB_CONFIG_ATT_SELFPOWER (contributed by Petteri Aimonen).
      +    * arch/arm/src/armv7-m/up_memcpy.S:  An optimized memcpy() function for
      +      the ARMv7-M family contributed by Mike Smith.
      +    * lib/strings/lib_vikmemcpy.c:  As an option, the larger but faster
      +      implemementation of memcpy from Daniel Vik is now available (this is
      +      from http://www.danielvik.com/2010/02/fast-memcpy-in-c.html).
      +    * lib/strings/lib_memset.c: CONFIG_MEMSET_OPTSPEED will select a
      +      version of memset() optimized for speed.  By default, memset() is
      +      optimized for size.
      +    * lib/strings/lib_memset.c: CONFIG_MEMSET_64BIT will perform 64-bit
      +      aligned memset() operations.
      +    * arch/arm/src/stm32/stm32_adc.c:  Need to put the ADC back into the
      +      initial reset in the open/setup logic.  Opening the ADC driver works
      +      the first time, but not the second because the device is left in a
      +      powered down state on the last close.
      +    * configs/olimex-lpc1766stck/scripts:  Replace all of the identical
      +      ld.script files with the common one in this directory.
      +    * configs/stm3220g-eval/scripts:  Replace all of the identical
      +      ld.script files with the common one in this directory.
      +    * configs/hymini-stm32v/scripts:  Replace all of the identical
      +      ld.script files with the common one in this directory.
      +    * configs/lpcxpresso-lpc1768/scripts:  Replace all of the identical
      +      ld.script files with the common one in this directory.
      +    * binfmt/elf.c, binfmt/libelf, include/elf.h, include/nuttx/elf.h: Add
      +      basic framework for loadable ELF module support.  The initial check-
      +      in is non-functional and is simply the framework for ELF support.
      +    * include/nuttx/binfmt.h, nxflat.h, elf.h, and symtab.h:  Moved to
      +      include/nuttx/binfmt/.
      +    * arch/sim/src/up_elf.c and arch/x86/src/common/up_elf.c:  Add
      +      for ELF modules.
      +    * arch/arm/include/elf.h:  Added ARM ELF header file.
      +    * include/elf32.h:  Renamed elf.h to elf32.h.
      +    * configs/stm32f4discovery/ostest:  Converted to use the new
      +      Kconfig-based configuration system.
      +    * configs/stm32f4discovery/elf and configs/stm32f4discovery/scripts/gnu-elf.ld
      +      Add a configuration for testing the ARM ELF loader.
      +    * binfmt/libelf:  Can't use fstat(). NuttX does not yet support it.  Damn!
      +    * binfmt/libelf:  The basic ELF module execution appears fully functional.
      +    * configs/shenzhou/src/up_relays.c:  Add support for relays from the
      +      Shenzhou board.  Contributed by Darcy Gong.
      +    * lib/fixedmath: Moved the old lib/math to lib/fixedmath to make room for
      +      the math library from the Rhombus OS
      +    * lib/math: Now contains the math library from the Rhombus OS by Nick Johnson
      +      (submitted by Darcy Gong).
      +    * include/float.h:  Add a first cut at the float.h header file.  This
      +      really should be an architecture/toolchain-specific header file.  It
      +      is only used if CONFIG_ARCH_FLOAT_H is defined.
      +    * lib/math: Files now conform to coding standards.  Separated float,
      +      double, and long double versions of code into separate files so that
      +      they don't draw in so much un-necessary code when doing a dumb link.
      +    * binfmt/libelf:  The ELF loader is working correctly with C++ static
      +      constructors and destructors and all.
      +    * Documentation/NuttXBinfmt.html:  Add documentionof the binary loader.
      +    * configs/sim/ostest:  Converted to use the mconfig configuration tool.
      +    * configs/sim/cxxtest:  New test that will be used to verify the uClibc++
      +      port (eventually).
      +    * include/nuttx/fs/fs.h, lib/stdio/lib_libfread.c, lib_ferror.c,
      +      lib_feof.c, and lib_clearerr.c:  Add support for ferror(), feof(),
      +      and clearerror().  ferror() support is bogus at the moment (it
      +      is equivalent to !feof()); the others should be good.
      +    * configs/stm32f4discovery/include/board.h:  Correct timer 2-7
      +      base frequency (provided by Freddie Chopin).
      +    * include/nuttx/sched.h, sched/atexit.c, and sched/task_deletehook.c:
      +      If both atexit() and on_exit() are enabled, then implement atexit()
      +      as just a special caseof on_exit().  This assumes that the ABI can
      +      handle receipt of more call parameters than the receiving function
      +      expects.  That is usually the case if parameters are passed in
      +      registers.
      +    * libxx/libxx_cxa_atexit():  Implements __cxa_atexit()
      +    * configs/stm32f4discovery/cxxtest:  New test that will be used to
      +      verify the uClibc++ port (eventually).  The sim platform turned not
      +      to be a good platform for testing uClibc++.  The sim example will not
      +      run because the simulator will attempt to execute the static
      +      constructors before main() starts. BUT... NuttX is not initialized
      +      and this results in a crash.  On the STM324Discovery, I will have
      +      better control over when the static constructors run.
      +    * RGMP 4.0 updated from Qiany Yu.
      +    * configs/*/Make.defs and configs/*/ld.script:  Massive clean-up
      +      and standardization of linker scripts from Freddie Chopin.
      +    * net/netdev_ioctl.c:  Add interface state flags and ioctl calls
      +      to bring network interfaces up and down (from Darcy Gong).
      +    * config/stm32f4discovery: Enable C++ exceptions.  Now the entire
      +      apps/examples/cxxtest works -- meaning the the uClibc++ is
      +      complete and verified for the STM32 platform.
       
      -apps-6.22 2012-09-29 Gregory Nutt <gnutt@nuttx.org>
      +apps-6.23 2012-11-05 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.
      +    * 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.
      +    * 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.
      +    * 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)
      +    * apps/nshlib/nsh_telnetd.c:  Add support for login to Telnet session via
      +      username and password (Darcy Gong).
      +    * apps/netutils/resolv/resolv.c (and files using the DNS resolver): Various
      +      DNS address resolution improvements from Darcy Gong.
      +    * apps/nshlib/nsh_netcmds.c:  The ping command now passes a maximum round
      +      trip time to uip_icmpping().  This allows pinging of hosts on complex
      +      networks where the ICMP ECHO round trip time may exceed the ping interval.
      +    * apps/examples/nxtext/nxtext_main.c:  Fix bad conditional compilation
      +      when CONFIG_NX_KBD is not defined.  Submitted by Petteri Aimonen.
      +    * apps/examples/nximage/nximage_main.c:  Add a 5 second delay after the
      +      NX logo is presented so that there is time for the image to be verified.
      +      Suggested by Petteri Aimonen.
      +    * apps/Makefile: Small change that reduces the number of shell invocations
      +      by one (Mike Smith).
      +    * apps/examples/elf:  Test example for the ELF loader.
      +    * apps/examples/elf:  The ELF module test example appears fully functional.
      +    * apps/netutils/json:  Add a snapshot of the cJSON project.  Contributed by
      +      Darcy Gong.
      +    * apps/examples/json:  Test example for cJSON from Darcy Gong
      +    * apps/nshlib/nsh_netinit.c: Fix static IP DNS problem (Darcy Gong)
      +    * apps/netutils/resolv/resolv.c: DNS fixes from Darcy Gong.
      +    * COPYING: Licensing information added.
      +    * apps/netutils/codec and include/netutils/urldecode.h, base64.h, and md5.h:
      +      A port of the BASE46, MD5 and URL CODEC library from Darcy Gong.
      +    * nsnlib/nsh_codeccmd.c:  NSH commands to use the CODEC library.
      +      Contributed by Darcy Gong.
      +    * apps/examples/wgetjson: Test example contributed by Darcy Gong
      +    * apps/examples/cxxtest:  A test for the uClibc++ library provided by
      +      Qiang Yu and the RGMP team.
      +    * apps/netutils/webclient, apps/netutils.codes, and apps/examples/wgetjson:
      +      Add support for wget POST interface.  Contributed by Darcy Gong.
      +    * apps/examples/relays:  A relay example contributed by Darcy Gong.
      +    * apps/nshlib/nsh_netcmds: Add ifup and ifdown commands (from Darcy
      +      Gong).
      +    * apps/nshlib/nsh_netcmds: Extend the ifconfig command so that it
      +      supports setting IP addresses, network masks, name server addresses,
      +      and hardware address (from Darcy Gong).
       
       NxWidgets-1.3 2012-09-29 Gregory Nutt <gnutt@nuttx.org>
       
      @@ -3597,36 +3368,44 @@ NxWidgets-1.3 2012-09-29 Gregory Nutt <gnutt@nuttx.org>
           * Kconfig:  Add option to turn on the memory monitor feature of the
             NxWidgets/NxWM unit tests.
       
      +uClibc++-1.0 2011-11-05 <gnutt@nuttx.org>
      +
      +    * The initial release of the uClibc++ implementation of the standard
      +      C++ library for NuttX.  This package was contributed ay Qiang Yu and
      +      David for the RGMP team.
      +
      +buildroot-1.11 2011-11-05 <gnutt@nuttx.org>
      +
      +    * configs/avr-defconfig-4.3.3 - Added --enable-long-long as a GCC
      +      option.
      +    * configs/avr-defconfig-4.5.2 - New configuration.
      +    * Config.in and almost all configurations in configs/ - Changed the
      +      default nuttx path to $(TOPDIR)/../../nuttx
      +    * Misc files.  Patch provided by Gerd v. Egidy that solves the following
      +      problems
      +      - binutils 2.21 is not available on the gnu servers anymore, they replaced
      +        it with 2.21.1
      +      - 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 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-).
      +    * ldnxflat: Add support for the R_ARM_REL32 relocation.  This relocation
      +      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.
      +
       pascal-3.0 2011-05-15 Gregory Nutt <gnutt@nuttx.org>
       
           * nuttx/:  The Pascal add-on module now installs and builds under the
             apps/interpreters directory.  This means that the pascal-2.1 module is
             incompatible with will all releases of NuttX prior to nuttx-6.0 where the 
             apps/ module was introduced.
      -
      -buildroot-1.10 2011-05-06 <gnutt@nuttx.org>
      -
      -    * Add patch submitted by Dimiter Georgiev to work around problems in building
      -      GDB 6.8 with versions of Cygwin > 1.7.
      -    * configs/i486-defconfig-4.3.3 - Builds an i486 cross development toolchain
      -      using gcc 4.3.3.  Why wouldyou want such a thing?  On Linux, of course,
      -      such a thing is not needed because you can use the installed GCC to build
      -      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-nuttx-elf-gcc to generate true ELF binaries
      -      under Cygwin.
      -    * Makefile - Alter copy arguments to avoid permissions problems when
      -      copying NuttX header files.
      -    * toolchain/nxflat/nxflat.mk and Makefile - Fix include paths.
      -    * toolchain/gcc/3.3.6 - Added a patch to fixed compilation error on Ubuntu
      -      9.10.
      -    * toolchain/nxflat/Makefile - Correct static library link order.
      -    * configs/arm920t-defconfig-4.3.3 - Enable support for NXFLAT tools.
      -    * toolchain/binutils/2.21 and toolchain/gcc/4.5.2 - Add support for GCC
      -      4.5.2 with binutils 2.21.
      -    * configs/arm920t-eabi-defconfig-4.5.2 - Add a configuration to build a
      -      GCC 4.5.2 EABI ARM toolchain for the ARM920t.
       
    diff --git a/nuttx/ReleaseNotes b/nuttx/ReleaseNotes index b1d5f6064c..5fe67a663e 100644 --- a/nuttx/ReleaseNotes +++ b/nuttx/ReleaseNotes @@ -3171,3 +3171,81 @@ Bugfixes (see the change log for details). Some of these are very important Vainish). Fix some field-width handling issues in sscanf() As well as other, less critical bugs (see the ChangeLog for details) + +NuttX-6.23 +^^^^^^^^^^ + +The 90th release of NuttX, Version 6.23, was made on November 5, 2012, +and is available for download from the SourceForge website. Note +that release consists of two tarballs: nuttx-6.23.tar.gz and +apps-6.23.tar.gz. Both may be needed (see the top-level nuttx/README.txt +file for build information). + +This release corresponds with SVN release number: r5313 + +Note that all SVN information has been stripped from the tarballs. If you +r5313 the SVN configuration, you should check out directly from SVN. Revision +r5206 should equivalent to release 6.22 of NuttX 6.22: + + svn checkout -r5313 svn://svn.code.sf.net/p/nuttx/code/trunk nuttx-code + +Or + + svn checkout -r5313 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code + +Additional new features and extended functionality: + + * RTOS: If both atexit() and on_exit() are enabled, use on_exit() to + implement atexit(). Updates for RGMP 4.0. + + * Binfmt: Add support for loading and executing ELF binary modules from + a file system. + + * Drivers: Maxim MAX11802 touchscreen controller (Petteri Aimonen) + + * STM32 Driver: Implementation of /dev/random using the STM32 Random Number + Generator (RNG). + + * STM32 Boards: ADC support for the Shenzhou IV board. Relay support for + the Shenzhou IV board. + + * C Library: Support is now included for the add-on uClibc++ C++ + standard library support. This includes support for iostreams, strings, + STL, RTTI, exceptions -- the complete C++ environment. (uClibc++ is + provided as a separate add-on package due to licensing issues). + + Optimized generic and ARM-specific memcpy() function. Optimized + memset() function. + + Add support for ferror(), feof(), and clearerror(). Add support for + __cxa_atexit(). + + Math Library: Port of the math library from Rhombus OS by Nick Johnson + (Darcy Gong). + + * Applications: New NSH commands: ifup, ifdown, urlencode, urldecode, + base64enc, bas64dec, md5 (Darcy Gong). Add support for NSH telnet login + (Darcy Gong). Enancements to NSH ping command to support pinging hosts + with very long round-trip times. Extensions to the ifconfig command + Darcy Gong), + + Many extensions to the webclient/wget and DNS resolver logic from Darcy + Gong. JSON, Base64, URL encoding, and MD5 libraries contributed by Darcy + Gong. + + New examples: ELF loader, JSON, wgetjson, cxxtest, relays. + +Bugfixes (see the change log for details). Some of these are very important +(marked *critical*): + + * Drivers: W25 SPI FLASH + + * STM32 Drivers: ADC reset + + * Graphics: Missing implementation of the blocked method (*critical*, + Petteri Aimonen). + + * C Library: Floating point numbers in printf and related formatting functions + (Mike Smith), cf[get|set]speed() (Mike Smith) + +As well as other, less critical bugs (see the ChangeLog for details) diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index db423d65b4..b6591c754b 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -1030,6 +1030,8 @@ Where is one of the following: 3. Then remove vterminate.o from the library. At build time, the uClibc++ package will provide a usable replacement vterminate.o. + Steps 2 and 3 will require root privileges on most systems (not Cygwin). + Now NuttX should link with no problem. If you want to restore the vterminate.o that you removed from libsupc++, you can do that with: From 7961d6ce58b0567f4c24cb0b242e2cd875a70c5b Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 5 Nov 2012 20:02:56 +0000 Subject: [PATCH 083/206] Make ostest RR scheduler test use less memory from Freddie Chopin; Plus build fix from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5314 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 5 + apps/examples/README.txt | 11 ++ apps/examples/elf/tests/Makefile | 2 +- apps/examples/nxflat/tests/Makefile | 2 +- apps/examples/ostest/Kconfig | 29 ++++++ apps/examples/ostest/roundrobin.c | 156 ++++++++++++---------------- apps/examples/relays/Makefile | 12 +-- nuttx/Documentation/NuttX.html | 2 +- 8 files changed, 119 insertions(+), 100 deletions(-) diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 8a168588bd..d755fcca05 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -407,3 +407,8 @@ and hardware address (from Darcy Gong). 6.24 2012-xx-xx Gregory Nutt + + * apps/examples/ostest/roundrobin.c: Replace large tables with + algorithmic prime number generation. This allows the roundrobin + test to run on platforms with minimal SRAM (Freddie Chopin). + diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 3bc6e50b5f..3ee1abcf6b 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -1087,6 +1087,17 @@ examples/ostest Specifies the number of threads to create in the barrier test. The default is 8 but a smaller number may be needed on systems without sufficient memory to start so many threads. + * CONFIG_EXAMPLES_OSTEST_RR_RANGE + During round-robin scheduling test two threads are created. Each of the threads + searches for prime numbers in the configurable range, doing that configurable + number of times. + This value specifies the end of search range and together with number of runs + allows to configure the length of this test - it should last at least a few + tens of seconds. Allowed values [1; 32767], default 10000 + * CONFIG_EXAMPLES_OSTEST_RR_RUNS + During round-robin scheduling test two threads are created. Each of the threads + searches for prime numbers in the configurable range, doing that configurable + number of times. examples/pashello ^^^^^^^^^^^^^^^^^ diff --git a/apps/examples/elf/tests/Makefile b/apps/examples/elf/tests/Makefile index d2192cb1e4..778dd64802 100644 --- a/apps/examples/elf/tests/Makefile +++ b/apps/examples/elf/tests/Makefile @@ -117,4 +117,4 @@ $(SYMTAB_SRC): build clean: $(foreach DIR, $(ALL_SUBDIRS), $(DIR)_clean) @rm -f $(ROMFS_HDR) $(ROMFS_IMG) $(SYMTAB_SRC) varlist.tmp - @rm -rf $(ROMFS_DIR) + @rm -rf $(ROMFS_DIR) $(DIRLIST_HDR) diff --git a/apps/examples/nxflat/tests/Makefile b/apps/examples/nxflat/tests/Makefile index 36bb0e88eb..4979c7fd47 100644 --- a/apps/examples/nxflat/tests/Makefile +++ b/apps/examples/nxflat/tests/Makefile @@ -98,6 +98,6 @@ $(SYMTAB): build clean: $(foreach DIR, $(SUBDIRS), $(DIR)_clean) @rm -f $(ROMFS_HDR) $(ROMFS_IMG) $(SYMTAB) - @rm -rf $(ROMFS_DIR) + @rm -rf $(ROMFS_DIR) $(ROMFS_DIRLIST) diff --git a/apps/examples/ostest/Kconfig b/apps/examples/ostest/Kconfig index 0da7e4ce34..3c64dc0c6d 100644 --- a/apps/examples/ostest/Kconfig +++ b/apps/examples/ostest/Kconfig @@ -39,4 +39,33 @@ config EXAMPLES_OSTEST_NBARRIER_THREADS is 8 but a smaller number may be needed on systems without sufficient memory to start so many threads. +config EXAMPLES_OSTEST_RR_RANGE + int "Round-robin test - end of search range" + default 10000 + range 1 32767 + depends on RR_INTERVAL > 0 + ---help--- + During round-robin scheduling test two threads are created. Each of the threads + searches for prime numbers in the configurable range, doing that configurable + number of times. + + This value specifies the end of search range and together with number of runs + allows to configure the length of this test - it should last at least a few + tens of seconds. Allowed values [1; 32767], default 10000 + +config EXAMPLES_OSTEST_RR_RUNS + int "Round-robin test - number of runs" + default 10 + range 1 32767 + depends on RR_INTERVAL > 0 + ---help--- + During round-robin scheduling test two threads are created. Each of the threads + searches for prime numbers in the configurable range, doing that configurable + number of times. + + This value specifies the number of times the thread searches the range for + prime numbers and together with end of search range allows to configure the + length of this test - it should last at least a few tens of seconds. Allowed + values [1; 32767], default 10 + endif diff --git a/apps/examples/ostest/roundrobin.c b/apps/examples/ostest/roundrobin.c index 5167a857ed..bfd344df34 100644 --- a/apps/examples/ostest/roundrobin.c +++ b/apps/examples/ostest/roundrobin.c @@ -1,7 +1,7 @@ /******************************************************************************** * examples/ostest/roundrobin.c * - * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -39,6 +39,7 @@ #include #include +#include #include "ostest.h" #if CONFIG_RR_INTERVAL > 0 @@ -47,115 +48,87 @@ * Definitions ********************************************************************************/ -/* This number may need to be tuned for different processor speeds. Since these - * arrays must be large to very correct SCHED_RR behavior, this test may require - * too much memory on many targets. - */ +/* This numbers should be tuned for different processor speeds via .config file. + * With default values the test takes about 30s on Cortex-M3 @ 24MHz. With 32767 + * range and 10 runs it takes ~320s. */ -/* #define CONFIG_NINTEGERS 32768 Takes forever on 60Mhz ARM7 */ +#ifndef CONFIG_EXAMPLES_OSTEST_RR_RANGE +# define CONFIG_EXAMPLES_OSTEST_RR_RANGE 10000 +# warning "CONFIG_EXAMPLES_OSTEST_RR_RANGE undefined, using default value = 10000" +#elif (CONFIG_EXAMPLES_OSTEST_RR_RANGE < 1) || (CONFIG_EXAMPLES_OSTEST_RR_RANGE > 32767) +# define CONFIG_EXAMPLES_OSTEST_RR_RANGE 10000 +# warning "Invalid value of CONFIG_EXAMPLES_OSTEST_RR_RANGE, using default value = 10000" +#endif -#define CONFIG_NINTEGERS 2048 - -/******************************************************************************** - * Private Data - ********************************************************************************/ - -static int prime1[CONFIG_NINTEGERS]; -static int prime2[CONFIG_NINTEGERS]; +#ifndef CONFIG_EXAMPLES_OSTEST_RR_RUNS +# define CONFIG_EXAMPLES_OSTEST_RR_RUNS 10 +# warning "CONFIG_EXAMPLES_OSTEST_RR_RUNS undefined, using default value = 10" +#elif (CONFIG_EXAMPLES_OSTEST_RR_RUNS < 1) || (CONFIG_EXAMPLES_OSTEST_RR_RUNS > 32767) +# define CONFIG_EXAMPLES_OSTEST_RR_RUNS 10 +# warning "Invalid value of CONFIG_EXAMPLES_OSTEST_RR_RUNS, using default value = 10" +#endif /******************************************************************************** * Private Functions ********************************************************************************/ /******************************************************************************** - * Name: dosieve + * Name: get_primes * * Description - * This implements a "sieve of aristophanes" algorithm for finding prime number. - * Credit for this belongs to someone, but I am not sure who anymore. Anyway, - * the only purpose here is that we need some algorithm that takes a long period - * of time to execute. - * + * This function searches for prime numbers in the most primitive way possible. ********************************************************************************/ -static void dosieve(int *prime) +static void get_primes(int *count, int *last) { - int a,d; - int i; - int j; + int number; + int local_count = 0; + *last = 0; // to make compiler happy - a = 2; - d = a; + for (number = 1; number < CONFIG_EXAMPLES_OSTEST_RR_RANGE; number++) + { + int div; + bool is_prime = true; - for (i = 0; i < CONFIG_NINTEGERS; i++) + for (div = 2; div <= number / 2; div++) + if (number % div == 0) + { + is_prime = false; + break; + } + + if (is_prime) { - prime[i] = i+2; - } - - for (i = 1; i < 10; i++) - { - for (j = 0; j < CONFIG_NINTEGERS; j++) - { - d = a + d; - if (d < CONFIG_NINTEGERS) - { - prime[d]=0; - } - } - a++; - d = a; - i++; - } - + local_count++; + *last = number; #if 0 /* We don't really care what the numbers are */ - for (i = 0, j= 0; i < CONFIG_NINTEGERS; i++) - { - if (prime[i] != 0) - { - printf(" Prime %d: %d\n", j, prime[i]); - j++; - } - } + printf(" Prime %d: %d\n", local_count, number); #endif + } + } + + *count = local_count; } /******************************************************************************** - * Name: sieve1 + * Name: get_primes_thread ********************************************************************************/ -static void *sieve1(void *parameter) +static void *get_primes_thread(void *parameter) { - int i; + int id = (int)parameter; + int i, count, last; - printf("sieve1 started\n"); + printf("get_primes_thread id=%d started, looking for primes < %d, doing %d run(s)\n", + id, CONFIG_EXAMPLES_OSTEST_RR_RANGE, CONFIG_EXAMPLES_OSTEST_RR_RUNS); - for (i = 0; i < 1000; i++) + for (i = 0; i < CONFIG_EXAMPLES_OSTEST_RR_RUNS; i++) { - dosieve(prime1); + get_primes(&count, &last); } - printf("sieve1 finished\n"); - - pthread_exit(NULL); - return NULL; /* To keep some compilers happy */ -} - -/******************************************************************************** - * Name: sieve2 - ********************************************************************************/ - -static void *sieve2(void *parameter) -{ - int i; - - printf("sieve2 started\n"); - - for (i = 0; i < 1000; i++) - { - dosieve(prime2); - } - - printf("sieve2 finished\n"); + printf("get_primes_thread id=%d finished, found %d primes, last one was %d\n", + id, count, last); pthread_exit(NULL); return NULL; /* To keep some compilers happy */ @@ -171,14 +144,13 @@ static void *sieve2(void *parameter) void rr_test(void) { - pthread_t sieve1_thread; - pthread_t sieve2_thread; + pthread_t get_primes1_thread; + pthread_t get_primes2_thread; struct sched_param sparam; pthread_attr_t attr; pthread_addr_t result; int status; - printf("rr_test: Starting sieve1 thread \n"); status = pthread_attr_init(&attr); if (status != OK) { @@ -203,29 +175,31 @@ void rr_test(void) } else { - printf("rr_test: Set thread policty to SCHED_RR\n"); + printf("rr_test: Set thread policy to SCHED_RR\n"); } - status = pthread_create(&sieve1_thread, &attr, sieve1, NULL); + printf("rr_test: Starting first get_primes_thread\n"); + + status = pthread_create(&get_primes1_thread, &attr, get_primes_thread, (void*)1); if (status != 0) { printf("rr_test: Error in thread 1 creation, status=%d\n", status); } - printf("rr_test: Starting sieve1 thread \n"); + printf("rr_test: Starting second get_primes_thread\n"); - status = pthread_create(&sieve2_thread, &attr, sieve2, NULL); + status = pthread_create(&get_primes2_thread, &attr, get_primes_thread, (void*)2); if (status != 0) { printf("rr_test: Error in thread 2 creation, status=%d\n", status); } - printf("rr_test: Waiting for sieves to complete -- this should take awhile\n"); + printf("rr_test: Waiting for threads to complete -- this should take awhile\n"); printf("rr_test: If RR scheduling is working, they should start and complete at\n"); printf("rr_test: about the same time\n"); - pthread_join(sieve2_thread, &result); - pthread_join(sieve1_thread, &result); + pthread_join(get_primes2_thread, &result); + pthread_join(get_primes1_thread, &result); printf("rr_test: Done\n"); } diff --git a/apps/examples/relays/Makefile b/apps/examples/relays/Makefile index 6641c94b4a..4a65306935 100644 --- a/apps/examples/relays/Makefile +++ b/apps/examples/relays/Makefile @@ -39,14 +39,14 @@ include $(APPDIR)/Make.defs # relays Example -ASRC = -CSRC = relays_main.c +ASRCS = +CSRCS = relays_main.c -AOBJ = $(ASRCS:.S=$(OBJEXT)) -COBJ = $(CSRCS:.c=$(OBJEXT)) +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) -SRC = $(ASRCS) $(CSRCS) -OBJ = $(AOBJS) $(COBJS) +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index af81335349..dd7b83cfc8 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -560,7 +560,7 @@ From 9fa8d5d6081fed3401c91a1d6ce0efece97de420 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 6 Nov 2012 13:36:51 +0000 Subject: [PATCH 084/206] STM32 F100 High Density support and generic board configuration from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5315 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Documentation/README.html | 2 + nuttx/README.txt | 2 + nuttx/arch/arm/include/stm32/chip.h | 200 ++++-- nuttx/arch/arm/src/stm32/Kconfig | 373 ++++++++--- .../arm/src/stm32/chip/stm32f100_pinmap.h | 526 +++++++++------ .../arm/src/stm32/chip/stm32f20xxx_pinmap.h | 2 +- .../arm/src/stm32/chip/stm32f40xxx_pinmap.h | 2 +- nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c | 50 ++ nuttx/configs/Kconfig | 153 +++-- nuttx/configs/README.txt | 80 +-- nuttx/configs/stm32f100rc_generic/Kconfig | 58 ++ nuttx/configs/stm32f100rc_generic/README.txt | 504 ++++++++++++++ .../stm32f100rc_generic/include/board.h | 223 +++++++ .../configs/stm32f100rc_generic/nsh/Make.defs | 147 ++++ .../configs/stm32f100rc_generic/nsh/defconfig | 629 ++++++++++++++++++ .../configs/stm32f100rc_generic/nsh/setenv.sh | 76 +++ .../stm32f100rc_generic/ostest/Make.defs | 147 ++++ .../stm32f100rc_generic/ostest/defconfig | 564 ++++++++++++++++ .../stm32f100rc_generic/ostest/setenv.sh | 76 +++ .../stm32f100rc_generic/scripts/ld.script | 118 ++++ .../configs/stm32f100rc_generic/src/Makefile | 83 +++ .../src/stm32f100rc_internal.h | 57 ++ .../configs/stm32f100rc_generic/src/up_boot.c | 70 ++ .../stm32f100rc_generic/src/up_buttons.c | 117 ++++ .../configs/stm32f100rc_generic/src/up_leds.c | 108 +++ 25 files changed, 3915 insertions(+), 452 deletions(-) create mode 100644 nuttx/configs/stm32f100rc_generic/Kconfig create mode 100644 nuttx/configs/stm32f100rc_generic/README.txt create mode 100644 nuttx/configs/stm32f100rc_generic/include/board.h create mode 100644 nuttx/configs/stm32f100rc_generic/nsh/Make.defs create mode 100644 nuttx/configs/stm32f100rc_generic/nsh/defconfig create mode 100755 nuttx/configs/stm32f100rc_generic/nsh/setenv.sh create mode 100644 nuttx/configs/stm32f100rc_generic/ostest/Make.defs create mode 100644 nuttx/configs/stm32f100rc_generic/ostest/defconfig create mode 100755 nuttx/configs/stm32f100rc_generic/ostest/setenv.sh create mode 100644 nuttx/configs/stm32f100rc_generic/scripts/ld.script create mode 100644 nuttx/configs/stm32f100rc_generic/src/Makefile create mode 100644 nuttx/configs/stm32f100rc_generic/src/stm32f100rc_internal.h create mode 100644 nuttx/configs/stm32f100rc_generic/src/up_boot.c create mode 100644 nuttx/configs/stm32f100rc_generic/src/up_buttons.c create mode 100644 nuttx/configs/stm32f100rc_generic/src/up_leds.c diff --git a/nuttx/Documentation/README.html b/nuttx/Documentation/README.html index 5fef40fc16..7c82c3f157 100644 --- a/nuttx/Documentation/README.html +++ b/nuttx/Documentation/README.html @@ -184,6 +184,8 @@ | | | `- README.txt | | |- stm3240g-eval/ | | | `- README.txt + | | |- stm32f100rc_generic/ + | | | `- README.txt | | |- stm32f4discovery/ | | | `- README.txt | | |- sure-pic32mx/ diff --git a/nuttx/README.txt b/nuttx/README.txt index d567d88c8c..02067fc73f 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -781,6 +781,8 @@ nuttx | | `- README.txt | |- stm3240g-eval/ | | `- README.txt + | |- stm32f100rc_generic/ + | | `- README.txt | |- stm32f4discovery/ | | `- README.txt | |- sure-pic32mx/ diff --git a/nuttx/arch/arm/include/stm32/chip.h b/nuttx/arch/arm/include/stm32/chip.h index d01929e1ca..d34c2eb4f0 100644 --- a/nuttx/arch/arm/include/stm32/chip.h +++ b/nuttx/arch/arm/include/stm32/chip.h @@ -59,12 +59,11 @@ /* STM32 F100 Value Line ************************************************************/ #if defined(CONFIG_ARCH_CHIP_STM32F100C8) || defined(CONFIG_ARCH_CHIP_STM32F100CB) \ - || defined(CONFIG_ARCH_CHIP_STM32F100R8) || defined(CONFIG_ARCH_CHIP_STM32F100RB) \ - || defined(CONFIG_ARCH_CHIP_STM32F100V8) || defined(CONFIG_ARCH_CHIP_STM32F100VB) + || defined(CONFIG_ARCH_CHIP_STM32F100R8) || defined(CONFIG_ARCH_CHIP_STM32F100RB) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# define CONFIG_STM32_MEDIUMDENSITY 1 /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# define CONFIG_STM32_MEDIUMDENSITY 1 /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # define CONFIG_STM32_VALUELINE 1 /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -72,15 +71,110 @@ # define STM32_NFSMC 0 /* FSMC */ # define STM32_NATIM 1 /* One advanced timer TIM1 */ # define STM32_NGTIM 3 /* 16-bit general timers TIM2,3,4 with DMA */ -# define STM32_NBTIM 0 /* No basic timers */ -# define STM32_NDMA 2 /* DMA1-2 */ +# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ +// TODO: there are also 3 additional timers (15-17) that don't fit any existing category +# define STM32_NDMA 1 /* DMA1 */ # define STM32_NSPI 2 /* SPI1-2 */ -# define STM32_NI2S 0 /* No I2S (?) */ +# define STM32_NI2S 0 /* No I2S */ # define STM32_NUSART 3 /* USART1-3 */ # define STM32_NI2C 2 /* I2C1-2 */ # define STM32_NCAN 0 /* No CAN */ # define STM32_NSDIO 0 /* No SDIO */ # define STM32_NUSBOTG 0 /* No USB OTG FS/HS */ +# define STM32_NGPIO 64 /* GPIOA-D */ +# define STM32_NADC 1 /* ADC1 */ +# define STM32_NDAC 2 /* DAC 1-2 */ +# define STM32_NCRC 1 /* CRC1 */ +# define STM32_NETHERNET 0 /* No ethernet */ +# define STM32_NRNG 0 /* No random number generator (RNG) */ +# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */ + +#elif defined(CONFIG_ARCH_CHIP_STM32F100V8) || defined(CONFIG_ARCH_CHIP_STM32F100VB) +# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# define CONFIG_STM32_MEDIUMDENSITY 1 /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# define CONFIG_STM32_VALUELINE 1 /* STM32F100x */ +# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ +# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ +# undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */ +# define STM32_NFSMC 0 /* FSMC */ +# define STM32_NATIM 1 /* One advanced timer TIM1 */ +# define STM32_NGTIM 3 /* 16-bit general timers TIM2,3,4 with DMA */ +# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ +// TODO: there are also 3 additional timers (15-17) that don't fit any existing category +# define STM32_NDMA 1 /* DMA1 */ +# define STM32_NSPI 2 /* SPI1-2 */ +# define STM32_NI2S 0 /* No I2S */ +# define STM32_NUSART 3 /* USART1-3 */ +# define STM32_NI2C 2 /* I2C1-2 */ +# define STM32_NCAN 0 /* No CAN */ +# define STM32_NSDIO 0 /* No SDIO */ +# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */ +# define STM32_NGPIO 80 /* GPIOA-E */ +# define STM32_NADC 1 /* ADC1 */ +# define STM32_NDAC 2 /* DAC 1-2 */ +# define STM32_NCRC 1 /* CRC1 */ +# define STM32_NETHERNET 0 /* No ethernet */ +# define STM32_NRNG 0 /* No random number generator (RNG) */ +# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */ + +/* STM32 F100 High-density value Line ************************************************************/ + +#elif defined(CONFIG_ARCH_CHIP_STM32F100RC) || defined(CONFIG_ARCH_CHIP_STM32F100RD) \ + || defined(CONFIG_ARCH_CHIP_STM32F100RE) +# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# define CONFIG_STM32_VALUELINE 1 /* STM32F100x */ +# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ +# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ +# undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */ +# define STM32_NFSMC 0 /* FSMC */ +# define STM32_NATIM 1 /* One advanced timer TIM1 */ +# define STM32_NGTIM 4 /* 16-bit general timers TIM2,3,4,5 with DMA */ +# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ +// TODO: there are also 6 additional timers (12-17) that don't fit any existing category +# define STM32_NDMA 2 /* DMA1-2 */ +# define STM32_NSPI 3 /* SPI1-3 */ +# define STM32_NI2S 0 /* No I2S */ +# define STM32_NUSART 5 /* USART1-5 */ +# define STM32_NI2C 2 /* I2C1-2 */ +# define STM32_NCAN 0 /* No CAN */ +# define STM32_NSDIO 0 /* No SDIO */ +# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */ +# define STM32_NGPIO 64 /* GPIOA-D */ +# define STM32_NADC 1 /* ADC1 */ +# define STM32_NDAC 2 /* DAC 1-2 */ +# define STM32_NCRC 1 /* CRC1 */ +# define STM32_NETHERNET 0 /* No ethernet */ +# define STM32_NRNG 0 /* No random number generator (RNG) */ +# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */ + +#elif defined(CONFIG_ARCH_CHIP_STM32F100VC) || defined(CONFIG_ARCH_CHIP_STM32F100VD) \ + || defined(CONFIG_ARCH_CHIP_STM32F100VE) +# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# define CONFIG_STM32_VALUELINE 1 /* STM32F100x */ +# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ +# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ +# undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */ +# define STM32_NFSMC 1 /* FSMC */ +# define STM32_NATIM 1 /* One advanced timer TIM1 */ +# define STM32_NGTIM 4 /* 16-bit general timers TIM2,3,4,5 with DMA */ +# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ +// TODO: there are also 6 additional timers (12-17) that don't fit any existing category +# define STM32_NDMA 2 /* DMA1-2 */ +# define STM32_NSPI 3 /* SPI1-3 */ +# define STM32_NI2S 0 /* No I2S */ +# define STM32_NUSART 5 /* USART1-5 */ +# define STM32_NI2C 2 /* I2C1-2 */ +# define STM32_NCAN 0 /* No CAN */ +# define STM32_NSDIO 0 /* No SDIO */ +# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */ # define STM32_NGPIO 80 /* GPIOA-E */ # define STM32_NADC 1 /* ADC1 */ # define STM32_NDAC 2 /* DAC 1-2 */ @@ -96,9 +190,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F103RET6) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -129,9 +223,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F103VCT6) || defined(CONFIG_ARCH_CHIP_STM32F103VET6) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -162,9 +256,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F103ZET6) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -192,9 +286,9 @@ /* STM32 F105/F107 Connectivity Line *******************************************************/ #elif defined(CONFIG_ARCH_CHIP_STM32F105VBT7) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # define CONFIG_STM32_CONNECTIVITYLINE 1 /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -221,9 +315,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F107VC) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # define CONFIG_STM32_CONNECTIVITYLINE 1 /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -251,9 +345,9 @@ /* STM32 F2 Family ******************************************************************/ #elif defined(CONFIG_ARCH_CHIP_STM32F207IG) /* UFBGA-176 1024Kb FLASH 128Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # define CONFIG_STM32_STM32F20XX 1 /* STM32F205x and STM32F207x */ @@ -283,9 +377,9 @@ /* STM23 F4 Family ******************************************************************/ #elif defined(CONFIG_ARCH_CHIP_STM32F405RG) /* LQFP 64 10x10x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -314,9 +408,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F405VG) /* LQFP 100 14x14x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -345,9 +439,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F405ZG) /* LQFP 144 20x20x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -376,9 +470,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407VE) /* LQFP-100 512Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -407,9 +501,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407VG) /* LQFP-100 14x14x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -438,9 +532,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407ZE) /* LQFP-144 512Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -469,9 +563,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407ZG) /* LQFP 144 20x20x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -500,9 +594,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407IE) /* LQFP 176 24x24x1.4 512Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -531,9 +625,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407IG) /* BGA 176; LQFP 176 24x24x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 4fcaa756f2..8cb6360d2c 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -34,6 +34,27 @@ config ARCH_CHIP_STM32F100RB select STM32_STM32F10XX select STM32_VALUELINE +config ARCH_CHIP_STM32F100RC + bool "STM32F100RC" + select ARCH_CORTEXM3 + select STM32_STM32F10XX + select STM32_VALUELINE + select STM32_HIGHDENSITY + +config ARCH_CHIP_STM32F100RD + bool "STM32F100RD" + select ARCH_CORTEXM3 + select STM32_STM32F10XX + select STM32_VALUELINE + select STM32_HIGHDENSITY + +config ARCH_CHIP_STM32F100RE + bool "STM32F100RE" + select ARCH_CORTEXM3 + select STM32_STM32F10XX + select STM32_VALUELINE + select STM32_HIGHDENSITY + config ARCH_CHIP_STM32F100V8 bool "STM32F100V8" select ARCH_CORTEXM3 @@ -46,6 +67,27 @@ config ARCH_CHIP_STM32F100VB select STM32_STM32F10XX select STM32_VALUELINE +config ARCH_CHIP_STM32F100VC + bool "STM32F100VC" + select ARCH_CORTEXM3 + select STM32_STM32F10XX + select STM32_VALUELINE + select STM32_HIGHDENSITY + +config ARCH_CHIP_STM32F100VD + bool "STM32F100VD" + select ARCH_CORTEXM3 + select STM32_STM32F10XX + select STM32_VALUELINE + select STM32_HIGHDENSITY + +config ARCH_CHIP_STM32F100VE + bool "STM32F100VE" + select ARCH_CORTEXM3 + select STM32_STM32F10XX + select STM32_VALUELINE + select STM32_HIGHDENSITY + config ARCH_CHIP_STM32F103RET6 bool "STM32F103RET6" select ARCH_CORTEXM3 @@ -183,6 +225,7 @@ endchoice config STM32_DFU bool "DFU bootloader" default n + depends on !STM32_VALUELINE ---help--- Configure and position code for use with the STMicro DFU bootloader. Do not select this option if you will load code using JTAG/SWM. @@ -198,25 +241,13 @@ config STM32_ADC2 bool "ADC2" default n select STM32_ADC + depends on !STM32_VALUELINE config STM32_ADC3 bool "ADC3" default n select STM32_ADC - -config STM32_CRC - bool "CRC" - default n - -config STM32_DMA1 - bool "DMA1" - default n - select ARCH_DMA - -config STM32_DMA2 - bool "DMA2" - default n - select ARCH_DMA + depends on !STM32_VALUELINE config STM32_BKP bool "BKP" @@ -233,6 +264,7 @@ config STM32_CAN1 default n select CAN select STM32_CAN + depends on !STM32_VALUELINE config STM32_CAN2 bool "CAN2" @@ -246,11 +278,31 @@ config STM32_CCMDATARAM default n depends on STM32_STM32F40XX +config STM32_CEC + bool "CEC" + default n + depends on STM32_VALUELINE + +config STM32_CRC + bool "CRC" + default n + config STM32_CRYP bool "CRYP" default n depends on STM32_STM32F20XX || STM32_STM32F40XX +config STM32_DMA1 + bool "DMA1" + default n + select ARCH_DMA + +config STM32_DMA2 + bool "DMA2" + default n + select ARCH_DMA + depends on !STM32_VALUELINE || (STM32_VALUELINE && STM32_HIGHDENSITY) + config STM32_DAC1 bool "DAC1" default n @@ -275,7 +327,7 @@ config STM32_ETHMAC config STM32_FSMC bool "FSMC" default n - depends on !STM32_CONNECTIVITYLINE + depends on !STM32_CONNECTIVITYLINE && STM32_HIGHDENSITY config STM32_HASH bool "HASH" @@ -326,7 +378,7 @@ config STM32_RNG config STM32_SDIO bool "SDIO" default n - depends on !STM32_CONNECTIVITYLINE + depends on !STM32_CONNECTIVITYLINE && !STM32_VALUELINE config STM32_SPI1 bool "SPI1" @@ -343,7 +395,7 @@ config STM32_SPI2 config STM32_SPI3 bool "SPI3" default n - depends on STM32_CONNECTIVITYLINE || STM32_STM32F20XX || STM32_STM32F40XX + depends on STM32_CONNECTIVITYLINE || STM32_STM32F20XX || STM32_STM32F40XX || (STM32_VALUELINE && STM32_HIGHDENSITY) select SPI select STM32_SPI @@ -383,6 +435,7 @@ config STM32_TIM7 config STM32_TIM8 bool "TIM8" default n + depends on !STM32_VALUELINE config STM32_TIM9 bool "TIM9" @@ -402,17 +455,32 @@ config STM32_TIM11 config STM32_TIM12 bool "TIM12" default n - depends on STM32_STM32F20XX || STM32_STM32F40XX + depends on STM32_STM32F20XX || STM32_STM32F40XX || STM32_VALUELINE config STM32_TIM13 bool "TIM13" default n - depends on STM32_STM32F20XX || STM32_STM32F40XX + depends on STM32_STM32F20XX || STM32_STM32F40XX || STM32_VALUELINE config STM32_TIM14 bool "TIM14" default n - depends on STM32_STM32F20XX || STM32_STM32F40XX + depends on STM32_STM32F20XX || STM32_STM32F40XX || STM32_VALUELINE + +config STM32_TIM15 + bool "TIM15" + default n + depends on STM32_VALUELINE + +config STM32_TIM16 + bool "TIM16" + default n + depends on STM32_VALUELINE + +config STM32_TIM17 + bool "TIM17" + default n + depends on STM32_VALUELINE config STM32_USART1 bool "USART1" @@ -448,7 +516,7 @@ config STM32_USART6 config STM32_USB bool "USB Device" default n - depends on STM32_STM32F10XX + depends on STM32_STM32F10XX && !STM32_VALUELINE select USBDEV config STM32_WWDG @@ -475,6 +543,52 @@ config STM32_CAN menu "Alternate Pin Mapping" +choice + prompt "CAN1 Alternate Pin Mappings" + depends on STM32_STM32F10XX && STM32_CAN1 + default STM32_CAN1_NO_REMAP + +config STM32_CAN1_NO_REMAP + bool "No pin remapping" + +config STM32_CAN1_REMAP1 + bool "CAN1 alternate pin remapping #1" + +config STM32_CAN1_REMAP2 + bool "CAN1 alternate pin remapping #2" + +endchoice + +config STM32_CAN2_REMAP + bool "CAN2 Alternate Pin Mapping" + default n + depends on STM32_CONNECTIVITYLINE && STM32_CAN2 + +config STM32_CEC_REMAP + bool "CEC Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_CEC + +config STM32_ETH_REMAP + bool "Ethernet Alternate Pin Mapping" + default n + depends on STM32_CONNECTIVITYLINE && STM32_ETHMAC + +config STM32_I2C1_REMAP + bool "I2C1 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_I2C1 + +config STM32_SPI1_REMAP + bool "SPI1 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_SPI1 + +config STM32_SPI3_REMAP + bool "SPI3 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_SPI3 && !STM32_VALUELINE + choice prompt "TIM1 Alternate Pin Mappings" depends on STM32_STM32F10XX && STM32_TIM1 @@ -531,6 +645,51 @@ config STM32_TIM4_REMAP default n depends on STM32_STM32F10XX && STM32_TIM4 +config STM32_TIM9_REMAP + bool "TIM9 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_TIM9 + +config STM32_TIM10_REMAP + bool "TIM10 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_TIM10 + +config STM32_TIM11_REMAP + bool "TIM11 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_TIM11 + +config STM32_TIM12_REMAP + bool "TIM12 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_TIM12 + +config STM32_TIM13_REMAP + bool "TIM13 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_TIM13 + +config STM32_TIM14_REMAP + bool "TIM14 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_TIM14 + +config STM32_TIM15_REMAP + bool "TIM15 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_TIM15 + +config STM32_TIM16_REMAP + bool "TIM16 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_TIM16 + +config STM32_TIM17_REMAP + bool "TIM17 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_TIM17 + config STM32_USART1_REMAP bool "USART1 Alternate Pin Mapping" default n @@ -557,47 +716,6 @@ config STM32_USART3_PARTIAL_REMAP endchoice -config STM32_SPI1_REMAP - bool "SPI1 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_SPI1 - -config STM32_SPI3_REMAP - bool "SPI3 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_SPI3 - -config STM32_I2C1_REMAP - bool "I2C1 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_I2C1 - -choice - prompt "CAN1 Alternate Pin Mappings" - depends on STM32_STM32F10XX && STM32_CAN1 - default STM32_CAN1_NO_REMAP - -config STM32_CAN1_NO_REMAP - bool "No pin remapping" - -config STM32_CAN1_REMAP1 - bool "CAN1 alternate pin remapping #1" - -config STM32_CAN1_REMAP2 - bool "CAN1 alternate pin remapping #2" - -endchoice - -config STM32_CAN2_REMAP - bool "CAN2 Alternate Pin Mapping" - default n - depends on STM32_CONNECTIVITYLINE && STM32_CAN2 - -config STM32_ETH_REMAP - bool "Ethernet Alternate Pin Mapping" - default n - depends on STM32_CONNECTIVITYLINE && STM32_ETHMAC - endmenu choice @@ -666,6 +784,7 @@ config STM32_TIM1_PWM config STM32_TIM1_CHANNEL int "TIM1 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM1_PWM ---help--- If TIM1 is enabled for PWM usage, you also need specifies the timer output @@ -676,7 +795,7 @@ config STM32_TIM2_PWM default n depends on STM32_TIM2 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 2 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM2 @@ -686,6 +805,7 @@ config STM32_TIM2_PWM config STM32_TIM2_CHANNEL int "TIM2 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM2_PWM ---help--- If TIM2 is enabled for PWM usage, you also need specifies the timer output @@ -696,7 +816,7 @@ config STM32_TIM3_PWM default n depends on STM32_TIM3 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 3 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM3 @@ -706,6 +826,7 @@ config STM32_TIM3_PWM config STM32_TIM3_CHANNEL int "TIM3 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM3_PWM ---help--- If TIM3 is enabled for PWM usage, you also need specifies the timer output @@ -716,7 +837,7 @@ config STM32_TIM4_PWM default n depends on STM32_TIM4 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 4 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM4 @@ -726,6 +847,7 @@ config STM32_TIM4_PWM config STM32_TIM4_CHANNEL int "TIM4 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM4_PWM ---help--- If TIM4 is enabled for PWM usage, you also need specifies the timer output @@ -736,7 +858,7 @@ config STM32_TIM5_PWM default n depends on STM32_TIM5 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 5 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM5 @@ -746,6 +868,7 @@ config STM32_TIM5_PWM config STM32_TIM5_CHANNEL int "TIM5 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM5_PWM ---help--- If TIM5 is enabled for PWM usage, you also need specifies the timer output @@ -756,7 +879,7 @@ config STM32_TIM8_PWM default n depends on STM32_TIM8 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 8 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM8 @@ -766,6 +889,7 @@ config STM32_TIM8_PWM config STM32_TIM8_CHANNEL int "TIM8 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM8_PWM ---help--- If TIM8 is enabled for PWM usage, you also need specifies the timer output @@ -776,7 +900,7 @@ config STM32_TIM9_PWM default n depends on STM32_TIM9 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 9 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM9 @@ -786,6 +910,7 @@ config STM32_TIM9_PWM config STM32_TIM9_CHANNEL int "TIM9 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM9_PWM ---help--- If TIM9 is enabled for PWM usage, you also need specifies the timer output @@ -796,7 +921,7 @@ config STM32_TIM10_PWM default n depends on STM32_TIM10 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 10 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM10 @@ -806,6 +931,7 @@ config STM32_TIM10_PWM config STM32_TIM10_CHANNEL int "TIM10 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM10_PWM ---help--- If TIM10 is enabled for PWM usage, you also need specifies the timer output @@ -816,7 +942,7 @@ config STM32_TIM11_PWM default n depends on STM32_TIM11 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 11 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM11 @@ -826,6 +952,7 @@ config STM32_TIM11_PWM config STM32_TIM11_CHANNEL int "TIM11 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM11_PWM ---help--- If TIM11 is enabled for PWM usage, you also need specifies the timer output @@ -836,7 +963,7 @@ config STM32_TIM12_PWM default n depends on STM32_TIM12 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 12 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM12 @@ -846,6 +973,7 @@ config STM32_TIM12_PWM config STM32_TIM12_CHANNEL int "TIM12 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM12_PWM ---help--- If TIM12 is enabled for PWM usage, you also need specifies the timer output @@ -856,7 +984,7 @@ config STM32_TIM13_PWM default n depends on STM32_TIM13 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 13 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM13 @@ -866,6 +994,7 @@ config STM32_TIM13_PWM config STM32_TIM13_CHANNEL int "TIM13 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM13_PWM ---help--- If TIM13 is enabled for PWM usage, you also need specifies the timer output @@ -876,7 +1005,7 @@ config STM32_TIM14_PWM default n depends on STM32_TIM14 ---help--- - Reserve timer 1 for use by PWM + Reserve timer 14 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM14 @@ -886,11 +1015,75 @@ config STM32_TIM14_PWM config STM32_TIM14_CHANNEL int "TIM14 PWM Output Channel" default 1 + range 1 4 depends on STM32_TIM14_PWM ---help--- If TIM14 is enabled for PWM usage, you also need specifies the timer output channel {1,..,4} +config STM32_TIM15_PWM + bool "TIM15 PWM" + default n + depends on STM32_TIM15 + ---help--- + Reserve timer 15 for use by PWM + + Timer devices may be used for different purposes. One special purpose is + to generate modulated outputs for such things as motor control. If STM32_TIM15 + is defined then THIS following may also be defined to indicate that + the timer is intended to be used for pulsed output modulation. + +config STM32_TIM15_CHANNEL + int "TIM15 PWM Output Channel" + default 1 + range 1 2 + depends on STM32_TIM15_PWM + ---help--- + If TIM15 is enabled for PWM usage, you also need specifies the timer output + channel {1,2} + +config STM32_TIM16_PWM + bool "TIM16 PWM" + default n + depends on STM32_TIM16 + ---help--- + Reserve timer 16 for use by PWM + + Timer devices may be used for different purposes. One special purpose is + to generate modulated outputs for such things as motor control. If STM32_TIM16 + is defined then THIS following may also be defined to indicate that + the timer is intended to be used for pulsed output modulation. + +config STM32_TIM16_CHANNEL + int "TIM16 PWM Output Channel" + default 1 + range 1 1 + depends on STM32_TIM16_PWM + ---help--- + If TIM16 is enabled for PWM usage, you also need specifies the timer output + channel {1} + +config STM32_TIM17_PWM + bool "TIM17 PWM" + default n + depends on STM32_TIM17 + ---help--- + Reserve timer 17 for use by PWM + + Timer devices may be used for different purposes. One special purpose is + to generate modulated outputs for such things as motor control. If STM32_TIM17 + is defined then THIS following may also be defined to indicate that + the timer is intended to be used for pulsed output modulation. + +config STM32_TIM17_CHANNEL + int "TIM17 PWM Output Channel" + default 1 + range 1 1 + depends on STM32_TIM17_PWM + ---help--- + If TIM17 is enabled for PWM usage, you also need specifies the timer output + channel {1} + config STM32_TIM1_ADC bool "TIM1 ADC" default n @@ -1233,7 +1426,7 @@ config STM32_TIM2_DAC default n depends on STM32_TIM2 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 2 for use by DAC Timer devices may be used for different purposes. If STM32_TIM2 is defined then the following may also be defined to indicate that the @@ -1264,7 +1457,7 @@ config STM32_TIM3_DAC default n depends on STM32_TIM3 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 3 for use by DAC Timer devices may be used for different purposes. If STM32_TIM3 is defined then the following may also be defined to indicate that the @@ -1295,7 +1488,7 @@ config STM32_TIM4_DAC default n depends on STM32_TIM4 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 4 for use by DAC Timer devices may be used for different purposes. If STM32_TIM4 is defined then the following may also be defined to indicate that the @@ -1326,7 +1519,7 @@ config STM32_TIM5_DAC default n depends on STM32_TIM5 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 5 for use by DAC Timer devices may be used for different purposes. If STM32_TIM5 is defined then the following may also be defined to indicate that the @@ -1357,7 +1550,7 @@ config STM32_TIM6_DAC default n depends on STM32_TIM6 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 6 for use by DAC Timer devices may be used for different purposes. If STM32_TIM6 is defined then the following may also be defined to indicate that the @@ -1388,7 +1581,7 @@ config STM32_TIM7_DAC default n depends on STM32_TIM7 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 7 for use by DAC Timer devices may be used for different purposes. If STM32_TIM7 is defined then the following may also be defined to indicate that the @@ -1419,7 +1612,7 @@ config STM32_TIM8_DAC default n depends on STM32_TIM8 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 8 for use by DAC Timer devices may be used for different purposes. If STM32_TIM8 is defined then the following may also be defined to indicate that the @@ -1450,7 +1643,7 @@ config STM32_TIM9_DAC default n depends on STM32_TIM9 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 9 for use by DAC Timer devices may be used for different purposes. If STM32_TIM9 is defined then the following may also be defined to indicate that the @@ -1481,7 +1674,7 @@ config STM32_TIM10_DAC default n depends on STM32_TIM10 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 10 for use by DAC Timer devices may be used for different purposes. If STM32_TIM10 is defined then the following may also be defined to indicate that the @@ -1512,7 +1705,7 @@ config STM32_TIM11_DAC default n depends on STM32_TIM11 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 11 for use by DAC Timer devices may be used for different purposes. If STM32_TIM11 is defined then the following may also be defined to indicate that the @@ -1543,7 +1736,7 @@ config STM32_TIM12_DAC default n depends on STM32_TIM12 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 12 for use by DAC Timer devices may be used for different purposes. If STM32_TIM12 is defined then the following may also be defined to indicate that the @@ -1574,7 +1767,7 @@ config STM32_TIM13_DAC default n depends on STM32_TIM13 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 13 for use by DAC Timer devices may be used for different purposes. If STM32_TIM13 is defined then the following may also be defined to indicate that the @@ -1605,7 +1798,7 @@ config STM32_TIM14_DAC default n depends on STM32_TIM14 && STM32_DAC ---help--- - Reserve timer 1 for use by DAC + Reserve timer 14 for use by DAC Timer devices may be used for different purposes. If STM32_TIM14 is defined then the following may also be defined to indicate that the @@ -1992,14 +2185,14 @@ config STM32_OTGFS_NPTXFIFO_SIZE depends on USBHOST && STM32_OTGFS ---help--- Size of the non-periodic Tx FIFO in 32-bit words. Default 96 (384 bytes) - + config STM32_OTGFS_PTXFIFO_SIZE int "Periodic Tx FIFO size" default 128 depends on USBHOST && STM32_OTGFS ---help--- Size of the periodic Tx FIFO in 32-bit words. Default 96 (384 bytes) - + config STM32_OTGFS_DESCSIZE int "Descriptor Size" default 128 @@ -2013,14 +2206,14 @@ config STM32_OTGFS_SOFINTR depends on USBHOST && STM32_OTGFS ---help--- Enable SOF interrupts. Why would you ever want to do that? - + config STM32_USBHOST_REGDEBUG bool "Register-Level Debug" default n depends on USBHOST && STM32_OTGFS ---help--- Enable very low-level register access debug. Depends on DEBUG. - + config STM32_USBHOST_PKTDUMP bool "Packet Dump Debug" default n diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h index 01d6e1ce06..1a684771ec 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h @@ -6,6 +6,8 @@ * Copyright (C) 2012 Michael Smith. All Rights reserved. * Author: Gregory Nutt * Uros Platise + * Michael Smith + * Freddie Chopin * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -49,219 +51,343 @@ * Pre-processor Definitions ************************************************************************************/ -/* TIMERS */ +/* Alternate Pin Functions: */ -#if defined(CONFIG_STM32_TIM1_FULL_REMAP) -# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN7) -# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN9) -# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN9) -# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN11) -# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN11) -# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN13) -# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN13) -# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN14) -# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN14) -# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN15) -# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN8) -# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN10) -# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN12) -#elif defined(CONFIG_STM32_TIM1_PARTIAL_REMAP) -# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12) -# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8) -# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8) -# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9) -# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9) -# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10) -# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN10) -# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN11) -# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11) -# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) -# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7) -# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0) -# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1) +/* ADC */ + +#define GPIO_ADC1_IN0 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) +#define GPIO_ADC1_IN1 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN1) +#define GPIO_ADC1_IN2 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN2) +#define GPIO_ADC1_IN3 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) +#define GPIO_ADC1_IN4 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN4) +#define GPIO_ADC1_IN5 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN5) +#define GPIO_ADC1_IN6 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN6) +#define GPIO_ADC1_IN7 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN7) +#define GPIO_ADC1_IN8 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN0) +#define GPIO_ADC1_IN9 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN1) +#define GPIO_ADC1_IN10 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN0) +#define GPIO_ADC1_IN11 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN1) +#define GPIO_ADC1_IN12 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN2) +#define GPIO_ADC1_IN13 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN3) +#define GPIO_ADC1_IN14 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN4) +#define GPIO_ADC1_IN15 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN5) + +/* CEC */ +#if defined(CONFIG_STM32_CEC_REMAP) +# define GPIO_CEC (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN10) #else -# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12) -# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8) -# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8) -# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9) -# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9) -# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10) -# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN10) -# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN11) -# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11) -# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN12) -# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13) -# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) -# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15) +# define GPIO_CEC (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN8) #endif -#if defined(CONFIG_STM32_TIM2_FULL_REMAP) -# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) -# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) -# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15) -# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN3) -# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3) -# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10) -# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) -# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11) -# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11) -#elif defined(CONFIG_STM32_TIM2_PARTIAL_REMAP_1) -# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) -# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) -# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15) -# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN3) -# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3) -# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2) -# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3) -#elif defined(CONFIG_STM32_TIM2_PARTIAL_REMAP_2) -# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0) -# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) -# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1) -# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10) -# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) -# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11) -# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11) -#else -# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0) -# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) -# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1) -# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2) -# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3) -#endif +/* DAC + * Note from RM0041, 11.2: "Once the DAC channelx is enabled, the corresponding + * GPIO pin (PA4 or PA5) is automatically connected to the analog converter + * output (DAC_OUTx). In order to avoid parasitic consumption, the PA4 or PA5 + * pin should first be configured to analog (AIN)." + */ -#if defined(CONFIG_STM32_TIM3_FULL_REMAP) -# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN6) -# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN6) -# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN7) -# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN7) -# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN8) -# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN8) -# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN9) -# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN9) -#elif defined(CONFIG_STM32_TIM3_PARTIAL_REMAP) -# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4) -# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN4) -# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5) -# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) -# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) -# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0) -# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) -# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1) -#else -# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) -# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6) -# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) -# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7) -# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) -# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0) -# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) -# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1) -#endif +#define GPIO_DAC_OUT1 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN4) +#define GPIO_DAC_OUT2 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN5) -#if defined(CONFIG_STM32_TIM4_REMAP) -# define GPIO_TIM4_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN12) -# define GPIO_TIM4_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN12) -# define GPIO_TIM4_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN13) -# define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN13) -# define GPIO_TIM4_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN14) -# define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN14) -# define GPIO_TIM4_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN15) -# define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN15) -#else -# define GPIO_TIM4_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN6) -# define GPIO_TIM4_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6) -# define GPIO_TIM4_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN7) -# define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7) -# define GPIO_TIM4_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN8) -# define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8) -# define GPIO_TIM4_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9) -# define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9) -#endif +/* FSMC */ -/* USART */ - -#if defined(CONFIG_STM32_USART1_REMAP) -# define GPIO_USART1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6) -# define GPIO_USART1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN7) -#else -# define GPIO_USART1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9) -# define GPIO_USART1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10) -#endif - -#if defined(CONFIG_STM32_USART2_REMAP) -# define GPIO_USART2_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN3) -# define GPIO_USART2_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN4) -# define GPIO_USART2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN5) -# define GPIO_USART2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN6) -# define GPIO_USART2_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN7) -#else -# define GPIO_USART2_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -# define GPIO_USART2_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1) -# define GPIO_USART2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2) -# define GPIO_USART2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -# define GPIO_USART2_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4) -#endif - -#if defined(CONFIG_STM32_USART3_FULL_REMAP) -# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN8) -# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN9) -# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN10) -# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN11) -# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN12) -#elif defined(CONFIG_STM32_USART3_PARTIAL_REMAP) -# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10) -# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN11) -# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12) -# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13) -# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) -#else -# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) -# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11) -# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) -# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13) -# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) -#endif - -/* SPI */ - -#if defined(CONFIG_STM32_SPI1_REMAP) -# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) -# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3) -# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4) -# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) -#else -# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4) -# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN5) -# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6) -# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7) -#endif - -#define GPIO_SPI2_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) -#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13) -#define GPIO_SPI2_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) -#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15) +/* TODO - VL devices in 100- and 144-pin packages have FSMC */ /* I2C */ #if defined(CONFIG_STM32_I2C1_REMAP) -# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8) -# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9) +# define GPIO_I2C1_SCL (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN8) +# define GPIO_I2C1_SDA (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN9) #else -# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6) -# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7) +# define GPIO_I2C1_SCL (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN6) +# define GPIO_I2C1_SDA (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN7) #endif -#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) +#define GPIO_I2C1_SMBA (GPIO_ALT | GPIO_CNF_INFLOAT | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN5) -#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) -#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11) -#define GPIO_I2C2_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) +#define GPIO_I2C2_SCL (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN11) +#define GPIO_I2C2_SMBA (GPIO_ALT | GPIO_CNF_INFLOAT | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN12) + +/* SPI */ + +#if defined(CONFIG_STM32_SPI1_REMAP) +# define GPIO_SPI1_NSS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN15) +# define GPIO_SPI1_SCK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN3) +# define GPIO_SPI1_MISO (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN4) +# define GPIO_SPI1_MOSI (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN5) +#else +# define GPIO_SPI1_NSS (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN4) +# define GPIO_SPI1_SCK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN5) +# define GPIO_SPI1_MISO (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN6) +# define GPIO_SPI1_MOSI (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN7) +#endif + +#define GPIO_SPI2_NSS (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN12) +#define GPIO_SPI2_SCK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN13) +#define GPIO_SPI2_MISO (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN14) +#define GPIO_SPI2_MOSI (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN15) + +#define GPIO_SPI3_NSS (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN15) +#define GPIO_SPI3_SCK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN3) +#define GPIO_SPI3_MISO (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN4) +#define GPIO_SPI3_MOSI (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN5) + +/* TIMERS */ + +#if defined(CONFIG_STM32_TIM1_FULL_REMAP) +# define GPIO_TIM1_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN7) +# define GPIO_TIM1_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN9) +# define GPIO_TIM1_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN9) +# define GPIO_TIM1_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN11) +# define GPIO_TIM1_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN11) +# define GPIO_TIM1_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN13) +# define GPIO_TIM1_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN13) +# define GPIO_TIM1_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN14) +# define GPIO_TIM1_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN14) +# define GPIO_TIM1_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN15) +# define GPIO_TIM1_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN8) +# define GPIO_TIM1_CH2N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN10) +# define GPIO_TIM1_CH3N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN12) +#elif defined(CONFIG_STM32_TIM1_PARTIAL_REMAP) +# define GPIO_TIM1_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN12) +# define GPIO_TIM1_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN8) +# define GPIO_TIM1_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN8) +# define GPIO_TIM1_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN9) +# define GPIO_TIM1_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN9) +# define GPIO_TIM1_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN10) +# define GPIO_TIM1_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN10) +# define GPIO_TIM1_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN11) +# define GPIO_TIM1_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN11) +# define GPIO_TIM1_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN6) +# define GPIO_TIM1_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN7) +# define GPIO_TIM1_CH2N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN0) +# define GPIO_TIM1_CH3N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN1) +#else +# define GPIO_TIM1_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN12) +# define GPIO_TIM1_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN8) +# define GPIO_TIM1_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN8) +# define GPIO_TIM1_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN9) +# define GPIO_TIM1_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN9) +# define GPIO_TIM1_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN10) +# define GPIO_TIM1_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN10) +# define GPIO_TIM1_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN11) +# define GPIO_TIM1_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN11) +# define GPIO_TIM1_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN12) +# define GPIO_TIM1_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN13) +# define GPIO_TIM1_CH2N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN14) +# define GPIO_TIM1_CH3N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN15) +#endif + +#if defined(CONFIG_STM32_TIM2_FULL_REMAP) +# define GPIO_TIM2_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN15) +# define GPIO_TIM2_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN15) +# define GPIO_TIM2_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN15) +# define GPIO_TIM2_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN3) +# define GPIO_TIM2_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN3) +# define GPIO_TIM2_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN10) +# define GPIO_TIM2_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN10) +# define GPIO_TIM2_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN11) +# define GPIO_TIM2_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN11) +#elif defined(CONFIG_STM32_TIM2_PARTIAL_REMAP_1) +# define GPIO_TIM2_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN15) +# define GPIO_TIM2_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN15) +# define GPIO_TIM2_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN15) +# define GPIO_TIM2_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN3) +# define GPIO_TIM2_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN3) +# define GPIO_TIM2_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN2) +# define GPIO_TIM2_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN2) +# define GPIO_TIM2_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) +# define GPIO_TIM2_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN3) +#elif defined(CONFIG_STM32_TIM2_PARTIAL_REMAP_2) +# define GPIO_TIM2_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) +# define GPIO_TIM2_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) +# define GPIO_TIM2_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN0) +# define GPIO_TIM2_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN1) +# define GPIO_TIM2_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN1) +# define GPIO_TIM2_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN10) +# define GPIO_TIM2_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN10) +# define GPIO_TIM2_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN11) +# define GPIO_TIM2_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN11) +#else +# define GPIO_TIM2_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) +# define GPIO_TIM2_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) +# define GPIO_TIM2_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN0) +# define GPIO_TIM2_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN1) +# define GPIO_TIM2_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN1) +# define GPIO_TIM2_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN2) +# define GPIO_TIM2_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN2) +# define GPIO_TIM2_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) +# define GPIO_TIM2_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN3) +#endif + +#if defined(CONFIG_STM32_TIM3_FULL_REMAP) +# define GPIO_TIM3_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN6) +# define GPIO_TIM3_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN6) +# define GPIO_TIM3_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN7) +# define GPIO_TIM3_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN7) +# define GPIO_TIM3_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN8) +# define GPIO_TIM3_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN8) +# define GPIO_TIM3_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN9) +# define GPIO_TIM3_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN9) +#elif defined(CONFIG_STM32_TIM3_PARTIAL_REMAP) +# define GPIO_TIM3_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN4) +# define GPIO_TIM3_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN4) +# define GPIO_TIM3_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN5) +# define GPIO_TIM3_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN5) +# define GPIO_TIM3_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN0) +# define GPIO_TIM3_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN0) +# define GPIO_TIM3_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN1) +# define GPIO_TIM3_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN1) +#else +# define GPIO_TIM3_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN6) +# define GPIO_TIM3_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN6) +# define GPIO_TIM3_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN7) +# define GPIO_TIM3_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN7) +# define GPIO_TIM3_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN0) +# define GPIO_TIM3_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN0) +# define GPIO_TIM3_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN1) +# define GPIO_TIM3_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN1) +#endif + +#if defined(CONFIG_STM32_TIM4_REMAP) +# define GPIO_TIM4_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN12) +# define GPIO_TIM4_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN12) +# define GPIO_TIM4_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN13) +# define GPIO_TIM4_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN13) +# define GPIO_TIM4_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN14) +# define GPIO_TIM4_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN14) +# define GPIO_TIM4_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN15) +# define GPIO_TIM4_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN15) +#else +# define GPIO_TIM4_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN6) +# define GPIO_TIM4_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN6) +# define GPIO_TIM4_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN7) +# define GPIO_TIM4_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN7) +# define GPIO_TIM4_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN8) +# define GPIO_TIM4_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN8) +# define GPIO_TIM4_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN9) +# define GPIO_TIM4_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN9) +#endif + +#define GPIO_TIM5_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) +#define GPIO_TIM5_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN0) +#define GPIO_TIM5_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN1) +#define GPIO_TIM5_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN1) +#define GPIO_TIM5_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN2) +#define GPIO_TIM5_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN2) +#define GPIO_TIM5_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) +#define GPIO_TIM5_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN3) + +#if defined(CONFIG_STM32_TIM12_REMAP) +# define GPIO_TIM12_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN12) +# define GPIO_TIM12_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN12) +# define GPIO_TIM12_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN13) +# define GPIO_TIM12_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN13) +#else +# define GPIO_TIM12_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN4) +# define GPIO_TIM12_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN4) +# define GPIO_TIM12_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN5) +# define GPIO_TIM12_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN5) +#endif + +#if defined(CONFIG_STM32_TIM13_REMAP) +# define GPIO_TIM13_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN0) +# define GPIO_TIM13_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN0) +#else +# define GPIO_TIM13_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN8) +# define GPIO_TIM13_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN8) +#endif + +#if defined(CONFIG_STM32_TIM14_REMAP) +# define GPIO_TIM14_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN1) +# define GPIO_TIM14_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN1) +#else +# define GPIO_TIM14_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN9) +# define GPIO_TIM14_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN9) +#endif + +#if defined(CONFIG_STM32_TIM15_REMAP) +# define GPIO_TIM15_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN14) +# define GPIO_TIM15_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN14) +# define GPIO_TIM15_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN15) +# define GPIO_TIM15_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN15) +#else +# define GPIO_TIM15_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN2) +# define GPIO_TIM15_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN2) +# define GPIO_TIM15_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) +# define GPIO_TIM15_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN3) +#endif +#define GPIO_TIM15_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN9) +#define GPIO_TIM15_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN15) + +#if defined(CONFIG_STM32_TIM16_REMAP) +# define GPIO_TIM16_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN6) +# define GPIO_TIM16_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN6) +#else +# define GPIO_TIM16_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN8) +# define GPIO_TIM16_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN8) +#endif +#define GPIO_TIM16_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN5) +#define GPIO_TIM16_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN6) + +#if defined(CONFIG_STM32_TIM17_REMAP) +# define GPIO_TIM17_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN7) +# define GPIO_TIM17_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN7) +#else +# define GPIO_TIM17_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN9) +# define GPIO_TIM17_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN9) +#endif +#define GPIO_TIM17_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN10) +#define GPIO_TIM17_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN7) + +/* USART */ + +#if defined(CONFIG_STM32_USART1_REMAP) +# define GPIO_USART1_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN6) +# define GPIO_USART1_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN7) +#else +# define GPIO_USART1_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN9) +# define GPIO_USART1_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN10) +#endif + +#if defined(CONFIG_STM32_USART2_REMAP) +# define GPIO_USART2_CTS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN3) +# define GPIO_USART2_RTS (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN4) +# define GPIO_USART2_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN5) +# define GPIO_USART2_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN6) +# define GPIO_USART2_CK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN7) +#else +# define GPIO_USART2_CTS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) +# define GPIO_USART2_RTS (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN1) +# define GPIO_USART2_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN2) +# define GPIO_USART2_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) +# define GPIO_USART2_CK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN4) +#endif + +#if defined(CONFIG_STM32_USART3_FULL_REMAP) +# define GPIO_USART3_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN8) +# define GPIO_USART3_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN9) +# define GPIO_USART3_CK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN10) +# define GPIO_USART3_CTS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN11) +# define GPIO_USART3_RTS (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN12) +#elif defined(CONFIG_STM32_USART3_PARTIAL_REMAP) +# define GPIO_USART3_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN10) +# define GPIO_USART3_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN11) +# define GPIO_USART3_CK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN12) +# define GPIO_USART3_CTS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN13) +# define GPIO_USART3_RTS (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN14) +#else +# define GPIO_USART3_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN10) +# define GPIO_USART3_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN11) +# define GPIO_USART3_CK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN12) +# define GPIO_USART3_CTS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN13) +# define GPIO_USART3_RTS (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN14) +#endif + +#define GPIO_UART4_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN10) +#define GPIO_UART4_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN11) + +#define GPIO_UART5_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN12) +#define GPIO_UART5_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN2) #endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F100_PINMAP_H */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h index 817e747f71..699ca4fdc4 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h @@ -222,7 +222,7 @@ #define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) #define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) #define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN8) -#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULLGPIO_PORTA|GPIO_PIN7) +#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) #define GPIO_ETH_RMII_REF_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) #define GPIO_ETH_RMII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4) #define GPIO_ETH_RMII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5) diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h index ae2436a70f..31e51caf07 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h @@ -222,7 +222,7 @@ #define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) #define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) #define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN8) -#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULLGPIO_PORTA|GPIO_PIN7) +#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) #define GPIO_ETH_RMII_REF_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) #define GPIO_ETH_RMII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4) #define GPIO_ETH_RMII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5) diff --git a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c index ed767db77f..ae3fa516ea 100644 --- a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c +++ b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c @@ -228,6 +228,27 @@ static inline void rcc_enableapb1(void) #endif #endif +#ifdef CONFIG_STM32_TIM12 + /* Timer 12 clock enable */ +#ifdef CONFIG_STM32_FORCEPOWER + regval |= RCC_APB1ENR_TIM12EN; +#endif +#endif + +#ifdef CONFIG_STM32_TIM13 + /* Timer 13 clock enable */ +#ifdef CONFIG_STM32_FORCEPOWER + regval |= RCC_APB1ENR_TIM13EN; +#endif +#endif + +#ifdef CONFIG_STM32_TIM14 + /* Timer 14 clock enable */ +#ifdef CONFIG_STM32_FORCEPOWER + regval |= RCC_APB1ENR_TIM14EN; +#endif +#endif + #ifdef CONFIG_STM32_WWDG /* Window Watchdog clock enable */ @@ -319,6 +340,13 @@ static inline void rcc_enableapb1(void) regval |= RCC_APB1ENR_DACEN; #endif + +#ifdef CONFIG_STM32_CEC + /* CEC clock enable */ + + regval |= RCC_APB1ENR_CECEN; +#endif + putreg32(regval, STM32_RCC_APB1ENR); } @@ -408,6 +436,28 @@ static inline void rcc_enableapb2(void) regval |= RCC_APB2ENR_ADC3EN; #endif + +#ifdef CONFIG_STM32_TIM15 + /* TIM15 Timer clock enable */ +#ifdef CONFIG_STM32_FORCEPOWER + regval |= RCC_APB2ENR_TIM15EN; +#endif +#endif + +#ifdef CONFIG_STM32_TIM16 + /* TIM16 Timer clock enable */ +#ifdef CONFIG_STM32_FORCEPOWER + regval |= RCC_APB2ENR_TIM16EN; +#endif +#endif + +#ifdef CONFIG_STM32_TIM17 + /* TIM17 Timer clock enable */ +#ifdef CONFIG_STM32_FORCEPOWER + regval |= RCC_APB2ENR_TIM17EN; +#endif +#endif + putreg32(regval, STM32_RCC_APB2ENR); } diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig index 600e74ef44..c03102409d 100644 --- a/nuttx/configs/Kconfig +++ b/nuttx/configs/Kconfig @@ -41,7 +41,7 @@ config ARCH_BOARD_C5471EVM ---help--- 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. + 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-nuttx-elf toolchain*. This port is complete and verified. @@ -79,7 +79,7 @@ config ARCH_BOARD_EA3131 select ARCH_HAVE_LEDS select ARCH_HAVE_BUTTONS ---help--- - Embedded Artists EA3131 Development board. This board is based on the + Embedded Artists EA3131 Development board. This board is based on the an NXP LPC3131 MCU. This OS is built with the arm-nuttx-elf toolchain*. STATUS: This port is complete and mature. @@ -89,7 +89,7 @@ config ARCH_BOARD_EA3152 select ARCH_HAVE_LEDS select ARCH_HAVE_BUTTONS ---help--- - Embedded Artists EA3152 Development board. This board is based on the + Embedded Artists EA3152 Development board. This board is based on the 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. @@ -99,7 +99,7 @@ config ARCH_BOARD_EAGLE100 depends on ARCH_CHIP_LM3S6918 select ARCH_HAVE_LEDS ---help--- - Micromint Eagle-100 Development board. This board is based on the + 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-nuttx-elf toolchain*. STATUS: This port is complete and mature. @@ -108,7 +108,7 @@ config ARCH_BOARD_EKK_LM3S9B96 depends on ARCH_CHIP_LM3S9B96 select ARCH_HAVE_LEDS ---help--- - TI/Stellaris EKK-LM3S9B96 board. This board is based on the + TI/Stellaris EKK-LM3S9B96 board. This board is based on the an EKK-LM3S9B96 which is a Cortex-M3. config ARCH_BOARD_EZ80F910200KITG @@ -182,7 +182,7 @@ config ARCH_BOARD_LM3S6965EK depends on ARCH_CHIP_LM3S6965 select ARCH_HAVE_LEDS ---help--- - Stellaris LM3S6965 Evaluation Kit. This board is based on the + 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-nuttx-elf toolchain*. STATUS: This port is complete and mature. @@ -274,7 +274,7 @@ config ARCH_BOARD_NTOSD_DM320 toolchain*: see http://wiki.neurostechnology.com/index.php/OSD_1.0_Developer_Home - + There are some differences between the Dev Board and the currently available commercial v1.0 Boards. See @@ -386,7 +386,7 @@ config ARCH_BOARD_RGMP bool "RGMP" depends on ARCH_RGMP ---help--- - RGMP stands for RTOS and GPOS on Multi-Processor. RGMP is a project for + RGMP stands for RTOS and GPOS on Multi-Processor. RGMP is a project for running GPOS and RTOS simultaneously on multi-processor platforms. You can port your favorite RTOS to RGMP together with an unmodified Linux to form a hybrid operating system. This makes your application able to use both RTOS @@ -457,6 +457,15 @@ config ARCH_BOARD_STM3240G_EVAL microcontroller (ARM Cortex-M4 with FPU). This port uses a GNU Cortex-M4 toolchain (such as CodeSourcery). +config ARCH_BOARD_STM32F100RC_GENERIC + bool "STMicro STM32F100RC generic board" + depends on ARCH_CHIP_STM32F100RC + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS + ---help--- + STMicro STM32F100RC generic board. + config ARCH_BOARD_STM32F4_DISCOVERY bool "STMicro STM32F4-Discovery board" depends on ARCH_CHIP_STM32F407VG @@ -464,7 +473,7 @@ config ARCH_BOARD_STM32F4_DISCOVERY select ARCH_HAVE_BUTTONS select ARCH_HAVE_IRQBUTTONS ---help--- - STMicro STM32F4-Discovery board boased on the STMIcro STM32F407VGT6 MCU. + STMicro STM32F4-Discovery board based on the STMicro STM32F407VGT6 MCU. config ARCH_BOARD_SUREPIC32MX bool "Sure PIC32MX boards" @@ -534,7 +543,7 @@ config ARCH_BOARD_XTRS depends on ARCH_CHIP_Z80 ---help--- TRS80 Model 3. This port uses a vintage computer based on the Z80. - An emulator for this computer is available to run TRS80 programs on a + An emulator for this computer is available to run TRS80 programs on a linux platform (http://www.tim-mann.org/xtrs.html). config ARCH_BOARD_Z16F2800100ZCOG @@ -595,66 +604,67 @@ endchoice config ARCH_BOARD string - default "amber" if ARCH_BOARD_AMBER - default "avr32dev1" if ARCH_BOARD_AVR32DEV1 - default "c5471evm" if ARCH_BOARD_C5471EVM - default "compal_e88" if ARCH_BOARD_COMPALE88 - default "compal_e99" if ARCH_BOARD_COMPALE99 - default "demo9s12ne64" if ARCH_BOARD_DEMOS92S12NEC64 - default "ea3131" if ARCH_BOARD_EA3131 - default "ea3152" if ARCH_BOARD_EA3152 - default "eagle100" if ARCH_BOARD_EAGLE100 - default "ekk-lm3s9b96" if ARCH_BOARD_EKK_LM3S9B96 - default "ez80f0910200kitg" if ARCH_BOARD_EZ80F910200KITG - default "ez80f0910200zco" if ARCH_BOARD_EZ80F910200ZCO - default "fire-stm32v2" if ARCH_BOARD_FIRE_STM32 - default "hymini-stm32v" if ARCH_BOARD_HYMINI_STM32V - default "kwikstik-k40" if ARCH_BOARD_KWIKSTIK_K40 - default "lincoln60" if ARCH_BOARD_LINCOLN60 - default "lm3s6432-s2e" if ARCH_BOARD_LM3S6432S2E - default "lm3s6965-ek" if ARCH_BOARD_LM3S6965EK - default "lm3s8962-ek" if ARCH_BOARD_LM3S8962EK - default "lpc4330-xplorer" if ARCH_BOARD_LPC4330_XPLORER - default "lpcxpresso-lpc1768" if ARCH_BOARD_LPCXPRESSO - default "m68322evb" if ARCH_BOARD_M68332EVB - default "mbed" if ARCH_BOARD_MBED - default "mcu123-lpc214x" if ARCH_BOARD_MCU123 - default "micropendous3" if ARCH_BOARD_MICROPENDOUS3 - default "mirtoo" if ARCH_BOARD_MIRTOO - default "mx1ads" if ARCH_BOARD_MX1ADS - default "ne64badge" if ARCH_BOARD_NE64BADGE - default "ntosd-dm320" if ARCH_BOARD_NTOSD_DM320 - default "nucleus2g" if ARCH_BOARD_NUCLEUS2G - default "olimex-lpc1766stk" if ARCH_BOARD_LPC1766STK - default "olimex-lpc2378" if ARCH_BOARD_OLIMEXLPC2378 - default "olimex-stm32-p107" if ARCH_BOARD_OLIMEX_STM32P107 - default "olimex-strp711" if ARCH_BOARD_OLIMEX_STRP711 - default "pcblogic-pic32mx" if ARCH_BOARD_PCBLOGICPIC32MX - default "pic32-starterkit" if ARCH_BOARD_PIC32_STARTERKIT - default "pic32mx7mmb" if ARCH_BOARD_PIC32_PIC32MX7MMB - default "pjrc-8051" if ARCH_BOARD_PJRC_87C52 - default "qemu-i486" if ARCH_BOARD_QEMU_I486 - default "rgmp" if ARCH_BOARD_RGMP - default "sam3u-ek" if ARCH_BOARD_SAM3UEK - default "shenzhou" if ARCH_BOARD_SHENZHOU - default "skp16c26" if ARCH_BOARD_SKP16C26 - default "stm3210e-eval" if ARCH_BOARD_STM3210E_EVAL - default "stm3220g-eval" if ARCH_BOARD_STM3220G_EVAL - default "stm3240g-eval" if ARCH_BOARD_STM3240G_EVAL - default "stm32f4discovery" if ARCH_BOARD_STM32F4_DISCOVERY - default "sure-pic32mx" if ARCH_BOARD_SUREPIC32MX - default "teensy" if ARCH_BOARD_TEENSY - default "twr-k60n512" if ARCH_BOARD_TWR_K60N512 - default "ubw32" if ARCH_BOARD_UBW32 - default "us7032evb1" if ARCH_BOARD_US7032EVB1 - default "vsn" if ARCH_BOARD_VSN - default "xtrs" if ARCH_BOARD_XTRS - default "z16f2800100zcog" if ARCH_BOARD_Z16F2800100ZCOG - default "z80sim" if ARCH_BOARD_Z80SIM - default "z8encore000zco" if ARCH_BOARD_Z8ENCORE000ZCO - default "z8f64200100kit" if ARCH_BOARD_Z8F64200100KI - default "sim" if ARCH_BOARD_SIM - default "" if ARCH_BOARD_CUSTOM + default "amber" if ARCH_BOARD_AMBER + default "avr32dev1" if ARCH_BOARD_AVR32DEV1 + default "c5471evm" if ARCH_BOARD_C5471EVM + default "compal_e88" if ARCH_BOARD_COMPALE88 + default "compal_e99" if ARCH_BOARD_COMPALE99 + default "demo9s12ne64" if ARCH_BOARD_DEMOS92S12NEC64 + default "ea3131" if ARCH_BOARD_EA3131 + default "ea3152" if ARCH_BOARD_EA3152 + default "eagle100" if ARCH_BOARD_EAGLE100 + default "ekk-lm3s9b96" if ARCH_BOARD_EKK_LM3S9B96 + default "ez80f0910200kitg" if ARCH_BOARD_EZ80F910200KITG + default "ez80f0910200zco" if ARCH_BOARD_EZ80F910200ZCO + default "fire-stm32v2" if ARCH_BOARD_FIRE_STM32 + default "hymini-stm32v" if ARCH_BOARD_HYMINI_STM32V + default "kwikstik-k40" if ARCH_BOARD_KWIKSTIK_K40 + default "lincoln60" if ARCH_BOARD_LINCOLN60 + default "lm3s6432-s2e" if ARCH_BOARD_LM3S6432S2E + default "lm3s6965-ek" if ARCH_BOARD_LM3S6965EK + default "lm3s8962-ek" if ARCH_BOARD_LM3S8962EK + default "lpc4330-xplorer" if ARCH_BOARD_LPC4330_XPLORER + default "lpcxpresso-lpc1768" if ARCH_BOARD_LPCXPRESSO + default "m68322evb" if ARCH_BOARD_M68332EVB + default "mbed" if ARCH_BOARD_MBED + default "mcu123-lpc214x" if ARCH_BOARD_MCU123 + default "micropendous3" if ARCH_BOARD_MICROPENDOUS3 + default "mirtoo" if ARCH_BOARD_MIRTOO + default "mx1ads" if ARCH_BOARD_MX1ADS + default "ne64badge" if ARCH_BOARD_NE64BADGE + default "ntosd-dm320" if ARCH_BOARD_NTOSD_DM320 + default "nucleus2g" if ARCH_BOARD_NUCLEUS2G + default "olimex-lpc1766stk" if ARCH_BOARD_LPC1766STK + default "olimex-lpc2378" if ARCH_BOARD_OLIMEXLPC2378 + default "olimex-stm32-p107" if ARCH_BOARD_OLIMEX_STM32P107 + default "olimex-strp711" if ARCH_BOARD_OLIMEX_STRP711 + default "pcblogic-pic32mx" if ARCH_BOARD_PCBLOGICPIC32MX + default "pic32-starterkit" if ARCH_BOARD_PIC32_STARTERKIT + default "pic32mx7mmb" if ARCH_BOARD_PIC32_PIC32MX7MMB + default "pjrc-8051" if ARCH_BOARD_PJRC_87C52 + default "qemu-i486" if ARCH_BOARD_QEMU_I486 + default "rgmp" if ARCH_BOARD_RGMP + default "sam3u-ek" if ARCH_BOARD_SAM3UEK + default "shenzhou" if ARCH_BOARD_SHENZHOU + default "skp16c26" if ARCH_BOARD_SKP16C26 + default "stm3210e-eval" if ARCH_BOARD_STM3210E_EVAL + default "stm3220g-eval" if ARCH_BOARD_STM3220G_EVAL + default "stm3240g-eval" if ARCH_BOARD_STM3240G_EVAL + default "stm32f100rc_generic" if ARCH_BOARD_STM32F100RC_GENERIC + default "stm32f4discovery" if ARCH_BOARD_STM32F4_DISCOVERY + default "sure-pic32mx" if ARCH_BOARD_SUREPIC32MX + default "teensy" if ARCH_BOARD_TEENSY + default "twr-k60n512" if ARCH_BOARD_TWR_K60N512 + default "ubw32" if ARCH_BOARD_UBW32 + default "us7032evb1" if ARCH_BOARD_US7032EVB1 + default "vsn" if ARCH_BOARD_VSN + default "xtrs" if ARCH_BOARD_XTRS + default "z16f2800100zcog" if ARCH_BOARD_Z16F2800100ZCOG + default "z80sim" if ARCH_BOARD_Z80SIM + default "z8encore000zco" if ARCH_BOARD_Z8ENCORE000ZCO + default "z8f64200100kit" if ARCH_BOARD_Z8F64200100KI + default "sim" if ARCH_BOARD_SIM + default "" if ARCH_BOARD_CUSTOM comment "Common Board Options" @@ -849,6 +859,9 @@ endif if ARCH_BOARD_STM3240G_EVAL source "configs/stm3240g-eval/Kconfig" endif +if ARCH_BOARD_STM32F100RC_GENERIC +source "configs/stm32f100_generic/Kconfig" +endif if ARCH_BOARD_STM32F4_DISCOVERY source "configs/stm32f4discovery/Kconfig" endif diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index cca4d7f324..81749f29fc 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -317,7 +317,7 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_RR_INTERVAL - The round robin timeslice will be set this number of milliseconds; Round robin scheduling can be disabled by setting this value to zero. - CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in + CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in scheduler to monitor system performance CONFIG_TASK_NAME_SIZE - Specifies that maximum size of a task name to save in the TCB. Useful if scheduler @@ -345,7 +345,7 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority inheritance is enabled. It defines the maximum number of different threads (minus one) that can take counts on a - semaphore with priority inheritance support. This may be + semaphore with priority inheritance support. This may be set to zero if priority inheritance is disabled OR if you are only using semaphores as mutexes (only one holder) OR if no more than two threads participate using a counting @@ -436,7 +436,7 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_ELF_STACKSIZE - This is the default stack size that will will be used when starting ELF binaries. CONFIG_ELF_BUFFERSIZE - This is an I/O buffer that is used to access - the ELF file. Variable length items will need to be read (such as + the ELF file. Variable length items will need to be read (such as symbol names). This is really just this initial size of the buffer; it will be reallocated as necessary to hold large symbol names). Default: 128 @@ -532,7 +532,7 @@ defconfig -- This is a configuration file similar to the Linux from the end of RAM for page tables or other system usage. The configuration settings and linker directives must be cognizant of that: CONFIG_PAGING_NDATA should be defined to prevent the data region from - extending all the way to the end of memory. + extending all the way to the end of memory. CONFIG_PAGING_DEFPRIO - The default, minimum priority of the page fill worker thread. The priority of the page fill work thread will be boosted boosted dynmically so that it matches the priority of the task on behalf @@ -546,7 +546,7 @@ defconfig -- This is a configuration file similar to the Linux transfer is completed. Default: Undefined (non-blocking). CONFIG_PAGING_WORKPERIOD - The page fill worker thread will wake periodically even if there is no mapping to do. This selection controls that wake-up - period (in microseconds). This wake-up a failsafe that will handle any + period (in microseconds). This wake-up a failsafe that will handle any cases where a single is lost (that would really be a bug and shouldn't happen!) and also supports timeouts for case of non-blocking, asynchronous fills (see CONFIG_PAGING_TIMEOUT_TICKS). @@ -558,7 +558,7 @@ defconfig -- This is a configuration file similar to the Linux Some architecture-specific settings. Defaults are architecture specific. If you don't know what you are doing, it is best to leave these undefined and try the system defaults: - + CONFIG_PAGING_VECPPAGE - This the physical address of the page in memory to be mapped to the vector address. CONFIG_PAGING_VECL2PADDR - This is the physical address of the L2 @@ -581,7 +581,7 @@ defconfig -- This is a configuration file similar to the Linux devices. CONFIG_PAGING_SDSLOT identifies the slot number of the SD device to initialize. This must be undefined if SD is not being used. This should be defined to be zero for the typical device that has - only a single slot (See CONFIG_MMCSD_NSLOTS). If defined, + only a single slot (See CONFIG_MMCSD_NSLOTS). If defined, CONFIG_PAGING_SDSLOT will instruct certain board-specific logic to initialize the media in this SD slot. CONFIG_PAGING_M25PX - Use the m25px.c FLASH driver. If this is selected, @@ -762,7 +762,7 @@ defconfig -- This is a configuration file similar to the Linux If CONFIG_ARCH_ROMGETC is defined, then the architecture logic must export the function up_romgetc(). up_romgetc() will simply read one byte of data from the instruction space. - + If CONFIG_ARCH_ROMGETC, certain C stdio functions are effected: (1) All format strings in printf, fprintf, sprintf, etc. are assumed to lie in FLASH (string arguments for %s are still assumed @@ -832,7 +832,7 @@ defconfig -- This is a configuration file similar to the Linux much sense in supporting FAT date and time unless you have a hardware RTC or other way to get the time and date. CONFIG_FS_NXFFS: Enable NuttX FLASH file system (NXFF) support. - CONFIG_NXFFS_ERASEDSTATE: The erased state of FLASH. + CONFIG_NXFFS_ERASEDSTATE: The erased state of FLASH. This must have one of the values of 0xff or 0x00. Default: 0xff. CONFIG_NXFFS_PACKTHRESHOLD: When packing flash file data, @@ -986,7 +986,7 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_INPUT Enables general support for input devices - + CONFIG_INPUT_TSC2007 If CONFIG_INPUT is selected, then this setting will enable building of the TI TSC2007 touchscreen driver. @@ -1001,14 +1001,14 @@ defconfig -- This is a configuration file similar to the Linux Enables support for the SPI interface (not currenly supported) CONFIG_STMPE811_I2C Enables support for the I2C interface - CONFIG_STMPE811_MULTIPLE + CONFIG_STMPE811_MULTIPLE Can be defined to support multiple STMPE811 devices on board. CONFIG_STMPE811_ACTIVELOW Interrupt is generated by an active low signal (or falling edge). CONFIG_STMPE811_EDGE Interrupt is generated on an edge (vs. on the active level) CONFIG_STMPE811_NPOLLWAITERS - Maximum number of threads that can be waiting on poll() (ignored if + Maximum number of threads that can be waiting on poll() (ignored if CONFIG_DISABLE_POLL is set). CONFIG_STMPE811_TSC_DISABLE Disable driver touchscreen functionality. @@ -1117,21 +1117,21 @@ defconfig -- This is a configuration file similar to the Linux port. The default data link layer for uIP is Ethernet. If CONFIG_NET_SLIP is defined in the NuttX configuration file, then SLIP will be supported. The basic differences between the SLIP and Ethernet configurations is that - when SLIP is selected: + when SLIP is selected: - * The link level header (that comes before the IP header) is omitted. - * All MAC address processing is suppressed. + * The link level header (that comes before the IP header) is omitted. + * All MAC address processing is suppressed. * ARP is disabled. If CONFIG_NET_SLIP is not selected, then Ethernet will be used (there is no need to define anything special in the configuration file to use - Ethernet -- it is the default). + Ethernet -- it is the default). CONFIG_NET_SLIP -- Enables building of the SLIP driver. SLIP requires at least one IP protocols selected and the following additional network settings: CONFIG_NET_NOINTS and CONFIG_NET_MULTIBUFFER. CONFIG_NET_BUFSIZE *must* be set to 296. Other optional configuration - settings that affect the SLIP driver: CONFIG_NET_STATISTICS. + settings that affect the SLIP driver: CONFIG_NET_STATISTICS. Default: Ethernet If SLIP is selected, then the following SLIP options are available: @@ -1172,7 +1172,7 @@ defconfig -- This is a configuration file similar to the Linux to run before killing them. CONFIG_THTTPD_CHARSET- The default character set name to use with text MIME types. - CONFIG_THTTPD_IOBUFFERSIZE - + CONFIG_THTTPD_IOBUFFERSIZE - CONFIG_THTTPD_INDEX_NAMES - A list of index filenames to check. The files are searched for in this order. CONFIG_AUTH_FILE - The file to use for authentication. If this is @@ -1204,7 +1204,7 @@ defconfig -- This is a configuration file similar to the Linux You can also leave both options undefined, and thttpd will not do anything special about tildes. Enabling both options is an error. Typical values, if they're defined, are "users" for - CONFIG_THTTPD_TILDE_MAP1 and "public_html"forCONFIG_THTTPD_TILDE_MAP2. + CONFIG_THTTPD_TILDE_MAP1 and "public_html"forCONFIG_THTTPD_TILDE_MAP2. CONFIG_THTTPD_GENERATE_INDICES CONFIG_THTTPD_URLPATTERN - If defined, then it will be used to match and verify referrers. @@ -1262,7 +1262,7 @@ defconfig -- This is a configuration file similar to the Linux USB host HID class driver. Requires CONFIG_USBHOST=y, CONFIG_USBHOST_INT_DISABLE=n, CONFIG_NFILE_DESCRIPTORS > 0, CONFIG_SCHED_WORKQUEUE=y, and CONFIG_DISABLE_SIGNALS=n. - + CONFIG_HIDKBD_POLLUSEC Device poll rate in microseconds. Default: 100 milliseconds. CONFIG_HIDKBD_DEFPRIO @@ -1281,7 +1281,7 @@ defconfig -- This is a configuration file similar to the Linux If set to y all 231 possible scancodes will be converted to something. Default: 104 key US keyboard. CONFIG_HIDKBD_NODEBOUNCE - If set to y normal debouncing is disabled. Default: + If set to y normal debouncing is disabled. Default: Debounce enabled (No repeat keys). USB host mass storage class driver. Requires CONFIG_USBHOST=y, @@ -1318,12 +1318,12 @@ defconfig -- This is a configuration file similar to the Linux Configure the CDC serial driver as part of a composite driver (only if CONFIG_USBDEV_COMPOSITE is also defined) CONFIG_CDCACM_IFNOBASE - If the CDC driver is part of a composite device, then this may need to + If the CDC driver is part of a composite device, then this may need to be defined to offset the CDC/ACM interface numbers so that they are unique and contiguous. When used with the Mass Storage driver, the correct value for this offset is zero. CONFIG_CDCACM_STRBASE - If the CDC driver is part of a composite device, then this may need to + If the CDC driver is part of a composite device, then this may need to be defined to offset the CDC/ACM string numbers so that they are unique and contiguous. When used with the Mass Storage driver, the correct value for this offset is four (this value actuallly only needs @@ -1382,13 +1382,13 @@ defconfig -- This is a configuration file similar to the Linux Configure the mass storage driver as part of a composite driver (only if CONFIG_USBDEV_COMPOSITE is also defined) CONFIG_USBMSC_IFNOBASE - If the CDC driver is part of a composite device, then this may need to + If the CDC driver is part of a composite device, then this may need to be defined to offset the mass storage interface number so that it is unique and contiguous. When used with the CDC/ACM driver, the correct value for this offset is two (because of the two CDC/ACM interfaces that will precede it). CONFIG_USBMSC_STRBASE - If the CDC driver is part of a composite device, then this may need to + If the CDC driver is part of a composite device, then this may need to be defined to offset the mass storage string numbers so that they are unique and contiguous. When used with the CDC/ACM driver, the correct value for this offset is four (or perhaps 5 or 6, depending @@ -1596,7 +1596,7 @@ configs/avr32dev1 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. + 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-nuttx-elf toolchain*. This port is complete and verified. @@ -1612,23 +1612,23 @@ configs/demo9s12ne64 is code complete but has not yet been verified. configs/ea3131 - Embedded Artists EA3131 Development board. This board is based on the + Embedded Artists EA3131 Development board. This board is based on the 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 + Embedded Artists EA3152 Development board. This board is based on the 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 + 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-nuttx-elf toolchain*. STATUS: This port is complete and mature. configs/ekk-lm3s9b96 - TI/Stellaris EKK-LM3S9B96 board. This board is based on the + TI/Stellaris EKK-LM3S9B96 board. This board is based on the an EKK-LM3S9B96 which is a Cortex-M3. configs/ez80f0910200kitg @@ -1656,13 +1656,13 @@ configs/kwikstik-k40. configs/lincoln60 NuttX port to the Micromint Lincoln 60 board. - + configs/lm3s6432-s2e Stellaris RDK-S2E Reference Design Kit and the MDL-S2E Ethernet to Serial module. configs/lm3s6965-ek - Stellaris LM3S6965 Evaluation Kit. This board is based on the + 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-nuttx-elf toolchain*. STATUS: This port is complete and mature. @@ -1719,7 +1719,7 @@ configs/ntosd-dm320 toolchain*: see http://wiki.neurostechnology.com/index.php/OSD_1.0_Developer_Home - + There are some differences between the Dev Board and the currently available commercial v1.0 Boards. See @@ -1789,7 +1789,7 @@ configs/qemu-i486 hardwared (Google the Bifferboard). configs/rgmp - RGMP stands for RTOS and GPOS on Multi-Processor. RGMP is a project for + RGMP stands for RTOS and GPOS on Multi-Processor. RGMP is a project for running GPOS and RTOS simultaneously on multi-processor platforms. You can port your favorite RTOS to RGMP together with an unmodified Linux to form a hybrid operating system. This makes your application able to use both RTOS @@ -1830,8 +1830,14 @@ configs/stm3240g-eval microcontroller (ARM Cortex-M4 with FPU). This port uses a GNU Cortex-M4 toolchain (such as CodeSourcery). +configs/stm32f100rc_generic + STMicro STM32F100RC generic board based on STM32F100RC high-density value line + chip. This "generic" configuration is not very usable out-of-box, but can be + used as a starting point to creating new configs with similar STM32 + high-density value line chips. + configs/stm32f4discovery - STMicro STM32F4-Discovery board boased on the STMIcro STM32F407VGT6 MCU. + STMicro STM32F4-Discovery board based on the STMIcro STM32F407VGT6 MCU. configs/sure-pic32mx The "Advanced USB Storage Demo Board," Model DB-DP11215, from Sure @@ -1868,7 +1874,7 @@ configs/vsn configs/xtrs TRS80 Model 3. This port uses a vintage computer based on the Z80. - An emulator for this computer is available to run TRS80 programs on a + An emulator for this computer is available to run TRS80 programs on a linux platform (http://www.tim-mann.org/xtrs.html). configs/z16f2800100zcog @@ -1919,7 +1925,7 @@ And if configs///appconfig exists and your application directory is not in the standard loction (../apps), then you should also specify the location of the application directory on the command line like: - + cd tools ./configure.sh -a / diff --git a/nuttx/configs/stm32f100rc_generic/Kconfig b/nuttx/configs/stm32f100rc_generic/Kconfig new file mode 100644 index 0000000000..7f333d7386 --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/Kconfig @@ -0,0 +1,58 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +if ARCH_BOARD_STM32F100RC_GENERIC +comment "STM32F100RC Generic Hardware Configuration" + +config PM_BUTTONS + bool "PM Button support" + default n + depends on PM && ARCH_IRQBUTTONS + ---help--- + Enable PM button EXTI interrupts to support PM testing + +config PM_BUTTON_ACTIVITY + int "Button PM activity weight" + default 10 + depends on PM_BUTTONS + ---help--- + The activity weight to report to the power management subsystem when a button is pressed. + +config PM_ALARM_SEC + int "PM_STANDBY delay (seconds)" + default 15 + depends on PM && RTC_ALARM + --help--- + Number of seconds to wait in PM_STANDBY before going to PM_STANDBY mode. + +config PM_ALARM_NSEC + int "PM_STANDBY delay (nanoseconds)" + default 0 + depends on PM && RTC_ALARM + --help--- + Number of additional nanoseconds to wait in PM_STANDBY before going to PM_STANDBY mode. + +config PM_SLEEP_WAKEUP + bool "PM_SLEEP wake-up alarm" + default n + depends on PM && RTC_ALARM + --help--- + Wake-up of PM_SLEEP mode after a delay and resume normal operation. + +config PM_SLEEP_WAKEUP_SEC + int "PM_SLEEP delay (seconds)" + default 10 + depends on PM && RTC_ALARM + --help--- + Number of seconds to wait in PM_SLEEP before going to PM_STANDBY mode. + +config PM_SLEEP_WAKEUP_NSEC + int "PM_SLEEP delay (nanoseconds)" + default 0 + depends on PM && RTC_ALARM + --help--- + Number of additional nanoseconds to wait in PM_SLEEP before going to PM_STANDBY mode. + +endif diff --git a/nuttx/configs/stm32f100rc_generic/README.txt b/nuttx/configs/stm32f100rc_generic/README.txt new file mode 100644 index 0000000000..e9959431c2 --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/README.txt @@ -0,0 +1,504 @@ +README +====== + +This README discusses issues unique to NuttX configurations for the STMicro +STM32F100RC generic board. This "generic" configuration is not very usable +out-of-box, but can be used as a starting point to creating new configs with +similar STM32 high-density value line chips. As a bare-minimum this config only +specifies one LED (on PA0) and one button (on PA1), you should change that to +match your hardware (some details below and in source files). + +Contents +======== + + - Development Environment + - GNU Toolchain Options + - IDEs + - NuttX EABI "buildroot" Toolchain + - NuttX OABI "buildroot" Toolchain + - NXFLAT Toolchain + - LEDs + - UARTs + - "STMicro STM32F100RC generic" specific Configuration Options + - Configurations + +Development Environment +======================= + + Either Linux or Cygwin on Windows can be used for the development environment. + The source has been built only using the GNU toolchain (see below). Other + toolchains will likely cause problems. + +GNU Toolchain Options +===================== + + Toolchain Configurations + ------------------------ + The NuttX make system has been modified to support the following different + toolchain options. + + 1. The CodeSourcery GNU toolchain, + 2. The Atollic Toolchain, + 3. The devkitARM GNU toolchain, + 4. Raisonance GNU toolchain, or + 5. The NuttX buildroot Toolchain (see below). + + All testing has been conducted using the CodeSourcery toolchain for Windows. To use + the Atollic, devkitARM, Raisonance GNU, or NuttX buildroot toolchain, you simply need to + add one of the following configuration options to your .config (or defconfig) + file: + + CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux + CONFIG_STM32_ATOLLIC_LITE=y : The free, "Lite" version of Atollic toolchain under Windows + CONFIG_STM32_ATOLLIC_PRO=y : The paid, "Pro" version of Atollic toolchain under Windows + 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) + + If you change the default toolchain, then you may also have to modify the PATH in + the setenv.sh file if your make cannot find the tools. + + NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are + Windows native toolchains. The CodeSourcey (for Linux) and NuttX buildroot + toolchains are Cygwin and/or Linux native toolchains. There are several limitations + to using a Windows based toolchain in a Cygwin environment. The three biggest are: + + 1. The Windows toolchain cannot follow Cygwin paths. Path conversions are + performed automatically in the Cygwin makefiles using the 'cygpath' utility + but you might easily find some new path problems. If so, check out 'cygpath -w' + + 2. Windows toolchains cannot follow Cygwin symbolic links. Many symbolic links + are used in Nuttx (e.g., include/arch). The make system works around these + problems for the Windows tools by copying directories instead of linking them. + But this can also cause some confusion for you: For example, you may edit + a file in a "linked" directory and find that your changes had no effect. + That is because you are building the copy of the file in the "fake" symbolic + directory. If you use a Windows toolchain, you should get in the habit of + making like this: + + make clean_context all + + An alias in your .bashrc file might make that less painful. + + 3. Dependencies are not made when using Windows versions of the GCC. This is + because the dependencies are generated using Windows pathes which do not + work with the Cygwin make. + + Support has been added for making dependencies with the windows-native toolchains. + That support can be enabled by modifying your Make.defs file as follows: + + - MKDEP = $(TOPDIR)/tools/mknulldeps.sh + + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" + + If you have problems with the dependency build (for example, if you are not + building on C:), then you may need to modify tools/mkdeps.sh + + The CodeSourcery Toolchain (2009q1) + ----------------------------------- + The CodeSourcery toolchain (2009q1) does not work with default optimization + level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with + -Os. + + The Atollic "Pro" and "Lite" Toolchain + -------------------------------------- + One problem that I had with the Atollic toolchains is that the provide a gcc.exe + and g++.exe in the same bin/ file as their ARM binaries. If the Atollic bin/ path + appears in your PATH variable before /usr/bin, then you will get the wrong gcc + when you try to build host executables. This will cause to strange, uninterpretable + errors build some host binaries in tools/ when you first make. + + The Atollic "Lite" Toolchain + ---------------------------- + The free, "Lite" version of the Atollic toolchain does not support C++ nor + does it support ar, nm, objdump, or objdcopy. If you use the Atollic "Lite" + toolchain, you will have to set: + + CONFIG_HAVE_CXX=n + + In order to compile successfully. Otherwise, you will get errors like: + + "C++ Compiler only available in TrueSTUDIO Professional" + + The make may then fail in some of the post link processing because of some of + the other missing tools. The Make.defs file replaces the ar and nm with + the default system x86 tool versions and these seem to work okay. Disable all + of the following to avoid using objcopy: + + CONFIG_RRLOAD_BINARY=n + CONFIG_INTELHEX_BINARY=n + CONFIG_MOTOROLA_SREC=n + CONFIG_RAW_BINARY=n + + devkitARM + --------- + The devkitARM toolchain includes a version of MSYS make. Make sure that the + the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM + path or will get the wrong version of make. + +IDEs +==== + + NuttX is built using command-line make. It can be used with an IDE, but some + effort will be required to create the project. + + Makefile Build + -------------- + Under Eclipse, it is pretty easy to set up an "empty makefile project" and + simply use the NuttX makefile to build the system. That is almost for free + under Linux. Under Windows, you will need to set up the "Cygwin GCC" empty + makefile project in order to work with Windows (Google for "Eclipse Cygwin" - + there is a lot of help on the internet). + + Native Build + ------------ + Here are a few tips before you start that effort: + + 1) Select the toolchain that you will be using in your .config file + 2) Start the NuttX build at least one time from the Cygwin command line + before trying to create your project. This is necessary to create + certain auto-generated files and directories that will be needed. + 3) Set up include pathes: You will need include/, arch/arm/src/stm32, + arch/arm/src/common, arch/arm/src/armv7-m, and sched/. + 4) All assembly files need to have the definition option -D __ASSEMBLY__ + on the command line. + + Startup files will probably cause you some headaches. The NuttX startup file + is arch/arm/src/stm32/stm32_vectors.S. With RIDE, I have to build NuttX + one time from the Cygwin command line in order to obtain the pre-built + startup object needed by RIDE. + +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 + different from the default in your PATH variable). + + If you have no Cortex-M3 toolchain, one can be downloaded from the NuttX + SourceForge download site (https://sourceforge.net/projects/nuttx/files/buildroot/). + 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 stm32f100rc_generic/ + + 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-eabi-defconfig-4.6.3 .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly built binaries. + + See the file configs/README.txt in the buildroot source tree. That has more + 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 +================================ + + 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 +==== + +It is asumed that STMicro STM32F100RC generic board board has one LED on PA0. +You should configure the port and pin number in +configs/stm32f100rc_generic/src/stm32f100rc_internal.h. This LED is not used by +the board port unless CONFIG_ARCH_LEDS is defined. In that case, the usage by +the board port is defined in include/board.h and src/up_leds.c. The LED is used +to encode OS-related events as follows: + + SYMBOL Meaning LED1* + green + ------------------- ----------------------- ------- + LED_STARTED NuttX has been started ON + LED_HEAPALLOCATE Heap has been allocated ON + LED_IRQSENABLED Interrupts enabled ON + LED_STACKCREATED Idle stack created ON + LED_INIRQ In an interrupt ON + LED_SIGNAL In a signal handler ON + LED_ASSERTION An assertion failed OFF + LED_PANIC The system has crashed OFF + +So basically if the LED is off it means that there is a problem. + +UART +==== + +Default USART/UART Configuration +-------------------------------- + +USART2 is enabled in all configurations (see */defconfig). RX and TX are +configured on pins PA3 and PA2, respectively. + +"STMicro STM32F100RC generic" specific Configuration Options +============================================================ + + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: + + CONFIG_ARCH=arm + + CONFIG_ARCH_family - For use in C code: + + CONFIG_ARCH_ARM=y + + CONFIG_ARCH_architecture - For use in C code: + + CONFIG_ARCH_CORTEXM3=y + + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + + CONFIG_ARCH_CHIP=stm32 + + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: + + CONFIG_ARCH_CHIP_STM32F100RC=y + + 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=stm32f100rc_generic + + CONFIG_ARCH_BOARD_name - For use in C code + + CONFIG_ARCH_BOARD_STM32F100RC_GENERIC=y + + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops + + 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=24576 (24kB) + + CONFIG_DRAM_START - The start address of installed DRAM + + CONFIG_DRAM_START=0x20000000 + + CONFIG_ARCH_IRQPRIO - STM32F100RC chip supports interrupt prioritization + + CONFIG_ARCH_IRQPRIO=y + + CONFIG_ARCH_LEDS - Use LED to show state. Unique to boards that have LED(s) + + 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_CALIBRATION - when used togeter with CONFIG_DEBUG 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_CRC + CONFIG_STM32_DMA1 + CONFIG_STM32_DMA2 + + APB1 + ---- + CONFIG_STM32_TIM2 + CONFIG_STM32_TIM3 + CONFIG_STM32_TIM4 + CONFIG_STM32_TIM5 + CONFIG_STM32_TIM6 + CONFIG_STM32_TIM7 + CONFIG_STM32_TIM12 + CONFIG_STM32_TIM13 + CONFIG_STM32_TIM14 + CONFIG_STM32_RTC + CONFIG_STM32_WWDG + CONFIG_STM32_IWDG + CONFIG_STM32_SPI2 + CONFIG_STM32_SPI3 + CONFIG_STM32_USART2 + CONFIG_STM32_USART3 + CONFIG_STM32_UART4 + CONFIG_STM32_UART5 + CONFIG_STM32_I2C1 + CONFIG_STM32_I2C2 + CONFIG_STM32_PWR -- Required for RTC + CONFIG_STM32_BKP -- Required for RTC + CONFIG_STM32_DAC1 + CONFIG_STM32_DAC2 + CONFIG_STM32_CEC + + APB2 + ---- + CONFIG_STM32_ADC1 + CONFIG_STM32_TIM1 + CONFIG_STM32_SPI1 + CONFIG_STM32_USART1 + CONFIG_STM32_TIM15 + CONFIG_STM32_TIM16 + CONFIG_STM32_TIM17 + + Timer devices may be used for different purposes. One special purpose is + to generate modulated outputs for such things as motor control. If CONFIG_STM32_TIMn + is defined (as above) then the following may also be defined to indicate that + the timer is intended to be used for pulsed output modulation, ADC conversion, + or DAC conversion. Note that ADC/DAC require two definition: Not only do you have + 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,..,17 + CONFIG_STM32_TIMn_ADC Reserve timer n for use by ADC, n=1,..,17 + CONFIG_STM32_TIMn_ADC1 Reserve timer n to trigger ADCm, n=1,..,17 + CONFIG_STM32_TIMn_DAC Reserve timer n for use by DAC, n=1,..,17 + CONFIG_STM32_TIMn_DACm Reserve timer n to trigger DACm, n=1,..,17, m=1,..,2 + + For each timer that is enabled for PWM usage, we need the following additional + configuration settings: + + CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4} + + NOTE: The STM32 timers are each capable of generating different signals on + each of the four channels with different duty cycles. That capability is + not supported by this driver: Only one output channel per timer. + + JTAG Enable settings (by default full SWJ is enabled): + + CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) + CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) + but without JNTRST. + CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled + + STMicro STM32F100RC generic specific device driver settings + + 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). + 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 + +Configurations +============== + +Each STMicro STM32F100RC generic configuration is maintained in a sudirectory +and can be selected as follow: + + cd tools + ./configure.sh stm32f100rc_generic/ + cd - + . ./setenv.sh + +Where is one of the following: + + ostest: + ------ + This configuration directory, performs a simple OS test using + apps/examples/ostest. + + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Default toolchain: + + CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux / Mac OS X + + 3. By default, this project assumes that you are *NOT* using the DFU + bootloader. + + nsh: + --- + Configures the NuttShell (nsh) located at apps/examples/nsh. The + Configuration enables only the serial NSH interfaces. + + Default toolchain: + + CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux / Mac OS X diff --git a/nuttx/configs/stm32f100rc_generic/include/board.h b/nuttx/configs/stm32f100rc_generic/include/board.h new file mode 100644 index 0000000000..74fcd7daf3 --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/include/board.h @@ -0,0 +1,223 @@ +/************************************************************************************ + * configs/stm32f100rc_generic/include/board.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Freddie Chopin + * + * 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_BOARD_BOARD_H +#define __ARCH_BOARD_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#ifndef __ASSEMBLY__ +# include +#endif +#include "stm32_rcc.h" +#include "stm32_internal.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ + +/* On-board crystal frequency is 8MHz (HSE) */ + +#define STM32_BOARD_XTAL 8000000ul + +/* PLL source is HSE / 1, PLL multiplier is 3: PLL output frequency is 8MHz (XTAL) x 3 = 24MHz */ + +#define STM32_CFGR2_PREDIV1 RCC_CFGR2_PREDIV1d1 +#define STM32_CFGR_PLLSRC RCC_CFGR_PLLSRC +#define STM32_CFGR_PLLXTPRE 0 +#define STM32_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx3 +#define STM32_PLL_FREQUENCY (3 * STM32_BOARD_XTAL) + +/* Use the PLL and set the SYSCLK source to be the PLL */ + +#define STM32_SYSCLK_SW RCC_CFGR_SW_PLL +#define STM32_SYSCLK_SWS RCC_CFGR_SWS_PLL +#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY + +/* AHB clock (HCLK) is SYSCLK (24MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK +#define STM32_HCLK_FREQUENCY STM32_PLL_FREQUENCY + +/* APB2 clock (PCLK2) is HCLK (24MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK +#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY + +/* APB2 timers (1, 15-17) will receive PCLK2. */ + +#define STM32_APB2_TIM1_CLKIN STM32_PCLK2_FREQUENCY +#define STM32_APB2_TIM15_CLKIN STM32_PCLK2_FREQUENCY +#define STM32_APB2_TIM16_CLKIN STM32_PCLK2_FREQUENCY +#define STM32_APB2_TIM17_CLKIN STM32_PCLK2_FREQUENCY + +/* APB1 clock (PCLK1) is HCLK (24MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK +#define STM32_PCLK1_FREQUENCY STM32_HCLK_FREQUENCY + +/* APB1 timers (2-7, 12-14) will receive PCLK1. */ + +#define STM32_APB1_TIM2_CLKIN STM32_PCLK1_FREQUENCY +#define STM32_APB1_TIM3_CLKIN STM32_PCLK1_FREQUENCY +#define STM32_APB1_TIM4_CLKIN STM32_PCLK1_FREQUENCY +#define STM32_APB1_TIM5_CLKIN STM32_PCLK1_FREQUENCY +#define STM32_APB1_TIM6_CLKIN STM32_PCLK1_FREQUENCY +#define STM32_APB1_TIM7_CLKIN STM32_PCLK1_FREQUENCY +#define STM32_APB1_TIM12_CLKIN STM32_PCLK1_FREQUENCY +#define STM32_APB1_TIM13_CLKIN STM32_PCLK1_FREQUENCY +#define STM32_APB1_TIM14_CLKIN STM32_PCLK1_FREQUENCY + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,15-17 are on APB2, others on APB1 */ + +#define STM32_TIM18_FREQUENCY STM32_HCLK_FREQUENCY +#define STM32_TIM27_FREQUENCY STM32_HCLK_FREQUENCY + +/* LED definitions ******************************************************************/ + +/* It is assumed that a generic board has 1 LED. Thus only two different states + * can be shown. Statuses defined as "1" will light the LED, the ones defined as + * "0" will turn the LED off. */ + +#define LED_STARTED 1 +#define LED_HEAPALLOCATE 1 +#define LED_IRQSENABLED 1 +#define LED_STACKCREATED 1 +#define LED_INIRQ 1 +#define LED_SIGNAL 1 +#define LED_ASSERTION 0 +#define LED_PANIC 0 + +/* Button definitions ***************************************************************/ + +/* It is assumed that a generic board has 1 button. */ + +#define BUTTON_0 0 + +#define NUM_BUTTONS 1 + +#define BUTTON_0_BIT (1 << BUTTON_0) + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +EXTERN void stm32_boardinitialize(void); + +/************************************************************************************ + * Name: stm32_ledinit, stm32_setled, and stm32_setleds + * + * Description: + * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If + * CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to + * control the LEDs from user applications. + * + ************************************************************************************/ + +#ifndef CONFIG_ARCH_LEDS +EXTERN void stm32_ledinit(void); +EXTERN void stm32_setled(int led, bool ledon); +EXTERN void stm32_setleds(uint8_t ledset); +#endif + +/************************************************************************************ + * Button support. + * + * Description: + * up_buttoninit() must be called to initialize button resources. After + * that, up_buttons() may be called to collect the current state of all + * buttons or up_irqbutton() may be called to register button interrupt + * handlers. + * + * After up_buttoninit() has been called, up_buttons() may be called to + * collect the state of all buttons. up_buttons() returns an 8-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT + * definitions in board.h for the meaning of each bit. + * + * up_irqbutton() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* and JOYSTICK_* definitions in board.h for the meaning of enumeration + * value. The previous interrupt handler address is returned (so that it may + * restored, if so desired). + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_BUTTONS +EXTERN void up_buttoninit(void); +EXTERN uint8_t up_buttons(void); +#ifdef CONFIG_ARCH_IRQBUTTONS +EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler); +#endif +#endif + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/nuttx/configs/stm32f100rc_generic/nsh/Make.defs b/nuttx/configs/stm32f100rc_generic/nsh/Make.defs new file mode 100644 index 0000000000..7d016a674e --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/nsh/Make.defs @@ -0,0 +1,147 @@ +############################################################################ +# configs/stm32f100rc_generic/nsh/Make.defs +# +# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Freddie Chopin +# +# 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 +include ${TOPDIR}/tools/Config.mk + +# Setup for the selected toolchain + +LDSCRIPT = ld.script + +ifeq ($(CONFIG_STM32_CODESOURCERYW),y) + # CodeSourcery under Windows + CROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_CODESOURCERYL),y) + # CodeSourcery under Linux + CROSSDEV = arm-none-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -Os +endif +ifeq ($(CONFIG_STM32_DEVKITARM),y) + # devkitARM under Windows + CROSSDEV = arm-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_RAISONANCE),y) + # Raisonance RIDE7 under Windows + CROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_BUILDROOT),y) + # NuttX buildroot under Linux or Cygwin + # 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 ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/winlink.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + 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)/scripts/$(LDSCRIPT)}" + MAXOPTIMIZATION = -O2 +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)/scripts/$(LDSCRIPT) +endif + +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 + +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 ("${CONFIG_DEBUG_SYMBOLS}","y") + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +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__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS = -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS = -g +endif + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx/configs/stm32f100rc_generic/nsh/defconfig b/nuttx/configs/stm32f100rc_generic/nsh/defconfig new file mode 100644 index 0000000000..b5698ad189 --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/nsh/defconfig @@ -0,0 +1,629 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM3S is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_HAVE_CMNVECTOR=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARMV7M_CMNVECTOR=y +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set +CONFIG_ARCH_IRQPRIO=y +CONFIG_BOARD_LOOPSPERMSEC=2398 +# CONFIG_ARCH_CALIBRATION is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +CONFIG_ARCH_CHIP_STM32F100RC=y +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +CONFIG_STM32_STM32F10XX=y +CONFIG_STM32_VALUELINE=y +CONFIG_STM32_HIGHDENSITY=y +# CONFIG_STM32_CODESOURCERYW is not set +CONFIG_STM32_CODESOURCERYL=y +# CONFIG_STM32_ATOLLIC_LITE is not set +# CONFIG_STM32_ATOLLIC_PRO is not set +# CONFIG_STM32_DEVKITARM is not set +# CONFIG_STM32_RAISONANCE is not set +# CONFIG_STM32_BUILDROOT is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_ADC1 is not set +CONFIG_STM32_BKP=y +# CONFIG_STM32_CEC is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_IWDG is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 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 +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_TIM15 is not set +# CONFIG_STM32_TIM16 is not set +# CONFIG_STM32_TIM17 is not set +# CONFIG_STM32_USART1 is not set +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_WWDG is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_USART2_REMAP is not set +# CONFIG_STM32_JTAG_DISABLE is not set +CONFIG_STM32_JTAG_FULL_ENABLE=y +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +# CONFIG_STM32_JTAG_SW_ENABLE is not set +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set + +# +# USB Host Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_STACKDUMP=y + +# +# Board Settings +# +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=24576 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_STM32F100RC_GENERIC=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="stm32f100rc_generic" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_NSH_MMCSDMINOR=0 + +# +# Board-Specific Options +# + +# +# STM32F100RC Generic Hardware Configuration +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2012 +CONFIG_START_MONTH=11 +CONFIG_START_DAY=1 +CONFIG_DEV_CONSOLE=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_WORKPRIORITY=192 +CONFIG_SCHED_WORKPERIOD=50000 +CONFIG_SCHED_WORKSTACKSIZE=1024 +CONFIG_SIG_SIGWORK=4 +# CONFIG_SCHED_LPWORK is not set +CONFIG_SCHED_WAITPID=y +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set +CONFIG_DISABLE_POLL=y + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Stack and heap information +# +# CONFIG_CUSTOM_STACK is not set +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_SPI 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_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_USART2=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# 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_RAMMAP is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_SYMTAB_ORDEREDBYNAME=y + +# +# Library Routines +# +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set + +# +# Basic CXX Support +# +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# Named Applications +# +CONFIG_NAMEDAPP=y + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_NETTEST is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WLAN is not set + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSFMOUNT is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PING is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_CONDEV is not set +# CONFIG_NSH_ARCHINIT is not set + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# 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/stm32f100rc_generic/nsh/setenv.sh b/nuttx/configs/stm32f100rc_generic/nsh/setenv.sh new file mode 100755 index 0000000000..0e3810cbbe --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/nsh/setenv.sh @@ -0,0 +1,76 @@ +#!/bin/bash +# configs/stm32f100rc_generic/nsh/setenv.sh +# +# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Freddie Chopin +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +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" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm32f100rc_generic/ostest/Make.defs b/nuttx/configs/stm32f100rc_generic/ostest/Make.defs new file mode 100644 index 0000000000..68d5410b34 --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/ostest/Make.defs @@ -0,0 +1,147 @@ +############################################################################ +# configs/stm32f100rc_generic/ostest/Make.defs +# +# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Freddie Chopin +# +# 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 +include ${TOPDIR}/tools/Config.mk + +# Setup for the selected toolchain + +LDSCRIPT = ld.script + +ifeq ($(CONFIG_STM32_CODESOURCERYW),y) + # CodeSourcery under Windows + CROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_CODESOURCERYL),y) + # CodeSourcery under Linux + CROSSDEV = arm-none-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -Os +endif +ifeq ($(CONFIG_STM32_DEVKITARM),y) + # devkitARM under Windows + CROSSDEV = arm-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_RAISONANCE),y) + # Raisonance RIDE7 under Windows + CROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_BUILDROOT),y) + # NuttX buildroot under Linux or Cygwin + # 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 ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/winlink.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + 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)/scripts/$(LDSCRIPT)}" + MAXOPTIMIZATION = -O2 +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)/scripts/$(LDSCRIPT) +endif + +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 + +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 ("${CONFIG_DEBUG_SYMBOLS}","y") + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +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__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS = -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS = -g +endif + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx/configs/stm32f100rc_generic/ostest/defconfig b/nuttx/configs/stm32f100rc_generic/ostest/defconfig new file mode 100644 index 0000000000..92faa7f032 --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/ostest/defconfig @@ -0,0 +1,564 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM3S is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_HAVE_CMNVECTOR=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARMV7M_CMNVECTOR=y +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set +CONFIG_ARCH_IRQPRIO=y +CONFIG_BOARD_LOOPSPERMSEC=2398 +# CONFIG_ARCH_CALIBRATION is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +CONFIG_ARCH_CHIP_STM32F100RC=y +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +CONFIG_STM32_STM32F10XX=y +CONFIG_STM32_VALUELINE=y +CONFIG_STM32_HIGHDENSITY=y +# CONFIG_STM32_CODESOURCERYW is not set +CONFIG_STM32_CODESOURCERYL=y +# CONFIG_STM32_ATOLLIC_LITE is not set +# CONFIG_STM32_ATOLLIC_PRO is not set +# CONFIG_STM32_DEVKITARM is not set +# CONFIG_STM32_RAISONANCE is not set +# CONFIG_STM32_BUILDROOT is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_BKP is not set +# CONFIG_STM32_CEC is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_IWDG is not set +# CONFIG_STM32_PWR is not set +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 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 +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_TIM15 is not set +# CONFIG_STM32_TIM16 is not set +# CONFIG_STM32_TIM17 is not set +# CONFIG_STM32_USART1 is not set +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_WWDG is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_USART2_REMAP is not set +# CONFIG_STM32_JTAG_DISABLE is not set +CONFIG_STM32_JTAG_FULL_ENABLE=y +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +# CONFIG_STM32_JTAG_SW_ENABLE is not set +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set + +# +# USB Host Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_STACKDUMP=y + +# +# Board Settings +# +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=24576 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_STM32F100RC_GENERIC=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="stm32f100rc_generic" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y + +# +# Board-Specific Options +# + +# +# STM32F100RC Generic Hardware Configuration +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2012 +CONFIG_START_MONTH=11 +CONFIG_START_DAY=1 +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=y +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_WAITPID is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="ostest_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_POLL=y + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Stack and heap information +# +# CONFIG_CUSTOM_STACK is not set +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_SPI is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_USART2=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_FS_RAMMAP is not set + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_SYMTAB_ORDEREDBYNAME=y + +# +# Library Routines +# +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set + +# +# Basic CXX Support +# +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# Named Applications +# +# CONFIG_NAMEDAPP is not set + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_NETTEST is not set +# CONFIG_EXAMPLES_NSH is not set +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +CONFIG_EXAMPLES_OSTEST=y +# CONFIG_EXAMPLES_OSTEST_BUILTIN is not set +CONFIG_EXAMPLES_OSTEST_LOOPS=1 +CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048 +CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 +CONFIG_EXAMPLES_OSTEST_RR_RANGE=16383 +CONFIG_EXAMPLES_OSTEST_RR_RUNS=10 +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WLAN is not set + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +# CONFIG_NSH_LIBRARY is not set + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +# CONFIG_SYSTEM_READLINE is not set + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# 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/stm32f100rc_generic/ostest/setenv.sh b/nuttx/configs/stm32f100rc_generic/ostest/setenv.sh new file mode 100755 index 0000000000..8c924f83fa --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/ostest/setenv.sh @@ -0,0 +1,76 @@ +#!/bin/bash +# configs/stm32f100rc_generic/ostest/setenv.sh +# +# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Freddie Chopin +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +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" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/stm32f100rc_generic/scripts/ld.script b/nuttx/configs/stm32f100rc_generic/scripts/ld.script new file mode 100644 index 0000000000..f9fde02ace --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/scripts/ld.script @@ -0,0 +1,118 @@ +/**************************************************************************** + * configs/stm32f100rc_generic/scripts/ld.script + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Freddie Chopin + * + * 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. + * + ****************************************************************************/ + +/* The STM32F100RC has 256kB of FLASH beginning at address 0x08000000 and 24kB + * of SRAM beginning at address 0x20000000. When booting from FLASH, FLASH + * memory is aliased to address 0x00000000 where the code expects to begin + * execution by jumping to the entry point in the 0x08000000 address range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 24K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* 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/stm32f100rc_generic/src/Makefile b/nuttx/configs/stm32f100rc_generic/src/Makefile new file mode 100644 index 0000000000..1624a12239 --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/src/Makefile @@ -0,0 +1,83 @@ +############################################################################ +# configs/stm32f100rc_generic/src/Makefile +# +# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Freddie Chopin +# +# 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)/Make.defs + +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) + +CSRCS = up_boot.c up_leds.c up_buttons.c +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +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}" +else + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m +endif + +all: libboard$(LIBEXT) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +libboard$(LIBEXT): $(OBJS) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) + +.depend: Makefile $(SRCS) + @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ + +depend: .depend + +clean: + @rm -f libboard$(LIBEXT) *~ .*.swp + $(call CLEAN) + +distclean: clean + @rm -f Make.dep .depend + +-include Make.dep diff --git a/nuttx/configs/stm32f100rc_generic/src/stm32f100rc_internal.h b/nuttx/configs/stm32f100rc_generic/src/stm32f100rc_internal.h new file mode 100644 index 0000000000..2d4b282c0c --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/src/stm32f100rc_internal.h @@ -0,0 +1,57 @@ +/************************************************************************************ + * configs/stm32f100rc_generic/src/stm32f100rc_internal.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Freddie Chopin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __CONFIGS_STM32F100RC_GENERIC_SRC_STM32F100RC_INTERNAL_H +#define __CONFIGS_STM32F100RC_GENERIC_SRC_STM32F100RC_INTERNAL_H + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* LED - assume it is on PA0 */ + +#define GPIO_LED1 (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_OUTPUT_CLEAR | GPIO_PORTA | GPIO_PIN0) + +/* BUTTON - assume it is on PA1 */ + +#define MIN_IRQBUTTON BUTTON_0 +#define MAX_IRQBUTTON BUTTON_0 +#define NUM_IRQBUTTONS 1 + +#define GPIO_BTN_0 (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN1) + +#endif /* __CONFIGS_STM32F100RC_GENERIC_SRC_STM32F100RC_INTERNAL_H */ + diff --git a/nuttx/configs/stm32f100rc_generic/src/up_boot.c b/nuttx/configs/stm32f100rc_generic/src/up_boot.c new file mode 100644 index 0000000000..d1922b9bfb --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/src/up_boot.c @@ -0,0 +1,70 @@ +/************************************************************************************ + * configs/stm32f100rc_generic/src/up_boot.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Freddie Chopin + * + * 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 "up_arch.h" +#include "stm32f100rc_internal.h" + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32_boardinitialize(void) +{ + /* Configure on-board LEDs if LED support has been selected. */ +#ifdef CONFIG_ARCH_LEDS + up_ledinit(); +#endif +} diff --git a/nuttx/configs/stm32f100rc_generic/src/up_buttons.c b/nuttx/configs/stm32f100rc_generic/src/up_buttons.c new file mode 100644 index 0000000000..7200d9ce86 --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/src/up_buttons.c @@ -0,0 +1,117 @@ +/**************************************************************************** + * configs/stm32f100rc_generic/src/up_buttons.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Freddie Chopin + * + * 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 "stm32f100rc_internal.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_buttoninit + * + * Description: + * up_buttoninit() must be called to initialize button resources. After + * that, up_buttons() may be called to collect the current state of all + * buttons or up_irqbutton() may be called to register button interrupt + * handlers. + * + ****************************************************************************/ + +void up_buttoninit(void) +{ + stm32_configgpio(GPIO_BTN_0); /* Configure the GPIO pins as inputs. */ +} + +/**************************************************************************** + * Name: up_buttons + ****************************************************************************/ + +uint8_t up_buttons(void) +{ + uint8_t ret = 0; + + ret = (stm32_gpioread(g_buttons[i]) == false ? 1 : 0); + + return ret; +} + +/************************************************************************************ + * Button support. + * + * Description: + * up_buttoninit() must be called to initialize button resources. After + * that, up_buttons() may be called to collect the current state of all + * buttons or up_irqbutton() may be called to register button interrupt + * handlers. + * + * After up_buttoninit() has been called, up_buttons() may be called to + * collect the state of all buttons. up_buttons() returns an 8-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT + * definitions in board.h for the meaning of each bit. + * + * up_irqbutton() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* and JOYSTICK_* definitions in board.h for the meaning of enumeration + * value. The previous interrupt handler address is returned (so that it may + * restored, if so desired). + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +xcpt_t up_irqbutton(int id, xcpt_t irqhandler) +{ + xcpt_t oldhandler = NULL; + + if (id == 0) + oldhandler = stm32_gpiosetevent(GPIO_BTN_0, true, true, true, irqhandler); + + return oldhandler; +} +#endif +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/nuttx/configs/stm32f100rc_generic/src/up_leds.c b/nuttx/configs/stm32f100rc_generic/src/up_leds.c new file mode 100644 index 0000000000..152c104c48 --- /dev/null +++ b/nuttx/configs/stm32f100rc_generic/src/up_leds.c @@ -0,0 +1,108 @@ +/**************************************************************************** + * configs/stm32f100rc_generic/src/up_leds.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Freddie Chopin + * + * 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 "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32_internal.h" +#include "stm32f100rc_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Enables debug output from this file (needs CONFIG_DEBUG with + * CONFIG_DEBUG_VERBOSE too) + */ + +#undef LED_DEBUG /* Define to enable debug */ + +#ifdef LED_DEBUG +# define leddbg lldbg +# define ledvdbg llvdbg +#else +# define leddbg(x...) +# define ledvdbg(x...) +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_ledinit + ****************************************************************************/ + +#ifdef CONFIG_ARCH_LEDS +void up_ledinit(void) +{ + stm32_configgpio(GPIO_LED1); /* Configure LED1 GPIO for output */ +} + +/**************************************************************************** + * Name: up_ledon + ****************************************************************************/ + +void up_ledon(int led) +{ + if (led == 1) + stm32_gpiowrite(GPIO_LED1, true); +} + +/**************************************************************************** + * Name: up_ledoff + ****************************************************************************/ + +void up_ledoff(int led) +{ + if (led == 0) + stm32_gpiowrite(GPIO_LED1, false); +} + +#endif /* CONFIG_ARCH_LEDS */ From e99deb5c4af245a03351ed2ec021cdde3e33fbba Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 6 Nov 2012 14:57:01 +0000 Subject: [PATCH 085/206] Patch to removed MMCSD NSLOTS warning from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5316 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 6 ++++++ nuttx/configs/amber/hello/defconfig | 8 ++++++++ nuttx/configs/avr32dev1/nsh/defconfig | 8 ++++++++ nuttx/configs/avr32dev1/ostest/defconfig | 8 ++++++++ nuttx/configs/c5471evm/httpd/defconfig | 8 ++++++++ nuttx/configs/c5471evm/nettest/defconfig | 8 ++++++++ nuttx/configs/c5471evm/nsh/defconfig | 8 ++++++++ nuttx/configs/c5471evm/ostest/defconfig | 8 ++++++++ nuttx/configs/compal_e88/nsh_highram/defconfig | 8 ++++++++ nuttx/configs/compal_e99/nsh_compalram/defconfig | 8 ++++++++ nuttx/configs/compal_e99/nsh_highram/defconfig | 8 ++++++++ nuttx/configs/demo9s12ne64/ostest/defconfig | 8 ++++++++ nuttx/configs/ea3131/nsh/defconfig | 8 ++++++++ nuttx/configs/ea3131/ostest/defconfig | 8 ++++++++ nuttx/configs/ea3131/pgnsh/defconfig | 8 ++++++++ nuttx/configs/ea3131/usbserial/defconfig | 8 ++++++++ nuttx/configs/ea3131/usbstorage/defconfig | 8 ++++++++ nuttx/configs/ea3152/ostest/defconfig | 8 ++++++++ nuttx/configs/eagle100/httpd/defconfig | 8 ++++++++ nuttx/configs/eagle100/nettest/defconfig | 8 ++++++++ nuttx/configs/eagle100/nsh/defconfig | 8 ++++++++ nuttx/configs/eagle100/nxflat/defconfig | 8 ++++++++ nuttx/configs/eagle100/ostest/defconfig | 8 ++++++++ nuttx/configs/eagle100/thttpd/defconfig | 8 ++++++++ nuttx/configs/ekk-lm3s9b96/nsh/defconfig | 8 ++++++++ nuttx/configs/ekk-lm3s9b96/ostest/defconfig | 8 ++++++++ nuttx/configs/ez80f910200kitg/ostest/defconfig | 8 ++++++++ nuttx/configs/ez80f910200zco/dhcpd/defconfig | 8 ++++++++ nuttx/configs/ez80f910200zco/httpd/defconfig | 8 ++++++++ nuttx/configs/ez80f910200zco/nettest/defconfig | 8 ++++++++ nuttx/configs/ez80f910200zco/nsh/defconfig | 8 ++++++++ nuttx/configs/ez80f910200zco/ostest/defconfig | 8 ++++++++ nuttx/configs/ez80f910200zco/poll/defconfig | 8 ++++++++ nuttx/configs/hymini-stm32v/buttons/defconfig | 10 +++++++++- nuttx/configs/hymini-stm32v/nsh/defconfig | 10 +++++++++- nuttx/configs/hymini-stm32v/nsh2/defconfig | 10 +++++++++- nuttx/configs/hymini-stm32v/nx/defconfig | 10 +++++++++- nuttx/configs/hymini-stm32v/nxlines/defconfig | 10 +++++++++- nuttx/configs/hymini-stm32v/usbserial/defconfig | 10 +++++++++- nuttx/configs/hymini-stm32v/usbstorage/defconfig | 10 +++++++++- nuttx/configs/kwikstik-k40/ostest/defconfig | 8 ++++++++ nuttx/configs/lincoln60/nsh/defconfig | 8 ++++++++ nuttx/configs/lincoln60/ostest/defconfig | 8 ++++++++ nuttx/configs/lm3s6432-s2e/nsh/defconfig | 8 ++++++++ nuttx/configs/lm3s6432-s2e/ostest/defconfig | 8 ++++++++ nuttx/configs/lm3s6965-ek/nsh/defconfig | 8 ++++++++ nuttx/configs/lm3s6965-ek/nx/defconfig | 8 ++++++++ nuttx/configs/lm3s6965-ek/ostest/defconfig | 8 ++++++++ nuttx/configs/lm3s8962-ek/nsh/defconfig | 8 ++++++++ nuttx/configs/lm3s8962-ek/nx/defconfig | 8 ++++++++ nuttx/configs/lm3s8962-ek/ostest/defconfig | 8 ++++++++ nuttx/configs/lpc4330-xplorer/nsh/defconfig | 8 ++++++++ nuttx/configs/lpc4330-xplorer/ostest/defconfig | 8 ++++++++ nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig | 8 ++++++++ nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig | 8 ++++++++ nuttx/configs/lpcxpresso-lpc1768/nx/defconfig | 8 ++++++++ nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig | 8 ++++++++ nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig | 8 ++++++++ .../lpcxpresso-lpc1768/usbstorage/defconfig | 8 ++++++++ nuttx/configs/m68332evb/defconfig | 8 ++++++++ nuttx/configs/mbed/hidkbd/defconfig | 8 ++++++++ nuttx/configs/mbed/nsh/defconfig | 8 ++++++++ nuttx/configs/mcu123-lpc214x/composite/defconfig | 8 ++++++++ nuttx/configs/mcu123-lpc214x/nsh/defconfig | 8 ++++++++ nuttx/configs/mcu123-lpc214x/ostest/defconfig | 8 ++++++++ nuttx/configs/mcu123-lpc214x/usbserial/defconfig | 8 ++++++++ nuttx/configs/mcu123-lpc214x/usbstorage/defconfig | 8 ++++++++ nuttx/configs/micropendous3/hello/defconfig | 8 ++++++++ nuttx/configs/mirtoo/nsh/defconfig | 8 ++++++++ nuttx/configs/mirtoo/nxffs/defconfig | 8 ++++++++ nuttx/configs/mirtoo/ostest/defconfig | 8 ++++++++ nuttx/configs/mx1ads/ostest/defconfig | 8 ++++++++ nuttx/configs/ne64badge/ostest/defconfig | 10 +++++++++- nuttx/configs/ntosd-dm320/nettest/defconfig | 8 ++++++++ nuttx/configs/ntosd-dm320/nsh/defconfig | 8 ++++++++ nuttx/configs/ntosd-dm320/ostest/defconfig | 8 ++++++++ nuttx/configs/ntosd-dm320/poll/defconfig | 8 ++++++++ nuttx/configs/ntosd-dm320/thttpd/defconfig | 8 ++++++++ nuttx/configs/ntosd-dm320/udp/defconfig | 8 ++++++++ nuttx/configs/ntosd-dm320/uip/defconfig | 8 ++++++++ nuttx/configs/nucleus2g/nsh/defconfig | 8 ++++++++ nuttx/configs/nucleus2g/ostest/defconfig | 8 ++++++++ nuttx/configs/nucleus2g/usbserial/defconfig | 8 ++++++++ nuttx/configs/nucleus2g/usbstorage/defconfig | 8 ++++++++ nuttx/configs/olimex-lpc1766stk/ftpc/defconfig | 8 ++++++++ nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig | 8 ++++++++ nuttx/configs/olimex-lpc1766stk/nettest/defconfig | 8 ++++++++ nuttx/configs/olimex-lpc1766stk/nsh/defconfig | 8 ++++++++ nuttx/configs/olimex-lpc1766stk/nx/defconfig | 8 ++++++++ nuttx/configs/olimex-lpc1766stk/ostest/defconfig | 8 ++++++++ .../configs/olimex-lpc1766stk/slip-httpd/defconfig | 8 ++++++++ nuttx/configs/olimex-lpc1766stk/thttpd/defconfig | 8 ++++++++ .../configs/olimex-lpc1766stk/usbserial/defconfig | 8 ++++++++ .../configs/olimex-lpc1766stk/usbstorage/defconfig | 8 ++++++++ nuttx/configs/olimex-lpc1766stk/wlan/defconfig | 8 ++++++++ nuttx/configs/olimex-lpc2378/nsh/defconfig | 8 ++++++++ nuttx/configs/olimex-lpc2378/ostest/defconfig | 8 ++++++++ nuttx/configs/olimex-stm32-p107/nsh/defconfig | 10 +++++++++- nuttx/configs/olimex-stm32-p107/ostest/defconfig | 12 ++++++++++-- nuttx/configs/olimex-strp711/nettest/defconfig | 8 ++++++++ nuttx/configs/olimex-strp711/nsh/defconfig | 8 ++++++++ nuttx/configs/olimex-strp711/ostest/defconfig | 8 ++++++++ nuttx/configs/pcblogic-pic32mx/nsh/defconfig | 8 ++++++++ nuttx/configs/pcblogic-pic32mx/ostest/defconfig | 8 ++++++++ nuttx/configs/pic32-starterkit/nsh/defconfig | 8 ++++++++ nuttx/configs/pic32-starterkit/nsh2/defconfig | 8 ++++++++ nuttx/configs/pic32-starterkit/ostest/defconfig | 8 ++++++++ nuttx/configs/pic32mx7mmb/nsh/defconfig | 8 ++++++++ nuttx/configs/pic32mx7mmb/ostest/defconfig | 8 ++++++++ nuttx/configs/pjrc-8051/defconfig | 8 ++++++++ nuttx/configs/qemu-i486/nsh/defconfig | 8 ++++++++ nuttx/configs/qemu-i486/ostest/defconfig | 8 ++++++++ nuttx/configs/rgmp/arm/default/defconfig | 7 +++++++ nuttx/configs/rgmp/arm/nsh/defconfig | 7 +++++++ nuttx/configs/rgmp/x86/cxxtest/defconfig | 14 +++++++++++--- nuttx/configs/rgmp/x86/default/defconfig | 8 ++++++++ nuttx/configs/rgmp/x86/helloxx/defconfig | 14 +++++++++++--- nuttx/configs/rgmp/x86/nsh/defconfig | 7 +++++++ nuttx/configs/sam3u-ek/knsh/defconfig | 8 ++++++++ nuttx/configs/sam3u-ek/nsh/defconfig | 8 ++++++++ nuttx/configs/sam3u-ek/nx/defconfig | 8 ++++++++ nuttx/configs/sam3u-ek/ostest/defconfig | 8 ++++++++ nuttx/configs/sam3u-ek/touchscreen/defconfig | 10 +++++++++- nuttx/configs/sim/mount/defconfig | 8 ++++++++ nuttx/configs/sim/nettest/defconfig | 8 ++++++++ nuttx/configs/sim/nsh/defconfig | 8 ++++++++ nuttx/configs/sim/nsh2/defconfig | 8 ++++++++ nuttx/configs/sim/nx/defconfig | 8 ++++++++ nuttx/configs/sim/nx11/defconfig | 8 ++++++++ nuttx/configs/sim/nxffs/defconfig | 8 ++++++++ nuttx/configs/sim/nxwm/defconfig | 8 ++++++++ nuttx/configs/sim/pashello/defconfig | 8 ++++++++ nuttx/configs/sim/touchscreen/defconfig | 8 ++++++++ nuttx/configs/skp16c26/ostest/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/RIDE/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/buttons/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/composite/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/nsh/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/nsh2/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/nx/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/nxconsole/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/nxlines/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/nxtext/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/ostest/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/pm/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/usbserial/defconfig | 8 ++++++++ nuttx/configs/stm3210e-eval/usbstorage/defconfig | 8 ++++++++ nuttx/configs/stm3220g-eval/dhcpd/defconfig | 8 ++++++++ nuttx/configs/stm3220g-eval/nettest/defconfig | 8 ++++++++ nuttx/configs/stm3220g-eval/nsh/defconfig | 8 ++++++++ nuttx/configs/stm3220g-eval/nsh2/defconfig | 8 ++++++++ nuttx/configs/stm3220g-eval/nxwm/defconfig | 8 ++++++++ nuttx/configs/stm3220g-eval/ostest/defconfig | 8 ++++++++ nuttx/configs/stm3220g-eval/telnetd/defconfig | 8 ++++++++ nuttx/configs/stm3240g-eval/dhcpd/defconfig | 8 ++++++++ nuttx/configs/stm3240g-eval/nettest/defconfig | 8 ++++++++ nuttx/configs/stm3240g-eval/nsh/defconfig | 8 ++++++++ nuttx/configs/stm3240g-eval/nsh2/defconfig | 8 ++++++++ nuttx/configs/stm3240g-eval/nxconsole/defconfig | 8 ++++++++ nuttx/configs/stm3240g-eval/nxwm/defconfig | 8 ++++++++ nuttx/configs/stm3240g-eval/ostest/defconfig | 8 ++++++++ nuttx/configs/stm3240g-eval/telnetd/defconfig | 8 ++++++++ nuttx/configs/stm3240g-eval/webserver/defconfig | 8 ++++++++ nuttx/configs/stm32f4discovery/nsh/defconfig | 8 ++++++++ nuttx/configs/stm32f4discovery/nxlines/defconfig | 8 ++++++++ nuttx/configs/stm32f4discovery/pm/defconfig | 8 ++++++++ nuttx/configs/sure-pic32mx/nsh/defconfig | 8 ++++++++ nuttx/configs/sure-pic32mx/ostest/defconfig | 8 ++++++++ nuttx/configs/sure-pic32mx/usbnsh/defconfig | 8 ++++++++ nuttx/configs/teensy/hello/defconfig | 8 ++++++++ nuttx/configs/teensy/nsh/defconfig | 8 ++++++++ nuttx/configs/teensy/usbstorage/defconfig | 8 ++++++++ nuttx/configs/twr-k60n512/nsh/defconfig | 8 ++++++++ nuttx/configs/twr-k60n512/ostest/defconfig | 8 ++++++++ nuttx/configs/ubw32/nsh/defconfig | 8 ++++++++ nuttx/configs/ubw32/ostest/defconfig | 8 ++++++++ nuttx/configs/us7032evb1/nsh/defconfig | 8 ++++++++ nuttx/configs/us7032evb1/ostest/defconfig | 8 ++++++++ nuttx/configs/vsn/nsh/defconfig | 8 ++++++++ nuttx/configs/xtrs/nsh/defconfig | 8 ++++++++ nuttx/configs/xtrs/ostest/defconfig | 8 ++++++++ nuttx/configs/xtrs/pashello/defconfig | 8 ++++++++ nuttx/configs/z16f2800100zcog/ostest/defconfig | 8 ++++++++ nuttx/configs/z16f2800100zcog/pashello/defconfig | 8 ++++++++ nuttx/configs/z80sim/nsh/defconfig | 8 ++++++++ nuttx/configs/z80sim/ostest/defconfig | 8 ++++++++ nuttx/configs/z80sim/pashello/defconfig | 8 ++++++++ nuttx/configs/z8encore000zco/ostest/defconfig | 8 ++++++++ nuttx/configs/z8f64200100kit/ostest/defconfig | 8 ++++++++ nuttx/drivers/mmcsd/Make.defs | 12 +++++++++++- nuttx/drivers/mmcsd/mmcsd_sdio.c | 5 +++++ nuttx/drivers/mmcsd/mmcsd_spi.c | 5 +++++ 192 files changed, 1546 insertions(+), 19 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index e131d26b24..8c19ca1554 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3571,3 +3571,9 @@ complete and verified for the STM32 platform. 6.24 2012-xx-xx Gregory Nutt + + * arch/arm/src/stm32: Support for STM32F100 high density chips + added by Freddie Chopin. + * configs/stm32f100_generic: Support for generic STM32F100RC board + contributed by Freddie Chopin. + diff --git a/nuttx/configs/amber/hello/defconfig b/nuttx/configs/amber/hello/defconfig index 2439279104..5d028e321c 100644 --- a/nuttx/configs/amber/hello/defconfig +++ b/nuttx/configs/amber/hello/defconfig @@ -220,6 +220,14 @@ CONFIG_PREALLOC_TIMERS=0 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/avr32dev1/nsh/defconfig b/nuttx/configs/avr32dev1/nsh/defconfig index 3ca2fac382..2b66316c31 100755 --- a/nuttx/configs/avr32dev1/nsh/defconfig +++ b/nuttx/configs/avr32dev1/nsh/defconfig @@ -239,6 +239,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/avr32dev1/ostest/defconfig b/nuttx/configs/avr32dev1/ostest/defconfig index ed7280dc60..9b67be09ea 100755 --- a/nuttx/configs/avr32dev1/ostest/defconfig +++ b/nuttx/configs/avr32dev1/ostest/defconfig @@ -239,6 +239,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/c5471evm/httpd/defconfig b/nuttx/configs/c5471evm/httpd/defconfig index 52a0fc4bbe..8f4bd6927c 100644 --- a/nuttx/configs/c5471evm/httpd/defconfig +++ b/nuttx/configs/c5471evm/httpd/defconfig @@ -258,3 +258,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/c5471evm/nettest/defconfig b/nuttx/configs/c5471evm/nettest/defconfig index 6da9fa522f..71065fc662 100644 --- a/nuttx/configs/c5471evm/nettest/defconfig +++ b/nuttx/configs/c5471evm/nettest/defconfig @@ -258,3 +258,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/c5471evm/nsh/defconfig b/nuttx/configs/c5471evm/nsh/defconfig index 6b583d31a5..3750f9e5da 100644 --- a/nuttx/configs/c5471evm/nsh/defconfig +++ b/nuttx/configs/c5471evm/nsh/defconfig @@ -258,3 +258,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/c5471evm/ostest/defconfig b/nuttx/configs/c5471evm/ostest/defconfig index 04ac9677f4..f4d7b8c365 100644 --- a/nuttx/configs/c5471evm/ostest/defconfig +++ b/nuttx/configs/c5471evm/ostest/defconfig @@ -258,3 +258,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/compal_e88/nsh_highram/defconfig b/nuttx/configs/compal_e88/nsh_highram/defconfig index b429af6966..d67674f4e1 100644 --- a/nuttx/configs/compal_e88/nsh_highram/defconfig +++ b/nuttx/configs/compal_e88/nsh_highram/defconfig @@ -277,3 +277,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/compal_e99/nsh_compalram/defconfig b/nuttx/configs/compal_e99/nsh_compalram/defconfig index 52f99bf124..e8c53947b8 100644 --- a/nuttx/configs/compal_e99/nsh_compalram/defconfig +++ b/nuttx/configs/compal_e99/nsh_compalram/defconfig @@ -279,3 +279,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/compal_e99/nsh_highram/defconfig b/nuttx/configs/compal_e99/nsh_highram/defconfig index b1539c98c9..c986454781 100644 --- a/nuttx/configs/compal_e99/nsh_highram/defconfig +++ b/nuttx/configs/compal_e99/nsh_highram/defconfig @@ -323,3 +323,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/demo9s12ne64/ostest/defconfig b/nuttx/configs/demo9s12ne64/ostest/defconfig index 5033d82011..9c9668aacc 100755 --- a/nuttx/configs/demo9s12ne64/ostest/defconfig +++ b/nuttx/configs/demo9s12ne64/ostest/defconfig @@ -213,6 +213,14 @@ CONFIG_PREALLOC_TIMERS=0 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ea3131/nsh/defconfig b/nuttx/configs/ea3131/nsh/defconfig index c97f521a52..735af431b0 100644 --- a/nuttx/configs/ea3131/nsh/defconfig +++ b/nuttx/configs/ea3131/nsh/defconfig @@ -218,6 +218,14 @@ CONFIG_FS_ROMFS=n CONFIG_FS_READAHEAD=n CONFIG_FS_WRITEBUFFER=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SDIO-based MMC/SD driver # diff --git a/nuttx/configs/ea3131/ostest/defconfig b/nuttx/configs/ea3131/ostest/defconfig index c66ee51a44..2f73ad5c9e 100644 --- a/nuttx/configs/ea3131/ostest/defconfig +++ b/nuttx/configs/ea3131/ostest/defconfig @@ -218,6 +218,14 @@ CONFIG_FS_ROMFS=n CONFIG_FS_READAHEAD=n CONFIG_FS_WRITEBUFFER=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SDIO-based MMC/SD driver # diff --git a/nuttx/configs/ea3131/pgnsh/defconfig b/nuttx/configs/ea3131/pgnsh/defconfig index c9e0963580..32f89c5001 100644 --- a/nuttx/configs/ea3131/pgnsh/defconfig +++ b/nuttx/configs/ea3131/pgnsh/defconfig @@ -261,6 +261,14 @@ CONFIG_FS_ROMFS=n CONFIG_FS_READAHEAD=n CONFIG_FS_WRITEBUFFER=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SDIO-based MMC/SD driver # diff --git a/nuttx/configs/ea3131/usbserial/defconfig b/nuttx/configs/ea3131/usbserial/defconfig index 1e8f5cf945..3d33a1b67d 100644 --- a/nuttx/configs/ea3131/usbserial/defconfig +++ b/nuttx/configs/ea3131/usbserial/defconfig @@ -221,6 +221,14 @@ CONFIG_FS_WRITABLE=y CONFIG_FS_READAHEAD=n CONFIG_FS_WRITEBUFFER=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SDIO-based MMC/SD driver # diff --git a/nuttx/configs/ea3131/usbstorage/defconfig b/nuttx/configs/ea3131/usbstorage/defconfig index d8088b5dfa..8d9933f555 100644 --- a/nuttx/configs/ea3131/usbstorage/defconfig +++ b/nuttx/configs/ea3131/usbstorage/defconfig @@ -222,6 +222,14 @@ CONFIG_FS_WRITABLE=y CONFIG_FS_READAHEAD=n CONFIG_FS_WRITEBUFFER=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SDIO-based MMC/SD driver # diff --git a/nuttx/configs/ea3152/ostest/defconfig b/nuttx/configs/ea3152/ostest/defconfig index 34cf49dfba..d85fd58218 100644 --- a/nuttx/configs/ea3152/ostest/defconfig +++ b/nuttx/configs/ea3152/ostest/defconfig @@ -219,6 +219,14 @@ CONFIG_FS_ROMFS=n CONFIG_FS_READAHEAD=n CONFIG_FS_WRITEBUFFER=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SDIO-based MMC/SD driver # diff --git a/nuttx/configs/eagle100/httpd/defconfig b/nuttx/configs/eagle100/httpd/defconfig index 7916569bc0..6d4ee61a27 100644 --- a/nuttx/configs/eagle100/httpd/defconfig +++ b/nuttx/configs/eagle100/httpd/defconfig @@ -213,6 +213,14 @@ CONFIG_PREALLOC_TIMERS=8 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/eagle100/nettest/defconfig b/nuttx/configs/eagle100/nettest/defconfig index 6f47953863..4956d0875b 100644 --- a/nuttx/configs/eagle100/nettest/defconfig +++ b/nuttx/configs/eagle100/nettest/defconfig @@ -213,6 +213,14 @@ CONFIG_PREALLOC_TIMERS=8 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/eagle100/nsh/defconfig b/nuttx/configs/eagle100/nsh/defconfig index b50413db0e..7f6bd1f540 100644 --- a/nuttx/configs/eagle100/nsh/defconfig +++ b/nuttx/configs/eagle100/nsh/defconfig @@ -215,6 +215,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/eagle100/nxflat/defconfig b/nuttx/configs/eagle100/nxflat/defconfig index 98029ddd83..a4760eae52 100644 --- a/nuttx/configs/eagle100/nxflat/defconfig +++ b/nuttx/configs/eagle100/nxflat/defconfig @@ -219,6 +219,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=y +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/eagle100/ostest/defconfig b/nuttx/configs/eagle100/ostest/defconfig index f3634aa55f..4b98e25e0f 100644 --- a/nuttx/configs/eagle100/ostest/defconfig +++ b/nuttx/configs/eagle100/ostest/defconfig @@ -213,6 +213,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/eagle100/thttpd/defconfig b/nuttx/configs/eagle100/thttpd/defconfig index d68d51acfc..5af32d2022 100644 --- a/nuttx/configs/eagle100/thttpd/defconfig +++ b/nuttx/configs/eagle100/thttpd/defconfig @@ -220,6 +220,14 @@ CONFIG_PREALLOC_TIMERS=8 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=y +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/defconfig b/nuttx/configs/ekk-lm3s9b96/nsh/defconfig index 2a1a0552d2..8047a23dac 100644 --- a/nuttx/configs/ekk-lm3s9b96/nsh/defconfig +++ b/nuttx/configs/ekk-lm3s9b96/nsh/defconfig @@ -232,6 +232,14 @@ CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n CONFIG_NFS=y +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/defconfig b/nuttx/configs/ekk-lm3s9b96/ostest/defconfig index c465cb8b7c..6ce065ca81 100644 --- a/nuttx/configs/ekk-lm3s9b96/ostest/defconfig +++ b/nuttx/configs/ekk-lm3s9b96/ostest/defconfig @@ -231,6 +231,14 @@ CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n CONFIG_NFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ez80f910200kitg/ostest/defconfig b/nuttx/configs/ez80f910200kitg/ostest/defconfig index 9ceb261b22..3039eec6cb 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/defconfig +++ b/nuttx/configs/ez80f910200kitg/ostest/defconfig @@ -199,6 +199,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ez80f910200zco/dhcpd/defconfig b/nuttx/configs/ez80f910200zco/dhcpd/defconfig index a20e86a45a..329ff28245 100644 --- a/nuttx/configs/ez80f910200zco/dhcpd/defconfig +++ b/nuttx/configs/ez80f910200zco/dhcpd/defconfig @@ -203,6 +203,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ez80f910200zco/httpd/defconfig b/nuttx/configs/ez80f910200zco/httpd/defconfig index cccecf2bfc..1feeafd585 100644 --- a/nuttx/configs/ez80f910200zco/httpd/defconfig +++ b/nuttx/configs/ez80f910200zco/httpd/defconfig @@ -203,6 +203,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ez80f910200zco/nettest/defconfig b/nuttx/configs/ez80f910200zco/nettest/defconfig index e018164b01..1ba356095a 100644 --- a/nuttx/configs/ez80f910200zco/nettest/defconfig +++ b/nuttx/configs/ez80f910200zco/nettest/defconfig @@ -203,6 +203,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ez80f910200zco/nsh/defconfig b/nuttx/configs/ez80f910200zco/nsh/defconfig index 34fbe603d1..73de6b096e 100644 --- a/nuttx/configs/ez80f910200zco/nsh/defconfig +++ b/nuttx/configs/ez80f910200zco/nsh/defconfig @@ -203,6 +203,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=y CONFIG_FS_ROMFS=y +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ez80f910200zco/ostest/defconfig b/nuttx/configs/ez80f910200zco/ostest/defconfig index 1954b7a5d8..bf306e38d1 100644 --- a/nuttx/configs/ez80f910200zco/ostest/defconfig +++ b/nuttx/configs/ez80f910200zco/ostest/defconfig @@ -201,6 +201,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ez80f910200zco/poll/defconfig b/nuttx/configs/ez80f910200zco/poll/defconfig index a98526466a..0d7d765cf4 100644 --- a/nuttx/configs/ez80f910200zco/poll/defconfig +++ b/nuttx/configs/ez80f910200zco/poll/defconfig @@ -203,6 +203,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/hymini-stm32v/buttons/defconfig b/nuttx/configs/hymini-stm32v/buttons/defconfig index 8ee2c1d763..bbd6c2319d 100644 --- a/nuttx/configs/hymini-stm32v/buttons/defconfig +++ b/nuttx/configs/hymini-stm32v/buttons/defconfig @@ -68,7 +68,7 @@ CONFIG_STM32_DFU=n # # Individual subsystems can be enabled: # -# AHB: +# AHB: CONFIG_STM32_DMA1=n CONFIG_STM32_DMA2=n CONFIG_STM32_CRC=n @@ -270,6 +270,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/hymini-stm32v/nsh/defconfig b/nuttx/configs/hymini-stm32v/nsh/defconfig index f18194bce5..ca589278af 100755 --- a/nuttx/configs/hymini-stm32v/nsh/defconfig +++ b/nuttx/configs/hymini-stm32v/nsh/defconfig @@ -66,7 +66,7 @@ CONFIG_STM32_DFU=n # # Individual subsystems can be enabled: -# AHB: +# AHB: CONFIG_STM32_DMA1=n CONFIG_STM32_DMA2=y CONFIG_STM32_CRC=n @@ -267,6 +267,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/hymini-stm32v/nsh2/defconfig b/nuttx/configs/hymini-stm32v/nsh2/defconfig index b11895c9b1..5091843ad3 100644 --- a/nuttx/configs/hymini-stm32v/nsh2/defconfig +++ b/nuttx/configs/hymini-stm32v/nsh2/defconfig @@ -67,7 +67,7 @@ CONFIG_STM32_DFU=n # # Individual subsystems can be enabled: -# AHB: +# AHB: CONFIG_STM32_DMA1=n CONFIG_STM32_DMA2=y CONFIG_STM32_CRC=n @@ -301,6 +301,14 @@ CONFIG_FS_ROMFS=y CONFIG_FS_READAHEAD=n CONFIG_FS_WRITEBUFFER=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # STM32 SDIO-based MMC/SD driver # diff --git a/nuttx/configs/hymini-stm32v/nx/defconfig b/nuttx/configs/hymini-stm32v/nx/defconfig index b46c68e293..f4beaf7d51 100644 --- a/nuttx/configs/hymini-stm32v/nx/defconfig +++ b/nuttx/configs/hymini-stm32v/nx/defconfig @@ -66,7 +66,7 @@ CONFIG_STM32_DFU=n # # Individual subsystems can be enabled: -# AHB: +# AHB: CONFIG_STM32_DMA1=n CONFIG_STM32_DMA2=y CONFIG_STM32_CRC=n @@ -284,6 +284,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/hymini-stm32v/nxlines/defconfig b/nuttx/configs/hymini-stm32v/nxlines/defconfig index 863e7a327d..89f72e3307 100644 --- a/nuttx/configs/hymini-stm32v/nxlines/defconfig +++ b/nuttx/configs/hymini-stm32v/nxlines/defconfig @@ -67,7 +67,7 @@ CONFIG_STM32_DFU=n # # Individual subsystems can be enabled: -# AHB: +# AHB: CONFIG_STM32_DMA1=n CONFIG_STM32_DMA2=y CONFIG_STM32_CRC=n @@ -288,6 +288,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/hymini-stm32v/usbserial/defconfig b/nuttx/configs/hymini-stm32v/usbserial/defconfig index a6ed06dee9..732c1e8b6f 100755 --- a/nuttx/configs/hymini-stm32v/usbserial/defconfig +++ b/nuttx/configs/hymini-stm32v/usbserial/defconfig @@ -68,7 +68,7 @@ CONFIG_STM32_DFU=n # # Individual subsystems can be enabled: # -# AHB: +# AHB: CONFIG_STM32_DMA1=n CONFIG_STM32_DMA2=n CONFIG_STM32_CRC=n @@ -270,6 +270,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/hymini-stm32v/usbstorage/defconfig b/nuttx/configs/hymini-stm32v/usbstorage/defconfig index 7d75577fe5..7e49de0e87 100755 --- a/nuttx/configs/hymini-stm32v/usbstorage/defconfig +++ b/nuttx/configs/hymini-stm32v/usbstorage/defconfig @@ -67,7 +67,7 @@ CONFIG_STM32_DFU=n # # Individual subsystems can be enabled: -# AHB: +# AHB: CONFIG_STM32_DMA1=n CONFIG_STM32_DMA2=y CONFIG_STM32_CRC=n @@ -277,6 +277,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/kwikstik-k40/ostest/defconfig b/nuttx/configs/kwikstik-k40/ostest/defconfig index a811ee0632..759cff20b0 100755 --- a/nuttx/configs/kwikstik-k40/ostest/defconfig +++ b/nuttx/configs/kwikstik-k40/ostest/defconfig @@ -279,6 +279,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lincoln60/nsh/defconfig b/nuttx/configs/lincoln60/nsh/defconfig index bb08a7deca..e5009f8d6e 100644 --- a/nuttx/configs/lincoln60/nsh/defconfig +++ b/nuttx/configs/lincoln60/nsh/defconfig @@ -252,6 +252,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lincoln60/ostest/defconfig b/nuttx/configs/lincoln60/ostest/defconfig index 0576d018fa..986f9bf438 100644 --- a/nuttx/configs/lincoln60/ostest/defconfig +++ b/nuttx/configs/lincoln60/ostest/defconfig @@ -262,6 +262,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lm3s6432-s2e/nsh/defconfig b/nuttx/configs/lm3s6432-s2e/nsh/defconfig index d203b29546..9aa8f1db39 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/defconfig +++ b/nuttx/configs/lm3s6432-s2e/nsh/defconfig @@ -230,6 +230,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lm3s6432-s2e/ostest/defconfig b/nuttx/configs/lm3s6432-s2e/ostest/defconfig index 02b7dbd314..299cef48c2 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/defconfig +++ b/nuttx/configs/lm3s6432-s2e/ostest/defconfig @@ -229,6 +229,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lm3s6965-ek/nsh/defconfig b/nuttx/configs/lm3s6965-ek/nsh/defconfig index 5afac6e6fb..d10ad9db9b 100755 --- a/nuttx/configs/lm3s6965-ek/nsh/defconfig +++ b/nuttx/configs/lm3s6965-ek/nsh/defconfig @@ -232,6 +232,14 @@ CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n CONFIG_NFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lm3s6965-ek/nx/defconfig b/nuttx/configs/lm3s6965-ek/nx/defconfig index b6cb0cad5a..10d10f705c 100755 --- a/nuttx/configs/lm3s6965-ek/nx/defconfig +++ b/nuttx/configs/lm3s6965-ek/nx/defconfig @@ -245,6 +245,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lm3s6965-ek/ostest/defconfig b/nuttx/configs/lm3s6965-ek/ostest/defconfig index da35e55314..e638ac3c70 100755 --- a/nuttx/configs/lm3s6965-ek/ostest/defconfig +++ b/nuttx/configs/lm3s6965-ek/ostest/defconfig @@ -230,6 +230,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lm3s8962-ek/nsh/defconfig b/nuttx/configs/lm3s8962-ek/nsh/defconfig index 2a80e84e70..769c5d8e97 100755 --- a/nuttx/configs/lm3s8962-ek/nsh/defconfig +++ b/nuttx/configs/lm3s8962-ek/nsh/defconfig @@ -230,6 +230,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lm3s8962-ek/nx/defconfig b/nuttx/configs/lm3s8962-ek/nx/defconfig index 51063f7558..653bdc4834 100755 --- a/nuttx/configs/lm3s8962-ek/nx/defconfig +++ b/nuttx/configs/lm3s8962-ek/nx/defconfig @@ -244,6 +244,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lm3s8962-ek/ostest/defconfig b/nuttx/configs/lm3s8962-ek/ostest/defconfig index c540b1d7f6..ce1ed1a1dd 100755 --- a/nuttx/configs/lm3s8962-ek/ostest/defconfig +++ b/nuttx/configs/lm3s8962-ek/ostest/defconfig @@ -229,6 +229,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lpc4330-xplorer/nsh/defconfig b/nuttx/configs/lpc4330-xplorer/nsh/defconfig index a97b9f789e..0afcbae892 100644 --- a/nuttx/configs/lpc4330-xplorer/nsh/defconfig +++ b/nuttx/configs/lpc4330-xplorer/nsh/defconfig @@ -323,6 +323,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lpc4330-xplorer/ostest/defconfig b/nuttx/configs/lpc4330-xplorer/ostest/defconfig index cddf7d0e8f..76d3f11e95 100644 --- a/nuttx/configs/lpc4330-xplorer/ostest/defconfig +++ b/nuttx/configs/lpc4330-xplorer/ostest/defconfig @@ -320,6 +320,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig index 92aa13f7b0..f56dfca1ba 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig @@ -264,6 +264,14 @@ CONFIG_PREALLOC_TIMERS=8 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig b/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig index 0e149e1864..ef70b55080 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig @@ -260,6 +260,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig b/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig index 88a2cd7a22..a0d3cd2836 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig @@ -277,6 +277,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig b/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig index 1fa3e79bce..660bd6c8b4 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig @@ -262,6 +262,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig b/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig index 3d014d2914..7558691560 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig @@ -264,6 +264,14 @@ CONFIG_PREALLOC_TIMERS=8 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=y +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig index 8e51d52057..004d92cb34 100755 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig @@ -258,6 +258,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/m68332evb/defconfig b/nuttx/configs/m68332evb/defconfig index 39b3c77324..4c40201847 100644 --- a/nuttx/configs/m68332evb/defconfig +++ b/nuttx/configs/m68332evb/defconfig @@ -209,3 +209,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/mbed/hidkbd/defconfig b/nuttx/configs/mbed/hidkbd/defconfig index 3c31b2f926..ba0af97cac 100644 --- a/nuttx/configs/mbed/hidkbd/defconfig +++ b/nuttx/configs/mbed/hidkbd/defconfig @@ -257,6 +257,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/mbed/nsh/defconfig b/nuttx/configs/mbed/nsh/defconfig index fca08b577b..a1168dd197 100755 --- a/nuttx/configs/mbed/nsh/defconfig +++ b/nuttx/configs/mbed/nsh/defconfig @@ -252,6 +252,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/mcu123-lpc214x/composite/defconfig b/nuttx/configs/mcu123-lpc214x/composite/defconfig index 0599fed14f..04fbe2b9e7 100644 --- a/nuttx/configs/mcu123-lpc214x/composite/defconfig +++ b/nuttx/configs/mcu123-lpc214x/composite/defconfig @@ -193,6 +193,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/mcu123-lpc214x/nsh/defconfig b/nuttx/configs/mcu123-lpc214x/nsh/defconfig index e2d37a938c..a8a53a3403 100644 --- a/nuttx/configs/mcu123-lpc214x/nsh/defconfig +++ b/nuttx/configs/mcu123-lpc214x/nsh/defconfig @@ -191,6 +191,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/mcu123-lpc214x/ostest/defconfig b/nuttx/configs/mcu123-lpc214x/ostest/defconfig index 5fc7df5c75..9d59439be5 100644 --- a/nuttx/configs/mcu123-lpc214x/ostest/defconfig +++ b/nuttx/configs/mcu123-lpc214x/ostest/defconfig @@ -191,6 +191,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/mcu123-lpc214x/usbserial/defconfig b/nuttx/configs/mcu123-lpc214x/usbserial/defconfig index c35d804868..3097f7d783 100644 --- a/nuttx/configs/mcu123-lpc214x/usbserial/defconfig +++ b/nuttx/configs/mcu123-lpc214x/usbserial/defconfig @@ -191,6 +191,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig b/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig index a25f2e170b..7b22bf6b0e 100644 --- a/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig +++ b/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig @@ -193,6 +193,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/micropendous3/hello/defconfig b/nuttx/configs/micropendous3/hello/defconfig index 63a8f249c8..ea8faf8f52 100644 --- a/nuttx/configs/micropendous3/hello/defconfig +++ b/nuttx/configs/micropendous3/hello/defconfig @@ -215,6 +215,14 @@ CONFIG_PREALLOC_TIMERS=0 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/mirtoo/nsh/defconfig b/nuttx/configs/mirtoo/nsh/defconfig index 0883cc9ea0..f2e2b8991b 100644 --- a/nuttx/configs/mirtoo/nsh/defconfig +++ b/nuttx/configs/mirtoo/nsh/defconfig @@ -283,6 +283,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/mirtoo/nxffs/defconfig b/nuttx/configs/mirtoo/nxffs/defconfig index f2f5286e65..29de6f1e72 100644 --- a/nuttx/configs/mirtoo/nxffs/defconfig +++ b/nuttx/configs/mirtoo/nxffs/defconfig @@ -283,6 +283,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/mirtoo/ostest/defconfig b/nuttx/configs/mirtoo/ostest/defconfig index 77b3e38b83..dfe7a25c54 100644 --- a/nuttx/configs/mirtoo/ostest/defconfig +++ b/nuttx/configs/mirtoo/ostest/defconfig @@ -274,6 +274,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/mx1ads/ostest/defconfig b/nuttx/configs/mx1ads/ostest/defconfig index 55b3c72b8c..03d79e70af 100644 --- a/nuttx/configs/mx1ads/ostest/defconfig +++ b/nuttx/configs/mx1ads/ostest/defconfig @@ -321,3 +321,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/ne64badge/ostest/defconfig b/nuttx/configs/ne64badge/ostest/defconfig index c101aa01b0..78e10f87ca 100755 --- a/nuttx/configs/ne64badge/ostest/defconfig +++ b/nuttx/configs/ne64badge/ostest/defconfig @@ -55,7 +55,7 @@ CONFIG_ARCH_BUTTONS=n CONFIG_ARCH_CALIBRATION=n CONFIG_ARCH_DMA=n -# +# CONFIG_GPIO_IRQ=n CONFIG_HCS12_PORTG_INTS=n CONFIG_HCS12_PORTH_INTS=n @@ -219,6 +219,14 @@ CONFIG_PREALLOC_TIMERS=0 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ntosd-dm320/nettest/defconfig b/nuttx/configs/ntosd-dm320/nettest/defconfig index 297df2173f..dd2aff53c3 100644 --- a/nuttx/configs/ntosd-dm320/nettest/defconfig +++ b/nuttx/configs/ntosd-dm320/nettest/defconfig @@ -317,3 +317,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/ntosd-dm320/nsh/defconfig b/nuttx/configs/ntosd-dm320/nsh/defconfig index 2b02c2d4e4..98de53fe03 100644 --- a/nuttx/configs/ntosd-dm320/nsh/defconfig +++ b/nuttx/configs/ntosd-dm320/nsh/defconfig @@ -348,3 +348,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/ntosd-dm320/ostest/defconfig b/nuttx/configs/ntosd-dm320/ostest/defconfig index a9fca828af..5d606453b1 100644 --- a/nuttx/configs/ntosd-dm320/ostest/defconfig +++ b/nuttx/configs/ntosd-dm320/ostest/defconfig @@ -313,3 +313,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/ntosd-dm320/poll/defconfig b/nuttx/configs/ntosd-dm320/poll/defconfig index 08f75e6b6a..e43eccce56 100644 --- a/nuttx/configs/ntosd-dm320/poll/defconfig +++ b/nuttx/configs/ntosd-dm320/poll/defconfig @@ -324,3 +324,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/ntosd-dm320/thttpd/defconfig b/nuttx/configs/ntosd-dm320/thttpd/defconfig index d2de4c167d..fbb6d644f9 100644 --- a/nuttx/configs/ntosd-dm320/thttpd/defconfig +++ b/nuttx/configs/ntosd-dm320/thttpd/defconfig @@ -392,3 +392,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/ntosd-dm320/udp/defconfig b/nuttx/configs/ntosd-dm320/udp/defconfig index de3b240560..5859279d0b 100644 --- a/nuttx/configs/ntosd-dm320/udp/defconfig +++ b/nuttx/configs/ntosd-dm320/udp/defconfig @@ -325,3 +325,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/ntosd-dm320/uip/defconfig b/nuttx/configs/ntosd-dm320/uip/defconfig index 281a63bd0c..69387e7f6d 100644 --- a/nuttx/configs/ntosd-dm320/uip/defconfig +++ b/nuttx/configs/ntosd-dm320/uip/defconfig @@ -325,3 +325,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/nucleus2g/nsh/defconfig b/nuttx/configs/nucleus2g/nsh/defconfig index 5bc94e607e..cc747e0c8c 100755 --- a/nuttx/configs/nucleus2g/nsh/defconfig +++ b/nuttx/configs/nucleus2g/nsh/defconfig @@ -253,6 +253,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/nucleus2g/ostest/defconfig b/nuttx/configs/nucleus2g/ostest/defconfig index 945e82a057..3d777de9cc 100755 --- a/nuttx/configs/nucleus2g/ostest/defconfig +++ b/nuttx/configs/nucleus2g/ostest/defconfig @@ -252,6 +252,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/nucleus2g/usbserial/defconfig b/nuttx/configs/nucleus2g/usbserial/defconfig index 25804407f3..e5762e8bcb 100755 --- a/nuttx/configs/nucleus2g/usbserial/defconfig +++ b/nuttx/configs/nucleus2g/usbserial/defconfig @@ -253,6 +253,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/nucleus2g/usbstorage/defconfig b/nuttx/configs/nucleus2g/usbstorage/defconfig index cc677b9f44..88c54bccc7 100755 --- a/nuttx/configs/nucleus2g/usbstorage/defconfig +++ b/nuttx/configs/nucleus2g/usbstorage/defconfig @@ -254,6 +254,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig b/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig index 7cf2e0e880..36c5eefc4f 100755 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig @@ -275,6 +275,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig index ac94ecfb86..9a4c37fb44 100755 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig @@ -267,6 +267,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig index 7e662fb97a..f89d265b00 100755 --- a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig @@ -267,6 +267,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig index b12dd731a9..0d82b458ba 100755 --- a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig @@ -279,6 +279,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/nx/defconfig b/nuttx/configs/olimex-lpc1766stk/nx/defconfig index 0235c29b5f..55c480fe3a 100755 --- a/nuttx/configs/olimex-lpc1766stk/nx/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/nx/defconfig @@ -280,6 +280,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig index fcc2bba448..32e2cacc58 100755 --- a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig @@ -262,6 +262,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig index 94d5da763f..ff2674c793 100755 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig @@ -272,6 +272,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=y +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig b/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig index c14e1362b6..936dba3593 100755 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig @@ -270,6 +270,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=y +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig index e1216d8968..603a1562a6 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig @@ -263,6 +263,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig index 2f91efe474..2c29d2ffd1 100755 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig @@ -264,6 +264,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig index aa896c30ce..009191f654 100755 --- a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig @@ -259,6 +259,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc2378/nsh/defconfig b/nuttx/configs/olimex-lpc2378/nsh/defconfig index 30801a6ab4..fcddbaaca0 100755 --- a/nuttx/configs/olimex-lpc2378/nsh/defconfig +++ b/nuttx/configs/olimex-lpc2378/nsh/defconfig @@ -208,6 +208,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-lpc2378/ostest/defconfig b/nuttx/configs/olimex-lpc2378/ostest/defconfig index 129bb7fbe5..b7216c7c4a 100755 --- a/nuttx/configs/olimex-lpc2378/ostest/defconfig +++ b/nuttx/configs/olimex-lpc2378/ostest/defconfig @@ -208,6 +208,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-stm32-p107/nsh/defconfig b/nuttx/configs/olimex-stm32-p107/nsh/defconfig index 9b9a72dcdb..7aaae25140 100644 --- a/nuttx/configs/olimex-stm32-p107/nsh/defconfig +++ b/nuttx/configs/olimex-stm32-p107/nsh/defconfig @@ -81,7 +81,7 @@ CONFIG_STM32_SPI1_REMAP=n CONFIG_STM32_SPI3_REMAP=n CONFIG_STM32_I2C1_REMAP=n CONFIG_STM32_CAN1_REMAP1=y -CONFIG_STM32_CAN1_REMAP2=n +CONFIG_STM32_CAN1_REMAP2=n # @@ -309,6 +309,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-stm32-p107/ostest/defconfig b/nuttx/configs/olimex-stm32-p107/ostest/defconfig index 21aa07875a..d4bba38fbb 100644 --- a/nuttx/configs/olimex-stm32-p107/ostest/defconfig +++ b/nuttx/configs/olimex-stm32-p107/ostest/defconfig @@ -90,13 +90,13 @@ CONFIG_STM32_SPI1_REMAP=n CONFIG_STM32_SPI3_REMAP=n CONFIG_STM32_I2C1_REMAP=n CONFIG_STM32_CAN1_REMAP1=y -CONFIG_STM32_CAN1_REMAP2=n +CONFIG_STM32_CAN1_REMAP2=n # # Individual subsystems can be enabled: # -# AHB: +# AHB: CONFIG_STM32_DMA1=n CONFIG_STM32_DMA2=n CONFIG_STM32_CRC=n @@ -317,6 +317,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-strp711/nettest/defconfig b/nuttx/configs/olimex-strp711/nettest/defconfig index eb8c911088..4d73540b80 100755 --- a/nuttx/configs/olimex-strp711/nettest/defconfig +++ b/nuttx/configs/olimex-strp711/nettest/defconfig @@ -242,6 +242,14 @@ CONFIG_ENC28J60_NINTERFACES=1 CONFIG_ENC28J60_STATS=y CONFIG_ENC28J60_HALFDUPPLEX=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-strp711/nsh/defconfig b/nuttx/configs/olimex-strp711/nsh/defconfig index 2deb556408..b621945ed6 100644 --- a/nuttx/configs/olimex-strp711/nsh/defconfig +++ b/nuttx/configs/olimex-strp711/nsh/defconfig @@ -225,6 +225,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/olimex-strp711/ostest/defconfig b/nuttx/configs/olimex-strp711/ostest/defconfig index e60b7349f1..02804cd67e 100644 --- a/nuttx/configs/olimex-strp711/ostest/defconfig +++ b/nuttx/configs/olimex-strp711/ostest/defconfig @@ -225,6 +225,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/pcblogic-pic32mx/nsh/defconfig b/nuttx/configs/pcblogic-pic32mx/nsh/defconfig index 3a480d7865..b4bd30ae84 100644 --- a/nuttx/configs/pcblogic-pic32mx/nsh/defconfig +++ b/nuttx/configs/pcblogic-pic32mx/nsh/defconfig @@ -275,6 +275,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/pcblogic-pic32mx/ostest/defconfig b/nuttx/configs/pcblogic-pic32mx/ostest/defconfig index da8ff40edb..08bdccddd7 100644 --- a/nuttx/configs/pcblogic-pic32mx/ostest/defconfig +++ b/nuttx/configs/pcblogic-pic32mx/ostest/defconfig @@ -265,6 +265,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/pic32-starterkit/nsh/defconfig b/nuttx/configs/pic32-starterkit/nsh/defconfig index 17fbd6f4ec..f2cd275601 100644 --- a/nuttx/configs/pic32-starterkit/nsh/defconfig +++ b/nuttx/configs/pic32-starterkit/nsh/defconfig @@ -358,6 +358,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/pic32-starterkit/nsh2/defconfig b/nuttx/configs/pic32-starterkit/nsh2/defconfig index 0eec631180..6f227f638d 100644 --- a/nuttx/configs/pic32-starterkit/nsh2/defconfig +++ b/nuttx/configs/pic32-starterkit/nsh2/defconfig @@ -357,6 +357,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/pic32-starterkit/ostest/defconfig b/nuttx/configs/pic32-starterkit/ostest/defconfig index e386b59360..922cb8901a 100644 --- a/nuttx/configs/pic32-starterkit/ostest/defconfig +++ b/nuttx/configs/pic32-starterkit/ostest/defconfig @@ -355,6 +355,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/pic32mx7mmb/nsh/defconfig b/nuttx/configs/pic32mx7mmb/nsh/defconfig index c55e802093..8d9dffc214 100644 --- a/nuttx/configs/pic32mx7mmb/nsh/defconfig +++ b/nuttx/configs/pic32mx7mmb/nsh/defconfig @@ -373,6 +373,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/pic32mx7mmb/ostest/defconfig b/nuttx/configs/pic32mx7mmb/ostest/defconfig index a2e653a563..1d656380d6 100644 --- a/nuttx/configs/pic32mx7mmb/ostest/defconfig +++ b/nuttx/configs/pic32mx7mmb/ostest/defconfig @@ -355,6 +355,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/pjrc-8051/defconfig b/nuttx/configs/pjrc-8051/defconfig index c223f64e18..b41d74e315 100644 --- a/nuttx/configs/pjrc-8051/defconfig +++ b/nuttx/configs/pjrc-8051/defconfig @@ -208,3 +208,11 @@ CONFIG_PTHREAD_STACK_MIN= CONFIG_PTHREAD_STACK_DEFAULT= CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/qemu-i486/nsh/defconfig b/nuttx/configs/qemu-i486/nsh/defconfig index b693c94f76..792157fe0e 100644 --- a/nuttx/configs/qemu-i486/nsh/defconfig +++ b/nuttx/configs/qemu-i486/nsh/defconfig @@ -309,3 +309,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=2048 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/qemu-i486/ostest/defconfig b/nuttx/configs/qemu-i486/ostest/defconfig index 63c27a2317..b0036289a8 100644 --- a/nuttx/configs/qemu-i486/ostest/defconfig +++ b/nuttx/configs/qemu-i486/ostest/defconfig @@ -225,3 +225,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=2048 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/rgmp/arm/default/defconfig b/nuttx/configs/rgmp/arm/default/defconfig index a78500bf4c..0c40e8bd21 100644 --- a/nuttx/configs/rgmp/arm/default/defconfig +++ b/nuttx/configs/rgmp/arm/default/defconfig @@ -220,6 +220,13 @@ CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y ########################################## # RGMP specific configuration diff --git a/nuttx/configs/rgmp/arm/nsh/defconfig b/nuttx/configs/rgmp/arm/nsh/defconfig index bee14b0a2a..0ae14b1418 100644 --- a/nuttx/configs/rgmp/arm/nsh/defconfig +++ b/nuttx/configs/rgmp/arm/nsh/defconfig @@ -221,6 +221,13 @@ CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y ########################################## # RGMP specific configuration diff --git a/nuttx/configs/rgmp/x86/cxxtest/defconfig b/nuttx/configs/rgmp/x86/cxxtest/defconfig index 34430ae86a..1d2996557f 100644 --- a/nuttx/configs/rgmp/x86/cxxtest/defconfig +++ b/nuttx/configs/rgmp/x86/cxxtest/defconfig @@ -74,7 +74,7 @@ CONFIG_ARCH_BOARD_RGMP=y # CONFIG_RR_INTERVAL - The round robin timeslice will be set # this number of milliseconds; Round robin scheduling can # be disabled by setting this value to zero. -# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in # scheduler to monitor system performance # CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a # task name to save in the TCB. Useful if scheduler @@ -89,11 +89,11 @@ CONFIG_ARCH_BOARD_RGMP=y # CONFIG_MUTEX_TYPES: Set to enable support for recursive and # errorcheck mutexes. Enables pthread_mutexattr_settype(). # CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority -# inheritance on mutexes and semaphores. +# inheritance on mutexes and semaphores. # CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority # inheritance is enabled. It defines the maximum number of # different threads (minus one) that can take counts on a -# semaphore with priority inheritance support. This may be +# semaphore with priority inheritance support. This may be # set to zero if priority inheritance is disabled OR if you # are only using semaphores as mutexes (only one holder) OR # if no more than two threads participate using a counting @@ -326,6 +326,14 @@ CONFIG_NET_BROADCAST=n CONFIG_NET_DHCP_LIGHT=n CONFIG_NET_RESOLV_ENTRIES=4 +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # Settings for examples/uip CONFIG_EXAMPLE_UIP_IPADDR=0xc0a80a02 diff --git a/nuttx/configs/rgmp/x86/default/defconfig b/nuttx/configs/rgmp/x86/default/defconfig index 30b27c4a13..070ffcb30b 100644 --- a/nuttx/configs/rgmp/x86/default/defconfig +++ b/nuttx/configs/rgmp/x86/default/defconfig @@ -181,6 +181,14 @@ CONFIG_NET_BROADCAST=n CONFIG_NET_DHCP_LIGHT=n CONFIG_NET_RESOLV_ENTRIES=4 +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # Settings for examples/uip CONFIG_EXAMPLES_UIP_IPADDR=0xc0a80a02 diff --git a/nuttx/configs/rgmp/x86/helloxx/defconfig b/nuttx/configs/rgmp/x86/helloxx/defconfig index ed7d5d8b99..c8400560a9 100644 --- a/nuttx/configs/rgmp/x86/helloxx/defconfig +++ b/nuttx/configs/rgmp/x86/helloxx/defconfig @@ -74,7 +74,7 @@ CONFIG_ARCH_BOARD_RGMP=y # CONFIG_RR_INTERVAL - The round robin timeslice will be set # this number of milliseconds; Round robin scheduling can # be disabled by setting this value to zero. -# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in # scheduler to monitor system performance # CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a # task name to save in the TCB. Useful if scheduler @@ -89,11 +89,11 @@ CONFIG_ARCH_BOARD_RGMP=y # CONFIG_MUTEX_TYPES: Set to enable support for recursive and # errorcheck mutexes. Enables pthread_mutexattr_settype(). # CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority -# inheritance on mutexes and semaphores. +# inheritance on mutexes and semaphores. # CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority # inheritance is enabled. It defines the maximum number of # different threads (minus one) that can take counts on a -# semaphore with priority inheritance support. This may be +# semaphore with priority inheritance support. This may be # set to zero if priority inheritance is disabled OR if you # are only using semaphores as mutexes (only one holder) OR # if no more than two threads participate using a counting @@ -388,6 +388,14 @@ CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= CONFIG_USER_ENTRYPOINT="helloxx_main" +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # uClibc++ Standard C++ Library # diff --git a/nuttx/configs/rgmp/x86/nsh/defconfig b/nuttx/configs/rgmp/x86/nsh/defconfig index 90797a20b2..891d58ba8f 100644 --- a/nuttx/configs/rgmp/x86/nsh/defconfig +++ b/nuttx/configs/rgmp/x86/nsh/defconfig @@ -230,6 +230,13 @@ CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y ########################################## # RGMP specific configuration diff --git a/nuttx/configs/sam3u-ek/knsh/defconfig b/nuttx/configs/sam3u-ek/knsh/defconfig index 416ca3fa3a..e61180407f 100755 --- a/nuttx/configs/sam3u-ek/knsh/defconfig +++ b/nuttx/configs/sam3u-ek/knsh/defconfig @@ -267,6 +267,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/sam3u-ek/nsh/defconfig b/nuttx/configs/sam3u-ek/nsh/defconfig index 69a2081ff2..288df5957f 100755 --- a/nuttx/configs/sam3u-ek/nsh/defconfig +++ b/nuttx/configs/sam3u-ek/nsh/defconfig @@ -242,6 +242,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/sam3u-ek/nx/defconfig b/nuttx/configs/sam3u-ek/nx/defconfig index aae6aa5fa1..7b56b9d41b 100755 --- a/nuttx/configs/sam3u-ek/nx/defconfig +++ b/nuttx/configs/sam3u-ek/nx/defconfig @@ -251,6 +251,14 @@ CONFIG_FB_HWCURSORIMAGE=n CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/sam3u-ek/ostest/defconfig b/nuttx/configs/sam3u-ek/ostest/defconfig index 14b8eaa6ee..b2e9a5184f 100755 --- a/nuttx/configs/sam3u-ek/ostest/defconfig +++ b/nuttx/configs/sam3u-ek/ostest/defconfig @@ -243,6 +243,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/sam3u-ek/touchscreen/defconfig b/nuttx/configs/sam3u-ek/touchscreen/defconfig index cd1fec7d1d..b3fc37d2a4 100755 --- a/nuttx/configs/sam3u-ek/touchscreen/defconfig +++ b/nuttx/configs/sam3u-ek/touchscreen/defconfig @@ -276,6 +276,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # @@ -549,7 +557,7 @@ CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN=y CONFIG_EXAMPLES_TOUCHSCREEN_MINOR=0 CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH="/dev/input0" CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES=25 - + # # Stack and heap information # diff --git a/nuttx/configs/sim/mount/defconfig b/nuttx/configs/sim/mount/defconfig index 7caa878525..d5e108782c 100644 --- a/nuttx/configs/sim/mount/defconfig +++ b/nuttx/configs/sim/mount/defconfig @@ -223,3 +223,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/sim/nettest/defconfig b/nuttx/configs/sim/nettest/defconfig index c216e2edc8..1df980ea83 100644 --- a/nuttx/configs/sim/nettest/defconfig +++ b/nuttx/configs/sim/nettest/defconfig @@ -222,3 +222,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/sim/nsh/defconfig b/nuttx/configs/sim/nsh/defconfig index a217dd71d7..a60edd4ac5 100644 --- a/nuttx/configs/sim/nsh/defconfig +++ b/nuttx/configs/sim/nsh/defconfig @@ -267,3 +267,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/sim/nsh2/defconfig b/nuttx/configs/sim/nsh2/defconfig index 0e93cd4810..903c6322df 100644 --- a/nuttx/configs/sim/nsh2/defconfig +++ b/nuttx/configs/sim/nsh2/defconfig @@ -370,3 +370,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/sim/nx/defconfig b/nuttx/configs/sim/nx/defconfig index d5cad6741b..9036a79561 100644 --- a/nuttx/configs/sim/nx/defconfig +++ b/nuttx/configs/sim/nx/defconfig @@ -324,3 +324,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/sim/nx11/defconfig b/nuttx/configs/sim/nx11/defconfig index 0ac3362be2..46b5cb4147 100644 --- a/nuttx/configs/sim/nx11/defconfig +++ b/nuttx/configs/sim/nx11/defconfig @@ -319,3 +319,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/sim/nxffs/defconfig b/nuttx/configs/sim/nxffs/defconfig index 79f5b0f93a..c8aadee257 100644 --- a/nuttx/configs/sim/nxffs/defconfig +++ b/nuttx/configs/sim/nxffs/defconfig @@ -232,3 +232,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/sim/nxwm/defconfig b/nuttx/configs/sim/nxwm/defconfig index 9029b3b2f1..e38e07b170 100644 --- a/nuttx/configs/sim/nxwm/defconfig +++ b/nuttx/configs/sim/nxwm/defconfig @@ -402,3 +402,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/sim/pashello/defconfig b/nuttx/configs/sim/pashello/defconfig index b40ec626ec..fedf401d85 100644 --- a/nuttx/configs/sim/pashello/defconfig +++ b/nuttx/configs/sim/pashello/defconfig @@ -211,3 +211,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/sim/touchscreen/defconfig b/nuttx/configs/sim/touchscreen/defconfig index 6a2e3e304d..df2a0553c8 100644 --- a/nuttx/configs/sim/touchscreen/defconfig +++ b/nuttx/configs/sim/touchscreen/defconfig @@ -318,3 +318,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=8192 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/skp16c26/ostest/defconfig b/nuttx/configs/skp16c26/ostest/defconfig index f3370d48cb..d223a8350d 100644 --- a/nuttx/configs/skp16c26/ostest/defconfig +++ b/nuttx/configs/skp16c26/ostest/defconfig @@ -317,3 +317,11 @@ CONFIG_PTHREAD_STACK_MIN=64 CONFIG_PTHREAD_STACK_DEFAULT=256 CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/stm3210e-eval/RIDE/defconfig b/nuttx/configs/stm3210e-eval/RIDE/defconfig index 7032bd975b..64665f47e7 100755 --- a/nuttx/configs/stm3210e-eval/RIDE/defconfig +++ b/nuttx/configs/stm3210e-eval/RIDE/defconfig @@ -275,6 +275,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/buttons/defconfig b/nuttx/configs/stm3210e-eval/buttons/defconfig index 37b1cf968c..0d6882b5d1 100644 --- a/nuttx/configs/stm3210e-eval/buttons/defconfig +++ b/nuttx/configs/stm3210e-eval/buttons/defconfig @@ -286,6 +286,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/composite/defconfig b/nuttx/configs/stm3210e-eval/composite/defconfig index fa485f4df5..2db58aee50 100755 --- a/nuttx/configs/stm3210e-eval/composite/defconfig +++ b/nuttx/configs/stm3210e-eval/composite/defconfig @@ -292,6 +292,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/nsh/defconfig b/nuttx/configs/stm3210e-eval/nsh/defconfig index 1341c58916..52fdd777f4 100755 --- a/nuttx/configs/stm3210e-eval/nsh/defconfig +++ b/nuttx/configs/stm3210e-eval/nsh/defconfig @@ -283,6 +283,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/nsh2/defconfig b/nuttx/configs/stm3210e-eval/nsh2/defconfig index 0ce49deb5c..a55a0da5f7 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/defconfig +++ b/nuttx/configs/stm3210e-eval/nsh2/defconfig @@ -348,6 +348,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/nx/defconfig b/nuttx/configs/stm3210e-eval/nx/defconfig index 6569c9a652..9c2ccf67c1 100644 --- a/nuttx/configs/stm3210e-eval/nx/defconfig +++ b/nuttx/configs/stm3210e-eval/nx/defconfig @@ -300,6 +300,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/nxconsole/defconfig b/nuttx/configs/stm3210e-eval/nxconsole/defconfig index 070bcde42a..c4de790d9c 100644 --- a/nuttx/configs/stm3210e-eval/nxconsole/defconfig +++ b/nuttx/configs/stm3210e-eval/nxconsole/defconfig @@ -301,6 +301,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/nxlines/defconfig b/nuttx/configs/stm3210e-eval/nxlines/defconfig index 8517f45e52..c24e858245 100644 --- a/nuttx/configs/stm3210e-eval/nxlines/defconfig +++ b/nuttx/configs/stm3210e-eval/nxlines/defconfig @@ -300,6 +300,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/nxtext/defconfig b/nuttx/configs/stm3210e-eval/nxtext/defconfig index d554a0a7a9..038e20927a 100644 --- a/nuttx/configs/stm3210e-eval/nxtext/defconfig +++ b/nuttx/configs/stm3210e-eval/nxtext/defconfig @@ -300,6 +300,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig index abb4b925ca..8ed1795a6b 100755 --- a/nuttx/configs/stm3210e-eval/ostest/defconfig +++ b/nuttx/configs/stm3210e-eval/ostest/defconfig @@ -295,6 +295,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/pm/defconfig b/nuttx/configs/stm3210e-eval/pm/defconfig index 00d307c64c..02823ef291 100644 --- a/nuttx/configs/stm3210e-eval/pm/defconfig +++ b/nuttx/configs/stm3210e-eval/pm/defconfig @@ -379,6 +379,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/usbserial/defconfig b/nuttx/configs/stm3210e-eval/usbserial/defconfig index 0672be24d9..b41b41f508 100755 --- a/nuttx/configs/stm3210e-eval/usbserial/defconfig +++ b/nuttx/configs/stm3210e-eval/usbserial/defconfig @@ -285,6 +285,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3210e-eval/usbstorage/defconfig b/nuttx/configs/stm3210e-eval/usbstorage/defconfig index 57facca011..9f927d7e30 100755 --- a/nuttx/configs/stm3210e-eval/usbstorage/defconfig +++ b/nuttx/configs/stm3210e-eval/usbstorage/defconfig @@ -292,6 +292,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3220g-eval/dhcpd/defconfig b/nuttx/configs/stm3220g-eval/dhcpd/defconfig index 39f2427fd7..04f243d718 100644 --- a/nuttx/configs/stm3220g-eval/dhcpd/defconfig +++ b/nuttx/configs/stm3220g-eval/dhcpd/defconfig @@ -356,6 +356,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3220g-eval/nettest/defconfig b/nuttx/configs/stm3220g-eval/nettest/defconfig index a186ad67ce..201df86b0b 100644 --- a/nuttx/configs/stm3220g-eval/nettest/defconfig +++ b/nuttx/configs/stm3220g-eval/nettest/defconfig @@ -356,6 +356,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3220g-eval/nsh/defconfig b/nuttx/configs/stm3220g-eval/nsh/defconfig index 92741b91fb..f1838a38b7 100644 --- a/nuttx/configs/stm3220g-eval/nsh/defconfig +++ b/nuttx/configs/stm3220g-eval/nsh/defconfig @@ -402,6 +402,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3220g-eval/nsh2/defconfig b/nuttx/configs/stm3220g-eval/nsh2/defconfig index 98b8b1923e..2395fd785a 100644 --- a/nuttx/configs/stm3220g-eval/nsh2/defconfig +++ b/nuttx/configs/stm3220g-eval/nsh2/defconfig @@ -401,6 +401,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3220g-eval/nxwm/defconfig b/nuttx/configs/stm3220g-eval/nxwm/defconfig index 32d9c31ebb..78439e4c01 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/defconfig +++ b/nuttx/configs/stm3220g-eval/nxwm/defconfig @@ -403,6 +403,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3220g-eval/ostest/defconfig b/nuttx/configs/stm3220g-eval/ostest/defconfig index 2f69fdc24b..9384a7f141 100644 --- a/nuttx/configs/stm3220g-eval/ostest/defconfig +++ b/nuttx/configs/stm3220g-eval/ostest/defconfig @@ -346,6 +346,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3220g-eval/telnetd/defconfig b/nuttx/configs/stm3220g-eval/telnetd/defconfig index c41c370881..1401dc6e7d 100644 --- a/nuttx/configs/stm3220g-eval/telnetd/defconfig +++ b/nuttx/configs/stm3220g-eval/telnetd/defconfig @@ -356,6 +356,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3240g-eval/dhcpd/defconfig b/nuttx/configs/stm3240g-eval/dhcpd/defconfig index dd0342d70b..80293f66a5 100644 --- a/nuttx/configs/stm3240g-eval/dhcpd/defconfig +++ b/nuttx/configs/stm3240g-eval/dhcpd/defconfig @@ -362,6 +362,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3240g-eval/nettest/defconfig b/nuttx/configs/stm3240g-eval/nettest/defconfig index 5c5053dda8..81a53bd680 100644 --- a/nuttx/configs/stm3240g-eval/nettest/defconfig +++ b/nuttx/configs/stm3240g-eval/nettest/defconfig @@ -362,6 +362,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig index 1501e32d1b..3b1092487c 100644 --- a/nuttx/configs/stm3240g-eval/nsh/defconfig +++ b/nuttx/configs/stm3240g-eval/nsh/defconfig @@ -407,6 +407,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3240g-eval/nsh2/defconfig b/nuttx/configs/stm3240g-eval/nsh2/defconfig index 4e5eff8bd8..ba64456157 100644 --- a/nuttx/configs/stm3240g-eval/nsh2/defconfig +++ b/nuttx/configs/stm3240g-eval/nsh2/defconfig @@ -407,6 +407,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3240g-eval/nxconsole/defconfig b/nuttx/configs/stm3240g-eval/nxconsole/defconfig index 5eada6ab2b..49a2b6631b 100644 --- a/nuttx/configs/stm3240g-eval/nxconsole/defconfig +++ b/nuttx/configs/stm3240g-eval/nxconsole/defconfig @@ -406,6 +406,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3240g-eval/nxwm/defconfig b/nuttx/configs/stm3240g-eval/nxwm/defconfig index 39ffcd07d3..7ab42a7cb9 100644 --- a/nuttx/configs/stm3240g-eval/nxwm/defconfig +++ b/nuttx/configs/stm3240g-eval/nxwm/defconfig @@ -408,6 +408,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3240g-eval/ostest/defconfig b/nuttx/configs/stm3240g-eval/ostest/defconfig index 3c29fca51c..95a06dea03 100644 --- a/nuttx/configs/stm3240g-eval/ostest/defconfig +++ b/nuttx/configs/stm3240g-eval/ostest/defconfig @@ -351,6 +351,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3240g-eval/telnetd/defconfig b/nuttx/configs/stm3240g-eval/telnetd/defconfig index 8d5b449744..471845c144 100644 --- a/nuttx/configs/stm3240g-eval/telnetd/defconfig +++ b/nuttx/configs/stm3240g-eval/telnetd/defconfig @@ -362,6 +362,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm3240g-eval/webserver/defconfig b/nuttx/configs/stm3240g-eval/webserver/defconfig index 1ea4cf9438..c365b7fa10 100644 --- a/nuttx/configs/stm3240g-eval/webserver/defconfig +++ b/nuttx/configs/stm3240g-eval/webserver/defconfig @@ -407,6 +407,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm32f4discovery/nsh/defconfig b/nuttx/configs/stm32f4discovery/nsh/defconfig index df802fee39..8967fd01c5 100644 --- a/nuttx/configs/stm32f4discovery/nsh/defconfig +++ b/nuttx/configs/stm32f4discovery/nsh/defconfig @@ -376,6 +376,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm32f4discovery/nxlines/defconfig b/nuttx/configs/stm32f4discovery/nxlines/defconfig index 34f6f636d9..f19882006b 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/defconfig +++ b/nuttx/configs/stm32f4discovery/nxlines/defconfig @@ -376,6 +376,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/stm32f4discovery/pm/defconfig b/nuttx/configs/stm32f4discovery/pm/defconfig index 0a463d9bd6..105eb4d37c 100644 --- a/nuttx/configs/stm32f4discovery/pm/defconfig +++ b/nuttx/configs/stm32f4discovery/pm/defconfig @@ -395,6 +395,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/sure-pic32mx/nsh/defconfig b/nuttx/configs/sure-pic32mx/nsh/defconfig index ae7b4b83e3..050f302479 100644 --- a/nuttx/configs/sure-pic32mx/nsh/defconfig +++ b/nuttx/configs/sure-pic32mx/nsh/defconfig @@ -287,6 +287,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/sure-pic32mx/ostest/defconfig b/nuttx/configs/sure-pic32mx/ostest/defconfig index 95c0448510..eb386e2327 100644 --- a/nuttx/configs/sure-pic32mx/ostest/defconfig +++ b/nuttx/configs/sure-pic32mx/ostest/defconfig @@ -266,6 +266,14 @@ CONFIG_PREALLOC_TIMERS=4 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/sure-pic32mx/usbnsh/defconfig b/nuttx/configs/sure-pic32mx/usbnsh/defconfig index cfdc83d4be..2b28b94c72 100644 --- a/nuttx/configs/sure-pic32mx/usbnsh/defconfig +++ b/nuttx/configs/sure-pic32mx/usbnsh/defconfig @@ -284,6 +284,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/teensy/hello/defconfig b/nuttx/configs/teensy/hello/defconfig index 05349bf473..93376ac575 100644 --- a/nuttx/configs/teensy/hello/defconfig +++ b/nuttx/configs/teensy/hello/defconfig @@ -215,6 +215,14 @@ CONFIG_PREALLOC_TIMERS=0 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/teensy/nsh/defconfig b/nuttx/configs/teensy/nsh/defconfig index f8e71d7e94..ffcd94c1dc 100755 --- a/nuttx/configs/teensy/nsh/defconfig +++ b/nuttx/configs/teensy/nsh/defconfig @@ -215,6 +215,14 @@ CONFIG_PREALLOC_TIMERS=0 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/teensy/usbstorage/defconfig b/nuttx/configs/teensy/usbstorage/defconfig index 08b8fd842e..dba45073f9 100755 --- a/nuttx/configs/teensy/usbstorage/defconfig +++ b/nuttx/configs/teensy/usbstorage/defconfig @@ -216,6 +216,14 @@ CONFIG_PREALLOC_TIMERS=0 CONFIG_FS_FAT=y CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/twr-k60n512/nsh/defconfig b/nuttx/configs/twr-k60n512/nsh/defconfig index d4b8f77fa8..aeb0c5359a 100644 --- a/nuttx/configs/twr-k60n512/nsh/defconfig +++ b/nuttx/configs/twr-k60n512/nsh/defconfig @@ -279,6 +279,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/twr-k60n512/ostest/defconfig b/nuttx/configs/twr-k60n512/ostest/defconfig index 8505ac12d8..9cf37c763b 100644 --- a/nuttx/configs/twr-k60n512/ostest/defconfig +++ b/nuttx/configs/twr-k60n512/ostest/defconfig @@ -278,6 +278,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ubw32/nsh/defconfig b/nuttx/configs/ubw32/nsh/defconfig index a6fe0051d4..320b7e2669 100644 --- a/nuttx/configs/ubw32/nsh/defconfig +++ b/nuttx/configs/ubw32/nsh/defconfig @@ -274,6 +274,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/ubw32/ostest/defconfig b/nuttx/configs/ubw32/ostest/defconfig index 857684409e..71f2867001 100644 --- a/nuttx/configs/ubw32/ostest/defconfig +++ b/nuttx/configs/ubw32/ostest/defconfig @@ -273,6 +273,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_FS_NXFFS=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/us7032evb1/nsh/defconfig b/nuttx/configs/us7032evb1/nsh/defconfig index 7dd5dc6983..2405dc2d3b 100644 --- a/nuttx/configs/us7032evb1/nsh/defconfig +++ b/nuttx/configs/us7032evb1/nsh/defconfig @@ -191,6 +191,14 @@ CONFIG_PREALLOC_TIMERS=0 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/us7032evb1/ostest/defconfig b/nuttx/configs/us7032evb1/ostest/defconfig index 286c619989..e910f112f2 100644 --- a/nuttx/configs/us7032evb1/ostest/defconfig +++ b/nuttx/configs/us7032evb1/ostest/defconfig @@ -191,6 +191,14 @@ CONFIG_PREALLOC_TIMERS=0 CONFIG_FS_FAT=n CONFIG_FS_ROMFS=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/vsn/nsh/defconfig b/nuttx/configs/vsn/nsh/defconfig index a43deab6f1..fa5570596a 100755 --- a/nuttx/configs/vsn/nsh/defconfig +++ b/nuttx/configs/vsn/nsh/defconfig @@ -326,6 +326,14 @@ CONFIG_I2C_WRITEREAD=y CONFIG_I2C_TRANSFER=y CONFIG_I2C_SLAVE=n +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y + # # SPI-based MMC/SD driver # diff --git a/nuttx/configs/xtrs/nsh/defconfig b/nuttx/configs/xtrs/nsh/defconfig index 7065ad8d5c..dc4e595563 100644 --- a/nuttx/configs/xtrs/nsh/defconfig +++ b/nuttx/configs/xtrs/nsh/defconfig @@ -217,3 +217,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=1024 CONFIG_HEAP_SIZE= CONFIG_HEAP_BASE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/xtrs/ostest/defconfig b/nuttx/configs/xtrs/ostest/defconfig index 5759b9105f..0104deb2c9 100644 --- a/nuttx/configs/xtrs/ostest/defconfig +++ b/nuttx/configs/xtrs/ostest/defconfig @@ -202,3 +202,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=1024 CONFIG_HEAP_SIZE= CONFIG_HEAP_BASE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/xtrs/pashello/defconfig b/nuttx/configs/xtrs/pashello/defconfig index 0d80ec0741..52d4e6b839 100644 --- a/nuttx/configs/xtrs/pashello/defconfig +++ b/nuttx/configs/xtrs/pashello/defconfig @@ -202,3 +202,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=1024 CONFIG_HEAP_SIZE= CONFIG_HEAP_BASE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/z16f2800100zcog/ostest/defconfig b/nuttx/configs/z16f2800100zcog/ostest/defconfig index 0bfb09ea81..16f0177784 100644 --- a/nuttx/configs/z16f2800100zcog/ostest/defconfig +++ b/nuttx/configs/z16f2800100zcog/ostest/defconfig @@ -215,3 +215,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_SIZE= CONFIG_HEAP_BASE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/z16f2800100zcog/pashello/defconfig b/nuttx/configs/z16f2800100zcog/pashello/defconfig index 1c2fb80f20..eec7b15752 100644 --- a/nuttx/configs/z16f2800100zcog/pashello/defconfig +++ b/nuttx/configs/z16f2800100zcog/pashello/defconfig @@ -215,3 +215,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=4096 CONFIG_HEAP_SIZE= CONFIG_HEAP_BASE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/z80sim/nsh/defconfig b/nuttx/configs/z80sim/nsh/defconfig index 5dd0cdc4b3..c86b0edc1d 100644 --- a/nuttx/configs/z80sim/nsh/defconfig +++ b/nuttx/configs/z80sim/nsh/defconfig @@ -213,3 +213,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=1024 CONFIG_HEAP_SIZE= CONFIG_HEAP_BASE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/z80sim/ostest/defconfig b/nuttx/configs/z80sim/ostest/defconfig index 9fa525259e..d81ae74582 100644 --- a/nuttx/configs/z80sim/ostest/defconfig +++ b/nuttx/configs/z80sim/ostest/defconfig @@ -198,3 +198,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=1024 CONFIG_HEAP_SIZE= CONFIG_HEAP_BASE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/z80sim/pashello/defconfig b/nuttx/configs/z80sim/pashello/defconfig index db32f93fb8..655c87408b 100644 --- a/nuttx/configs/z80sim/pashello/defconfig +++ b/nuttx/configs/z80sim/pashello/defconfig @@ -198,3 +198,11 @@ CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=1024 CONFIG_HEAP_SIZE= CONFIG_HEAP_BASE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/z8encore000zco/ostest/defconfig b/nuttx/configs/z8encore000zco/ostest/defconfig index 35ed60abad..4ed80ba69c 100644 --- a/nuttx/configs/z8encore000zco/ostest/defconfig +++ b/nuttx/configs/z8encore000zco/ostest/defconfig @@ -219,3 +219,11 @@ CONFIG_PTHREAD_STACK_MIN=128 CONFIG_PTHREAD_STACK_DEFAULT=256 CONFIG_HEAP_SIZE= CONFIG_HEAP_BASE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/configs/z8f64200100kit/ostest/defconfig b/nuttx/configs/z8f64200100kit/ostest/defconfig index 3384346986..bed04a40e5 100644 --- a/nuttx/configs/z8f64200100kit/ostest/defconfig +++ b/nuttx/configs/z8f64200100kit/ostest/defconfig @@ -219,3 +219,11 @@ CONFIG_PTHREAD_STACK_MIN=128 CONFIG_PTHREAD_STACK_DEFAULT=256 CONFIG_HEAP_SIZE= CONFIG_HEAP_BASE= + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y diff --git a/nuttx/drivers/mmcsd/Make.defs b/nuttx/drivers/mmcsd/Make.defs index 8504565972..455ac286d2 100644 --- a/nuttx/drivers/mmcsd/Make.defs +++ b/nuttx/drivers/mmcsd/Make.defs @@ -33,9 +33,17 @@ # ############################################################################ +if ($(CONFIG_MMCSD),y) + # Include MMC/SD drivers -CSRCS += mmcsd_sdio.c mmcsd_spi.c mmcsd_debug.c +if ($(CONFIG_MMCSD_SDIO),y) +CSRCS += mmcsd_sdio.c +endif + +if ($(CONFIG_MMCSD_SPI),y) +CSRCS += mmcsd_spi.c mmcsd_debug.c +endif # Include MMC/SD driver build support @@ -43,4 +51,6 @@ DEPPATH += --dep-path mmcsd VPATH += :mmcsd CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/mmcsd} +endif + diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.c b/nuttx/drivers/mmcsd/mmcsd_sdio.c index d0bc6659cb..64b045bc27 100644 --- a/nuttx/drivers/mmcsd/mmcsd_sdio.c +++ b/nuttx/drivers/mmcsd/mmcsd_sdio.c @@ -38,6 +38,9 @@ ****************************************************************************/ #include + +#if defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SDIO) + #include #include @@ -3178,3 +3181,5 @@ errout_with_alloc: kfree(priv); return ret; } + +#endif /* defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SDIO) */ diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c index 39b5705812..d437b7feaa 100644 --- a/nuttx/drivers/mmcsd/mmcsd_spi.c +++ b/nuttx/drivers/mmcsd/mmcsd_spi.c @@ -38,6 +38,9 @@ ****************************************************************************/ #include + +#if defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SPI) + #include #include @@ -1878,3 +1881,5 @@ int mmcsd_spislotinitialize(int minor, int slotno, FAR struct spi_dev_s *spi) (void)SPI_REGISTERCALLBACK(spi, mmcsd_mediachanged, (void*)slot); return OK; } + +#endif /* defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SPI) */ From a1d2cc2cb43cd7b09ecf12b876fd033e871bd79f Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 6 Nov 2012 16:59:45 +0000 Subject: [PATCH 086/206] Fix apps/netutils/webclient build problem git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5317 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/ostest/Kconfig | 2 - apps/include/netutils/webclient.h | 2 + apps/netutils/webclient/webclient.c | 17 +- nuttx/configs/Kconfig | 2 +- nuttx/configs/shenzhou/nsh/defconfig | 311 ++++----------------------- nuttx/drivers/mmcsd/Make.defs | 6 +- 6 files changed, 65 insertions(+), 275 deletions(-) diff --git a/apps/examples/ostest/Kconfig b/apps/examples/ostest/Kconfig index 3c64dc0c6d..c3fe8f21df 100644 --- a/apps/examples/ostest/Kconfig +++ b/apps/examples/ostest/Kconfig @@ -43,7 +43,6 @@ config EXAMPLES_OSTEST_RR_RANGE int "Round-robin test - end of search range" default 10000 range 1 32767 - depends on RR_INTERVAL > 0 ---help--- During round-robin scheduling test two threads are created. Each of the threads searches for prime numbers in the configurable range, doing that configurable @@ -57,7 +56,6 @@ config EXAMPLES_OSTEST_RR_RUNS int "Round-robin test - number of runs" default 10 range 1 32767 - depends on RR_INTERVAL > 0 ---help--- During round-robin scheduling test two threads are created. Each of the threads searches for prime numbers in the configurable range, doing that configurable diff --git a/apps/include/netutils/webclient.h b/apps/include/netutils/webclient.h index 3a4c4ea909..85ca759e92 100644 --- a/apps/include/netutils/webclient.h +++ b/apps/include/netutils/webclient.h @@ -109,12 +109,14 @@ extern "C" { #define EXTERN extern #endif +#ifdef WGET_USE_URLENCODE EXTERN char *web_post_str(FAR char *buffer, int *size, FAR char *name, FAR char *value); EXTERN char *web_posts_str(FAR char *buffer, int *size, FAR char **name, FAR char **value, int len); EXTERN int web_post_strlen(FAR char *name, FAR char *value); EXTERN int web_posts_strlen(FAR char **name, FAR char **value, int len); +#endif /**************************************************************************** * Name: wget diff --git a/apps/netutils/webclient/webclient.c b/apps/netutils/webclient/webclient.c index 2604ce020c..927993179b 100644 --- a/apps/netutils/webclient/webclient.c +++ b/apps/netutils/webclient/webclient.c @@ -77,12 +77,15 @@ #if defined(CONFIG_NETUTILS_CODECS) # if defined(CONFIG_CODECS_URLCODE) -# define WGET_USE_URLENCODE 1 +# define WGET_USE_URLENCODE 1 # include # endif # if defined(CONFIG_CODECS_BASE64) # include # endif +#else +# undef CONFIG_CODECS_URLCODE +# undef CONFIG_CODECS_BASE64 #endif #ifndef CONFIG_NSH_WGET_USERAGENT @@ -206,7 +209,7 @@ static char *wget_strcpy(char *dest, const char *src) * Name: wget_urlencode_strcpy ****************************************************************************/ -#ifdef WGET_USE_URLENCODE +#ifdef WGET_USE_URLENCODE static char *wget_urlencode_strcpy(char *dest, const char *src) { int len = strlen(src); @@ -621,6 +624,7 @@ errout: * Name: web_post_str ****************************************************************************/ +#ifdef WGET_USE_URLENCODE char *web_post_str(FAR char *buffer, int *size, FAR char *name, FAR char *value) { @@ -631,20 +635,24 @@ char *web_post_str(FAR char *buffer, int *size, FAR char *name, *size = buffer - dst; return dst; } +#endif /**************************************************************************** * Name: web_post_strlen ****************************************************************************/ +#ifdef WGET_USE_URLENCODE int web_post_strlen(FAR char *name, FAR char *value) { return strlen(name) + urlencode_len(value,strlen(value)) + 1; } +#endif /**************************************************************************** * Name: web_posts_str ****************************************************************************/ +#ifdef WGET_USE_URLENCODE char *web_posts_str(FAR char *buffer, int *size, FAR char **name, FAR char **value, int len) { @@ -667,11 +675,13 @@ char *web_posts_str(FAR char *buffer, int *size, FAR char **name, *size=buffer-dst; return dst; } +#endif /**************************************************************************** * Name: web_posts_strlen ****************************************************************************/ +#ifdef WGET_USE_URLENCODE int web_posts_strlen(FAR char **name, FAR char **value, int len) { int wlen = 0; @@ -684,6 +694,7 @@ int web_posts_strlen(FAR char **name, FAR char **value, int len) return wlen + len - 1; } +#endif /**************************************************************************** * Name: wget @@ -720,7 +731,7 @@ int wget(FAR const char *url, FAR char *buffer, int buflen, } /**************************************************************************** - * Name: web_posts_strlen + * Name: wget_post ****************************************************************************/ int wget_post(FAR const char *url, FAR const char *posts, FAR char *buffer, diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig index c03102409d..be93b7a442 100644 --- a/nuttx/configs/Kconfig +++ b/nuttx/configs/Kconfig @@ -860,7 +860,7 @@ if ARCH_BOARD_STM3240G_EVAL source "configs/stm3240g-eval/Kconfig" endif if ARCH_BOARD_STM32F100RC_GENERIC -source "configs/stm32f100_generic/Kconfig" +source "configs/stm32f100rc_generic/Kconfig" endif if ARCH_BOARD_STM32F4_DISCOVERY source "configs/stm32f4discovery/Kconfig" diff --git a/nuttx/configs/shenzhou/nsh/defconfig b/nuttx/configs/shenzhou/nsh/defconfig index b37da788e3..c1e1818a5f 100644 --- a/nuttx/configs/shenzhou/nsh/defconfig +++ b/nuttx/configs/shenzhou/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # # CONFIG_ARCH_STDBOOL_H is not set # CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set # CONFIG_ARCH_STDARG_H is not set # @@ -51,6 +52,10 @@ CONFIG_ARCH_ARM=y # CONFIG_ARCH_Z16 is not set # CONFIG_ARCH_Z80 is not set CONFIG_ARCH="arm" + +# +# ARM Options +# # CONFIG_ARCH_CHIP_C5471 is not set # CONFIG_ARCH_CHIP_CALYPSO is not set # CONFIG_ARCH_CHIP_DM320 is not set @@ -68,6 +73,8 @@ CONFIG_ARCH_CHIP_STM32=y CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARMV7M_MPU is not set CONFIG_ARCH_IRQPRIO=y @@ -83,8 +90,14 @@ CONFIG_BOARD_LOOPSPERMSEC=5483 # CONFIG_ARCH_CHIP_STM32F100CB is not set # CONFIG_ARCH_CHIP_STM32F100R8 is not set # CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set # CONFIG_ARCH_CHIP_STM32F100V8 is not set # CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set # CONFIG_ARCH_CHIP_STM32F103RET6 is not set # CONFIG_ARCH_CHIP_STM32F103VCT6 is not set # CONFIG_ARCH_CHIP_STM32F103VET6 is not set @@ -118,11 +131,11 @@ CONFIG_STM32_CODESOURCERYW=y # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set +CONFIG_STM32_BKP=y +# CONFIG_STM32_CAN1 is not set # CONFIG_STM32_CRC is not set # CONFIG_STM32_DMA1 is not set # CONFIG_STM32_DMA2 is not set -CONFIG_STM32_BKP=y -# CONFIG_STM32_CAN1 is not set # CONFIG_STM32_DAC1 is not set # CONFIG_STM32_DAC2 is not set CONFIG_STM32_ETHMAC=y @@ -153,9 +166,9 @@ CONFIG_STM32_SPI=y # # Alternate Pin Mapping # -CONFIG_STM32_USART2_REMAP=y -# CONFIG_STM32_SPI1_REMAP is not set CONFIG_STM32_ETH_REMAP=y +# CONFIG_STM32_SPI1_REMAP is not set +CONFIG_STM32_USART2_REMAP=y # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -445,6 +458,14 @@ CONFIG_FAT_MAXFNAME=32 CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + # # Library Routines # @@ -452,6 +473,7 @@ CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" +# CONFIG_LIBM is not set # CONFIG_NOPRINTF_FIELDWIDTH is not set # CONFIG_LIBC_FLOATINGPOINT is not set # CONFIG_EOL_IS_CR is not set @@ -464,10 +486,19 @@ CONFIG_ARCH_LOWPUTC=y CONFIG_LIB_SENDFILE_BUFSIZE=512 # CONFIG_ARCH_ROMGETC is not set # CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set + +# +# Basic CXX Support +# CONFIG_HAVE_CXX=y # CONFIG_HAVE_CXXINITIALIZE is not set # CONFIG_CXX_NEWLONG is not set +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + # # Application Configuration # @@ -480,260 +511,57 @@ CONFIG_NAMEDAPP=y # # Examples # - -# -# ADC Example -# -# CONFIG_EXAMPLES_ADC is not set - -# -# Buttons Example -# # CONFIG_EXAMPLES_BUTTONS is not set - -# -# CAN Example -# # CONFIG_EXAMPLES_CAN is not set - -# -# USB CDC/ACM Class Driver Example -# # CONFIG_EXAMPLES_CDCACM is not set - -# -# USB composite Class Driver Example -# # CONFIG_EXAMPLES_COMPOSITE is not set - -# -# DHCP Server Example -# +# CONFIG_EXAMPLES_CXXTEST is not set # CONFIG_EXAMPLES_DHCPD is not set - -# -# FTP Client Example -# +# CONFIG_EXAMPLES_ELF is not set # CONFIG_EXAMPLES_FTPC is not set - -# -# FTP Server Example -# # CONFIG_EXAMPLES_FTPD is not set - -# -# "Hello, World!" Example -# # CONFIG_EXAMPLES_HELLO is not set - -# -# "Hello, World!" C++ Example -# # CONFIG_EXAMPLES_HELLOXX is not set - -# -# USB HID Keyboard Example -# +# CONFIG_EXAMPLES_JSON is not set # CONFIG_EXAMPLES_HIDKBD is not set - -# -# IGMP Example -# # CONFIG_EXAMPLES_IGMP is not set - -# -# LCD Read/Write Example -# # CONFIG_EXAMPLES_LCDRW is not set - -# -# Memory Management Example -# # CONFIG_EXAMPLES_MM is not set - -# -# File System Mount Example -# # CONFIG_EXAMPLES_MOUNT is not set - -# -# FreeModBus Example -# # CONFIG_EXAMPLES_MODBUS is not set - -# -# Network Test Example -# # CONFIG_EXAMPLES_NETTEST is not set - -# -# NuttShell (NSH) Example -# CONFIG_EXAMPLES_NSH=y - -# -# NULL Example -# # CONFIG_EXAMPLES_NULL is not set - -# -# NX Graphics Example -# # CONFIG_EXAMPLES_NX is not set - -# -# NxConsole Example -# # CONFIG_EXAMPLES_NXCONSOLE is not set - -# -# NXFFS File System Example -# # CONFIG_EXAMPLES_NXFFS is not set - -# -# NXFLAT Example -# # CONFIG_EXAMPLES_NXFLAT is not set - -# -# NX Graphics "Hello, World!" Example -# # CONFIG_EXAMPLES_NXHELLO is not set - -# -# NX Graphics image Example -# # CONFIG_EXAMPLES_NXIMAGE is not set - -# -# NX Graphics lines Example -# # CONFIG_EXAMPLES_NXLINES is not set - -# -# NX Graphics Text Example -# # CONFIG_EXAMPLES_NXTEXT is not set - -# -# OS Test Example -# # CONFIG_EXAMPLES_OSTEST is not set - -# -# Pascal "Hello, World!"example -# # CONFIG_EXAMPLES_PASHELLO is not set - -# -# Pipe Example -# # CONFIG_EXAMPLES_PIPE is not set - -# -# Poll Example -# # CONFIG_EXAMPLES_POLL is not set - -# -# Pulse Width Modulation (PWM) Example -# - -# -# Quadrature Encoder Example -# # CONFIG_EXAMPLES_QENCODER is not set - -# -# RGMP Example -# # CONFIG_EXAMPLES_RGMP is not set - -# -# ROMFS Example -# # CONFIG_EXAMPLES_ROMFS is not set - -# -# sendmail Example -# # CONFIG_EXAMPLES_SENDMAIL is not set - -# -# Serial Loopback Example -# # CONFIG_EXAMPLES_SERLOOP is not set - -# -# Telnet Daemon Example -# # CONFIG_EXAMPLES_TELNETD is not set - -# -# THTTPD Web Server Example -# # CONFIG_EXAMPLES_THTTPD is not set - -# -# TIFF Generation Example -# # CONFIG_EXAMPLES_TIFF is not set - -# -# Touchscreen Example -# # CONFIG_EXAMPLES_TOUCHSCREEN is not set - -# -# UDP Example -# # CONFIG_EXAMPLES_UDP is not set - -# -# UDP Discovery Daemon Example -# # CONFIG_EXAMPLES_DISCOVER is not set - -# -# uIP Web Server Example -# # CONFIG_EXAMPLES_UIP is not set - -# -# USB Serial Test Example -# # CONFIG_EXAMPLES_USBSERIAL is not set - -# -# USB Mass Storage Class Example -# # CONFIG_EXAMPLES_USBMSC is not set - -# -# USB Serial Terminal Example -# # CONFIG_EXAMPLES_USBTERM is not set - -# -# Watchdog timer Example -# # CONFIG_EXAMPLES_WATCHDOG is not set - -# -# wget Example -# -# CONFIG_EXAMPLES_WGET is not set - -# -# WLAN Example -# # CONFIG_EXAMPLES_WLAN is not set -# -# XML RPC Example -# - # # Interpreters # @@ -751,76 +579,24 @@ CONFIG_EXAMPLES_NSH=y # # Networking Utilities # - -# -# DHCP client -# +# CONFIG_NETUTILS_CODECS is not set # CONFIG_NETUTILS_DHCPC is not set - -# -# DHCP server -# # CONFIG_NETUTILS_DHCPD is not set - -# -# FTP client -# # CONFIG_NETUTILS_FTPC is not set - -# -# FTP server -# # CONFIG_NETUTILS_FTPD is not set - -# -# Name resolution -# +# CONFIG_NETUTILS_JSON is not set CONFIG_NETUTILS_RESOLV=y CONFIG_NET_RESOLV_ENTRIES=8 - -# -# SMTP -# +CONFIG_NET_RESOLV_MAXRESPONSE=96 # CONFIG_NETUTILS_SMTP is not set - -# -# TFTP client -# CONFIG_NETUTILS_TELNETD=y - -# -# TFTP client -# CONFIG_NETUTILS_TFTPC=y - -# -# THTTPD web server -# # CONFIG_NETUTILS_THTTPD is not set - -# -# uIP support library -# CONFIG_NETUTILS_UIPLIB=y - -# -# uIP web client -# CONFIG_NETUTILS_WEBCLIENT=y - -# -# uIP web server -# +CONFIG_NSH_WGET_USERAGENT="NuttX/6.xx.x (; http://www.nuttx.org/)" # CONFIG_NETUTILS_WEBSERVER is not set - -# -# UDP Discovery Utility -# # CONFIG_NETUTILS_DISCOVER is not set - -# -# XML-RPC library -# # CONFIG_NETUTILS_XMLRPC is not set # @@ -879,6 +655,7 @@ CONFIG_NSH_BUILTIN_APPS=y # CONFIG_NSH_DISABLE_USLEEP is not set # CONFIG_NSH_DISABLE_WGET is not set # CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_CODECS_BUFSIZE=128 CONFIG_NSH_FILEIOSIZE=512 CONFIG_NSH_LINELEN=64 CONFIG_NSH_NESTDEPTH=3 @@ -894,10 +671,12 @@ CONFIG_NSH_TELNETD_DAEMONSTACKSIZE=2048 CONFIG_NSH_TELNETD_CLIENTPRIO=100 CONFIG_NSH_TELNETD_CLIENTSTACKSIZE=2048 CONFIG_NSH_IOBUFFER_SIZE=512 +# CONFIG_NSH_TELNET_LOGIN is not set CONFIG_NSH_IPADDR=0x0a000002 CONFIG_NSH_DRIPADDR=0x0a000001 CONFIG_NSH_NETMASK=0xffffff00 CONFIG_NSH_NOMAC=y +CONFIG_NSH_MAX_ROUNDTRIP=20 # # NxWidgets/NxWM diff --git a/nuttx/drivers/mmcsd/Make.defs b/nuttx/drivers/mmcsd/Make.defs index 455ac286d2..410da741b6 100644 --- a/nuttx/drivers/mmcsd/Make.defs +++ b/nuttx/drivers/mmcsd/Make.defs @@ -33,15 +33,15 @@ # ############################################################################ -if ($(CONFIG_MMCSD),y) +ifeq ($(CONFIG_MMCSD),y) # Include MMC/SD drivers -if ($(CONFIG_MMCSD_SDIO),y) +ifeq ($(CONFIG_MMCSD_SDIO),y) CSRCS += mmcsd_sdio.c endif -if ($(CONFIG_MMCSD_SPI),y) +ifeq ($(CONFIG_MMCSD_SPI),y) CSRCS += mmcsd_spi.c mmcsd_debug.c endif From ae6c7f885a8f03c8ba52e125aafdbdd9480cf72f Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 7 Nov 2012 16:04:10 +0000 Subject: [PATCH 087/206] STM32 OTG FS device fix from Petteri Aimonen git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5318 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 +- nuttx/README.txt | 11 ++++++++++- nuttx/arch/arm/src/stm32/stm32_otgfsdev.c | 13 ++++++++++++- nuttx/drivers/lcd/ug-9664hswag01.c | 2 +- 4 files changed, 24 insertions(+), 4 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 8c19ca1554..5e89c7af85 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3576,4 +3576,4 @@ added by Freddie Chopin. * configs/stm32f100_generic: Support for generic STM32F100RC board contributed by Freddie Chopin. - + * arch/arm/src/stm32_otgfsdev.c: Partial fix from Petteri Aimonen. diff --git a/nuttx/README.txt b/nuttx/README.txt index 02067fc73f..ee7f62588d 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -205,7 +205,8 @@ Instantiating "Canned" Configurations Where is the name of your development board and . Configuring NuttX requires only copying three files from the -to the directly where you installed NuttX (TOPDIR): +to the directory where you installed NuttX (TOPDIR) (and sometimes one +additional file to the directory the NuttX application package (APPSDIR)): Copy configs///Make.def to ${TOPDIR}/Make.defs @@ -227,6 +228,14 @@ to the directly where you installed NuttX (TOPDIR): included in the build and what is not. This file is also used to generate a C configuration header at include/nuttx/config.h. + Copy configs///appconfig to ${APPSDIR}/.config + + The appconfig file describes the applications that need to be + built in the appliction directory (APPSDIR). Not all configurations + have an appconfig file. This file is deprecated and will not be + used with new defconfig files produced with the mconf configuration + tool. + General information about configuring NuttX can be found in: ${TOPDIR}/configs/README.txt diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c index 461d500ad1..2d6ca9831c 100644 --- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c +++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c @@ -3900,7 +3900,7 @@ static void stm32_epout_disable(FAR struct stm32_ep_s *privep) * Name: stm32_epin_disable * * Description: - * Diable an IN endpoint will no longer be used + * Disable an IN endpoint when it will no longer be used * *******************************************************************************/ @@ -3912,6 +3912,17 @@ static void stm32_epin_disable(FAR struct stm32_ep_s *privep) usbtrace(TRACE_EPDISABLE, privep->epphy); + /* After USB reset, the endpoint will already be deactivated by the + * hardware. Trying to disable again will just hang in the wait. + */ + + regaddr = STM32_OTGFS_DIEPCTL(privep->epphy); + regval = stm32_getreg(regaddr); + if ((regval & OTGFS_DIEPCTL_USBAEP) == 0) + { + return; + } + /* Make sure that there is no pending IPEPNE interrupt (because we are * to poll this bit below). */ diff --git a/nuttx/drivers/lcd/ug-9664hswag01.c b/nuttx/drivers/lcd/ug-9664hswag01.c index e0e8e8e3a0..aae21d648e 100644 --- a/nuttx/drivers/lcd/ug-9664hswag01.c +++ b/nuttx/drivers/lcd/ug-9664hswag01.c @@ -182,7 +182,7 @@ #define UG_BPP 1 #define UG_COLORFMT FB_FMT_Y1 -/* Bytes per logical row andactual device row */ +/* Bytes per logical row and actual device row */ #define UG_XSTRIDE (UG_XRES >> 3) /* Pixels arrange "horizontally for user" */ #define UG_YSTRIDE (UG_YRES >> 3) /* But actual device arrangement is "vertical" */ From 44b76a4244d517b33d1038513e426418e30bcec8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 7 Nov 2012 21:53:14 +0000 Subject: [PATCH 088/206] Add driver for Univision UG-2864AMBAG01 git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5319 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 3 + nuttx/drivers/lcd/Kconfig | 91 +- nuttx/drivers/lcd/Make.defs | 4 + nuttx/drivers/lcd/ug-2864ambag01.c | 1175 ++++++++++++++++++++++ nuttx/drivers/lcd/ug-9664hswag01.c | 13 +- nuttx/include/nuttx/lcd/ug-2864ambag01.h | 243 +++++ nuttx/include/nuttx/lcd/ug-9664hswag01.h | 15 +- 7 files changed, 1522 insertions(+), 22 deletions(-) create mode 100644 nuttx/drivers/lcd/ug-2864ambag01.c create mode 100644 nuttx/include/nuttx/lcd/ug-2864ambag01.h diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 5e89c7af85..65c5078905 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3577,3 +3577,6 @@ * configs/stm32f100_generic: Support for generic STM32F100RC board contributed by Freddie Chopin. * arch/arm/src/stm32_otgfsdev.c: Partial fix from Petteri Aimonen. + * drivers/lcd/ug-2864ambag01.c and include/nuttx/lcd/ug_2864ambag01.h: + LCD driver for the Univision OLED of the same name. + diff --git a/nuttx/drivers/lcd/Kconfig b/nuttx/drivers/lcd/Kconfig index 640239e637..18c0dd87c6 100644 --- a/nuttx/drivers/lcd/Kconfig +++ b/nuttx/drivers/lcd/Kconfig @@ -183,12 +183,95 @@ config NOKIA6100_RGBORD endif config LCD_UG9664HSWAG01 - bool "9664HSWAG01 OLED Display Module" + bool "UG-9664HSWAG01 OLED Display Module" default n ---help--- - ug-9664hswag01.c. OLED Display Module, UG-9664HSWAG01", Univision - Technology Inc. Used with the LPC Xpresso and Embedded Artists - base board. + OLED Display Module, UG-9664HSWAG01, Univision Technology Inc. Used + with the LPCXpresso and Embedded Artists base board. + + Required LCD driver settings: + LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. + LCD_MAXPOWER should be 1: 0=off, 1=on + + Required SPI driver settings: + SPI_CMDDATA - Include support for cmd/data selection. + +if LCD_UG9664HSWAG01 + +config UG9664HSWAG01_SPIMODE + int "UG-9664HSWAG01 SPI Mode" + default 0 + ---help--- + Controls the SPI mode + +config UG9664HSWAG01_FREQUENCY + int "UG-9664HSWAG01 SPI Frequency" + default 3500000 + ---help--- + Define to use a different bus frequency + +config UG9664HSWAG01_NINTERFACES + int "Number of UG-9664HSWAG01 Devices" + default 1 + ---help--- + Specifies the number of physical UG-9664HSWAG01 devices that will be + supported. NOTE: At present, this must be undefined or defined to be 1. + +config UG9664HSWAG01_POWER + bool "Power control" + default n + ---help--- + If the hardware supports a controllable OLED a power supply, this + configuration should be defined. In this case the system must + provide an interface ug_power(). + +endif + +config LCD_UG2864AMBAG01 + bool "UG-2864AMBAG01 OLED Display Module" + default n + ---help--- + OLED Display Module, UG-2864AMBAG01, Univision Technology Inc. + + Required LCD driver settings: + LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. + LCD_MAXPOWER should be 1: 0=off, 1=on + + Required SPI driver settings: + SPI_CMDDATA - Include support for cmd/data selection. + +if LCD_UG2864AMBAG01 + + config UG2864AMBAG01_SPIMODE + int "UG-2864AMBAG01 SPI Mode" + default 3 + ---help--- + Controls the SPI mode + +config UG2864AMBAG01_FREQUENCY + int "UG-2864AMBAG01 SPI Frequency" + default 3500000 + ---help--- + Define to use a different bus frequency + +config UG2864AMBAG01_NINTERFACES + int "Number of UG-2864AMBAG01 Devices" + default 1 + ---help--- + Specifies the number of physical UG-9664HSWAG01 devices that will be + supported. NOTE: At present, this must be undefined or defined to be 1. + +config UG2864AMBAG01_FRAMEBUFFER + bool "UG-2864AMBAG01 Framebuffer" + default y + ---help--- + If defined, accesses will be performed using an in-memory copy of the + OLED's GRAM. This cost of this buffer is 128 * 64 / 8 = 1Kb. + + If G2864AMBAG01_FRAMEBUFFER is not defined and the LCD is a LANDSCAPE + mode, then a 128 byte buffer is still required. + +endif config LCD_SSD1289 bool "LCD Based on SSD1289 Controller" diff --git a/nuttx/drivers/lcd/Make.defs b/nuttx/drivers/lcd/Make.defs index 26b169391f..575751d393 100644 --- a/nuttx/drivers/lcd/Make.defs +++ b/nuttx/drivers/lcd/Make.defs @@ -47,6 +47,10 @@ ifeq ($(CONFIG_LCD_NOKIA6100),y) CSRCS += nokia6100.c endif +ifeq ($(CONFIG_LCD_UG2864AMBAG01),y) + CSRCS += ug-2864ambag01.c +endif + ifeq ($(CONFIG_LCD_UG9664HSWAG01),y) CSRCS += ug-9664hswag01.c endif diff --git a/nuttx/drivers/lcd/ug-2864ambag01.c b/nuttx/drivers/lcd/ug-2864ambag01.c new file mode 100644 index 0000000000..b62fa6e43a --- /dev/null +++ b/nuttx/drivers/lcd/ug-2864ambag01.c @@ -0,0 +1,1175 @@ +/************************************************************************************** + * drivers/lcd/ug-2864ambag01.c + * Driver for Univision UG-2864AMBAG01 OLED display (wih SH1101A controller) + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * 1. Product Specification (Preliminary), Part Name: OEL Display Module, Part ID: + * UG-2864AMBAG01, Doc No: SASI-9015-A, Univision Technology Inc. + * 2. SH1101A, 132 X 64 Dot Matrix OLED/PLED, Preliminary Segment/Common Driver with + * Controller, Sino Wealth + * + * 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. + * + **************************************************************************************/ +/************************************************************************************** + * Device memory organization: + * + * +----------------------------+ + * | Column | + * --------+----+---+---+---+-...-+-----+ + * Page | 0 | 1 | 2 | 3 | ... | 131 | + * --------+----+---+---+---+-...-+-----+ + * Page 0 | D0 | X | | | | | + * | D1 | X | | | | | + * | D2 | X | | | | | + * | D3 | X | | | | | + * | D4 | X | | | | | + * | D5 | X | | | | | + * | D6 | X | | | | | + * | D7 | X | | | | | + * --------+----+---+---+---+-...-+-----+ + * Page 1 | | | | | | | + * --------+----+---+---+---+-...-+-----+ + * Page 2 | | | | | | | + * --------+----+---+---+---+-...-+-----+ + * Page 3 | | | | | | | + * --------+----+---+---+---+-...-+-----+ + * Page 4 | | | | | | | + * --------+----+---+---+---+-...-+-----+ + * Page 5 | | | | | | | + * --------+----+---+---+---+-...-+-----+ + * Page 6 | | | | | | | + * --------+----+---+---+---+-...-+-----+ + * Page 7 | | | | | | | + * --------+----+---+---+---+-...-+-----+ + * + * -----------------------------------+--------------------------------------- + * Landscape Display: | Reverse Landscape Display: + * --------+-----------------------+ | --------+---------------------------+ + * | Column | | | Column | + * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ + * Page 0 | 0 | 1 | 2 | | 131 | | Page 7 | 131 | 130 | 129 | | 0 | + * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ + * Page 1 | V | | Page 6 | ^ | + * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ + * Page 2 | V | | Page 5 | ^ | + * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ + * Page 3 | V | | Page 4 | ^ | + * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ + * Page 4 | V | | Page 3 | ^ | + * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ + * Page 5 | V | | Page 2 | ^ | + * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ + * Page 6 | V | | Page 1 | ^ | + * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ + * Page 7 | V | | Page 0 | ^ | + * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ + * -----------------------------------+--------------------------------------- + * + * -----------------------------------+--------------------------------------- + * Portrait Display: | Reverse Portrait Display: + * -----------+---------------------+ | -----------+---------------------+ + * | Page | | | Page | + * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ + * Column 0 | 0 | 1 | 2 | | 7 | | Column 131 | 7 | 6 | 5 | | 0 | + * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ + * Column 1 | > > > > > | | Column 130 | | + * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ + * Column 2 | | | Column 129 | | + * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ + * ... | | | ... | | + * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ + * Column 131 | | | Column 0 | < < < < < | + * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ + * -----------------------------------+---------------------------------------- + **************************************************************************************/ + +/************************************************************************************** + * Included Files + **************************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +#ifdef CONFIG_LCD_UG2864AMBAG01 + +/************************************************************************************** + * Pre-processor Definitions + **************************************************************************************/ +/* Configuration **********************************************************************/ +/* Limitations of the current configuration that I hope to fix someday */ + +#if CONFIG_UG2864AMBAG01_NINTERFACES != 1 +# warning "This implementation supports only a single OLED device" +# undef CONFIG_UG2864AMBAG01_NINTERFACES +# define CONFIG_UG2864AMBAG01_NINTERFACES 1 +#endif + +#ifndef CONFIG_UG2864AMBAG01_FRAMEBUFFER +# warning "CONFIG_UG2864AMBAG01_FRAMEBUFFER is required" +# define CONFIG_UG2864AMBAG01_FRAMEBUFFER 1 +#endif + +#if defined(CONFIG_LCD_PORTRAIT) || defined(CONFIG_LCD_RPORTRAIT) +# warning "No support yet for portrait modes" +# define CONFIG_LCD_LANDSCAPE 1 +# undef CONFIG_LCD_PORTRAIT +# undef CONFIG_LCD_RLANDSCAPE +# undef CONFIG_LCD_RPORTRAIT +#endif + +/* SH1101A Commands *******************************************************************/ + +#define SH1101A_SETCOLL(ad) (0x00 | ((ad) & 0x0f)) /* Set Lower Column Address: (00h - 0fh) */ +#define SH1101A_SETCOLH(ad) (0x10 | ((ad) & 0x0f)) /* Set Higher Column Address: (10h - 1fh) */ +#define SH1101A_STARTLINE(ln) (0x40 | ((ln) & 0x3f)) /* Set Display Start Line: (40h - 7fh) */ +#define SH1101A_CONTRAST_MODE (0x81) /* Set Contrast Control Register: (Double Bytes Command) */ +# define SH1101A_CONTRAST(c) (c) +#define SH1101A_SEGREMAP(m) (0xa0 | ((m) & 0x01)) /* Set Segment Re-map: (a0h - a1h) */ +# define SH1101A_REMAPRIGHT SH1101A_SEGREMAP(0) /* Right rotation */ +# define SH1101A_REMAPPLEFT SH1101A_SEGREMAP(1) /* Left rotation */ +#define SH1101A_EDISPOFFON(s) (0xa4 | ((s) & 0x01)) /* Set Entire Display OFF/ON: (a4h - a5h) */ +# define SH1101A_EDISPOFF SH1101A_EDISPOFFON(0) /* Display off */ +# define SH1101A_EDISPON SH1101A_EDISPOFFON(1) /* Display on */ +#define SH1101A_NORMREV(s) (0xa6 | ((s) & 0x01)) /* Set Normal/Reverse Display: (a6h -a7h) */ +# define SH1101A_NORMAL SH1101A_NORMREV(0) /* Normal display */ +# define SH1101A_REVERSE SH1101A_NORMREV(1) /* Reverse display */ +#define SH1101A_MRATIO_MODE (0xa8) /* Set Multiplex Ration: (Double Bytes Command) */ +# define SH1101A_MRATIO(d) ((d) & 0x3f) +#define SH1101A_DCDC_MODE (0xad) /* Set DC-DC OFF/ON: (Double Bytes Command) */ +# define SH1101A_DCDC_OFF (0x8a) + # define SH1101A_DCDC_ON (0x8b) +#define SH1101A_DISPOFFON(s) (0xae | ((s) & 0x01)) /* Display OFF/ON: (aeh - afh) */ +# define SH1101A_DISPOFF SH1101A_DISPOFFON(0) /* Display off */ +# define SH1101A_DISPON SH1101A_DISPOFFON(1) /* Display on */ +#define SH1101A_PAGEADDR(a) (0xb0 | ((a) & 0x0f)) /* Set Page Address: (b0h - b7h) */ +#define SH1101A_SCANDIR(d) (0xc0 | ((d) & 0x08)) /* Set Common Output Scan Direction: (c0h - c8h) */ +# define SH1101A_SCANFROMCOM0 SH1101A_SCANDIR(0x00) /* Scan from COM[0] to COM[n-1]*/ +# define SH1101A_SCANTOCOM0 SH1101A_SCANDIR(0x08) /* Scan from COM[n-1] to COM[0] */ +#define SH1101A_DISPOFFS_MODE (0xd3) /* Set Display Offset: (Double Bytes Command) */ +# define SH1101A_DISPOFFS(o) ((o) & 0x3f) +#define SH1101A_CLKDIV_SET (0xd5) /* Set Display Clock Divide Ratio/Oscillator Frequency: (Double Bytes Command) */ +# define SH1101A_CLKDIV(f,d) ((((f) & 0x0f) << 4) | ((d) & 0x0f)) +#define SH1101A_CHRGPER_SET (0xd9) /* Set Dis-charge/Pre-charge Period: (Double Bytes Command) */ +# define SH1101A_CHRGPER(d,p) ((((d) & 0x0f) << 4) | ((p) & 0x0f)) +#define SH1101A_CMNPAD_CONFIG (0xda) /* Set Common pads hardware configuration: (Double Bytes Command) */ + #define SH1101A_CMNPAD(c) ((0x02) | ((c) & 0x10)) +#define SH1101A_VCOM_SET (0xdb) /* Set VCOM Deselect Level: (Double Bytes Command) */ +# define SH1101A_VCOM(v) (v) +#define SH1101A_RMWSTART (0xe0) /* Read-Modify-Write: (e0h) */ +#define SH1101A_NOP (0xe3) /* NOP: (e3h) */ +#define SH1101A_END (0xee) /* End: (eeh) */ + +#define SH1101A_WRDATA(d) (d) /* Write Display Data */ +#define SH1101A_STATUS_BUSY (0x80) /* Read Status */ +#define SH1101A_STATUS_ONOFF (0x40) +#define SH1101A_RDDATA(d) (d) /* Read Display Data */ + +/* Define the CONFIG_DEBUG_LCD to enable detailed debug output (stuff you would + * never want to see unless you are debugging this file). Verbose debug must also be + * enabled + */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_VERBOSE +#endif + +#ifndef CONFIG_DEBUG_VERBOSE +# undef CONFIG_DEBUG_LCD +#endif + +/* Color Properties *******************************************************************/ +/* Display Resolution + * + * The SH1101A display controller can handle a resolution of 132x64. The UG-2864AMBAG01 + * on the base board is 128x64. + */ + +#define UG2864AMBAG01_DEV_XRES 128 /* Only 128 of 131 columns used */ +#define UG2864AMBAG01_DEV_YRES 64 /* 8 pages each 8 rows */ +#define UG2864AMBAG01_DEV_XOFFSET 2 /* Offset to logical column 0 */ +#define UG2864AMBAG01_DEV_PAGES 8 /* 8 pages */ + +#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) +# define UG2864AMBAG01_XRES UG2864AMBAG01_DEV_XRES +# define UG2864AMBAG01_YRES UG2864AMBAG01_DEV_YRES +#else +# define UG2864AMBAG01_XRES UG2864AMBAG01_DEV_YRES +# define UG2864AMBAG01_YRES UG2864AMBAG01_DEV_XRES +#endif + +/* Color depth and format */ + +#define UG2864AMBAG01_BPP 1 +#define UG2864AMBAG01_COLORFMT FB_FMT_Y1 + +/* Bytes per logical row and actual device row */ + +#define UG2864AMBAG01_XSTRIDE (UG2864AMBAG01_XRES >> 3) +#define UG2864AMBAG01_YSTRIDE (UG2864AMBAG01_YRES >> 3) + +/* Default contrast */ + +#define UG2864AMBAG01_CONTRAST (128) + +/* The size of the shadow frame buffer or one row buffer. + * + * Frame buffer size: 128 columns x 64 rows / 8 bits-per-pixel + * Row size: 128 columns x 8 rows-per-page / 8 bits-per-pixel + */ + +#define UG2864AMBAG01_FBSIZE ((UG2864AMBAG01_XRES * UG2864AMBAG01_YRES) >> 3) +#define UG2864AMBAG01_ROWSIZE (UG2864AMBAG01_XRES) + +/* Bit helpers */ + +#define LS_BIT (1 << 0) +#define MS_BIT (1 << 7) + +/* Debug ******************************************************************************/ + +#ifdef CONFIG_DEBUG_LCD +# define lcddbg(format, arg...) vdbg(format, ##arg) +#else +# define lcddbg(x...) +#endif + +/************************************************************************************** + * Private Type Definition + **************************************************************************************/ + +/* This structure describes the state of this driver */ + +struct ug2864ambag01_dev_s +{ + struct lcd_dev_s dev; /* Publically visible device structure */ + + /* Private LCD-specific information follows */ + + FAR struct spi_dev_s *spi; /* Cached SPI device reference */ + uint8_t contrast; /* Current contrast setting */ + bool on; /* true: display is on */ + + + /* If the SH1101A does not support reading from the display memory, then it will be + * necessary to keep a shadow copy of the framebuffer memory. At 128x64, this amounts + * to 1KB. + * + * If the SH1101A is writable but the display is in a landscape mode then a small + * 128 / 8 = 16 byte buffer is still required in order to perform the 90 degree + * rotation. + */ + +#if CONFIG_UG2864AMBAG01_FRAMEBUFFER + uint8_t fb[UG2864AMBAG01_FBSIZE]; +#elif defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) + uint8_t buffer[UG2864AMBAG01_ROWSIZE]; +#endif +}; + +/************************************************************************************** + * Private Function Protototypes + **************************************************************************************/ + +/* Low-level SPI helpers */ + +#ifdef CONFIG_SPI_OWNBUS +static inline void ug2864ambag01_configspi(FAR struct spi_dev_s *spi); +# define ug2864ambag01_lock(spi) +# define ug2864ambag01_unlock(spi) +#else +# define ug2864ambag01_configspi(spi) +static void ug2864ambag01_lock(FAR struct spi_dev_s *spi); +static void ug2864ambag01_unlock(FAR struct spi_dev_s *spi); +#endif + +/* Buffer Management */ + +static int ug2864ambag01_readdisplay(FAR struct ug2864ambag01_dev_s *priv, + fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, + size_t npixels); +static int ug2864ambag01_putbuffer(FAR struct ug2864ambag01_dev_s *priv, + fb_coord_t row, fb_coord_t col, + FAR const uint8_t *buffer, size_t npixels); +static int ug2864ambag01_getbuffer(FAR struct ug2864ambag01_dev_s *priv, + fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, + size_t npixels); + +/* LCD Data Transfer Methods */ + +static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, + FAR const uint8_t *buffer, size_t npixels); +static int ug2864ambag01_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, + size_t npixels); + +/* LCD Configuration */ + +static int ug2864ambag01_getvideoinfo(FAR struct lcd_dev_s *dev, + FAR struct fb_videoinfo_s *vinfo); +static int ug2864ambag01_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno, + FAR struct lcd_planeinfo_s *pinfo); + +/* LCD RGB Mapping */ + +#ifdef CONFIG_FB_CMAP +# error "RGB color mapping not supported by this driver" +#endif + +/* Cursor Controls */ + +#ifdef CONFIG_FB_HWCURSOR +# error "Cursor control not supported by this driver" +#endif + +/* LCD Specific Controls */ + +static int ug2864ambag01_getpower(struct lcd_dev_s *dev); +static int ug2864ambag01_setpower(struct lcd_dev_s *dev, int power); +static int ug2864ambag01_getcontrast(struct lcd_dev_s *dev); +static int ug2864ambag01_setcontrast(struct lcd_dev_s *dev, unsigned int contrast); + +/************************************************************************************** + * Private Data + **************************************************************************************/ + + +/* 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 + * (bpp * xres / 8). Actual alignment of the buffer must conform to the + * bitwidth of the underlying pixel type. + * + * If there are multiple planes, they may share the same working buffer + * because different planes will not be operate on concurrently. However, + * if there are multiple LCD devices, they must each have unique run buffers. + */ + +static uint8_t g_runbuffer[UG2864AMBAG01_ROWSIZE]; + +/* This structure describes the overall LCD video controller */ + +static const struct fb_videoinfo_s g_videoinfo = +{ + .fmt = UG2864AMBAG01_COLORFMT, /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */ + .xres = UG2864AMBAG01_XRES, /* Horizontal resolution in pixel columns */ + .yres = UG2864AMBAG01_YRES, /* Vertical resolution in pixel rows */ + .nplanes = 1, /* Number of color planes supported */ +}; + +/* This is the standard, NuttX Plane information object */ + +static const struct lcd_planeinfo_s g_planeinfo = +{ + .putrun = ug2864ambag01_putrun, /* Put a run into LCD memory */ + .getrun = ug2864ambag01_getrun, /* Get a run from LCD memory */ + .buffer = (uint8_t*)g_runbuffer, /* Run scratch buffer */ + .bpp = UG2864AMBAG01_BPP, /* Bits-per-pixel */ +}; + +/* This is the OLED driver instance (only a single device is supported for now) */ + +static struct ug2864ambag01_dev_s g_oleddev = +{ + .dev = + { + /* LCD Configuration */ + + .getvideoinfo = ug2864ambag01_getvideoinfo, + .getplaneinfo = ug2864ambag01_getplaneinfo, + + /* LCD RGB Mapping -- Not supported */ + /* Cursor Controls -- Not supported */ + + /* LCD Specific Controls */ + + .getpower = ug2864ambag01_getpower, + .setpower = ug2864ambag01_setpower, + .getcontrast = ug2864ambag01_getcontrast, + .setcontrast = ug2864ambag01_setcontrast, + }, +}; + +/************************************************************************************** + * Private Functions + **************************************************************************************/ + +/************************************************************************************** + * Name: ug2864ambag01_configspi + * + * Description: + * Configure the SPI for use with the UG-2864AMBAG01 + * + * Input Parameters: + * spi - Reference to the SPI driver structure + * + * Returned Value: + * None + * + * Assumptions: + * + **************************************************************************************/ + +#ifdef CONFIG_SPI_OWNBUS +static inline void ug2864ambag01_configspi(FAR struct spi_dev_s *spi) +{ + lcddbg("Mode: %d Bits: 8 Frequency: %d\n", + CONFIG_UG2864AMBAG01_SPIMODE, CONFIG_UG2864AMBAG01_FREQUENCY); + + /* Configure SPI for the UG-2864AMBAG01. But only if we own the SPI bus. Otherwise, + * don't bother because it might change. + */ + + SPI_SETMODE(spi, CONFIG_UG2864AMBAG01_SPIMODE); + SPI_SETBITS(spi, 8); + SPI_SETFREQUENCY(spi, CONFIG_UG2864AMBAG01_FREQUENCY) +} +#endif + +/************************************************************************************** + * Name: ug2864ambag01_lock + * + * Description: + * Select the SPI, locking and re-configuring if necessary + * + * Input Parameters: + * spi - Reference to the SPI driver structure + * + * Returned Value: + * None + * + * Assumptions: + * + **************************************************************************************/ + +#ifndef CONFIG_SPI_OWNBUS +static inline void ug2864ambag01_lock(FAR struct spi_dev_s *spi) +{ + /* Lock the SPI bus if there are multiple devices competing for the SPI bus. */ + + SPI_LOCK(spi, true); + + /* Now make sure that the SPI bus is configured for the UG-2864AMBAG01 (it + * might have gotten configured for a different device while unlocked) + */ + + SPI_SETMODE(spi, CONFIG_UG2864AMBAG01_SPIMODE); + SPI_SETBITS(spi, 8); + SPI_SETFREQUENCY(spi, CONFIG_UG2864AMBAG01_FREQUENCY); +} +#endif + +/************************************************************************************** + * Name: ug2864ambag01_unlock + * + * Description: + * De-select the SPI + * + * Input Parameters: + * spi - Reference to the SPI driver structure + * + * Returned Value: + * None + * + * Assumptions: + * + **************************************************************************************/ + +#ifndef CONFIG_SPI_OWNBUS +static inline void ug2864ambag01_unlock(FAR struct spi_dev_s *spi) +{ + /* De-select UG-2864AMBAG01 chip and relinquish the SPI bus. */ + + SPI_LOCK(spi, false); +} +#endif + +/************************************************************************************** + * Name: ug2864ambag01_putrun + * + * Description: + * This method can be used to write a partial raster line to the LCD. + * + * Input Parameters: + * row - Starting row to write to (range: 0 <= row < yres) + * col - Starting column to write to (range: 0 <= col <= xres-npixels) + * buffer - The buffer containing the run to be written to the LCD + * npixels - The number of pixels to write to the LCD + * (range: 0 < npixels <= xres-col) + * + **************************************************************************************/ + +#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) +static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, + size_t npixels) +{ + /* Because of this line of code, we will only be able to support a single UG device */ + + FAR struct ug2864ambag01_dev_s *priv = (FAR struct ug2864ambag01_dev_s *)&g_oleddev; + FAR uint8_t *fbptr; + FAR uint8_t *ptr; + uint8_t devcol; + uint8_t fbmask; + uint8_t page; + uint8_t usrmask; + int pixlen; + uint8_t i; + + gvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); + DEBUGASSERT(buffer); + + /* Clip the run to the display */ + + pixlen = npixels; + if ((unsigned int)col + (unsigned int)pixlen > (unsigned int)UG2864AMBAG01_XRES) + { + pixlen = (int)UG2864AMBAG01_XRES - (int)col; + } + + /* Verify that some portion of the run remains on the display */ + + if (pixlen <= 0 || row > UG2864AMBAG01_YRES) + { + return OK; + } + + /* Perform coordinate conversion for reverse landscape mode */ + +#ifdef CONFIG_LCD_RLANDSCAPE + row = (UG2864AMBAG01_YRES-1) - row; + col = (UG2864AMBAG01_XRES-1) - col; +#endif + + /* Get the page number. The range of 64 lines is divided up into eight + * pages of 8 lines each. + */ + + page = row >> 3; + + /* Update the shadow frame buffer memory. First determine the pixel + * position in the frame buffer memory. Pixels are organized like + * this: + * + * --------+---+---+---+---+-...-+-----+ + * Segment | 0 | 1 | 2 | 3 | ... | 131 | + * --------+---+---+---+---+-...-+-----+ + * D0 | | X | | | | | + * D1 | | X | | | | | + * D2 | | X | | | | | + * D3 | | X | | | | | + * D4 | | X | | | | | + * D5 | | X | | | | | + * D6 | | X | | | | | + * D7 | | X | | | | | + * --------+---+---+---+---+-...-+-----+ + * + * So, in order to draw a white, horizontal line, at row 45. we + * would have to modify all of the bytes in page 45/8 = 5. We + * would have to set bit 45%8 = 5 in every byte in the page. + */ + + fbmask = 1 << (row & 7); + fbptr = &priv->fb[page * UG2864AMBAG01_XRES + col]; + ptr = fbptr; +#ifdef CONFIG_NX_PACKEDMSFIRST + usrmask = MS_BIT; +#else + usrmask = LS_BIT; +#endif + + for (i = 0; i < pixlen; i++) + { + /* Set or clear the corresponding bit */ + + if ((*buffer & usrmask) != 0) + { + *ptr++ |= fbmask; + } + else + { + *ptr++ &= ~fbmask; + } + + /* Inc/Decrement to the next source pixel */ + +#ifdef CONFIG_NX_PACKEDMSFIRST + if (usrmask == LS_BIT) + { + buffer++; + usrmask = MS_BIT; + } + else + { + usrmask >>= 1; + } +#else + if (usrmask == MS_BIT) + { + buffer++; + usrmask = LS_BIT; + } + else + { + usrmask <<= 1; + } +#endif + } + + /* Offset the column position to account for smaller horizontal + * display range. + */ + + devcol = col + UG2864AMBAG01_DEV_XOFFSET; + + /* Lock and select device */ + + ug2864ambag01_lock(priv->spi); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); + + /* Select command transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); + + /* Set the starting position for the run */ + /* Set the column address to the XOFFSET value */ + + SPI_SEND(priv->spi, SH1101A_SETCOLL(devcol & 0x0f)); + SPI_SEND(priv->spi, SH1101A_SETCOLH(devcol >> 4)); + + /* Set the page address */ + + SPI_SEND(priv->spi, SH1101A_PAGEADDR(page)); + + /* Select data transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, false); + + /* Then transfer all of the data */ + + (void)SPI_SNDBLOCK(priv->spi, fbptr, pixlen); + + /* De-select and unlock the device */ + + SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); + ug2864ambag01_unlock(priv->spi); + return OK; +} +#else +# error "Configuration not implemented" +#endif + +/************************************************************************************** + * Name: ug2864ambag01_getrun + * + * Description: + * This method can be used to read a partial raster line from the LCD: + * + * Description: + * This method can be used to write a partial raster line to the LCD. + * + * row - Starting row to read from (range: 0 <= row < yres) + * col - Starting column to read read (range: 0 <= col <= xres-npixels) + * buffer - The buffer in which to return the run read from the LCD + * npixels - The number of pixels to read from the LCD + * (range: 0 < npixels <= xres-col) + * + **************************************************************************************/ + +#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) +static int ug2864ambag01_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, + size_t npixels) +{ + /* Because of this line of code, we will only be able to support a single UG device */ + + FAR struct ug2864ambag01_dev_s *priv = &g_oleddev; + FAR uint8_t *fbptr; + uint8_t page; + uint8_t fbmask; + uint8_t usrmask; + int pixlen; + uint8_t i; + + gvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); + DEBUGASSERT(buffer); + + /* Clip the run to the display */ + + pixlen = npixels; + if ((unsigned int)col + (unsigned int)pixlen > (unsigned int)UG2864AMBAG01_XRES) + { + pixlen = (int)UG2864AMBAG01_XRES - (int)col; + } + + /* Verify that some portion of the run is actually the display */ + + if (pixlen <= 0 || row > UG2864AMBAG01_YRES) + { + return -EINVAL; + } + + /* Perform coordinate conversion for reverse landscape mode */ + +#ifdef CONFIG_LCD_RLANDSCAPE + row = (UG2864AMBAG01_YRES-1) - row; + col = (UG2864AMBAG01_XRES-1) - col; +#endif + + /* Then transfer the display data from the shadow frame buffer memory */ + /* Get the page number. The range of 64 lines is divided up into eight + * pages of 8 lines each. + */ + + page = row >> 3; + + /* Update the shadow frame buffer memory. First determine the pixel + * position in the frame buffer memory. Pixels are organized like + * this: + * + * --------+---+---+---+---+-...-+-----+ + * Segment | 0 | 1 | 2 | 3 | ... | 131 | + * --------+---+---+---+---+-...-+-----+ + * D0 | | X | | | | | + * D1 | | X | | | | | + * D2 | | X | | | | | + * D3 | | X | | | | | + * D4 | | X | | | | | + * D5 | | X | | | | | + * D6 | | X | | | | | + * D7 | | X | | | | | + * --------+---+---+---+---+-...-+-----+ + * + * So, in order to draw a white, horizontal line, at row 45. we + * would have to modify all of the bytes in page 45/8 = 5. We + * would have to set bit 45%8 = 5 in every byte in the page. + */ + + fbmask = 1 << (row & 7); + fbptr = &priv->fb[page * UG2864AMBAG01_XRES + col]; +#ifdef CONFIG_NX_PACKEDMSFIRST + usrmask = MS_BIT; +#else + usrmask = LS_BIT; +#endif + + *buffer = 0; + for (i = 0; i < pixlen; i++) + { + /* Set or clear the corresponding bit */ + + uint8_t byte = *fbptr++; + if ((byte & fbmask) != 0) + { + *buffer |= usrmask; + } + + /* Inc/Decrement to the next destination pixel. Hmmmm. It looks like + * this logic could write past the end of the user buffer. Revisit + * this! + */ + +#ifdef CONFIG_NX_PACKEDMSFIRST + if (usrmask == LS_BIT) + { + buffer++; + *buffer = 0; + usrmask = MS_BIT; + } + else + { + usrmask >>= 1; + } +#else + if (usrmask == MS_BIT) + { + buffer++; + *buffer = 0; + usrmask = LS_BIT; + } + else + { + usrmask <<= 1; + } +#endif + } + + return OK; +} +#else +# error "Configuration not implemented" +#endif + +/************************************************************************************** + * Name: ug2864ambag01_getvideoinfo + * + * Description: + * Get information about the LCD video controller configuration. + * + **************************************************************************************/ + +static int ug2864ambag01_getvideoinfo(FAR struct lcd_dev_s *dev, + FAR struct fb_videoinfo_s *vinfo) +{ + DEBUGASSERT(dev && vinfo); + gvdbg("fmt: %d xres: %d yres: %d nplanes: %d\n", + g_videoinfo.fmt, g_videoinfo.xres, g_videoinfo.yres, g_videoinfo.nplanes); + memcpy(vinfo, &g_videoinfo, sizeof(struct fb_videoinfo_s)); + return OK; +} + +/************************************************************************************** + * Name: ug2864ambag01_getplaneinfo + * + * Description: + * Get information about the configuration of each LCD color plane. + * + **************************************************************************************/ + +static int ug2864ambag01_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno, + FAR struct lcd_planeinfo_s *pinfo) +{ + DEBUGASSERT(pinfo && planeno == 0); + gvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp); + memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s)); + return OK; +} + +/************************************************************************************** + * Name: ug2864ambag01_getpower + * + * Description: + * Get the LCD panel power status (0: full off - CONFIG_LCD_MAXPOWER: full on. On + * backlit LCDs, this setting may correspond to the backlight setting. + * + **************************************************************************************/ + +static int ug2864ambag01_getpower(FAR struct lcd_dev_s *dev) +{ + FAR struct ug2864ambag01_dev_s *priv = (FAR struct ug2864ambag01_dev_s *)dev; + DEBUGASSERT(priv); + + gvdbg("power: %s\n", priv->on ? "ON" : "OFF"); + return priv->on ? CONFIG_LCD_MAXPOWER : 0; +} + +/************************************************************************************** + * Name: ug2864ambag01_setpower + * + * Description: + * Enable/disable LCD panel power (0: full off - CONFIG_LCD_MAXPOWER: full on). On + * backlit LCDs, this setting may correspond to the backlight setting. + * + **************************************************************************************/ + +static int ug2864ambag01_setpower(struct lcd_dev_s *dev, int power) +{ + struct ug2864ambag01_dev_s *priv = (struct ug2864ambag01_dev_s *)dev; + DEBUGASSERT(priv && (unsigned)power <= CONFIG_LCD_MAXPOWER && priv->spi); + + gvdbg("power: %d [%d]\n", power, priv->on ? CONFIG_LCD_MAXPOWER : 0); + + /* Lock and select device */ + + ug2864ambag01_lock(priv->spi); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); + + if (power <= 0) + { + /* Turn the display off */ + + (void)SPI_SEND(priv->spi, SH1101A_DISPOFF); + priv->on = false; + } + else + { + /* Turn the display on */ + + (void)SPI_SEND(priv->spi, SH1101A_DISPON); /* Display on, dim mode */ + priv->on = true; + } + + /* De-select and unlock the device */ + + SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); + ug2864ambag01_unlock(priv->spi); + return OK; +} + +/************************************************************************************** + * Name: ug2864ambag01_getcontrast + * + * Description: + * Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST). + * + **************************************************************************************/ + +static int ug2864ambag01_getcontrast(struct lcd_dev_s *dev) +{ + struct ug2864ambag01_dev_s *priv = (struct ug2864ambag01_dev_s *)dev; + DEBUGASSERT(priv); + + gvdbg("contrast: %d\n", priv->contrast); + return priv->contrast; +} + +/************************************************************************************** + * Name: ug2864ambag01_setcontrast + * + * Description: + * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST). + * + **************************************************************************************/ + +static int ug2864ambag01_setcontrast(struct lcd_dev_s *dev, unsigned int contrast) +{ + struct ug2864ambag01_dev_s *priv = (struct ug2864ambag01_dev_s *)dev; + unsigned int scaled; + + gvdbg("contrast: %d\n", contrast); + DEBUGASSERT(priv); + + /* Verify the contrast value */ + +#ifdef CONFIG_DEBUG + if (contrast > CONFIG_LCD_MAXCONTRAST) + { + return -EINVAL; + } +#endif + + /* Scale contrast: newcontrast = 255 * contrast / CONFIG_LCD_MAXCONTRAST + * Where contrast is in the range {1,255} + */ + +#if CONFIG_LCD_MAXCONTRAST != 255 + newcontrast = ((contrast << 8) - 1) / CONFIG_LCD_MAXCONTRAST; +#else + scaled = contrast; +#endif + + /* Lock and select device */ + + ug2864ambag01_lock(priv->spi); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); + + /* Select command transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); + + /* Set the contrast */ + + (void)SPI_SEND(priv->spi, SH1101A_CONTRAST_MODE); /* Set contrast control register */ + (void)SPI_SEND(priv->spi, SH1101A_CONTRAST(scaled)); /* Data 1: Set 1 of 256 contrast steps */ + priv->contrast = contrast; + + /* De-select and unlock the device */ + + SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); + ug2864ambag01_unlock(priv->spi); + return OK; +} + +/************************************************************************************** + * Public Functions + **************************************************************************************/ + +/************************************************************************************** + * Name: ug2864ambag01_initialize + * + * Description: + * Initialize the UG-2864AMBAG01 video hardware. The initial state of the + * OLED is fully initialized, display memory cleared, and the OLED ready + * to use, but with the power setting at 0 (full off == sleep mode). + * + * Input Parameters: + * + * spi - A reference to the SPI driver instance. + * devno - A value in the range of 0 through CONFIG_UG2864AMBAG01_NINTERFACES-1. + * This allows support for multiple OLED devices. + * + * Returned Value: + * + * On success, this function returns a reference to the LCD object for + * the specified OLED. NULL is returned on any failure. + * + **************************************************************************************/ + +FAR struct lcd_dev_s *ug2864ambag01_initialize(FAR struct spi_dev_s *spi, unsigned int devno) +{ + FAR struct ug2864ambag01_dev_s *priv = &g_oleddev; + + gvdbg("Initializing\n"); + DEBUGASSERT(spi && devno == 0); + + /* Save the reference to the SPI device */ + + priv->spi = spi; + + /* Configure the SPI */ + + ug2864ambag01_configspi(spi) + + /* Lock and select device */ + + ug2864ambag01_lock(priv->spi); + SPI_SELECT(spi, SPIDEV_DISPLAY, true); + + /* Select command transfer */ + + SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); + + /* Configure the device */ + + SPI_SEND(spi, SH1101A_DISPOFF); /* Display off */ + SPI_SEND(spi, SH1101A_SETCOLL(0)); /* Set lower column address */ + SPI_SEND(spi, SH1101A_SETCOLH(0)); /* Set higher column address */ + SPI_SEND(spi, SH1101A_STARTLINE(0)); /* Set display start line */ + SPI_SEND(spi, SH1101A_PAGEADDR(0)); /* Set page address */ + SPI_SEND(spi, SH1101A_CONTRAST_MODE); /* Contrast control */ + SPI_SEND(spi ,UG2864AMBAG01_CONTRAST); /* Default contrast */ + SPI_SEND(spi, SH1101A_REMAPPLEFT); /* Set segment remap left */ + SPI_SEND(spi, SH1101A_EDISPOFF); /* Normal display */ + SPI_SEND(spi, SH1101A_NORMAL); /* Normal (un-reversed) display mode */ + SPI_SEND(spi, SH1101A_MRATIO_MODE); /* Multiplex ratio */ + SPI_SEND(spi, SH1101A_MRATIO(0x3f)); /* Duty = 1/64 */ + SPI_SEND(spi, SH1101A_SCANTOCOM0); /* Com scan direction: Scan from COM[n-1] to COM[0] */ + SPI_SEND(spi, SH1101A_DISPOFFS_MODE); /* Set display offset */ + SPI_SEND(spi, SH1101A_DISPOFFS(0)); + SPI_SEND(spi, SH1101A_CLKDIV_SET); /* Set clock divider */ + SPI_SEND(spi, SH1101A_CLKDIV(0,0)); + SPI_SEND(spi, SH1101A_CMNPAD_CONFIG); /* Set common pads */ + SPI_SEND(spi, SH1101A_CMNPAD(0x10)); + SPI_SEND(spi, SH1101A_VCOM_SET); + SPI_SEND(spi, SH1101A_VCOM(0x40)); + SPI_SEND(spi, SH1101A_DCDC_MODE); /* DC/DC control mode: on */ + SPI_SEND(spi, SH1101A_DCDC_ON); + SPI_SEND(spi, SH1101A_DISPON); /* display ON */ + + /* De-select and unlock the device */ + + SPI_SELECT(spi, SPIDEV_DISPLAY, false); + ug2864ambag01_unlock(priv->spi); + + /* Clear the display */ + + up_mdelay(100); + ug2864ambag01_fill(&priv->dev, UG_Y1_BLACK); + return &priv->dev; +} + +/************************************************************************************** + * Name: ug2864ambag01_fill + * + * Description: + * This non-standard method can be used to clear the entire display by writing one + * color to the display. This is much faster than writing a series of runs. + * + * Input Parameters: + * priv - Reference to private driver structure + * + * Assumptions: + * Caller has selected the OLED section. + * + **************************************************************************************/ + +void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color) +{ + FAR struct ug2864ambag01_dev_s *priv = &g_oleddev; + unsigned int page; + unsigned int col; + + /* Make an 8-bit version of the selected color */ + + if (color & 1) + { + color = 0xff; + } + else + { + color = 0; + } + + /* Initialize the framebuffer */ + +#ifdef CONFIG_UG2864AMBAG01_FRAMEBUFFER + memset(priv->fb, color, UG2864AMBAG01_FBSIZE); +#endif + + /* Lock and select device */ + + ug2864ambag01_lock(priv->spi); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); + + /* Visit each page */ + + for (page = 0; page < UG2864AMBAG01_DEV_PAGES; page++) + { + /* Select command transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); + + /* Set the column address to the XOFFSET value */ + + SPI_SEND(priv->spi, SH1101A_SETCOLL(UG2864AMBAG01_DEV_XOFFSET)); + SPI_SEND(priv->spi, SH1101A_SETCOLH(0)); + + /* Set the page address */ + + SPI_SEND(priv->spi, SH1101A_PAGEADDR(page)); + + /* Select data transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, false); + + /* Transfer one page of the selected color */ + + (void)SPI_SNDBLOCK(priv->spi, &priv->fb[page * UG2864AMBAG01_XRES], + UG2864AMBAG01_XRES); + } + + /* De-select and unlock the device */ + + SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); + ug2864ambag01_unlock(priv->spi); +} + +#endif /* CONFIG_LCD_UG2864AMBAG01 */ diff --git a/nuttx/drivers/lcd/ug-9664hswag01.c b/nuttx/drivers/lcd/ug-9664hswag01.c index aae21d648e..6ef78fca6e 100644 --- a/nuttx/drivers/lcd/ug-9664hswag01.c +++ b/nuttx/drivers/lcd/ug-9664hswag01.c @@ -73,8 +73,6 @@ * CONFIG_UG9664HSWAG01_POWER * If the hardware supports a controllable OLED a power supply, this * configuration shold be defined. (See ug_power() below). - * CONFIG_LCD_UGDEBUG - Enable detailed UG-9664HSWAG01 debug output - * (CONFIG_DEBUG and CONFIG_VERBOSE must also be enabled). * * Required LCD driver settings: * CONFIG_LCD_UG9664HSWAG01 - Enable UG-9664HSWAG01 support @@ -119,11 +117,10 @@ #ifndef CONFIG_DEBUG # undef CONFIG_DEBUG_VERBOSE -# undef CONFIG_DEBUG_GRAPHICS #endif #ifndef CONFIG_DEBUG_VERBOSE -# undef CONFIG_LCD_UGDEBUG +# undef CONFIG_DEBUG_LCD #endif /* Check contrast selection */ @@ -198,10 +195,10 @@ /* Debug ******************************************************************************/ -#ifdef CONFIG_LCD_UGDEBUG -# define ugdbg(format, arg...) vdbg(format, ##arg) +#ifdef CONFIG_DEBUG_LCD +# define lcddbg(format, arg...) vdbg(format, ##arg) #else -# define ugdbg(x...) +# define lcddbg(x...) #endif /************************************************************************************** @@ -997,7 +994,7 @@ FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devn SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); - /* Set the starting position for the run */ + /* Configure the device */ (void)SPI_SEND(spi, SSD1305_SETCOLL + 2); /* Set low column address */ (void)SPI_SEND(spi, SSD1305_SETCOLH + 2); /* Set high column address */ diff --git a/nuttx/include/nuttx/lcd/ug-2864ambag01.h b/nuttx/include/nuttx/lcd/ug-2864ambag01.h new file mode 100644 index 0000000000..86c4a03b43 --- /dev/null +++ b/nuttx/include/nuttx/lcd/ug-2864ambag01.h @@ -0,0 +1,243 @@ +/************************************************************************************** + * include/nuttx/lcd/ug-2864ambag01.h + * Driver for Univision UG-2864AMBAG01 OLED display (wih SH1101A controller) + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * 1. Product Specification (Preliminary), Part Name: OEL Display Module, Part ID: + * UG-2864AMBAG01, Doc No: SASI-9015-A, Univision Technology Inc. + * 2. SH1101A, 132 X 64 Dot Matrix OLED/PLED, Preliminary Segment/Common Driver with + * Controller, Sino Wealth + * + * 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 __INCLUDE_NUTTX_UG_8264AMBAG01_H +#define __INCLUDE_NUTTX_UG_8264AMBAG01_H + +/************************************************************************************** + * Included Files + **************************************************************************************/ + +#include + +/************************************************************************************** + * Pre-processor Definitions + **************************************************************************************/ +/* Configuration **********************************************************************/ +/* UG-2864AMBAG01 Configuration Settings: + * + * CONFIG_UG2864AMBAG01_SPIMODE - Controls the SPI mode + * CONFIG_UG2864AMBAG01_FREQUENCY - Define to use a different bus frequency + * CONFIG_UG2864AMBAG01_NINTERFACES - Specifies the number of physical UG-2864AMBAG01 + * devices that will be supported. + * CONFIG_UG2864AMBAG01_FRAMEBUFFER - If defined, accesses will be performed using an + * in-memory copy of the OLEDs GDDRAM. This cost of this buffer is 128 * 64 / 8 = + * 1Kb. + * + * If CONFIG_UG2864AMBAG01_FRAMEBUFFER is not defined and the LCD is a LANDSCAPE mode, + * then a 128 byte buffer is still required. + * + * Required LCD driver settings: + * + * CONFIG_LCD_UG28AMBAG01 - Enable UG-2864AMBAG01 support + * CONFIG_LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. + * CONFIG_LCD_MAXPOWER must be 1 + * + * Option LCD driver settings: + * CONFIG_LCD_LANDSCAPE, CONFIG_LCD_PORTRAIT, CONFIG_LCD_RLANDSCAPE, and + * CONFIG_LCD_RPORTRAIT - Display orientation. + * + * Required SPI driver settings: + * CONFIG_SPI_CMDDATA - Include support for cmd/data selection. + */ + +/* SPI Interface + * + * "The serial interface consists of serial clock SCL, serial data SI, A0 and + * CS . SI is shifted into an 8-bit shift register on every rising edge of + * SCL in the order of D7, D6, … and D0. A0 is sampled on every eighth clock + * and the data byte in the shift register is written to the display data RAM + * or command register in the same clock." + * + * MODE 3: + * Clock polarity: High (CPOL=1) + * Clock phase: Sample on trailing (rising edge) (CPHA 1) + */ + +#ifndef CONFIG_UG2864AMBAG01_SPIMODE +# define CONFIG_UG2864AMBAG01_SPIMODE SPIDEV_MODE3 +#endif + +/* "This module determines whether the input data is interpreted as data or + * command. When A0 = “H”, the inputs at D7 - D0 are interpreted as data and be + * written to display RAM. When A0 = “L”, the inputs at D7 - D0 are interpreted + * as command, they will be decoded and be written to the corresponding command + * registers. + */ + +#ifndef CONFIG_SPI_CMDDATA +# error "CONFIG_SPI_CMDDATA must be defined in your NuttX configuration" +#endif + +/* CONFIG_UG2864AMBAG01_NINTERFACES determines the number of physical interfaces + * that will be supported. + */ + +#ifndef CONFIG_UG2864AMBAG01_NINTERFACES +# define CONFIG_UG2864AMBAG01_NINTERFACES 1 +#endif + +/* Check contrast selection */ + +#if !defined(CONFIG_LCD_MAXCONTRAST) +# define CONFIG_LCD_MAXCONTRAST 255 +#endif + +#if CONFIG_LCD_MAXCONTRAST <= 0|| CONFIG_LCD_MAXCONTRAST > 255 +# error "CONFIG_LCD_MAXCONTRAST exceeds supported maximum" +#endif + +#if CONFIG_LCD_MAXCONTRAST < 255 +# warning "Optimal setting of CONFIG_LCD_MAXCONTRAST is 255" +#endif + +/* Check power setting */ + +#if !defined(CONFIG_LCD_MAXPOWER) +# define CONFIG_LCD_MAXPOWER 1 +#endif + +#if CONFIG_LCD_MAXPOWER != 1 +# warning "CONFIG_LCD_MAXPOWER exceeds supported maximum" +# undef CONFIG_LCD_MAXPOWER +# define CONFIG_LCD_MAXPOWER 1 +#endif + +/* Color is 1bpp monochrome with leftmost column contained in bits 0 */ + +#ifdef CONFIG_NX_DISABLE_1BPP +# warning "1 bit-per-pixel support needed" +#endif + +/* Orientation */ + +#if defined(CONFIG_LCD_LANDSCAPE) +# undef CONFIG_LCD_PORTRAIT +# undef CONFIG_LCD_RLANDSCAPE +# undef CONFIG_LCD_RPORTRAIT +#elif defined(CONFIG_LCD_PORTRAIT) +# undef CONFIG_LCD_LANDSCAPE +# undef CONFIG_LCD_RLANDSCAPE +# undef CONFIG_LCD_RPORTRAIT +#elif defined(CONFIG_LCD_RLANDSCAPE) +# undef CONFIG_LCD_LANDSCAPE +# undef CONFIG_LCD_PORTRAIT +# undef CONFIG_LCD_RPORTRAIT +#elif defined(CONFIG_LCD_RPORTRAIT) +# undef CONFIG_LCD_LANDSCAPE +# undef CONFIG_LCD_PORTRAIT +# undef CONFIG_LCD_RLANDSCAPE +#else +# define CONFIG_LCD_LANDSCAPE 1 +# warning "Assuming landscape orientation" +#endif + +/* Some important "colors" */ + +#define UG_Y1_BLACK 0 +#define UG_Y1_WHITE 1 + +/************************************************************************************** + * Public Types + **************************************************************************************/ + +/************************************************************************************** + * Public Data + **************************************************************************************/ + +#ifdef __cplusplus +extern "C" +{ +#endif + +/************************************************************************************** + * Public Function Prototypes + **************************************************************************************/ + +/************************************************************************************** + * Name: ug2864ambag01_initialize + * + * Description: + * Initialize the UG-2864AMBAG01 video hardware. The initial state of the + * OLED is fully initialized, display memory cleared, and the OLED ready + * to use, but with the power setting at 0 (full off == sleep mode). + * + * Input Parameters: + * + * spi - A reference to the SPI driver instance. + * devno - A value in the range of 0 through CONFIG_UG2864AMBAG01_NINTERFACES-1. + * This allows support for multiple OLED devices. + * + * Returned Value: + * + * On success, this function returns a reference to the LCD object for + * the specified OLED. NULL is returned on any failure. + * + **************************************************************************************/ + +struct lcd_dev_s; /* See nuttx/lcd.h */ +struct spi_dev_s; /* See nuttx/spi.h */ +FAR struct lcd_dev_s *ug2864ambag01_initialize(FAR struct spi_dev_s *spi, + unsigned int devno); + +/************************************************************************************************ + * Name: ug2864ambag01_fill + * + * Description: + * This non-standard method can be used to clear the entire display by writing one + * color to the display. This is much faster than writing a series of runs. + * + * Input Parameters: + * priv - Reference to private driver structure + * + * Assumptions: + * Caller has selected the OLED section. + * + **************************************************************************************/ + +void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color); + +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_NUTTX_UG_8264AMBAG01_H */ diff --git a/nuttx/include/nuttx/lcd/ug-9664hswag01.h b/nuttx/include/nuttx/lcd/ug-9664hswag01.h index 696005b5d0..b470e0895e 100644 --- a/nuttx/include/nuttx/lcd/ug-9664hswag01.h +++ b/nuttx/include/nuttx/lcd/ug-9664hswag01.h @@ -3,7 +3,7 @@ * Driver for the Univision UG-9664HSWAG01 Display with the Solomon Systech * SSD1305 LCD controller. * - * 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 @@ -58,8 +58,6 @@ * CONFIG_UG9664HSWAG01_POWER * If the hardware supports a controllable OLED a power supply, this * configuration shold be defined. (See ug_power() below). - * CONFIG_LCD_UGDEBUG - Enable detailed UG-9664HSWAG01 debug output - * (CONFIG_DEBUG and CONFIG_VERBOSE must also be enabled). * * Required LCD driver settings: * CONFIG_LCD_UG9664HSWAG01 - Enable UG-9664HSWAG01 support @@ -90,10 +88,8 @@ ****************************************************************************/ #ifdef __cplusplus -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern +extern "C" +{ #endif /**************************************************************************** @@ -123,7 +119,7 @@ extern "C" { struct lcd_dev_s; /* see nuttx/lcd.h */ struct spi_dev_s; /* see nuttx/spi.h */ -EXTERN FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devno); +FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devno); /**************************************************************************** * Name: ug_power @@ -145,12 +141,11 @@ EXTERN FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned i **************************************************************************************/ #ifdef CONFIG_UG9664HSWAG01_POWER -EXTERN void ug_power(unsigned int devno, bool on); +void ug_power(unsigned int devno, bool on); #else # define ug_power(a,b) #endif -#undef EXTERN #ifdef __cplusplus } #endif From 0bb1b8c74c5a63cadeeb20f3eafd65b6dd2fdab8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 7 Nov 2012 23:55:49 +0000 Subject: [PATCH 089/206] Convert configs/stm32f4discovery/nxlines to use Kconfig tool git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5320 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/Makefile | 5 +- apps/examples/README.txt | 5 +- apps/examples/nxlines/Kconfig | 74 + apps/examples/nxlines/Makefile | 2 +- apps/examples/nxlines/nxlines_bkgd.c | 2 +- nuttx/ChangeLog | 2 + nuttx/arch/arm/src/stm32/Kconfig | 2 +- .../configs/compal_e99/nsh_highram/defconfig | 1 - nuttx/configs/hymini-stm32v/nsh2/defconfig | 1 - nuttx/configs/hymini-stm32v/nx/defconfig | 1 - nuttx/configs/hymini-stm32v/nxlines/defconfig | 1 - nuttx/configs/pic32mx7mmb/nsh/defconfig | 1 - nuttx/configs/sam3u-ek/touchscreen/defconfig | 1 - nuttx/configs/sim/nsh2/defconfig | 1 - nuttx/configs/sim/nx/defconfig | 1 - nuttx/configs/sim/nxwm/defconfig | 1 - nuttx/configs/stm3210e-eval/nsh2/defconfig | 1 - nuttx/configs/stm3210e-eval/nx/defconfig | 1 - .../configs/stm3210e-eval/nxconsole/defconfig | 1 - nuttx/configs/stm3210e-eval/nxlines/defconfig | 1 - nuttx/configs/stm3210e-eval/nxtext/defconfig | 1 - nuttx/configs/stm3210e-eval/pm/defconfig | 1 - nuttx/configs/stm3220g-eval/nsh/defconfig | 1 - nuttx/configs/stm3220g-eval/nsh2/defconfig | 1 - nuttx/configs/stm3220g-eval/nxwm/defconfig | 1 - nuttx/configs/stm3220g-eval/ostest/defconfig | 1 - nuttx/configs/stm3240g-eval/nsh/defconfig | 1 - .../configs/stm3240g-eval/nxconsole/defconfig | 1 - nuttx/configs/stm3240g-eval/nxwm/defconfig | 1 - nuttx/configs/stm3240g-eval/ostest/defconfig | 1 - .../configs/stm3240g-eval/webserver/defconfig | 1 - nuttx/configs/stm32f4discovery/README.txt | 15 +- .../stm32f4discovery/nxlines/appconfig | 38 - .../stm32f4discovery/nxlines/defconfig | 1222 ++++++++--------- 34 files changed, 701 insertions(+), 690 deletions(-) delete mode 100644 nuttx/configs/stm32f4discovery/nxlines/appconfig diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 8e058998f2..2ab3cf05c9 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -58,7 +58,7 @@ CNTXTDIRS = pwm ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) CNTXTDIRS += adc can cdcacm composite cxxtestdhcpd discover ftpd json -CNTXTDIRS += modbus nettest relays qencoder telnetd watchdog wgetjson +CNTXTDIRS += modbus nettest nxlines relays qencoder telnetd watchdog wgetjson endif ifeq ($(CONFIG_EXAMPLES_HELLO_BUILTIN),y) @@ -79,9 +79,6 @@ endif ifeq ($(CONFIG_EXAMPLES_NXIMAGE_BUILTIN),y) CNTXTDIRS += nximage endif -ifeq ($(CONFIG_EXAMPLES_LINES_BUILTIN),y) -CNTXTDIRS += nxlines -endif ifeq ($(CONFIG_EXAMPLES_NXTEXT_BUILTIN),y) CNTXTDIRS += nxtext endif diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 3ee1abcf6b..1463b0253f 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -941,8 +941,6 @@ examplex/nxlines The following configuration options can be selected: - CONFIG_EXAMPLES_NXLINES_BUILTIN -- Build the NXLINES example as a "built-in" - that can be executed from the NSH command line CONFIG_EXAMPLES_NXLINES_VPLANE -- The plane to select from the frame- buffer driver for use in the test. Default: 0 CONFIG_EXAMPLES_NXLINES_DEVNO - The LCD device to select from the LCD @@ -980,6 +978,9 @@ examplex/nxlines FAR struct fb_vtable_s *up_nxdrvinit(unsigned int devno); #endif + CONFIG_NSH_BUILTIN_APPS - Build the NX lines examples as an NSH built-in + function. + examples/nxtext ^^^^^^^^^^^^^^^ diff --git a/apps/examples/nxlines/Kconfig b/apps/examples/nxlines/Kconfig index 5d18e00e0e..af1286a4f9 100644 --- a/apps/examples/nxlines/Kconfig +++ b/apps/examples/nxlines/Kconfig @@ -10,4 +10,78 @@ config EXAMPLES_NXLINES Enable the X graphics lines example if EXAMPLES_NXLINES + +config EXAMPLES_NXLINES_VPLANE + int "Graphics Plane" + default 0 + ---help--- + The plane to select from the frame-buffer driver for use in the test. Default: 0 + +config EXAMPLES_NXLINES_DEVNO + int "Graphics Device Number" + default 0 + ---help--- + The LCD device to select from the LCD driver for use in the test: Default: 0 + +config EXAMPLES_NXLINES_BGCOLOR + hex "Background Color" + default 0x00 + ---help--- + The color of the background. Default depends on EXAMPLES_NXLINES_BPP. + +config EXAMPLES_NXLINES_LINEWIDTH + int "Line Width" + default 16 + ---help--- + Selects the width of the lines in pixels (default: 16) + +config EXAMPLES_NXLINES_LINECOLOR + hex "Line Color" + default 0x00 + ---help--- + The color of the central lines drawn in the background window. Default + depends on EXAMPLES_NXLINES_BPP (there really is no meaningful default). + +config EXAMPLES_NXLINES_BORDERWIDTH + int "Border Width" + default 16 + ---help--- + The width of the circular border drawn in the background window. (default: 16). + +config EXAMPLES_NXLINES_BORDERCOLOR + hex "Border Color" + default 0x00 + ---help--- + The color of the circular border drawn in the background window. Default + depends on EXAMPLES_NXLINES_BPP (there really is no meaningful default). + +config EXAMPLES_NXLINES_CIRCLECOLOR + hex "Circle Color" + default 0x00 + ---help--- + The color of the circular region filled in the background window. Default + depends on EXAMPLES_NXLINES_BPP (there really is no meaningful default). + +config EXAMPLES_NXLINES_BPP + int "Bits Per Pixel" + default 8 + ---help--- + Pixels per pixel to use. Valid options include 2, 4, 8, 16, 24, and 32. + Default is 16. + +config EXAMPLES_NXLINES_EXTERNINIT + bool "External Device Initialization" + default false + ---help--- + The driver for the graphics device on this platform requires some unusual + initialization. This is the for, for example, SPI LCD/OLED devices. If + this configuration is selected, then the platform code must provide an LCD + initialization function with a prototype like: + + #ifdef NX_LCDDRIVER + FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno); + #else + FAR struct fb_vtable_s *up_nxdrvinit(unsigned int devno); + #endif + endif diff --git a/apps/examples/nxlines/Makefile b/apps/examples/nxlines/Makefile index d6ddcf0b18..e69ce6c0db 100644 --- a/apps/examples/nxlines/Makefile +++ b/apps/examples/nxlines/Makefile @@ -82,7 +82,7 @@ $(COBJS): %$(OBJEXT): %.c @touch .built .context: -ifeq ($(CONFIG_EXAMPLES_NXLINES_BUILTIN),y) +ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) @touch $@ endif diff --git a/apps/examples/nxlines/nxlines_bkgd.c b/apps/examples/nxlines/nxlines_bkgd.c index 4c09519edc..9dd7856052 100644 --- a/apps/examples/nxlines/nxlines_bkgd.c +++ b/apps/examples/nxlines/nxlines_bkgd.c @@ -316,7 +316,7 @@ void nxlines_test(NXWINDOW hwnd) if (angle > (31 * (2 * b16PI) / 32)) { -#ifdef CONFIG_EXAMPLES_NXLINES_BUILTIN +#ifdef CONFIG_NSH_BUILTIN_APPS /* If this example was built as an NSH add-on, then exit after we * have gone all the way around once. */ diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 65c5078905..c74dc6ec95 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3579,4 +3579,6 @@ * arch/arm/src/stm32_otgfsdev.c: Partial fix from Petteri Aimonen. * drivers/lcd/ug-2864ambag01.c and include/nuttx/lcd/ug_2864ambag01.h: LCD driver for the Univision OLED of the same name. + * configs/stm32f4discovery/nxlines: Configure to use mconf/Kconfig + tool. diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 8cb6360d2c..047359ea07 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -327,7 +327,7 @@ config STM32_ETHMAC config STM32_FSMC bool "FSMC" default n - depends on !STM32_CONNECTIVITYLINE && STM32_HIGHDENSITY + depends on !STM32_CONNECTIVITYLINE && (STM32_HIGHDENSITY || STM32_STM32F20XX || STM32_STM32F40XX) config STM32_HASH bool "HASH" diff --git a/nuttx/configs/compal_e99/nsh_highram/defconfig b/nuttx/configs/compal_e99/nsh_highram/defconfig index c986454781..1f4d54a1c3 100644 --- a/nuttx/configs/compal_e99/nsh_highram/defconfig +++ b/nuttx/configs/compal_e99/nsh_highram/defconfig @@ -261,7 +261,6 @@ CONFIG_EXAMPLES_HELLO_BUILTIN=y CONFIG_EXAMPLES_NXHELLO_BUILTIN=y CONFIG_EXAMPLES_NXTEXT_BUILTIN=y CONFIG_EXAMPLES_NXIMAGE_BUILTIN=y -CONFIG_EXAMPLES_NXLINES_BUILTIN=y CONFIG_EXAMPLES_NXLINES_BORDERWIDTH=2 CONFIG_EXAMPLES_NXLINES_LINEWIDTH=4 diff --git a/nuttx/configs/hymini-stm32v/nsh2/defconfig b/nuttx/configs/hymini-stm32v/nsh2/defconfig index 5091843ad3..5a8c0bea25 100644 --- a/nuttx/configs/hymini-stm32v/nsh2/defconfig +++ b/nuttx/configs/hymini-stm32v/nsh2/defconfig @@ -542,7 +542,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/hymini-stm32v/nx/defconfig b/nuttx/configs/hymini-stm32v/nx/defconfig index f4beaf7d51..28b08582cd 100644 --- a/nuttx/configs/hymini-stm32v/nx/defconfig +++ b/nuttx/configs/hymini-stm32v/nx/defconfig @@ -552,7 +552,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/hymini-stm32v/nxlines/defconfig b/nuttx/configs/hymini-stm32v/nxlines/defconfig index 89f72e3307..880efb7d81 100644 --- a/nuttx/configs/hymini-stm32v/nxlines/defconfig +++ b/nuttx/configs/hymini-stm32v/nxlines/defconfig @@ -557,7 +557,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/pic32mx7mmb/nsh/defconfig b/nuttx/configs/pic32mx7mmb/nsh/defconfig index 8d9dffc214..aa7fc23df9 100644 --- a/nuttx/configs/pic32mx7mmb/nsh/defconfig +++ b/nuttx/configs/pic32mx7mmb/nsh/defconfig @@ -715,7 +715,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=y CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/sam3u-ek/touchscreen/defconfig b/nuttx/configs/sam3u-ek/touchscreen/defconfig index b3fc37d2a4..e89db8c4b3 100755 --- a/nuttx/configs/sam3u-ek/touchscreen/defconfig +++ b/nuttx/configs/sam3u-ek/touchscreen/defconfig @@ -538,7 +538,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/sim/nsh2/defconfig b/nuttx/configs/sim/nsh2/defconfig index 903c6322df..e5dcce322a 100644 --- a/nuttx/configs/sim/nsh2/defconfig +++ b/nuttx/configs/sim/nsh2/defconfig @@ -331,7 +331,6 @@ CONFIG_EXAMPLES_NXHELLO_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 #CONFIG_EXAMPLES_NXLINES_BGCOLOR CONFIG_EXAMPLES_NXLINES_LINEWIDTH=16 diff --git a/nuttx/configs/sim/nx/defconfig b/nuttx/configs/sim/nx/defconfig index 9036a79561..714d5dbb6a 100644 --- a/nuttx/configs/sim/nx/defconfig +++ b/nuttx/configs/sim/nx/defconfig @@ -295,7 +295,6 @@ CONFIG_EXAMPLES_NX_NOTIFYSIGNO=4 # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 #CONFIG_EXAMPLES_NXLINES_BGCOLOR= diff --git a/nuttx/configs/sim/nxwm/defconfig b/nuttx/configs/sim/nxwm/defconfig index e38e07b170..161322da8c 100644 --- a/nuttx/configs/sim/nxwm/defconfig +++ b/nuttx/configs/sim/nxwm/defconfig @@ -363,7 +363,6 @@ CONFIG_EXAMPLES_NXHELLO_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 #CONFIG_EXAMPLES_NXLINES_BGCOLOR CONFIG_EXAMPLES_NXLINES_LINEWIDTH=16 diff --git a/nuttx/configs/stm3210e-eval/nsh2/defconfig b/nuttx/configs/stm3210e-eval/nsh2/defconfig index a55a0da5f7..18e42d539c 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/defconfig +++ b/nuttx/configs/stm3210e-eval/nsh2/defconfig @@ -683,7 +683,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3210e-eval/nx/defconfig b/nuttx/configs/stm3210e-eval/nx/defconfig index 9c2ccf67c1..68a3ad9b54 100644 --- a/nuttx/configs/stm3210e-eval/nx/defconfig +++ b/nuttx/configs/stm3210e-eval/nx/defconfig @@ -579,7 +579,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3210e-eval/nxconsole/defconfig b/nuttx/configs/stm3210e-eval/nxconsole/defconfig index c4de790d9c..9cb8689c6b 100644 --- a/nuttx/configs/stm3210e-eval/nxconsole/defconfig +++ b/nuttx/configs/stm3210e-eval/nxconsole/defconfig @@ -610,7 +610,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3210e-eval/nxlines/defconfig b/nuttx/configs/stm3210e-eval/nxlines/defconfig index c24e858245..ab42612f3d 100644 --- a/nuttx/configs/stm3210e-eval/nxlines/defconfig +++ b/nuttx/configs/stm3210e-eval/nxlines/defconfig @@ -600,7 +600,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3210e-eval/nxtext/defconfig b/nuttx/configs/stm3210e-eval/nxtext/defconfig index 038e20927a..c00e9b1e87 100644 --- a/nuttx/configs/stm3210e-eval/nxtext/defconfig +++ b/nuttx/configs/stm3210e-eval/nxtext/defconfig @@ -600,7 +600,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3210e-eval/pm/defconfig b/nuttx/configs/stm3210e-eval/pm/defconfig index 02823ef291..7babce8f67 100644 --- a/nuttx/configs/stm3210e-eval/pm/defconfig +++ b/nuttx/configs/stm3210e-eval/pm/defconfig @@ -728,7 +728,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3220g-eval/nsh/defconfig b/nuttx/configs/stm3220g-eval/nsh/defconfig index f1838a38b7..8baf52f7e8 100644 --- a/nuttx/configs/stm3220g-eval/nsh/defconfig +++ b/nuttx/configs/stm3220g-eval/nsh/defconfig @@ -787,7 +787,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3220g-eval/nsh2/defconfig b/nuttx/configs/stm3220g-eval/nsh2/defconfig index 2395fd785a..c273ce60f8 100644 --- a/nuttx/configs/stm3220g-eval/nsh2/defconfig +++ b/nuttx/configs/stm3220g-eval/nsh2/defconfig @@ -774,7 +774,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3220g-eval/nxwm/defconfig b/nuttx/configs/stm3220g-eval/nxwm/defconfig index 78439e4c01..065fbb1372 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/defconfig +++ b/nuttx/configs/stm3220g-eval/nxwm/defconfig @@ -820,7 +820,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=y CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3220g-eval/ostest/defconfig b/nuttx/configs/stm3220g-eval/ostest/defconfig index 9384a7f141..2393d0a69e 100644 --- a/nuttx/configs/stm3220g-eval/ostest/defconfig +++ b/nuttx/configs/stm3220g-eval/ostest/defconfig @@ -645,7 +645,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig index 3b1092487c..54eb1d56f4 100644 --- a/nuttx/configs/stm3240g-eval/nsh/defconfig +++ b/nuttx/configs/stm3240g-eval/nsh/defconfig @@ -787,7 +787,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3240g-eval/nxconsole/defconfig b/nuttx/configs/stm3240g-eval/nxconsole/defconfig index 49a2b6631b..f8a1fb7d5b 100644 --- a/nuttx/configs/stm3240g-eval/nxconsole/defconfig +++ b/nuttx/configs/stm3240g-eval/nxconsole/defconfig @@ -758,7 +758,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=y CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3240g-eval/nxwm/defconfig b/nuttx/configs/stm3240g-eval/nxwm/defconfig index 7ab42a7cb9..5dfdb28fc3 100644 --- a/nuttx/configs/stm3240g-eval/nxwm/defconfig +++ b/nuttx/configs/stm3240g-eval/nxwm/defconfig @@ -820,7 +820,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=y CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3240g-eval/ostest/defconfig b/nuttx/configs/stm3240g-eval/ostest/defconfig index 95a06dea03..38b51e84b0 100644 --- a/nuttx/configs/stm3240g-eval/ostest/defconfig +++ b/nuttx/configs/stm3240g-eval/ostest/defconfig @@ -657,7 +657,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm3240g-eval/webserver/defconfig b/nuttx/configs/stm3240g-eval/webserver/defconfig index c365b7fa10..e9cbbf93d4 100644 --- a/nuttx/configs/stm3240g-eval/webserver/defconfig +++ b/nuttx/configs/stm3240g-eval/webserver/defconfig @@ -788,7 +788,6 @@ CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n # # Settings for examples/nxlines # -CONFIG_EXAMPLES_NXLINES_BUILTIN=n CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index b6591c754b..c193a1f421 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -1299,17 +1299,24 @@ Where is one of the following: The STM32F4Discovery board does not have any graphics capability. This configuration assumes that you have connected an SD1289-based LCD as - described about under "SSD1289". NOTE: At present, it has not been + described above under "SSD1289". NOTE: At present, it has not been proven that the STM32F4Discovery can actually drive an LCD. There are some issues with how some of the dedicated FSMC pins are used on the boards. This configuration may not be useful and may only serve as an illustration of how to build for th SSD1289 LCD. - Default toolchain: + NOTES: - CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + 1. As of this writing, I have not seen the LCD work! - NOTE: As of this writing, I have not seen the LCD work! + 2. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. pm: -- diff --git a/nuttx/configs/stm32f4discovery/nxlines/appconfig b/nuttx/configs/stm32f4discovery/nxlines/appconfig deleted file mode 100644 index 1f99214612..0000000000 --- a/nuttx/configs/stm32f4discovery/nxlines/appconfig +++ /dev/null @@ -1,38 +0,0 @@ -############################################################################ -# configs/stm32f4discovery/nxlines/appconfig -# -# 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. -# -############################################################################ - -# Path to example in apps/examples containing the user_start entry point - -CONFIGURED_APPS += examples/nxlines diff --git a/nuttx/configs/stm32f4discovery/nxlines/defconfig b/nuttx/configs/stm32f4discovery/nxlines/defconfig index f19882006b..be71de2ad7 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/defconfig +++ b/nuttx/configs/stm32f4discovery/nxlines/defconfig @@ -1,344 +1,286 @@ -############################################################################ -# configs/stm32f4discovery/nxlines/defconfig # -# Copyright (C) 2012 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration # -# 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. -# -############################################################################ -# -# Architecture Selection -# -CONFIG_ARCH="arm" -CONFIG_ARCH_ARM=y -CONFIG_ARCH_CORTEXM4=y -CONFIG_ARCH_CHIP="stm32" -CONFIG_ARCH_CHIP_STM32F407VG=y -CONFIG_ARCH_BOARD="stm32f4discovery" -CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y -CONFIG_BOARD_LOOPSPERMSEC=16717 -CONFIG_DRAM_SIZE=114688 -CONFIG_DRAM_START=0x20000000 -CONFIG_ARCH_IRQPRIO=y -CONFIG_ARCH_FPU=n -CONFIG_ARCH_INTERRUPTSTACK=0 -CONFIG_ARCH_STACKDUMP=y -CONFIG_ARCH_BOOTLOADER=n -CONFIG_ARCH_LEDS=y -CONFIG_ARCH_BUTTONS=y -CONFIG_ARCH_CALIBRATION=n -CONFIG_ARCH_DMA=n +CONFIG_NUTTX_NEWCONFIG=y # -# Identify toolchain and linker options +# Build Setup # -CONFIG_STM32_CODESOURCERYW=y -CONFIG_STM32_CODESOURCERYL=n -CONFIG_STM32_ATOLLIC_LITE=n -CONFIG_STM32_ATOLLIC_PRO=n -CONFIG_STM32_DEVKITARM=n -CONFIG_STM32_RAISONANCE=n -CONFIG_STM32_BUILDROOT=n +# CONFIG_EXPERIMENTAL is not set # -# JTAG Enable settings (by default only SW-DP is enabled): +# Build Configuration # -CONFIG_STM32_DFU=n -CONFIG_STM32_JTAG_FULL_ENABLE=n -CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n -CONFIG_STM32_JTAG_SW_ENABLE=y +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set # -# Individual subsystems can be enabled: +# Binary Output Formats # -# AHB1: -CONFIG_STM32_CRC=n -CONFIG_STM32_BKPSRAM=n -CONFIG_STM32_CCMDATARAM=n -CONFIG_STM32_DMA1=n -CONFIG_STM32_DMA2=n -CONFIG_STM32_ETHMAC=n -CONFIG_STM32_OTGHS=n -# AHB2: -CONFIG_STM32_DCMI=n -CONFIG_STM32_CRYP=n -CONFIG_STM32_HASH=n -CONFIG_STM32_RNG=n -CONFIG_STM32_OTGFS=y -# AHB3: -CONFIG_STM32_FSMC=y -# APB1: -CONFIG_STM32_TIM2=n -CONFIG_STM32_TIM3=n -CONFIG_STM32_TIM4=n -CONFIG_STM32_TIM5=n -CONFIG_STM32_TIM6=n -CONFIG_STM32_TIM7=n -CONFIG_STM32_TIM12=n -CONFIG_STM32_TIM13=n -CONFIG_STM32_TIM14=n -CONFIG_STM32_WWDG=n -CONFIG_STM32_IWDG=n -CONFIG_STM32_SPI2=n -CONFIG_STM32_SPI3=n -CONFIG_STM32_USART2=y -CONFIG_STM32_USART3=n -CONFIG_STM32_UART4=n -CONFIG_STM32_UART5=n -CONFIG_STM32_I2C1=n -CONFIG_STM32_I2C2=n -CONFIG_STM32_I2C3=n -CONFIG_STM32_CAN1=n -CONFIG_STM32_CAN2=n -CONFIG_STM32_DAC=n -CONFIG_STM32_PWR=y -# APB2: -CONFIG_STM32_TIM1=n -CONFIG_STM32_TIM8=n -CONFIG_STM32_USART1=n -CONFIG_STM32_USART6=n -CONFIG_STM32_ADC1=n -CONFIG_STM32_ADC2=n -CONFIG_STM32_ADC3=n -CONFIG_STM32_SDIO=n -CONFIG_STM32_SPI1=y -CONFIG_STM32_SYSCFG=y -CONFIG_STM32_TIM9=n -CONFIG_STM32_TIM10=n -CONFIG_STM32_TIM11=n - -# -# STM32F40xxx specific serial device driver settings -# -CONFIG_USART1_SERIAL_CONSOLE=n -CONFIG_USART2_SERIAL_CONSOLE=y -CONFIG_USART3_SERIAL_CONSOLE=n -CONFIG_UART4_SERIAL_CONSOLE=n -CONFIG_UART5_SERIAL_CONSOLE=n - -CONFIG_USART1_TXBUFSIZE=128 -CONFIG_USART2_TXBUFSIZE=128 -CONFIG_USART3_TXBUFSIZE=128 -CONFIG_UART4_TXBUFSIZE=128 -CONFIG_UART5_TXBUFSIZE=128 - -CONFIG_USART1_RXBUFSIZE=128 -CONFIG_USART2_RXBUFSIZE=128 -CONFIG_USART3_RXBUFSIZE=128 -CONFIG_UART4_RXBUFSIZE=128 -CONFIG_UART5_RXBUFSIZE=128 - -CONFIG_USART1_BAUD=115200 -CONFIG_USART2_BAUD=115200 -CONFIG_USART3_BAUD=115200 -CONFIG_UART4_BAUD=115200 -CONFIG_UART5_BAUD=115200 - -CONFIG_USART1_BITS=8 -CONFIG_USART2_BITS=8 -CONFIG_USART3_BITS=8 -CONFIG_UART4_BITS=8 -CONFIG_UART5_BITS=8 - -CONFIG_USART1_PARITY=0 -CONFIG_USART2_PARITY=0 -CONFIG_USART3_PARITY=0 -CONFIG_UART4_PARITY=0 -CONFIG_UART5_PARITY=0 - -CONFIG_USART1_2STOP=0 -CONFIG_USART2_2STOP=0 -CONFIG_USART3_2STOP=0 -CONFIG_UART4_2STOP=0 -CONFIG_UART5_2STOP=0 - -# -# STM32F40xxx specific SPI device driver settings -# -CONFIG_SPI_EXCHANGE=y - -# -# STM32F40xxx specific CAN device driver settings -# -CONFIG_CAN=n -CONFIG_CAN_EXTID=n -#CONFIG_CAN_FIFOSIZE -#CONFIG_CAN_NPENDINGRTR -CONFIG_CAN_LOOPBACK=n -CONFIG_CAN1_BAUD=700000 -CONFIG_CAN2_BAUD=700000 - -# -# STM32F40xxx Ethernet device driver settings -# -CONFIG_STM32_PHYADDR=1 -CONFIG_STM32_MII=y -CONFIG_STM32_MII_MCO1=y -CONFIG_STM32_MII_MCO2=n -CONFIG_STM32_RMII=n -CONFIG_STM32_AUTONEG=y -#CONFIG_STM32_ETHFD -#CONFIG_STM32_ETH100MB -CONFIG_STM32_PHYSR=16 -CONFIG_STM32_PHYSR_SPEED=0x0002 -CONFIG_STM32_PHYSR_100MBPS=0x0000 -CONFIG_STM32_PHYSR_MODE=0x0004 -CONFIG_STM32_PHYSR_FULLDUPLEX=0x0004 -CONFIG_STM32_ETH_PTP=n -CONFIG_STM32_ETHMAC_REGDEBUG=n - -# -# PWM configuration -# -# The stm32f4discovery has no real on-board PWM devices, but the board can be configured to output -# a pulse train using TIM4 CH2. (Don't forget to set CONFIG_STM32_TIM4=y above) -# -CONFIG_PWM=n -CONFIG_STM32_TIM4_PWM=y -CONFIG_STM32_TIM4_CHANNEL=2 - -# -# Quadrature Encoder configuration. -# -CONFIG_QENCODER=n -CONFIG_STM32_TIM2_QE=n -CONFIG_STM32_TIM2_QECLKOUT=28000000 -CONFIG_STM32_TIM8_QE=y -CONFIG_STM32_TIM8_QECLKOUT=28000000 - -# -# General build options -# -CONFIG_RRLOAD_BINARY=n +# CONFIG_RRLOAD_BINARY is not set CONFIG_INTELHEX_BINARY=y -CONFIG_MOTOROLA_SREC=n +# CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # -# General OS setup +# Customize Header Files # -CONFIG_USER_ENTRYPOINT="nxlines_main" -CONFIG_DEBUG=n -CONFIG_DEBUG_VERBOSE=n -CONFIG_DEBUG_SYMBOLS=n -CONFIG_DEBUG_FS=n -CONFIG_DEBUG_GRAPHICS=n -CONFIG_DEBUG_LCD=n -CONFIG_DEBUG_USB=n -CONFIG_DEBUG_NET=n -CONFIG_DEBUG_RTC=n -CONFIG_DEBUG_ANALOG=n -CONFIG_DEBUG_PWM=n -CONFIG_DEBUG_CAN=n -CONFIG_DEBUG_QENCODER=n -CONFIG_HAVE_CXX=y -CONFIG_HAVE_CXXINITIALIZE=y -CONFIG_MM_REGIONS=2 -CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM3S is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM4=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARCH_FPU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set +CONFIG_ARCH_IRQPRIO=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +CONFIG_ARCH_CHIP_STM32F407VG=y +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +CONFIG_STM32_STM32F40XX=y +CONFIG_STM32_CODESOURCERYW=y +# CONFIG_STM32_CODESOURCERYL is not set +# CONFIG_STM32_ATOLLIC_LITE is not set +# CONFIG_STM32_ATOLLIC_PRO is not set +# CONFIG_STM32_DEVKITARM is not set +# CONFIG_STM32_RAISONANCE is not set +# CONFIG_STM32_BUILDROOT is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_BKPSRAM is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CCMDATARAM is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_CRYP is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +CONFIG_STM32_FSMC=y +# CONFIG_STM32_HASH is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_IWDG is not set +CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGHS is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +CONFIG_STM32_SPI1=y +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_USART1 is not set +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +# CONFIG_STM32_WWDG is not set +CONFIG_STM32_SPI=y + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +# CONFIG_STM32_CCMEXCLUDE is not set +# CONFIG_STM32_FSMC_SRAM is not set + +# +# SPI Configuration +# +# CONFIG_STM32_SPI_INTERRUPTS is not set +# CONFIG_STM32_SPI_DMA is not set + +# +# USB Host Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_STACKDUMP=y + +# +# Board Settings +# +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=114688 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="stm32f4discovery" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +# CONFIG_ARCH_IRQBUTTONS is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 CONFIG_RR_INTERVAL=200 -CONFIG_SCHED_INSTRUMENTATION=n +# CONFIG_SCHED_INSTRUMENTATION is not set CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set CONFIG_START_YEAR=2011 CONFIG_START_MONTH=12 CONFIG_START_DAY=6 -CONFIG_GREGORIAN_TIME=n -CONFIG_JULIAN_TIME=n CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=n -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=n +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set CONFIG_SDCLONE_DISABLE=y -CONFIG_SCHED_WORKQUEUE=n -CONFIG_SCHED_WORKPRIORITY=192 -CONFIG_SCHED_WORKPERIOD=50000 -CONFIG_SCHED_WORKSTACKSIZE=1024 -CONFIG_SIG_SIGWORK=4 +# CONFIG_SCHED_WORKQUEUE is not set CONFIG_SCHED_WAITPID=y -CONFIG_SCHED_ATEXIT=n - -# -# Settings for NXFLAT -# -CONFIG_NXFLAT=n -CONFIG_NXFLAT_DUMPBUFFER=n -CONFIG_SYMTAB_ORDEREDBYNAME=y - -# -# The following can be used to disable categories of -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=n -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=n -CONFIG_DISABLE_MOUNTPOINT=n -CONFIG_DISABLE_ENVIRON=n +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="nxlines_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set CONFIG_DISABLE_POLL=y -# -# Misc libc settings -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve system performance -# -CONFIG_ARCH_MEMCPY=n -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n - # # Sizes of configurable things (0 disables) # @@ -348,9 +290,6 @@ CONFIG_NPTHREAD_KEYS=4 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 CONFIG_MAX_WDOGPARMS=2 @@ -358,361 +297,261 @@ CONFIG_PREALLOC_WDOGS=4 CONFIG_PREALLOC_TIMERS=4 # -# Framebuffer driver options +# Stack and heap information # -CONFIG_FB_CMAP=n -CONFIG_FB_HWCURSOR=n -CONFIG_FB_HWCURSORIMAGE=n -#CONFIG_FB_HWCURSORSIZE -#CONFIG_FB_TRANSPARENCY +# CONFIG_CUSTOM_STACK is not set +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 # -# Filesystem configuration +# Device Drivers # -CONFIG_FS_FAT=n -CONFIG_FAT_LCNAMES=y -CONFIG_FAT_LFN=y -CONFIG_FAT_MAXFNAME=32 -CONFIG_FS_NXFFS=n -CONFIG_FS_ROMFS=n +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +CONFIG_ARCH_HAVE_I2CRESET=y +CONFIG_SPI=y +# CONFIG_SPI_OWNBUS is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +CONFIG_LCD=y +# CONFIG_LCD_NOGETRUN is not set +CONFIG_LCD_MAXCONTRAST=1 +CONFIG_LCD_MAXPOWER=255 +# CONFIG_LCD_P14201 is not set +# CONFIG_LCD_NOKIA6100 is not set +# CONFIG_LCD_UG9664HSWAG01 is not set +# CONFIG_LCD_UG2864AMBAG01 is not set +CONFIG_LCD_SSD1289=y +CONFIG_SSD1289_PROFILE1=y +# CONFIG_SSD1289_PROFILE2 is not set +# CONFIG_SSD1289_PROFILE3 is not set +CONFIG_LCD_LANDSCAPE=y +# CONFIG_LCD_PORTRAIT is not set +# CONFIG_LCD_RPORTRAIT is not set +# CONFIG_LCD_RLANDSCAPE is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_USART2=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set # -# Maintain legacy build behavior (revisit) +# USART2 Configuration # - -CONFIG_MMCSD=y -CONFIG_MMCSD_SPI=y -CONFIG_MMCSD_SDIO=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set # -# SPI-based MMC/SD driver +# System Logging Device Options # -CONFIG_MMCSD_NSLOTS=0 -CONFIG_MMCSD_READONLY=n -CONFIG_MMCSD_SPICLOCK=12500000 # -# Block driver buffering +# System Logging # -CONFIG_FS_READAHEAD=n -CONFIG_FS_WRITEBUFFER=n +# CONFIG_RAMLOG is not set # -# STM32 SDIO-based MMC/SD driver +# Networking Support # -CONFIG_SDIO_DMA=n -#CONFIG_SDIO_PRI=128 -#CONFIG_SDIO_DMAPRIO -#CONFIG_SDIO_WIDTH_D1_ONLY -CONFIG_MMCSD_MULTIBLOCK_DISABLE=y -CONFIG_MMCSD_MMCSUPPORT=n -CONFIG_MMCSD_HAVECARDDETECT=n +# CONFIG_NET is not set # -# TCP/IP and UDP support via uIP +# File Systems # -CONFIG_NET=n -CONFIG_NET_NOINTS=n -CONFIG_NET_MULTIBUFFER=y -CONFIG_NET_IPv6=n -CONFIG_NSOCKET_DESCRIPTORS=10 -CONFIG_NET_SOCKOPTS=y -CONFIG_NET_BUFSIZE=562 -CONFIG_NET_TCP=y -CONFIG_NET_TCP_CONNS=40 -#CONFIG_NET_TCP_READAHEAD_BUFSIZE -CONFIG_NET_NTCP_READAHEAD_BUFFERS=16 -CONFIG_NET_TCPBACKLOG=y -CONFIG_NET_MAX_LISTENPORTS=40 -CONFIG_NET_UDP=y -CONFIG_NET_UDP_CHECKSUMS=y -#CONFIG_NET_UDP_CONNS=10 -CONFIG_NET_ICMP=y -CONFIG_NET_ICMP_PING=y -#CONFIG_NET_PINGADDRCONF=0 -CONFIG_NET_STATISTICS=y -#CONFIG_NET_RECEIVE_WINDOW= -CONFIG_NET_BROADCAST=n -#CONFIG_NET_ARPTAB_SIZE=8 -CONFIG_NET_ARP_IPIN=n -CONFIG_NET_MULTICAST=n # -# UIP Network Utilities +# File system configuration # -CONFIG_NET_DHCP_LIGHT=n -CONFIG_NET_RESOLV_ENTRIES=4 +# CONFIG_FS_FAT is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set # -# RTC Configuration +# System Logging # -CONFIG_RTC=n -CONFIG_RTC_DATETIME=y -CONFIG_RTC_HIRES=n -CONFIG_RTC_FREQUENCY=1 -CONFIG_RTC_ALARM=n +# CONFIG_SYSLOG is not set # -# STM32 USB OTG FS Device Configuration -# -CONFIG_USBDEV=n -CONFIG_USBDEV_ISOCHRONOUS=n -CONFIG_USBDEV_DUALSPEED=n -CONFIG_USBDEV_SELFPOWERED=y -CONFIG_USBDEV_REMOTEWAKEUP=n -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 (Prolifics PL2303 emulation) -# -CONFIG_PL2303=n -CONFIG_PL2303_EPINTIN=1 -CONFIG_PL2303_EPBULKOUT=2 -CONFIG_PL2303_EPBULKIN=3 -CONFIG_PL2303_NWRREQS=4 -CONFIG_PL2303_NRDREQS=4 -CONFIG_PL2303_VENDORID=0x067b -CONFIG_PL2303_PRODUCTID=0x2303 -CONFIG_PL2303_VENDORSTR="Nuttx" -CONFIG_PL2303_PRODUCTSTR="USBdev Serial" -CONFIG_PL2303_RXBUFSIZE=512 -CONFIG_PL2303_TXBUFSIZE=512 - -# -# USB serial device class driver (Standard CDC ACM class) -# -CONFIG_CDCACM=n -CONFIG_CDCACM_CONSOLE=n -#CONFIG_CDCACM_EP0MAXPACKET -CONFIG_CDCACM_EPINTIN=1 -#CONFIG_CDCACM_EPINTIN_FSSIZE -#CONFIG_CDCACM_EPINTIN_HSSIZE -CONFIG_CDCACM_EPBULKOUT=3 -#CONFIG_CDCACM_EPBULKOUT_FSSIZE -#CONFIG_CDCACM_EPBULKOUT_HSSIZE -CONFIG_CDCACM_EPBULKIN=2 -#CONFIG_CDCACM_EPBULKIN_FSSIZE -#CONFIG_CDCACM_EPBULKIN_HSSIZE -#CONFIG_CDCACM_NWRREQS -#CONFIG_CDCACM_NRDREQS -#CONFIG_CDCACM_VENDORID -#CONFIG_CDCACM_VENDORSTR -#CONFIG_CDCACM_PRODUCTID -#CONFIG_CDCACM_PRODUCTSTR -#CONFIG_CDCACM_RXBUFSIZE -#CONFIG_CDCACM_TXBUFSIZE - -# -# USB Storage Device Configuration -# -CONFIG_USBMSC=n -CONFIG_USBMSC_EP0MAXPACKET=64 -CONFIG_USBMSC_EPBULKOUT=2 -CONFIG_USBMSC_EPBULKIN=5 -CONFIG_USBMSC_NRDREQS=2 -CONFIG_USBMSC_NWRREQS=2 -CONFIG_USBMSC_BULKINREQLEN=256 -CONFIG_USBMSC_BULKOUTREQLEN=256 -CONFIG_USBMSC_VENDORID=0x584e -CONFIG_USBMSC_VENDORSTR="NuttX" -CONFIG_USBMSC_PRODUCTID=0x5342 -CONFIG_USBMSC_PRODUCTSTR="USBdev Storage" -CONFIG_USBMSC_VERSIONNO=0x0399 -CONFIG_USBMSC_REMOVABLE=y - -# -# Watchdog timer configuration -# -CONFIG_WATCHDOG=n - -# -# Graphics related configuration settings +# Graphics Support # CONFIG_NX=y -CONFIG_NX_MULTIUSER=n +CONFIG_NX_LCDDRIVER=y CONFIG_NX_NPLANES=1 +# CONFIG_NX_WRITEONLY is not set + +# +# Supported Pixel Depths +# CONFIG_NX_DISABLE_1BPP=y CONFIG_NX_DISABLE_2BPP=y CONFIG_NX_DISABLE_4BPP=y CONFIG_NX_DISABLE_8BPP=y -CONFIG_NX_DISABLE_16BPP=n +# CONFIG_NX_DISABLE_16BPP is not set CONFIG_NX_DISABLE_24BPP=y CONFIG_NX_DISABLE_32BPP=y -CONFIG_NX_PACKEDMSFIRST=n -CONFIG_NX_LCDDRIVER=y -CONFIG_LCD_MAXPOWER=255 -CONFIG_LCD_MAXCONTRAST=1 +# CONFIG_NX_PACKEDMSFIRST is not set + +# +# Input Devices +# CONFIG_NX_MOUSE=y CONFIG_NX_KBD=y -#CONFIG_NXTK_BORDERWIDTH=4 + +# +# Framed Window Borders +# +CONFIG_NXTK_BORDERWIDTH=4 CONFIG_NXTK_BORDERCOLOR1=0x5cb7 CONFIG_NXTK_BORDERCOLOR2=0x21c9 CONFIG_NXTK_BORDERCOLOR3=0xffdf -CONFIG_NXTK_AUTORAISE=n -CONFIG_NXFONT_SANS17X22=n -CONFIG_NXFONT_SANS20X26=n -CONFIG_NXFONT_SANS22X29=n -CONFIG_NXFONT_SANS23X27=y -CONFIG_NXFONT_SANS28X37=n -CONFIG_NXFONT_SANS17X23B=n -CONFIG_NXFONT_SANS20X27B=n -CONFIG_NXFONT_SANS22X29B=y -CONFIG_NXFONT_SANS28X37B=n -CONFIG_NXFONT_SANS40X49B=n -CONFIG_NXFONT_SERIF22X29=n -CONFIG_NXFONT_SERIF29X37=n -CONFIG_NXFONT_SERIF38X48=n -CONFIG_NXFONT_SERIF22X28B=n -CONFIG_NXFONT_SERIF27X38B=n -CONFIG_NXFONT_SERIF38X49B=n +# CONFIG_NXTK_AUTORAISE is not set + +# +# Font Selections +# CONFIG_NXFONTS_CHARBITS=7 -CONFIG_NX_BLOCKING=y -CONFIG_NX_MXSERVERMSGS=32 -CONFIG_NX_MXCLIENTMSGS=16 +# CONFIG_NXFONT_SANS17X22 is not set +# CONFIG_NXFONT_SANS20X26 is not set +CONFIG_NXFONT_SANS23X27=y +# CONFIG_NXFONT_SANS22X29 is not set +# CONFIG_NXFONT_SANS28X37 is not set +# CONFIG_NXFONT_SANS39X48 is not set +# CONFIG_NXFONT_SANS17X23B is not set +# CONFIG_NXFONT_SANS20X27B is not set +CONFIG_NXFONT_SANS22X29B=y +# CONFIG_NXFONT_SANS28X37B is not set +# CONFIG_NXFONT_SANS40X49B is not set +# CONFIG_NXFONT_SERIF22X29 is not set +# CONFIG_NXFONT_SERIF29X37 is not set +# CONFIG_NXFONT_SERIF38X48 is not set +# CONFIG_NXFONT_SERIF22X28B is not set +# CONFIG_NXFONT_SERIF27X38B is not set +# CONFIG_NXFONT_SERIF38X49B is not set +# CONFIG_NXCONSOLE is not set # -# SSD1289 LCD Hardware Configuration +# NX Multi-user only options # -CONFIG_LCD_SSD1289=y -CONFIG_LCD_NOGETRUN=n -CONFIG_LCD_LANDSCAPE=y -CONFIG_LCD_RLANDSCAPE=n -CONFIG_LCD_PORTRAIT=n -CONFIG_LCD_RPORTRAIT=n +# CONFIG_NX_MULTIUSER is not set # -# Settings for examples/uip +# Memory Management # -CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLES_UIP_DHCPC=n +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_GRAN is not set # -# Settings for examples/nettest +# Binary Formats # -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 +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_SYMTAB_ORDEREDBYNAME=y # -# Settings for examples/ostest +# Library Routines # -CONFIG_EXAMPLES_OSTEST_LOOPS=1 -CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048 -CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set # -# Settings for apps/nshlib +# Basic CXX Support # -CONFIG_NSH_BUILTIN_APPS=n -CONFIG_NSH_FILEIOSIZE=512 -CONFIG_NSH_STRERROR=n -CONFIG_NSH_LINELEN=64 -CONFIG_NSH_NESTDEPTH=3 -CONFIG_NSH_DISABLESCRIPT=n -CONFIG_NSH_DISABLEBG=n -CONFIG_NSH_ROMFSETC=n -CONFIG_NSH_CONSOLE=y -CONFIG_NSH_TELNET=n -CONFIG_NSH_ARCHINIT=n -CONFIG_NSH_IOBUFFER_SIZE=512 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=y -CONFIG_NSH_IPADDR=0x0a000002 -CONFIG_NSH_DRIPADDR=0x0a000001 -CONFIG_NSH_NETMASK=0xffffff00 -CONFIG_NSH_ROMFSMOUNTPT="/etc" -CONFIG_NSH_INITSCRIPT="init.d/rcS" -CONFIG_NSH_ROMFSDEVNO=0 -CONFIG_NSH_ROMFSSECTSIZE=64 -CONFIG_NSH_FATDEVNO=1 -CONFIG_NSH_FATSECTSIZE=512 -CONFIG_NSH_FATNSECTORS=1024 -CONFIG_NSH_FATMOUNTPT="/tmp" +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set # -# Architecture-specific NSH options +# uClibc++ Standard C++ Library # -CONFIG_NSH_MMCSDSPIPORTNO=0 -CONFIG_NSH_MMCSDSLOTNO=0 -CONFIG_NSH_MMCSDMINOR=0 +# CONFIG_UCLIBCXX is not set # -# Settings for examples/usbserial -# -CONFIG_EXAMPLES_USBSERIAL_INONLY=n -CONFIG_EXAMPLES_USBSERIAL_OUTONLY=n -CONFIG_EXAMPLES_USBSERIAL_ONLYSMALL=n -CONFIG_EXAMPLES_USBSERIAL_ONLYBIG=n - -CONFIG_EXAMPLES_USBSERIAL_TRACEINIT=n -CONFIG_EXAMPLES_USBSERIAL_TRACECLASS=n -CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=n -CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n -CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n - -# -# Settings for examples/cdcacm -# -# Configuration prequisites: -# -CONFIG_EXAMPLES_CDCACM_DEVMINOR=0 -CONFIG_EXAMPLES_CDCACM_TRACEINIT=n -CONFIG_EXAMPLES_CDCACM_TRACECLASS=n -CONFIG_EXAMPLES_CDCACM_TRACETRANSFERS=n -CONFIG_EXAMPLES_CDCACM_TRACECONTROLLER=n -CONFIG_EXAMPLES_CDCACM_TRACEINTERRUPTS=n - -# -# Settings for examples/adc +# Application Configuration # # -# Settings for examples/can +# Named Applications # +# CONFIG_NAMEDAPP is not set # -# Settings for examples/pwm +# Examples # - -# -# Settings for examples/watchdog -# - -# This test depends on these specific Watchdog/NSH configurations settings (your -# specific watchdog hardware settings might require additional settings). -# - -# -# Settings for examples/watchdog -# -# This test depends on these specific Watchdog/NSH configurations settings (your -# specific watchdog hardware settings might require additional settings). -# - -# -# Settings for examples/nxlines -# -CONFIG_EXAMPLES_NXLINES_BUILTIN=n +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_NETTEST is not set +# CONFIG_EXAMPLES_NSH is not set +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +CONFIG_EXAMPLES_NXLINES=y CONFIG_EXAMPLES_NXLINES_VPLANE=0 CONFIG_EXAMPLES_NXLINES_DEVNO=0 CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 @@ -722,17 +561,170 @@ CONFIG_EXAMPLES_NXLINES_BORDERWIDTH=4 CONFIG_EXAMPLES_NXLINES_BORDERCOLOR=0xffe0 CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR=0xf7bb CONFIG_EXAMPLES_NXLINES_BPP=16 -CONFIG_EXAMPLES_NXLINES_EXTERNINIT=n +# CONFIG_EXAMPLES_NXLINES_EXTERNINIT is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WLAN is not set # -# Stack and heap information +# Interpreters # -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_IDLETHREAD_STACKSIZE=1024 -CONFIG_USERMAIN_STACKSIZE=2048 -CONFIG_PTHREAD_STACK_MIN=256 -CONFIG_PTHREAD_STACK_DEFAULT=2048 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSFMOUNT is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PING is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_CONDEV is not set +# CONFIG_NSH_ARCHINIT is not set + +# +# NxWidgets/NxWM +# +# CONFIG_NXWIDGETS is not set + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card +# +# CONFIG_SYSTEM_SDCARD is not set + +# +# Sysinfo +# +# CONFIG_SYSTEM_SYSINFO is not set From c9750ef39f6796da96b830295323785bea281d92 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 8 Nov 2012 01:28:32 +0000 Subject: [PATCH 090/206] Add UG-2864AMBAG01 initialization for use on STM32F4Discovery git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5321 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 6 +- .../configs/lpcxpresso-lpc1768/src/up_oled.c | 6 +- nuttx/configs/stm32f4discovery/src/Makefile | 4 + .../stm32f4discovery/src/up_ug2864ambag01.c | 206 ++++++++++++++++++ nuttx/drivers/lcd/ug-2864ambag01.c | 13 -- nuttx/include/nuttx/lcd/ug-2864ambag01.h | 13 +- 6 files changed, 228 insertions(+), 20 deletions(-) create mode 100644 nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index c74dc6ec95..9b27102330 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3578,7 +3578,9 @@ contributed by Freddie Chopin. * arch/arm/src/stm32_otgfsdev.c: Partial fix from Petteri Aimonen. * drivers/lcd/ug-2864ambag01.c and include/nuttx/lcd/ug_2864ambag01.h: - LCD driver for the Univision OLED of the same name. + LCD driver for the Univision OLED of the same name (untested on + initial check-in). * configs/stm32f4discovery/nxlines: Configure to use mconf/Kconfig tool. - + * configs/stm32f4discovery/src/up_ug2864ambag01.c: Board-specific + initialization for UG-2864AMBAG01 OLED connecte to STM32F4Disovery. diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c index 7060a92e69..f3ecde9095 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c +++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c @@ -68,7 +68,7 @@ #endif /* Debug ********************************************************************/ -/* Define the CONFIG_LCD_UGDEBUG to enable detailed debug output (stuff you +/* Define the CONFIG_DEBUG_LCD to enable detailed debug output (stuff you * would never want to see unless you are debugging this file). * * Verbose debug must also be enabled @@ -80,10 +80,10 @@ #endif #ifndef CONFIG_DEBUG_VERBOSE -# undef CONFIG_LCD_UGDEBUG +# undef CONFIG_DEBUG_LCD #endif -#ifdef CONFIG_LCD_UGDEBUG +#ifdef CONFIG_DEBUG_LCD # define ugdbg(format, arg...) vdbg(format, ##arg) # define oleddc_dumpgpio(m) lpc17_dumpgpio(LPCXPRESSO_OLED_POWER, m) # define oledcs_dumpgpio(m) lpc17_dumpgpio(LPCXPRESSO_OLED_CS, m) diff --git a/nuttx/configs/stm32f4discovery/src/Makefile b/nuttx/configs/stm32f4discovery/src/Makefile index 97753132ac..1803d30996 100644 --- a/nuttx/configs/stm32f4discovery/src/Makefile +++ b/nuttx/configs/stm32f4discovery/src/Makefile @@ -96,6 +96,10 @@ CSRCS += up_ssd1289.c endif endif +ifeq ($(CONFIG_LCD_UG2864AMBAG01),y) +CSRCS += up_ug2864ambag01.c +endif + COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) diff --git a/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c b/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c new file mode 100644 index 0000000000..111ec80038 --- /dev/null +++ b/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c @@ -0,0 +1,206 @@ +/**************************************************************************** + * config/stm32f4discovery/src/up_ug2864ambag01.c + * arch/arm/src/board/up_ug2864ambag01.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include +#include + +#include "stm32f4discovery-internal.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ +/* This module is only built if CONFIG_NX_LCDDRIVER is selected. In this + * case, it would be an error if SSP1 is not also enabled. + */ + +#ifndef CONFIG_STM32_SPI1 +# error "The OLED driver requires CONFIG_STM32_SPI1 in the configuration" +#endif + +#ifndef CONFIG_SPI_CMDDATA +# error "The OLED driver requires CONFIG_SPI_CMDDATA in the configuration" +#endif + +/* Pin Configuration ********************************************************/ +/* Connector CON10 J1: + * + * 1 3v3 2 5V Vcc + * 3 RESET 4 DI + * 5 CS 6 SCLK + * 7 A0 8 LED- (N/C) + * 9 LED+ (N/C) 9 GND + */ + +#define STM32_OLED_RESET +#define STM32_OLED_A0 + +/* Debug ********************************************************************/ +/* Define the CONFIG_DEBUG_LCD to enable detailed debug output (stuff you + * would never want to see unless you are debugging this file). + * + * Verbose debug must also be enabled + */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_VERBOSE +# undef CONFIG_DEBUG_GRAPHICS +#endif + +#ifndef CONFIG_DEBUG_VERBOSE +# undef CONFIG_DEBUG_LCD +#endif + +#ifdef CONFIG_DEBUG_LCD +# define lcddbg(format, arg...) vdbg(format, ##arg) +# define oleddc_dumpgpio(m) stm32_dumpgpio(STM32_OLED_POWER, m) +# define oledcs_dumpgpio(m) stm32_dumpgpio(STM32_OLED_CS, m) +#else +# define lcddbg(x...) +# define oleddc_dumpgpio(m) +# define oledcs_dumpgpio(m) +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_nxdrvinit + * + * Description: + * Called by NX initialization logic to configure the OLED. + * + ****************************************************************************/ + +FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno) +{ + FAR struct spi_dev_s *spi; + FAR struct lcd_dev_s *dev; + + /* Configure the OLED GPIOs. For the SPI interface, insert jumpers in J42, + * J43, J45 pin1-2 and J46 pin 1-2. + */ + + oledcs_dumpgpio("up_nxdrvinit: After OLED CS setup"); + oleddc_dumpgpio("up_nxdrvinit: On entry"); + + (void)stm32_configgpio(STM32_OLED_RESET); /* OLED reset */ + (void)stm32_configgpio(STM32_OLED_A0); /* OLED Command/Data */ + + oleddc_dumpgpio("up_nxdrvinit: After OLED GPIO setup"); + + /* Wait a bit then release the OLED from the reset state */ + + up_mdelay(20); + stm32_gpiowrite(STM32_OLED_A0, true); + + /* Get the SSI port (configure as a Freescale SPI port) */ + + spi = up_spiinitialize(1); + if (!spi) + { + glldbg("Failed to initialize SSI port 1\n"); + } + else + { + /* Bind the SSI port to the OLED */ + + dev = ug2864ambag01_initialize(spi, devno); + if (!dev) + { + glldbg("Failed to bind SSI port 1 to OLED %d: %d\n", devno); + } + else + { + gllvdbg("Bound SSI port 1 to OLED %d\n", devno); + + /* And turn the OLED on */ + + (void)dev->setpower(dev, CONFIG_LCD_MAXPOWER); + return dev; + } + } + + return NULL; +} + +/**************************************************************************** + * Name: stm32_ssp1cmddata + * + * Description: + * Set or clear the SD1329 D/Cn bit to select data (true) or command + * (false). This function must be provided by platform-specific logic. + * This is an implementation of the cmddata method of the SPI + * interface defined by struct spi_ops_s (see include/nuttx/spi.h). + * + * Input Parameters: + * + * spi - SPI device that controls the bus the device that requires the CMD/ + * DATA selection. + * devid - If there are multiple devices on the bus, this selects which one + * to select cmd or data. NOTE: This design restricts, for example, + * one one SPI display per SPI bus. + * cmd - true: select command; false: select data + * + * Returned Value: + * None + * + ****************************************************************************/ + +int stm32_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ + if (devid == SPIDEV_DISPLAY) + { + /* Set GPIO to 1 for data, 0 for command */ + + (void)stm32_gpiowrite(STM32_OLED_A0, !cmd); + return OK; + } + + return -ENODEV; +} diff --git a/nuttx/drivers/lcd/ug-2864ambag01.c b/nuttx/drivers/lcd/ug-2864ambag01.c index b62fa6e43a..ff538ac82b 100644 --- a/nuttx/drivers/lcd/ug-2864ambag01.c +++ b/nuttx/drivers/lcd/ug-2864ambag01.c @@ -324,18 +324,6 @@ static void ug2864ambag01_lock(FAR struct spi_dev_s *spi); static void ug2864ambag01_unlock(FAR struct spi_dev_s *spi); #endif -/* Buffer Management */ - -static int ug2864ambag01_readdisplay(FAR struct ug2864ambag01_dev_s *priv, - fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, - size_t npixels); -static int ug2864ambag01_putbuffer(FAR struct ug2864ambag01_dev_s *priv, - fb_coord_t row, fb_coord_t col, - FAR const uint8_t *buffer, size_t npixels); -static int ug2864ambag01_getbuffer(FAR struct ug2864ambag01_dev_s *priv, - fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, - size_t npixels); - /* LCD Data Transfer Methods */ static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, @@ -1115,7 +1103,6 @@ void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color) { FAR struct ug2864ambag01_dev_s *priv = &g_oleddev; unsigned int page; - unsigned int col; /* Make an 8-bit version of the selected color */ diff --git a/nuttx/include/nuttx/lcd/ug-2864ambag01.h b/nuttx/include/nuttx/lcd/ug-2864ambag01.h index 86c4a03b43..a7de77efaa 100644 --- a/nuttx/include/nuttx/lcd/ug-2864ambag01.h +++ b/nuttx/include/nuttx/lcd/ug-2864ambag01.h @@ -47,8 +47,16 @@ * Included Files **************************************************************************************/ +#include + #include +#include + +#include "stm32_gpio.h" + +#ifdef CONFIG_LCD_UG2864AMBAG01 + /************************************************************************************** * Pre-processor Definitions **************************************************************************************/ @@ -214,8 +222,8 @@ extern "C" * **************************************************************************************/ -struct lcd_dev_s; /* See nuttx/lcd.h */ -struct spi_dev_s; /* See nuttx/spi.h */ +struct lcd_dev_s; /* See include/nuttx/lcd/lcd.h */ +struct spi_dev_s; /* See include/nuttx/spi.h */ FAR struct lcd_dev_s *ug2864ambag01_initialize(FAR struct spi_dev_s *spi, unsigned int devno); @@ -240,4 +248,5 @@ void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color); } #endif +#endif /* CONFIG_LCD_UG2864AMBAG01 */ #endif /* __INCLUDE_NUTTX_UG_8264AMBAG01_H */ From 169012eca915fde1276888796ac9a068bab596a1 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 8 Nov 2012 14:10:24 +0000 Subject: [PATCH 091/206] STM32 OTG FS fix from Petteri Aimonen; Finish off some UG-2864AMBAG01 test logic git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5322 42af7a65-404d-4744-a932-0658087f49c3 --- .../arm/src/stm32/chip/stm32f100_pinmap.h | 476 +++++++++--------- nuttx/arch/arm/src/stm32/stm32_otgfsdev.c | 13 +- nuttx/configs/stm32f4discovery/README.txt | 67 ++- .../configs/stm32f4discovery/include/board.h | 2 +- .../stm32f4discovery/nxlines/defconfig | 2 +- .../src/stm32f4discovery-internal.h | 25 + nuttx/configs/stm32f4discovery/src/up_spi.c | 86 +++- .../stm32f4discovery/src/up_ug2864ambag01.c | 114 ++--- nuttx/drivers/lcd/Kconfig | 10 - nuttx/drivers/lcd/ug-2864ambag01.c | 69 +-- nuttx/include/nuttx/lcd/ug-2864ambag01.h | 11 +- 11 files changed, 477 insertions(+), 398 deletions(-) diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h index 1a684771ec..addef02656 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h @@ -55,28 +55,28 @@ /* ADC */ -#define GPIO_ADC1_IN0 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) -#define GPIO_ADC1_IN1 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN1) -#define GPIO_ADC1_IN2 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN2) -#define GPIO_ADC1_IN3 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) -#define GPIO_ADC1_IN4 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN4) -#define GPIO_ADC1_IN5 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN5) -#define GPIO_ADC1_IN6 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN6) -#define GPIO_ADC1_IN7 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN7) -#define GPIO_ADC1_IN8 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN0) -#define GPIO_ADC1_IN9 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN1) -#define GPIO_ADC1_IN10 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN0) -#define GPIO_ADC1_IN11 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN1) -#define GPIO_ADC1_IN12 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN2) -#define GPIO_ADC1_IN13 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN3) -#define GPIO_ADC1_IN14 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN4) -#define GPIO_ADC1_IN15 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN5) +#define GPIO_ADC1_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC1_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC1_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC1_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC1_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC1_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC1_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC1_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC1_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC1_IN9 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) +#define GPIO_ADC1_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC1_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC1_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC1_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC1_IN14 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC1_IN15 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) /* CEC */ #if defined(CONFIG_STM32_CEC_REMAP) -# define GPIO_CEC (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN10) +# define GPIO_CEC (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) #else -# define GPIO_CEC (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN8) +# define GPIO_CEC (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8) #endif /* DAC @@ -86,8 +86,8 @@ * pin should first be configured to analog (AIN)." */ -#define GPIO_DAC_OUT1 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN4) -#define GPIO_DAC_OUT2 (GPIO_INPUT | GPIO_CNF_ANALOGIN | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN5) +#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) /* FSMC */ @@ -96,298 +96,298 @@ /* I2C */ #if defined(CONFIG_STM32_I2C1_REMAP) -# define GPIO_I2C1_SCL (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN8) -# define GPIO_I2C1_SDA (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN9) +# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8) +# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9) #else -# define GPIO_I2C1_SCL (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN6) -# define GPIO_I2C1_SDA (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN7) +# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6) +# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7) #endif -#define GPIO_I2C1_SMBA (GPIO_ALT | GPIO_CNF_INFLOAT | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN5) +#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) -#define GPIO_I2C2_SCL (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN10) -#define GPIO_I2C2_SDA (GPIO_ALT | GPIO_CNF_AFOD | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN11) -#define GPIO_I2C2_SMBA (GPIO_ALT | GPIO_CNF_INFLOAT | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN12) +#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11) +#define GPIO_I2C2_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) /* SPI */ #if defined(CONFIG_STM32_SPI1_REMAP) -# define GPIO_SPI1_NSS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN15) -# define GPIO_SPI1_SCK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN3) -# define GPIO_SPI1_MISO (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN4) -# define GPIO_SPI1_MOSI (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN5) +# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) +# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3) +# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4) +# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) #else -# define GPIO_SPI1_NSS (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN4) -# define GPIO_SPI1_SCK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN5) -# define GPIO_SPI1_MISO (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN6) -# define GPIO_SPI1_MOSI (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN7) +# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4) +# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN5) +# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6) +# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7) #endif -#define GPIO_SPI2_NSS (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN12) -#define GPIO_SPI2_SCK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN13) -#define GPIO_SPI2_MISO (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN14) -#define GPIO_SPI2_MOSI (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN15) +#define GPIO_SPI2_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) +#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13) +#define GPIO_SPI2_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) +#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15) -#define GPIO_SPI3_NSS (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN15) -#define GPIO_SPI3_SCK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN3) -#define GPIO_SPI3_MISO (GPIO_INPUT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN4) -#define GPIO_SPI3_MOSI (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN5) +#define GPIO_SPI3_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15) +#define GPIO_SPI3_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3) +#define GPIO_SPI3_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN4) +#define GPIO_SPI3_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) /* TIMERS */ #if defined(CONFIG_STM32_TIM1_FULL_REMAP) -# define GPIO_TIM1_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN7) -# define GPIO_TIM1_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN9) -# define GPIO_TIM1_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN9) -# define GPIO_TIM1_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN11) -# define GPIO_TIM1_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN11) -# define GPIO_TIM1_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN13) -# define GPIO_TIM1_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN13) -# define GPIO_TIM1_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN14) -# define GPIO_TIM1_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN14) -# define GPIO_TIM1_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTE | GPIO_PIN15) -# define GPIO_TIM1_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN8) -# define GPIO_TIM1_CH2N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN10) -# define GPIO_TIM1_CH3N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTE | GPIO_PIN12) +# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN7) +# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN9) +# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN9) +# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN11) +# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN11) +# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN13) +# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN13) +# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN14) +# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN14) +# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN15) +# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN8) +# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN10) +# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN12) #elif defined(CONFIG_STM32_TIM1_PARTIAL_REMAP) -# define GPIO_TIM1_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN12) -# define GPIO_TIM1_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN8) -# define GPIO_TIM1_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN8) -# define GPIO_TIM1_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN9) -# define GPIO_TIM1_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN9) -# define GPIO_TIM1_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN10) -# define GPIO_TIM1_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN10) -# define GPIO_TIM1_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN11) -# define GPIO_TIM1_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN11) -# define GPIO_TIM1_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN6) -# define GPIO_TIM1_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN7) -# define GPIO_TIM1_CH2N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN0) -# define GPIO_TIM1_CH3N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN1) +# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12) +# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8) +# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8) +# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9) +# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9) +# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10) +# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN10) +# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN11) +# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11) +# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) +# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7) +# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0) +# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1) #else -# define GPIO_TIM1_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN12) -# define GPIO_TIM1_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN8) -# define GPIO_TIM1_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN8) -# define GPIO_TIM1_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN9) -# define GPIO_TIM1_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN9) -# define GPIO_TIM1_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN10) -# define GPIO_TIM1_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN10) -# define GPIO_TIM1_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN11) -# define GPIO_TIM1_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN11) -# define GPIO_TIM1_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN12) -# define GPIO_TIM1_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN13) -# define GPIO_TIM1_CH2N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN14) -# define GPIO_TIM1_CH3N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN15) +# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12) +# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8) +# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8) +# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9) +# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9) +# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10) +# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN10) +# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN11) +# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11) +# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN12) +# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13) +# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) +# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15) #endif #if defined(CONFIG_STM32_TIM2_FULL_REMAP) -# define GPIO_TIM2_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN15) -# define GPIO_TIM2_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN15) -# define GPIO_TIM2_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN15) -# define GPIO_TIM2_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN3) -# define GPIO_TIM2_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN3) -# define GPIO_TIM2_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN10) -# define GPIO_TIM2_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN10) -# define GPIO_TIM2_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN11) -# define GPIO_TIM2_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN11) +# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) +# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) +# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15) +# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN3) +# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3) +# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10) +# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) +# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11) +# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11) #elif defined(CONFIG_STM32_TIM2_PARTIAL_REMAP_1) -# define GPIO_TIM2_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN15) -# define GPIO_TIM2_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN15) -# define GPIO_TIM2_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN15) -# define GPIO_TIM2_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN3) -# define GPIO_TIM2_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN3) -# define GPIO_TIM2_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN2) -# define GPIO_TIM2_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN2) -# define GPIO_TIM2_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) -# define GPIO_TIM2_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN3) +# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) +# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) +# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15) +# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN3) +# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3) +# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2) +# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3) #elif defined(CONFIG_STM32_TIM2_PARTIAL_REMAP_2) -# define GPIO_TIM2_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) -# define GPIO_TIM2_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) -# define GPIO_TIM2_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN0) -# define GPIO_TIM2_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN1) -# define GPIO_TIM2_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN1) -# define GPIO_TIM2_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN10) -# define GPIO_TIM2_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN10) -# define GPIO_TIM2_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN11) -# define GPIO_TIM2_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN11) +# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0) +# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) +# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1) +# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10) +# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) +# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11) +# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11) #else -# define GPIO_TIM2_ETR (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) -# define GPIO_TIM2_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) -# define GPIO_TIM2_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN0) -# define GPIO_TIM2_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN1) -# define GPIO_TIM2_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN1) -# define GPIO_TIM2_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN2) -# define GPIO_TIM2_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN2) -# define GPIO_TIM2_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) -# define GPIO_TIM2_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN3) +# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0) +# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) +# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1) +# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2) +# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3) #endif #if defined(CONFIG_STM32_TIM3_FULL_REMAP) -# define GPIO_TIM3_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN6) -# define GPIO_TIM3_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN6) -# define GPIO_TIM3_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN7) -# define GPIO_TIM3_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN7) -# define GPIO_TIM3_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN8) -# define GPIO_TIM3_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN8) -# define GPIO_TIM3_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN9) -# define GPIO_TIM3_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN9) +# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN6) +# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN6) +# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN7) +# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN7) +# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN8) +# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN8) +# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN9) +# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN9) #elif defined(CONFIG_STM32_TIM3_PARTIAL_REMAP) -# define GPIO_TIM3_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN4) -# define GPIO_TIM3_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN4) -# define GPIO_TIM3_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN5) -# define GPIO_TIM3_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN5) -# define GPIO_TIM3_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN0) -# define GPIO_TIM3_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN0) -# define GPIO_TIM3_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN1) -# define GPIO_TIM3_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN1) +# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4) +# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN4) +# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5) +# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) +# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) +# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0) +# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) +# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1) #else -# define GPIO_TIM3_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN6) -# define GPIO_TIM3_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN6) -# define GPIO_TIM3_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN7) -# define GPIO_TIM3_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN7) -# define GPIO_TIM3_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN0) -# define GPIO_TIM3_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN0) -# define GPIO_TIM3_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN1) -# define GPIO_TIM3_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN1) +# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) +# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6) +# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) +# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7) +# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) +# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0) +# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) +# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1) #endif #if defined(CONFIG_STM32_TIM4_REMAP) -# define GPIO_TIM4_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN12) -# define GPIO_TIM4_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN12) -# define GPIO_TIM4_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN13) -# define GPIO_TIM4_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN13) -# define GPIO_TIM4_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN14) -# define GPIO_TIM4_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN14) -# define GPIO_TIM4_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN15) -# define GPIO_TIM4_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN15) +# define GPIO_TIM4_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN12) +# define GPIO_TIM4_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN12) +# define GPIO_TIM4_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN13) +# define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN13) +# define GPIO_TIM4_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN14) +# define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN14) +# define GPIO_TIM4_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN15) +# define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN15) #else -# define GPIO_TIM4_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN6) -# define GPIO_TIM4_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN6) -# define GPIO_TIM4_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN7) -# define GPIO_TIM4_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN7) -# define GPIO_TIM4_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN8) -# define GPIO_TIM4_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN8) -# define GPIO_TIM4_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN9) -# define GPIO_TIM4_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN9) +# define GPIO_TIM4_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN6) +# define GPIO_TIM4_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6) +# define GPIO_TIM4_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN7) +# define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7) +# define GPIO_TIM4_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN8) +# define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8) +# define GPIO_TIM4_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9) +# define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9) #endif -#define GPIO_TIM5_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) -#define GPIO_TIM5_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN0) -#define GPIO_TIM5_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN1) -#define GPIO_TIM5_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN1) -#define GPIO_TIM5_CH3IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN2) -#define GPIO_TIM5_CH3OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN2) -#define GPIO_TIM5_CH4IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) -#define GPIO_TIM5_CH4OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN3) +#define GPIO_TIM5_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM5_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM5_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM5_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM5_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM5_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM5_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM5_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3) #if defined(CONFIG_STM32_TIM12_REMAP) -# define GPIO_TIM12_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN12) -# define GPIO_TIM12_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN12) -# define GPIO_TIM12_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN13) -# define GPIO_TIM12_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN13) +# define GPIO_TIM12_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN12) +# define GPIO_TIM12_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) +# define GPIO_TIM12_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13) +# define GPIO_TIM12_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13) #else -# define GPIO_TIM12_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN4) -# define GPIO_TIM12_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN4) -# define GPIO_TIM12_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN5) -# define GPIO_TIM12_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN5) +# define GPIO_TIM12_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) +# define GPIO_TIM12_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN4) +# define GPIO_TIM12_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) +# define GPIO_TIM12_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN5) #endif #if defined(CONFIG_STM32_TIM13_REMAP) -# define GPIO_TIM13_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN0) -# define GPIO_TIM13_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN0) +# define GPIO_TIM13_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) +# define GPIO_TIM13_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0) #else -# define GPIO_TIM13_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN8) -# define GPIO_TIM13_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN8) +# define GPIO_TIM13_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN8) +# define GPIO_TIM13_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN8) #endif #if defined(CONFIG_STM32_TIM14_REMAP) -# define GPIO_TIM14_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN1) -# define GPIO_TIM14_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN1) +# define GPIO_TIM14_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) +# define GPIO_TIM14_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1) #else -# define GPIO_TIM14_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN9) -# define GPIO_TIM14_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN9) +# define GPIO_TIM14_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN9) +# define GPIO_TIM14_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN9) #endif #if defined(CONFIG_STM32_TIM15_REMAP) -# define GPIO_TIM15_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN14) -# define GPIO_TIM15_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN14) -# define GPIO_TIM15_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN15) -# define GPIO_TIM15_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN15) +# define GPIO_TIM15_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN14) +# define GPIO_TIM15_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) +# define GPIO_TIM15_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN15) +# define GPIO_TIM15_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15) #else -# define GPIO_TIM15_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN2) -# define GPIO_TIM15_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN2) -# define GPIO_TIM15_CH2IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) -# define GPIO_TIM15_CH2OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN3) +# define GPIO_TIM15_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +# define GPIO_TIM15_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2) +# define GPIO_TIM15_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +# define GPIO_TIM15_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3) #endif -#define GPIO_TIM15_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN9) -#define GPIO_TIM15_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN15) +#define GPIO_TIM15_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM15_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15) #if defined(CONFIG_STM32_TIM16_REMAP) -# define GPIO_TIM16_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN6) -# define GPIO_TIM16_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN6) +# define GPIO_TIM16_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) +# define GPIO_TIM16_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6) #else -# define GPIO_TIM16_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN8) -# define GPIO_TIM16_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN8) +# define GPIO_TIM16_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN8) +# define GPIO_TIM16_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8) #endif -#define GPIO_TIM16_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN5) -#define GPIO_TIM16_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN6) +#define GPIO_TIM16_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5) +#define GPIO_TIM16_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6) #if defined(CONFIG_STM32_TIM17_REMAP) -# define GPIO_TIM17_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN7) -# define GPIO_TIM17_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN7) +# define GPIO_TIM17_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) +# define GPIO_TIM17_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7) #else -# define GPIO_TIM17_CH1IN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN9) -# define GPIO_TIM17_CH1OUT (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN9) +# define GPIO_TIM17_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9) +# define GPIO_TIM17_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9) #endif -#define GPIO_TIM17_BKIN (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN10) -#define GPIO_TIM17_CH1N (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN7) +#define GPIO_TIM17_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10) +#define GPIO_TIM17_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7) /* USART */ #if defined(CONFIG_STM32_USART1_REMAP) -# define GPIO_USART1_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN6) -# define GPIO_USART1_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN7) +# define GPIO_USART1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6) +# define GPIO_USART1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN7) #else -# define GPIO_USART1_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN9) -# define GPIO_USART1_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN10) +# define GPIO_USART1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9) +# define GPIO_USART1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10) #endif #if defined(CONFIG_STM32_USART2_REMAP) -# define GPIO_USART2_CTS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN3) -# define GPIO_USART2_RTS (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN4) -# define GPIO_USART2_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN5) -# define GPIO_USART2_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN6) -# define GPIO_USART2_CK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN7) +# define GPIO_USART2_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN3) +# define GPIO_USART2_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN4) +# define GPIO_USART2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN5) +# define GPIO_USART2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN6) +# define GPIO_USART2_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN7) #else -# define GPIO_USART2_CTS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN0) -# define GPIO_USART2_RTS (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN1) -# define GPIO_USART2_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN2) -# define GPIO_USART2_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTA | GPIO_PIN3) -# define GPIO_USART2_CK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN4) +# define GPIO_USART2_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +# define GPIO_USART2_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1) +# define GPIO_USART2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2) +# define GPIO_USART2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +# define GPIO_USART2_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4) #endif #if defined(CONFIG_STM32_USART3_FULL_REMAP) -# define GPIO_USART3_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN8) -# define GPIO_USART3_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN9) -# define GPIO_USART3_CK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN10) -# define GPIO_USART3_CTS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN11) -# define GPIO_USART3_RTS (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN12) +# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN8) +# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN9) +# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN10) +# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN11) +# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN12) #elif defined(CONFIG_STM32_USART3_PARTIAL_REMAP) -# define GPIO_USART3_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN10) -# define GPIO_USART3_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN11) -# define GPIO_USART3_CK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN12) -# define GPIO_USART3_CTS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN13) -# define GPIO_USART3_RTS (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN14) +# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10) +# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN11) +# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12) +# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13) +# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) #else -# define GPIO_USART3_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN10) -# define GPIO_USART3_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN11) -# define GPIO_USART3_CK (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN12) -# define GPIO_USART3_CTS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTB | GPIO_PIN13) -# define GPIO_USART3_RTS (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTB | GPIO_PIN14) +# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) +# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11) +# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) +# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13) +# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) #endif -#define GPIO_UART4_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN10) -#define GPIO_UART4_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTC | GPIO_PIN11) +#define GPIO_UART4_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10) +#define GPIO_UART4_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN11) -#define GPIO_UART5_TX (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN12) -#define GPIO_UART5_RX (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT | GPIO_PORTD | GPIO_PIN2) +#define GPIO_UART5_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12) +#define GPIO_UART5_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN2) #endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F100_PINMAP_H */ diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c index 2d6ca9831c..94772b693f 100644 --- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c +++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c @@ -3651,10 +3651,14 @@ static int stm32_epout_configure(FAR struct stm32_ep_s *privep, uint8_t eptype, regval = stm32_getreg(regaddr); if ((regval & OTGFS_DOEPCTL_USBAEP) == 0) { - regval &= ~(OTGFS_DOEPCTL_MPSIZ_MASK | OTGFS_DIEPCTL_EPTYP_MASK | OTGFS_DIEPCTL_TXFNUM_MASK); + if (regval & OTGFS_DOEPCTL_NAKSTS) + { + regval |= OTGFS_DOEPCTL_CNAK; + } + + regval &= ~(OTGFS_DOEPCTL_MPSIZ_MASK | OTGFS_DOEPCTL_EPTYP_MASK); regval |= mpsiz; regval |= (eptype << OTGFS_DOEPCTL_EPTYP_SHIFT); - regval |= (eptype << OTGFS_DIEPCTL_TXFNUM_SHIFT); regval |= (OTGFS_DOEPCTL_SD0PID | OTGFS_DOEPCTL_USBAEP); stm32_putreg(regval, regaddr); @@ -3743,6 +3747,11 @@ static int stm32_epin_configure(FAR struct stm32_ep_s *privep, uint8_t eptype, regval = stm32_getreg(regaddr); if ((regval & OTGFS_DIEPCTL_USBAEP) == 0) { + if (regval & OTGFS_DIEPCTL_NAKSTS) + { + regval |= OTGFS_DIEPCTL_CNAK; + } + regval &= ~(OTGFS_DIEPCTL_MPSIZ_MASK | OTGFS_DIEPCTL_EPTYP_MASK | OTGFS_DIEPCTL_TXFNUM_MASK); regval |= mpsiz; regval |= (eptype << OTGFS_DIEPCTL_EPTYP_SHIFT); diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index c193a1f421..896bf3662d 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -2,7 +2,7 @@ README ====== This README discusses issues unique to NuttX configurations for the -STMicro STM32F4 Discovery development board. +STMicro STM32F4Discovery development board. Contents ======== @@ -20,6 +20,7 @@ Contents - FPU - FSMC SRAM - SSD1289 + - UG-2864AMBAG01 - STM32F4Discovery-specific Configuration Options - Configurations @@ -564,7 +565,7 @@ by the "Lite" version of the Atollic toolchain. SSD1289 ======= -I purchased an LCD display on eBay from china. The LCD is 320x240 RGB565 and +I purchased an LCD display on eBay from China. The LCD is 320x240 RGB565 and is based on an SSD1289 LCD controller and an XPT2046 touch IC. The pin out from the 2x16 connect on the LCD is labeled as follows: @@ -702,6 +703,31 @@ The following summarize the bit banging oprations: WriteData(data); } +UG-2864AMBAG01 +============== + +I purchased an OLED display on eBay. The OLDE is 128x64 monochrome and +is based on an UG-2864AMBAG01 OLED controller. The OLED can run in either +parallel or SPI mode. I am using SPI mode. In SPI mode, the OLED is +write only so the driver keeps a 128*64/8 = 1KB framebuffer to remember +the display contents: + +Here is how I have the OLED connected. But you can change this with the +settings in include/board.h and src/stm324fdiscovery-internal.h: + + Connector CON10 J1: STM32F4Discovery + + 1 3v3 P2 3V + 3 RESET P2 PB6 (Arbitrary selection) + 5 CS P3 PB7 (Arbitrary selection) + 7 A0 P2 PB8 (Arbitrary selection) + 9 LED+ (N/C) ----- + 2 5V Vcc P2 5V + 4 DI P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1) + 6 SCLK P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1) + 8 LED- (N/C) ------ + 10 GND P2 GND + STM32F4Discovery-specific Configuration Options =============================================== @@ -1318,6 +1344,43 @@ Where is one of the following: b. Execute 'make menuconfig' in nuttx/ in order to start the reconfiguration process. + 3. This configured can be re-configured to use the UG-2864AMBAG01 + 0.96 inch OLED by adding or changing the following items int + the configuration (using 'make menuconfig'): + + +CONFIG_SPI_CMDDATA=y + + -CONFIG_LCD_MAXCONTRAST=1 + -CONFIG_LCD_MAXPOWER=255 + +CONFIG_LCD_MAXCONTRAST=255 + +CONFIG_LCD_MAXPOWER=1 + + -CONFIG_LCD_SSD1289=y + -CONFIG_SSD1289_PROFILE1=y + +CONFIG_LCD_UG2864AMBAG01=y + +CONFIG_UG2864AMBAG01_SPIMODE=3 + +CONFIG_UG2864AMBAG01_FREQUENCY=3500000 + +CONFIG_UG2864AMBAG01_NINTERFACES=1 + + -CONFIG_NX_DISABLE_1BPP=y + +CONFIG_NX_DISABLE_16BPP=y + + -CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 + -CONFIG_EXAMPLES_NXLINES_LINEWIDTH=16 + -CONFIG_EXAMPLES_NXLINES_LINECOLOR=0xffe0 + -CONFIG_EXAMPLES_NXLINES_BORDERWIDTH=4 + -CONFIG_EXAMPLES_NXLINES_BORDERCOLOR=0xffe0 + -CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR=0xf7bb + -CONFIG_EXAMPLES_NXLINES_BPP=16 + +CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x00 + +CONFIG_EXAMPLES_NXLINES_LINEWIDTH=4 + +CONFIG_EXAMPLES_NXLINES_LINECOLOR=0x01 + +CONFIG_EXAMPLES_NXLINES_BORDERWIDTH=2 + +CONFIG_EXAMPLES_NXLINES_BORDERCOLOR=0x01 + +CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR=0x00 + +CONFIG_EXAMPLES_NXLINES_BPP=1 + +CONFIG_EXAMPLES_NXLINES_EXTERNINIT=y + pm: -- This is a configuration that is used to test STM32 power management, i.e., diff --git a/nuttx/configs/stm32f4discovery/include/board.h b/nuttx/configs/stm32f4discovery/include/board.h index 01ae56b300..6171c3e403 100644 --- a/nuttx/configs/stm32f4discovery/include/board.h +++ b/nuttx/configs/stm32f4discovery/include/board.h @@ -224,7 +224,7 @@ #define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2 -/* SPI */ +/* SPI - There is a MEMS device on SPI1 using these pins: */ #define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 #define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 diff --git a/nuttx/configs/stm32f4discovery/nxlines/defconfig b/nuttx/configs/stm32f4discovery/nxlines/defconfig index be71de2ad7..286dd55ed6 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/defconfig +++ b/nuttx/configs/stm32f4discovery/nxlines/defconfig @@ -148,7 +148,7 @@ CONFIG_STM32_FSMC=y # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set # CONFIG_STM32_IWDG is not set -CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y # CONFIG_STM32_RNG is not set diff --git a/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h b/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h index 2824cd2bdd..0539442ca2 100644 --- a/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h +++ b/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h @@ -113,6 +113,31 @@ # define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN5) #endif +/* UG-2864AMBAG01 OLED Display: + * + * Connector CON10 J1: STM32F4Discovery + * + * 1 3v3 P2 3V + * 3 RESET P2 PB6 (Arbitrary selection) + * 5 CS P3 PB7 (Arbitrary selection) + * 7 A0 P2 PB8 (Arbitrary selection) + * 9 LED+ (N/C) ----- + * 2 5V Vcc P2 5V + * 4 DI P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1) + * 6 SCLK P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1) + * 8 LED- (N/C) ------ + * 10 GND P2 GND + */ + +#ifdef CONFIG_LCD_UG2864AMBAG01 +# define GPIO_OLED_RESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN6) +# define GPIO_OLED_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN7) +# define GPIO_OLED_A0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8) +#endif + /**************************************************************************************************** * Public Types ****************************************************************************************************/ diff --git a/nuttx/configs/stm32f4discovery/src/up_spi.c b/nuttx/configs/stm32f4discovery/src/up_spi.c index 3cf7d38b53..7ef3138fdd 100644 --- a/nuttx/configs/stm32f4discovery/src/up_spi.c +++ b/nuttx/configs/stm32f4discovery/src/up_spi.c @@ -42,6 +42,7 @@ #include #include +#include #include #include @@ -95,7 +96,11 @@ void weak_function stm32_spiinitialize(void) { #ifdef CONFIG_STM32_SPI1 - stm32_configgpio(GPIO_CS_MEMS); + (void)stm32_configgpio(GPIO_CS_MEMS); +#endif +#ifdef CONFIG_LCD_UG2864AMBAG01 + (void)stm32_configgpio(GPIO_OLED_CS); /* OLED chip select */ + (void)stm32_configgpio(GPIO_OLED_A0); /* OLED Command/Data */ #endif } @@ -129,12 +134,21 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele { spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - stm32_gpiowrite(GPIO_CS_MEMS, !selected); +#ifdef CONFIG_LCD_UG2864AMBAG01 + if (devid == SPIDEV_DISPLAY) + { + stm32_gpiowrite(GPIO_OLED_CS, !selected); + } + else +#endif + { + stm32_gpiowrite(GPIO_CS_MEMS, !selected); + } } uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) { - return SPI_STATUS_PRESENT; + return 0; } #endif @@ -146,7 +160,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) { - return SPI_STATUS_PRESENT; + return 0; } #endif @@ -158,8 +172,70 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) { - return SPI_STATUS_PRESENT; + return 0; } #endif +/**************************************************************************** + * Name: stm32_spi1cmddata + * + * Description: + * Set or clear the SD1329 D/Cn bit to select data (true) or command + * (false). This function must be provided by platform-specific logic. + * This is an implementation of the cmddata method of the SPI + * interface defined by struct spi_ops_s (see include/nuttx/spi.h). + * + * Input Parameters: + * + * spi - SPI device that controls the bus the device that requires the CMD/ + * DATA selection. + * devid - If there are multiple devices on the bus, this selects which one + * to select cmd or data. NOTE: This design restricts, for example, + * one one SPI display per SPI bus. + * cmd - true: select command; false: select data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SPI_CMDDATA +#ifdef CONFIG_STM32_SPI1 +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ +#ifdef CONFIG_LCD_UG2864AMBAG01 + if (devid == SPIDEV_DISPLAY) + { + /* "This is the Data/Command control pad which determines whether the + * data bits are data or a command. + * + * A0 = “H”: the inputs at D0 to D7 are treated as display data. + * A0 = “L”: the inputs at D0 to D7 are transferred to the command + * registers." + */ + + (void)stm32_gpiowrite(GPIO_OLED_A0, !cmd); + return OK; + } +#endif + + return -ENODEV; +} +#endif + +#ifdef CONFIG_STM32_SPI2 +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ + return -ENODEV; +} +#endif + +#ifdef CONFIG_STM32_SPI3 +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ + return -ENODEV; +} +#endif +#endif /* CONFIG_SPI_CMDDATA */ + #endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */ diff --git a/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c b/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c index 111ec80038..a012d7384f 100644 --- a/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c +++ b/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c @@ -40,23 +40,22 @@ #include -#include #include -#include #include #include #include +#include "stm32_gpio.h" #include "stm32f4discovery-internal.h" +#ifdef CONFIG_LCD_UG2864AMBAG01 + /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ /* Configuration ************************************************************/ -/* This module is only built if CONFIG_NX_LCDDRIVER is selected. In this - * case, it would be an error if SSP1 is not also enabled. - */ +/* The pin configurations here require that SPI1 is selected */ #ifndef CONFIG_STM32_SPI1 # error "The OLED driver requires CONFIG_STM32_SPI1 in the configuration" @@ -67,42 +66,32 @@ #endif /* Pin Configuration ********************************************************/ -/* Connector CON10 J1: +/* Connector CON10 J1: STM32F4Discovery * - * 1 3v3 2 5V Vcc - * 3 RESET 4 DI - * 5 CS 6 SCLK - * 7 A0 8 LED- (N/C) - * 9 LED+ (N/C) 9 GND + * 1 3v3 P2 3V + * 3 RESET P2 PB6 (Arbitrary selection) + * 5 CS P3 PB7 (Arbitrary selection) + * 7 A0 P2 PB8 (Arbitrary selection) + * 9 LED+ (N/C) ----- + * 2 5V Vcc P2 5V + * 4 DI P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1) + * 6 SCLK P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1) + * 8 LED- (N/C) ------ + * 10 GND P2 GND + * + * Note that the OLED CS and A0 are managed in the up_spi.c file. */ -#define STM32_OLED_RESET -#define STM32_OLED_A0 +/* Definitions in stm32f4discovery-internal.h */ /* Debug ********************************************************************/ -/* Define the CONFIG_DEBUG_LCD to enable detailed debug output (stuff you - * would never want to see unless you are debugging this file). - * - * Verbose debug must also be enabled - */ - -#ifndef CONFIG_DEBUG -# undef CONFIG_DEBUG_VERBOSE -# undef CONFIG_DEBUG_GRAPHICS -#endif - -#ifndef CONFIG_DEBUG_VERBOSE -# undef CONFIG_DEBUG_LCD -#endif #ifdef CONFIG_DEBUG_LCD -# define lcddbg(format, arg...) vdbg(format, ##arg) -# define oleddc_dumpgpio(m) stm32_dumpgpio(STM32_OLED_POWER, m) -# define oledcs_dumpgpio(m) stm32_dumpgpio(STM32_OLED_CS, m) +# define lcddbg(format, arg...) dbg(format, ##arg) +# define lcdvdbg(format, arg...) vdbg(format, ##arg) #else # define lcddbg(x...) -# define oleddc_dumpgpio(m) -# define oledcs_dumpgpio(m) +# define lcdvdbg(x...) #endif /**************************************************************************** @@ -122,42 +111,36 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno) FAR struct spi_dev_s *spi; FAR struct lcd_dev_s *dev; - /* Configure the OLED GPIOs. For the SPI interface, insert jumpers in J42, - * J43, J45 pin1-2 and J46 pin 1-2. + /* Configure the OLED GPIOs. This initial configuration is RESET low, + * putting the OLED into reset state. */ - oledcs_dumpgpio("up_nxdrvinit: After OLED CS setup"); - oleddc_dumpgpio("up_nxdrvinit: On entry"); - - (void)stm32_configgpio(STM32_OLED_RESET); /* OLED reset */ - (void)stm32_configgpio(STM32_OLED_A0); /* OLED Command/Data */ - - oleddc_dumpgpio("up_nxdrvinit: After OLED GPIO setup"); + (void)stm32_configgpio(GPIO_OLED_RESET); /* Wait a bit then release the OLED from the reset state */ up_mdelay(20); - stm32_gpiowrite(STM32_OLED_A0, true); + stm32_gpiowrite(GPIO_OLED_RESET, true); - /* Get the SSI port (configure as a Freescale SPI port) */ + /* Get the SPI1 port interface */ spi = up_spiinitialize(1); if (!spi) { - glldbg("Failed to initialize SSI port 1\n"); + lcddbg("Failed to initialize SPI port 1\n"); } else { - /* Bind the SSI port to the OLED */ + /* Bind the SPI port to the OLED */ dev = ug2864ambag01_initialize(spi, devno); if (!dev) { - glldbg("Failed to bind SSI port 1 to OLED %d: %d\n", devno); + lcddbg("Failed to bind SPI port 1 to OLED %d: %d\n", devno); } else { - gllvdbg("Bound SSI port 1 to OLED %d\n", devno); + lcdvdbg("Bound SPI port 1 to OLED %d\n", devno); /* And turn the OLED on */ @@ -168,39 +151,4 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno) return NULL; } - -/**************************************************************************** - * Name: stm32_ssp1cmddata - * - * Description: - * Set or clear the SD1329 D/Cn bit to select data (true) or command - * (false). This function must be provided by platform-specific logic. - * This is an implementation of the cmddata method of the SPI - * interface defined by struct spi_ops_s (see include/nuttx/spi.h). - * - * Input Parameters: - * - * spi - SPI device that controls the bus the device that requires the CMD/ - * DATA selection. - * devid - If there are multiple devices on the bus, this selects which one - * to select cmd or data. NOTE: This design restricts, for example, - * one one SPI display per SPI bus. - * cmd - true: select command; false: select data - * - * Returned Value: - * None - * - ****************************************************************************/ - -int stm32_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) -{ - if (devid == SPIDEV_DISPLAY) - { - /* Set GPIO to 1 for data, 0 for command */ - - (void)stm32_gpiowrite(STM32_OLED_A0, !cmd); - return OK; - } - - return -ENODEV; -} +#endif /* CONFIG_LCD_UG2864AMBAG01 */ diff --git a/nuttx/drivers/lcd/Kconfig b/nuttx/drivers/lcd/Kconfig index 18c0dd87c6..2d20003ac5 100644 --- a/nuttx/drivers/lcd/Kconfig +++ b/nuttx/drivers/lcd/Kconfig @@ -261,16 +261,6 @@ config UG2864AMBAG01_NINTERFACES Specifies the number of physical UG-9664HSWAG01 devices that will be supported. NOTE: At present, this must be undefined or defined to be 1. -config UG2864AMBAG01_FRAMEBUFFER - bool "UG-2864AMBAG01 Framebuffer" - default y - ---help--- - If defined, accesses will be performed using an in-memory copy of the - OLED's GRAM. This cost of this buffer is 128 * 64 / 8 = 1Kb. - - If G2864AMBAG01_FRAMEBUFFER is not defined and the LCD is a LANDSCAPE - mode, then a 128 byte buffer is still required. - endif config LCD_SSD1289 diff --git a/nuttx/drivers/lcd/ug-2864ambag01.c b/nuttx/drivers/lcd/ug-2864ambag01.c index ff538ac82b..3b418bf059 100644 --- a/nuttx/drivers/lcd/ug-2864ambag01.c +++ b/nuttx/drivers/lcd/ug-2864ambag01.c @@ -1,6 +1,7 @@ /************************************************************************************** * drivers/lcd/ug-2864ambag01.c - * Driver for Univision UG-2864AMBAG01 OLED display (wih SH1101A controller) + * Driver for Univision UG-2864AMBAG01 OLED display (wih SH1101A controller) in SPI + * mode * * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -146,11 +147,6 @@ # define CONFIG_UG2864AMBAG01_NINTERFACES 1 #endif -#ifndef CONFIG_UG2864AMBAG01_FRAMEBUFFER -# warning "CONFIG_UG2864AMBAG01_FRAMEBUFFER is required" -# define CONFIG_UG2864AMBAG01_FRAMEBUFFER 1 -#endif - #if defined(CONFIG_LCD_PORTRAIT) || defined(CONFIG_LCD_RPORTRAIT) # warning "No support yet for portrait modes" # define CONFIG_LCD_LANDSCAPE 1 @@ -206,19 +202,6 @@ #define SH1101A_STATUS_ONOFF (0x40) #define SH1101A_RDDATA(d) (d) /* Read Display Data */ -/* Define the CONFIG_DEBUG_LCD to enable detailed debug output (stuff you would - * never want to see unless you are debugging this file). Verbose debug must also be - * enabled - */ - -#ifndef CONFIG_DEBUG -# undef CONFIG_DEBUG_VERBOSE -#endif - -#ifndef CONFIG_DEBUG_VERBOSE -# undef CONFIG_DEBUG_LCD -#endif - /* Color Properties *******************************************************************/ /* Display Resolution * @@ -259,8 +242,8 @@ * Row size: 128 columns x 8 rows-per-page / 8 bits-per-pixel */ -#define UG2864AMBAG01_FBSIZE ((UG2864AMBAG01_XRES * UG2864AMBAG01_YRES) >> 3) -#define UG2864AMBAG01_ROWSIZE (UG2864AMBAG01_XRES) +#define UG2864AMBAG01_FBSIZE (UG2864AMBAG01_XSTRIDE * UG2864AMBAG01_YRES) +#define UG2864AMBAG01_ROWSIZE (UG2864AMBAG01_XSTRIDE) /* Bit helpers */ @@ -270,9 +253,11 @@ /* Debug ******************************************************************************/ #ifdef CONFIG_DEBUG_LCD -# define lcddbg(format, arg...) vdbg(format, ##arg) +# define lcddbg(format, arg...) dbg(format, ##arg) +# define lcdvdbg(format, arg...) vdbg(format, ##arg) #else # define lcddbg(x...) +# define lcdvdbg(x...) #endif /************************************************************************************** @@ -292,20 +277,12 @@ struct ug2864ambag01_dev_s bool on; /* true: display is on */ - /* If the SH1101A does not support reading from the display memory, then it will be - * necessary to keep a shadow copy of the framebuffer memory. At 128x64, this amounts - * to 1KB. - * - * If the SH1101A is writable but the display is in a landscape mode then a small - * 128 / 8 = 16 byte buffer is still required in order to perform the 90 degree - * rotation. + /* The SH1101A does not support reading from the display memory in SPI mode. + * Since there is 1 BPP and access is byte-by-byte, it is necessary to keep + * a shadow copy of the framebuffer memory. At 128x64, this amounts to 1KB. */ -#if CONFIG_UG2864AMBAG01_FRAMEBUFFER uint8_t fb[UG2864AMBAG01_FBSIZE]; -#elif defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) - uint8_t buffer[UG2864AMBAG01_ROWSIZE]; -#endif }; /************************************************************************************** @@ -441,8 +418,8 @@ static struct ug2864ambag01_dev_s g_oleddev = #ifdef CONFIG_SPI_OWNBUS static inline void ug2864ambag01_configspi(FAR struct spi_dev_s *spi) { - lcddbg("Mode: %d Bits: 8 Frequency: %d\n", - CONFIG_UG2864AMBAG01_SPIMODE, CONFIG_UG2864AMBAG01_FREQUENCY); + lcdvdbg("Mode: %d Bits: 8 Frequency: %d\n", + CONFIG_UG2864AMBAG01_SPIMODE, CONFIG_UG2864AMBAG01_FREQUENCY); /* Configure SPI for the UG-2864AMBAG01. But only if we own the SPI bus. Otherwise, * don't bother because it might change. @@ -543,7 +520,7 @@ static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_ int pixlen; uint8_t i; - gvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); + lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); DEBUGASSERT(buffer); /* Clip the run to the display */ @@ -717,7 +694,7 @@ static int ug2864ambag01_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buf int pixlen; uint8_t i; - gvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); + lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); DEBUGASSERT(buffer); /* Clip the run to the display */ @@ -838,8 +815,8 @@ static int ug2864ambag01_getvideoinfo(FAR struct lcd_dev_s *dev, FAR struct fb_videoinfo_s *vinfo) { DEBUGASSERT(dev && vinfo); - gvdbg("fmt: %d xres: %d yres: %d nplanes: %d\n", - g_videoinfo.fmt, g_videoinfo.xres, g_videoinfo.yres, g_videoinfo.nplanes); + lcdvdbg("fmt: %d xres: %d yres: %d nplanes: %d\n", + g_videoinfo.fmt, g_videoinfo.xres, g_videoinfo.yres, g_videoinfo.nplanes); memcpy(vinfo, &g_videoinfo, sizeof(struct fb_videoinfo_s)); return OK; } @@ -856,7 +833,7 @@ static int ug2864ambag01_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int pl FAR struct lcd_planeinfo_s *pinfo) { DEBUGASSERT(pinfo && planeno == 0); - gvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp); + lcdvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp); memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s)); return OK; } @@ -875,7 +852,7 @@ static int ug2864ambag01_getpower(FAR struct lcd_dev_s *dev) FAR struct ug2864ambag01_dev_s *priv = (FAR struct ug2864ambag01_dev_s *)dev; DEBUGASSERT(priv); - gvdbg("power: %s\n", priv->on ? "ON" : "OFF"); + lcdvdbg("power: %s\n", priv->on ? "ON" : "OFF"); return priv->on ? CONFIG_LCD_MAXPOWER : 0; } @@ -893,7 +870,7 @@ static int ug2864ambag01_setpower(struct lcd_dev_s *dev, int power) struct ug2864ambag01_dev_s *priv = (struct ug2864ambag01_dev_s *)dev; DEBUGASSERT(priv && (unsigned)power <= CONFIG_LCD_MAXPOWER && priv->spi); - gvdbg("power: %d [%d]\n", power, priv->on ? CONFIG_LCD_MAXPOWER : 0); + lcdvdbg("power: %d [%d]\n", power, priv->on ? CONFIG_LCD_MAXPOWER : 0); /* Lock and select device */ @@ -935,7 +912,7 @@ static int ug2864ambag01_getcontrast(struct lcd_dev_s *dev) struct ug2864ambag01_dev_s *priv = (struct ug2864ambag01_dev_s *)dev; DEBUGASSERT(priv); - gvdbg("contrast: %d\n", priv->contrast); + lcdvdbg("contrast: %d\n", priv->contrast); return priv->contrast; } @@ -952,7 +929,7 @@ static int ug2864ambag01_setcontrast(struct lcd_dev_s *dev, unsigned int contras struct ug2864ambag01_dev_s *priv = (struct ug2864ambag01_dev_s *)dev; unsigned int scaled; - gvdbg("contrast: %d\n", contrast); + lcdvdbg("contrast: %d\n", contrast); DEBUGASSERT(priv); /* Verify the contrast value */ @@ -1025,7 +1002,7 @@ FAR struct lcd_dev_s *ug2864ambag01_initialize(FAR struct spi_dev_s *spi, unsign { FAR struct ug2864ambag01_dev_s *priv = &g_oleddev; - gvdbg("Initializing\n"); + lcdvdbg("Initializing\n"); DEBUGASSERT(spi && devno == 0); /* Save the reference to the SPI device */ @@ -1117,9 +1094,7 @@ void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color) /* Initialize the framebuffer */ -#ifdef CONFIG_UG2864AMBAG01_FRAMEBUFFER memset(priv->fb, color, UG2864AMBAG01_FBSIZE); -#endif /* Lock and select device */ diff --git a/nuttx/include/nuttx/lcd/ug-2864ambag01.h b/nuttx/include/nuttx/lcd/ug-2864ambag01.h index a7de77efaa..deb5689812 100644 --- a/nuttx/include/nuttx/lcd/ug-2864ambag01.h +++ b/nuttx/include/nuttx/lcd/ug-2864ambag01.h @@ -1,6 +1,7 @@ /************************************************************************************** * include/nuttx/lcd/ug-2864ambag01.h - * Driver for Univision UG-2864AMBAG01 OLED display (wih SH1101A controller) + * Driver for Univision UG-2864AMBAG01 OLED display (wih SH1101A controller) in SPI + * mode * * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -53,8 +54,6 @@ #include -#include "stm32_gpio.h" - #ifdef CONFIG_LCD_UG2864AMBAG01 /************************************************************************************** @@ -67,12 +66,6 @@ * CONFIG_UG2864AMBAG01_FREQUENCY - Define to use a different bus frequency * CONFIG_UG2864AMBAG01_NINTERFACES - Specifies the number of physical UG-2864AMBAG01 * devices that will be supported. - * CONFIG_UG2864AMBAG01_FRAMEBUFFER - If defined, accesses will be performed using an - * in-memory copy of the OLEDs GDDRAM. This cost of this buffer is 128 * 64 / 8 = - * 1Kb. - * - * If CONFIG_UG2864AMBAG01_FRAMEBUFFER is not defined and the LCD is a LANDSCAPE mode, - * then a 128 byte buffer is still required. * * Required LCD driver settings: * From bf340e0ab5a30b324ce56d09f6be0fa630990327 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 8 Nov 2012 18:05:39 +0000 Subject: [PATCH 092/206] Support for non-common vectors from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5323 42af7a65-404d-4744-a932-0658087f49c3 --- .../arch/arm/include/stm32/stm32f10xxx_irq.h | 12 ++-- .../arm/src/stm32/chip/stm32f10xxx_vectors.h | 64 ++++++++++++++++++- nuttx/configs/stm32f4discovery/README.txt | 30 +++++---- .../src/stm32f4discovery-internal.h | 30 +++++---- .../stm32f4discovery/src/up_ug2864ambag01.c | 33 ++++++---- 5 files changed, 127 insertions(+), 42 deletions(-) diff --git a/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h b/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h index 0a7c230bce..7c3f7cf958 100644 --- a/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h +++ b/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h @@ -62,7 +62,7 @@ */ /* Value line devices */ - + #if defined(CONFIG_STM32_VALUELINE) # define STM32_IRQ_WWDG (16) /* 0: Window Watchdog interrupt */ # define STM32_IRQ_PVD (17) /* 1: PVD through EXTI Line detection interrupt */ @@ -83,7 +83,10 @@ # define STM32_IRQ_DMA1CH6 (32) /* 16: DMA1 Channel 6 global interrupt */ # define STM32_IRQ_DMA1CH7 (33) /* 17: DMA1 Channel 7 global interrupt */ # define STM32_IRQ_ADC1 (34) /* 18: ADC1 global interrupt */ - /* 19-22: reserved */ +# define STM32_IRQ_RESERVED0 (35) /* 19: Reserved 0 */ +# define STM32_IRQ_RESERVED1 (36) /* 20: Reserved 1 */ +# define STM32_IRQ_RESERVED2 (37) /* 21: Reserved 2 */ +# define STM32_IRQ_RESERVED3 (38) /* 22: Reserved 3 */ # define STM32_IRQ_EXTI95 (39) /* 23: EXTI Line[9:5] interrupts */ # define STM32_IRQ_TIM1BRK (40) /* 24: TIM1 Break interrupt */ # define STM32_IRQ_TIM15 (40) /* TIM15 global interrupt */ @@ -110,9 +113,10 @@ # define STM32_IRQ_TIM12 (59) /* 43: TIM12 global interrupt */ # define STM32_IRQ_TIM13 (60) /* 44: TIM13 global interrupt */ # define STM32_IRQ_TIM14 (61) /* 45: TIM14 global interrupt */ - /* 46-47: reserved */ +# define STM32_IRQ_RESERVED4 (62) /* 46: Reserved 4 */ +# define STM32_IRQ_RESERVED5 (63) /* 47: Reserved 5 */ # define STM32_IRQ_FSMC (64) /* 48: FSMC global interrupt */ - /* 49: reserved */ +# define STM32_IRQ_RESERVED6 (65) /* 49: Reserved 6 */ # define STM32_IRQ_TIM5 (66) /* 50: TIM5 global interrupt */ # define STM32_IRQ_SPI3 (67) /* 51: SPI3 global interrupt */ # define STM32_IRQ_UART4 (68) /* 52: USART2 global interrupt */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h index 1259f2fce8..24822c37d3 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h @@ -56,7 +56,69 @@ # define ARMV7M_PERIPHERAL_INTERRUPTS 61 #else -# error This target requires CONFIG_ARMV7M_CMNVECTOR + +VECTOR(stm32_wwdg, STM32_IRQ_WWDG) /* Vector 16+0: Window Watchdog interrupt */ +VECTOR(stm32_pvd, STM32_IRQ_PVD) /* Vector 16+1: PVD through EXTI Line detection interrupt */ +VECTOR(stm32_tamper, STM32_IRQ_TAMPER) /* Vector 16+2: Tamper interrupt */ +VECTOR(stm32_rtc, STM32_IRQ_RTC) /* Vector 16+3: RTC Wakeup through EXTI line interrupt */ +VECTOR(stm32_flash, STM32_IRQ_FLASH) /* Vector 16+4: Flash global interrupt */ +VECTOR(stm32_rcc, STM32_IRQ_RCC) /* Vector 16+5: RCC global interrupt */ +VECTOR(stm32_exti0, STM32_IRQ_EXTI0) /* Vector 16+6: EXTI Line 0 interrupt */ +VECTOR(stm32_exti1, STM32_IRQ_EXTI1) /* Vector 16+7: EXTI Line 1 interrupt */ +VECTOR(stm32_exti2, STM32_IRQ_EXTI2) /* Vector 16+8: EXTI Line 2 interrupt */ +VECTOR(stm32_exti3, STM32_IRQ_EXTI3) /* Vector 16+9: EXTI Line 3 interrupt */ +VECTOR(stm32_exti4, STM32_IRQ_EXTI4) /* Vector 16+10: EXTI Line 4 interrupt */ +VECTOR(stm32_dma1ch1, STM32_IRQ_DMA1CH1) /* Vector 16+11: DMA1 Channel 1 global interrupt */ +VECTOR(stm32_dma1ch2, STM32_IRQ_DMA1CH2) /* Vector 16+12: DMA1 Channel 2 global interrupt */ +VECTOR(stm32_dma1ch3, STM32_IRQ_DMA1CH3) /* Vector 16+13: DMA1 Channel 3 global interrupt */ +VECTOR(stm32_dma1ch4, STM32_IRQ_DMA1CH4) /* Vector 16+14: DMA1 Channel 4 global interrupt */ +VECTOR(stm32_dma1ch5, STM32_IRQ_DMA1CH5) /* Vector 16+15: DMA1 Channel 5 global interrupt */ +VECTOR(stm32_dma1ch6, STM32_IRQ_DMA1CH6) /* Vector 16+16: DMA1 Channel 6 global interrupt */ +VECTOR(stm32_dma1ch7, STM32_IRQ_DMA1CH7) /* Vector 16+17: DMA1 Channel 7 global interrupt */ +VECTOR(stm32_adc1, STM32_IRQ_ADC1) /* Vector 16+18: ADC1 global interrupt */ +UNUSED(STM32_IRQ_RESERVED0) /* Vector 16+19: Reserved 0 */ +UNUSED(STM32_IRQ_RESERVED1) /* Vector 16+20: Reserved 1 */ +UNUSED(STM32_IRQ_RESERVED2) /* Vector 16+21: Reserved 2 */ +UNUSED(STM32_IRQ_RESERVED3) /* Vector 16+22: Reserved 3 */ +VECTOR(stm32_exti95, STM32_IRQ_EXTI95) /* Vector 16+23: EXTI Line[9:5] interrupts */ +VECTOR(stm32_tim1brk, STM32_IRQ_TIM1BRK) /* Vector 16+24: TIM1 Break interrupt; TIM15 global interrupt */ +VECTOR(stm32_tim1up, STM32_IRQ_TIM1UP) /* Vector 16+25: TIM1 Update interrupt; TIM16 global interrupt */ +VECTOR(stm32_tim1trgcom, STM32_IRQ_TIM1TRGCOM) /* Vector 16+26: TIM1 Trigger and Commutation interrupts; TIM17 global interrupt */ +VECTOR(stm32_tim1cc, STM32_IRQ_TIM1CC) /* Vector 16+27: TIM1 Capture Compare interrupt */ +VECTOR(stm32_tim2, STM32_IRQ_TIM2) /* Vector 16+28: TIM2 global interrupt */ +VECTOR(stm32_tim3, STM32_IRQ_TIM3) /* Vector 16+29: TIM3 global interrupt */ +VECTOR(stm32_tim4, STM32_IRQ_TIM4) /* Vector 16+30: TIM4 global interrupt */ +VECTOR(stm32_i2c1ev, STM32_IRQ_I2C1EV) /* Vector 16+31: I2C1 event interrupt */ +VECTOR(stm32_i2c1er, STM32_IRQ_I2C1ER) /* Vector 16+32: I2C1 error interrupt */ +VECTOR(stm32_i2c2ev, STM32_IRQ_I2C2EV) /* Vector 16+33: I2C2 event interrupt */ +VECTOR(stm32_i2c2er, STM32_IRQ_I2C2ER) /* Vector 16+34: I2C2 error interrupt */ +VECTOR(stm32_spi1, STM32_IRQ_SPI1) /* Vector 16+35: SPI1 global interrupt */ +VECTOR(stm32_spi2, STM32_IRQ_SPI2) /* Vector 16+36: SPI2 global interrupt */ +VECTOR(stm32_usart1, STM32_IRQ_USART1) /* Vector 16+37: USART1 global interrupt */ +VECTOR(stm32_usart2, STM32_IRQ_USART2) /* Vector 16+38: USART2 global interrupt */ +VECTOR(stm32_usart3, STM32_IRQ_USART3) /* Vector 16+39: USART3 global interrupt */ +VECTOR(stm32_exti1510, STM32_IRQ_EXTI1510) /* Vector 16+40: EXTI Line[15:10] interrupts */ +VECTOR(stm32_rtcalr, STM32_IRQ_RTCALR) /* Vector 16+41: RTC alarms (A and B) through EXTI line interrupt */ +VECTOR(stm32_cec, STM32_IRQ_CEC) /* Vector 16+42: CEC global interrupt */ +VECTOR(stm32_tim12, STM32_IRQ_TIM12) /* Vector 16+43: TIM12 global interrupt */ +VECTOR(stm32_tim13, STM32_IRQ_TIM13) /* Vector 16+44: TIM13 global interrupt */ +VECTOR(stm32_tim14, STM32_IRQ_TIM14) /* Vector 16+45: TIM14 global interrupt */ +UNUSED(STM32_IRQ_RESERVED4) /* Vector 16+46: Reserved 4 */ +UNUSED(STM32_IRQ_RESERVED5) /* Vector 16+47: Reserved 5 */ +VECTOR(stm32_fsmc, STM32_IRQ_FSMC) /* Vector 16+48: FSMC global interrupt */ +UNUSED(STM32_IRQ_RESERVED6) /* Vector 16+49: Reserved 6 */ +VECTOR(stm32_tim5, STM32_IRQ_TIM5) /* Vector 16+50: TIM5 global interrupt */ +VECTOR(stm32_spi3, STM32_IRQ_SPI3) /* Vector 16+51: SPI3 global interrupt */ +VECTOR(stm32_uart4, STM32_IRQ_UART4) /* Vector 16+52: USART2 global interrupt */ +VECTOR(stm32_uart5, STM32_IRQ_UART5) /* Vector 16+53: USART5 global interrupt */ +VECTOR(stm32_tim6, STM32_IRQ_TIM6) /* Vector 16+54: TIM6 global interrupt */ +VECTOR(stm32_tim7, STM32_IRQ_TIM7) /* Vector 16+55: TIM7 global interrupt */ +VECTOR(stm32_dma2ch1, STM32_IRQ_DMA2CH1) /* Vector 16+56: DMA2 Channel 1 global interrupt */ +VECTOR(stm32_dma2ch2, STM32_IRQ_DMA2CH2) /* Vector 16+57: DMA2 Channel 2 global interrupt */ +VECTOR(stm32_dma2ch3, STM32_IRQ_DMA2CH3) /* Vector 16+58: DMA2 Channel 3 global interrupt */ +VECTOR(stm32_dma2ch45, STM32_IRQ_DMA2CH45) /* Vector 16+59: DMA2 Channel 4 and 5 global interrupt */ +VECTOR(stm32_dma2ch5, STM32_IRQ_DMA2CH5) /* Vector 16+60: DMA2 Channel 5 global interrupt */ + # endif /* CONFIG_ARMV7M_CMNVECTOR */ #elif defined(CONFIG_STM32_CONNECTIVITYLINE) diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index 896bf3662d..900e93a97b 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -715,18 +715,24 @@ the display contents: Here is how I have the OLED connected. But you can change this with the settings in include/board.h and src/stm324fdiscovery-internal.h: - Connector CON10 J1: STM32F4Discovery - - 1 3v3 P2 3V - 3 RESET P2 PB6 (Arbitrary selection) - 5 CS P3 PB7 (Arbitrary selection) - 7 A0 P2 PB8 (Arbitrary selection) - 9 LED+ (N/C) ----- - 2 5V Vcc P2 5V - 4 DI P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1) - 6 SCLK P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1) - 8 LED- (N/C) ------ - 10 GND P2 GND + --------------------------+---------------------------------------------- + Connector CON10 J1: | STM32F4Discovery + --------------+-----------+---------------------------------------------- + CON10 J1: | CON20 J2: | P1/P2: + --------------+-----------+---------------------------------------------- + 1 3v3 | 3,4 3v3 | P2 3V + 3 /RESET | 8 /RESET | P2 PB6 (Arbitrary selection) + 5 /CS | 7 /CS | P3 PB7 (Arbitrary selection) + 7 A0 | 9 A0 | P2 PB8 (Arbitrary selection) + 9 LED+ (N/C) | ----- | ----- + 2 5V Vcc | 1,2 Vcc | P2 5V + 4 DI | 18 D1/SI | P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1 (1)) + 6 SCLK | 19 D0/SCL | P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1 (1)) + 8 LED- (N/C) | ----- | ------ + 10 GND | 20 GND | P2 GND + --------------+-----------+---------------------------------------------- + (1) Required because of on-board MEMS + ------------------------------------------------------------------------- STM32F4Discovery-specific Configuration Options =============================================== diff --git a/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h b/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h index 0539442ca2..73a42d3fdd 100644 --- a/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h +++ b/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h @@ -115,18 +115,24 @@ /* UG-2864AMBAG01 OLED Display: * - * Connector CON10 J1: STM32F4Discovery - * - * 1 3v3 P2 3V - * 3 RESET P2 PB6 (Arbitrary selection) - * 5 CS P3 PB7 (Arbitrary selection) - * 7 A0 P2 PB8 (Arbitrary selection) - * 9 LED+ (N/C) ----- - * 2 5V Vcc P2 5V - * 4 DI P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1) - * 6 SCLK P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1) - * 8 LED- (N/C) ------ - * 10 GND P2 GND + * --------------------------+---------------------------------------------- + * Connector CON10 J1: | STM32F4Discovery + * --------------+-----------+---------------------------------------------- + * CON10 J1: | CON20 J2: | P1/P2: + * --------------+-----------+---------------------------------------------- + * 1 3v3 | 3,4 3v3 | P2 3V + * 3 /RESET | 8 /RESET | P2 PB6 (Arbitrary selection) + * 5 /CS | 7 /CS | P3 PB7 (Arbitrary selection) + * 7 A0 | 9 A0 | P2 PB8 (Arbitrary selection) + * 9 LED+ (N/C) | ----- | ----- + * 2 5V Vcc | 1,2 Vcc | P2 5V + * 4 DI | 18 D1/SI | P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1 (1)) + * 6 SCLK | 19 D0/SCL | P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1 (1)) + * 8 LED- (N/C) | ----- | ------ + * 10 GND | 20 GND | P2 GND + * --------------+-----------+---------------------------------------------- + * (1) Required because of on-board MEMS + * ------------------------------------------------------------------------- */ #ifdef CONFIG_LCD_UG2864AMBAG01 diff --git a/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c b/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c index a012d7384f..eabb771292 100644 --- a/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c +++ b/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c @@ -66,20 +66,27 @@ #endif /* Pin Configuration ********************************************************/ -/* Connector CON10 J1: STM32F4Discovery +/* UG-2864AMBAG01 OLED Display: * - * 1 3v3 P2 3V - * 3 RESET P2 PB6 (Arbitrary selection) - * 5 CS P3 PB7 (Arbitrary selection) - * 7 A0 P2 PB8 (Arbitrary selection) - * 9 LED+ (N/C) ----- - * 2 5V Vcc P2 5V - * 4 DI P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1) - * 6 SCLK P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1) - * 8 LED- (N/C) ------ - * 10 GND P2 GND - * - * Note that the OLED CS and A0 are managed in the up_spi.c file. + * --------------------------+---------------------------------------------- + * Connector CON10 J1: | STM32F4Discovery + * --------------+-----------+---------------------------------------------- + * CON10 J1: | CON20 J2: | P1/P2: + * --------------+-----------+---------------------------------------------- + * 1 3v3 | 3,4 3v3 | P2 3V + * 3 /RESET | 8 /RESET | P2 PB6 (Arbitrary selection) + * 5 /CS | 7 /CS | P3 PB7 (Arbitrary selection)(2) + * 7 A0 | 9 A0 | P2 PB8 (Arbitrary selection)(2) + * 9 LED+ (N/C) | ----- | ----- + * 2 5V Vcc | 1,2 Vcc | P2 5V + * 4 DI | 18 D1/SI | P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1 (1)) + * 6 SCLK | 19 D0/SCL | P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1 (2)) + * 8 LED- (N/C) | ----- | ------ + * 10 GND | 20 GND | P2 GND + * --------------+-----------+---------------------------------------------- + * (1) Required because of on-board MEMS + * (2) Note that the OLED CS and A0 are managed in the up_spi.c file. + * ------------------------------------------------------------------------- */ /* Definitions in stm32f4discovery-internal.h */ From d04ce723f0872cda3ebcc496efd45965a6ec3a70 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 9 Nov 2012 14:54:29 +0000 Subject: [PATCH 093/206] Several patches from Petteri Aimonen (mostly NxWidgets) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5324 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/ChangeLog.txt | 19 ++- NxWidgets/Kconfig | 16 +++ NxWidgets/nxwm/src/capplicationwindow.cxx | 30 ++-- NxWidgets/nxwm/src/chexcalculator.cxx | 2 + NxWidgets/nxwm/src/cstartwindow.cxx | 2 + NxWidgets/nxwm/src/ctaskbar.cxx | 19 ++- NxWidgets/tools/README.txt | 51 +++++++ NxWidgets/tools/bitmap_converter.py | 148 +++++++++++++++++++ NxWidgets/tools/install.sh | 2 + apps/ChangeLog.txt | 3 + apps/NxWidgets/Kconfig | 16 +++ apps/nshlib/Kconfig | 4 + apps/nshlib/README.txt | 29 ++-- apps/nshlib/nsh.h | 6 +- apps/nshlib/nsh_dbgcmds.c | 60 +++++++- apps/nshlib/nsh_parse.c | 6 + nuttx/ChangeLog | 1 + nuttx/Documentation/NuttShell.html | 164 +++++++++++++--------- nuttx/Documentation/README.html | 72 +++++----- nuttx/README.txt | 9 ++ nuttx/arch/arm/src/stm32/Kconfig | 1 - nuttx/arch/arm/src/stm32/chip/stm32_eth.h | 8 -- nuttx/libxx/Makefile | 7 +- nuttx/libxx/libxx_stdthrow.cxx | 74 ++++++++++ 24 files changed, 616 insertions(+), 133 deletions(-) create mode 100755 NxWidgets/tools/README.txt create mode 100755 NxWidgets/tools/bitmap_converter.py create mode 100644 nuttx/libxx/libxx_stdthrow.cxx diff --git a/NxWidgets/ChangeLog.txt b/NxWidgets/ChangeLog.txt index f4aedd8285..113945f2f4 100644 --- a/NxWidgets/ChangeLog.txt +++ b/NxWidgets/ChangeLog.txt @@ -182,4 +182,21 @@ * libnxwidgets/src/cnxserver.cxx: Reduce delay to allow NX server to start. One second was un-necessarily long. Reduced to 50 MS. Reduction suggested by Petteri Aimonen. - +* tools/bitmap_converter.py: This script converts from any image type + supported by Python imaging library to the RLE-encoded format used by + NxWidgets. +* NxWidgets/nxwm/src/capplicationwindow.cxx: If the "desktop" is empty, + users have no need to minimize any windows. If the buttons are small, + it's easy to hit minimize button accidentally when trying to close an + application. Contributed by Petteri Aimonen. +* NxWidgets/nxwm/src/ctaskbar.cxx: Add an option to eliminate the + background image. Contributed by Petteri Aimonen. +* NxWidgets/nxwm/src/chexcalculator.cxx and NxWidgets/nxwm/src/cstartwindow.cxx: + The config settings CONFIG_NXWM_STARTWINDOW_ICON and CONFIG_NXWM_HEXCALCULATOR_ICON + allow changing the icons used for these applications. However, to declare symbols + for these icons user would need to modify NxWidgets header files. + This commit adds a simple forward declaration to the relevant files, based on the + configured icon. If the icon does not exist, linker will give an error about it. + Contributed by Petteri Aimonen. +* NxWidgets/nxwm/src/ctaskbar.cxx: Highlight the current window in the task bar. + Contributed by Petteri Aimonen. diff --git a/NxWidgets/Kconfig b/NxWidgets/Kconfig index 6befd1ace9..59d8856bce 100644 --- a/NxWidgets/Kconfig +++ b/NxWidgets/Kconfig @@ -308,6 +308,14 @@ config NXWM_TASKBAR_WIDTH ---help--- Task bar thickness (either vertical or horizontal). Default: 25 + 2*spacing +config NXWM_DISABLE_MINIMIZE + bool "Disable Minimize Button" + default n + ---help--- + If the "desktop" is empty, users have no need to minimize any windows. If the buttons + are small, it's easy to hit minimize button accidentally when trying to close an + application. + comment "Tool Bar Configuration" config NXWM_TOOLBAR_HEIGHT @@ -319,8 +327,16 @@ config NXWM_TOOLBAR_HEIGHT comment "Background Image" +config NXWM_DISABLE_BACKGROUND_IMAGE + bool "Disable Background Image" + default n if !NXWM_DISABLE_MINIMIZE + default y if NXWM_DISABLE_MINIMIZE + ---help--- + Disable support for the "Desktop" background image. + config NXWM_BACKGROUND_IMAGE string "Background Image" + depends on !NXWM_DISABLE_BACKGROUND_IMAGE ---help--- The name of the image to use in the background window. Default: NXWidgets::g_nuttxBitmap diff --git a/NxWidgets/nxwm/src/capplicationwindow.cxx b/NxWidgets/nxwm/src/capplicationwindow.cxx index 65de1b1a4c..d2e0442986 100644 --- a/NxWidgets/nxwm/src/capplicationwindow.cxx +++ b/NxWidgets/nxwm/src/capplicationwindow.cxx @@ -241,6 +241,7 @@ bool CApplicationWindow::open(void) m_stopImage->addWidgetEventHandler(this); } +#ifndef CONFIG_NXWM_DISABLE_MINIMIZE // Create MINIMIZE application bitmap container m_minimizeBitmap = new NXWidgets::CRlePaletteBitmap(&g_minimizeBitmap); @@ -289,6 +290,7 @@ bool CApplicationWindow::open(void) m_minimizeImage->setBorderless(true); m_minimizeImage->addWidgetEventHandler(this); +#endif // The rest of the toolbar will hold the left-justified application label // Create the default font instance @@ -364,12 +366,16 @@ void CApplicationWindow::redraw(void) m_stopImage->setRaisesEvents(true); } - // Draw the minimize image - - m_minimizeImage->enableDrawing(); - m_minimizeImage->redraw(); - m_minimizeImage->setRaisesEvents(true); + // Draw the minimize image (which may not be present if this is a + // mimimization is disabled) + if (m_minimizeImage) + { + m_minimizeImage->enableDrawing(); + m_minimizeImage->redraw(); + m_minimizeImage->setRaisesEvents(true); + } + // And finally draw the window label m_windowLabel->enableDrawing(); @@ -392,11 +398,15 @@ void CApplicationWindow::hide(void) m_stopImage->setRaisesEvents(false); } - // Disable the minimize image - - m_minimizeImage->disableDrawing(); - m_minimizeImage->setRaisesEvents(false); + // Disable the minimize image(which may not be present if this is a + // mimimization is disabled) + if (m_minimizeImage) + { + m_minimizeImage->disableDrawing(); + m_minimizeImage->setRaisesEvents(false); + } + // Disable the window label m_windowLabel->disableDrawing(); @@ -570,7 +580,7 @@ void CApplicationWindow::handleActionEvent(const NXWidgets::CWidgetEventArgs &e) // Check the minimize image (only if the stop application image is not pressed) - else if (m_minimizeImage->isClicked()) + else if (m_minimizeImage && m_minimizeImage->isClicked()) { // Notify the controlling logic that the application should be miminsed diff --git a/NxWidgets/nxwm/src/chexcalculator.cxx b/NxWidgets/nxwm/src/chexcalculator.cxx index f8f1bb246a..eeb0b1d1da 100644 --- a/NxWidgets/nxwm/src/chexcalculator.cxx +++ b/NxWidgets/nxwm/src/chexcalculator.cxx @@ -191,6 +191,8 @@ namespace NxWM * CHexCalculator Method Implementations ********************************************************************************************/ +extern const struct NXWidgets::SRlePaletteBitmap CONFIG_NXWM_HEXCALCULATOR_ICON; + using namespace NxWM; /** diff --git a/NxWidgets/nxwm/src/cstartwindow.cxx b/NxWidgets/nxwm/src/cstartwindow.cxx index 5c54cba3ac..a99e81d88b 100644 --- a/NxWidgets/nxwm/src/cstartwindow.cxx +++ b/NxWidgets/nxwm/src/cstartwindow.cxx @@ -71,6 +71,8 @@ FAR const char *NxWM::g_startWindowMqName = CONFIG_NXWM_STARTWINDOW_MQNAME; * CStartWindow Method Implementations ********************************************************************************************/ +extern const struct NXWidgets::SRlePaletteBitmap CONFIG_NXWM_STARTWINDOW_ICON; + using namespace NxWM; /** diff --git a/NxWidgets/nxwm/src/ctaskbar.cxx b/NxWidgets/nxwm/src/ctaskbar.cxx index c494fcba33..23d2d23b50 100644 --- a/NxWidgets/nxwm/src/ctaskbar.cxx +++ b/NxWidgets/nxwm/src/ctaskbar.cxx @@ -991,6 +991,7 @@ bool CTaskbar::createBackgroundWindow(void) bool CTaskbar::createBackgroundImage(void) { +#ifndef CONFIG_NXWM_DISABLE_BACKGROUND_IMAGE // Get the size of the display struct nxgl_size_s windowSize; @@ -1054,6 +1055,8 @@ bool CTaskbar::createBackgroundImage(void) m_backImage->setBorderless(true); m_backImage->setRaisesEvents(false); +#endif + return true; } @@ -1128,6 +1131,10 @@ bool CTaskbar::redrawTaskbarWindow(void) image->disableDrawing(); image->setRaisesEvents(false); + // Highlight the icon for the top-most window + + image->highlight(m_slots.at(i).app == m_topApp); + // Get the size of the icon image NXWidgets::CRect rect; @@ -1302,8 +1309,12 @@ bool CTaskbar::redrawBackgroundWindow(void) // Then re-draw the background image on the window - m_backImage->enableDrawing(); - m_backImage->redraw(); + if (m_backImage) + { + m_backImage->enableDrawing(); + m_backImage->redraw(); + } + return true; } @@ -1330,6 +1341,10 @@ bool CTaskbar::redrawApplicationWindow(IApplication *app) raiseTopApplication(); + // Redraw taskbar + + redrawTaskbarWindow(); + // Every application provides a method to obtain its application window IApplicationWindow *appWindow = app->getWindow(); diff --git a/NxWidgets/tools/README.txt b/NxWidgets/tools/README.txt new file mode 100755 index 0000000000..22b2bf2a9e --- /dev/null +++ b/NxWidgets/tools/README.txt @@ -0,0 +1,51 @@ +NxWidgets/tools README File +=========================== + +addobjs.sh +---------- + + $0 will add all object (.o) files in directory to an archive. + + Usage: tools/addobjs.sh [OPTIONS] + + Where: + is the full, absolute path to the library to use + is full path to the directory containing the object files to be added + OPTIONS include: + -p Prefix to use. For example, to use arm-elf-ar, add '-p arm-elf-' + -w Use Windows style paths insted of POSIX paths + -d Enable script debug + -h Show this usage information + +bitmap_converter.py +------------------- + + This script converts from any image type supported by Python imaging library to + the RLE-encoded format used by NxWidgets. + +indent.sh +--------- + + This script uses the Linux 'indent' utility to re-format C source files + to match the coding style that I use. It differs from my coding style in that + + - I normally put the traiing */ of a multi-line comment on a separate line, + - I usually align things vertically (like '='in assignments. + +install.sh +---------- + + Install a unit test in the NuttX source tree" + + USAGE: tools/install.sh + + Where: + is the full, absolute path to the NuttX apps/ directory + is the name of a sub-directory in the UnitTests directory + +zipme.sh +-------- + + Pack up the NxWidgets tarball for release. + + USAGE: tools/zipme.sh diff --git a/NxWidgets/tools/bitmap_converter.py b/NxWidgets/tools/bitmap_converter.py new file mode 100755 index 0000000000..2cb7e8869d --- /dev/null +++ b/NxWidgets/tools/bitmap_converter.py @@ -0,0 +1,148 @@ +#!/usr/bin/env python + +'''This script converts from any image type supported by +Python imaging library to the RLE-encoded format used by +NxWidgets. +''' + +from PIL import Image + +def get_palette(img, maxcolors = 255): + '''Returns a list of colors. If there are too many colors in the image, + the least used are removed. + ''' + img = img.convert("RGB") + colors = img.getcolors(65536) + colors.sort(key = lambda c: -c[0]) + return [c[1] for c in colors[:maxcolors]] + +def write_palette(outfile, palette): + '''Write the palette (normal and hilight) to the output file.''' + + outfile.write('static const NXWidgets::nxwidget_pixel_t palette[BITMAP_PALETTESIZE] =\n'); + outfile.write('{\n') + + for i in range(0, len(palette), 4): + outfile.write(' '); + for r, g, b in palette[i:i+4]: + outfile.write('MKRGB(%3d,%3d,%3d), ' % (r, g, b)) + outfile.write('\n'); + + outfile.write('};\n\n') + + outfile.write('static const NXWidgets::nxwidget_pixel_t hilight_palette[BITMAP_PALETTESIZE] =\n'); + outfile.write('{\n') + + for i in range(0, len(palette), 4): + outfile.write(' '); + for r, g, b in palette[i:i+4]: + r = min(255, r + 50) + g = min(255, g + 50) + b = min(255, b + 50) + outfile.write('MKRGB(%3d,%3d,%3d), ' % (r, g, b)) + outfile.write('\n'); + + outfile.write('};\n\n') + + +def quantize(color, palette): + '''Return the color index to closest match in the palette.''' + try: + return palette.index(color) + except ValueError: + # No exact match, search for the closest + def distance(color2): + return sum([(a - b)**2 for a, b in zip(color, color2)]) + + return palette.index(min(palette, key = distance)); + +def encode_row(img, palette, y): + '''RLE-encode one row of image data.''' + entries = [] + color = None + repeats = 0 + + for x in range(0, img.size[0]): + c = quantize(img.getpixel((x, y)), palette) + if c == color: + repeats += 1 + else: + if color is not None: + entries.append((repeats, color)) + + repeats = 1 + color = c + + if color is not None: + entries.append((repeats, color)) + + return entries + +def write_image(outfile, img, palette): + '''Write the image contents to the output file.''' + + outfile.write('static const NXWidgets::SRlePaletteBitmapEntry bitmap[] =\n'); + outfile.write('{\n'); + + for y in range(0, img.size[1]): + entries = encode_row(img, palette, y) + row = "" + for r, c in entries: + if len(row) > 60: + outfile.write(' ' + row + '\n') + row = "" + + row += '{%3d, %3d}, ' % (r, c) + + row += ' ' * (73 - len(row)) + outfile.write(' ' + row + '/* Row %d */\n' % y) + + outfile.write('};\n\n'); + +def write_descriptor(outfile, name): + '''Write the public descriptor structure for the image.''' + + outfile.write('extern const struct NXWidgets::SRlePaletteBitmap g_%s =\n' % name) + outfile.write('{\n') + outfile.write(' CONFIG_NXWIDGETS_BPP,\n') + outfile.write(' CONFIG_NXWIDGETS_FMT,\n') + outfile.write(' BITMAP_PALETTESIZE,\n') + outfile.write(' BITMAP_WIDTH,\n') + outfile.write(' BITMAP_HEIGHT,\n') + outfile.write(' {palette, hilight_palette},\n') + outfile.write(' bitmap\n') + outfile.write('};\n') + +if __name__ == '__main__': + import sys + import os.path + + if len(sys.argv) != 3: + print "Usage: bitmap_converter.py source.png output.cxx" + sys.exit(1) + + img = Image.open(sys.argv[1]) + outfile = open(sys.argv[2], 'w') + palette = get_palette(img) + + outfile.write( +''' +/* Automatically NuttX bitmap file. */ +/* Generated from %(src)s by bitmap_converter.py. */ + +#include +#include + +#define BITMAP_WIDTH %(width)s +#define BITMAP_HEIGHT %(height)s +#define BITMAP_PALETTESIZE %(palettesize)s + +''' % {'src': sys.argv[1], 'width': img.size[0], 'height': img.size[1], + 'palettesize': len(palette)} + ) + + name = os.path.splitext(os.path.basename(sys.argv[1]))[0] + + write_palette(outfile, palette) + write_image(outfile, img, palette) + write_descriptor(outfile, name) diff --git a/NxWidgets/tools/install.sh b/NxWidgets/tools/install.sh index 6917b4b036..dd212b5a6b 100755 --- a/NxWidgets/tools/install.sh +++ b/NxWidgets/tools/install.sh @@ -39,6 +39,8 @@ function ShowUsage() { + echo "" + echo "Install a unit test in the NuttX source tree" echo "" echo "USAGE: $0 " echo "" diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index d755fcca05..99f0ebc532 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -411,4 +411,7 @@ * apps/examples/ostest/roundrobin.c: Replace large tables with algorithmic prime number generation. This allows the roundrobin test to run on platforms with minimal SRAM (Freddie Chopin). + * apps/nshlib/nsh_dbgcmds.c: Add hexdump command to dump the contents + of a file (or character device) to the console Contributed by Petteri + Aimonen. diff --git a/apps/NxWidgets/Kconfig b/apps/NxWidgets/Kconfig index 6befd1ace9..59d8856bce 100644 --- a/apps/NxWidgets/Kconfig +++ b/apps/NxWidgets/Kconfig @@ -308,6 +308,14 @@ config NXWM_TASKBAR_WIDTH ---help--- Task bar thickness (either vertical or horizontal). Default: 25 + 2*spacing +config NXWM_DISABLE_MINIMIZE + bool "Disable Minimize Button" + default n + ---help--- + If the "desktop" is empty, users have no need to minimize any windows. If the buttons + are small, it's easy to hit minimize button accidentally when trying to close an + application. + comment "Tool Bar Configuration" config NXWM_TOOLBAR_HEIGHT @@ -319,8 +327,16 @@ config NXWM_TOOLBAR_HEIGHT comment "Background Image" +config NXWM_DISABLE_BACKGROUND_IMAGE + bool "Disable Background Image" + default n if !NXWM_DISABLE_MINIMIZE + default y if NXWM_DISABLE_MINIMIZE + ---help--- + Disable support for the "Desktop" background image. + config NXWM_BACKGROUND_IMAGE string "Background Image" + depends on !NXWM_DISABLE_BACKGROUND_IMAGE ---help--- The name of the image to use in the background window. Default: NXWidgets::g_nuttxBitmap diff --git a/apps/nshlib/Kconfig b/apps/nshlib/Kconfig index 7009e6a3d6..17b107b8f5 100644 --- a/apps/nshlib/Kconfig +++ b/apps/nshlib/Kconfig @@ -74,6 +74,10 @@ config NSH_DISABLE_HELP bool "Disable help" default n +config NSH_DISABLE_HEXDUMP + bool "Disable hexdump" + default n + config NSH_DISABLE_IFCONFIG bool "Disable ifconfig" default n diff --git a/apps/nshlib/README.txt b/apps/nshlib/README.txt index 227f01c0a0..59f0538f08 100644 --- a/apps/nshlib/README.txt +++ b/apps/nshlib/README.txt @@ -385,6 +385,10 @@ o help [-v] [] Show full command usage only for this command +o hexdump + + Dump data in hexadecimal format from a file or character device. + o ifconfig [nic_name [ip]] [dr|gw|gateway ] [netmask ] [dns ] [hw ] Show the current configuration of the network, for example: @@ -865,6 +869,7 @@ Command Dependencies on Configuration Settings free -- get CONFIG_NET && CONFIG_NET_UDP && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NET_BUFSIZE >= 558 (see note 1) help -- + hexdump CONFIG_NFILE_DESCRIPTORS > 0 ifconfig CONFIG_NET ifdown CONFIG_NET ifup CONFIG_NET @@ -917,18 +922,18 @@ also allow it to squeeze into very small memory footprints. CONFIG_NSH_DISABLE_CD, CONFIG_NSH_DISABLE_CP, CONFIG_NSH_DISABLE_DD, CONFIG_NSH_DISABLE_DF, CONFIG_NSH_DISABLE_ECHO, CONFIG_NSH_DISABLE_EXEC, CONFIG_NSH_DISABLE_EXIT, CONFIG_NSH_DISABLE_FREE, CONFIG_NSH_DISABLE_GET, - CONFIG_NSH_DISABLE_HELP, CONFIG_NSH_DISABLE_IFCONFIG, CONFIG_NSH_DISABLE_IFUPDOWN, - CONFIG_NSH_DISABLE_KILL, CONFIG_NSH_DISABLE_LOSETUP, CONFIG_NSH_DISABLE_LS, - CONFIG_NSH_DISABLE_MD5 CONFIG_NSH_DISABLE_MB, CONFIG_NSH_DISABLE_MKDIR, - CONFIG_NSH_DISABLE_MKFATFS, CONFIG_NSH_DISABLE_MKFIFO, CONFIG_NSH_DISABLE_MKRD, - CONFIG_NSH_DISABLE_MH, CONFIG_NSH_DISABLE_MOUNT, CONFIG_NSH_DISABLE_MW, - CONFIG_NSH_DISABLE_MV, CONFIG_NSH_DISABLE_NFSMOUNT, CONFIG_NSH_DISABLE_PS, - CONFIG_NSH_DISABLE_PING, CONFIG_NSH_DISABLE_PUT, CONFIG_NSH_DISABLE_PWD, - CONFIG_NSH_DISABLE_RM, CONFIG_NSH_DISABLE_RMDIR, CONFIG_NSH_DISABLE_SET, - CONFIG_NSH_DISABLE_SH, CONFIG_NSH_DISABLE_SLEEP, CONFIG_NSH_DISABLE_TEST, - CONFIG_NSH_DISABLE_UMOUNT, CONFIG_NSH_DISABLE_UNSET, CONFIG_NSH_DISABLE_URLDECODE, - CONFIG_NSH_DISABLE_URLENCODE, CONFIG_NSH_DISABLE_USLEEP, CONFIG_NSH_DISABLE_WGET, - CONFIG_NSH_DISABLE_XD + CONFIG_NSH_DISABLE_HELP, CONFIG_NSH_DISABLE_HEXDUMP, CONFIG_NSH_DISABLE_IFCONFIG, + CONFIG_NSH_DISABLE_IFUPDOWN, CONFIG_NSH_DISABLE_KILL, CONFIG_NSH_DISABLE_LOSETUP, + CONFIG_NSH_DISABLE_LS, CONFIG_NSH_DISABLE_MD5 CONFIG_NSH_DISABLE_MB, + CONFIG_NSH_DISABLE_MKDIR, CONFIG_NSH_DISABLE_MKFATFS, CONFIG_NSH_DISABLE_MKFIFO, + CONFIG_NSH_DISABLE_MKRD, CONFIG_NSH_DISABLE_MH, CONFIG_NSH_DISABLE_MOUNT, + CONFIG_NSH_DISABLE_MW, CONFIG_NSH_DISABLE_MV, CONFIG_NSH_DISABLE_NFSMOUNT, + CONFIG_NSH_DISABLE_PS, CONFIG_NSH_DISABLE_PING, CONFIG_NSH_DISABLE_PUT, + CONFIG_NSH_DISABLE_PWD, CONFIG_NSH_DISABLE_RM, CONFIG_NSH_DISABLE_RMDIR, + CONFIG_NSH_DISABLE_SET, CONFIG_NSH_DISABLE_SH, CONFIG_NSH_DISABLE_SLEEP, + CONFIG_NSH_DISABLE_TEST, CONFIG_NSH_DISABLE_UMOUNT, CONFIG_NSH_DISABLE_UNSET, + CONFIG_NSH_DISABLE_URLDECODE, CONFIG_NSH_DISABLE_URLENCODE, CONFIG_NSH_DISABLE_USLEEP, + CONFIG_NSH_DISABLE_WGET, CONFIG_NSH_DISABLE_XD Verbose help output can be suppressed by defining CONFIG_NSH_HELP_TERSE. In that case, the help command is still available but will be slightly smaller. diff --git a/apps/nshlib/nsh.h b/apps/nshlib/nsh.h index ac75cf2e1d..a046a384fc 100644 --- a/apps/nshlib/nsh.h +++ b/apps/nshlib/nsh.h @@ -47,6 +47,7 @@ #include #include #include +#include #include #include @@ -540,7 +541,7 @@ void nsh_usbtrace(void); #ifndef CONFIG_NSH_DISABLE_XD int cmd_xd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); #endif - + #if !defined(CONFIG_NSH_DISABLESCRIPT) && !defined(CONFIG_NSH_DISABLE_TEST) int cmd_test(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); int cmd_lbracket(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); @@ -562,6 +563,9 @@ void nsh_usbtrace(void); # ifndef CONFIG_NSH_DISABLE_DD int cmd_dd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); # endif +# ifndef CONFIG_NSH_DISABLE_HEXDUMP + int cmd_hexdump(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); +# endif # ifndef CONFIG_NSH_DISABLE_LS int cmd_ls(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); # endif diff --git a/apps/nshlib/nsh_dbgcmds.c b/apps/nshlib/nsh_dbgcmds.c index 384b377f3a..627c56bcda 100644 --- a/apps/nshlib/nsh_dbgcmds.c +++ b/apps/nshlib/nsh_dbgcmds.c @@ -46,6 +46,10 @@ #include #include +#if CONFIG_NFILE_DESCRIPTORS > 0 +# include +#endif + #include "nsh.h" #include "nsh_console.h" @@ -327,7 +331,7 @@ void nsh_dumpbuffer(FAR struct nsh_vtbl_s *vtbl, const char *msg, } /**************************************************************************** - * Name: cmd_xd + * Name: cmd_xd, hex dump of memory ****************************************************************************/ #ifndef CONFIG_NSH_DISABLE_XD @@ -353,3 +357,57 @@ int cmd_xd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) return OK; } #endif + +/**************************************************************************** + * Name: cmd_hexdump, hex dump of files + ****************************************************************************/ + +#if CONFIG_NFILE_DESCRIPTORS > 0 +#ifndef CONFIG_NSH_DISABLE_HEXDUMP +int cmd_hexdump(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + uint8_t buffer[IOBUFFERSIZE]; + int fd; + int ret = OK; + char msg[32]; + + /* Open the file for reading */ + + fd = open(argv[1], O_RDONLY); + if (fd < 0) + { + nsh_output(vtbl, g_fmtcmdfailed, "hexdump", "open", NSH_ERRNO); + return ERROR; + } + + int position = 0; + for (;;) + { + int nbytesread = read(fd, buffer, IOBUFFERSIZE); + + /* Check for read errors */ + + if (nbytesread < 0) + { + int errval = errno; + nsh_output(vtbl, g_fmtcmdfailed, "hexdump", "read", NSH_ERRNO_OF(errval)); + ret = ERROR; + break; + } + else if (nbytesread > 0) + { + snprintf(msg, sizeof(msg), "%s at %08x", argv[1], position); + nsh_dumpbuffer(vtbl, msg, buffer, nbytesread); + position += nbytesread; + } + else + { + break; // EOF + } + } + + (void)close(fd); + return ret; +} +#endif +#endif diff --git a/apps/nshlib/nsh_parse.c b/apps/nshlib/nsh_parse.c index bf2b8a4a47..abdf5c321e 100644 --- a/apps/nshlib/nsh_parse.c +++ b/apps/nshlib/nsh_parse.c @@ -226,6 +226,12 @@ static const struct cmdmap_s g_cmdmap[] = { "help", cmd_help, 1, 3, "[-v] []" }, # endif #endif + +#if CONFIG_NFILE_DESCRIPTORS > 0 +#ifndef CONFIG_NSH_DISABLE_HEXDUMP + { "hexdump", cmd_hexdump, 2, 2, "" }, +#endif +#endif #ifdef CONFIG_NET # ifndef CONFIG_NSH_DISABLE_IFCONFIG diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 9b27102330..39a4dff565 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3584,3 +3584,4 @@ tool. * configs/stm32f4discovery/src/up_ug2864ambag01.c: Board-specific initialization for UG-2864AMBAG01 OLED connecte to STM32F4Disovery. + * libxx/libxx_stdthrow.cxx: Exception stubs from Petteri Aimonen. diff --git a/nuttx/Documentation/NuttShell.html b/nuttx/Documentation/NuttShell.html index 31546a100c..1b14f96f61 100644 --- a/nuttx/Documentation/NuttShell.html +++ b/nuttx/Documentation/NuttShell.html @@ -8,7 +8,7 @@

    -

  • Add-on uClibc++ module provides Standard C++ Library(LGPL).
  • +
  • Add-on uClibc++ module provides Standard C++ Library (LGPL).
  • NuttShell (NSH)

    -

    Last Updated: November 4, 2012

    +

    Last Updated: November 9, 2012

    @@ -173,187 +173,193 @@
    - 2.16 Manage Network Configuration (ifconfig) + 2.16 Hexadecimal Dump of File or Device (hexdump)
    - 2.17 Take a network down (ifdown) + 2.17 Manage Network Configuration (ifconfig)
    - 2.18 Bring a network up (ifup) + 2.18 Take a network down (ifdown)
    - 2.19 Send a signal to a task (kill) + 2.19 Bring a network up (ifup)
    - 2.20 Setup/teardown the Loop Device (losetup) + 2.20 Send a signal to a task (kill)
    - 2.21 List Directory Contents (ls) + 2.21 Setup/teardown the Loop Device (losetup)
    - 2.22 Calculate MD5 (md5) + 2.22 List Directory Contents (ls)
    - 2.23 Access Memory (mb, mh, and mw) + 2.23 Calculate MD5 (md5)
    - 2.24 Show Current Tasks and Threads (ps) + 2.24 Access Memory (mb, mh, and mw)
    - 2.25 Create a Directory (mkdir) + 2.25 Show Current Tasks and Threads (ps)
    - 2.26 Create a FAT Filesystem (mkfatfs) + 2.26 Create a Directory (mkdir)
    - 2.27 Create a FIFO (mkfifo) + 2.27 Create a FAT Filesystem (mkfatfs)
    - 2.28 Create a RAMDISK (mkrd) + 2.28 Create a FIFO (mkfifo)
    - 2.29 Mount a File System (mount) + 2.29 Create a RAMDISK (mkrd)
    - 2.30 Rename a File (mv) + 2.30 Mount a File System (mount)
    - 2.31 Mount an NFS file system (nfsmount) + 2.31 Rename a File (mv)
    - 2.32 Check Network Peer (ping) + 2.32 Mount an NFS file system (nfsmount)
    - 2.33 Send File Via TFTP (put) + 2.33 Check Network Peer (ping)
    - 2.34 Show Current Working Directory (pwd) + 2.34 Send File Via TFTP (put)
    - 2.35 Remove a File (rm) + 2.35 Show Current Working Directory (pwd)
    - 2.36 Remove a Directory (rmdir) + 2.36 Remove a File (rm)
    - 2.37 Set an Environment Variable (set) + 2.37 Remove a Directory (rmdir)
    - 2.38 Execute an NSH Script (sh) + 2.38 Set an Environment Variable (set)
    - 2.39 Wait for Seconds (sleep) + 2.39 Execute an NSH Script (sh)
    - 2.40 Unmount a File System (umount) + 2.40 Wait for Seconds (sleep)
    - 2.41 Unset an Environment Variable (unset) + 2.41 Unmount a File System (umount)
    - 2.42 URL Decode (urldecode) + 2.42 Unset an Environment Variable (unset)
    - 2.43 URL Encode (urlencode) + 2.43 URL Decode (urldecode)
    - 2.44 Wait for Microseconds (usleep) + 2.44 URL Encode (urlencode)
    - 2.45 Get File Via HTTP (wget) + 2.45 Wait for Microseconds (usleep)
    - 2.46 Hexadecimal Dump (xd) + 2.46 Get File Via HTTP (wget) + + + +
    + + 2.47 Hexadecimal Dump of Memory (xd) @@ -1182,7 +1188,31 @@ help [-v] [<cmd>] + +
    -

    2.16 Manage Network Configuration (ifconfig)

    +

    2.16 Hexadecimal Dump of File or Device (hexdump)

    +
    + +

    Command Syntax:

    +
      +hexdump <file or device>
      +
    +

    + Synopsis. + Dump data in hexadecimal format from a file or character device. +

    + + +
    + + + + + + + +
    +

    2.17 Manage Network Configuration (ifconfig)

    @@ -1236,7 +1266,7 @@ ifconfig nic_name ip_address
    -

    2.17 Take a network down (ifdown)

    +

    2.18 Take a network down (ifdown)

    @@ -1259,7 +1289,7 @@ ifdown eth0
    -

    2.18 Bring a network up (ifup)

    +

    2.19 Bring a network up (ifup)

    @@ -1282,7 +1312,7 @@ ifup eth0
    -

    2.19 Send a signal to a task (kill)

    +

    2.20 Send a signal to a task (kill)

    @@ -1323,7 +1353,7 @@ nsh>
    -

    2.20 Setup/teardown the Loop Device (losetup)

    +

    2.21 Setup/teardown the Loop Device (losetup)

    @@ -1376,7 +1406,7 @@ losetup d <dev-path>
    -

    2.21 List Directory Contents (ls)

    +

    2.22 List Directory Contents (ls)

    @@ -1413,7 +1443,7 @@ ls [-lRs] <dir-path>
    -

    2.22 Calculate MD5 (md5)

    +

    2.23 Calculate MD5 (md5)

    @@ -1430,7 +1460,7 @@ md5 [-f] <string or filepath>
    -

    2.23 Access Memory (mb, mh, and mw)

    +

    2.24 Access Memory (mb, mh, and mw)

    @@ -1484,7 +1514,7 @@ nsh>
    -

    2.24 Show Current Tasks and Threads (ps)

    +

    2.25 Show Current Tasks and Threads (ps)

    @@ -1510,7 +1540,7 @@ nsh>
    -

    2.25 Create a Directory (mkdir)

    +

    2.26 Create a Directory (mkdir)

    @@ -1545,7 +1575,7 @@ nsh>
    -

    2.26 Create a FAT Filesystem (mkfatfs)

    +

    2.27 Create a FAT Filesystem (mkfatfs)

    @@ -1565,7 +1595,7 @@ mkfatfs <path>
    -

    2.27 Create a FIFO (mkfifo)

    +

    2.28 Create a FIFO (mkfifo)

    @@ -1603,7 +1633,7 @@ nsh>
    -

    2.28 Create a RAMDISK (mkrd)

    +

    2.29 Create a RAMDISK (mkrd)

    @@ -1654,7 +1684,7 @@ nsh>
    -

    2.29 Mount a File System (mount)

    +

    2.30 Mount a File System (mount)

    @@ -1733,7 +1763,7 @@ nsh> mount
    -

    2.30 Rename a File (mv)

    +

    2.31 Rename a File (mv)

    @@ -1751,7 +1781,7 @@ mv <old-path> <new-path>
    -

    2.31 Mount an NFS file system (nfsmount)

    +

    2.32 Mount an NFS file system (nfsmount)

    @@ -1770,7 +1800,7 @@ nfsmount <server-address> <mount-point> <remote-path>
    -

    2.32 Check Network Peer (ping)

    +

    2.33 Check Network Peer (ping)

    @@ -1803,7 +1833,7 @@ nsh>
    -

    2.33 Send File Via TFTP (put)

    +

    2.34 Send File Via TFTP (put)

    @@ -1838,7 +1868,7 @@ put [-b|-n] [-f <remote-path>] -h <ip-address> <local-path>
    -

    2.34 Show Current Working Directory (pwd)

    +

    2.35 Show Current Working Directory (pwd)

    @@ -1868,7 +1898,7 @@ nsh>
    -

    2.35 Remove a File (rm)

    +

    2.36 Remove a File (rm)

    @@ -1902,7 +1932,7 @@ nsh>
    -

    2.36 Remove a Directory (rmdir)

    +

    2.37 Remove a Directory (rmdir)

    @@ -1937,7 +1967,7 @@ nsh>
    -

    2.37 Set an Environment Variable (set)

    +

    2.38 Set an Environment Variable (set)

    @@ -1963,7 +1993,7 @@ nsh>
    -

    2.38 Execute an NSH Script (sh)

    +

    2.39 Execute an NSH Script (sh)

    @@ -1981,7 +2011,7 @@ sh <script-path>
    -

    2.39 Wait for Seconds (sleep)

    +

    2.40 Wait for Seconds (sleep)

    @@ -1998,7 +2028,7 @@ sleep <sec>
    -

    2.40 Unmount a File System (umount)

    +

    2.41 Unmount a File System (umount)

    @@ -2028,7 +2058,7 @@ nsh>
    -

    2.41 Unset an Environment Variable (unset)

    +

    2.42 Unset an Environment Variable (unset)

    @@ -2054,7 +2084,7 @@ nsh>
    -

    2.42 URL Decode (urldecode)

    +

    2.43 URL Decode (urldecode)

    @@ -2071,7 +2101,7 @@ urldecode [-f] <string or filepath>
    -

    2.43 URL Encode (urlencode)

    +

    2.44 URL Encode (urlencode)

    @@ -2088,7 +2118,7 @@ urlencode [-f] <string or filepath>
    -

    2.44 Wait for Microseconds (usleep)

    +

    2.45 Wait for Microseconds (usleep)

    @@ -2105,7 +2135,7 @@ usleep <usec>
    - 2.45 Get File Via HTTP (wget) + 2.46 Get File Via HTTP (wget)
    @@ -2132,7 +2162,7 @@ wget [-o <local-path>] <url>
    -

    2.46 Hexadecimal dump (xd)

    +

    2.47 Hexadecimal Dump of Memory (xd)

    @@ -2271,6 +2301,11 @@ nsh>
    CONFIG_NSH_DISABLE_HELP + + hexdump + CONFIG_NFILE_DESCRIPTORS > 0 + CONFIG_NSH_DISABLE_HEXDUMP + ifconfig CONFIG_NET @@ -3795,14 +3830,15 @@ mount -t vfat /dev/ram1 /tmp
  • exec
  • exec_namedapp()
  • exit
  • +
  • free
  • -
  • free
  • g_cmdmap
  • genromfs
  • get
  • Greeting
  • help
  • +
  • hexdump
  • if-then[-else]-fi
  • ifconfig
  • ifdown
  • diff --git a/nuttx/Documentation/README.html b/nuttx/Documentation/README.html index 7c82c3f157..61d5c43af1 100644 --- a/nuttx/Documentation/README.html +++ b/nuttx/Documentation/README.html @@ -246,38 +246,46 @@ | | `- README.txt | `- tools/ | `- README.txt - `- apps/ - |- README.txt - |- examples/ - | |- json/README.txt - | |- pashello/README.txt - | `- README.txt - |- graphics/ - | `- "tiff/README.txt - |- interpreters/ - | |- ficl/README.txt - | `- README.txt - |- modbus/ - | `- README.txt - |- netutils/ - | | |- discover/README.txt - | | |- ftpc/README.txt - | | |- json/README.txt - | | |- telnetd/README.txt - | `- README.txt - |- nshlib/ - | `- README.txt - |- NxWidgets/ - | `- 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 + |- apps/ + | |- README.txt + | |- examples/ + | | |- json/README.txt + | | |- pashello/README.txt + | | `- README.txt + | |- graphics/ + | | `- "tiff/README.txt + | |- interpreters/ + | | |- ficl/README.txt + | | `- README.txt + | |- modbus/ + | | `- README.txt + | |- netutils/ + | | | |- discover/README.txt + | | | |- ftpc/README.txt + | | | |- json/README.txt + | | | |- telnetd/README.txt + | | `- README.txt + | |- nshlib/ + | | `- README.txt + | |- NxWidgets/ + | | `- 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 + `- NxWidgets + |- Doxygen + | `- README.txt + |- tools + | `- README.txt + |- UnitTests + | `- README.txt + `- README.txt diff --git a/nuttx/README.txt b/nuttx/README.txt index ee7f62588d..85bb7f3814 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -894,3 +894,12 @@ apps | `- sysinfo | `- README.txt `- README.txt + + NxWidgets + |- Doxygen + | `- README.txt + |- tools + | `- README.txt + |- UnitTests + | `- README.txt + `- README.txt diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 047359ea07..a0e3fab0c6 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -180,7 +180,6 @@ config STM32_STM32F10XX config STM32_VALUELINE bool - select ARMV7M_CMNVECTOR config STM32_HIGHDENSITY bool diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_eth.h b/nuttx/arch/arm/src/stm32/chip/stm32_eth.h index a4a109d016..92a229cccd 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32_eth.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32_eth.h @@ -835,14 +835,6 @@ struct eth_rxdesc_s * Public Functions ****************************************************************************************************/ -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - #endif /* __ASSEMBLY__ */ #endif /* STM32_NETHERNET > 0 */ #endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32_ETH_H */ diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile index a749269b09..584af4e962 100644 --- a/nuttx/libxx/Makefile +++ b/nuttx/libxx/Makefile @@ -46,7 +46,12 @@ CXXSRCS = libxx_cxapurevirtual.cxx libxx_eabi_atexit.cxx libxx_cxa_atexit.cxx # uClibx++ replaces them ifneq ($(CONFIG_UCLIBCXX),y) -CXXSRCS += libxx_delete.cxx libxx_deletea.cxx libxx_new.cxx libxx_newa.cxx +CXXSRCS += libxx_delete.cxx libxx_deletea.cxx libxx_new.cxx libxx_newa.cxx +CXXSRCS += libxx_stdthrow.cxx +else +ifneq ($(UCLIBCXX_EXCEPTION),y) +CXXSRCS += libxx_stdthrow.cxx +endif endif # Paths diff --git a/nuttx/libxx/libxx_stdthrow.cxx b/nuttx/libxx/libxx_stdthrow.cxx new file mode 100644 index 0000000000..588fae2642 --- /dev/null +++ b/nuttx/libxx/libxx_stdthrow.cxx @@ -0,0 +1,74 @@ +//*************************************************************************** +// libxx/libxx_newa.cxx +// +// Copyright (C) 2012 Gregory Nutt. All rights reserved. +// Author: Petteri Aimonen ; +// +// 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 + +//*************************************************************************** +// Definitions +//*************************************************************************** + +//*************************************************************************** +// Private Data +//*************************************************************************** + +//*************************************************************************** +// Public Functions +//*************************************************************************** + +namespace std +{ + void __throw_out_of_range(const char*) + { + dbg("C++: Vector .at() with argument out of range\n"); + abort(); + } + + void __throw_length_error(const char*) + { + dbg("C++: Vector resize to excessive length\n"); + abort(); + } + + void __throw_bad_alloc() + { + dbg("C++: Bad allocation\n"); + abort(); + } +} From b5167ec3a4f1096bc1ef7874541277fca4e01b72 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 9 Nov 2012 17:37:27 +0000 Subject: [PATCH 094/206] UG-2864AMBAG01 driver is basically functional git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5325 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 6 +++ nuttx/Kconfig | 38 +++++++++++++++++++ nuttx/configs/stm32f4discovery/README.txt | 16 ++++++-- .../src/stm32f4discovery-internal.h | 2 +- .../stm32f4discovery/src/up_ug2864ambag01.c | 2 +- nuttx/drivers/lcd/ug-2864ambag01.c | 1 - 6 files changed, 58 insertions(+), 7 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 39a4dff565..247704b7a0 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3585,3 +3585,9 @@ * configs/stm32f4discovery/src/up_ug2864ambag01.c: Board-specific initialization for UG-2864AMBAG01 OLED connecte to STM32F4Disovery. * libxx/libxx_stdthrow.cxx: Exception stubs from Petteri Aimonen. + * configs/stm32f4discovery/src/up_ug2864ambag01.c: Driver has been + verified on the STM32F4Discovery platform. Some tuning of the + configuration could improve the presentation. Lower resolution displays + are also more subject to the "fat, flat line bug" that I need to fix + someday. See http://www.nuttx.org/doku.php?id=wiki:graphics:nxgraphics + for a description of the fat, flat line bug. diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 2d5b9e5851..b647a49f81 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -20,7 +20,45 @@ menu "Build Setup" config EXPERIMENTAL bool "Prompt for development and/or incomplete code/drivers" +choice + prompt "Build Host Platform" + default HOST_LINUX + +config HOST_LINUX + bool "Linux" + +config HOST_OSX + bool "OSX" + +config HOST_WINDOWS + bool "Windows" + +config HOST_OTHER + bool "Other" + +endchoice + +choice + prompt "Windows Build Environment" + default WINDOWS_CYGWIN + depends on HOST_WINDOWS + +config WINDOWS_NATIVE + bool "Windows Native" + +config WINDOWS_CYGWIN + bool "Cygwin" + +config WINDOWS_MSYS + bool "MSYS" + +config WINDOWS_OTHER + bool "Other" + +endchoice + menu "Build Configuration" + config APPS_DIR string "Application directory" default "../apps" diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index 900e93a97b..216ce85cc6 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -308,8 +308,8 @@ The STM32F4Discovery has no real on-board PWM devices, but the board can be configured to output a pulse train using TIM4 CH2 on PD3. This pin is available next to the audio jack. -UART -==== +UARTs +===== UART/USART PINS --------------- @@ -713,7 +713,9 @@ write only so the driver keeps a 128*64/8 = 1KB framebuffer to remember the display contents: Here is how I have the OLED connected. But you can change this with the -settings in include/board.h and src/stm324fdiscovery-internal.h: +settings in include/board.h and src/stm324fdiscovery-internal.h. Connector +pinout for the UG-2864AMBAG01 is specific to the theO.net display board +that I am using: --------------------------+---------------------------------------------- Connector CON10 J1: | STM32F4Discovery @@ -722,7 +724,7 @@ settings in include/board.h and src/stm324fdiscovery-internal.h: --------------+-----------+---------------------------------------------- 1 3v3 | 3,4 3v3 | P2 3V 3 /RESET | 8 /RESET | P2 PB6 (Arbitrary selection) - 5 /CS | 7 /CS | P3 PB7 (Arbitrary selection) + 5 /CS | 7 /CS | P2 PB7 (Arbitrary selection) 7 A0 | 9 A0 | P2 PB8 (Arbitrary selection) 9 LED+ (N/C) | ----- | ----- 2 5V Vcc | 1,2 Vcc | P2 5V @@ -1387,6 +1389,12 @@ Where is one of the following: +CONFIG_EXAMPLES_NXLINES_BPP=1 +CONFIG_EXAMPLES_NXLINES_EXTERNINIT=y + There are some issues with with the presentation... some tuning of the + configuration could fix that. Lower resolution displays are also more + subject to the "fat, flat line bug" that I need to fix someday. See + http://www.nuttx.org/doku.php?id=wiki:graphics:nxgraphics for a description + of the fat, flat line bug. + pm: -- This is a configuration that is used to test STM32 power management, i.e., diff --git a/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h b/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h index 73a42d3fdd..00f17b58e9 100644 --- a/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h +++ b/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h @@ -122,7 +122,7 @@ * --------------+-----------+---------------------------------------------- * 1 3v3 | 3,4 3v3 | P2 3V * 3 /RESET | 8 /RESET | P2 PB6 (Arbitrary selection) - * 5 /CS | 7 /CS | P3 PB7 (Arbitrary selection) + * 5 /CS | 7 /CS | P2 PB7 (Arbitrary selection) * 7 A0 | 9 A0 | P2 PB8 (Arbitrary selection) * 9 LED+ (N/C) | ----- | ----- * 2 5V Vcc | 1,2 Vcc | P2 5V diff --git a/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c b/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c index eabb771292..2f21331168 100644 --- a/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c +++ b/nuttx/configs/stm32f4discovery/src/up_ug2864ambag01.c @@ -75,7 +75,7 @@ * --------------+-----------+---------------------------------------------- * 1 3v3 | 3,4 3v3 | P2 3V * 3 /RESET | 8 /RESET | P2 PB6 (Arbitrary selection) - * 5 /CS | 7 /CS | P3 PB7 (Arbitrary selection)(2) + * 5 /CS | 7 /CS | P2 PB7 (Arbitrary selection)(2) * 7 A0 | 9 A0 | P2 PB8 (Arbitrary selection)(2) * 9 LED+ (N/C) | ----- | ----- * 2 5V Vcc | 1,2 Vcc | P2 5V diff --git a/nuttx/drivers/lcd/ug-2864ambag01.c b/nuttx/drivers/lcd/ug-2864ambag01.c index 3b418bf059..aa50abaedc 100644 --- a/nuttx/drivers/lcd/ug-2864ambag01.c +++ b/nuttx/drivers/lcd/ug-2864ambag01.c @@ -338,7 +338,6 @@ static int ug2864ambag01_setcontrast(struct lcd_dev_s *dev, unsigned int contras * Private Data **************************************************************************************/ - /* 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 From 07c9ee788cd985e015f4b9665f1ef35e74fd3b57 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 9 Nov 2012 22:37:52 +0000 Subject: [PATCH 095/206] Misc changes to accept setenv.bat; Add UG-2864AMBAG01 reverse landscape support git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5326 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Kconfig | 20 ++- nuttx/Makefile | 256 +++++++++++++++-------------- nuttx/drivers/lcd/ug-2864ambag01.c | 25 +++ nuttx/tools/configure.sh | 66 +++++--- 4 files changed, 218 insertions(+), 149 deletions(-) diff --git a/nuttx/Kconfig b/nuttx/Kconfig index b647a49f81..90fe74f257 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -53,10 +53,28 @@ config WINDOWS_MSYS bool "MSYS" config WINDOWS_OTHER - bool "Other" + bool "Other POSIX-like environment" endchoice +config WINDOWS_MKLINK + bool "Use mklink" + default y + depends on HOST_WINDOWS + ---help--- + Use the mklink command to set up symbolic links when NuttX is + configured. Otherwise, configuration directories will be copied to + establish the configuration. + + If directories are copied, then some confusion can result ("Which + version of the file did I modify?"). In that case, it is recommended + that you re-build using 'make clean_context all'. That will cause the + configured directories to be recopied on each build. + + NOTE: This option also (1) that you have administrator privileges, (2) + that you are using Windows 2000 or better, and (3) that you are using + the NTFS file system. Select 'n' is that is not the case. + menu "Build Configuration" config APPS_DIR diff --git a/nuttx/Makefile b/nuttx/Makefile index 0813098c6a..8235854fd1 100644 --- a/nuttx/Makefile +++ b/nuttx/Makefile @@ -33,7 +33,7 @@ # ############################################################################ -TOPDIR := ${shell pwd | sed -e 's/ /\\ /g'} +TOPDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include ${TOPDIR}/.config -include ${TOPDIR}/tools/Config.mk -include ${TOPDIR}/Make.defs @@ -49,21 +49,21 @@ endif # Default tools ifeq ($(DIRLINK),) -DIRLINK = $(TOPDIR)/tools/link.sh -DIRUNLINK = $(TOPDIR)/tools/unlink.sh +DIRLINK = $(TOPDIR)/tools/link.sh +DIRUNLINK = $(TOPDIR)/tools/unlink.sh endif # This define is passed as EXTRADEFINES for kernel-mode builds. It is also passed # during PASS1 (but not PASS2) context and depend targets. -KDEFINE = ${shell $(TOPDIR)/tools/define.sh $(CC) __KERNEL__} +KDEFINE = ${shell $(TOPDIR)/tools/define.sh $(CC) __KERNEL__} # Process architecture and board-specific directories -ARCH_DIR = arch/$(CONFIG_ARCH) -ARCH_SRC = $(ARCH_DIR)/src -ARCH_INC = $(ARCH_DIR)/include -BOARD_DIR = configs/$(CONFIG_ARCH_BOARD) +ARCH_DIR = arch/$(CONFIG_ARCH) +ARCH_SRC = $(ARCH_DIR)/src +ARCH_INC = $(ARCH_DIR)/include +BOARD_DIR = configs/$(CONFIG_ARCH_BOARD) # Add-on directories. These may or may not be in place in the # NuttX source tree (they must be specifically installed) @@ -74,22 +74,22 @@ BOARD_DIR = configs/$(CONFIG_ARCH_BOARD) # a Makefile is found at the path provided by CONFIG_APPS_DIR ifeq ($(CONFIG_APPS_DIR),) -CONFIG_APPS_DIR = ../apps +CONFIG_APPS_DIR = ../apps endif -APPDIR := ${shell if [ -r $(CONFIG_APPS_DIR)/Makefile ]; then echo "$(CONFIG_APPS_DIR)"; fi} +APPDIR := ${shell if [ -r $(CONFIG_APPS_DIR)/Makefile ]; then echo "$(CONFIG_APPS_DIR)"; fi} # All add-on directories. # # NUTTX_ADDONS is the list of directories built into the NuttX kernel. # USER_ADDONS is the list of directories that will be built into the user application -NUTTX_ADDONS := $(NX_DIR) -USER_ADDONS := +NUTTX_ADDONS := $(NX_DIR) +USER_ADDONS := ifeq ($(CONFIG_NUTTX_KERNEL),y) -USER_ADDONS += $(APPDIR) +USER_ADDONS += $(APPDIR) else -NUTTX_ADDONS += $(APPDIR) +NUTTX_ADDONS += $(APPDIR) endif # Lists of build directories. @@ -106,37 +106,37 @@ endif # be cleaned to prevent garbarge from collecting in them when changing # configurations. -NONFSDIRS = sched $(ARCH_SRC) $(NUTTX_ADDONS) -FSDIRS = fs drivers binfmt -CONTEXTDIRS = $(APPDIR) -USERDIRS = +NONFSDIRS = sched $(ARCH_SRC) $(NUTTX_ADDONS) +FSDIRS = fs drivers binfmt +CONTEXTDIRS = $(APPDIR) +USERDIRS = ifeq ($(CONFIG_NUTTX_KERNEL),y) -NONFSDIRS += syscall -CONTEXTDIRS += syscall -USERDIRS += syscall lib mm $(USER_ADDONS) +NONFSDIRS += syscall +CONTEXTDIRS += syscall +USERDIRS += syscall lib mm $(USER_ADDONS) ifeq ($(CONFIG_HAVE_CXX),y) -USERDIRS += libxx +USERDIRS += libxx endif else -NONFSDIRS += lib mm -OTHERDIRS += syscall $(USER_ADDONS) +NONFSDIRS += lib mm +OTHERDIRS += syscall $(USER_ADDONS) ifeq ($(CONFIG_HAVE_CXX),y) -NONFSDIRS += libxx +NONFSDIRS += libxx else -OTHERDIRS += libxx +OTHERDIRS += libxx endif endif ifeq ($(CONFIG_NX),y) -NONFSDIRS += graphics -CONTEXTDIRS += graphics +NONFSDIRS += graphics +CONTEXTDIRS += graphics else -OTHERDIRS += graphics +OTHERDIRS += graphics endif # CLEANDIRS are the directories that will clean in. These are @@ -147,29 +147,29 @@ endif # USERDEPDIRS. If NuttX and applications are built separately (CONFIG_NUTTX_KERNEL), # then this holds only the directories containing user files. -CLEANDIRS = $(NONFSDIRS) $(FSDIRS) $(USERDIRS) $(OTHERDIRS) -KERNDEPDIRS = $(NONFSDIRS) -USERDEPDIRS = $(USERDIRS) +CLEANDIRS = $(NONFSDIRS) $(FSDIRS) $(USERDIRS) $(OTHERDIRS) +KERNDEPDIRS = $(NONFSDIRS) +USERDEPDIRS = $(USERDIRS) # Add file system directories to KERNDEPDIRS (they are already in CLEANDIRS) ifeq ($(CONFIG_NFILE_DESCRIPTORS),0) ifeq ($(CONFIG_NET),y) ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0) -KERNDEPDIRS += fs +KERNDEPDIRS += fs endif -KERNDEPDIRS += drivers +KERNDEPDIRS += drivers endif else -KERNDEPDIRS += $(FSDIRS) +KERNDEPDIRS += $(FSDIRS) endif # Add networking directories to KERNDEPDIRS and CLEANDIRS ifeq ($(CONFIG_NET),y) -KERNDEPDIRS += net +KERNDEPDIRS += net endif -CLEANDIRS += net +CLEANDIRS += net # # Extra objects used in the final link. @@ -179,7 +179,7 @@ CLEANDIRS += net # be created). If the pass1 obect is an archive, it could go anywhere. ifeq ($(CONFIG_BUILD_2PASS),y) -EXTRA_OBJS += $(CONFIG_PASS1_OBJECT) +EXTRA_OBJS += $(CONFIG_PASS1_OBJECT) endif # NUTTXLIBS is the list of NuttX libraries that is passed to the @@ -189,18 +189,18 @@ endif # USERLIBS is the list of libraries used to build the final user-space # application -NUTTXLIBS = sched/libsched$(LIBEXT) $(ARCH_SRC)/libarch$(LIBEXT) -USERLIBS = +NUTTXLIBS = sched/libsched$(LIBEXT) $(ARCH_SRC)/libarch$(LIBEXT) +USERLIBS = # Add libraries for syscall support. The C library will be needed by # both the kernel- and user-space builds. For now, the memory manager (mm) # is placed in user space (only). ifeq ($(CONFIG_NUTTX_KERNEL),y) -NUTTXLIBS += syscall/libstubs$(LIBEXT) lib/libklib$(LIBEXT) -USERLIBS += syscall/libproxies$(LIBEXT) lib/libulib$(LIBEXT) mm/libmm$(LIBEXT) +NUTTXLIBS += syscall/libstubs$(LIBEXT) lib/libklib$(LIBEXT) +USERLIBS += syscall/libproxies$(LIBEXT) lib/libulib$(LIBEXT) mm/libmm$(LIBEXT) else -NUTTXLIBS += mm/libmm$(LIBEXT) lib/liblib$(LIBEXT) +NUTTXLIBS += mm/libmm$(LIBEXT) lib/liblib$(LIBEXT) endif # Add libraries for C++ support. CXX, CXXFLAGS, and COMPILEXX must @@ -208,9 +208,9 @@ endif ifeq ($(CONFIG_HAVE_CXX),y) ifeq ($(CONFIG_NUTTX_KERNEL),y) -USERLIBS += libxx/liblibxx$(LIBEXT) +USERLIBS += libxx/liblibxx$(LIBEXT) else -NUTTXLIBS += libxx/liblibxx$(LIBEXT) +NUTTXLIBS += libxx/liblibxx$(LIBEXT) endif endif @@ -218,44 +218,44 @@ endif ifneq ($(APPDIR),) ifeq ($(CONFIG_NUTTX_KERNEL),y) -USERLIBS += $(APPDIR)/libapps$(LIBEXT) +USERLIBS += $(APPDIR)/libapps$(LIBEXT) else -NUTTXLIBS += $(APPDIR)/libapps$(LIBEXT) +NUTTXLIBS += $(APPDIR)/libapps$(LIBEXT) endif endif # Add libraries for network support ifeq ($(CONFIG_NET),y) -NUTTXLIBS += net/libnet$(LIBEXT) +NUTTXLIBS += net/libnet$(LIBEXT) endif # Add libraries for file system support ifeq ($(CONFIG_NFILE_DESCRIPTORS),0) ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0) -NUTTXLIBS += fs/libfs$(LIBEXT) +NUTTXLIBS += fs/libfs$(LIBEXT) endif ifeq ($(CONFIG_NET),y) -NUTTXLIBS += drivers/libdrivers$(LIBEXT) +NUTTXLIBS += drivers/libdrivers$(LIBEXT) endif else -NUTTXLIBS += fs/libfs$(LIBEXT) drivers/libdrivers$(LIBEXT) binfmt/libbinfmt$(LIBEXT) +NUTTXLIBS += fs/libfs$(LIBEXT) drivers/libdrivers$(LIBEXT) binfmt/libbinfmt$(LIBEXT) endif # Add libraries for the NX graphics sub-system ifneq ($(NX_DIR),) -NUTTXLIBS += $(NX_DIR)/libnx$(LIBEXT) +NUTTXLIBS += $(NX_DIR)/libnx$(LIBEXT) endif ifeq ($(CONFIG_NX),y) -NUTTXLIBS += graphics/libgraphics$(LIBEXT) +NUTTXLIBS += graphics/libgraphics$(LIBEXT) endif # This is the name of the final target (relative to the top level directorty) -BIN = nuttx$(EXEEXT) +BIN = nuttx$(EXEEXT) all: $(BIN) .PHONY: context clean_context check_context export subdir_clean clean subdir_distclean distclean apps_clean apps_distclean @@ -286,7 +286,7 @@ endif ifeq ($(NEED_MATH_H),y) include/math.h: include/nuttx/math.h - @cp -f include/nuttx/math.h include/math.h + $(Q) cp -f include/nuttx/math.h include/math.h else include/math.h: endif @@ -299,7 +299,7 @@ endif ifeq ($(CONFIG_ARCH_FLOAT_H),y) include/float.h: include/nuttx/float.h - @cp -f include/nuttx/float.h include/float.h + $(Q) cp -f include/nuttx/float.h include/float.h else include/float.h: endif @@ -311,7 +311,7 @@ endif ifeq ($(CONFIG_ARCH_STDARG_H),y) include/stdarg.h: include/nuttx/stdarg.h - @cp -f include/nuttx/stdarg.h include/stdarg.h + $(Q) cp -f include/nuttx/stdarg.h include/stdarg.h else include/stdarg.h: endif @@ -321,27 +321,27 @@ endif # tools/mkversion tool is built and used to create include/nuttx/version.h tools/mkversion: - @$(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkversion + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkversion $(TOPDIR)/.version: - @if [ ! -f .version ]; then \ + $(Q) if [ ! -f .version ]; then \ echo "No .version file found, creating one"; \ tools/version.sh -v 0.0 -b 0 .version; \ chmod 755 .version; \ fi include/nuttx/version.h: $(TOPDIR)/.version tools/mkversion - @tools/mkversion $(TOPDIR) > include/nuttx/version.h + $(Q) tools/mkversion $(TOPDIR) > include/nuttx/version.h # Targets used to build include/nuttx/config.h. Creation of config.h is # part of the overall NuttX configuration sequence. Notice that the # tools/mkconfig tool is built and used to create include/nuttx/config.h tools/mkconfig: - @$(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkconfig + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkconfig include/nuttx/config.h: $(TOPDIR)/.config tools/mkconfig - @tools/mkconfig $(TOPDIR) > include/nuttx/config.h + $(Q) tools/mkconfig $(TOPDIR) > include/nuttx/config.h # dirlinks, and helpers # @@ -353,7 +353,8 @@ include/nuttx/config.h: $(TOPDIR)/.config tools/mkconfig include/apps: Make.defs ifneq ($(APPDIR),) - @if [ -d $(TOPDIR)/$(APPDIR)/include ]; then \ + @echo "LN: include/apps -> $(APPDIR)/include" + $(Q) if [ -d $(TOPDIR)/$(APPDIR)/include ]; then \ $(DIRLINK) $(TOPDIR)/$(APPDIR)/include include/apps; \ fi endif @@ -361,30 +362,35 @@ endif # Link the arch//include directory to include/arch include/arch: Make.defs - @$(DIRLINK) $(TOPDIR)/$(ARCH_DIR)/include include/arch + @echo "LN: include/arch -> $(TOPDIR)/$(ARCH_DIR)/include" + $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_DIR)/include include/arch # Link the configs//include directory to include/arch/board include/arch/board: include/arch Make.defs include/arch - @$(DIRLINK) $(TOPDIR)/$(BOARD_DIR)/include include/arch/board + @echo "LN: include/arch/board -> $(TOPDIR)/$(BOARD_DIR)/include" + $(Q) $(DIRLINK) $(TOPDIR)/$(BOARD_DIR)/include include/arch/board # Link the configs//src dir to arch//src/board $(ARCH_SRC)/board: Make.defs - @$(DIRLINK) $(TOPDIR)/$(BOARD_DIR)/src $(ARCH_SRC)/board + @echo "LN: $(ARCH_SRC)/board -> $(TOPDIR)/$(BOARD_DIR)/src" + $(Q) $(DIRLINK) $(TOPDIR)/$(BOARD_DIR)/src $(ARCH_SRC)/board # Link arch//include/ to arch//include/chip $(ARCH_SRC)/chip: Make.defs ifneq ($(CONFIG_ARCH_CHIP),) - @$(DIRLINK) $(TOPDIR)/$(ARCH_SRC)/$(CONFIG_ARCH_CHIP) $(ARCH_SRC)/chip + @echo "LN: $(ARCH_SRC)/chip -> $(TOPDIR)\$(ARCH_SRC)/$(CONFIG_ARCH_CHIP)" + $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_SRC)/$(CONFIG_ARCH_CHIP) $(ARCH_SRC)/chip endif # Link arch//src/ to arch//src/chip include/arch/chip: include/arch Make.defs ifneq ($(CONFIG_ARCH_CHIP),) - @$(DIRLINK) $(TOPDIR)/$(ARCH_INC)/$(CONFIG_ARCH_CHIP) include/arch/chip + @echo "LN: include/arch/chip -> $(TOPDIR)/$(ARCH_INC)/$(CONFIG_ARCH_CHIP)" + $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_INC)/$(CONFIG_ARCH_CHIP) include/arch/chip endif dirlinks: include/arch include/arch/board include/arch/chip $(ARCH_SRC)/board $(ARCH_SRC)/chip include/apps @@ -397,7 +403,7 @@ dirlinks: include/arch include/arch/board include/arch/chip $(ARCH_SRC)/board $( # the establishment of symbolic links to configured directories. context: check_context include/nuttx/config.h include/nuttx/version.h include/math.h include/float.h include/stdarg.h dirlinks - @for dir in $(CONTEXTDIRS) ; do \ + $(Q) for dir in $(CONTEXTDIRS) ; do \ $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" context; \ done @@ -407,16 +413,16 @@ context: check_context include/nuttx/config.h include/nuttx/version.h include/ma # and symbolic links created by the context target. clean_context: - @rm -f include/nuttx/config.h - @rm -f include/nuttx/version.h - @rm -f include/math.h - @rm -f include/stdarg.h - @$(DIRUNLINK) include/arch/board - @$(DIRUNLINK) include/arch/chip - @$(DIRUNLINK) include/arch - @$(DIRUNLINK) $(ARCH_SRC)/board - @$(DIRUNLINK) $(ARCH_SRC)/chip - @$(DIRUNLINK) include/apps + $(Q) rm -f include/nuttx/config.h + $(Q) rm -f include/nuttx/version.h + $(Q) rm -f include/math.h + $(Q) rm -f include/stdarg.h + $(Q) $(DIRUNLINK) include/arch/board + $(Q) $(DIRUNLINK) include/arch/chip + $(Q) $(DIRUNLINK) include/arch + $(Q) $(DIRUNLINK) $(ARCH_SRC)/board + $(Q) $(DIRUNLINK) $(ARCH_SRC)/chip + $(Q) $(DIRUNLINK) include/apps # check_context # @@ -426,7 +432,7 @@ clean_context: # configuration files have been installed and that NuttX is ready to be built. check_context: - @if [ ! -e ${TOPDIR}/.config -o ! -e ${TOPDIR}/Make.defs ]; then \ + $(Q) if [ ! -e ${TOPDIR}/.config -o ! -e ${TOPDIR}/Make.defs ]; then \ echo "" ; echo "Nuttx has not been configured:" ; \ echo " cd tools; ./configure.sh " ; echo "" ; \ exit 1 ; \ @@ -440,53 +446,53 @@ check_context: # Possible kernel-mode builds lib/libklib$(LIBEXT): context - @$(MAKE) -C lib TOPDIR="$(TOPDIR)" libklib$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C lib TOPDIR="$(TOPDIR)" libklib$(LIBEXT) EXTRADEFINES=$(KDEFINE) sched/libsched$(LIBEXT): context - @$(MAKE) -C sched TOPDIR="$(TOPDIR)" libsched$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C sched TOPDIR="$(TOPDIR)" libsched$(LIBEXT) EXTRADEFINES=$(KDEFINE) $(ARCH_SRC)/libarch$(LIBEXT): context - @$(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" libarch$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" libarch$(LIBEXT) EXTRADEFINES=$(KDEFINE) net/libnet$(LIBEXT): context - @$(MAKE) -C net TOPDIR="$(TOPDIR)" libnet$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C net TOPDIR="$(TOPDIR)" libnet$(LIBEXT) EXTRADEFINES=$(KDEFINE) fs/libfs$(LIBEXT): context - @$(MAKE) -C fs TOPDIR="$(TOPDIR)" libfs$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C fs TOPDIR="$(TOPDIR)" libfs$(LIBEXT) EXTRADEFINES=$(KDEFINE) drivers/libdrivers$(LIBEXT): context - @$(MAKE) -C drivers TOPDIR="$(TOPDIR)" libdrivers$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C drivers TOPDIR="$(TOPDIR)" libdrivers$(LIBEXT) EXTRADEFINES=$(KDEFINE) binfmt/libbinfmt$(LIBEXT): context - @$(MAKE) -C binfmt TOPDIR="$(TOPDIR)" libbinfmt$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C binfmt TOPDIR="$(TOPDIR)" libbinfmt$(LIBEXT) EXTRADEFINES=$(KDEFINE) graphics/libgraphics$(LIBEXT): context - @$(MAKE) -C graphics TOPDIR="$(TOPDIR)" libgraphics$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C graphics TOPDIR="$(TOPDIR)" libgraphics$(LIBEXT) EXTRADEFINES=$(KDEFINE) syscall/libstubs$(LIBEXT): context - @$(MAKE) -C syscall TOPDIR="$(TOPDIR)" libstubs$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libstubs$(LIBEXT) EXTRADEFINES=$(KDEFINE) # Possible user-mode builds lib/libulib$(LIBEXT): context - @$(MAKE) -C lib TOPDIR="$(TOPDIR)" libulib$(LIBEXT) + $(Q) $(MAKE) -C lib TOPDIR="$(TOPDIR)" libulib$(LIBEXT) libxx/liblibxx$(LIBEXT): context - @$(MAKE) -C libxx TOPDIR="$(TOPDIR)" liblibxx$(LIBEXT) + $(Q) $(MAKE) -C libxx TOPDIR="$(TOPDIR)" liblibxx$(LIBEXT) mm/libmm$(LIBEXT): context - @$(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) EXTRADEFINES=$(KDEFINE) $(APPDIR)/libapps$(LIBEXT): context - @$(MAKE) -C $(APPDIR) TOPDIR="$(TOPDIR)" libapps$(LIBEXT) + $(Q) $(MAKE) -C $(APPDIR) TOPDIR="$(TOPDIR)" libapps$(LIBEXT) syscall/libproxies$(LIBEXT): context - @$(MAKE) -C syscall TOPDIR="$(TOPDIR)" libproxies$(LIBEXT) + $(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libproxies$(LIBEXT) # Possible non-kernel builds lib/liblib$(LIBEXT): context - @$(MAKE) -C lib TOPDIR="$(TOPDIR)" liblib$(LIBEXT) + $(Q) $(MAKE) -C lib TOPDIR="$(TOPDIR)" liblib$(LIBEXT) # pass1 and pass2 # @@ -502,46 +508,46 @@ pass1deps: context pass1dep $(USERLIBS) pass1: pass1deps ifeq ($(CONFIG_BUILD_2PASS),y) - @if [ -z "$(CONFIG_PASS1_BUILDIR)" ]; then \ + $(Q) if [ -z "$(CONFIG_PASS1_BUILDIR)" ]; then \ echo "ERROR: CONFIG_PASS1_BUILDIR not defined"; \ exit 1; \ fi - @if [ ! -d "$(CONFIG_PASS1_BUILDIR)" ]; then \ + $(Q) if [ ! -d "$(CONFIG_PASS1_BUILDIR)" ]; then \ echo "ERROR: CONFIG_PASS1_BUILDIR does not exist"; \ exit 1; \ fi - @if [ ! -f "$(CONFIG_PASS1_BUILDIR)/Makefile" ]; then \ + $(Q) if [ ! -f "$(CONFIG_PASS1_BUILDIR)/Makefile" ]; then \ echo "ERROR: No Makefile in CONFIG_PASS1_BUILDIR"; \ exit 1; \ fi - @$(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" LINKLIBS="$(NUTTXLIBS)" USERLIBS="$(USERLIBS)" "$(CONFIG_PASS1_TARGET)" + $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" LINKLIBS="$(NUTTXLIBS)" USERLIBS="$(USERLIBS)" "$(CONFIG_PASS1_TARGET)" endif pass2deps: context pass2dep $(NUTTXLIBS) pass2: pass2deps - @$(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(NUTTXLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN) - @if [ -w /tftpboot ] ; then \ + $(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(NUTTXLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN) + $(Q) if [ -w /tftpboot ] ; then \ cp -f $(BIN) /tftpboot/$(BIN).${CONFIG_ARCH}; \ fi ifeq ($(CONFIG_RRLOAD_BINARY),y) @echo "MK: $(BIN).rr" - @$(TOPDIR)/tools/mkimage.sh --Prefix $(CROSSDEV) $(BIN) $(BIN).rr - @if [ -w /tftpboot ] ; then \ + $(Q) $(TOPDIR)/tools/mkimage.sh --Prefix $(CROSSDEV) $(BIN) $(BIN).rr + $(Q) if [ -w /tftpboot ] ; then \ cp -f $(BIN).rr /tftpboot/$\(BIN).rr.$(CONFIG_ARCH); \ fi endif ifeq ($(CONFIG_INTELHEX_BINARY),y) @echo "CP: $(BIN).hex" - @$(OBJCOPY) $(OBJCOPYARGS) -O ihex $(BIN) $(BIN).hex + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O ihex $(BIN) $(BIN).hex endif ifeq ($(CONFIG_MOTOROLA_SREC),y) @echo "CP: $(BIN).srec" - @$(OBJCOPY) $(OBJCOPYARGS) -O srec $(BIN) $(BIN).srec + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O srec $(BIN) $(BIN).srec endif ifeq ($(CONFIG_RAW_BINARY),y) @echo "CP: $(BIN).bin" - @$(OBJCOPY) $(OBJCOPYARGS) -O binary $(BIN) $(BIN).bin + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O binary $(BIN) $(BIN).bin endif # $(BIN) @@ -568,12 +574,12 @@ download: $(BIN) # pass2dep: Create pass2 build dependencies pass1dep: context - @for dir in $(USERDEPDIRS) ; do \ + $(Q) for dir in $(USERDEPDIRS) ; do \ $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" depend ; \ done pass2dep: context - @for dir in $(KERNDEPDIRS) ; do \ + $(Q) for dir in $(KERNDEPDIRS) ; do \ $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" EXTRADEFINES=$(KDEFINE) depend; \ done @@ -585,13 +591,13 @@ pass2dep: context # misc/tools/README.txt for additional information. config: - @APPSDIR=${CONFIG_APPS_DIR} conf Kconfig + $(Q) APPSDIR=${CONFIG_APPS_DIR} conf Kconfig oldconfig: - @APPSDIR=${CONFIG_APPS_DIR} conf --oldconfig Kconfig + $(Q) APPSDIR=${CONFIG_APPS_DIR} conf --oldconfig Kconfig menuconfig: - @APPSDIR=${CONFIG_APPS_DIR} mconf Kconfig + $(Q) APPSDIR=${CONFIG_APPS_DIR} mconf Kconfig # export # @@ -602,7 +608,7 @@ menuconfig: # that the archiver is 'ar' export: pass2deps - @tools/mkexport.sh -w$(WINTOOL) -t "$(TOPDIR)" -l "$(NUTTXLIBS)" + $(Q) tools/mkexport.sh -w$(WINTOOL) -t "$(TOPDIR)" -l "$(NUTTXLIBS)" # General housekeeping targets: dependencies, cleaning, etc. # @@ -617,23 +623,23 @@ export: pass2deps depend: pass1dep pass2dep subdir_clean: - @for dir in $(CLEANDIRS) ; do \ + $(Q) for dir in $(CLEANDIRS) ; do \ if [ -e $$dir/Makefile ]; then \ $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" clean ; \ fi \ done - @$(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" clean - @$(MAKE) -C mm -f Makefile.test TOPDIR="$(TOPDIR)" clean + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" clean + $(Q) $(MAKE) -C mm -f Makefile.test TOPDIR="$(TOPDIR)" clean ifeq ($(CONFIG_BUILD_2PASS),y) - @$(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" clean + $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" clean endif clean: subdir_clean - @rm -f $(BIN) nuttx.* mm_test *.map _SAVED_APPS_config *~ - @rm -f nuttx-export* + $(Q) rm -f $(BIN) nuttx.* mm_test *.map _SAVED_APPS_config *~ + $(Q) rm -f nuttx-export* subdir_distclean: - @for dir in $(CLEANDIRS) ; do \ + $(Q) for dir in $(CLEANDIRS) ; do \ if [ -e $$dir/Makefile ]; then \ $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" distclean ; \ fi \ @@ -641,9 +647,9 @@ subdir_distclean: distclean: clean subdir_distclean clean_context ifeq ($(CONFIG_BUILD_2PASS),y) - @$(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean + $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean endif - @rm -f Make.defs setenv.sh .config .config.old + $(Q) rm -f Make.defs setenv.sh .config .config.old # Application housekeeping targets. The APPDIR variable refers to the user # application directory. A sample apps/ directory is included with NuttX, @@ -663,19 +669,19 @@ endif apps_clean: ifneq ($(APPDIR),) - @$(MAKE) -C "$(TOPDIR)/$(APPDIR)" TOPDIR="$(TOPDIR)" clean + $(Q) $(MAKE) -C "$(TOPDIR)/$(APPDIR)" TOPDIR="$(TOPDIR)" clean endif apps_distclean: ifneq ($(APPDIR),) - @if [ -r "$(TOPDIR)/$(APPDIR)/.config" ]; then \ + $(Q) if [ -r "$(TOPDIR)/$(APPDIR)/.config" ]; then \ cp "$(TOPDIR)/$(APPDIR)/.config" _SAVED_APPS_config || \ { echo "Copy of $(APPDIR)/.config failed" ; exit 1 ; } \ else \ rm -f _SAVED_APPS_config; \ fi - @$(MAKE) -C "$(TOPDIR)/$(APPDIR)" TOPDIR="$(TOPDIR)" distclean - @if [ -r _SAVED_APPS_config ]; then \ + $(Q) $(MAKE) -C "$(TOPDIR)/$(APPDIR)" TOPDIR="$(TOPDIR)" distclean + $(Q) if [ -r _SAVED_APPS_config ]; then \ mv _SAVED_APPS_config "$(TOPDIR)/$(APPDIR)/.config" || \ { echo "Copy of _SAVED_APPS_config failed" ; exit 1 ; } \ fi diff --git a/nuttx/drivers/lcd/ug-2864ambag01.c b/nuttx/drivers/lcd/ug-2864ambag01.c index aa50abaedc..e133f39010 100644 --- a/nuttx/drivers/lcd/ug-2864ambag01.c +++ b/nuttx/drivers/lcd/ug-2864ambag01.c @@ -153,6 +153,8 @@ # undef CONFIG_LCD_PORTRAIT # undef CONFIG_LCD_RLANDSCAPE # undef CONFIG_LCD_RPORTRAIT +#elif defined(CONFIG_LCD_RLANDSCAPE) +# warning "Reverse landscape mode is untested and, hence, probably buggy" #endif /* SH1101A Commands *******************************************************************/ @@ -574,7 +576,11 @@ static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_ fbmask = 1 << (row & 7); fbptr = &priv->fb[page * UG2864AMBAG01_XRES + col]; +#ifdef CONFIG_LCD_RLANDSCAPE + ptr = fbptr + pixlen - 1; +#else ptr = fbptr; +#endif #ifdef CONFIG_NX_PACKEDMSFIRST usrmask = MS_BIT; #else @@ -585,6 +591,16 @@ static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_ { /* Set or clear the corresponding bit */ +#ifdef CONFIG_LCD_RLANDSCAPE + if ((*buffer & usrmask) != 0) + { + *ptr-- |= fbmask; + } + else + { + *ptr-- &= ~fbmask; + } +#else if ((*buffer & usrmask) != 0) { *ptr++ |= fbmask; @@ -593,6 +609,7 @@ static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_ { *ptr++ &= ~fbmask; } +#endif /* Inc/Decrement to the next source pixel */ @@ -748,7 +765,11 @@ static int ug2864ambag01_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buf */ fbmask = 1 << (row & 7); +#ifdef CONFIG_LCD_RLANDSCAPE + fbptr = &priv->fb[page * (UG2864AMBAG01_XRES-1) + col + pixlen]; +#else fbptr = &priv->fb[page * UG2864AMBAG01_XRES + col]; +#endif #ifdef CONFIG_NX_PACKEDMSFIRST usrmask = MS_BIT; #else @@ -760,7 +781,11 @@ static int ug2864ambag01_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buf { /* Set or clear the corresponding bit */ +#ifdef CONFIG_LCD_RLANDSCAPE + uint8_t byte = *fbptr--; +#else uint8_t byte = *fbptr++; +#endif if ((byte & fbmask) != 0) { *buffer |= usrmask; diff --git a/nuttx/tools/configure.sh b/nuttx/tools/configure.sh index 3b68fe3f62..1cba7805f6 100755 --- a/nuttx/tools/configure.sh +++ b/nuttx/tools/configure.sh @@ -100,18 +100,36 @@ if [ ! -d "${configpath}" ]; then exit 3 fi -if [ ! -r "${configpath}/Make.defs" ]; then - echo "File \"${configpath}/Make.defs\" does not exist" +src_makedefs="${configpath}/Make.defs" +dest_makedefs="${TOPDIR}/Make.defs" + +if [ ! -r "${src_makedefs}" ]; then + echo "File \"${src_makedefs}\" does not exist" exit 4 fi -if [ ! -r "${configpath}/setenv.sh" ]; then - echo "File \"${configpath}/setenv.sh\" does not exist" - exit 5 +src_setenv="${configpath}/setenv.sh" +unset have_setenv + +if [ -r "${src_setenv}" ]; then + dest_setenv=${TOPDIR}/setenv.sh + have_setenv=y +else + src_setenv="${configpath}/setenv.bat" + if [ -r "${src_setenv}" ]; then + dest_setenv=${TOPDIR}/setenv.bat + have_setenv=y + else + unset src_setenv + fi fi -if [ ! -r "${configpath}/defconfig" ]; then - echo "File \"${configpath}/defconfig\" does not exist" +src_config="${configpath}/defconfig" +tmp_config="${TOPDIR}/.configX" +dest_config="${TOPDIR}/.config" + +if [ ! -r "${src_config}" ]; then + echo "File \"${src_config}\" does not exist" exit 6 fi @@ -121,11 +139,11 @@ fi # (2) The CONFIG_APPS_DIR to see if there is a configured location for the # application directory. -newconfig=`grep CONFIG_NUTTX_NEWCONFIG= "${configpath}/defconfig" | cut -d'=' -f2` +newconfig=`grep CONFIG_NUTTX_NEWCONFIG= "${src_config}" | cut -d'=' -f2` defappdir=y if [ -z "${appdir}" ]; then - quoted=`grep "^CONFIG_APPS_DIR=" "${configpath}/defconfig" | cut -d'=' -f2` + quoted=`grep "^CONFIG_APPS_DIR=" "${src_config}" | cut -d'=' -f2` if [ ! -z "${appdir}" ]; then appdir=`echo ${quoted} | sed -e "s/\"//g"` defappdir=n @@ -167,24 +185,26 @@ fi # Okay... Everything looks good. Setup the configuration -install -C "${configpath}/Make.defs" "${TOPDIR}/." || \ - { echo "Failed to copy ${configpath}/Make.defs" ; exit 7 ; } -install -C "${configpath}/setenv.sh" "${TOPDIR}/." || \ - { echo "Failed to copy ${configpath}/setenv.sh" ; exit 8 ; } -chmod 755 "${TOPDIR}/setenv.sh" -install -C "${configpath}/defconfig" "${TOPDIR}/.configX" || \ - { echo "Failed to copy ${configpath}/defconfig" ; exit 9 ; } +install -C "${src_makedefs}" "${dest_makedefs}" || \ + { echo "Failed to copy \"${src_makedefs}\"" ; exit 7 ; } +if [ "X${have_setenv}" = "Xy" ]; then + install -C "${src_setenv}" "${dest_setenv}" || \ + { echo "Failed to copy ${src_setenv}" ; exit 8 ; } + chmod 755 "${dest_setenv}" +fi +install -C "${src_config}" "${tmp_config}" || \ + { echo "Failed to copy \"${src_config}\"" ; exit 9 ; } # If we did not use the CONFIG_APPS_DIR that was in the defconfig config file, # then append the correct application information to the tail of the .config # file if [ "X${defappdir}" = "Xy" ]; then - sed -i -e "/^CONFIG_APPS_DIR/d" "${TOPDIR}/.configX" - echo "" >> "${TOPDIR}/.configX" - echo "# Application configuration" >> "${TOPDIR}/.configX" - echo "" >> "${TOPDIR}/.configX" - echo "CONFIG_APPS_DIR=\"$appdir\"" >> "${TOPDIR}/.configX" + sed -i -e "/^CONFIG_APPS_DIR/d" "${tmp_config}" + echo "" >> "${tmp_config}" + echo "# Application configuration" >> "${tmp_config}" + echo "" >> "${tmp_config}" + echo "CONFIG_APPS_DIR=\"$appdir\"" >> "${tmp_config}" fi # Copy appconfig file. The appconfig file will be copied to ${appdir}/.config @@ -203,6 +223,6 @@ fi # install the final .configX only if it differs from any existing # .config file. -install -C "${TOPDIR}/.configX" "${TOPDIR}/.config" -rm -f "${TOPDIR}/.configX" +install -C "${tmp_config}" "${dest_config}" +rm -f "${tmp_config}" From 0c0440210befd8e4bc9971defad4d654c03aae3b Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 10 Nov 2012 00:43:01 +0000 Subject: [PATCH 096/206] Update to kconfig-frontends-3.6.0, Expand the tarball so that we can accept patches against it git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5327 42af7a65-404d-4744-a932-0658087f49c3 --- misc/tools/README.txt | 17 +- misc/tools/kconfig-frontends-3.3.0-1.tar.gz | Bin 504640 -> 0 bytes misc/tools/kconfig-frontends/.version | 2 + misc/tools/kconfig-frontends/AUTHORS | 14 + misc/tools/kconfig-frontends/COPYING | 357 + misc/tools/kconfig-frontends/INSTALL | 365 + misc/tools/kconfig-frontends/Makefile.am | 7 + misc/tools/kconfig-frontends/Makefile.in | 778 + misc/tools/kconfig-frontends/README | 39 + misc/tools/kconfig-frontends/aclocal.m4 | 9137 +++++++ misc/tools/kconfig-frontends/bootstrap | 22 + misc/tools/kconfig-frontends/configure | 20052 ++++++++++++++++ misc/tools/kconfig-frontends/configure.ac | 502 + misc/tools/kconfig-frontends/docs/Makefile.am | 1 + misc/tools/kconfig-frontends/docs/Makefile.in | 452 + .../docs/kconfig-language.txt | 413 + misc/tools/kconfig-frontends/docs/kconfig.txt | 191 + .../kconfig-frontends/frontends/Makefile.am | 16 + .../kconfig-frontends/frontends/Makefile.in | 610 + .../frontends/conf/Makefile.am | 10 + .../frontends/conf/Makefile.in | 600 + .../kconfig-frontends/frontends/conf/conf.c | 694 + .../frontends/gconf/Makefile.am | 17 + .../frontends/gconf/Makefile.in | 653 + .../kconfig-frontends/frontends/gconf/gconf.c | 1546 ++ .../frontends/gconf/gconf.c.patch | 40 + .../frontends/gconf/gconf.glade | 661 + .../frontends/mconf/Makefile.am | 13 + .../frontends/mconf/Makefile.in | 606 + .../kconfig-frontends/frontends/mconf/mconf.c | 882 + .../frontends/nconf/Makefile.am | 12 + .../frontends/nconf/Makefile.in | 621 + .../kconfig-frontends/frontends/nconf/nconf.c | 1550 ++ .../frontends/nconf/nconf.gui.c | 654 + .../kconfig-frontends/frontends/nconf/nconf.h | 96 + .../frontends/qconf/Makefile.am | 23 + .../frontends/qconf/Makefile.in | 636 + .../frontends/qconf/qconf.cc | 1789 ++ .../frontends/qconf/qconf.cc.patch | 12 + .../kconfig-frontends/frontends/qconf/qconf.h | 337 + misc/tools/kconfig-frontends/libs/Makefile.am | 7 + misc/tools/kconfig-frontends/libs/Makefile.in | 607 + .../kconfig-frontends/libs/images/Makefile.am | 13 + .../kconfig-frontends/libs/images/Makefile.in | 550 + .../libs/images/images.c_orig | 326 + .../libs/lxdialog/Makefile.am | 15 + .../libs/lxdialog/Makefile.in | 652 + .../libs/lxdialog/checklist.c | 332 + .../kconfig-frontends/libs/lxdialog/dialog.h | 230 + .../libs/lxdialog/inputbox.c | 238 + .../kconfig-frontends/libs/lxdialog/menubox.c | 434 + .../kconfig-frontends/libs/lxdialog/textbox.c | 393 + .../kconfig-frontends/libs/lxdialog/util.c | 657 + .../kconfig-frontends/libs/lxdialog/yesno.c | 114 + .../kconfig-frontends/libs/parser/Makefile.am | 46 + .../kconfig-frontends/libs/parser/Makefile.in | 749 + .../kconfig-frontends/libs/parser/confdata.c | 1164 + .../kconfig-frontends/libs/parser/expr.c | 1168 + .../kconfig-frontends/libs/parser/expr.h | 225 + .../kconfig-frontends/libs/parser/hconf.gperf | 47 + .../kconfig-frontends/libs/parser/lconf.c | 2434 ++ .../kconfig-frontends/libs/parser/lconf.l | 364 + .../tools/kconfig-frontends/libs/parser/lkc.h | 190 + .../kconfig-frontends/libs/parser/lkc_proto.h | 54 + .../kconfig-frontends/libs/parser/menu.c | 607 + .../kconfig-frontends/libs/parser/symbol.c | 1310 + .../kconfig-frontends/libs/parser/util.c | 140 + .../kconfig-frontends/libs/parser/yconf.c | 2531 ++ .../kconfig-frontends/libs/parser/yconf.y | 740 + .../libs/parser/yconf.y.patch | 29 + .../scripts/.autostuff/config.h.in | 202 + .../scripts/.autostuff/scripts/compile | 143 + .../scripts/.autostuff/scripts/config.guess | 1502 ++ .../scripts/.autostuff/scripts/config.sub | 1714 ++ .../scripts/.autostuff/scripts/depcomp | 630 + .../scripts/.autostuff/scripts/install-sh | 520 + .../scripts/.autostuff/scripts/ltmain.sh | 8413 +++++++ .../scripts/.autostuff/scripts/missing | 376 + .../scripts/.autostuff/scripts/ylwrap | 222 + .../kconfig-frontends/scripts/Makefile.am | 1 + .../kconfig-frontends/scripts/Makefile.in | 403 + .../kconfig-frontends/scripts/ksync.list | 35 + misc/tools/kconfig-frontends/scripts/ksync.sh | 61 + .../kconfig-frontends/scripts/version.sh | 43 + .../tools/kconfig-frontends/utils/Makefile.am | 21 + .../tools/kconfig-frontends/utils/Makefile.in | 708 + misc/tools/kconfig-frontends/utils/diff | 129 + misc/tools/kconfig-frontends/utils/gettext.c | 235 + misc/tools/kconfig-frontends/utils/merge | 130 + misc/tools/kconfig-frontends/utils/tweak.in | 187 + .../kconfig-frontends/utils/tweak.in.patch | 23 + 91 files changed, 76482 insertions(+), 9 deletions(-) delete mode 100644 misc/tools/kconfig-frontends-3.3.0-1.tar.gz create mode 100644 misc/tools/kconfig-frontends/.version create mode 100644 misc/tools/kconfig-frontends/AUTHORS create mode 100644 misc/tools/kconfig-frontends/COPYING create mode 100644 misc/tools/kconfig-frontends/INSTALL create mode 100644 misc/tools/kconfig-frontends/Makefile.am create mode 100644 misc/tools/kconfig-frontends/Makefile.in create mode 100644 misc/tools/kconfig-frontends/README create mode 100644 misc/tools/kconfig-frontends/aclocal.m4 create mode 100755 misc/tools/kconfig-frontends/bootstrap create mode 100755 misc/tools/kconfig-frontends/configure create mode 100644 misc/tools/kconfig-frontends/configure.ac create mode 100644 misc/tools/kconfig-frontends/docs/Makefile.am create mode 100644 misc/tools/kconfig-frontends/docs/Makefile.in create mode 100644 misc/tools/kconfig-frontends/docs/kconfig-language.txt create mode 100644 misc/tools/kconfig-frontends/docs/kconfig.txt create mode 100644 misc/tools/kconfig-frontends/frontends/Makefile.am create mode 100644 misc/tools/kconfig-frontends/frontends/Makefile.in create mode 100644 misc/tools/kconfig-frontends/frontends/conf/Makefile.am create mode 100644 misc/tools/kconfig-frontends/frontends/conf/Makefile.in create mode 100644 misc/tools/kconfig-frontends/frontends/conf/conf.c create mode 100644 misc/tools/kconfig-frontends/frontends/gconf/Makefile.am create mode 100644 misc/tools/kconfig-frontends/frontends/gconf/Makefile.in create mode 100644 misc/tools/kconfig-frontends/frontends/gconf/gconf.c create mode 100644 misc/tools/kconfig-frontends/frontends/gconf/gconf.c.patch create mode 100644 misc/tools/kconfig-frontends/frontends/gconf/gconf.glade create mode 100644 misc/tools/kconfig-frontends/frontends/mconf/Makefile.am create mode 100644 misc/tools/kconfig-frontends/frontends/mconf/Makefile.in create mode 100644 misc/tools/kconfig-frontends/frontends/mconf/mconf.c create mode 100644 misc/tools/kconfig-frontends/frontends/nconf/Makefile.am create mode 100644 misc/tools/kconfig-frontends/frontends/nconf/Makefile.in create mode 100644 misc/tools/kconfig-frontends/frontends/nconf/nconf.c create mode 100644 misc/tools/kconfig-frontends/frontends/nconf/nconf.gui.c create mode 100644 misc/tools/kconfig-frontends/frontends/nconf/nconf.h create mode 100644 misc/tools/kconfig-frontends/frontends/qconf/Makefile.am create mode 100644 misc/tools/kconfig-frontends/frontends/qconf/Makefile.in create mode 100644 misc/tools/kconfig-frontends/frontends/qconf/qconf.cc create mode 100644 misc/tools/kconfig-frontends/frontends/qconf/qconf.cc.patch create mode 100644 misc/tools/kconfig-frontends/frontends/qconf/qconf.h create mode 100644 misc/tools/kconfig-frontends/libs/Makefile.am create mode 100644 misc/tools/kconfig-frontends/libs/Makefile.in create mode 100644 misc/tools/kconfig-frontends/libs/images/Makefile.am create mode 100644 misc/tools/kconfig-frontends/libs/images/Makefile.in create mode 100644 misc/tools/kconfig-frontends/libs/images/images.c_orig create mode 100644 misc/tools/kconfig-frontends/libs/lxdialog/Makefile.am create mode 100644 misc/tools/kconfig-frontends/libs/lxdialog/Makefile.in create mode 100644 misc/tools/kconfig-frontends/libs/lxdialog/checklist.c create mode 100644 misc/tools/kconfig-frontends/libs/lxdialog/dialog.h create mode 100644 misc/tools/kconfig-frontends/libs/lxdialog/inputbox.c create mode 100644 misc/tools/kconfig-frontends/libs/lxdialog/menubox.c create mode 100644 misc/tools/kconfig-frontends/libs/lxdialog/textbox.c create mode 100644 misc/tools/kconfig-frontends/libs/lxdialog/util.c create mode 100644 misc/tools/kconfig-frontends/libs/lxdialog/yesno.c create mode 100644 misc/tools/kconfig-frontends/libs/parser/Makefile.am create mode 100644 misc/tools/kconfig-frontends/libs/parser/Makefile.in create mode 100644 misc/tools/kconfig-frontends/libs/parser/confdata.c create mode 100644 misc/tools/kconfig-frontends/libs/parser/expr.c create mode 100644 misc/tools/kconfig-frontends/libs/parser/expr.h create mode 100644 misc/tools/kconfig-frontends/libs/parser/hconf.gperf create mode 100644 misc/tools/kconfig-frontends/libs/parser/lconf.c create mode 100644 misc/tools/kconfig-frontends/libs/parser/lconf.l create mode 100644 misc/tools/kconfig-frontends/libs/parser/lkc.h create mode 100644 misc/tools/kconfig-frontends/libs/parser/lkc_proto.h create mode 100644 misc/tools/kconfig-frontends/libs/parser/menu.c create mode 100644 misc/tools/kconfig-frontends/libs/parser/symbol.c create mode 100644 misc/tools/kconfig-frontends/libs/parser/util.c create mode 100644 misc/tools/kconfig-frontends/libs/parser/yconf.c create mode 100644 misc/tools/kconfig-frontends/libs/parser/yconf.y create mode 100644 misc/tools/kconfig-frontends/libs/parser/yconf.y.patch create mode 100644 misc/tools/kconfig-frontends/scripts/.autostuff/config.h.in create mode 100755 misc/tools/kconfig-frontends/scripts/.autostuff/scripts/compile create mode 100755 misc/tools/kconfig-frontends/scripts/.autostuff/scripts/config.guess create mode 100755 misc/tools/kconfig-frontends/scripts/.autostuff/scripts/config.sub create mode 100755 misc/tools/kconfig-frontends/scripts/.autostuff/scripts/depcomp create mode 100755 misc/tools/kconfig-frontends/scripts/.autostuff/scripts/install-sh create mode 100755 misc/tools/kconfig-frontends/scripts/.autostuff/scripts/ltmain.sh create mode 100755 misc/tools/kconfig-frontends/scripts/.autostuff/scripts/missing create mode 100755 misc/tools/kconfig-frontends/scripts/.autostuff/scripts/ylwrap create mode 100644 misc/tools/kconfig-frontends/scripts/Makefile.am create mode 100644 misc/tools/kconfig-frontends/scripts/Makefile.in create mode 100644 misc/tools/kconfig-frontends/scripts/ksync.list create mode 100755 misc/tools/kconfig-frontends/scripts/ksync.sh create mode 100755 misc/tools/kconfig-frontends/scripts/version.sh create mode 100644 misc/tools/kconfig-frontends/utils/Makefile.am create mode 100644 misc/tools/kconfig-frontends/utils/Makefile.in create mode 100755 misc/tools/kconfig-frontends/utils/diff create mode 100644 misc/tools/kconfig-frontends/utils/gettext.c create mode 100755 misc/tools/kconfig-frontends/utils/merge create mode 100644 misc/tools/kconfig-frontends/utils/tweak.in create mode 100644 misc/tools/kconfig-frontends/utils/tweak.in.patch diff --git a/misc/tools/README.txt b/misc/tools/README.txt index 4a141cb941..9faba836db 100644 --- a/misc/tools/README.txt +++ b/misc/tools/README.txt @@ -10,15 +10,14 @@ genromfs-0.5.2.tar.gz This tool is also include in the buildroot and can be built automatically from the buildroot. -kconfig-frontends-3.3.0-1.tar.gz +kconfig-frontends - This is a snapshot of the kconfig-frontends tarball taken from - http://ymorin.is-a-geek.org/projects/kconfig-frontends on April 5, 2012. - This snapshot is provided so that a working version of the mconf - utility is always available. + This is a snapshot of the kconfig-frontends version 3.6.0 tarball taken + from http://ymorin.is-a-geek.org/projects/kconfig-frontends. General build instructions: + cd kconfig-frontends ./configure make make install @@ -32,8 +31,8 @@ kconfig-frontends-3.3.0-1.tar.gz kconfig-frontends-3.3.0-1-libintl.patch The above build instructions did not work for me under my Cygwin - installation. This patch is a awful hack but will successfully - build 'mconf' under Cygwin. + installation with kconfig-frontends-4.4.0. This patch is a awful hack + but will successfully build 'mconf' under Cygwin. cat kconfig-frontends-3.3.0-1-libintl.patch | patch -p0 cd kconfig-frontends-3.3.0-1 @@ -44,10 +43,10 @@ kconfig-frontends-3.3.0-1-libintl.patch See: http://ymorin.is-a-geek.org/hg/kconfig-frontends/file/tip/docs/known-issues.txt Update: According to the release notes, version 3.6.0 (and above) - will build on Cygwin with not patches: + will build on Cygwin with no patches: http://ymorin.is-a-geek.org/download/kconfig-frontends/ kconfig-macos.path - This is a patch to make the kconfig-frontends build on Mac OS X. + This is a patch to make the kconfig-frontends-3.3.0 build on Mac OS X. diff --git a/misc/tools/kconfig-frontends-3.3.0-1.tar.gz b/misc/tools/kconfig-frontends-3.3.0-1.tar.gz deleted file mode 100644 index 2f2f4eb9c9aa453dfc12c2e0c742fe164b6968f5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 504640 zcmV(*K;FL}iwFqE@O@7J18ZY%Zf0p`EoO3WZggdCWOFSuE;BALEio>1VR8WETYGof zNV1=Q!>8yaWPmKj!OmkQS?*i~V~0B!ygVk8#U4e72DBCuBMCd6+5PVKSJkZtFXu7Y zIp?0su>nclRn_&b>gL+^y{R)hmzN{rieIf~5Jq#_vb`e$4MrD}aK}XMFXX-(T?icl`dn5T}8ZqVG?m zTPu*_)L(fMQ0aRW(emsnrVr*$D5j1p1%1-!P>+5kqPg4)08?kqjSR)gbDf1lJXp$L z;e;U`ipUo>RwpcPa_9$Q;)GG)j8_q`L`3wh6U_x4(5JtO#KNCAQ!tMphZSLk!i7H3 zXGHXQJ~+!1E(00L;6_fWxtRE6;LieUK~GaW6XAGF|J+|ne6b>620GUjV<}dloUU9V z1Y^b9*5FNdI1onXop@{XdPZmPu0l(o`SJryJ5pNQKK;EL{gf zz^cIVqC4SF#d)*Wcms&W>sGrpct?vqZ4EljeqWq+d&0o{3!^t^HHK}YCoYD)i*CP( z#Vwwi&eWU8X=!9MOk+6cHoBct^QUI7-|BX*DmfuW7(-kx(U%LO@uP9pOb3Xa^U7D{ ziRUWlCA1ij zB=o=sg933Q1J(~PCLUT9q6G!8?!>JhTvu2kO5|d;vWSloz$3q!YfZ&n3=l#eyK(_t zp<6WDQ^Q0cW0F`Vl|Cy?%4H8=3Z#D}U^NEdh@Alh=Wf|5^sd$qt& zC2W3X+1J)gLMiT++Qi=z{eh$v6syEm(nr@BN4`&fUmU=^DLN29eVaL?bTW)INmX(N zv11^=@DO0cm$`=6DJYk~aMoX&PU7RIP-%EWOr^wzd5sO2}@?mnB*^Y zBg%;Yz~{S>O(y~%U*txV6*!(Ojm-AIY;-T)wK`{HKx8TZC#50Q<*~Gah)nLRGZbyD zqC75hV~54k)hE(rb^Tcay3R%6$(fzFm5OwJ;q zFX>)5PYrD!3tkB&t>mtwbf#Lk5eiF$OKCfx zOn$H>508ERezHl9j&eg8o}?bpN||jXfeCcM0|ZuZ$AO4IgzT5Vw-7EhD~8mcIiBsV zCRyMKlK~;L7BVG)X=lcBq$3dI)?$AHWsj6d@K95=QvtqS{7mBGz0nZ>J{BK$MMoj} zQffxrqhhrDg-;G$Mwa7-YRMFnLQsaNz>x$#T*3z-g;T!fqpAxS7P}SpKN$|b5}_hX ziAy^Yif>bLJr#`s^U12l6liWe*S97VJOh6r=25hKd3bnxdt04(tEwN&4qb&aJe)1v z>O5Mwq~?I&kFg|A8O|-70;!SK-uvAM3GG=8gDmgbg^c?VhJ&_KXNuLFy1pM&#A^g7 zns9E2Cr7m!N}6NxYQw%!&8bKS?@6Zf?74u;Y;{_L9NoqDi(a$W{Ci1f5oO#w*m`m9 z3vIv($eF+Zp^##8lgYF}+{jPTs>Qfau4U;<5M_J{~+S^BRyo zp7+m8*nTHv%fy!|i?hjt+)8*3HkjKvqI`&qN|K9VuvcaA>QzpLmYvgV&`MPrbuR`G zQU7X>A_4PB^K{r@xzY@x7dN#QB7uGO9cR4aEqg5@wbf~~hbPTG%`}GX0Reg4gtKWv z&`&7t16JEW3c#uIuBY&J7sJ8c=O=ANOPp$JP1wm_9+M*qlk$)_=M}*?E3)ShnEbGW zmB7|98==7t{E*CEYv)VCfC?O<^h~(Cu`?-+eldT*;E{3g5A*7;g@llJ7&2J@7Nbf; zP_ujbFMOP|&)VJBMq7Pv8~=D`c6(;0`<8B;gHJ8 zx`J?M7ZVA4guo-er30>+&uNQQfB-G!{{ zoCn={NmUZhsuv5T{+njIT^5BBWMwiQIE?b49$F+m^oOtegOZ-3)}>c5ydX?n4`qIy8-T%jlPs#S#-0GHqoVKxWwaJ;O5Ucu=c8 z6=T$Fh=3FDm102Tj2+jB?p`WeOZ>(T)EZc3%r@SvyM_ZW`pu4U-Yhj5yB!rfY|FJ* zl#2@6HplR(#0JV`uAQa0_DE7hDN+ZNG=a559TakSB!dqRP_j&&57kX?ogydKM=1}W zqp)0(cP-TN`ByMbcxiUxh4dLaZjFze`Dk=`d3be|-mz`Vp07PpH`rIxWJ(roJ2N1; zv0MdI7o<=0jb!TO!QH!bX6{H3VO#N z$or)z{NA{z=k299nCAbTqwDjZ>iNY@dfhv(=Yxg1CS%;ghL}UjzB5eOAcUXmFq^na zd~XXf3WRM*M@NTQ)39`Nwd)|jmWN2(a{zA$iaHYWZx_`eji9b%sk&7 z!ya%4-fZ`17i@mM7qf!8g?fW4>{=R)UGWF0>fntTb86SK&iVat+a0s7MnqHu9{eWq z1-h3P-+n9TOFi#;;vmd#kk0e)S);eNbIHXwVl;Qzs71iJF5D}ki+3IFCW8Fa`H6XM z{A{+HolOq;?~YO;rK+!^MeJq-tvCFyo=rPgUrHcevtMm zvc|652PX!zE2!@>%Khmahg0*kX$*$F=Dv|&MX%ZJ8YlNbIycT*NT-`9srQWooNoKX zG*CFVeroO?r1Ckl|L**Cx2=iFsTNn~w3UQ2ooU15sj5ab0WnkM7_2;M_#(E8-@r6E;ol%tM16e;KW|%0)CYvRnxhJa zwbK*%%fj#f=)Z{*uD=4|zw?57h#azT4cwyB<<+SiB{y}*#b=>>8IW8mhVJYCq1tPU zuLA?N+C9I3cJxvmWK*LUg<#zHvEMfOZ*n;makclMh-*0?j=5q&me%?iRl^ z6ebOARU~l-qR{|1T^ELMlyq$b3i^PjG8_cXkP3ArwOBfhZoA!V3{1)j`a*g)PT+gg z(H1ur%68zX#4T^e$)Ij5&k5(0HCPDX(_ripMc;5rThTgRXh|m%2bWj#3t{ z(@^JI$QAt{T7QBEV7y4`Kh{F%*=ig{PNX|qRQb=PyQH+1+V&uO1!8_(`PBDN8wix{ zg{~FOovFhOWiZ!Di(CbS)EaPI$`m69QJR>I6;J#X7;!)V33(I%Y*@`9!7%xr$@J8V z;o)UzG|Im(TwY#XU6v0oFE49{vm#SXRW{^kjr|*`b}>LH)xQiO;XFh(m4QUQ3Q*jC8f?zI zmFZ5n5H#%@lbnUVhnmm_d5s1hHX3<#aoRS{sBBbU@`{T&L$TF{eZsIF>3vp!l<7sIy4#CaVKiTN!^`fZYOC1KTWRczINQ1I&4&k zODR=fbFGSk3X58>>q8}DU-KGCpq03Zrf$P^%>79$Gx+W(Lxl>^h_6gVa#bfd+UHN? z5&{ZMhGuGL2mmz1Tv#*5<}i>r)k6Bfv=@`SsEcBXrgwt@vns` zY`qn!w%l}QKkh4pcHk_d9HsWdi;He=&^)0qR~k`H%ABQUnAy;2LwZLiM%nv1vp|GA zH##T%q~6d?16^Wd8YbJ-7w&ZYNbfmtN7(i!yp2U0uhjAO5g@r={ytupEUNTG->8yF zt->Ne!3Y(k+ob=uK_j`1WXCvel?b8%8h=L?xB->Jwdcbq+?BFmsG_y{U{0JM)6Jq- zqqcVpJ{xk)n@6Ef&z2|`? zH=t8-(-{8D8Ld7Ruz9;QQXQmfIKRrI);sgWbg}hfA-yO6hHIMztMU-QM=zqA<~>8`|zD)Y2Uby%9n^DsQ6Z ztCslY{H;xIwck<8k(w#j-0~npRNlYIEt+=0Ebrkd+|{RZGRwcO&ALCrwPXojnR6M| zY;dn{{M1YyXLtxdLF_iaNIlniz0t7TftOgeOQPHz-)la!Yqr+f>-NqKMRBt;P;0@L zk5f(w+hihKX|Y$K3YKc6g%!YW=uK5R>BxKN5=8~&YEnfUOGJU?;CcoqntmkHcKV@v64s0Toh>#)h z&8MGD5YQp5n90cxbSFc~GrGQ0ob-I{k~6*t8vePa@kfkdQx`OPqAs=4L@bKEiX(a% z@$rM030QTaEu~Svd13U7LAOW4^&)E3YW0g~&eFOI9S4K>0SY5T+)`EwitB~{PEJg0 zjO`C!|JZz&@^}yNf6V!;F?^i>?Ww5}1kWF;le$l|{^+A4g(olJm3%Rkx2O|leA+a8 zDKJ{OY1MZBgz@;V#dDN#YR!%rx24q?CAg}HP0ye~9e*w;)~7wdJ_3g&Il7{nV?zm5 zC+I(cRbfrruOI1y@6Dl4rSm0r7#c0 z-|FH>*Q13ebcl-=T3S1sr7{&nva52rvKcd2JLy9kl;Turm*W9PlIh{nbs|EeHj9vA zr^vN~?U(7?7!oVufSp46W-%_7BaQ*qY|_fuf#X(V)7=5xc^Vz@i2AUA0?{IMcIP~4|Yd8UPeW1 zP?7OZ*)nEe42FFUumoXeTDHllSoR1TD_Pa>bS!7+KG;QVc(8G{(bQyLNL^Mt54_vyiHb=R0E15X}eo( z#$}lhR=9;n{n&@pY@)Nb%-@Cju|h^b+>BD}=gtDR_V86P6N*be9a@a#WU{d#!kd9h z86e3QDDu;iqoUZ&{V9F&iX_h^X`((#59pjV(H^INqD1YhWY=M z6$;<@bgAsA^0y_U-5_*_$X1pNRLbDiokP~PwO663_n>H&G`R9rdF@DT+&Lh>y+b!> zhhP<PEopJY*7 z@y}NLK>a#K+&J7W=hC!Jn_ZW_z;LRR+t*IsFv64F^yV79_D(aYcw)RY7 z7@fdfg>!Dsn;T`c*bI*!LA6nbXK`@p@p-URau~;MRj#a2SRWOxl3u1NPu8Ckw?~;F zM;{-u{`7O`yh<0lmgt$(bQn<|Yw0g{uz9`C$m)RhCeWyRVh5gF1pZ`Y%Z&DB;x1dX z=X(d*qW6Ur+6P)W`e+hN$MGoP&1}tSs&rcm7QqG=`-|*8gKk0zF}NS4DDm%b;*G&| z1bjx()<2jE_*@7rl0DCcS7Q!s?m+Ee;$AnuuITp_`kue9NZk$wn{MvoVSuSDk#D-s z2kvtjF@VpAW^1L!r!GJr5#Lw_umkzJFaN}}b4RBLU^cp2s-&-(@t5^qr)+JR?Y5LY zZH}dTaTDRI2n*+5Sc~1HymQM-d+ii=L-p&hRDb!Tgi4Yqgs3wt*`6x3?&%Dabrb)b zigxPA)&Mq6gDUYJBT=&1kd0AgEt+=(w{!1Gx;x0Z07tNRe=!SJrG^e=i?jmQ_m|n^ z`+wQ{(uOvUq~Xu#SM(0b3SmhcK9b-iSuC*427_O~v9mzLAdO(wl19-;24a)n{?^gw z96A6y-hIMuENP~@`mU<3Q^7;Ku8?SEg^N5i2=+xLU6eLI)mFGyxYTR8z z?KHFZ^Y-ReWBd8m&HQfrQwi8_foYchN8cl;(x%+*To97+&? z>V|>eLR8io!6h4gbC8*tjPoKobL1XLP_Tj=x z8PAh`wO%sCN?JiP#YCg0W)Kg_|Bo#G-Dy%#6t{KZ>>t-|J?w=;1`3nGL!NTD@2 zR%3YfvxQbi;<#{P5p`E`S(e@^(qHBH6yXatHk3D0{&8G{D&Fy_@?;@T6Z$(nKK8K0 z$%*t%6x2!KL5oytoy&P#R>Fnf?=)Qa0T*BVsqVfKW@7CO5QOK+*0f*Cq}EkqS+$KL z3{3T=WuB^RRqs6Ut^cZ-PoD=YI&Nj`${8o*ORe4W@TxlMi#99U6aWL`4?5R2{fpWe z>U*(p79b0bh8%SX+87L$D`+x?a~P64m(u1NO+M35#BnOL5!z+K%scMInipcPD^0~~ zOOpO}hBpQ23cb5`xLpSpiVWFsDGjBEIRK_d{NR~Kp7_T<;A3m=d13x{W(KGvai zV0RS#xX}$z&apr0SwSJlQB>Q@>3JEB&WtBPb2J#B=){pQ)d~evKXe)~fawj_VMXJh zKy9xd>+#X=DtGCoAUnweNRHrGz6EZF-C+(kV9mGxy;W$yqu2YWt=K9Qf~%m39MP+- zg9G%!f4&KXGxc<5?*+d3K}~IRUigUqfw0@)0}4Ldd$(}3FI`mRQ zFfQomNw6AkV*fmVt#!0~B964<`$+-DTfL~jLBZ}bqEYM%Yyx~(VWt?vC}82Av9O9t zpbD$sy;1iJ8Dgi#Z&>5EQ3#9+F^`e7P{NAjd4e{rKqRn-=q*xhVTD$3HaeFT(D|D@ zd~nd+eninuaD&E$!hS%0A5fUs?tj3Ss+@y=$~YH4)I7CFvZJ_8bR`9Dirv{{)COrw zk$fah%K8{u!l7hsD?FCScnoJ#tstK|5`~@H2hobPb#Sd!(`Nu+7)e4y9Qd&*%wmK9Z$`xon9Q2mSS`dBKXGH*7l-J;qpU7OylubHB}k+JA+ zRJ6(%j=$2A-*jaM1riJfvRGD8Ew=Xe_x2Z#Mm-Gnb>4&fNK3lEtMQM!{pt zV=S4-Ghq)s4jA8ZlndqaJO;Y5@VFIx$$khy%1gx-cR=CDOc540pbX=E(8s%G)aSTfx`Q<# zUXmI&;AJ9Iu!#-nC8~&^-44i=4cMe+CyLn+)$R#NK2&T8rC1aTgP@Ep;&wwh9gTzS zo^>B!@WwaOEB2xWlS^{LECu0)OOSj|Saj9|GHygw3Y#Br!5(U1U5iK$Au?M#8Bl%`MRhn;W3ULgHK zLdeY$c``^@QTEJrCEX@~%3?)UQ15BW-iK>6!a_2!Uoufu`g2l)H1#IaYDg^m>+Uh%|=SQRUesVElGWjqNMa63^13?~Fw-Y#J7 zH0VqvFQbgt@gj=Xu~PiauN=hVR8&#P_91KqlJDveQIrw%s^o5ob1(Jd7>VpdNZz#e zjVTq6mpOj1P?XGD@o*as`{Bl`*JV+Z6N*<;6>LW%Yhndqp(zB#=>mR`xEPNAh`v;N z!17swKpxS`Z>MYM%C>j7wI=EpaLo_!Zp#`1D}<`F?FQ5h^u7~C@6oqNJ56E8I^O9N zORkWzWq>B;=jX+SlXZ3bZ`MPI%x-&aPQ>leTEG`jgw>ZQVGGrNxE411KXZb8>`uOV1hY=uq z@vj%JU&C=3@}^}8N1K4aSO5_M!s&)r@U*_awDX+s)z0&3gkG`e%YwAvAnY}{F=P?w zR!j?w!jLP9(2Q=fL&HKqOTg<7V}^j+nt<12@KNfUoNw+4dO@>EO9$_U&>d#AE-$X> zzKNO}6!COg>b8ndqaTr(MI5p8t9`;*kPj53$@rF)=GZ!py_`eitmv1Rd)*HNn3;`7mkq5O*-f)8!S7`hdRNcbvlC)L1Kq>WP zfi;81C`c@XfsB^qi}`Xb6U!kW#!+YmpNZ8JF)wGJw~Xp|G&x$}67d2B6H?M*8)&X2 z6 zU+!^s4k&mXU^qt0xDW$4gmIJfv7{j-8#oG|k+g$Tu@DeCl#={Uh5cgJ*e*+l1&1Qk zR4LiRwc<+26}LLCt&nSVP5D(6U1XP$N9{$IDSHj}Tn~Ck0$LJEnmatO;LBPI_)lui z&=QVd8Ae=oMp@Rd%UK8L{m4Hjo)LGtbn+9jBMHee1)F3Y{Mb;F#;t^HsE|XQo14=k zU8qZ!i~55H_{Mti?wx$~FaLw@zI##smwX3g7M76{Q(ZIK+&4W-qGwUIXN`;<335TYBjQ zHAX;cb&)LR#1&20H_7$M>$$zXXo%@p3V6-Xw+!0@SnWQ*lvat<9!|9*%jyEf6?N0Z z3DbjbWQ{%6lSrE6%VCvdF6C^iCeyRL$(V zirX?Zv+Ftt#O>x>)?Cx8#AM^MvI|^!h6*VLVDO3YxDB{3RTIwBX&P|{?lj@N5+;6i zKKPUTjjAf{CpPMS#zwWvCfeP%H|l;}dA{Z&7qqR%(A2>&kdZYg@~a8Is;{VY`pr>) z@Sx1mU(-eT%$oC}=~jM?dParZ(mdh1IMU4WokGke#+Z&Un;P5LBK1inh&61T@^p#N0lOI-DK9L;lfpF5Tt<6EY*y~76GHLRUOakMus4ZE}>EB zd}Ojwkj#qZ#>$hpW{kZsV3#`0&XzIaY<|#qwuc|DcQy{U##kLA!>&VZ=>eWa_|c~r zJ<==~^SE$^Ar=P}IJrlRStINWQ0ZN1IiGJORcA3=~uD%V5wEI zfCYm=p~3#4Y>RQ!b>lj2zQ$_C>^c`3sot z&HXPQ_F&qz!?Jf-IG&|xmaRI-Sh+z^(x`A=pc_Oo+ zoK%jo#k@icF8qERwXRWt-tq^RVb5fL;Fzf#v}g0+mshB;p$HuDb$2ujJNSL=B(wPL ztF2A6+7(B=ZqN#cV~Xx7x8q6*goFpW34`A)Ss6 zQ3OD-+j?Q2V~)wtjxDkIc4PlJTPFyZhciq7h6XW$vNkov-hp_R*_N4-jFy_DN}#xw zK0RQ=C2n9cY&D1D#{jo%5m5+c8Qq-6G#R{}dkcQ2)mlR7N6=}@Yl_N+2B0pgd*UqY z`Gas;=)6i(!G8iQS~winj96K&Jvu2D^!C_*4Z@pbfr9B*rMGK0YK-QpT}MD@;V9Cs-SO+k$R?crARRYGzwEO73ySo+|*g+J$b0 zsz2=5gAj-Y5PwrE%%Kc=fQxpfkz(r_ek~T}7n4z$Vzp8ILmBb{P2E0t8!ns-7n?u97DVqes z<4_cNZKP;7gCK^vZ z(Zj4EmwH{Txns%JkXjxyD1anOsEVH1Ew~Rd+pO62m618!@^*i+MKyHo#yi>m#w)~> zN90U2H)%u^NojI1jBiz#GyS&5&z(9^`roP8hLzgU(eldbi57;C6R1DntV9jWa)(lg z)_SS<@v?JM)ei*yMxig-qn30Y5(#y2N_en4hU5;+NvLLNWU(yf)IRvuHfBlbSySiJpCbWJE$`5ehm%NmCCe+0rL^`8}v87Qv4d%{L0NUoCLOm!D5 zg2VDPu}S8+m=&;t2D;(!M_Gqg?BlDA`rg4iOeVCm_X|3`!_{y9#nxdJsxRMEXi0HB z=kRxB@w+FBRi1?J7C-SL`TOYT`xWy3n45J~C0=Zx1;nUN(~hmloiY`~nb#E?xTn6# z)6bTd!m-1&<2>i0RWyScF^}q&g?>v#hhmhJZBJG^c_(^&V_XF*#OozFi`m$z z$hSVcZDFL};zz*eIR7_QS*!;2;461BU`xB)rv4~0-;2a*TF8Rl+~mxH;@Qby!&}Q3 zuDqULXseb*KEoFr6ogw4?Ga_ zuzchax9IFv$tjYA&dy~z=MGqwdL`**E}4IfOddB-Z_wy8E26kkW|C-?#C$M#v2L)9 z?1VzvM2pK^lV?Fz!T17}r0)+e*drbbTe?5D5=C5Xs4gQT&_EFy*D96V!XyqrFF6^o zJ*OiHtUyq?s8`Iv9A3f7xTW$~DUt|V6nYM{L{-K#0w#fg#wXb&ifAKcBN(&c)1|YH zx;$GzV$Pyi%0yso*QIYw?%K;C9~Ys0n~yy%W=#+>!N)~@5C6hRj>WNxj1S+mT#JRB zRkU!zrJ#vAE)HKURLNG%6+W4*+b?B3Gqrbd*y{$R4SmynpI4xuz z7d0KvWwdY{^+Nd&yN=aq&3tm`qO9-eh!fRVH+UIH|4Ovu#pp0(#Zgh|DD{}^kzl}& zXwYJBAbG9y!z5F&iVs1s*oqQAh;Tk}9M3K^gs`D7M9^(eSFU7Lu;3FcuukqEfjkOuYPP$it`1elE#$T!qkbDB8)DA?Po zbUZ9Q6*o36Ii)OP@8E^7TKpyK_XB{=)i9`U{5J_U4&<`&*3R7@(wS0uWa7ko&IA=d zt~|iU|MYGs>E=vRLar^aDV%sJdVUjrXaxYcXgS@mPdPRE)dYxg(6rjedcd|P5{{IO z7no1WO}#lU5s3^Agwxf*LEx8u6jO*)@CECdN;>2a_8FK>m|zNp{Cg0u3Cg1en5idLe*%tc1^;=x zvMSE5DGKw-6ZNfDs~Jt|N0FSSb&h0Igb|!3&H#EO&p{P6#mTB9J;`{S03%zs?qGsb znrlrKs}Rr?UpZpVd`PA9v>6_BM2}E`@Fw>4R0B#4+5pTSw;tnK!4i$~VLFIlmxZt( zz#%XK+zih{Ov3r52dt-JQ)&4n>yE)I$beabv1yu6;eg(g`@IOeYVVpDi&lB|H<563 zND1;cyr3Z|(y(-VOyQ0&#V3`Pbq=BmtPR|OkP?z3CbNBr1o0Gc;3nqy0SgUEvA`2t zW7`3=F+#mq*hY8u?dJzDS@7?Ak$5H@sb8Nb%oT|75eat?_cdysS?2-kvgMM5>X|*h zpj5s^yp~eGK7A6YhlYnN>qWN~{&c}q$E{bMu<>#?p9Lpl|CO_M-`#g0{t*TDbo<^E z$1ihgUB$t>A~O?!SRLxa`{Zqc>jx4%L`O9&O3@a~-sw>AX^hSgTPVt$dnPi~!IVdT z%<d8bnbCVe@^>UBr?qTT;5T4qg~6xl-1rH0Pf7OvpUd9d@R+N4?%}q|>w=O%I3v%DU^vyfeih64HLc=p zrk5?pFgncjnQ}xBaTh~14pb6);OOTta9!|WeXW3B?JJ16Kcw##*_V&x1M31qEZ3aG zSCei6)=eUH2Ot<~Uht1u5c+`zaQI0B@~}Q_R*uazXDfTK1W~DUKMm}>8xB@Jl|}d* zBulE7g!D5HT{VYd-Kec*6N@>sp17iWQ6Jg%w;aucMB?c6g)z;6E&30p6@u*rcXnEI z>|2ei(l(-t{G4Xj8KX4Oj(QB?@K74$)Gn^&}&beMk&LqCh5& z7R8;-K3_N`8+DHNvmmQeMoQO$n&4rOYt7*l*0xaApYtQ=i7?eDU!Fr zRgt~6bs`c3Ku7$l7oj*P<29L}6lC5TR^OrBjml6xi2A^U4*7xOp=PXxaND0p5o)0l zkqTryVQthG`cEEJ7poWj(bXbLW}oA|hLh~zcHelm?c}p35g(B{HZ8>B*3R?l!&S7~d-?j!yT6jaa9@eMcu)KazKDpHk3!Y%FbhDVxXMkybTy7t~kJYsP8BI$Mm z{2}>`QMf(Ba&R^ss>R7AfF3oQWG5Uq@Tm#;!Nwt|n6FD$jfuW2M<*v0{HLtF?Ht(b z!jk!hyjFB01a$8;JyO*3N|8^eBC}>mvpQo4gc0rNVsYMViq+b8wdINk&YQ7VsVyV_ z)eB&=K1GLqS{-s$LbwD*Pqwuhp4tzv_-dQQtV;Q65w<}e7D-MsBL=_2bS{?19vDMC z@pxgtYKy#*ZC#{$vRaF*UL|#`=Bk`QrSU4BrqgcfjN>1Do#YfD+OcjJCi{cAAd<=?_V81`4 zQ-Rs_Fg&dluv~=&SXe2`$g5<%>;pDfWPD>HDMteavaniK$!*9^f=%B1kTj;A?vY2a z0Tv#XF=_yZ8)(%S!Y&JK;kgwq2a_!zPpjpJ5~^eFfimB-;2e$>Lz0SwR@4F3NyOoK zPb^U6O>uGE2Lx6oAvCp)^BG@6BRD*`XOsaOhQbrdm_<$s#Vl?IgP?~AEkA@lz|#Q| zFpV|I1Ucq1iA@6@nVETQqiBZ%l6Jfl_?H}6)@nS-H^(2BD=Wu0V(st6=7r_JnyMwPihZw2w0QgML{}%ZRlg@Yr2x4Stl{|I)YLp5uUG% zjz*XtfP7M<23{q0E9OOtqOGR$yiw31Csxr_UjoVuYUD13^=p-DDRvSPB@q0~P7Z!*4>VOFkC9aUUK$>)_T`c&BWF=5{|M9`0+rj{kD z_fO3GCnq|UM+W_%V1|G;&}D|A7;fxrZydN0{*n|&WD=r#2_~3s%E@(2F2GZgcai%0 zeDr+`O_$n>F%;by))%MePV5gI!h>jPIaQ|b3QLNC<-#AyN0*XAU5hOm2^iN8l?!sN)BRAVa0S9wrrdz(n#^P zXpv^%mgvt#fJOywTV#zxkxnc*XIHvmTV_L`j|_r*l!ZVO2-ZTN&T*XreI|~#$T;)& zfjU#onBebtVS2UkuCcSVTbNH`E+=feRWc(+YJFpOZ+E-CvD0|DcOV0}OUr!R6zRwbm!Ff|8Crh;?{r8`+a#~Cs{RRBdM^&lr|V8AH#5@ zqdwZe42RdSWS9h`H6kur=YhfG#o<{~f?7b-!2Zs9L?XCq1_6Z_TU}mWW*-1S*-+T> zwB1Jfff3I}N_5*AksAbt%;S_37+R-X6JiTVj?Bf2s7&T0;Y6Jj6pI|V!dL=oGS#A+ z13KQIQ-x&E!lAlSoCS=vGG}^yWp(wt@18QamDQi{g5jT0{wFjiP!bFHJnxP4oW3Dn z8w@@Bax`e!GbE9f<%fntJ) zI11PUDR1D_m8aI|n%CzTP6;q^7nbG{zchpMX4BqAZ^PdAS4+sGnDL%bR$$mh)hbOn zreX`wryCt|hv+IG>+_^OM(`utA=1mm>}+v9pajEL{ip{+4lz%Z8unWtMmlE+^?|4y z=R^%C0v>1Fqab%fKSqm?imZ%bmXNMNC*_^gYY(E|gPup&X+!~`f)C_7tTTY2({6~D zOs#E@i8-<0a70P0)L_MegbUNl>t>d7_3@MUWi^a#HfO59`(Y_&1FZfC^GYh$Ve+I# zGy+g05S5|_PL`U=PDeR1nuH5TNip>#TtdHF`F>R_0N1d4xU~Ay(!1B?aR&fP+dIMU zhUb11+Y7&ekM<7a#I)EJTWME$N<9i+l^oQBM#XOf{~Snh=UR`A4CT>8{wzQT+yQ2CmAmZWcTb)jY*r}w zSKtGa0Hiy7k9$m}7Ea`XyAn$=ndV)`&7sRfWRK(2E{_6U;EH-RIPp;Elyx5+8#=0h zW^Ex+C#Mz7$Yg_g^7!$?Cv)iOM?x0mHpC7U9Rah%XIyedz(*nz*&=^8za0Q=`CWN> z&lDb;iB2b-4l`59!J?VG7&o#^ zIMa=DDztM)#A8j;JXto|ERT=$atP<*EIdcfRm$!uz=#fCk#ubW20*O*q*e z8a1n&VQ4~AB3Ex|(IL4u=F(`sG^oUVi!>Ht%yN_qztdI>lHWvTEm54fQw{18)A^wL z;842D;~%GD*Zv3IX))hU93>l>6Xv-t9>>ZP0shbeJ+BseGNj$qRb}c?F+{7Fm2dIV zva~8*J+t;f&_ga(FP2{4P;J>zJP<3VcUgDj3NhiN3|0}S&8WDz(J;nzv5GX*rZ`B> z9C~6+c(p~2_OE(s^;36agV~JmyoWhOeBdu7iEjHC8$e&b>JJ`R5rOdfJH%K8R=C(M zx+Hvn4bufC5Oa&SDRMSS-(dgfie zFPVy;BEDmq8Oq00tEVX>tAbxzs4}O%#*|X7vA=cjX6JAryR;THxrKYMHAu>2_c|Lw zLLZ+HdMqp5`dfLRvt=v3x+ec973&Ex(PXg}1<`@hSc}9(A}K(+52;p0E0#jw<<`dL z)_!Ai=Xrg1at0u~v}0_dG&Dr4c!0T-_^I(HwX2-{jE&31^$`x&o_1s902wG zy@P`)YfiQ^5**c>h zUMhO)%TM`tFKUc{#~TFeE9wbatI21pTurH6Z3qRHv!~S&c0`r=e3yp8yo_GP4`EK? z+Jy(J45NFA29Gr0#!FM~A94@GA~Z+y$i89i%^j<5c5SDKs-0bQnTk-CRnM0e@qULfc~k;iyW-Bqzkg}$ z?KgJ!-l`xHj_8fTiLoeO8heJ80~MJmKs5?8r9>|^vABeDgTVn)jhKPcoZy@EXsq&b z?o>H5dOdpv#26q>IRnJ$i|pNaNXe2mEUQxvtbAz6k}kCTddpT7UhLEl{ngzKbXRTn zqCsn+4166~=B__leR@;Cub3Y|ER+i$Va2KBA{o4_i&h6kNn&BSV(+(4$&QtuvUEZ4 zF-DsQ`yfA+5oQ(;Dqnv-7Szm%g;obcXVc4yM}73lWjV|QK#fcEeH3QS09gl@6YAiz0kb%4wP9PZy!+{gF^Id^@30Tw*QR!B7nb5*86$rK>m%G1Kli51-`ZQzWY zQMQ`&qt=r;UcA;dZlSiMN^=(Or=px?O_B-(WFc1$vrnRetD=5xqySfmNiJi)Y<=~= zN=+fWUroK2YyRnK5new`7&6mxtts^d5fzTF*7kunWwmbcVL^G-QYwzDY*Y!Nrjtwq z!(l(p%%$sQb#`maNFB8^C7%L5PUIbBD+zr2hJ~b^()L`4Fh?q2cO>#sy|r8#IVvZ(Jx_5hSh|07P}u zX82`*tue+^;<7_`5po{VhK!dTK^9P|4qBvY<0=`PS|wxAsUD7<*0!HfQ}Ds<$OozQ z6tavyxmm7nCW$JFbkwYpu`+M96oQb36>}nsiZ1Ym$;2v^oX2@pdQnylx=fZ8hH`}2 ziG4@qGc15^vofjDOihoi3|2YQ%LPf>O;WAa%o8r#y4AcZs-Hdm_S*>na53`VT8pAl z1D{!8pC#vT%FR0_2bbK~det!g*M#wx;b|FQaz0;iv5!;IP{K;|^? zeZR@Ij{VNfc@6I-N9(_>p|q0=KGRqly>)fJ<=AP4V0O@h!trrJ5vH9b!Z;0U zdI5zgXT(f}rG<9F2sU{=@4m;#tLiO2X||l7Tp(hF-7Q_O3L?w*3MK=ACo3*?OFyc_ypDIKO0PlUNtRPpvWRx9 zO17LXndf0JEjrC~F<@u%(Su7-LuGm99&kOicoAM~J34VTD3&hpCbB+`Aq*RoC4C9a zNVxVe=+Yvvv+;^7aU-V_;k>fs9ir--Nk2a5lI<1w0wf5qz9Sw z<+f*&GS+8Lw2CY+ceIIE)sWCkZo*scZ>f(?kct6?;1URYJfgZlepL{~`| zw{6=s0XZs~_fAwF&w9ZNWuZR_HILfXJY>6|wQH*4<>DdUKS_ z;U{_L-m`ygZtqXF_pnPVdyiz+bxwq55Ssd3IN}`cHIk&+95-{*>F3%`sKqb!8rgu? z>6J-6^Xj0wxp!bzjFRKgR8iJvW?6~-G>j)1B|1P!+{enU%)Y_w%92I9UNW$Uo{D8H zvWGtkkwXdfq(PvSHs-?DOmj>$EuwU7IwCDDxkhww+r{JooL81KXL4!O1q@K$_U=~W z&F=quvv;_)xu8o_w2`XJTjbf{2xj43sGMnA*Z9z{42HOj+F(q!$8G4?Xl=)T;u|4#co$(j3XCahbF+E6uYcd^)!TTi+soj*NR3 zE*5?-jJqaghP9%UJ;F)xd>JSx%9dsjAV#lnOoYoYCaYx*!At5wKJYz}+_2XQ5aH6x zz%pFLdfMLE7uUhCI*h7kLDj&}CaClCt$2^Y!(`!PkpM{#&gon<$1L=N_vCnc|~g^vs|3o=Q6#CXb)jep$qYJt%u!i&;oWo zaA>FMff9~U119e!5F#>bkX?{A*s_@F1oK|*W}eg=JE=JICdqJ2sBU{yXRowX7>_1T zy>qJVYGDs{dN^!QqE=nW*3Qg}=RQU4r0wdffHf8~L)Ty_5^h7;hAfLbiIpg>Xf`l; z&H@`6HzfX%jmmE7j!K{=%ecez=Ju->G=n(iW0~16;ET{HNpVb0bgaZgItIKi6ZjmB z{jqCqR#d|4e$Pq~YZ0>?^5I17qfm74VhVoBDxE8v-FmUVg+VDPlpXYRokFvjUn#Ps zRAnaiouS%x_-hKuSfXadCjO zc+l}&+~LDyS}ElVbF@kpVR})oC+SGW2{2~>FHipEd-P&l_m+OuJ7I09vb3|mq~o@Z zE9p5=7*U%NV4%VVXDtS9c>R=8pHsG_D!;_*2~ZsY5J^ZbA?p;#f$(Cd5om=TR@R|s zm2>Zu*;kb}Dx+0TqrVac%{9^ohyP-+G1Cuyee<4rY>|(Fc;k4~CAVG9&p`L908>H? zS%L{b4BM*wnN6PHUJIo+1YcJZ3t=s&32)6S3yO50LpgA3Ext|yhuN2ThJE-kpseTs zh;E=xXDL1cR$=~Eb?d!_3m@>;t9nMf<1h~YPBrw`BB|gq?d4S^q9fZ zKWkpuG5hB?>-ffgW!ir5K$(``@D0lp!TPEgf>^feo1p*>=2rN@Q(Ytl(6m~uTEzmshYFXPK0}gYq|ob#Mp3(H*GEWVbtu~(1nuxjH>z)ec$s5cT)52^q=W~f?_d}RsxAA6v=&YB zNSGgE4o};+iamCL>lmu?7^aJoE-^i){OU>$V&ZbyE$Ge_QoNKOUOgoK+?g!OBZ0?0 zz5b=*N4W!TiXR67MuWj`e4Rz}lA9ue8nt0kU}tjCnvaP$-6hobSMprmekUGM>>1!0 zWLLn+%HiyAP97V3B}@>-yvMB;g=g$Gi|4%O1geRZ z+(co-{>J_<4O&rGT8H9G;Oa4S0j$$%?fb{Is|s*`oeppXt1?`f)U~68v`cC(R5wTn zl#e>Vg~td~mZV>h9fnmw0;6aTbR;B%A%~X?#OeIsM6IN9cgv<#L^5$6^aAFslvHLI zNeJ9NMu<7Bl`2ZuNdjHKPNA-$LBmd_aBb?of*?Kwov2Sy;^Lm)2TqqA>v3`b@xv%# zeje7AnP<(s^#}p`^AS>T_^2HnEw2FaaDLTv(hHq!UX;+owb6L7`=;J#0G%c?jRpMx zh|emLX8GXN_U_(3mRlF!e_Jl;q_?6(f;RgBdlOR5TwrfM*6TN-isBA+Z^80bxDu85 zLS?Dt8qXJiP;>=){6U`(&qn0p8AcH=Qeb2J#hw4;d*bIOkBR+@52 z$c#K#6ldgcHSt=7;gBGZsZKX%c8uEK)B!7Y0-GaH$U#z~w?`x}Xpb-_jvGbGE5gDy zpbS#BVb~3%N+2tV8Ywh5$Tt)gSXyfkaH4R+9@SPU1s~>xEK}Gq*tP$_;r;;BPXn^j zOq%yTSx^Aw>IYH3qXR{;ab6s#0CXA%AWXE_rFI=rXK0d*-TdmtE0m6v9dh5K(o#V^vxx#gpzMb z^z<>yrp_k$Pr(j_XJIEGUyPn)9xN5l>wp5s{c8kAW_5Y_TNO6%5$vmW*bHUNKuO$C zP?p#qupSpWje^Q`YEEQ@PGA*waTT~az~j}O81sy*C9+N;-ml$(Zr2(21no?zsP>b|^6tm${fnztZ!Hra1R+Sq_9Jn?p za$jbI%}u*|JG&K%x1!6K*2|U{v^pIxa}#IWy)-!jM!Mp1%;*efI)%S<$MA>h92K+u z(Z}Is=$b*qn>#zMpEyiPae;SXd8t;zsBb8#O-etgdO8`_8H|HWf7eg(D{-R7#gF*p z=JXFq>02F=a;O+=q$sU63GvoM5m7jPg=!kw4L%5;GS_}wY;{OtgE-j0B#W|EfMIP0 zOQ-OUY@A!u1(lc+U!W)%P$e7DRr~6hDq2)y!(GB1lTE9V>bI)F=G*>*tGoi1vJ<<{ z+FBlpG2^%2!AjtdL=b!OR&WX>8zhK|3>+7KR5HMJSkg8MvkA=N@8@84ktuVRC_#ym;L|1GHmq~Jpr|jC z*_077H9nUyGFf+mDzGI0xl}q;0QAavr;=Sl|Ok;;GRv?4Z?Z3tkM_g5e_QvXdF?4A%2?D;BH(XO^!@ za2wSog&1y8+F-XSNH;qUq4AKM6SS=zb^A6fHlZb%7aE(GZeaXC>SWjs1J?A`#Ky&i z&TcYM0Wp48WNK0g4O>Y=?xT$fx>d&C?!hMxz#Mn{X`#aYv>vR;>sO+X$9mUDRZ_71~cI&Oz>pzQb&WXQw6G?gzth z9*w<(<(~E=AtxiUF}JOfTV6P7Jf-z%osX{Wtnc~a_v@LrM&|8$(nT5PN9K}P$vQSP zcB@c2w*Is5vGzrLEjP^GF=PuWG5|&kJ-wpz9neaw)!Xlq(mAR z;oo)!Q0XBs;5N`f<{~WCLqA(TO_y`5d@?y`In1M@mDPtRfU)4=a4dr}^FqfYaZ`9Z zyG_Ea7Iig!v9-%3x={ttnt*-w9XL+5nRO)e)8y%~sFoVY{f#24kLG=5Z%s-wn|4h) z8X5aTjz%#Rlku)>QPz7X)p%9{7g%8Zbb6q<%I9=@tEBBtHK-pSo8qKptUe~CqbZ&7 z^igf4wvs3WPbT+Y?v6>_hto9=z@x5sRC^-OYXP|gjb`p`nk;#*%6Rp4lL$%v#TWtf z=OPrjbBVKe(H~uXkGl!KtSswqE0RLIplI_-`${U=xF7Y%0ZS@$T$>LH%mKH<7D`7u zm)G26<@x7^R9sgGmTe!n_H+afA?_J z^@^A%LR!N830D=Df6RWGvIdQL!4f}+ zIiu5#_Q^vcPO)r#UeX^EsD4kUBX>y#2Y?kc7j6AE^6W) zKYon+KCMS$MGCy85vW_P%=dP5^zdHn8^72h+&?Rm6iRLL%!r4zE2(W=5eu)kDjel* zYv*}+DwXmizIH5!6ha3m0UCax{AWGjR)$euiY78IqgD}jE%gg?A1%xo!!j#=4Dhv$ zPRq3^o14qn7;|i|=f1+u7UtTav#Y1vK(}4JKV##~cpc7IEWN(&veIy{W9z(s=xYii zGrXNmG}h5-`C9i8N2)?gC``i0K|P>kd>Ia#7sL*W9Zo#HSbezqY0-m!h4*Q(+QnPm z>RH?k`}oxQDLm^Up6nPt>-y(mbN%6J^(-8!%~kC&^qvbIz{wZRgLD({%rvr#0%Fw; z{Lqa&d4!;V{;4LOJUX)mz`xSKp@IPpKQ!zokL)p&#}BxN8HB4{A0{?K-ab)gfLlZY zy_p(eOlApaj}lOk{OK^3=EX$olu3}iNtg^nG+I0|c(11ElwhD5b0d-oqalV>XUDKv`pY z_FqF4^H9&{x3Z$_Y1128P1@ub1hI=rAA77Igy{8;Y6aO;9iBBC)=h&0s0?^O9 zvHg5&=YZY2cQ$rkP#oR;jaTTlesoe+aU(Vkpy0xhSSU)DY_zk{X<~Gin6eX{?31AU zsGgj!+M=8aJ9dJJ3UxH$=5lw4jr8p&|Qeh zFrmFbwygl{DTPG+#tHi6RmAa8@np4Jek$VkK;zcYHuVNGH?_sW-|$gcIuByGWnBus z-IT;XlD%}byz{lirKP7!zhXYy#f!_P-^XuDt*7zQ(OPBh1U2aJef{Xy^^?US6y@(w zSkNmOZ}gKG4n*m=R}%2Q(@D3{g!^I9nk}!OBF>Xd{wU^^ry0kEr(3UL(^2j#QyHgk zN)g9^dBT}_0r=ZG1sL1F`s8ILu zLfwU<-BO{E3dT{N%E7>vcs>%b8%VK^^IyxjGnrbn6zY=63FuKP^E2O68%j$Z0jW>DYzT*EOMy&3qI zuFb#X&gX((1KzW2wzrA?@aON!y9l7B**_$EzRMQotvdFe& zILt*DI^H`Lf9qu!nZU!Z5FOt4<>JdB!%hok)S^dtzZ;7Mr@0Gzc}pa@Rk*WS8b*}E z>_M}HL>|^2VhRJC9l#}vE!YZ_NKO`Jc7v3XnF2o9eT4GK`cYdf&m|2QjHGW4{t}zV z6;gZ=lzdx+JZZ0J=KFWyolZ%aPBA>G<8>d!Rmc6_lasqz`>rbaGdqk-jytxlbaeFH z_hbN(c!K`ea}##=oX(j!sW5JNQ`$ap?S`z-1qiF#HaB2NPa#}A8&X%Jzo9lCDFI0P~!!NmLrBUi6kihsoxqFD!@+COMYTh2 zg;MX>aTJcm-nx*laeQ#)C>)8zKFTM(e>NGy?Hml7w{#$#IN?U!hVp<+MH}hxvUVI@S_n%3+10|o)1&)Vk<-}AL@c8eN+2zo8(f~3fCFI3u}DXa{~7^hm{&9VLcH@n9A zK%1_{AsQ;{WQmh3UAxgR8UP-fSU%g3cB%p8BK%TDxG#zG9XAro;*s{(;;Yw-b^?oP zi|h7+rg*CNaOU=#fjg*8vfr)EYLPJp$aFD`G_QoyK#JSA89l76>hF&~kd}Vb3$HGr z3H**+|C`tcRLz1ILpDhN0zEZr|+U@F#+EA7}euI7xQ0Y?6=0&yDdzky7hef zozMxBs6Y11VMI|5y z+&zC@RpvUC{+C$O872V#@LSdst`HE(E?;3*elRBf_5C1uXb04foMgy=x?wPS<~>%>>L zG$0$rDB! zmA*%+@iC5ovK0tSWE<16rR`78pe-}gNeP~FtOAaiM=-FAT-q!U3FPkVSXhskqozYI z&@qO}0mXezKGFm^j7?bds25b^uXsqeb&4{`Ht~llC9ho#tp!!|KBeu2i*ieT3VNQsOQ%J4I>|%15739`1EogvI7};%0_Z`cp8%hco@Y$+rO(uXqn*dbi zbLL?uoeKq=m)d+ehnY>dAzUUmqRUU;j3s`^f*))11};e9nHUSHjpQb(>0#bD%=VMReIqFIk$` zagL$N>TVqTRfVkNW*UK|w_py5N=_~sT~rAXv7L>5rd=GF+eDfQIgRX(dQ&%`@{Xj_ zedz2X6t#k~#4|6jfZxZb9>GY^AqDWD=(jQ&m$a=y^AMeHIFW9sV6xL^H9aXIP-fl_ z95N*`)u|bO-q=xzN^t^TZM=X{*I#V{biM`YCwLD!IyydHT0|9!_;C%tpDdE$Sr!Cf z81#1!laK{Nos?84a$woOa0)eqQDY`^Q9>rGwQR6ffv_FJtL^6p-ctept|ual6kt9m zqjYQ3?Ox;BH<7>Scf#RN2BK+3oEw;WSVdc(j*7JcXd3Ik-aFWSS6k(j=%y~<>lT@I zqoq>BsW76^usdru>`8o@YZ{s#jlhOt`#v*Wh?u)~=eGf^URg`oIoiPyZ)alFaB0yvi@BN&QP zE=j*jr$d?Hm7th#;i>Ubq$(9Rky$SpV+z|7 zE*^X6Ccds(^jT=s>zW~)l(R0k$g?-wJDbyFo14UyViOzt zFB)&RF{3kJs%ocY`BJ>x+IdZR|Bzv=R`JwTb)mT<%O<+64Y!$s(d4wmKmW1zPZ^eX zy%+s+?T3FFUkyti0hC(GB0qf+mV$!(DP(c`G3G*~?!#8XgR$Oejh8p7#M4mdyxCNd zAF*l`R~PDwbGVJh7T24}utPbzf1X{V>C}nqXUf`%#p+^}<72AG?${#5D@5?afzRRD zn?7*eKsw+Y4@U!)vU}8zgJH~338}go;pu`EveNE2`m+4}F?$nKTcUKlyz;no>Ucv= z3FFk!X!5vZRg;!uqsiCcvpDLEhJj+q`PPiL5Q>2VHxl_n>1PIU%V_6I z$F<|ylG3TdLiupGFc$)1Hs=T;57Cn4^pI4vL;1jyo*Je2n`8LJS$l?m8DFn%*fZ%K+OpwR7ie;fzF31*^5x2ZeWkMODz@0 zlX7ZRrMSDIAt7(>_xrxg7DM@ZNdVoGsd|_S&}E$6)-0tS-L|X-}f_jqS3Nof+vW8~!Cvfy~()~C>zEVZ@2zqgOM ziiPn~#1-VQyKs8gluU{cC8vaWl<*KAym@wT2rSelGRUcP;X9jJd2nci@Jbp?%FC1p z(PHqddqC`51YR*)#^5dXt(>?m}sjz2V;ig^Jr=5vvPz>vz7OpL$~;}ja;1B_7`a?Wh_X%*?787qOD z_qMVeX458O>DV6bbwN(Hoi=`dYiDm`Gxx>@WHs_zlyp!Ew&{{E4+x-IRhh5J4}#ys zByx~yNu&3%z|=Cb(Q_xV7M3K-Fso62D6{=ZP|?|cP%uN0u!*hap?6vhEs*#LBd$^>SVZ;oum+WPu5;Et0Q{#RRvFZa@?!a5xnvR}l1 z7?sbpNmqzs#d-Ufv}J;LEhGn<<*z?o~w@OajlRJ)kNfRe!6;zjZBV6daK0A;Hu@*Q} z4NDDibVLe(lM}aQCyJ;lMOmOU18f|lwX_A5PC!QK)L{~m>Iuokp)8`u+4RsxfEvZV zz|9Ra;!-T=(>9F&n#A3TYUdtW8al#hR4l;nl1!(E$#OZfF46B(GlwKFUu5t2MUtG8 zJltfNV1YP_&m+tamzfyXP6Rts=A$-H3GS8?-sjXMC=;%)6b7Z`Z=dlWs;$0CL^ zf@iOGPEHP1X2CtM8s@TN%y=`-z@y?qv6$ zMw;xHvVL`QSMea8;r4iS@XNsxXM|}*v;ko|eNeZS67OH7|B?|)C|^m&B)H?J6d+_~ z0tmuK_LWX8CU7DxQc33XC~*)8>7a8NFn`7^SLnE+)&YYRgI4T>1iw z;+I6(^4yo=Av=u8eXPMOt6&`Mr)!%=A+yEwgK)7LKK$;6Ket=mVX@A z7ZYTst$pBWKVw!P-UupJ@c3n_iGv`JS%qrT?_+lyRe#W}))vtcpcAA<121_nQw?QI z7L4i9RBnL(St3NFG|gJ{k%*}bU>9NgnB*+G660%pFR6Y^X`wBjYf6TLq8H4D6Axjb zjEH6@7?xsnX*-L6I6oUwscu?cZW&Q==f&&oI@z-#Dv&Xq0KZ#dVk^YXmr$vHEj}IBeBuW_HTq!_ ze;^8)fcGhqBuX*?W{(_qSb_9l;TU!Wf-DzxsD`4iL^*9+CQ$?AW8VB4<)W+$XlYx4>7$Z4xI;LL|9TsBxDt4fV8EV~!kMC^FB|Z3aeA->7@h>165U&z7#m`bBA|Fg7 zyV;zkWHgCD^qPZ-*xb_?VLAD z=d9j%6FDMRSfl!F$1#{`N&3xORI->aA&PnedAFZCPsIY$NW! z|6OFlRE8r7^+Q%!$1Ud-TbOGdg1Xse$lOVc<7~sU8j4 zhS92E_mypAgJuQ0uRP1{ZoJuo5%x%6>r~&egy?k}!-%IG-X+acdtI+E-nvxhIroZW zBS3rwk&Of^;Wp$x5Zn%tYSLQ`8^dlNN{~U2TUMI}O>bb7X<}reDj*ufjEMFF{xNEv z3H+to%r!`w#v}>K(4Z{aAwAHPhX@)b$yctm5jjAaf7qbHBxjtX5e(Va*QWu(0*jYqe_4}K?fWCYSD=G06}^;yD*P$o7m z!3fB{VQx{sXETRw36^9Iuq7mT^ery27ftf8$Zc4CMqV${@Q5(~99Kwnsz0eya91_m zDzhs~UbB6V-|L3CX*QBdS5%(xNkHBWV2bxa(6YEpvAtfGXCxG5H4I~>aS4aa%NCd^{fDohsGm{`RraxFf>GrejT_AFv zEF`M&b@wdl#2z}<_uh*tzA#S#(XW*mkTlJbFiz|%pI4Mmd3b9!TBY%+*9B#bZ!i(g z31A_dyRKyc2GlD_s*#{c>xPZVbjldFJ2Z~ajZMv<17+4~xBVu$_w!-^I=7w{MAq|l z4;O?nBQfwEhLcBwr-oLjV?cSdB~}>-YK#`qH+X^E)3_q$NAP3dDApQ{2v#C!G}g$t zSn8>dJpl6ejRRmK4h}Y6Y&CX(kU!rnYcQTw*n?B8+XHgTccr1QpJhRts!zMG#PRX5 z=ZpuD)YT9lPti{VkXhYJ_S>E|j4OSQ!(c<3F}-yf!X(An4Z#s$iAHJb3UB{@r?%*9 zfKmd=7y+2OwO$>lldSoUK^N((g14Bka0G60l7%B5A&W!IvT)2ObVmzEhL~&Ns9#Io z81vTIoH2Yg_Cj6s6;JzQt7;iMZ!_UaJFC6lfY_SU0`Km3-(3l!}w$Qz-h(`C47y%l2ry{7w zUbWM`^wQ-kunw^*Q^XGeC8?k?h#XVFDykw0DLY(vZ+024OTIUqhOagdugG0|=UkAM z5v-2-v%A;WKRn!CI6B;TK@m8{`~PPd$tGcC*@ppiT~3mgaj9^65yeshZiNjhF`3PJ zVZ4LV%kz9u7^1!{4Lp zZ*Ymh@+E~K3r6&QxW)+xxLa>J!$Eje6XNX!aV;`P7l+sfxIJ0o$G`neJT0H_JW88c z(d_tf4BfzBHfMOthB0&J)r6r|7utni_-(y(bo8vg2@3~X>7<0f_R%=8kJCmsHd#*& zNv4&;3qBcSawMM4HFv#EaDfJ_myQ>Xjv5=)fBV(nQEn^0viSD6Obu<4&6}Kxs?22E zG@;~bnMR33|J>dmvP>Q*o}u!t5gUAx4O6o62GoABeQ@|zL%2{XWrN*q4Hnu~IN>!N zP{E>>ZfBPHe|8~T%VQVZ+_%cuAvLW+)_gJ3vZ@p~`Guy@2c_mV z*-)~H=eq}oZ*&pjR@f%?GC&Jg=>oa?2F|ziXhhL%2*-=!xA+(+#@W=;0R{Ga^=FcW zjP*K6?Sp;Z2zF-<2YxR`i!>AxQF5*(CCcJv@&3W_ntU{c#E^M)IDBvj2NWd(k2m>+ z$m0$-nYdp=lz{uF%rW#@{?I4GUb44Pr%k(!bgnCfd1W3+)>-F4FBrgq_WRJL-@K?5 z@(>k@FtI!99-h@|Pv$%O^-$CnWeAqyQb1Q7LAldb7RpbT`XyDaD5q#KqdeN_Lj^4E z%`#IqM#oXh-+rq#0F*LzC=@QPAxkF5v?dVc{3-~)h~knEAL$Cag8x>;!iOkqq0z?j zO(k=Lc5UlB1M-en9U#YlKVBs`-t--|1HOLNzO%-9s_xG^4FEcSCSVi1(wsOJf<;gK|+uZMb* z%L%IpCU_OKmt{>t2^It6Q{WH9wbU5s$`MQUV3DqQ@!WqOkR!SgGx8|>YjMaLjNUalX9Kz&qIs_5 zf@OUyyQ#}bE<;i8nk=-@iKQgB{@?*sX*4i#WfNUI6tW}c;nl&evd78m*EhT^Qz^tNS0`?F9R^_#2-t?3&-Ue zwco}rijSOcQ?$j8;@CTc{{-M4ZxjBrK~M;`1q1H%m8|Fyr2-HMv%v4e#QSTTFn(16BHSL z6_<+ggcEKw2|XQ^nGQjUy`cL7N>K*PQ{!I8=M8#J5u8&}Ln+%#OQcPpvci1WhIg$ddV+6bzqgBas-uylUOY)P@dBWQJH<9DfqUaa&0o{~(IgKv`?5t1%#FdgcarU;-6K z1B!HrxDohjxHGq}m41}3t4f;-J;cHq7&GF(!Ro6ghe|cu{lLmw`B;CGkT|9t?ilNGV0)d7+)zFl`lg# zGv)rb!@2P$Vn$oiUnOq{k+#jLq}sWAL9yN*W*@c|j7M1gKqo=`knS#Ajnjk57*%13 zL;iK)8i3p7EErw}81%*P*RjQ5WAx<3r2@s_1hP69HHR>C!GSrMnP0>@XrDyKoBtLi z^ZFEyF$`5@>25&J-XSxK?!`e%4mv(MIyn*R1%&%ic>k1z|LL%>;-+HHv<$RkSWuf4 ztuYr`o5aX^GtRM@;p1^r3@t7@+;`#TshoEVjY!zqA5bI=UxyQf7NrM_io^iZF1O(G z{jDu{(RjPJ|I^0)9+3KiWUY7^xFr%?>X`*p*k35qTFJmtlh@&?LAqlxa%#sT+O!fc zi{WL&4zRT40jXr6M0yqvyVf&l*}$pNx1Sxb9^=5XpR@Ztyx}kOj>~2Mq_>G0GmDf} zAkhR7!2vtSTIZMlsEuB3?69B~QKp21gfn&Ti}t|Xe!D}5cPh3h>o#RvPvVws3`izK z3Ik>+F6VTtNrsmX4YN8-0OlA@SkVp~po39wJQ>V~O^`KQhFZk6BOMe)#lpbADmtPc zujRvX)VhlC`Qh)6Z58Xl;+E7_U1U~llbu+VOJfExmyV_(%W@OfEwc^MF(*{e&*|7t z?l0M)oMeV!%$a06_SJX+ke$C`BHYPDEho$nFJ4Zhq3C@%k;5WOsxBr--7S;OLu5|e zc+fp|k(bePDVBW9A*kEdZ9JA2X`+#iWlHvN$MwoCV|u2=1gY*({Q4|e;e>uTq9oPM z)Uv0UdRLdiIj$=DemIz=b581y8T*+?8*-N}vxzTSs7tvIkZkrzCmo*1)zzhx(yzDc zQ!AwNl+mv_R_kP~*f^SY*^#Q}afSL}bBa>Tb|_7Db}W0N9@BA$)WO2xP-GPfk4{!x z^>-8tm+!a_9tf?^L0Ml+Vj}9AY8eL;44W=Weev#H8kbHpC8g@yPNg)lxIOHW6l;|V zl9puTB~$t)CCloFjqP{ZF%o9My6=qF7NOlMRDBE-=hCR{(Qg(f6}4&6pfERm-=C?@ zJM@~J3aIDZ@Z6WqLy6&89_ENGcpXqcIR*a_b&SdW%VwcE@G_XGHpASS`?!&Oo3a^RM# z%(qnaA7#v#W#+0DT^T%$bC+dDv~0&T9u)fi$}~ArpRGcO!WP;)2;y47>55jh8tp5l z*Ur?vatm~Sy6`c6Z>)`f>5?6d2F-xYrO6T)gM=uj5RP$r7C>_v67l%dy|CAWyNyW^ z0~HtO`pd~yf-4IAt|iVUR7kmI9dOhYoO56*9t{QiWs`EWvVpll6o%1tWD={8fkmAb z;FD_|h+tkURI9BpMp<~(9}S}_#{?-`@%H7;x3TDp`oE-|&D>Zc8*2k?ZtmC)YH?4Y_l(|F<_2fy=-j$0@oeBD;8$M2fYZ5 zegS&P?fYWuKj;0v)!)s3y?Fgvv?4bMRqEs;o>1;qQ})7bIKv^HJ7BrLbJXcJKv<$p zA!%f6WJc0!9oEzjg*AENw``= zp}5+1$-|uk%pVs>Z5t)6KuQkxdl~Wv|MCc-2|nRQhMkG5WrT<|`x!m5(F_4Sw9S0} zzuk8x!a6Fzc;;kqH;xM>s><%Lfs}R^lCGnM4WxuQt~X8 zX9tx4k&LU7lLyubJ2scYbIna=w+Nk2X1Hcy7d6YJ#WvH|J?jCPtDbGIkpn86W7L1f zHK0l*65p7O)4YfVBjnp;N}gu3f$^0%c^xL|xoTcK`HtOj=EaKv%6wnKs>j52D^o^( zJ8l2GYPAC0BAs$zcd;oMWt`RAL$>!6$0|D!abpmxg9pQ_myw$ z-r%g}i{h)FUv25f^*VmkQ_sm>ExaO^+^bq#^F7Cl$4pD>oUl;Nq@W<_!2{)^H037! ziI1$@qwslt(Y#VH#!v0kZS-lsm?jkXj1lHUmx42(EGa&R4xY z&1@yER};%So1Vj|`W#kOMn;n`vd-_{k_UMDX@2l;376%tYO?)5caUjHGiMW;Pclx^ zoI>9Z{%w;p^_+)dcFxRmVn8S-xhXcIaae!6Y!InfqC)M#`cUj%FIj^9XK%g#FTTCW_rwsgJ!?ED0H{b(ixd%-Xh2eUVZnZ z0TftS_aL{TgURxQ*6x2*vvL0Haw2P>p*v7L$chPIj|*jaGm;S#)w44ypJ#hV`7GG&kpaxR$eT$uapT@f9R|Ekl(WxeWHmTKm zS(oy++brd8{1er>nY@>@62~Z3KieMjkAFMWM0)XH)H@b+n>@o4+QW})-_J&gZKQMi zEjjHR|37(01k^i$0Z5Xh>)sU!jLoC&ci+8tAAA^dGjR^glvDFoG%GBc!?4v;63_hb zb=K8A>$ZKb_w8{v?mOMNEg5f)q;?vn;P%9y=YQYkFZSs=C|SML+N0Xaoo+!6V%-eS zLsXygqZhTIMlr!oCjGAHVbICZgE1B&;mK}1?ax447 zm%#ho#Tm1J&TBz;+`xA2?Xes64&Xjqee({V3z)0r+YVyl0)4n5gQl6J;7z~RU{@YS zS=??f(jcVh7xT8F*X+cEJ%6IY|1XvQUn>88l~Gy1pW^nyOAo=(M)`UdSCOx3g#+kRlq~0G&UWffqU3*TiUw zO*YcA5eBemiF*CVDdu7g;BPky}Px;<8nN3gSfG^%(Uzmiq|@0gx|9XAw05JO&d}XbtU9M)X7>Fn8>Jp$ zLf)QnP45MlaTGt9@!s>3b?>?LdH$ccr;ZhM-h#P8w6u5dd}$>ME!_u8rIUQ!7eG5W zFz0aMA5Fx`dGNeM7+r^x;QtJC;G=r1xzfj1Fgt$bR<1gbyG@kQ2HJA&M`j8S|Q;rIla^4Q!8ij zRJFzja#zLv`S;;JE!o%+{GWRcU+m`;G{C$%DW8-*)i0I3zzQL9G*#m=SjC}=4S(6m z36-F1VBD;6 zg@?`F^Ov3Vv6Csu2M5&aaDF<5NMl+*9)D6SRDSHywCrr}{*;?A!|G}=-I#SKCY%Ua z$s7u-lL3*EO>xSpX$evie<3=uL1wNpzaNv+LK?bQ*-|OYTUJ5~IDt9}j-1Scml(}# z`n)U{_}rufln7O;s`NffYHMqW_&HAN$y^vaiG&s75?v$%?>vWrzB%09Il%NZ8$eqQ zZkN_#d{T^zd>&IK$4EuwQ5r3rPP3im#4Z$fHp^yule3y1s>j-rtnE?}1TlYVtP~r& zuV80~XMhZ1Y`X{hC=7bd07ETi1Wo(IK^;rSrBb|9TNF!6_!W6#d}JD06&*fXhHC_R;B(Cd;eVJt>S(F{!I{;+`;1M%PCc3eN{>R1pk{G~`KRT>L`2doM3@7472`UH%@sO zB+^e>>lFK(J7$c#*XnfW2{O6_BO_^vt^NL-XB6XI!VcRN`yvqLy(BJq1fU0xAWk)@2d*D_Id%%T-!^Qy1XT#0LG%{1QTeKUsMxFc{QWtwzo1^OW9eSsX(n5(KGJ* z&7dk*SLY8>O7TTTH;XnnGDfx{v?HYCnq^>10+GO@I=vZXFbaAIob$?1*GyMry@IXE zf_j$&^e&_Xb*EyXM5a`yCjJG z@0p~@7 zZ5@xgCN+hxu7tAwtFSqU;;22e;?&gC)y?)l`&-fhP0(ep0c<2tBPGnY*?toqhns@d zX{s-xez2sw#Zhz6)(4Lzj->hB_hMmPP6$`FTe_C^>eL3B)FC&UE+#v4AFQv8gjqBu>R{ zGHl{5#@jelr<-}=xJdF{;|!e=3hs~r{2U6vDtI#68BPjN#?rbVT6jGg4y6}aS3+V7 zQ{<7!(y}Y*6C9|)AVhZrgxw3!78`oQyUu2|cQzaQZ+1yWm0Ya}Y?QP!CH{kLO^aMG zD3$^I&DUMtToe z%O>#}5?Cz$fp1p~DEw9X{$Xvowt6fk_W`3py!^KIP}FL*B#>1AvNA1{SAY};s7Ls& zwweJ<^`2~p=#d_RDmmSJDcr_rgk;ikSLX^$$9s099jNwtC_Y?z{kl$KNQTd%Ss(z= zt!wEvC2LF({w^OAqhqz39%$uF^;q&%IpjLM}VVSt$klx zsbD7ufxPV?7)E9zx;@L{Au%>hxC>-?c11J+HL84wxUo&?6`=qne+)67DY`{w$@~qf zMyhcgjR*=fgj%E~qGLq$X=h(332gMWl=MdEj2E`A@iBTQ0A58f%2ULrJcjPNv@vrJ zCvGI!F}mLR&<~RdidXCFaWWo z{?7KZ{f+%!8rz#<#l!qhGuHokYyV(-Z&wt%{(qvuZ6NG#{k+W}2Em6AQP*@(HueSl z*PtXqGy{6o|0wQn?4nODKKNsy*-8LIiMRz%R3EOEa~FIPBU0UQIFE4<968Lj_R5^X zwcWA>%VjIpEJqPI!EpVH*MJfRopu(3VWZZ3DW@#}nwuB@isGPuA)W;oE$Pe$disz5 z49*_@^9(Z&!2$aLv!=$(qDtf%<4qozf2?j8C*2mHJMw930Y5tU5XibAa4qo=umS0- z1mB|EF6W&8Uc|{#?+pQ@-2hW`CnLI89J4*O@^bURNJK5kG~`s(vRt?_rnBSXAoS<*UbPNZ8==)syGX>->{2 z(0dJxVt@$oD*AxEfjcQ>fVZZE<<~4O-`^`O} z=2TWrVZ*`U`v}bT=H9Dnv3MiC5s#L?e15xOQ|K` z!+v{u$8yMbwnbI> zb{GDJuTc~4R-vFH7%D;kz`i%uVMu35rY2ejRF%=SM+XhPU z7m{F=zw#`=@%9eD8m9MQ+Ya$SrzRVG2G}Gl4zs{VFBOYnmi?mIau9*S1k}`3=jfGJq10XG_Rku8;r}l!U4&^z)-{P1g z_xn>Z-NC8;Zk?M?pT6L^na+kzW;9Q&#*32cp|9uDa?l@Fk(X;S$5vvhWI%ZQK(4)4 zx(^ALCQIhxTFlcW(Zw}sA22lo#|h3q%H-l}8FFeR!mdG+f2a%v>H8{g>uLb(;L`Cz zjioD3m$D?r84$S}c%A61iN&Yl=IN9bKlhUGb2;19xH$;>L#fuz?^{||fr-U)*fPK} zDxQSIM;XyR^vy4+;KJnZF>p~cA&ha#=*fq3k{#ugrL`etNf`^M`}5qyn-j8`(~G>+ zQYKH?+-=TRGP3nOAFa=ExbASggt+5eCr{2ahh|PCO4E2*j-q2Fx44ZUDL*lX#(%>@%82(pqOsCCkh#fgDc;+Z*Kx(LTSrbvg;_ z{WL1YY3Z9h6-pe61d>h1KuClcQTNji2`T)u=bK{nxc1#7W!!D-91brmecNj7JGk;j z?W7Hc#O=z8fgp^rWH{h)sc^BRs7snO5R7Tf8r}wC1UGWBSQtiP)IT5iE$ShGISYHE zVaSHXj$wuXh7x$ZU;r>SdTa$+U!9P7b@=_C@&1pM+0dlYK6`0!J`j> zv4$WZXfQj4K?Ka>=h4Rgb=K}I%h!QPvV)P>;Yw10NyeF}O=)$8Paflw@|}{Yq`Q_KAn3MR9%F=&+}Wqmqie;b|OI9hwaS6-xdQJcvklk<`e;lF@vKO1|O$C`9!M#{T?^RCR3 zIc9(2(aSd+nRLTF+geL)zr)8XtD^dn{ylrOcCf#dX-=BiqOqSq7qc~XaFR2vc8rWW zPS_|S9tjp}XZsn^Y_?(;m?)s^YvUBhZ4kCYcA~8AjI-FwF)GbUE~ZtU)!zliV8{%f zUvX*OV#~ai_Oc+Vngb4rRJ@ z5i;>j#g4{ID@Q7Ol7^vF9)_SHf_Mb?^3{hYC!ehEwZ%__Ivz{ZfgCS% zu)|c1G?ubi)H2GO&H~|;qACP)OC2V)W%||IPK95W?Hf+cj7lw|04y2!?~OznHJpxQ zI)y#Xa~P7CD<8VsR8bo1_D9w`zo zsPuyDF%Fyvde&n`LH1`-yTMnUsTvjr`~)gA@Vj{bCZASV1}_*4;LYJ)ot#PAz=C*~ z#ZXkcK<`4>PSs)5g#Do5)Ze|MgE9A2?8U8_cySQY=AQ@k!lNl?dw3ZbjHq%Es z6Fl&zyS%b$jxGJDak7H9u(L43neuf*V*=#9*zXRLHnZ#l z9nP4@H!)Nru_0(+!O-8H^C5&3dJzJ&c zs?e#e=&QB`S~r;LXdFaG9Z)qKggEtDQB^nuQRf3KT7wu|qXHtk0*O*+GUyx*0_-`Q zT?G$cui4jrQx;Rr*u`dH#aMMb6m4Hh@ZdVoLP=^b#;o;@MDP;v49>sxngNjDhEE-Z zC^2zM9aNoyJBqz_Bd zgwPz7Y-*7>Jwn)UyrT6>c=8~=kOY0&CbOKJ;eaq*rIlRQidB8~#erA=dcwBo- z=Zn^EjbG% z8nN2o8hXET6F?NSsRE76=pbS$^W7a#o22pF;+q7jY*)3bn3NDzx%b5j8w{BqEEwYT|Z zXNx1f!YRwLU6@X+ekQxNCUM6}ZzW zoXb3abGavP?lYV@X5gklgd&XzD_s2^aGm#6y&IQ(sJ{hBbgMPXWQNtrNY1F=gQR`#)-fD z6>H?LSR;SM8u@auM&ed@boA(Pw)^w=n@e>dUnF485C-FJp$^9fJ7l?K&h+Mn)v&{9 zXfXE|RwFBA+AR836viV-AEKL+&PYDbbInPcso@c}KLR2r3ejU@=EZtL(otX@m+JhhfRKAj#x-G}F zM%9Hq2eqFaY>L&|YK_G2DgwcXL_jKzZ}Y)}!Em`2vCwEpv2-!i0&HNkVvxX$ZRqpS z5Hls|0E|j_?;I+=icsKb4o$3^k?^#@i!^3h1J9O{Xr6^U_<1jE13V%b3(^3z8L==6 z#ahE*M;X*m&|eOxP_EgN2cw^5i_C7+Ce+n^Ne%HfTV{WXEpxwCar5F0CX*bFdj2rL z6$5ku=t!?C%(31s+&!U>7hqQIi$wGU;iG?v% zvbtTcnkzdrr<^}Th^>Ktj!{vrr=3gd0yAbFT>|^xu|Y5TqpR;T?1It?$eAxlk_I?2 zMK}vHUGW~AN!gWDddW$d?QZT)`5$aykX?J7*Xp)&p-jAi9tjpGIphz7$Hg8 zfJ%mNpd)VI7NN}+Ps%=iE6ZcgpQ!rj*y-9dcLp12`|K%y0NWmU+<}}4<4tvP5Fy8Y*>KOFB?gaQecb7CK>NG`6fbiU?UhZjcOE3#iDR zR65YW4WGgecXhrkX|IJgTsm!)kbkicDeb8>{lz6l3q8Ap7ia>NyeiZ-x{aGB)8ENrhw0YQ|Huq#4po!^d2_ct$(h~>UyDxUO#O~hi!OM;Pt<5Q$(8*-R7Y@2t zm=0WT&`GdyoBtc_$*TWu4u`0u}aPYNG2Zh|xB_DfCcS8zf7U$}x=M~@N^ zz$Yh$@MAuX9K8fZdwz>uFHj0w?P4+(?B4(6Y3-U+Gyeq#cV=D3m>u+AbNp$Ez9J+r zoe&Pq+e6fSoMwa!Kc$Qg6cV8=yl-OhO?-UZ^U^YP@3R+Qbeo@({^wiyi^kcs0s!_Z^GEne_OlIpB67W zB@G0F(*W*lk2)%t7}^3*ymM-tVlp1+=tXgefdEyih1J>kDU4`n?Ckh2@0v72#BL7tdRyb=`+R^m}c3H}E7~QJYW;*tZ;Vd@Pt53&!Z%Qo9i2W$J$Ta#uigR+^leS* zc8`u$mQPOXv^(G0nR#l=?8rd&Dy(qB4O`IFrEJfI?jD?j4eCvXpP3TH`Vh z-SGSZ1GL8>CTCKND8+wwLKy4tUKr>?B{#xwDHK71Yx%uv9aIZ*AaUHR4yI(cA}Vu8 zM~t{-gykw75C@GXj)3DS^&(~B&Mj#um{5p2C4+W$t~n$$$Fw)mUN}Jojz|t3kG2Mb zcdhda)jSzl!<8Jq68DXl{=~ zj<@$^kk!oUmHo;Te0R1i_pX7Yr?MwX5bD2>@n6Vzc4Ryn&X&9Czb)>|jPYJ*SEMp1 zIZ_f5lJr6+X_C43T2edY3nd5msJ3b`htYIP@;&ca}(iK1%*cPR%YYwe4{Bu$+ zY}6aC4qi0&w+`Oy94;K?r-FjA(`Ac7ogdKT2E}xeA&V#vhAjm%{(RhX+ry7bZf@0g z7LHCT;;2KhxA5CC{kL@6ILd}5MR4+z#v1JE348b)N!e8tIU3b(O zhE=&FQaIT(VcFynAtY;qrMxYd7Xf*s4Q+wB<(G!55NrNX%BLe1a%xC2UuXr2V5pi4 zpY}zQI5El|ighWq3%>R{gTQZHi#`e#V|-<}I^Y`N&~Wl0%CG@#Y7m&ZLl%`MyZ&;k z{?qpEi-jXK4tJ3g+livYo~Ri>EeIwE#Wh=0ScH@_m-6B9Kj{@bJ+cv50TugJDtFQ zw^yc&q(tlb!DVONL2b!YUzZ))fQ30_b3DE{l;ZLVzDsb|s~@cH8d_*S*ESNSla4*a zdd(hj&iueKp{HCHv+WEZmmAlhrefW7>BK^hJ=3elKOFykMI0-~g=3F4DSR9ow7U& zI)KMFGZvz1b#m0i37y0Q&e){YF`1~v)LrsCvY*vCpXN-N21B}t(GvWlHLJv{4j$zU_ec1cf_G2Xo9QI|xHLtGQ_e=BUa z0}MmV6R(ar0ZR6_Hl`EP^w+vSWbQ#3`dFhHovjfg7tn#voUshV?SOwy#|ednGT>(_ z(>pb!A=rsw&Sbv0tcFt}wVYOio=oP{i_(o`0nWWxXEYG$*dEHII zzff`jxEKU*l6uW+6~Nq6ef26LtOa=Yi-2;Sabno!h2J|5F#T;TLw92*Ey>f3OkZ4( zj5@VKMh0Zd9JIzxmo&$iVwxy0%MK2kwoTsT;KZ=>>Q>9=3~h>D9lVrDoEyN6u4C^$ zQ^#~rrdr`Iuhm3b2JJ7|rNRT02>2A79$}LiujZr0?8EMnHs_2iOS_ zku?+)ql9f`kq3NqthrIFLeYfP9=3W!Fouy+mSj&^ok*%8GWlf5hcl)m{>ImNN!1u} zelT&1b*OT=du${bDcz+?GQntkfuZ+d`-Q}CsL1Jbm#}%wY>J+dbZzX8NyzJ%-5d~|y4@O(7jKy2!W#k3&4sGDmX-FZhLVz+C6BRNlEo`N{AYH~q^Apx@zvj)@> zJIp=BabE(?3kvheyQ1A2D0M1vPN`PtJ_6*_9`zQEQX_}?J%ZQrjB){7m&O)Kmsp^$ zL^JjJx>u~%Jye7ckk@YxUM|#8@-7ad5%AWWrvms5xPD_da4PC7#g3^!Tr04QbG?bR z_Gq!PYRPf6Qq@^BxgOan5`HEHNm6zR(Cf&{^5uah5{+qTD=O%0=~fsco?Z7aE*VOv z8ybhMi{+=@c=&|jlfdaj8^|Suj2TfD${z>8a5U&GESI0&l(ZlTR_N91?VYWCoL-J_ zZvp_Sb+1SndN{-^2{EO!#{B_vY0~6U3OC#^=$=MbyMUOW0FfOVaaglyKp&lyIho4t z-s@UH3o$mgo^QO_Ib4UmfYX3`LtJtOxp?U;!ZL(oD7hz32(2LwyTDtS2iADDhaazZ zHV(H6)={+|7qo3$kCGa5A3QDccHr&qHTDk=w`EQa=hf@&de-B5V=wFRbNIKhvseG= zzf8JUSnln*ER(MEa$|q9zPAZLnZuJMRPCL;*IT=d0}jAMJ$bd+I5^zj zevLM=q;}d5$RCd_R1{w|yk-dzW{*(`hSXiTkfGNgW{6o4>EM^XhLf-}DJ4y6DN)}x zMsK2p9htzTS}O^Y!t3-R@`QBck)#sEIoP92+?BNCfHYNXMQ$Fd2#hh(D@wkDc{pgl z6Er*t$aK+cvD^iA30}=JoJaidN?D{%P}-^I)Ey;EcXlzS^zt0FjV-_eG;9C-<5(pD zJH~spir@zqtD%Y|OSMXNuCS8PUMmeg4B_bLQT2Om3YnEW^lzL!)Y3lYC)4dk!WqMD zCdTwoi`A2R&w)4f#!Kvm6IR~7LXQce<1%)p102O$PA?JtU9;|U+~7WaN(_!wA$bE) z@^6iGhzCK80JEWq>)z`EQCvfQJ;T%3G+gsEulM)h>AQCcJ_hLr5eWdTicnT&O2S!T zZr8_4mS92@i}ME$+_DEV1C|rj7n&G zErZPplwMXL2Z@#}IKQUYl*h^<&Cmdd{Q9*zP^!d$ha^jJgCzxO8(6sFD zZ5Uum*z`5CziQO7eZr=J-%cXsfwtSVaYmIXK?VyaufQdFh8o>m~G%Ve9~j(YEVKmnW^S!Pba zV)C(FCC4(_F@+oF5bEr~DRTfKUpe;f3OFqL_S)}Hdw)%VnBfMyi>W|+=n+b4bdt6p z$2uge$$na#6;fG2wNy58w#%0&5(&OB$0F->RM)Ty=Ku|>3HQNZ{%EMb7%K(06-L|5P@OuSe;Iy!+X_(x&n z1LCH{?a6GaQIBb4On${A)%DNMp?!xK!X-~;T_p;RMKPOrFsvDqMI&w?__N*W6W3?^ z0`FXdotr%wQA=v$J~p*P2n|&mw}<-tbc^BRS)hC-c7;S z^~tr%6gm+K)UWIH#D@?nTw$su@sd29}R; zJw!0fu(p7=z?|)z3s-^x+C)Nvu*VTpm43N%ow!H8;LC+;sp}fdCygHyuyyz$?5lji zcX`YFZDx4tsy$tI=P|Rg81=QZ5sg1&0#<`ml$k0r%c!%2?V;<}FM{TKY)I846eVp) zWG)j5e$csA`b{ItRP)X<8YK1-|Fi1jEI^cDr^t|S@k&dAO+>)T-ZM8bPIAyQrD*C! z@vuei8h!X3^c%`3E5m&QDnx^zCKg`3GWNc1 zSR@OU-)n}b>y}5R6}AvN>R@kGVzH~r7!Mc(VC#(OG^%(%_#NSK&@2kBS4H$wC5!3~ z2BxcGnq-oo070PWLu9910(9m8FNq&SGLM4Lf75dPaIA5tUMbOaCm>A8DwXPnZqzX^ zp1udViW}2fuY|>DSccWSK=#UPus$>7SbQG>bhBYLOJU)J5k?cuDG?7F7|Lk_`9Otv zwWc3s+LtWQ8!|q|$FL7!P!fN4#K_)y?c!!Xm%PZ#kA+yAsl+`H{m)A^BFdIM)UOsu+8+!svWritZaFL zqHLTuq;iPJiA83qlz61lYywUmMMxS%{a_%+qx|luD_L7U&k<9YSY|2x5B_E8fLH~T z!pWq6+unHcs3L8JaY=*jG8X93HNnc-X)3barMt1JXk_+N$5sT^AfRS zCRlYCTTwzNE(b>^gq_)zmWXn!74E>>PNjNw7M^qaYJ1l*?*$puJd@?05WsE5JfGt# zO^Q@8Q>+T7uxoVP&F1DUhj7%3sDD>>3)U3Mhs}#-G7;ZP2CG=z-G_<#kWihF0QcE}IIHfv)>}ZRyu1Jyr z{#CN~*EmBMCuph*%PU&HgeTAPi&COL2`*&bid+Pk*LpLNU!#=4KZo(i?`!~-0`{>Y zewMZwk86+VK;jvGyhC5NH>$|cJqw1ucqsORPT=$Ah1=vs^q#I`jILkQC=PBrLXo|c z+L3XHjJ!l!-<`%6HmNnI;uceyfNamA4LP&e*{ijK{ViG6*#p)Oo6OHDMnb*<4q3^f ze{fRc04Y1?@RcQOe<%{T=%`Y`dC2NLycbz;IBIYcBNi+)%EU{nOYm^W_Dl4c^4okP3OS9_apcD7i&4reyI`_qX{&twPJBm!M4@nXuyULj|0 z#tWL$X|9x1I3-9adB-fYby#k%loF_%S`n4ALzc4*)|FKCxH)EWtH{(DPYGLywWo06 zPfe%no5I?0Dpr(*RdR2R(_rS?gice=lxr%{=Gqd;o08!2x3O3KU2u3fFI_8dfnjD~ zg`JU?KF@-WTem4!$jhWNcR8yH0v%cBnCcnKI-$2)UggUvfE2+`*l=45A^``5F#sKta$feR|$M-?^2OF9jhvdcd=- zWI(-~1N=vE12EXeeuKpcIk^upz&0|T8QBrJpQT)`O?_2S>I7_x2vhxFZUc(5XEaj! z!dF@o=KeB7an3Mat1SZVXlLoA=BC`ai7VT@_*VqikPG0hn{bHE{N{!D$A1QA5C3_F zvU8Z&A2|9pMH!V-Ku)R1^AiB0nbYklulrUI2LssHT-zuJVOK#Bk|j@>5CzpCJ~T3G z>c$LRbygmSv}jtTV~`657mdLvwnPvtxM(&TXbVOSgf?5r0>v5RH3=XGE9JU_ac?QCK^#{sU~Djw% zHRmrae;~2$;KJ|6QR~{mv*cp2vHx~^R~eW--`Y5Qv%kgenHGs@osX`jConbalvx80Xkaa9R%J~rIDvKU`s>0c$fixu*15)n{5{-fI0z>BCQw-e}_nE$) z_eNIN%=3%>=<56I*_i6a``~P{1>XdL{#sU@sl>Hg_oqEfDl|CRg3_o+Mh%4na07=w zVgGSPH)#wjMH5-2R2EldHKniO(_*uF-O=vd%F<-~=5cH>5?IAgH9vvr!fb+>1{Ps_9J@_#0vRz6n#odj>6r}qw71Nt;g29+9 zm#B3}w-lw`_51yR#UA9@ap{wr5Uc{CCDteFu>gudb-$vhCIKuFZJDft$jHkbPwYhe zMon*@{D>0Jw5(6gVjO8l)@$h_aE_sBIGT^G6m?837?=*x6b7+7Be{lj6nF;~ZT)mX zZQ}{%bY;BHY#D>P)2FoR>z?jYc+P#3TGr(Yu=K#!ss*LbVqMG z4M&G8!pidEC;D8;usF0GGANitrm*dH?8JB&DNZ8WW~SL6xr7u4)%O>lJX-vOYMsOe zPi%j~Pv40{$$;!kxV0|hx<0PsQ@CVLDn2fKNX7_e?10UMjW0jOjw`R?j4Yht&T{!T zyGSncmNPf51>-b~-Iur-`lhAyCX>TeJIpfnoI<*$xVgOS?svw&r7S~Ic?j;Iqx_JR ztGNE`ob;J{f1f=cLlHmQ2#gu;-MC)~;%;oO*0kmEyIjEN^zOvrDy8xrSz8I_jy$b| z;xe=J@V>d&ubzp`7lw^tTNN^y%+J`^JOg#+pwB7K_gIeiOW;)(J7wY5&oGiNhj`P& z`yxa8l9)L;M1!G;!Au!h&dP2~!*Hl}Cf_W=9y)bh9UVPXZYoo7u(PB)zMW69NpU%I z7CJOeofj|t=KD4BvEl)WhqWt;v)1%`XfvvUmEguv8CoelhLn3#LMwo?&7PZCVG;*y z7=(fGhiH&U+8v6xA{Lh6y2gLv>>A<7qg5u_sUxtU81f?ga`gPhVzi|iZP5aS~Nt${}6>OBAPVle%Qn)*#oE(bt?#G_3;z& zQ~0dvcfxZFaAS4;EEry*=4AQmu^I!mwS4vD`SUve#3sSAMNDDqdR6 znWLIyFn`?h&@-Y6RK|ATGt8OBMS%WIaW9cc*AY2nJ=4~LqHfs*D?zls6vnCdP+So3;wjsI_Y&5d$CfCiT%C?pW8^Y|H z5*Z*?)lvzR!;nP*rSlaFa6gA{9glA6FJD*Rykiff0e3$`mN1OSido(Vs1zkIR?&fh zmuwFMovW3g%=O2?&AymY*9boA>&dAa)iM)lu* z_4kiACnv|{rDObCSvto;r%xG$hi3{NDPS}p514o!kEF~akPf-!1f7$15D%S1)(p2RKo~k66*8EBROaAy@D}SUdHb(YXjVRlD zH&hKULa<>6UGyK%uJCnAEN|&)l$2B?fZQ@_+Wm6y&)E1olZ^-J=W_8g@z@gbcn%vr z!)CvUq&=WdO_fnD(=qoqJA{$t_M{N|D)pVP~(7B0Bl=?2g z!DU*l6edNWN!(dM*CIIf1MzKbg)&^IqwWtnA%*E7zhi_)CsxA3;~WQ_5BliQUgq#_ zKg&4yRy-F^d6Iuy^JY{-X{o^H512SNouK0jb?bHk66fY@g&+C!Tl)$F3I&(SE*SrY z-F_p46S+QC-!P|S^QL@BR6}*(OW5X|E&ZKgX-i&F0YxXzDP=zQx{UYLg}W}9nZaqz zgufzeo`f>NPm+P;2Vay0(s38l5{>>j+=0-o>b%+Sr)*YVLoYjI`#gw7eTNF9QJ2A5 ziwN~t938DxAD^5c_(g(m9%Y&7*ctc~bKUR2EUzC*2~Z7w`~ho@tizxU909$?C)9(g zf}qevwQ2-OaEwtup(=?YZ&STrRq%1SZxN_^Bttx|>xjqdi8!T*FbX6^$`QwlwFr5J z-JR8g*QZ`7W28Cs^0SVXNiL-Wu!flQ6eR+kRd|Y_5m({-}dgh59Lzq;Mgly8p>!Ror(0{{EJYk^`Y7;L5|GmqH z&c@nJKTThHv;7JEyr;Edi@@9Q2bqG>uZ2rEaQ1N4EF-j_D4Cpk zq~&r-F23+^+Lx6L#d&B`+&_K>{3ifRa$IiN&Yl=IJ!G z?rpC5xtz)>hkutFD8C1Z6|yW0=ZyJ8O5iDH>G5xt4B=qZI~H{#DVP`VghUXJYu{%q zWNuWf>hBnaZOW@Cb?QZ4WVGtVXSC{_o_F}7{hN`g&Kk}{CSl)2Nq6OPlkDnKF&*Dq z{oP`FKYjXAY;StZV={kIKpuT0&~1t=rc_b|3{1sg{Z&psQ}}NBI|JuZrQhLzs5SK_ zml;4rRb-+lM~Gv>{(Tlz3VR5Is!_!->s=00BGomDQ^sCWO$-*o7F(>lvMM%71Vts=*R6F<| zd|O-dO7`Yh>AhvS?{7jE2WFs;dq)HQ@;^<;f z*Cn{6#S=Ww@3zP@x+_mUC!b4_X*0|Bpo!EI{=4u_^U=onAn2<%r^M*kL6oDo>O@oa z)V8U8SM6i+iGI_|iLU&o$%3b_NXr-0P38b8tX0v~a*(^$z&b+V38Z^_!^Yd6$Of4n8yE)t#i#KE3W7%iXQ7YeuHJlS} zU|N9V;5hdNbA0#hN?O))N=2Nn>+ZC+^1_;)(qW2!t9vT&Agr&OZnBUVzrA-kYAB=-?-UHb7n{| zLlk73W=OA3Nj65gz}mw5CKlhs$HzTSNF4x7BNr6jaWQ1!G;{$SLs=m9hv|$A`Ri4s z{>>`ul(H8sYt262lJPDMd&q3)U5xz`f8J`kQ-g8XWS?$#P*d92x!Ft}{?g9=rJa@9 zS^Wb_!|$~_t84$8w6){>fDtWB=lXlkOid;um1d=G={x(S*r2c35qZuH+45g7t6dYI z;WiWeXU?xhk?zyn;WqT`UMSo>(YPt7+~>+I&y2!X6O*VP-&XCFab%~7N*|Bl;6A!# z6cVYCd{n#oA{XoqCC8C1?TngX>x(q|XXZ0dApq{UKC2b+xOPQ{upVGkD9X8tMyJC1 zo8)BV1YwxjO64v#DxcFx<<@pn>ZX@%A!Q3RlO|HCW}Y!r@(wwEa+o;0O5E>0$Bg~q z-qvQ8izaPiW>SBp^N_3Qk%wdzvyh`F7Fu2<9@T(BcBM9RbYU_SuQdqK)Qcqe@bC-| z2nQ^S1}!NwhmWXF1inH5FmNwt)*TWVJ+1yOER}Id(=I-ZDp6bLq`s3>Q-XOB1*rm9@oCj$tXFNc8|ZQsk!~k zdu2A^?Vm+z=W?^CDf$XS)716z(p28K_i#PCw+q@-SG3P`NmG|+Cs^9NI4AAiw^Gtc zvor{P8->vQ)9Q~pn2fa7D+wb&)H@)!cEiCJ|INB8$?9tK6GKYy6!K+JrMTMKu!`kYH$F*fFxcbOS zQaAV$yP;^A#Px{4$V{sSpYxPG<6}cmNPN6LM!C53b<%u2qBr z#@D22U?33AK20|nt)5aL$}zuoEdGNx9sdllHfGaSB0y>c0ZPj;jpp|at z8t$mu7>=t1L;|B|(QQ}f;0)Ag@pw~!@r!75exVvg#V)1{hOcbj?dw=yB!~!E?Hh}W z!2fVvy?|i{)Dd_jr_c>KJ{^{Ef+yu`^i(Cvq!4Gv2+xjK^f?3S?`H?opP(Wst+~a= zgrl9+p`taMfI0LuwNO9wVZ5{_!Xs)L3es(!LF?>*o}Gz z!>C_<^A4X2z|YJ7^XiokSC`S?{g>6aeVNAepy}I2z47YcMPq;K;LXnA!cj37$_aN) z3cPZQvG@x`V?d}IXQPl_z62SDuIa+s4mZ8;4@+ z)$7B({WbNJZJfdwTL;G9@5iGKC&oj1FXgrE2NUy3<53YK#xQ<5ReJ{Ec!Ih6hU4f&UBEIy=3JdM) zYc)OAgI^9BFSj>0w=l*0v(2s7oLXMJuJ65iy}h%w-*~-U&wf#F>}9`r4*xcG_Ub>m z5M?6!gO|{p`v$wR`OEIctL?fhl~wWO#{On~Z*vQ~i*$*~Sgr3q-+m$MwL`Qq*H#w_ zXVF^L>+8i1pgtdPX1xv%b~fwp-mSw@(|7Zd9=x!Nzo7DVbX5JydI&|}Y4byasHueR zJV}-?U{VDJ(YXZMyt>k0%+sur*}XDz0>=pJ_`u2y8_>H(Fc?GwPyCI<%Y_1*&7F|)NCl$p7|*?)@t+|&SSxfN z0W;Pf^%jn@r{$zlID#@#9>}Hepu9QU-hth}^?U;m;lW9{)$2f;oA$8LO0wfO(G$Fl zNqZ>vF1gK^fVc1tM@_ne)>^?0_~?YwMa1U3PsZC#6(9ilH8b95CIKd?!I?%IChb6> z0E3k2pGrfzW00jKY}&Bf=fIB?01|g=1KDDMNVY=N)cqNB_?9$ECjHaJ|`|VUsGhYyo&VZB+aeiTJDj!jo4Sr$CdMY0@ zuI_m-SbQXW`NUseRwAKbI2tG}681n=uj-$%Q@88Vi~7H&>JzVv;HAP1@Daeu#ZW5& z54aTVk~4px*N?iuYY1O&oHZ-cX1xtk#Cp@A#juU6-r@c)jjf+Ib{1fCvX!z@eY zyp+ccv~rfLCnBUiIe!En{0@-c9I?7bjv%yRd`-ei%;8jbP%u^9r++(!VTXaCR9rJ4_5;OPsyuM=l}-TKM-S!d4tgzVTK@ zi~jXuAHE@i4tpb=(_QMzsDOHgx`0G;UNLt@6IyO-n&!+L@%4?P+7Hm{PVXwUGjIZ8 zh47m=gNmL;QlmGISDz0d(i5B)*fng=5eP-~gx?tie(Tz;uWDljx+---=0Re1I53w5 z<*6W31rlS=su$bAyf`gYb-cwhqugZDVz2lSm*WOLZak`NDK%$-GHqG34okEswH_o( zVfziQ+VOaCSwh+)(Iri^dc=phGNvL$B{Y1|1xwLfsvaQYR<(92-fUm*?H{5P49MbO07O8hI^hG;lkR7+v;hoJ)1e}`IQ%`a;f14= zb~=^kS5qs>jr&;0)X3}*2N#k6&LxtjmZ)`nso_ViqW<6k2Vn3C&%w!NhUx;@8ceMz z1x4Yog7=z|R1pma_^)^V;DLt}X!CIY5GOi+m(s0m>_*8gp{)pMiu$*JM>HL`qi z5lQ*n=Lm1%Ls+-75#Hgxl8sB>;NDzNOPR;9@v72_HgOH7HHy)VOya#;;XujVG@F2; z?&3YD#uDV_R()rI z1!FmV!FNDiX?cziHE_hSh_)@4gPnDDo$x3p;V_wgXGw=)O;a6kX`s{W%;MSDkDsvF1#7W$+30^ThgN#*C({{G%R z&MT^8T49U=WGswW9VWsWMZviWzym9u+&lgacdmE6NFQpE0TYi|KkBEuU?yERNFqMJ zNyfF+mD(e51}xoqC}&^EW8zu8R=S{xy=ELbWec&t=)s3)4BBZ8M( zJ@S#!msX_ws4rq2tCG7jJM4?+a|vu{EKo?Z%Rx9y$Sd7$L77u|FDWIrL}D6nXTbFBZ~ebF+xuII2_$WhR>!?L zc)4H(2opQ4MblIUQ*J3VHEXz5BAMXwj8E)B&a8!$^gJJgmq_K_?em`Eo9gQ9v6U;XiZst;GKO) zXbHi_Dp#tMG`9kvtX;~fiuka=YKiAIvSXV|v>`%s55ejIgW_O`-@|C^`9lnhn6Eh+ z3>fXPppb;qejgLL;+Iax(lSWb745H5K^VaHDE1!hOGo`7V^6qb4EY`sbalLRRHsJ0 zs_dv01JH2!2?~~C@X@29707r(lJgL(L00g17THE3Pq)189jEnv%DgG1$MXskS|(k;x8Kk|KMz_i$szTEaVf>3A+p0mOR%FYbQnHb zhzKC*xbfnpvk2#(TuN}v+lt#JnIn|3vyFo-v{hL+(ndmLaK{I)GVcYA)SBtsYD6Q3vP@8#J+F zPLz1>mBv~@NL8E$P$lnl7xCJ4AZ0@1#tAnhcbrOCmNy_Oby6N{Eegmc`TGBawdnt> zIcSD~Cs7_lhP;&NWCm9<#%j{s^%4S%x_kFci!bV5h4i96gYcrBlwH&lqKmpKxu{PN zT-0ZhTh#ACY*EjYTGXc(THIP@@pTI<>J#M^^?Y%~U$Tn7WEFqOD()t$Xl9EliXY)i zyV;20>D92>zL{2Zk%aeWNG|IC`+|%5Uvi7T9MH|4re>|5aDmJIOxk(}+ImNy!I2eo_C|=Q9Gp z_ZYzBU;YPQ$Ewt1R`QHr*X7#GNAh;9F4yQR=G?9i-~^7pFwpojuMGczH&fmcGJwo* zPned^9n0lfj&C>Kc&HW+o6EtL9Dh3P()Ce!&`HcpW}(Q(E*y|(?da&_1o^!WW$4CJ zaZ|#c+!v>t=5uG|a&vjyJPvnO{x-$krg&TYg4lpKT-dKw@4WdRU~wG=cPs;&OLoTd zwex_-{v}$lUPwlQD@-?{JY0aUKrDxE@p`G8IAtmsj;<8;YEw(6ZX;MIOklg6wcFim z>>nO(OXQtHeR62ec*>JUccvgK38I3&6ABLj=K(ALY^W41Nl_AqG8mNSl7{`yCuzm^ zZ^K>--J39e79q~Bnl9|;30)Og*ssq@753}dG-1%3k|Lx4d|`S}f?FBZc(nyI{v&;C zA8x%8-rr%+eXk-`mX|AnnD?zsiKp*IF?bi}^vC;)4rI^)CIb8Qst25Y3l7`NbRZYq z+ah2S_(b1fnvKYc4nG0&u4Uu46e>$1yYZ-P-(h+!4lbeYGukJc%i}O1VOwdt%nRZE zgudG)PmW%>W!(pKIY0n(G8%__dpmF${8vQ)k*+AQ1he^9M83&6XoR~)Mp&KvksI|hzo5se@_QnB?J266s z-@UCeFAY}e^9MHETV*BR~v%wUdm@q-_BD7cATBEskx z;egVhX&3oYERb(V5;N1mBq38{;+Kk+rCvWbuZ=DlpOMrLzpPVdRb%YRzzvey0&IOw z$gbtq$T5&#IH2oJ#I6}6$#G$9xj=eiYkv!{_po`Pv5_hKJkcU7WH9hMQaf)|!?oRw zdR3Uz0R5e+LF*hAMy-X)n22n~kcKCH+EMvWLKff|3i{0PKzU2rTVn6ozc$~zy5~)S z$;C$9d)ybYm+A8+UsP0+718!PaZt9lfGk40Kz?6W9dwsQw_;XOdcMots#u5C#!RcK zlb+dwt`GwQW6=M(xS=aP;NcGXN6{G!Q%&vk%Qz@&2Po(i_U z5-%7LLqbMJ6#jl(36 zSP~8ex@-kKJcHeEIFxavC?5+k#pJq(xlZQ=t&2W0P|<=9i}x0tp4drT9~nFxva%1C zkxoF`MP-WvoSg<|0#glCm=*w}DsyL1iy>oTp#VSd@!m4_Z@yq{9cMZU%EZRVzj;f? zYHh}>Hy+>(sMx?*KURo4fDC|v07nrfWgQTfv5*5fk5P0Q+^N_ewuTSR;R}XtJH$z3 z#f%J!PyBDtD$!X1tV51?y1wii%qCoMV&>GgpC7Cj;h(31z9B|}p1t1K-vF+zK%TyH~&gpP)>s zB#QD82QF*qJ6Npiab6Zbwu|+3N0y4F*`ftLsUzZ2F$y)WJ7kpNO$0^Vp2wXZr(mLvtv5xY(0Zebt27&*+Aa}#%1>NHZqreJgHMD2M`EG_f>~hGN zu9Zsyo+aiIp!KtX0dGjUKAhYien>vHmX17+m;B<=QVHh4Drj{EV~xOdM~w_xg`QN6 zyqF5uRh`1~D1=yECVEcjiPN3O0R|1}a{LpFP)OXCQT`RJjUuY&Lx6(&%)qrb(rIwj zAGlQ>h?UcV#1Pp4i~1Zo_`sY_yM}o=X6cPvcot?(>t&PJsFpM!`N(yj_c#9*H%0Mkh)dM(u zaAu!HqX96@aJb(cZ0mkuEXjF%h@1$8*XLMPKm&of1a{FMjs`(0@Mu=&GKqS+D|X&M zYLL4F48>rCF6StVJw%6Z^-lGna21CQf`KCP1-9TFb-UN=p1*Xq)bt8kyZuqWo1b4? zx~W(XzFAtlsn{jHkqSrr?%h;`GCf)s%?iM+s3&LyfN}Loyyq7d#0nk-Q7*$#|4po# zVyYAK8t#opWgeGAS^Qv7BH>7^29?anU)ll?=?;4nBs@LLKZ%5JknLl`nqC`@co%z2%6*A%=Fz*l6kBdjEC!RGC zPzr@RPz%b!4Ddwd%tNx#tl3DE88;_MaHV8rnjgSq3u58b#`ezoljWx{7dSZlStgr^ zt8kcFH;vgkn8zK;uhYLOXq0|Rmq`_Q!dz0+d;GqP|4djBD(tarq98TpThHp77!GA1 zHV*3B+Z-)~qi4MPG=y_5O2;e9Dp9D&#IA+EPh@5u)oi3VazsTVzW4>$kf=el) z!KpSNs67cne>WghH3q@}8HBnbX5w?lQv;A4zkj})i|OIHMC8btxtN@_N4;T8cNRpS z5{vVGQeuJ>GEX&bqKRoV!WL$57|WX1`o}-SF;?H&dye_gykfI`jw&6}RbXSt+LLsj z6g_<0(5e;9!+{mVU?wQ;C(TJ0I2V@es7f#fR4#Jr7>tIC9w-&z0~^2b`t{cCrjS8> zfHaIcLn33^a0kyXKgUwLd%K(4`+z@Q?`+h!UTy6j0-tVoaG_lISWq@~A6IU4tfVE_ zoOa0u1H~wcD@aL-A6EglOZ%@yA#zJURK;j#-smaP(Wr2a3hpD>E9arz0itc51xz&y zTf+rBcJlkd0Bw{L{h`cm_8f(1lZ<(L0G!%N7#$t%Olv43Pz$#vW>`+DX#R2+H*;wd zm2(!_Ed+FG6iB;ezMlboN-vp5)zoCH=@H>%I>X5Y??O*3AA;XTof<9yYiU*b*!Mvn zg@wK5#USd1zhgo@yms1sl*Z%^;2Qe(h@jmLo0u5xx?(azi56Vo&M6mdL>BQVL)FND zqlmLON3=$0xS-P38o46yuF`WWf1iEnGc?P=K*@NYdI^NB9bSoe)W#1voAg?|-rst@ z{f?&g;LUUV8nxTF(5M}xxc;dEv}j~i$T8w6^W+&D6T&Vy53V@on~%Zvjo7t<-1Y^! zWWd>L!WMvYb>4%YxE2buf32bVDqtBvX+diX@Qia~(QK0>f~Ed47QBze%5t^L;N=p* zk#D_^FT~^8YHj6_5wyW}DSmwSP4Sl-i|_+$gyC%kkNX$$8Y2)<97>@xI{I`29#|Zq zdjyPzB=m43qXBfBgCWaOEVr+z1=QVBD~Jm{=4Iydd0h4zZ{~Wy{NwJsvGz*T2L=(2 z!LZ=|bkMPWir?08BY(5Lc$0qX56E}q+Xz49^@XNS|=)-ie^MB-@u!j zTJa;BKHTUtRHiF)MunS98gxbIpK~x(qd}EzE(+E=d+7AU>BQm<^uvM&TnK6N;a^zr zuvtZ?95jTr-r5l9iG~OltK!k(3EZpf8AB1day~sc+=ojHoeKZ00AE^qu|G*GZpaenmrGOl*pVd zH1y$3An8+*EuzaUo<{uHExfdl{qCb0=#NYgi zTj!f^Jo)n&{;-MTB0M{_5c@s1lW4>1?AK7V$c8b`J zYX!?WpzlC{^V=!KOUE^s_8LrkaS15&Qt9-*h%{>jyyDS6Puw}WZ!)bLS~>B=n(%6i zo>;XcaVVW5HCNZaLNjQrduo$)4phu1HX-@Dl}JNY{ooJyu7`?6e)RLk&YLYolJNn> zJ4VroGU|mQ`)YohP+TOi`C`jM-}|{G5z~3{rjDGJ_rJF5VePxf*dZ# zqh53p@Z z`(kIS!NnI|ZPfSos>nc81V5r5Q>FAXGEv~pU;Gbj0pU{)t6Fj%&7h^ZuzZs?=GvB80^NVdV0-KW;KxJy@yOZ2 zZ+3UK4i036gRJ@3**-Y5`*nv|a3?^GQ+m&$OS>|q3ww6!bO21xl(!5zEhHw!9gUnF zjEn9!FSx`WwEz$i*+RoEA&8ZBHQV-uTmn7eGVEEU=~SW}J&g%ws+8MB8%7qI2qj*QBnmdlUh z2(D{T1fUR^G96+;h2OhYJN<%CO9rNDcF0d1>$ADM#LaN{w|BQ(6ecfkfD@lu;tfhz zLs!2uCXi(1C-H(r3Y^q09Hx?{n&~_tb3ucQ5$%Qqp-62UTv97>51N0Vk{Z6D zaSK@x;jR4uy=^Eg3@h=V>pseHh>wfma$7^$P`k{c*@#jYsr9);5&_(R1jPwQLQK^v zvXFr3f;eh*BH;D#oAmDI2OJgRq&ykGW!QVTT5WYY77Tg@kUAC^Gg6Xk2{JkkFe2Th zk9M)_M1{;~G(wxra6k&psE;CN6dm*>7bHbPGRrF_N+I!?oUSenqXbY z6?u47a2k6YM?nHR<){cH=-fb@N>B8vdWfCu!#O}&d#Pdtal{7doyu||fk_|D7`aT@ zwJ8=uMsjf5Cbk6m?A?uLfS(RtZtRow(PU`sY^q>0yH3gdf9b1edA-;sE45iC`c7n$3D9QDZ(AgZ{L)px5?zl8xmueQ6$z zSPo6N(*35vFh0?JETjfE4K_k^AhKwBqq>1!bJFBzb7$}M7Og`P6{jJSb>Qaq#*5v( z186$Jn0di4z{As@XVm0Xia!XsnjA_v3gc>v38>E2gzljny+Z!_%*W# zKp{;4$WzipEuzFlaHnrxpF>5fLt|-`b7IZD`Vxm$xAw))tu5vp#Yu0;tWX8w#LeA}dVFEjF<)bquvdAnhi!}yxBdLUW3MQ$ z_z^yC63$T-?eK%C%-@qolNmZWddzWc3$AAcf_qnlT2g)7w{q2{CdvxmCcTRAF9SBe zumZfP1#>~>ud@{}i*YRn6_f!v@H4i!9K+}@(-wQ{CX62!yHGL0PA>}MDfXCq#ljJV z*apDk`LxM5l!c>S#2l@0u87wP4hl@2_Iz^Sq`n2nRwsZ3)iL&@*}G|CbNgWGHj=|C zCwb0S$sUW;C>DzU#6dfil6?^Aj>&4bCMOv^lMX6Qp>$7(;3Oyx-3jl7;_wYLMR6p- zp|@#*BOiZRg2VUVe1b#oZ%c6G&3h8Tp<=lNCmBdIm*6;Ey-$LpqeEs992FunNpNz4 zjs7pw8xuwI-sla3%wOgldJ{3tacGSe15Kbc=`f^8T0=dUL~HV;PP5XQage5`HTt06 zn%1cBr}?yIiZ+tN8bfO&G?5y`SXyJ(av$Cwtbh_^fgoY)0?5sRidlzMUOztKk%bLuOG9QHTwa#h{8B30U;h+K z58X#Q%RIn0tp$ng!e^RW(mB!6$#kx%oP%xt8ujh=a@usmN$2mUnKu}BJoRo3HU9*B zkv##^2 zPken-xOlR+zqLK{jL$jMQDXq_9A_Qn`f9Swhd5tQmiZzreQ;yl_dK=HAS!!on+s4D zc;g9+NsA|=c`Tpq5|QAOF$I&slY(wo0a^pYz#O2NH_79DZVxkJV^Zg2)M*dcr6@v& zL!g-XBoJ^`>}7%eO1A|jD|ZufYYgBN_U{mM8FPv73pvTT9+5SR?t$hkd_1d%?*`d`oPae`lSCG}rR)H6S;w+WBb0wDQlmv9PQDPrk4)Vm)`0H>HJP4`#zS1uH-U9>Y8@ay|0o4-Jpq4=diT+bXB&q(%H7L#tKJR7|NjgzlmR*th2w7pWe$hW zR_pcp&5S(SkBx`jDF!BmqQu=$QGS9MqvIG6MQX;}_q)JwdGdZb#! z52b%pDx`$!A)37AFyz%#gJx8_f{nXfy|NfO!FW+Cr{ZhZzNTh=FNmYjl-!L2&Ooj> z5pRrUrIIFa9CpGa!L96U5DKc7OzA$shC4M&QH zlm2yj;-KZy=~wr8`W1_Q)o>oP4a7RUV$b1-b#g5)DVVNONP0@r*dj=eV zV1i`(s6S2Asj07g%55mqt{hIpHdE9umB~k%mtsGL^B!J}V4tI_M96o|anY!Mq=!6l z%_Rt-VIapacq362xwwfjKm?Ri08wT9X81bnR=8PCJ0k7a5w%2}GNc4L4&R`PDthDB zVLa8MSyiNz42VX5A$4Rl;l^4tj%H&IMDTM^R4!J^!AL-2Ym5ZP&?I;rA`hX*&gm7J z(c<#t5l%0DajNA@9C6Q+uDqkuz9Q!Uyv6idK{Y`9yDDfvHvVvMhCt|CU?X8|Yw-Lj z#>-=qUR?kDbh{Jdw#P|;Jx3=fa!PC6cEszb4@`cpu!Ryg0X~Jyb>g$JYi4bEI=Q92 z#>FhZ$3Wq12Y_FsG@EUQR3AXO2oi}*HXaDb0rg*(zWJb%fkYPoZ1L@_j0_Uv+!k5E zUz7+U(o)~6horZ;;$s{We!IOp!4ST7hJ_B)sb<;*TM}X-{m+w>CB~%97S*CGDi#+i zlZ(x-iS~Tu;l4B$oN@A0DksQ7OA}>1zB27}8bZs|`yh2!^#AnAje4>h0LMnZd&u3L|#xNf-)t&P2D8Om|B*9o+$Hd_Dyp+7f^ z<$82t0zTi{Yft}e}w$75*laNc*u6DiAJ6ZYj5=Ar9UtNYngc%F*gcvppS;t* z?6%1nmPLO8GE10e3$Yw5d6DRq9%rX7>QBP4bTiXK4`1;heE4xYbK0pXF1`GfXFuu;ClmEg zy!t^AV;sbjzly};89BM3KncjP+cC!YdR8LxaCzlxZvxW&9-%i1pwQ6MxmY-T@PyjoVUmLnxFYf0~# z?A;^>^EnY;ugs9@-Q>FAW3BS~|NUhy%lJ`h5(-8t!T~6O&4`FWfM)ej~TM`5GhfRF}ofZ`mEai}*AcB(jncrQW#41UC#;hAFEU2=FL z1a}tVfa)p7m;l2mg+9U2meC*^=d%d!OQOzeyxp6WQD_uOFrj|e^bl_yWA<=N%D)YP z(QrlyY2z{Qc!lmILM755n~AhK5tgv+P3;RSrhnugP{;zkZ0xphR?LVz)v zipmH!()}K*#b{zUu)f;K)@_*vrVQ zxWukr87dUu$-I!5`Vzexvl}oPZ5RhAi!wp;=qZHiHRYX)eyh*O9qldt6sEup7`S3>bUK zVGq0G0Olihz*?YHyUbuGpyxm1x@|%I8YU9sX%Gf+!h_4}YKRgd5&&_Jv|JRRA%{qt zhlC8cgF`}iYC6hmz7Z~+g-B1SmHO9JTqnE;MnJkv7>2Imbr_EL@|uU5^iL!^1{oqb zEytOf4C{Z8FPbMu`@7r6+q0d~_)(hleWpaN)E+k;oaEkm`ng0Ln~wP;0o@*?V7O7} z{DOEOn+zDBM=Q zd1kkbrhao1BTUb1mz!sPFEO|@ZBdR&t@WOBdz#KW8!{Tl?xYuA_WO)wGqbew@rLn% zIZ21jp4qjT1?G<&JdY87LE449wUJoGBk?7d_nG z-QU=1V^r8o`}6W-A#H6RV7zj%3*Xy5{&9aR11dMuO=~+9b$$NCWpdA-wP(BgPd4yz z?+Iz-u!_da>C4G}+twdgD}ozZevmuK>E+4c;pcC8n{5uf{i9=;7DT^W+p`yMDq9Mk zd#dIf-I>p`i&G@0S%oQFR2HW?VW@M^yZbe-a84lZEK1JJl>;psy*mplCr=uZ*>ybn z>0YHj&spQ!$1idSDgSf+F~xgyYxn799>tN$Fn^bA{R*SMvnf5Fiy%{3XA(0Uu4pDb zBcF57RIY+;8cpS8nn6=wF!9ZoFK5sd`s`azbkCfb!<=)* z`8K;C_o{8CUn{WQC-rTa8kkWO+MBb`xPQLkz=Ek5(HK3uMmZr$<13x^wXrHimV&0F_G2f?f7y$`SF`+eW zwsV!X68eZ2QL))Fvg}D%ZrVbfplw8zV%e$8szgGOI|cYC%_AA(!B5Ya;KT>UZi^>- zJI`xcLU>Ef28-)*Aj&oOD40MKW4wPpi@J*^zqNnBJSQ8q|8Bqfvcx!5XA1iL;U(m8 z+C{8#<%bg6j-VOQ&l`tap{_@rP$+YlPK*5*iB7I(7Heyvfe!2vaWHcfD|?X2=%E<> zR#L$9+3?`BAhCwD2F2myhPIYs^{7de1P2wEc4D==f-HZ-48>?)DMM0Lb+us>tlWcrK1?bP}qHaWY>d zaa3{C$__&lnm8al5_P8iU`(!VQF(RPo%Uf((sc}8A|FMA2)?t5uWgRBW3j?FK}HD< z!RQzU2_71waRi4vtV*)2#ry|}$qq3e@JqVSgBC5&-Ym$$hJmw!LE0s$r)y zWe>IzDI9TMSPwcB4~<>7Ybz|o@9zj@Opp;n$H@~CxBTgzN(l2QQp=i6`eIry}k+h@uFz#NT4Xxrov|RA|_A0 za{=(&4sy?!e{+9tZ-ZC3EW5jFN_ln|{&C?A3v|edcZJ&@kmAX!(n^!Q6;#;20i$8L z%(i7kyIjkw6StC6f7Bsu6)Jh?1zb6OWmKi8Y!7HC_NWHKVxw?5pQbUK++o*4I4ML! zuSY-bA0D^24-fYbkJ?8s4i4aTd+SDJOo#cH4dqs=v~UOH42;II7usGaLf1e;jwfwi zplvZi5r=bTY;MXN53^%6V{m*dtJu&1N={bWyfd3EgAk9mUy>2(25O6<9mbome{ERHp2IG>glowT zp=zSH8H*Bf=`geV=WJ=6$J8+gRd|&?&?Tw+SOddOqjdtM&(O?~x>}^*_NS&Dr2Kzt z;5R`7!t((j2Qgfa0l8i?d8P(v*LUs^Q1$-sT-3axi70s`K;~k!FFX#tb`;h3Uu+z; z_qLCYPz@7ki1t%Jj}NlS#4;~bY_V{1AfB(s;qTLEEJi=5KyD%_K+7g;g#y&*)K@5M z4&x+3!A{WqpJ_7DmS!n#D|f|e7F!Io(O6YWbtsl0I(&dHaW@!uB^qH}b|LK((J|Iz z3Jc591^$whv)4VT@)?Agze9wl?-2SHQ%4G9f^;`2^9)gA4T$(X z)Yl{I9!&~lYscuC#%DM-o7-7PxuYhsiylxRg)H~$j!>a+JXGfZ)_$%M^YPuqWHMT7 zG@N26*XxGK>&b9bACAu(-`8`;7kMiO&ooO8;bgJT1A}_f88FR2%xBL@ecj6TC z%;Hx`;q{@TMElq?k-t%+_5<`}p(ts}-a}8eu#nc2y|13^#$J2l#qs{$#!p7uYf*l0 z;jPr@lfJC~sxa_vDAlpXCiEeUY3YhinpTlTC0FdeuZxa@1sQNCQI(Oj>0(lncI!da zy+skSMsLXEnJN=f$Tu5?kx4xD%X-E2G??u?(j~#5-3~^PRViPoudI~GjmHrNl$pZ# zC9GbT1AzqcVn2$g7mvU|T?VLQOfUpja&VeK6i0*Uz=)86|3IBU9E*X8PfRP8dRcb^ z;GmBD3jE)*KS#{-bmMpfod9z9dOEO6%T-ps+#^*r(`q&#tG}vfXEMZ4NVgE3+;vsp zvd|icxhq1eCE6PaD?T^6j6rI00Ug57ydZsGs}Y@$_`4U8wmF%K4$q?wodVo~stIEo zbLMLmoyWtmEC{P|?>i&P>Av>SLOTY%$!xwjJluYMoSFWcsb<7OI3=^zPF^}kBEF`M zoP|8FT{B>ATw_aAvz$0J-*tca&+7@1=sD;?uR0s4&fJe>N3Fo-i-^j|a45$nB(Iz- z$J~WzOx1D=R?IAIym;BhsNLHy4>q1}>oiDb~v0 z(AT7ToRQ@jqK%yyJfKW)W1@6Am|kJTZu0(BO2!>{Za{W&6c%$_GE+fSWOhW@ATz8> zl&iLIyWI>wwF6iWMI7}HG$KsR&|D#D}cw-Pp)Z(zv(j*Z(s zy#ihx{brb;?xcH9`uzZeF8YYgm*%KN_Qg#sKPi5@qkv8~!hXM^x3gS8256^(b4S6w z`^3iKBz8lz$R%T;7`kw2Id!adJdL#-0MFZGg6kn3;>juA4)`V&$06|=@;lv#P2*|8 zgmvu3tp~Karf)2Pyu(XlimPnLph|b3WROp{n3u!xYsBv%3zjqBXk>NI=pKW(O7>_L z3M+ur07^r6DxKCgXwj230xIQ1FZoN*W=I-Wfl4B_oFRxN9Rm!RzyohKe3^8JA> z?}Rhr+eBHlyc+{_fF?1trI{01UDHHM#4m#JfPztK!w|jjA=fGH%`;+BVHm~1%-MLz zc1N)Y-#MPOKOC^|$;)eO_kwPkV^hOS6J|sbip^mXzUsi0bi=gbghjm`8&d!i#zPqf zw83;QX!4xGw8PMBL&R-sG-*I6%J*iuRa&(5RvKj;dE3IE0Nff~HI`b7^`%y&cq-;a zYyuTZ4MO0Q_I8er$calr70PR~*ebmxyMy=8$U(Y?MSa}ZP3a(d4U*Blw^|Kesp@GZ zD?ZrZlW7dZ7?4k1FNv0qhh#s4qvze;K+zwEmxNha@QEvrF};yJRaHNNRk69L2{p>o zL#rV)v_wb53vR1$pm_EzV#Q9dWfJtLNK3ltO`RAGan-b{=wzk}5K2{yXV~aU`)){` zS|m<2ixQWt8~|v3gr5J*_7kHuofWYh`?^7H+`ZgKaT*@_jQrSMPoL9(FkBUYdLhlV zxTFmdYRFg|il>u6AHZ~HI6=##%`Mtxa9RQJfc~0Dfpi-v#l@4=`d79@X!D`2QQwn4?!+a;C>xOsn3I`xTkUsf0_uvJ=LfOk<8q`6mg z6al|3%Zk3gqWDeFkGi&|H4>z=-v%nkekH26EvN`j8aFF9|>HuyinG+U-~m9IXO^Q!_wn& z<$8p}zvx_%qKDeI0^vPf9Q)}6>%F}S^+dfVC(gvv-7%TNGvzEUy6S}&OdklxPga#A z)M5Kw$WM3w;w{WwN`R7HkV=m`r2`{y z0Y_6p;{Qu~ozoB55#*^hBiP(5Lmq6H*zDp-4m8oYiceaGf|QxCQ&pzq#zHn(@gDb% zOs=E&wK3-o)DoPxOI1zk$l1*~VV=*C{efpx>%iGJZmD7E0HBcgt&M&{5-qDcsh1cU zUPH^04tgeq3YmJ}+*IMDQ`bBU3ev>_8>qey6!6ug@xh%4BNxVf;^E(MU7jg7EhO{OX;6#Q+4t=yOkI(xk35B{0$;GQ40Ck6G z1Z<^6(&#ZPu+fmYO=noxXP(1!ToOgf>z3~Yc~@sgZF94-ZV6jbxq(w88k6dh;cjtI zcy-{milr+TENs=ZDo`iDNQo&ng{#(rMO=2sJX)WBrtR)2m2O-nwkAu&APbok$^qei z-hXj?@Z#74`PHD?-0UPc+j+jZ`(kT5Hv?K!9UpF>@hROZdnY8)#R}bpk2;-Zu>{M5 znGU_S+UOdu>H5K>QZHXt-BPfeZcz#sS=E-JHJ2?_KJRoMD)>`Qmw$1v>DCIbx2Y8t zxmya?d`_vnTHSx9JRVDVwXzeL&5g|;xA{_N@xh3EzFtZMCtC;J2z1`S!QD2c zqA;AU-EV@jc<#qGNRVu#XRy zsO~Qw4$(i|bVN`91n%6k;rTR?ixk>PmwLlH-Yc*IKEKE0MV;fi6BxQ$C4IaJ9oyqj zZp;Z7Y_A^=YA;?=+hA6>Z-i8{O$jgp?tpzI^8OxGaM~BIIZnL0;BR%?UbFp zhDu}9RvAOP3|`~7AVYu^)={2;-;q>MGNSCfmc~zmAG*VJNrOOF5E1F*T!!UwNMN+H z5hH-HqCWWE8Tm7pZbqk@ZP+hzz=>=_y!X?*I?ITKLY|mNGvCzv33+uO4z(LjFr;u4 z2k30DLoz#O9b@ExglEyrAi*Gc&+&Nr_z@~icBlzEoA!`}381Jh?5Wjj9C|4s7<7#m z_IlWWVNZ@Xp{7vQgYc-gdInQ{Bp`IgOvmWn)ebMx7tj%Ep9f-~Pi`JMg5XUGF9;Yq zjM;XJJ=%;p-j30nE~QZgMe%X90kg>D6y*lBSe=xU#%~Ktt;Lg|_Ad@U|7xjKsgxS6 zmBy(2N`0s54OuRz!9hWP@M>`yM|k5E^qUkUn{_Xdy3%~n=B9Q|M>JPa@De=0cq}Y( zyOvt2hU(xg_ob_RLGM!eM-_NRkbeY30303ud z<1C6B$%T#$HW{LBc&Y~aW`c2vj?`OR=hBh)ieJfP;(MKD5~axq9IT|mc0fq^TJyl$z{w9u+h7$9$vD z83zq<}6EM-qZJ+nN76zL$0$$7ZY2vHoY+7u%c)z-2i?CnJei` z(=6zgW;yr_^!G|f2%x6k5;i-O$Md9_!boZ|80CIChHs{DiR8hSO3^d`OjgP3Tnc4d z2ufMg2DSRV$r6t7B0%Rl2lgS2wbKp$Ub%q2SeaA&@jZ&0k-I~|(p%)-Ysi(oSG5G0 zH^%IlLY^rDknAvq+KV0>C5YM)?;z_H>j-L9WBN;CizrEeijoLcb|a7?z#tgEPShgV z{1Te2{X#mw6}0f83sD}SNf(EmMOxQdA=rSTU69}fSD+g~tR3q^b#-t@qa0l~C4WKO z!%~^r-a(bR_jP@l&W^9^E41PJ0c}GJ=CEc8D$KeD{Fx<4bQjmSUeamcwv=mo<#oJF zG_gNLPp<2r7i7wUbHuud@sSA?V~f72FVC-;2Xf7+@1X2=+2Ybg8qsp9jb-I6@OSSV zIRO{&!1>uL{#Mb8My;(Y&$Q(>Y>Y-5rce&jrXM0{m^-cGgpLQQHtzYHs?>gK_6Y#9 zNvpXx+1ftPp}GuWyN$#Ip!l~`qP$S zo+-oC@8Jq^x;jw-bQE_5raWki@*?(9g#Ag9t{Qp%VRf0+iN)Tfrklt?0|-t6<*bB zX$HVqd`XH{hOZ2%Np$a}c{;hZMyEGN%-Aip%1adjLF@DiaJieQ$P_hXQS#k~L0^U1 zrZ@#6jRKZjIYKAW{n~rVY=Q``twe;~0Bg(hzA%b|Uh`C>1A|@>cp#DmhN_%2*6K^8 zMx%Tx;Mr(jTkC86xgfR*sn+;GUrY)Ore!w22=9kZz=KKWLVE?)A|w%}>(ccoW(G@& z6W=}xhv)%i%kkDhg70-aMDQojAHd7^XN?*wl6Sn5n zHX5SQFZ-1iC?x7~T1txs9cKjOYnvd_4jobWD9lZbK~#n7Y?#}e%Zp(@G z^tgB-{ub0WAAcf=*JcjbWhM=(%8_od9LNZ<1ccFkHtW-9r%hvGp--`QWgZF!Yoy~S z9Oon;u^J8N{de4dZoj=I<4kl#=JmvBo(I%PpAXr|m=B%$nt@HJxsZhul6#^!iB@07 zjlt;@YZUOZ=?w9}5}mq;H|7hk#uqbcdWttxxFnquTBK{V`KwBY0gU`UqXFfPZ;JB4>B!ZXYG6R9xsT5G#Fr1gAr_Ml35R# z`y!25Qwiz-;Qdx-G6l>H*n1jE#Tp6dFoJa>N#?y9D?KJfS=2BzC3mJvW@=DvR#%A% zwDwD}ELSh;JH69dg$E9bZke_=%4Xq}8|P*7{RMt_L20LsPLYNebFHIC)Dyh04B=xJW1sVT2r7k?7h; zE(o;XfQcH$!a%C!QM;%Mo(SQB#>LA8 zjJq6Wz(fu4uR*U__>QyGA<47HSk0&HvdVp=z(6}*t1B>bapfx>ATv=cq5%6w0+NB) z!c8BN<$pY8sQ5}pyV)8N!lHAT>_D7&BeP>y-hu0JVh~UHImwVh>nVV!%hCA8Q<8oje6)4OTgD#6A27 z3BqCHU><9!p6DNAgK5|#J_adr4Cx4=@;(+_9F0SxWsi}Omn&6!F?<%1zYrig*#H@B zdbt`g^)N=A`Uc_>@!cp$gxZJQj$PJaa>y_Mi7_#9)xKP^rk%tyXr&HP`k=hj_QYH^ z0&0R&c*54k8+cbGfaCCLV)+w^f#ulqp{@~qqAO!=Bv};c@j_v1pbf*UNlS;K_)-|n zVJsBC2FeCuJE{aJL@xw%okxM|taI6a_d_OE2 z;vzfO=VUkIDF|-<`iwj={$i&JuO1{XpfQ19jRTTM?%{Pfq^#Va8{WhRx+qq$$WK;%qgTcROSOeS~SJDGjzEW zIz7<1n3lWkifb2--?d)`8(Nk8Y_hF8hb2%emE5nkkt=YDtgKYE&3rGI;GpOhSXWKzn8)RLLs-r>x~yv;arDm9oH?s9a^@4g{o?t5z1TnA z-m>R@u_TX0Jo-iICcVO)l~dM`3dNE5ChiyZf6PyC#TUjW1#x$0F}5*+SyaplZmA{5-hu zsz$(cYtTP#Z)|NJa={Bgbm2Ig4?*udf4X0#Lm-NK!%BK^+(W6YZyM(2;ea=@vI(23 zjS#i&TyXi?5G_TbP66+tYM*F@sN_1CgacKCj76fn0;DhsTK3rwCTN?Uo?JOpH-5>V zSZ)z+Y`_yU5An?1TWSM9J8M%kan=}(z#gO9IZm#aNbdYSRdy6yWlLfrmD4UH{m*Z{ zmgwtwo6%l@>MaQcf8N;w{PlEu_sHoxsh?sE8FLA=<aa*d?1Jp?o=Nvk{k`Krl z=FMygX{pX=%FCCt+al$%jln=1Ghp4^9JGm;*&h5jvq7e0rbYB6r%4RXdgVz?X@U_W zC$;gE1OO^?JG`@t6y_oOTeSxqZkp3kFvbI#{k@P^-6jvryI1I+< z&JZanMT!OI&L5j^*%W280-60l(Becweq^O4h7 z3=J+qAS2z1kVYm0wUiU2OnoqH#`jL%=ZZ7*`Qxr5t&NgtwF|kEbLBMSFrgTzq7Nv3?+szE6|Bko9#>Eht*FS>-qj}yR--+Uq0S}| z6}&l!qVGn%UPyKf%t00k3ofIKZe(zXc#YvY<)gR#vHK0{6>4 z8~wr2l1S_Vw>_!K#U(P=y7d5pV%R#3XQLtSB6&uukUB=W+h9a)H&)6xl-=-(wD-9= zZK=CnXrl*!@p-efLXT8qyEB}|ljceR&umQP+&Se@>4}8vd;{#|C2pl8@YOr>xVEIU z)Z0_5w8`m)um_G(Dp`H0R!*HeViI?=6djdMWbB4xQ*lv!pOVw-53eex4Ox#TuhRA8 znK7pwNBsvm8BCFkxuQGEc9z7qXB+kQJ;6_!^vr5TrF>&}GLx%f>8%C*p5^07I5Dg= zFG%a&LMtS|GJ6L<50-ebSs1P>ma^-MMY7bAi?UHzm{T^tXi=|HmsPg_a&6`Rll+p2 zpnH`@A*FF4clUjAAc-BU3A-Q?#l(c&PIQ9;;|HiaoTLot)ZS5TYyU_q_U8D}b6Emd zmZED}pTN3vq&5XMTFWFG(NLGZxk_lR@?Nv|?4suH=qlaIo67wQK;?mz!^ z&7>Cq1hjdlXYGs0w3a-G@x?t;VCcw>72VM~4XLJ~Sc#ge(5&}#W0tL9X=}TZbP$%V zt0hugC>E?<2hk-k9n=1V^_Eeo0=1XWg8~L{qJiZ)1VUZt09~I9mSfTdeP#Edcr)=j z!iXmr$*F5-X|1Dysxw+UhR&2z-DuyEVAU}tI2F^&B^Z~M8RM1=KAj$JcjdR>Dzg-r z3X*PPATP2=p(6x?5nNL5pB!!F_TDp#wYoD+1tV*P&8$pN_bmKyl*)FPlpLgY=rmGt zv-_RW2ddk?d%8TuR#8+QoKb+@avBqind9`tf$VAB8n~S5x|}Xq`0x=iea~zy8G~E9 zvH6cwlGV8Ju}dCueDVxpgoItR?zIvn%*I-K+6aWKUbM174#lX$qo=4v4`QyYFOQnE zS?Duroi3h;U4fQik|N0(;zjL|gs*O0Uo5O-YCY{ubbOF_D30d>-}`#Kkq0ombjOk-RlWE;)4 z&FH3uvY{41L#5#8Zm*gL5naP*D%%{?2#+uxY021 zdbO~_N!aR}o6Lx#;t$??GbHaGn_!T09mtHt;B94)O>td&s; z%nf1y8<8igK1iY|le%t|wzx#;k_ZoY!i<@jae5N7C9K9+T86&pka zx1AYsv0t1mHt}2u{`HyE)E#VgM;fLSX{=M0UereAJSt1y<7V`+mgn5Gx_7@?VT%st zmHIb02rKn(>yM2kj5tQ7X0%7FxP_NhxRV7`mB6r5q1RzJ5-(Jq5rmYdKB4#CONn$!b?SNS- zElORLv|A8EB#7~hoT*~}D3EmLXZ1#RQKMLj z*~N~Sp)Q7@n^$*uBxyezno0&SEoE$_J4mSN-lXU>Q`( z#oopfvZ*7lcKvJdLdUp*&<4imll_S11ta#x?RU;LN7UJb?9L7vX`7* z#hoLotiV68E1uS%7yyt+nWSEGHy!Q*8n%TUTaW`9sT$blQj@kK2J7#cn@^a`D|3b#q z-(z~jmoV##qM6f0YxAGvoFyjGyO8vOnouh&CAOEv-&=ngIM7h)kX;f?W3rF#Tm)!} ziEJ-kg^MDy9P!4lKHALC&68GHK+~dNfU9Ps(+Po~r47zpPjIF^X)EiKw~n%*ey>?B zltt!@df>t&;9=V;wia5Y))%dEizKuC9-h8AYSGg0*=?hiy{hPwn2&lL0Ax;mE!BE3 zzfJ){)YO`d{A254OQTcRuVv#olXY4&;X`hB`ops`xdzk@Cn*=Xmo^Hr7+!HIcLKFt zF>jXX_M_|=(;1B5kX#QiT}wf35nWcm!Z& zeU$~FY;8eXalSifA+c&4&m zV4Tu^*RxHOewvQ%^i(XNnaBV?>{g8|Q2ba^RGV1!6Js+N#NubsfQfol_L?X+$yFuF zH|&0k^j4D#6^KvT80sTCS_8mTqJn-DB-Sw7!CJb0GIf`=Y5;J9NV(|5vp2r(FwJq^Ym^5T>_a_os2qXM^GM=y1n&ep7GJ)w*vzLQm2 ze3?~IDOe%&KCits6B^uaXB=L_c4f_}t~mmSeX`QLK$9eMYKiUi-wJ%LQv>w~^@p9; zEH&`&fUd)2mioniSa7&pW$#&Z9a632J%aq5VFTWTaTg^EqSjItPiN1bzo?j)IvB_r zc2;?U$afTWq8>ZK5FxXX4sbxHvnUQQ+?W#NsyGjQ~BTPRYCP|H@@|fhT%cLs0 zc!sJ23`{i?$Q%mC{B_70p5j-N^z()Z`bRO1C{Xx36F|u-_plV7L(&C`Mh(Z&Tn`B= zj}7L?L?o@W#nEh@=ueY|Z4;-SBMEaEySd52v6m~^Qamrm1Z@1DMG#Q-c_Z?uzQn4M#VdAHeA|WC zkCYFoIc>Wx=?bpu`e@*eL8o9KuFp`>z#f^Y(sTeij;&C4mqH^S@9*y}p2!rc6B;sj zSR;Jr&9Jt0A<2xRfric^Ye~@&3FQ{c59?wLv;X>7(p6Q<+CTohakztC)NbI1;p>4! z5;JT)Q3I@ZLbrb!6fBv4=;wdn3U?%kS88U}r#dM$(gG<%qZYur5yDe2sBm$!JPKzK((`3G{k|62oXRCFlmz zmKO1T9`aX=et)3dq8B*E5sSbTd)bDsTzgG7(DGTnzn20A4GqQ|Rge}8zcnpq44j8k z|M!ZugzA%Ed}E8Jv2C-sF9d?Rg8@SA*r9zg?|EoE?_~VvLHN$C)!)T>3R&BKg9!_{ zLfF`Y4|A_X(l^d0RD{fB(4@@|PX6X=<5fh)qggJ!r4sMaFD`5_II3hki{*7?df?={ zf?Ou*%SkFwf*9Dr6Pe4UjG`g= zmM%LGSa(Nsc_44Qv{EaX&+l1af&@@+$bmD_vI`nDxg3fsH`J>c#y0Aw#NuG4v|zpJ zYnqijt)X9U5=j}8oACvyL!Q=PcWN6DqOwrzWg1jSS$;?kNaK;H80S#*H6Q~L{E>k= zhd=A$ut+ngdw3(?-o+JJ(xr_3Jd7P|O6wxm`1#kXvgnlI#nJR;Lu@fe!z8-WmgYeB zT+jk8J4@Jw+Wug$8K}HB9I&`KSmBXw(DY)dh`%ioZ6&XPBSQ5X_^>9b5+*u;2>_!T zsK1g7jaIV2q7`Y75KBc^KCtKwcE-(duIn}0<5*65J8KBNJTu0F@(`MEMk2VX_?6-A zsqMm$;g+sl&Z#n+b5_NabL>=$+cQ-!=|kJfRBbedIa2R1Ig5JCu`F zafV1|=sN8quk>E~bOaiwWDQ4kTC__On>j`qPGJE|b_a$3TvvbrwV=qomE9^3$e# zY8C*c`m}4I@c%yl`wRVh&GP#iki_V>wwu%*)*sfFYb%Y77so&DA0B;#I+o$z<42G1 zcjfD^R_GW0PwDjhaOMB4tbD!v_~F-&R~~=;|CU$2`ugj~|4%J{gt~A1$0xJ;e?X@P zFc#;-8Tp>Wru{S8^C$lUZvA37Cc-nb6o84Pm=WQdu#aJo5-srD1#09N`8Z;mdEn>ZoFWSrKffV90#D8AT5U*fzSG#MmNwfY`R2suFp#QzcRZcu=S_ z2?bq-ruMaT7Mjf3x{sYA$_1^gVLg6Wi#J!PW_YeB?jwUr6 zh}0B0<5d5Q=KnMP&Bp)cV)ujVKqUY5S6}7g|JBupE6ZQ6BL084`t|Cg)rXL8~##sVHIJGmWema7q*V^n8lltFBKWe{tV!#1h(_%Q7QnWg}E1MAk3fW4N3tpbT*xlXS z+iI>6XL~RXYme%yHtZstdH)R^?hcWEh0}Y~kHqdPR;9NqUlvRMD83hev;}e9i4vG` zz-KvXH%u`$82TXM&^&w%(1Xn|9aE?aR@SJUtFnPuZkF*E#R<^6AuNLD`|W4D`%jqd z(png-c}7>rwPD5eLSRjOmq_NdR8dSAa9%};YJFYu=&wfK8#P1`@UslEw%EGHp0#+5`rwn)6uh#0L3SWhx+h-8p})%Qt2+tFC}P=F#g z1_|9b{R=&|cy3OgY}kEKa`uQ;*1}D~*VZpjS;$pGd7{#NIAtv~{aUQ#`am_4=zu8O z^mc5&#Plibqt2XHaZmj{`JieMKr7Cx7QdAB7BTnqFHaX~HBLKc4H7H?BB{lu3I6Wk z_Bfwiy*ynX9yHA|$(J&ai=~wk?G`P`v~5i1^<2m1z$VX1FgPnkwFbW}49d`IRnmZ+ zA|k10pHUJlS{t;D&)uNYYN;sAT&ffv=$gn8lUtYMSuZ?5n5XG{^(D?=ns%x~RFm}5 zJkJ7;(IX~f^v0rFLnXL_7WFv&Opht-2MVO=WzreS1yO%Yff7JwS*3vZAlTvXv8ct+ zH7DQa5k=wZgS;izzDL^!8;2Xm`-j%P&^0gg^U&$Dh-t7q09~%*pYpnTN=YUByRNu- zYq>)Iw|qNbA*|gAf{Ct}YF2q2$L>9!1`BHEDMp#l9z*Fqs!ICN;(C~FxT?6mfZgsy zNodSHFkAzifd9qus9^Mr1wNdSBhj)5yU0z7%B2o;Nv8}sM`W7|s16Co#U0dQIBK&S z<&E8+)FpXxbG-FJYf&p4%@ojzo36SgIvyS7q~4~FbBqxz7Ts75%_}Lw43W3>N&ym^ zMO7?5&*aTz7X_+@BoyTOY zwWKPz{sz}Dki8~+*P*x|F$vy;ZEREt{;Vr{@+XgO1tBM^i7Wcb*MXGTfl+Wn1aS!> zr}(kSH&2{nY;rV8%Q};8p!wiRut|KKsnI7kXiaq^R*t2+7$BPf<{Q+)8VnPPtbGO( zcTJ%{aH3Hu4Tz>wSkmH@vW$v?u?SUYM0r|RvN9y!jYuTB^HX<&6`Gz<=w|oSF*AT0 zL6`U&2cNN}ObLxa+^=hj!pN>^lSJwze_B`L5WB-(v0`fpK$iok{9jbxf3ZsV3l{Q< zprRMJv>g^pM@kV(MRw{-3zP>0ubPQVS`6#wb-V;#z?}yi{IYuS%g%G8St=4*LSQ(B zV9e6g#zp=n zhJw4iT|M~B3O^&htZn(SX3^odT4<%7=D1q_4wkEh91=F?AFYqbc6m^N^^(V1abK-m z_N(;~_^%>QjSjHXEW%4KZnN=t3EJTS96Pv9ZP*KANq z0-{8#pwhJ)g6GnMw3=CnT$Gm>_^Svq+q*g{-SBU`aVd#3MH;{ z&Y{I!W`$&INZh-_hlydw2Huu2b$LsB*H94K%^T3OHbA23aF*8c8ecNW)shrROsoRB zr5ONOFlJ{osCQk=fFMI@XHa*9wI0Togx_yLUUt|Xw|P~Cq`Ok5_N!i7*|o; ztz4lt+20a(N;-#R%uvh$1DyYKbUqHctPqJ{9@QV#AE5{xxsow8)QDjH!Ur5LZ^E+t z^O_D7^pEp+inog_`^sE87O*VKt(+05ivL#*YJANy0VLg$2!$IG0gl^D=5Ms7g>NSH zmslI&!Hmf?$z~dkso)@p*}9LMe;LP+?4O$~9L!w9)S!|K98Fk|wjt~X8VnJaYHSn6>WLhaFzY?Dyqgf1$F7{6?D zcV}~dcmJ^cbpLR3yQ!WXZXak5D$Rm0yIvkIOJUZ%q<5WpM8ok^do`MOpULHfaOdiO z-Z;#4TPEnrw#e_tSmgWj7?p@OM9L8gHNRvaB~ z9KVw+VC`)GBjBey51pK1ssWk^|gg(kM5~6>hoQIL9j= zwNN&IEEKml4mssEvsf-k?y_!HQuOk0Ti}7b_||IPKoA*5OxR1Cyr#-8@p|dxx5leh zrO}`V{BNnTR4S_$$1BeiXf#?C%r!s9JOHfmdh=jVT-1yCDZmZF9 z8Vt{+##^QolLm%e=jY$?=RN+R!dQqKUthX)_FDq3+ypXdK#qE2UHx9xA=R^MHs3NR z&4eX(aTnPvz+DsXEj^vu4zj!HNCjM16iQFjj_k#YE(27pMG6)T@H;v2=pxdF|8`$& z&%~~1nag<*vmuhg9Ytjj-LmJ9uGXD&93#r55XUpe!$BRhoqN!I6Tqi)vdBa#fzc&; z6dMRVEMyl))(zm0okag4FJy6uMqA_IC7PtZVe@?*HkP}TREdH>!$xV-Q6tz-*cT2@RX|d4lt=N?m(A66BZcQAB=}ZVXG$qp zJmZc3BHB+dPLose%Vw*DcOmb~jyz#r0mxrkkupHVD1V0SK>$Pw^m*g(S-oD*oozhQ zfoK_y2a56zLL4isWy(y7_#Foji7|r_b!RpawZW&(`@=Iq-cX*W-kB9r z0J?@Yew6?m1@6MI)=YB1M{-J_N{fq?3N;1MqdQyqLZ;hI4Gokt(A1QYx0SYa!xfV70vvZ0Tt79o(3ktc!(l|f{TO&X2$vWUGT z+ls3;Q+kwAePQt>8p7)5TCw!7_}-Da0-Vn4X8OI9N=P$XNXUe1E?kk^zBiLlTE(l- z(j(2GWJ>!PSIzokD$sP%r3SG8U6j#M4Dc9lEe3dsXF2+UKCX%{dF7Ht3Kpp^!RcME zLow1Fdbupuq*`wYGB@#$vn?o1q?-}7V9~5Rpl}+wA_ZN$my^DV&Qhc3-RnuVrhahh zH{bj=XoAZjwi>5S)#k{BUS`|qRxS{l^6ONszu1~-`k2adyH-Rk1CPRMP!f%JqqS&h zq)LjcTb@a;E#HAu&8;~q2@(jjz2u=+LGp^V@}+SCpa)geaj zNC-uA#_fKHZVZ!VIXLS8RdRk2{m<+EARdl>A19OPo6D=~f0ZTc?)LHV_Tf>pyzyjn zYy0W5A9w!w)9&8${ewikb8u|k^F18fPHt@5ys@nt+fF97ZQHheW81cKV>@r2&+l9H zR?T0h&faJ5?q2)MOt01b&CSd0b9>Lg;QMKpsG673B_)NAJGLG@T?oC{)79{HGp8Qg z^L4BRPkK7C;15y%&wp2lG!`yPx;#N_@ajnEYfFj!Uq$9pJF#Ihl2dUZgVkzZ_Pfo} zt7&aWggOc;6CxD2SP?uAsDcKI6YRMp0mpzXRsxs28AF?&g^u>?)83E9e#7ps3F2}c z=bXVZ+bp8GbMdleGDz*JCanj6^dX$ZLF?)zB>Q7gSls zt#9_f6OB{tJi8Hw+J`+tf=JB`Iyy(!7{pxXn~3*y?sNTb^ONEPPYh0n>JIS?-(_PVPxLO6u4^T$c*sGow#;T#;veaU8k8V?)44UltGZq z#yzV1r&d~}Q|ppKjU)3a=^-cdtI7EJ}pSZzjuajHG@ z?{GiUPJ#=%Wd}m$?ci;^+)>-({GGVfBYw9Rlue6Uvu4QTz;LPKkT&@c@;dZ^1iORh z7KRL)jQXw2nP{;&RaQp@VGEEGVC6U?sf#462GAd{ox`u1|M&-*KE(;^Ot1mYBakI=z%GeL#oR7f>C#29IEDjhVi(C1-l z1;#X1a;|OMRS<3F@Z!CU;*0=INoP|yqhcgo+4-s85p0m;JcY&V)-kY~-geLWa1c-% zlmh}c(Whj$%@GmE=wUIVmrxEmFYkezQISZ1-;<{x`%gc#_4|WykZ67E_wITyfIIY^NUvNK-W@CPfir^Ucz6WKGu3K-$M^-d1 z;&Ug!gD09+*@Vkf0_ZxFz=u<^Mwd=?d3hz3nsxTyKd?kTRONpf0&y7V$R8f9eTzvl zBd~znKH})vKh5v~$hy|`L@3~`;;DMxgkc;8m5EMvL0s6aJcWvlqXQvH(~mo;UY3v7 zko?_m&yR=KKUF1kq>h$$HhcvbFt6897%;MJ5kknHH1Cgg#0%Y>x%qEJk2v&$&F7O( zJo(wT@C!#1!xP`&TV1`5|I$8E*zgwJuzI(vRQB;c&IxEl%NU<#3BW-L|D{s#Zh9OM z#wX!ufRic6%wz4>7EeUhyWu9i1J0Kg=`N^|)uTyDq}HKK+Wnqbau%+)F(wApwy4HHv^qdaja{>XErVDWWU%67l|z8x?%U_SY? z_cYp9>Ag@#OU$gjsuP~)a**(&7YVdNn|mDC4ias=kX@^n2MI_T{=1oxq}+i!NCPy( zO+`~WtT*RP^ZUfG=|EIik+fHlQDus1L}c+X+u# zK8OI@6!Cu6@qBLU?*494(4;;UZ?D&KfwT4DE$eoZtWe>UMi`o62ha|dycEYI?Qr6X zlsn6#6_D8ueLj|*WeC-3rhd#F+@;8bLMbvq)Ex^j=)4o)k|69SLBeQA5)BJgcfuyO~j^sXV{%2ms8E8+``N1DwdaRnPW-Rel?Kn7>+B zPBpqLYOyq(6&SLlNy_=pT@*f6)MjZ>USjF#iPyVKWpj{4LL^_}i^(nUEfPj>v^*{X zjRV#}vbO9NM%Ys0c4dpArQ@9q0Ik6dXjt!<4gixf)n&5fJ<`&j-Yn>hZLx{`=`WUc zJExr~SZn5aE3{X<)JMl=4$ZyDEfs(I!w}FuXYhfd)hhkPe;;VOflxWIR!I#)abCZf zn~LJ3l50W;Mpf;cI~J@O23TA{|7#HKF47RmUNHPSU%o9~GnG_-33vk42u#K;6YU(v zY;MqlhSsx8Ed(}4VIrr^TfMPVVoJP{`8X?}i;-rq$~kA~N{^iJPi*|6eyzM7P|q_B zGDrh_4r%?c0rTnF(C8K?NI?lzt|#}L`$LS`Ik|D$B^Kva+k#QeG2`#h*Ka6%2ez&dB8W2$hd>rKC|dqHr;`y-gF z-*{p(Fhd$J<<=;sYpokQ6kM#94;-Z%LrcNTHAVm~fz++*kfDbInSg5!49;?IOu6H# z{75O?2wbatmkZ70d3DuWLadv~95Cpq*rKRYAA^+IkUwkY0>wO*E5>(@O_}QJP}6x2 z!FMZUM`hT_r)%xsY_(kf=zDY(|LX9K>nS5jk1SqH%l;rQ#D&xCk)Aly#k6B9%}1MZ%;1KCyd`TZ&!nUGiSm^+Y@(8dbbMqy;MiJ%s-4z z!$Rc~YBW0g1|}Q}@nxhGs5{se$fGoP*Tflq*9%#B=f`!*D%CnKlruD`Qu>(>Y|xGF|-K)piko(>qN#WR4Sq;sU%$a2E{g{_sx^^@mj8Z@>l2Ah!^8i84W~ z$v&7TzzCKemG=BwpbD1$s%h{LnUaqDRihv1Y>d_L$V{82kT9OJt%4vs9?|jPwwIqU zN|;fe>C*KUZSO4t%~KBsG6;2`;~m^!Bolzp&J07MV_72klNK_7Mu2B*j+bCeZp|F! z5zE)_R<`+cvO0-t#&XE$`MQcUdCb-+N_u&DXHXmE=B=wgVaz~2&)H+pyB+db>>Mi0 zMI=~OuS7F{U%SVIchuHk0>1QX`;{Y)ijjY#^HcOTU@aG=>)t-0&Y&0R7$1t|r)xcv zG8Jp4)5?BCEw&)<`uKI3_3yc0Z3_LVV;uG}Eab0D0UO>8TO-zWQ?3K08f#`;JKXIw@k#j%69*Bq9(}BwlNm>tN||K} zhFLj-@0&J_Y0cPGYX$_@%p*r&NGlxi9(iG$ZqvEnC6(xJ%GY@$A*I0MJ(PY$bq|X{Q=i7+S&Lk}5j}laU6W`<@c#f)I}f!!xr(da>&xJ^0oH z&Az0ezqqfR=hL)f{gV4X%KYXh(1e$ot*Nw2)`Y}Iv@$OVesod_27`1=XZ@D>AG*Xz z283aViu-0({M!L!qL0Uc@g7d=GL2(&SLHot_FJ|K3QA=Q<&)b_+h2RN^I2QF|FMcUeLCtrn{@0^Vi5JLFshq04v)cp{( zF27VU?PqSZcV8^PA`*N?qW6yXz%uuEv-fzDiR8?}l(8Ys-~v@b9$eqke}QHTZ1&>g zqwfRy3A62UrRNm>$z{|7B@1?ow_3C)P>xUuB@SANDxrmcyO!9Eg_tnwrUEj{v zDia}7@)rtY{6+|afy_!IMCLhI2KJ}p)!)IZiC*t~Gp@Op2b!qR0ZC7!;RTQuPXdx& zKA*uJ#vsV|;1kacEuN9!>O#F|UEJ#nOU)Adwp-j0n}a%_fv!ix>%6-6E^n~4Vv@86 z;}dtm?<-sMoPBqt)smiv6LZgrU&&Kh@#{(c>x&0X^^o%NyEk0xTbyt4dd0W`%06Iy z2?ky$UZWmj?YkxCIHhJcU$zXrr#|rhAZM z0}N^5Irggavl(e%;CRmgAh>hC6bQ?3*RBvKz~QQ5&_oOlQgdO}L5!~{PDS1c1&Hsl!EXvYrFNLYp<>j+B9m-a>~R!_aE2JtOjBu8Z%#|d9<>} za9ESD=dT;xS7;6VG}E~=9v~Txx%1BU}0^kk(+3dfjN4q{a^ zNSfWTMfB~kBmQVlgL`}VHPlT+hR9TA2OOrT0rD}&i=x20b4J$=HEgi*SC^tq14@n& z`hmd~+X7;KED806;3Ju!J=+{~Is%n-#5~cZ-kOWHs5Mtu#N@07Z7!wcY91|LTnIzy z8Dfwy>C$2Z%{E=>h8^UQWLL)sW;w;&^#+B2OGt7!Kb-qGI;7ICOViUh(cz@U3l_|P51be(X1WINv0)qUBIb-pDn4ahvpt#@x1)xb^-43V#i2h@kPmLJ!)$&`_tcNq)PBaFNor+9x2{+~Vn1 z%V}+1KRe!LmJ^TTL-_>=lc!#D;wfe$bJK#3L1^wM0Su0Nz&7I zq!wTnHvZ5muF;eCnO4}_x~X+HS+AgB*>(bOjzlpycZ;#6RLOf}36^r*zHb<4R3|1RVBM_CbS#r(pA z=f^~&`ue6KZC7=UVx$T=aEUv``?7X71~c(m5J*>)3+EK}*>d-yY59%XbRebacRS`L ziH8binWjvp>-rdGk$3-q%wki)uklfkC*bK$MCqGWQfC3qt>4iA+4ik{&Elpwo0|5$bLky+4x-)dZlk^qh2znm3;Ed*oVq% ze7=l{z|?@_NwpN%{%B(uRh8@>26uGP;LTf@>&5=`J^^ z4GKR*nz%`3l!VI!ESNZiuNC7NMLaI2HPj^N;*ho5i}-3uITqBrKC0p5GQUKTlX`7( z5B}3)?&o1u+Ph-B>V)bQd>6Y_>K*8X5pD{@q+01Pe$RVI*5Xo;oyUf0@nIQ?9yUEX zwl(VlFKQpdO!OM%2$V^R4QG(*q%liUB@rSeYOUid4Vs$+Sv(VJDiL<2)XZsRnmI{u9fBlGdR zJ3du~qVK=Kk^-X)-!I-j?Y;m@?7|%^JVcKOwdKq1*qfLqYy24$pLwBkMB)vFe^Bdd z&R$JRkWR{+5U9u@Ayt#STVlV=&$4(`-flD;^WE&OBCn#SQ!gU|`DN=rT)&q*S)2%= zryIQ|pQKidJWCL_iUC^8RA*pjM5n9*kH-lhOB7HpLH$oHx+ zOnOTx0PN^&(fmus4+50|lkv4#EA!Ezj{U0o1BKWtDw2qHIfoeOE`$iQ@V*++ZVu*961e_r@L51{x*j*mWEngRRc%AYu$b{M8+!f zc9xckIM|J^82>Txqof7FEJbJFVJiW2*t>q_c&y5GI;(Lpyx?H7T>QR>;E-eKH$54= z@tgga|H)s@nWs74^cKfEE>^Z0_>Kj zlU|nD`zh^IWcXR!@A0Q$DfP0^D)s9rZ>Hqi&YviK>$`4MMt0pozNanDNRX50ey^4L z<{J9E_?e7PLN3_-K%}39D$(bEVO!KWCF-23LEL;8@U!jzf^~h^Y0r8>155OEA@+F8 zuE_X+J%ZM140!j)@*PwORIOyhIg2Kadfgn)Lo&2IKMPDc3$5vW5S`5!-_Oon*VgM^ZUFz9U-lNWxe*Ov*ltk z2@rrMm3Z9a@q>W-EEbd!;AwL#rU#{#d@hSMQrBZyOKz?6tsm!f-Lk=t#V|z%mFvIF z@t#4x9ufFz7ttbyg{7zBmi-L2{tx1_cyV`YDI!zI9iykDQ9cR(FCCvEC zgIe%{La-@$(e@TK*Vz9vwRw)r`$clzg2;79 z(DqBzue+6% z^Q7=Uw+LP%_Pnmy?B8gf{m-eXz8`ZBt7NgTLB}a+4&PNdA$Q zY=5o*YPWbC7Cc*#OY}I%xEC%;%oE>E!N2I1)B4?O*H`7;cUTr;0^b!)M=3*z?j z#)gxkBeSWZmo-MJMTb~6z&`Vf699}>uDe4pcA7I)3X-k==qvNOGy8WL+EO=5UEUXOIPxyX3Cfm&5 zkdev>FU9v0KE^mnhpi{Blh5z0FzIm*xetLKcd!yNma}*n({q>?4?*pV5K^tg#Ekz%J~q_L&C=}Eo}L4 z6B(sp{C>oj@y5tjno=K+@qe!mm0!a#tP+d(ssI1}&fG%&j8IQHgk#tK95aR|f!mk= zt^O|ayu4c8!wUT+MTt)8f9P;6R`?GcKlmGqO0VYPvE4s}kuLh*dr9x>_Wk-?X#&bV zp^5x|XVuSs0R-AFT-|Pg?V`CUFs8Xb(;Cid!mn^)i4<#?$^2)+AVh(8S1L_94_VOS z3DPSJf$crp^q)F}Z5kNwtMa#|=_1;`7v0RVi;z3irN1&zg45oX0$+bWcuIXW5hY+?U3_7Yn=HvqW_C; zJSLYu8#eig;%zsFjNGCB!x`iPI}uL?F6^{0`V~Er>>b+@ce8n|_U{?BxPU8mg@t_D zE7)Noos$?yW9*)Om7&I}Nq8we-DqSTuk&>ACgKTk^iWkm~B@5P4 zCJ#nQI*4wgkw zC6@3J(JIHXXW4oEU_9*f`(0tU=7mSvE2}5zVU`!WFu#?|Pp6%Aej(p}`RrEgjKz*7 zHffJ3*4ndeYXw6hHtF^Z1eXL+e4%$cfrkx!N(;_GFaK!!jHFl{ME{I23)0fA)2RIt zs_Ge|j;MolZir>NZ|ejfIeIq6jibOX&hEv)y$B69QKV&~)&19Iu&paK3;_JJV@$eV zLh3-UWO0K>*@P;GJ%`TVi5dH*)hLCK_$Avt8w+7`!uI~3t_Vu;yDnrVET=jM7>&K#xkHYGC*lG15j1it&i4g z&v|Zym6i_{I3Evv+wp46>xDN=zJHg&O-E!&gE?r%5rco6$w>q;x2W6%GgsHBj}UQ? zpM_){y$P>hSvRFbWizrxYf{yoNj6jA$^VDqp$q&FB8S0k?=1U#?t3NKs3`S`MzrSI zmV1^|?a2g5-Ysr+J40uzu^BUmMioG=o--OhvfYJrB_|KAUA=EPz{Jh;4`feHS>6Dn z`xQA@JPf5_z+{+!T30aH3aH`h5M)B z;aAlk!!f=XE@pfMiLPue1HMs(`-TnPU;*}qEG}e*PBbxC{CBM3Ldibzj`)gPDdxl3 zTyCA(xCRX>DJhRe3%fZNU&*4<#yC?W-rw?aLjlmv6gEhhj<#DvA2_=_o%5n)2XUu# zc-2(Op7GXixl&%_e=ZgrD2mG1u!@_--7;jz7(gK;>eD?GSF7Lg&ot)G=a93C@H~Tc z(j8r}X$*=Uu_+ttxXZAQZREgeA}giOnWAy z2&dL$IQ-g8%1jr~Q)a&&3)px9JT4Q4h!=Y54=kq_^id`_3!EIHeiQkA%XQ^t6=NZi z{aw_dM*2tqoe^Z84=Gqck0Q~l#dLbAxbSvFoAzW-j4XenIfT@G!W=3-Yl0keZ!Cia z8;n1vRfW-866zwQGKoa6|HecH%DQ*Cr^UcW!bs$%<;Qi(WAo*_1JOxslO5^@?d4Ba z{!P`hJ6$~BZ{dspr(P^9EuYAzDD9I7wPsOd8M1>G$i#@Y$I8BU#j;4${*q)U!E6m* zIy!n@8y|FH81rj8#B9*tX|m?V+QVns<{F-oQYzbZhVlD}@HFlliM0Rl z4u-P5SWL8aNg>l}yYnR|*;0p*6LcHzu^hpK@9mA78Ytc&M|j?6^bAfr5_35aGSS}f^kBjBjE20yCdI(ek(q3^nrK5F z?>$s)Z2Nr=MWLirD;&ocsQ7?@z(Jd978SAjq4ZZ>Bb1TvG-N>|;c+$18h*1rm8cm9 zS8p3ejeS%fRD|jbnXiM0qw92cAJ)Q6fJy=ysN!2k(FW6NAo6w<;kzWr4&` zePNZdAfaf`kV2oQi&p~xMkT#7cLVD}RCK#f{UHpLj~L-BKAwZH-ROSM~_4jGSpx_ zw$`~8gFX16rEP|1D3^ z4$P>NRjaJ1>d;p0_}YJ0RBXzhYK8JKm+Se5imKBE7{UlvRqmxDK@TH=+B>?H@`jm& zbNNflC{+MdP^z%pu-?HDvI(A_TPFM@bA*2Qz5%o&SOc7dl^2G@{WfWsfn~BKgGo?A zk;nAdip`D~WM2cFEEJYz1#-p__FZnniJJ*g=X-=eF^mMi4GB5PWe||&BqteYMT@}I zP6ntDf7NOI8paAu?O$H@+iuUBb?hUZ{Rh=81C68yF9`%6qSIRf2xN3xal7Fj@CS^u zbk1Em?oL^u<8qstJDQ40bR&#&UVx|aaB8nJ!P*mAM~GXkA$7=&O_F(Mg6MFnqNrQ* zMp>O?$8bArnK8kwFojib%fTZ2NK_LJu|zo{Oosv{VuBHEr$6#|6dtl+haPw9R0|Pf zCuy8-1h=Ve6&+8HWb8exMOn2ol{;Vd4G9f5k}~v~nlct3UTB4xW$bW1PErT=vO?u` zdQZ1#g;yL@*T+|CBW2l`%?aKTR^=Mb+I4t7muTPBro`nv>VPxUf~+pcM@0+^HJ{O1jU=lK1~1R!7?G z`ECkur{u(AHJ6w)jYh>?tPD;BqFK}bE)=2wTaZ!P{>(HfS9-R+;wT*KKfL5IIopXC zoWCyv@G_a*aaf7|9glktTfAEaI;2}?C%6JM)~b^ zlwx4lNih|en}gSl@@)};x+N?rE*2K*W5I2^P^{t2T?*)MeAw4YG@<={Ovr`X3;gCa z#1<*)tx2gBiEr``tE~hNl&0uYVaJoZAL}ohAFkv5*3%Kj;sUFwPB>V*LZ)IorhC!Y zM>>77BLrk?c3o{0QIDRS0yt|@E)e+ zMZKz>AuLQYlNTo_;%qNSfX10vL*-DnFU&>O->GuOC+aAhU^iE`7y(P26J4E?mKw7W zfh~h5pXc5W+rE#LTe`f{?n)-h#6k6}3`*jC^L?QX#^x}Ne)H}?K?P|c?StQnGuT1Q zAat4MD-zcb`cDQEd)&cKN|UNd!Xa(9{qA80@E(icUvu1J`}~k*H)DNIki=L9*7BM` z`=n|ID*MGrq$P|M%kGPMuetiLt!aU?TikHmrGvUBFzR)5|UGE(lQIH!Yu-q|gdltkIcIH5mHjhw)f<9*{zNVME#7UuYzV@v-H& zf&?+=$0gN6z_PG`F5uEYEZB^^T*NB30J+?E#Scy23TiasiuEhkGC3%b!{@h}j3mMf zjUa06@_2tinZfo3Cp>c?gK8f67=SG-3^}NR?wm zO6^@btw+V`LRWBnMSn*+lB70Io+J>t)zwuL4 z{B)^`K}d?LOK-nLj6tk}FmpphH1KFqa6JNY?$MQ_xyI+STE7o=!xRFW3R&z7=JDtE z{39bbo|WWy3Hgxn<+?#wP<|_%9*(R6>It;^e;M3-ktjeao%HH^uiU4A8-Jf$gk5zr z4(!weN)&c(-J-*CHd=cw&?i^i{K6~Tr}g8q^-nl zzYbcR8U1@XtE~p^P&yPNEr~4o1VR1sH$`zs%|O&yFp^PX*a8$HVK!gp;->92diwVE zB6v5(Lfuiuo`*?~la$Sk*3?1)DB1!VM({2ejNr4fsQQIdyD z>3ZXRj!ocYcbq@uPXl;<@bkUQ4kTAVv~r*mgM}TSbvxer!I-qGvR!px!hC%wRCk70 zdp3PQ_MA1Y&lL!EWg&n>02sGY$jkmsobthXvc$zES;0DiE2TCR^N^=9%O3*&c#n(kl9j{_hDO9hu zNzAo~$B!cWUtyeG*6bO2S+Ob`%L*pF4ipR(C~S(+1=iQwW7>aJEldKNm{b0qwnji9 z5Jt6H>bpA&L1@BNk@l|KwR}<1FVf6&T~-Dxjfs_DJ)u`PD>s*5S6n9~bRg!(Gb8QS zL=-%9?r1tI9e6#*Bxz$ThEOm66U8}3;!Dv&5xjb$GoP~`XJydJN3%b-$@&mmFTBQi zeCxb-mWac^>XXBvop6m98pjI_Vk^G?d%QGXCp9bek0b0jG_#qig5XVyd+XZOz#rVA zS3rAzSlAlQ^D4?bty!o7+oux%ln{jws#Nz!zu#vMK1tEI{2#hmlF}ibAkVnW8S?BJ zAT|3({vbX;lF{=Qg|P~+IwLZTOs9u+iy-~6OYHW#%B78bm9eob!=E^ZgT-CwDZFYPYD)3cQ_{R;*^- z$$1cm9kb4(rU6IX-epo8@NlJJ!cqaLGHZD-UGefadAe%$rq!t_`5+%VS3hCdFboB9 zN8=vzA?sl}6UweeVu0POM#5zTRg_xPO?x`dzLDL25JCbDL|!dXQiUE@u#F~T8m6h5 zR!?Lj_?{6#vNvE6jQQf%y17O3*NfGn3ARqGfSO~E!a zBdl4NVO&#w6j9IJ11}N|6Dz-2$~%uSghE*WC2SgUl@$ zhPs#sD_P1YhGmM*qX*ZDhA%BpCnW3rOY+sUmW$fzwHa5Vxha|Je4p|mE~Z%yvwl=&F)mC#qi=5^(A_{d}sI@070vSr`yB0-ii%JxR4IvIOi|u67I;t zO?ibIrVY4N_>!gb)_8KH!hC@tN!8ys)rfBaj(r%;#QsRK#2zY`$?N^-vq<&<5?V9N zE?5-yt{;mt!-j;KMYELGdi208d?KUTY>77@^LX>0)0LaIDfGRj1I|9IX2NG}9xjCQ z1c5J3X*`-x`C-+FSclfekXenqBS)`JD zHapeLt#YlZNAi^U)*vVxZ-c|M)w1vB`DTkq8s*x}zmBgIM?hoHbfesc-5}&#a?Xox z6}hm&{I$r0KnO*LLxD=l=n(OA1rdR{;X?z8H;xFhS%no;AqkzmHF zZ^j6Qw}^(>3(!wI#XMmJ=Xr(+XiWp%-Ddp=#^ zV{6pQoh0%vJkCKX@}57=%tiCA-~?%Xb3ahHq`vO)h>%< zHQj<4m|qn;c(h%WKF6#ujryI%^7}?IzrN@uWyiF(aLXhAp{y>C;;M80{5j(_pyaro zOcXo3U_p*+8-M@NO_5`YbXd57cmb@B^8vBaoixCL2WMrBiw^;{>D+x3!si@;Wn>xL zs^J#J_xR-@{%~Y+>szp`cjMAsns*>BMvNmqB!#(2y_UcqGdSWq?J{M=O3364~4rP+B+!7=6wNaUM~~47?Fzgex%;rLx18?ETx$m_485fb0`F- z^QJWB;ce?SgKdqNiSO1HVg1G`+X3>vuWe2^c3KvCZ|u7e7gxW67IYO3 zl`B{4))KoVN{U6<1#`I~ZXsvpV^RF5l+c~#BHvrzB6)H5hMF1Qr9}7-6DtD~Zd@5* z^y(E)2Vr3UPNnVY8KikBqW7SUe@o$>s-I?%>f?dn<&bo9!;c=Ga|E0bDwOZxmuU5$ z(+u{s^^M{s5O#T)kU>WK01)i)jgYa-oN_@wW@hewh7gjbvTMCcUAORGUd*Jzh1511 z6Om<3g8M+Yfj*1rj9;gD&t7G2^$j)AT1@YKoEL)La_@>%(9K9As9u5X)~&HIt?U~% zF6hD0=W283O00jg3y5Q(6m9IW7M4gYg!Z`S5(Jfz+3l$wY8WWEMoa&^aYC%8Fxf`$?>3q+^P*)}Pl}i^dAi^}yAja?`uz z1A%b9Jwoa5<}H^7`@4<_nlZ!MALZjiX(8s>QZ9ylsgd`kG2;9CKN1(_8=~1ht$nH_ z#RYObAn3of?!ORnE}?0v!! z!6;7nMt~KoA~`oVv3>~1H3dwJbA{K|TzQOq*W0}+)4h1je81*=?|2?Sz~0@2@KxRz6`a;^V1rH&(f0oM_wxhc6w3r`6-?d={n4H)-_@tV4P_=- zV~Gf54Wwv;8bR@0AhNaEZ6lG=oA#1Oj}byvSEj%>SonpmT8-N8v`YJ;#j(MCT+A0x zSiXdg;qN_}Vs`8&;!PmPblzyVgnLF%;Flhe6leffB>TOSC!rx43yIbyK{O)lRvRjw z1wXy}Pdy<+L~UT6HR<&B_1TXVhJ#AuoalAn5Y)BT?0dxiqQ{5^T24cO2YRYw^XzuL zFZ?^-{#lW>x<3PUHOGDWPsdsp@+WJO5>algDp!dcA-kCH8%?PB3!$|~t%Y1OiQTwU z!>k16JgNXluK{oSNtM%?9H;NRb4@JYNo&T<+-b-dhM>}y_P^LKm6IvQ2L}pu>Kv9< zIRw6D@c{zA_q^UHvr|xsu1TXO0+``OAxoPo6N8#5h3vz&XskA52rD}L8cDcDE!RaX zy;QZ88*6BB1gFwpD(ENSPm%v{&+XQTB(Yt52``o&p9yBE0?=KiR2#Lp?8A8%TF?8d ziOwJrIibnHPfX7OO~v9shAhVBFx9t^4%U7VM{^xN9(F#V-i||@Wy>C|kj%89g*4rlCt69ijQv z-=%h@N+M&A|W0T+y7WkV&zi2 zb&ME;O;b@*3iF-T5jW;4LYFBP%oq+P@qbZ6hWS;=vuNeB@-m0hy%mZLO&zP#mw zL3)ZGws8S({BdH*Y|2V(5wZxhV7BN9*|RO|7j48O1Shri8WZNPszz@fr;(n|XQhKx zL`3N$D>|nXnD**QTocr()RghvY>%HgD29o~?3gr`#2zjktVPRBXn6gh1Ngj(Pm=Cx znBHe+|G78Mc@P#&a+-(#W0{=#z;UIw?oLmNPKT*yo1}GDt8JTwDbGf@x0zj^5MMl) z9AWM%FA*+V9`nz6)C zRnOcxIL^IQprCI*kNHdf48ebrx=^xROEudEYj6RX_NvcZBE<$!KfPW(s*`t))m!(# z@h>o%3xhL<5$%s40f^rO0~sv?(X&WDTP!k^)}e#g@1;5vNNDyF0o=c8$_Yudf86nL zpi_VuZWIfSuFYrJK?`^6LI=GR~=)GfasagcSw`;d}}gjSytBb(N5V_lsRhhGQaZuf=x) z7IfB#NL2YyLX1sgH$3ys98}L*YWCK^{{qWXn3rBMC4eZ+^V|`)7(nia-R1Wx4i1Y= zoFOKpE7@FUKEoCs@6!SGFBa}o9jtwzFW4!S)yIl12dvrGX7Q`@Qwl%DYNthyu9Z1|JX?6;afP3(J5eQnFp_? z@BJTfc7Z4XSj`!Fe%~Fxl{Lxr8N@LWPx0pC-ZWXuEdW_HS^Re^yG7?guCobD*0F3e z)tr*)vdLN>bWjpF3ffDkIqXYukdx3`8>NA2Oa0q)8{Wgg*)BR=G(Zy;gUY!2K)7&8 z(}H-QNqH)a=N$#yv6fP-yo!0ZhdC zg`3^NX`lrOL|d+_wRl%`ourI_LFC*W%L@}@oqSLHlPs3uzvcp^CNCuH@SMPN?ok5| zttFZ+UhihJ{75`*FHSB;NwkM2X6mm9-Tv6kCXpm6dKHn@-nh%rA6}BJK`hHvZQf%K z(YaE^WR`I8zFjeZH5phKljf>dtusicHp`=Y%~vS|Tk<5C6w|dQ^g6DENidJ%3pmh) zzLrJD{M~8%_ZW%AuXqMp2!umiO3o*pK9S{R_AHOnaFVY6%1aM}X{_E4ZVJG_XI{z; z%-Te|pASz{AQ*#3_D~h^;_EiBaS_ita`+&hb>Sck`KC7=j^y-ZA1vul-)dU$HsGfcZLTiKn5+`~%DYev z!;g_oz0<+4MPlQxG2>-1wkB&}Yr93!kgh$zWtpAecGsY#o4FL5p03y}6(crTASF;% zkj7B3#RTwm*?|=|fV!!A$e+yck-z{5?~=Vs&Ta2h)}rk=4oDTUtn4FZ83|dGW9#ad zilF3C2rBkz#A(|D$v7GWF-3&_B>4eq3&cZhpg4l4rLe>Cip3F_u&McOLFWh>=SVW= zQZ}FWYkmGOkPAM)g-E)DA-&iTW{6B=de0lxYZtsaT|8OdoMV$Guy!gm+ZGrn8Tt-xx)aBNV@P)~ z9$HrvGS!gTvBk?Q1PK{H%-&WWV#EWT2Fx1U8 zr{v+^by!JFWO;XY23}-;g+z?^j4;S;b9ObkpO}c`O_m)27b6t)W^BG{z-LlSRi{`x zJ)jI2(-pSS)EI4otENZ_g5`sN?5do}Xvo7y9skPcxCNBFU5f)%K3bd&%FaAwV3epR zraU-s%YvBTOe0<#!~5B;)khGOD6Oc-z>VG@*AG%PM6oh^)#Y_4B36$cAWXP1Fzk8} z&1IC}`U@8=Kr!))ZhPtzwK9mh-$-#iW-DQoQzwfm5k+F^F7?vjI1VOpM1SV3b^gvS zi6rDl?7Wa?V!7hL+i`^qX?!8{g@HwUX}L!5Mq!c6Bbh$fOG_r2GIp>+kv3A`xn7-% z)e3yrM#XQ<8l&e0s`}nt-lAYyCB$X14Rs|DojhNli%=B4o{gCX@D5i}`i}ycv`<@% zL=Rn*T#Kf>3&NZOG4wda2z$N{7T~0cP;;N|EI2=2D-{91{V1Znyj^R}=*S2bB@Qv3 zUo`&MX1Aw)iY9k&sEUevUF_W5!H2HvCpdBo$)~zGK`mBj{|<3r7R9U=gft~Q)n1_k zb`Gu7P9`c0i%L;QDgU&Ac-!ff-|SX0GgC%;f01RyA1-1asIh@8ytPMiu(m^(^c0@B zf_7MP*fhWVBVJJAQb)w;I%)SV9xYk$Yuz^d;UX6%3}5>D=f_o zaj9WW0el6~N$0-bECEIBx737eM8pPmbjHya}g&4owuCm zKwnYseRwM^0o#wREuW5_+CTNFD#NG8s}+jjg5m{uwjCDCtCEE=1@*?vmyb<;hXoQw zxH7d8uW}1l1w*OIatTS{Zrf?ul9Zo--+EEwzYL6DeR@)~+qw!DP{zs<$$WX*cM+u6 zArU5dCqAisY>5~W>Xh@o;;CzPI`$6@nQ@;4s+2?9&}^axjTd1r_DVVIEe@o@ZFiE1GXXYE{} zp+7=+Djf)V$z|d~(I8y4Cm3yXQ$reOKnmgz{Cp@4n0C(6MJMBk$?>VsG%kSi@o+i< zGIkdTCkFXIsK0u*#C zc!+rF0m)?x0>VVBa!B3-(rZ%gR0ZeikArD{5<#QK{QgfG5eWomMd+D%4-)IF>!A-Dj(z zbq!cv&kk&k31h?9KfdtJTx=ZQz=9@=4l2J!;->y>+dH~Mv)T`8ub|5s-Ffw*jvaBdj^aG;Qa=xLsb;e>;^dr1j5) z=G-wL&PK`-bECvY8HJks*H{dQ60Gx}ol_KM+KSz6A+T$PJ05Y=62Y{Z|949iWMRtQ zM7jjdlnGi^16xxyv`&KNS8TAQMJ9q&`GzhK2qgFD4nd`=hhI^cHxT8g%JBl6O1g zfF*v-F4B6@7+`h!$oWwTMb_LCS0CNgRIL{>)KvT6aR1ri#vYv~skCOf^j4DI1J{!+ zd$f7Db8zex<)j-+ZfzWIc;zs`Ermwej~_jP!uR(_LCmu!tVD0_L0YFj*B`~qvL1c9 zp#C|f)1O4$g`|&0n=1uI(h<-nlVC7%Q8itT8!CMoCqXZCICGkC7G>aiCSS~F$*@12 zgv1D83tgt4R<%O%5%0_SUWWol1!r)A0M8%-Ti65uzK#rSzt=1m%1kp7UKf|}K$^9R zt%X*p^+l_UVrb0zN+`0l@J1RwyKU66l)8$bNTyb$lXL2Bsn&xV>K7pP0)`XH`4tzC zG*qX6F3T)F!L7kqZfK2NVK<$fg*^89hKF*Mk!jTSr+6!|hf_a+zSeeSC+ZM*)*S;P zAszNBK)(Nafb!pUwk%?fF;Sy_a1AYp#$9zzRIPF1G#GYiA(8l+%VIMY!*gTW#LhpG zOm@QLT%_!p;uaR{G*#;4C>X~WFRx#!Q=o@yyAva7b%ib7A_n5gD(#@#80WBB!c(dE z($}tEz+vh}UCq<$TN|g|TU1Lm@j0CGbx1oa-3+{YeyK7*{ZdwCOcO0mS-;cS=1Ct- zCwF=(4kJP#6!{KMCSpG?MYAQ)a-2S{A@U7^y#57US{X1=uWDHvU|6b3Yf_Rp3>~+l z>K5*GVr8H{ikfEtm`XTY9P>Y^yBl3U5#_Q<4FGNshBby0s)N>bBH!qc(Vy{`2kc8X z9MiQSVpct^=^e}Si!g(6qSX&@6QLvn@AKHG5POE8^(Ym%^{}z7fue95?@M!)F*cA1 zT*Wn*SsayuUXj3K@)BIroPVatXtrggF09yO%DlPm^IPRCQ7$iP8x6;m0mTz_@Z&Xo;22}V71g}lnXOj?B1r& zXr;bcFPVypr+6NPS0miQj&xh%tD2J)>32M~^{vfm$IlKZ3lDLt{&@w=!rso&(a!T{ z!Xcn$waX)jxX8fNF<}%3gLxolt^jGGlP$tJ@A00+7HfzPO7y(tN^f$?<&=^#bTH#B zF0Cq3Er9{h!$QTa)31_%R<#=5A)`^ZbH6lb3up{f+)QUSj;&Jp?sC0uOg>wu0;23l z@F&9|A_rx?bKYn=dIvaom5vzBoo36u+<%tcYdHM`yj~PRKhkd)-litr#>wQ{IdhUKpHdVuWkcT*EwBdl#V{6<{S@tE z4$2<)VE8ep3iTMq)4p6)>1!iLpq+`a1CtvM&D5qX8nFu+!ZNupK+1%{|2u9S z?jxXD~zF z)5SN=AbcFG;{eRXJ?^Ocxj*Bf55_~@;C^Dr$J=iCZ7$rrlJ4b+)h@BDJ68AGAB&pO zh7z`Bpo*ROl<8Y5x>q4$zU9+gYlg5wC3><^Dq!4#%I(pMA@iAtr3#4LWDy6SV*r`Z z8v2DqtrOG|xsh+U4?r?a^ty!pejTssdUV|JE4cP$E@JV}K1~7qXYK$n)m$O~Yp`fJ zg$iCZ){^3VPfvWbdb~ox`@XHS#aw2+*IeX_Cs) z7>*{5q<4wh86S>@wT1%^(mDOGZo>UE8kG9OG#b#t*BC-S&>Q*mrkn1XsLOfIi1^~S z%)MSjKgZ~aV>*fYNkx@eW5v&N({~gI>hF*0D@zsQ@jAVNn)4cLO39tHIKC6Vcjo@t z-bK$oD9keGs(Ql?1C083fK7H1@4Dn!@WZ>tVhB?JcjzB?`7HJRpSXPX#>iqtn3LiM z+(2u5l|DC|biRS6*=UcN_LE%4$p;n^p_W$3Gh5dBS?CGEzyQ2H8IIa?Qwm9yhK5qK zS8i#&so?Up8sMK8|GqRed*9P8we}Mh(DJN#o=<$FXLkO@Uc* zLZ3LZj&Rw909A!Hq8}I*#Rfnj0sD8~wZyLy-#|CnARxIYzzMcic<>MEPx&AJ_{ZP> z{`aN~NRwa7+9lHhMUWtPsQ*A3GJwP*^tM#Q|a)K`SN7D(x5FLoou-_-$0-|ij;fNIxinX13QF;;q$Y$BC zuuKrB)#%M9B=S{S9`un3zP9Q~-GXN+>1(%$3A%e2rW7R7baqY!>vTugD*D#Gt)ggq z5T%#a1&oH7Eifw2XA=F zc*1kM;N4u>It$D=2^61EEM(F*o+=K*F8WB^*xcRU+}MR}EKfBgaJ>um_W>%v1pOL) zaINXy7l9!uY`i$$N7W{TA&+@L#D3Bg5$vHKXB5H4&a0RMmoU}G$T%V5mj-qFN@!&yU*F$;DUe{-4)4Z+spXid=FtK@tS z^b@S%8Z3_zq$3HB4nQH-H1_jdL9TM4aBsWIesqQlt&mktO=~UOT?V_$u*s~Duxn>H z!Vo8b2ME17j#0=B161BRy-^T*Z>Zu2oS9_c%Y)8%Xw6Jl>#Oz0XJtu7KP=k(^x^W# z*LsNMUw?wJ=X|4WPD6w9f)24lI(C;KG0%vTtwCb|D z_|;z^7W3%OH*Zc`hiuF{Z%qp!cU#Jx;C*){LZ7iQ^{33fq}lp_ZOMT1cBMP!_VNR4lz2%LK#y*WhTZVKjueu~ zb)QzGu1s4Smt+KPxOup-yobF=e83r-#f2ihlY_Npp$*Tx9h>O(g4~^q#n#CR@TfL{ zP-m03qOMuyMSI>K^l(_oJ^+LJDQI$+{0|4+ZiGs?+TwZ{Gu{ zTc{bN?th}SX=SCjxn*dKKVdBqGSTk>h15%L`>qNjRA>)z8OEAovSA$@>HJ>(4u#kD^@oRhyV8^& ziKP5QkAu$?<^L75pG#4GN(aDSlAzRTCo^%+Tx4=T-0>Mz+y+%Bt?}L-lbbI%VdCLu z1d>7^j>vRg1x-~neqv$K`X_5v-)WuskDDn)18#MC#ex}8v=DU zJRim;+Eg&Ps2WE+TGJyY2N>kng1p%JRuK+1RC4v?xQ1PzK*%0x@(Vhu8?x^o-Ix)PBYg7NWQ}ihFSENlJ*96~zAUTq`_ezGRnA}dD4BPP+=_BdS^0GO zb=VNJ;BP_J`anO_*e3_n=QHawdHbQ{?TkhG37j5(VZ4MR;q}2<0LgI7!(1s*YCewo z54Jx1EN}h4j+y*n{j?C$f1c2_pz`{ZHd_2Fn*GS4SRC96U~w#Xf<@h5a_O z?jC)2l`HU^6C^quQFEZ9*5yR)jjH{uYQM|7;7^<{oc{5()(Mn)OBM{&EG`R*i;E@B zUDQS*MK%&S<)0SEDuoQxXAV^hZ(_pfeY2lvrD@Af^Sy}nw)2Lp0XkfP?wa?mOuMKH$9=t+Fig=|{o zt{Y-xsxF$_+AE8d<=@L5Q02B|MX=Ju&9Wk0BUwwz+!ep3`f|&~*n(Zuq@m%S>oduS zOgLGQxZ=HFS=}Ve(9#m*7VblaCdmSBJ6bey1DWDaNS_FiOh#S`pJ6ngU z3h%Xz9L^vbHBz`zJ_s2{*~C;HS>8551$ByUhJWkbqhI&n5zb(Bh6(86_;`HnX!-&H zYUvOY8?82E(zS|qmgDdoO~4o;$BkeorD1;rxEZnp=P`$kAV1-H4JK9cDUNEdhybWn zxOpd2($fS;uzXkt>pp6(T6GW6l7m>#AAB;0vYl7VS88R=v9`E=P6s;1Z?5_>4B3)i z4=2B=S4)jX`BcI}su3Jr6rV_Irs7PkVHGloJZW}SUs=EMGJioEhu_Sk&AY^^(BlDv z(zud+jK{RBdEpRZG&=6`oi^W+(QgA}SHJ2Edp&xZbQAjR(%(_{jKAZe!iTdn`8lWG zK`^3UI61hK&Nt-0XaA#Pb3u)Ykfv@lji|hs))lQ+XWEI32ArHE?o4BPch3HD=-ula z;&jT8!sLGlGIY4P1rvg_wpw3#C{FwnVZfL~7u8DFQ}Jm$EZ4~hSlqh<+iMIb@MD#o zCtXH5@Fx3dK+S(Dzx{H1`{l7h_r+xjTL}Qr91+(72g*z?OgsU@0($L%^%AiYcjiJR zd?wk>8}1RAa)30R)H>0)GmR$P8X6beTn4|XY5Y3I@Ntu2!467&<_-kLk2j&i*vV4& z{Ez+HcWL2)Y}1qA>=j`fNOGU88+*hp6TRr4vz`FmUP&jy!=!FqY#N7e{K=*)a!nD{GGYGCZCPkM= zkwX&Tx+Dd2JRnbNu)H7G@Gw;gDMLj=Hq*gnht<)t4bZ(qguzJJWkMZGZzD8vBZjet z(9Q%X!Txag8d@`+_9oYB?j1_deG|l!;2ifN)ve>qNHCuCgyD4A1dF0`=LV;S#3Jrg z6rB6b9w~O0^Yj||9I&|O}^w}BEM{jWEDnRgbFeX(B z4A5auolsLOo7=oTzl`E41?I9fkn79^j>!%9b`*}`yjhIuVI3puV8C-E`aI|r^5E5{ zkUN)TQ;F~a$mw`c&d^=?+?3^;L{#*t6JyGylI}szh``-pyz)+NgWW#?Ij26i06AmW zqFl_erkq?+pF~5>29$=Rq>|01I+EBF9NwKPmm&FRKFOhKdcxo4W z72H`pjxmaFq!)B+aadN=<<)9zIt@2xPIo{r-6_UEbrz80zXroe_mC{FDh{`Y{=(ey z=sbyJTjZP<3%X?ehX}6#7Ghc#UMAR6uJ|gy;Eb!?jIpQmU~- zi&e@p1Anpc#xDHHRE~SMom%s#HtSr1&ei%wm{>+=L)I2#M>Y)>Pte-5;zuYmT`}OZ)0B12t z{*2s}OJvZHcPgh6nZw+(J#c(`nCg&UEvx(EaVSFA1l% zd;Q>?XWC6E$fcu~OPGdKQUB&3FYd=Vzv3oQV9gG4tf{t|0AMMeL~G!7~>jo37zEv7{2jU)c*lG zx&>@A9Y@1y0@Xp6mY2(aYeGdZP!yU1&cHBX*SO+ohLKG0G6YEfWt`98q^4; z6IvIJX+6Nqkaflc16uJ?$eVD+DH6)#>HhxWRRw2^+J4pVJT`4V!H+=&n~nqRHXid5 zK3$}JScSDSMK#VV+QYoDSJYelxVY4-aJHbb{@#9Gbw5jS&Vk9JAR427O+rP@My)Ew zD~n5&o6!mV)tH4EFh1|B7X%c%yjf3CT>3szEy4=I3{|yEw~+XJviwS+NXz@YVn5@+ z%%s>vs)ksC4g6}q_k;Mn|EAvr%nwJ0lMui>^1f&l9@I8~uB&YXsK)o9W3xMDzqyUF4JgexxHFZvy9z1e_KQiV>Oz zk|SGPq0XIeyf)*KTWqqVW5hNusEy6`=Emla+wGq>c10YVTNQ~MukIMt#VQKM99SpJ z1aU}xLV|-ukI=7s);5ik>1YIaH(OikldVmBFpD{Unux>^xL;fHhH@@NEID+`NO+pE zM9eM%<2V?3F*LFZ{=!~=3+QsWBW@GOF|+xM6i4$up(dX(o`(gZ4*o>2rkIRCmsW8$4~ z7&tio_Kg*RsCXcuHXRWZ06|fF$gvD7k#HPmO&*bEHQPI41?=~RLo>5(8-X$UZDLIT z=QeFv1_mVCj|a6EFR5+kK>ShP$Yv_rltAqJjml|Poo>PTQ8Sw6r?ovuz}wqIosPs1 z(+%+#tF1E9c^uc!tX_Db@0-IBQW`X(6v&UqPlF%2!*yvR6-44Ar#ub`42z_lNYo}) zAJ*L&`7@VpMyH!?*e{_t=%E-md<(&Jjl1^P(1RN-u>qy&-1`X`qM>ClUP$0YMid95 zQ9tUC<%zQckj_j}8j1vi^dXPO)5nj1_=EYvChP#_5JaqC0ua2hada97lOGTaqRqly z4;z4yKxo5|`7Bd+2#9RayFvZ3IKB^U(pwKsz{E^Oe-F=WNTAjIKpkjx^X&a2O5Eh3oQYqg9t*CV7;(` zz=XI&Mv6E*A)s(t2UR6zB1R!@5L^o&w6kK)iu%p+h5<(@#j+%?rvNf%NoPvbB!y)` zUCmH83V2Cq@dfPK5OAF4;KA3Put=C?biS_CFIYoa134PP z+(TEt0X*{-ebH6lOXy>5ERg?}BT?_a@UIil+%>Edohdl5#u-tovXQ3MInP zUolfpOI&9lOaUw1j>uTzIvTXagQ{1B!NwM^Au1*mnNnBBe}e7eA)ZQnDA|?-J+fLO zo5tY03X}z~%yE!ku>6M0-8*yE{nUM9DPh12>`G;ag{rTqmh1a4f!&)Hxpy zU*oFh^@ay^K+6hOE=~B5TP`v=f}@q~u63x@B-As@L)a&Kt9Up)ztBhYIXNfPxSR+E zwCW42x-y*9TH=S8#=-P3%F$qia-ObU5PH$hT(IdSn_d`kD0Tok$+$&bG18mXI-zaZ{m>)G1gL6y4qb$yx6j<4%0 zwBh>!Z9^0;ubF}hv#z0x-Vh|Zi)&mjxvk)~lxutCbu?tvX1RppqH)-D&`YR&VIZCX zoO(`?tg^BP&d**+$K=(F{kpvl z6s&S17opLHDU^e>=|{V<>Y&4z0y}yc_k2cC-^JaQd%1tC$eU}(%EfM1hGZ<8n_Jrl zd;444O@m%w`pP%X_bd=AhC8Yz#Th+f;zyLpPC8ul~afV ze&vF}ZcV`@p zCe5S~-2AU`cGJHGgO?kLG%uvScDNy@a=uTXXKa1kx9_6XWB3ncg~E~n5Qaq_>=NhO zZ+~}gz!QzV-a1vTqZFKdEO5%YkS?B>5JuVa1F46;O|B@6kYGXW4u>PiHzuk}JM#cO z3k%R;VEi-?V+-ue!QuY1=No(5wcVYg;{pY({dc*C)UHHv=+5DfnWX!xKCIv?>4z~w)*5gxW1Rac$7e0d%ANkpf8u|x^`6sfbQ(kts$ zB=I{_EwgUm@W?u)fW1(XqjY*ZwV5iJT}f*c<5vno%A~pMZ{_8c)rXJ1di?b_->UDe z!DAHT__2s?jm|V-2q((RlzMX@OgJ zVRP5cCmfZ=Ozt4Ksx7}yk-$%|6yE9q6V?mHz~I83#pQ?$;Oh`*C3KZykBhT#Lh+I{ z2AsdRvKtUv(KM~J1Q51mWqE0F^|zJf3SEMeL^+C4PLYJ+AYn~=II3b{D5+FVuUD2c z9*r}e^IUrmSYOJS8_zaMU+PImN}0`Ks!|VK+0L!*k@4U~Ub>U<_5LYal)e$7r2o|Ogv{KMhK()j5m{Ap6M zs)cGLY5exG(ZJBw=HLCOD&i1`Bw`_40$Tt+k(ib+ckL#3Dz|`e3##hb;r7ADxnM*{ zS<(ShKPB2Bm4yP7T#e2jp@`sS7Nf zAuqUfx1=xhKzLFWVJ!a)N-n!b( zCpxzOGpUa7BNH6kA4YL(&nG#y??iKKe;CoRolA9W--+zlP8|T-KH;(b*QPwSZ$)~@ zm~igWUx~)p{&R?o{6&_xG5;cT#`YgYXl&n&(g^=hQiG?J&nt=ZeQ)PInLf^;IktVG zV>?TAY=0Qp(YpoN(Yqzt@${pR9p&I`sZ+MJ$5Wkh3)17MM|wP+M|wQXCq172XObSh zk4$ww>3q`T>77WAryoXoJk2FNp5BS{c$zvDp8BN6)4w+9@$^=thl~l&)?bJ2 zc>3qi9r-IPZ&&_B=#Hm<6y5RkZgfZQ52ZVJTKTa0h;+x(o9K?GKHc#&OLsigbVuq2 z0VjiUC6b z4^N!?5o`cR+bLwC!)7QqKeI=|X(eom1js%DYfH5Ol)Mzn$pz|3KMc6plW{=KB%$1R z9AWSaG3;dab`x>DNS{Bd8-J&YR)gf8ArmXp7? z;NRaHe?K=a_xLzZ7ciu8v1Hm;%+X>665v6qRt-byEGB=qAfV==uGlIsIXH5cZ&r7= z(m_u}Pr6vt>t=_jD|7*vRC$YzV6B8~oe+#eRHbG6IM_*bZ>D9u+(n?_MTs${6R1gu zHcZCug2M;*3H>7CWytQP7PVbl1$(sY+pX>7PH*x1?N_8F`!~f7=1kuHylear4<0PY z+N~Sr(-$lq0e$SoQwI)k>N{R_Q>!aSfW^R zU=<7g^5ud>A>=G4WZKm;nHtVsdpG;5HIMd8{FFCd%`8xhIoJXF5Xmc!J`@^{nXuYr zVxVv3t{Mk)TB6CEVLGY?5?Nx5M!2`opoFY^D4JM|mU2A-#a1Zd7pV5eDuq8G>WRME zm|x;fv0>MUG5#G<#0gzq^G063ix_H@2<-0+Vmj5>81^=DN$8xkOiJ)io^F+4yFbX= zg@4l#k(i*=!L|rL%qoDvYja8%s|~A9ox5^m$)+a~dv#OnYzap$r@TbTrPBWJ_<@++ z{cv~6Za1q{v%7U~Omf?>%bAm5KA{ZDXRiLy-7%f)7<63#GqDKGsMu{Y2l34h`YIf{i z97qOcX4&TEps8?=@ocsaRp)wgv{gf+nZ2VL>iPqbaVGu+$l4f}Nj#|BaG2f>$PEh& z(Zln-4?krQt32OxT|&&qTXi4bJ>P3mc?T87gZ58w zRu<&KfQ;jb|8S4bOhtZz;(FM7K5{sd_GB=E97GZLc@1rFdkQ0$#!$q!cRC3fABX*( zm%uO6&Y8kDM;1DRBDoDsq7-+^As$ReH589-kxxFk!if%*qO`4OKIs92sQtqRw3vAn zD|8)6Q4%-0UF~O?+!n0-UPe*?xOFJP#1HF)owki!XTox+8RPpP|;e-f=(5m z6t(dh=F#3Iph?;wO6D0gv`SM5tspi!8(1lcEVCg%5x*A8>(8qeeG13VoBAW)Y0p)sBk%-Bip~ zGnJGrn8G&(Q1Lxr3X(lqj*2wS=vZP%TH>y3G+1#RGhyFxUBVDawdB`Rn_zGMkXXu4PvpLi$CYi_QNxgs;PVC`l2B>vx zJ=WJOt=`weszA8Oo2q2Hh3C|*7kdX!cAkHnQ(J&}cay1#nl{%h4tA>K-)OCM$9qJI zZsIWA_6iYa!@EMv-Vn~o><2u`9n=}C*T2u2ztWh;ncr%TJtDYTtuj3`_qsx`nQmz* z+xo)%HFS48Xckxs13Kw{D0^9OE$7eoDv_I#C=iYB*aj!AU?K|VVQ*I}|&xjmBlW#jPq&huw$ zatp)}_7J3YbA`t*I!Z$PNH>&|aWv|OIf08fveO3vr07pxmrxdFL|yLq_@h|Rm+{_E z+mi~Z|20>*LFB*wY)V@+f-D2fA#yN-d&{$km3M_s0JegDpTlu4=*%-qyrJZL$yGdP zo1FJP7_y+6MP!3m?7^dezN=9t+NKK*AoVW|{ygU_X$Ayo=CXp2tsBG=_q_bpWSd{4Dnt)kaT_6d#2IZeOKF#hJ>Ni=fdmT2anP?Xc{5T@m9l~kU(%PE>%Ak*&>AV9 zuQ#;xAxynn*9^`+orS|@-akrHAE`--+CDF$WlnByv+X`_^SRiM+ljOFFrCDxRPY0i zxa)MlO;wbn4?N7Of{~@E>60z<*&K5VEC(USa=}$Jm=07wjL#<*;x5*@g3>Ogl6&IH z+k(FVao!fpd@Pz=C#ay;?hLwZfb;<#b0Sh4Md%y?p;_E`vbj|x2U2vblMuc=6mPnN zq&rNy|8qVX8MTZ3SZ)3D*}*|oydPpiiI3?IFV%EJN*$AHbry8{*RXBLV=K^Pu>S|- zhPWS{bp+HR%Cm5$`*tK$c-09*k|?h(FE6XJ>j?%a*S;RlroEn~=BHYTr#mGNUg!Pc z89Go5h-^mJY1`<~Ozy73G4f+@+_PUoUX1LJGtwSr#fhg@+an*dW7cg15aLbnOgu{F zPEB)Vb@iKX)*0N&>Q5w(CQsPo==@@$bxh#*Jf4~{eGzv<*7x{vI_|n78!@S({iGQO zx#Xu?nTE$h7}r5Wk%{RR^QPq{<#wYpByiYE9icd!K2=*mB~JtN@*+{PfMyWX~kHJGHJnwYeW%NrFe|y!~+jjelt0=)`RIAaDPdm6862AVN1g}Hg zV;ISNN_(_r7(tpW*6l8R=?OA5C0X$MI9D&Tvg=BZ*oDV0h9~nwITb;)=sLa z!*owF#m1S=ir?Y@kq6J4ozB&-9>1>WZtQTFnJRq8h%4k}a5RlEGy*RX934hK07ZZp zH|uBGVJuXx9n%`ec52iQCcvi-k~Q_s%D1a(aTu%T$BosW8ZQqj^ELqHc2`0$h|Ysy z;!gYqChZ@|z;s_H7w!_ESq5@^I)-WQM=+f3)Uh{2(^b;opOOn_x3A8KVSDb<-Z-3` zC0$&wy>S@IBSvSE$8Io|mE9c&=Rkn;uT9^?1#<%16iraZ#QgFqd-%;`AX%$!c%9wo zHLkJVbd0+>rFV3t8VPwdzD_!mevT$lx*w-*e&hpR0}WP(9S@mUgU@QTA#}W-ylV}q zGBav1&e`(8JpSsdhmRkiFMRPWPvLu5C;}@HMv3>h(Ldk7n~!c6JHD7< z?WEAfrQDCI)liR4?_GFFJv?>R3SrFX%FO>SA;&(ztpo%$9Db{hS63cAqE&hkjJqB3 zY;4qloc^dqa&Hd3ugp7LzJ2_7`5UJN!=z_w-x}A|j~L)!`}OM(Yf}gPFi9x(0^hYI zVaV|ZaMr>;Af-6!pc`KDmW$MMbUqzx93_Xh-I?N{IK<0mnmi12)8;b*@~q(PF5S`A z(Tz19UHX8EIs}YQFSmM(>4gXkQ23i+#I#)>EvwE#I1BW)e@c>6@^lBi36f##E}ppu z^5ci!JYp!bcNq2D+X8$qo64bTzauTvnK1~CCYw@AD@&D`N2Qvfd?pI0P~F4&>YJ~Y z=B|b1)kn+APNC}rO5k;IXZY2d$MghAkLs(_%TEbzb4LYW~ikjhSUcYkT+^(0mLOLIacAP<4PGq+8Fz z9-8J*SQflGrU-3}dZLL{^9SpOJ{nkovH}{`E-FepLS8?(G{=I4UPR}Ee0h?Zg5(s5di{dJVUBNgXz&2gI% znvJJcPctZ%E$vYJ;-JbI5I*2OB_H+X3*>TgeV|Ax&dC0Bnif8}qnO_e5zeFL(dI$3 z*a0rKSA0+Jdp|degE#j5aIaY;8D{Z=1c|g?2<=T#gn;3gx)LPy<Pr+o2+B8hgHG2G%J99C$rTdAm8_&c0iCYx@= zf`R+KNO`_0tBgN)?H1g24%MUYzSK?m%<}fWu$cLyFOOF7%ch9)@3SJfxVH#U0}u1H zDf&>Cr@S{DHqV0bI#KQLqRxVUtt+|2SOFNNRag5La-c{PN*7xbd}u%C_NEG?@_#fN!%Xf0OIEU&PJsM@IDafTUTIFZ^0JT(ai!b-Jb zO)?pQAGw1aW6(2>a=}W3*KIoNY03BxmkD>AS5&sjQd^&xYqCZ+n*bwPsU_1j)cX%H9 zyjA)6;{ATN&1KrC2>XH8q&~1_xi&6;$nBU9ZpLw(%|sn_+mV}-*Kx^7!S!22W7eW7 z!fGMA6Xn7wdfAI+1xO;C#7VOZ^Wg!-P*Z%3sgq%Hl5)WsJDVF15${zz)-cz&8~>$h zJ;so-@RviN)?xtM?MG*D-e30L*Tys3kz(!c)fb;?^LNFqbb#lpuB9zIpi;b(y_YK6 z3|OC}YTN#kf1+x}$5Cn%V7cmS@~vreeO6)nU==nysI%5DmG~5t*>qD&+2$AKFQU7n zcC*4#*xX6~gVoj2>bcoYr!{rW_~=2o0b_jtg8G#4kvAA0Q`L4JZt`a!UE(vI`bes_ zW`I9AqJeNhhP4W30A{2m} z30p8jgC`fm`@0%okjR&|2f=yNK}G}kjJ=I#JDcszy{&Q~lY_7ug&Hl)Zcwu<=DX#> zf_g6Dh7&m%V5M|et;;Cr0=JA8{zlWpGYka~B%a^_^5cZp;bR%avt?8h@?yZJ;#)4L zQ{5)an&6R7noY5IROk*nB8=A-tAH9&8K+B;ZLuiThBEp#d>}B`YOhxOsy9JAR5U`RU&a;ptRKkwBIyo7K=i$|>SAI#?{~t#hXSF&SCo~`hFl=27 zNNqGknVqPGmHbK9Y6u+olTN`dbb~6zw(Rss+35lu5T5p^2k6Z7_i6Md=;P{z8H5aD zk>Ze+1H6|-l`271f(0W@Jhfv;>Sjwp|1!8vmPoU;N;R3gx=Xx%A;kljsd^#Hs0Y#2 z$)no0uNnySX{-9&IES0Iz|Xmi0vZa}-1) zuR?S)21#zi>%&#RdS_9WZ;@Ems{<&baz(_)5L7k@qPU)1+X2H-dx2&6bfp{Iz>L`qsYSF`Q9xv9H zs5uyd9eII?}(lpB}HE!QG3pAw*ecq+vpzPwmPJ*j1I(5Q8PguPpg5l zOX{oQzvyhpdYg0`K8+_)pAP~I2i*?|cTQ7U05{Iz;!_wUXvI5e&ATlcs;B+yN+UXX z2sj!#wMbqSIulj-p&Jsq7zG%7S`fAzuw}32)C_xgdR9h@r}+Yh3OV??zNEDj{HXG` z*?`XCFdIcHn%{m+U5utzE6erOWn5MCvf@Cvq0f2CCJG)u@)Wghp0UK9pY-P)EY+HQ zttbFsK%c+w9OYeFQ#%`vAI(4}&he-R9J}^#)j20+$S+2tVChe4@xeyzaOY@~$%Q)o zy?qBp!Rm7R@gwO$-}c}`n=Y+#8db^N2e)Ztrg5^Kaixg@Ep0(L)em+y6|2c6>TEoG z4U{Qh@g2^n9@ej_M5+VAxV*Sl?^^YMPW^Z7QPjZ~L^L;GcXC~Wu2#@YO<@Dkh3l7# zEm#Ezuu{_KIf6P#rxG7Xr7}h}h#@STrHWbXyIa~Um>7ueeKy~`FQ0+$X^a`oh zdZCYx*x}bpc)Xw|W_&?K_=InVDeZ2E#p>4cQ`qkrC?9-Y-FL=YyuiQIzj`I{D!3Kd zGj~CG;0#ud!^>gv_+v2@R+xD^jv|e;Z@G`-eqtGlrFb$Vw^+Z&S9d&Mv^hn^6-EC` z6;E%u0#2<@v!dn-Yv#-$+efKlwf;?QG`tMQqfYUUSS#5X{@?{Oe?6K7G)#IA$uuSD zJ(AzA?l=wO?wz?|z4z}}%27>c#dc3keHuqsmvFe?Gg4?Tp6|Rg>g!8dd;MR= z4;@TROXN)$cTtC#3>=4(;TZaKr}OfD?7iA^%BY{kx##Up{CrAr$=ISO6?eur_Q4q@ zZ8H%5J`LkZCBJ@_J!mvh{@@|n-J3r|s#12E7DpeaS;gBm%V|gPM%u;~ujm#>;Q&s@ zdrZTqbB{s}88sR8?zTmYO7DHug7WH^p&T?TtK6t~(^|@#>_Tpb=0JBY1oA8Y;tQ1v zQ+tAU|NQ~FGr{a+)uBA5)bMK-z4x9At^R4p--#XJ!<}A*_r*iEK z4J>)>EzDdYcSmHnhEfQNlm30GFX<&e!6|}P-GpK8hfqFI{GmJkF_l|p;1V;&PQK50 z5U zSkY>!dZ zrMLJ~E0#7l(U)6JX^L*i4(QWBX#NQh-vSUYdPIPHO+Y|5`siMNa}yWbY-&S0ch^-n zp;6Q$4(y62mo|k0I8gqKec=a}io=*OxZV(JBSR_ZhkWUchfv#~eh-qxsdE&JaqT_d zldvKTwq(YNmBQxGHFt(}b7TdK8xZu{+|TwX8r?Ti4XIOy30rq1L2UdJYwObC_%&I* ziVtv@#$I@di&-ov$!7EfU|eHAL+;RvJ|M%Zx>CPfP~a7D%?YJ+Yy!^l!{7d<)+?`g zx&x$M;d`ea0IKbVNoO3L;rPL5aewu^qOLtssn-L1YL-u)Y;J8oJ3KmmRYp*UXbd{S z;U=9`DJ31!v~Q;qk^w9b3hYCS8oo(TN5Q07ZY`d)H){VK)c*BKKac`mt5Rmfik5~l z2sPOx9b+k+)N>6$3AK3bK7J*N`#IqU$Z*gLLtu+y42)+xN5{YD@)ugc-!2$eyBO_R zoYUC{qzBLH>Z0*L)^;Fw#3{da>Yd8*UrrWR57)`Ib!clm5QKzBu*o)IgTY1{2WU2mTlfe! zuWV_x7$&1SZhKrc74qn+y1^tMb7``4(R->JVQ>>b;r;7sVL_XplJ(np7-Jj+^Z`2_ z0_Ld~X5lZ4bB@hv7I8b?8Uo`lzX^fujM`Hc7aq*=60oxh1!xc-KRBZ;K^?a@rWulfI_E`Su6Or zsusze{8B|Nzpv)@&z3b$45Zjv^#HWKXsr^A;_aJ?hO;6G`r}$nb_2I*_+2^=Kxg+K zCjCd4L7;Ls4|ks;?@I`lh(CgnLTZEya#ugX`gx69R) z*84K-*U4C2sWQ5dET5_c?N+fvtUGxo82N|;-Ou6<$8a!#uoB|0v@;xsff(XD8Oq`728E((@FGW7qtvlRq-)a)oWKu5(;o=C;S>1f~n59=BhUyG>fg)3NfBi zxYb%!@L!QD{ACDwtkoLn0L$M6UsrK%Q`s2Mn948?&upEi?rK4pl>?pC_^JRA_?}6 zeugYMk`6nmAm{QtLH|Ji5p9>-x^`prmf`Fx6RgKoWcdc=w z0^>#>f|J!(u=XoXk>q6M)&DkrJNd^CuNqtlB~|I~db*92n>LG7MR_OHR`DOLB2>cw zCJbPDmQ2Qr^up7!h$SnP_Xb>9VM_BiXCryykohad$H5$YqP3_IqCt$U3Vy)}bvjSyT|SA{ilV6s0Ta-?6=OSKTYtzf}GXG&7yi+SO{aFDhhOP1JWRoB5dFF0^xR@ zf}5VOeP!l{x9{`ndaotIx))kL`c~z| zp==drFqkbj9%rk_!48~wmd;lU{6SxEP65+RlV<6M!mVYYtZ~CAgidXorb-M} zcej_yw(Z}iO{X8^l)dkuCZe{fbJXi~wr^jGY9cu&yp^*pR3DUu z`-lJ9JlqH2s~}}v-UR*%}da`(iJv zy)*ERnS`oq-g5hRMMm0{NuKE@Tajm&!<@|hu9!@AZ(s=V&YA=1{t}c4WH|2U^ZN)E zLDF#Kz97~hsaqEv7Z9hduP`p$a6Rg4RTozRFTd24zlVmDtWLrbi{RUw1Wu&{OOZ-s zqBegdOKMx{b+nDibpLe8J+;DN+=bh!ElE`M%YI8(Y@_Tw|y-tJ+Iq&ym}J$F#KSSwsCIh6{Af?TWH!R z43e!mU07C!r)wt+J6VL*;Qeg?lS&{~RqaL%acfoK%M$KNeS59BXQz49>}xWlOJ1MR#W?F>wk86lR*f{p({1A;2}m`PB9Q{ zXLm&Oo9@F+YHReSLu7EC==j}wy}A7@R-7Bg*F5`>W`laV1|1WNoqCw_fMhKFR0GIg z`N^!Dc)8`&ft7Q`(bhisVH|nGbCC9)l$A+PR8HW#WOl~-i{oy$B8zjj1)Mo9Isj0P zHh6A6Ng94}ILc7Movs*Vdgpu(uU4x`ZJXHi#;)y5kn1gSTpkSS zrQ+7Xfx!Qv)hQJsnu_nXM5QIv%IQ|AdM$NDSzY!EB2$C5G^Btk?rmqlB%_aptj#oV zR+Xc*{ZyKrmEPUjlUt=&wN-lZ| zI~IR)Ot?ixIBOd+Qo$wK(2`Sd_dQ?}8|aivbP*L|q8kK8lR1M9I)%u0PZ4<2;qF1Wy9?ni5;Y8kBdKadvLGP9 z(qb-ijdTNK#dxu0C=Y@QaH^54Rs&;H8MPMDbr7`dCbf`wzV;km&b~{Cjb!CP_w_W} zPytD3inG3miUnZW|FnvwcNl=%4zGISk>9KKl2|pI`6p-Aw?Tf|eTm zre4;Kb`L>sw+?zUmNgTNsn3@X1E&XDOqoGp0xr$YrXxIy@n-YI=L^kEKQ5zaOZ7M> zQLx((tS_2A*$Z-)VY<1rDz*=aJ`Z&3j)HZgCI0e=Rs1k!4n8et_b$j+9O+U6cRw8| zO9|bLK5hr^M%(%jzMC4pYh#sxN@fUejQ+&AMnU<{-Gc<&?|E&1bSLsJgZd)5%d3|= z+qblJX_qa9p&`X+uxL*ttkpnFz#$L$9p4pj&!mSuRiynVIIXCTS zjMNs&5l*5|Hz!D6F#RzX;x1*|99m?peXRWhUAiNwRxR(BMvUx(moe-#Y4-Ny$wstP zN%m8bsuVd^ecF~{)iyrJu&FYviANfFO!?KKGBz)`PuaEW4}v?9ToKS0$v5_P5BBed zUm&DZK7lXl^8Eu}xHVsp%bAL*UkrPoK^9}9F67|L>}-JXDMqiE)?G-!!Q;qO!G4DiRDh@AxKi{uOYulM)w=n{@VrE&v$ zQ&%k>c)+cBfLhRWjQwI50uQqoA9x`TZD!{H602e~OF#X5B52Bi7|E^U;Z34QHzq(| zF1;}p;VuQyY}#Y4y50JL4&9L~Di`+)BRQSo) z=5RMcDlKXj{(dpMLJc)>jGwNh2&*O%-B4Ub3`-MO`T1uSS>uOfq_ zrbpId+`0IgL7VIyi1&D)Q+FxE;sSqh#3^I>g zxSbDTZMIme&?&;9glMZtPK-fJs6v9DxEa;1;Cz8D^n&)d>*@SIn3FA^j%Rnw53P0w zuxuEs8TG$0Y0rd+5xqiK>Ht#C4|}hhFMr;9y^DEqe%{-;Rws3CUOc-}g*PxN^TO{^ zs(GU8v8mD=#lM3w@ma+I5XQ-s@O%n9hnb92YCf-j?hk`LmRZqRutjVn*c%gSd%eNv zO30{c%AX@fe$OjoNGd>w5h2t{4~FTh@o*X^gg`OTl<}#`8AFF1%-^IV7TZ_wYf0sK z!!XlM5Xe-$GU9q=19rj)JZ-7gMXXpOimKF16hT}GlHU-GLZy8LQitEdUzK0G<=7%d zACRf&W`#c|#MGYCG*4Zj~J&YbF_IF|WBkkW)s6uTBL8edH;l!3LE+VxWL!$tSHq8|wQji~}L5phWcw=0-SQ^JD-I-1e~Ks7OA$l~yaC~c<9;7$L;#F#x%z}M9=aoMNCiKD{|~ys74hj2=*g%f z%Tin#hD@2be-{qxmpDtB+5x!me z$dBajx8JS2qfAixnHI93H`f`f5Jf(I1ruIRnXZgy#gD7TKpH_7`}k3;rw?0o zF+Uk?cftJ|=i!-M)H=gF;sNDo=0sU=_(1E#x_rSfN5abOX9-rEZEV~R(K6ZdP?ZU3 z_A2MSto|1aud22|1==`KD($v>qHzR%Boi51Ez(Vj(B#H49Fy?vV2t|P@8bZ#ixaQq zQc+Hv5@i?TEW2<3fEjpgZJ5IbK1~deW5-c{h{|Z_wtXzu<8~{6lJKSmC|<)qnXM_& z5N09Qxf#5#cU&BlH2Fnu(ELCd)ur_hr6YncFMh@vlj6*Cu>>UL*Wq%E0d54@HBMVC zvLGwn6ZiTQl@999=3~(T0)55?l1fzTR3*ip7Y9SH15dv1`aORHQsED{BHz1V=nY5s z%f}4&N3XZHnoZ2ZBuO`X*YCGHf?#y@E`gGT!aIje0w#+&1gV~%Eb2)gm*3rIWPIhl zd0iH*7OpKIXecurlZAE|j8D(3l*grz3xW>I1OrVy{~e=oN4AAs0BkW|z@0a79! z3mEhnmSx2%zEs_kQc5A8#(~^{1g+};@G8L}f~Dz>VG7a86y^yjjaPbwRmp%kN*XB4 z!DooxFv}FlTcQ2Dcs2~)dwovW9pXNmyImj6c2w^KhClNAW6u<>)8uMDr7i|-+`r1Q zLIXgi0;sr_SOWv=9JH)--2I?WD1jmxV{%9^-qF~KU8 z1x&4ZaJX}DxWCoheZI4Iv;)Vb)%DyyA3smo9 z(~%^w@5OHskO3gUCk2c7LD7C~WMNEnx{*>wEGedW$!Emu9tiXUfqo#+4+Q$}PoSe4 z$Em3(q4zoxy~Z&?y=a%#vu@)u8`Di&h}%d_MDa)A*y;!7x&)%!aO7bCeDz0HjHQJm z&jW}|J*(Z|v_ztL4{d>fnb_WmutGc$>K^p(tTq;I=Sz~KKZ9L`6O8gHJ@TDE zxMedOwOcn<+U}IPz(|1G5(zh-xx>@=Gi1&7vrac~i6Gt7KrVMJm24%}%QTB8U(Rj` zPtql|Tg3$USec7?Gyv=$iM8sbPzwVhoyRxpTm;<{J+HS^#?OF0%!MxzUGAJeL_1@w z@`9`n$fr9oSBG=rijRnJJ5;gGf#J5!&_Gk$!Pw1|L21P+1%**qbO~b#3T3~ z{HO>3v?$gQ!lD+9lizEwP`r@wUB9H82s8pOl>VF6Y?x>kX3S!mY0v~d!YZvT8#9n4 z8)fG=`-cl~);iF4VZo!Xe6`S7T%@mmC7z89-cfGhfs z9_bv-3-A?a5q7bH1^lsCR!fIJ77KImu~9GvS&!bLSzS(w-?JG}GMd%tm=4-_vo((? zILlI1GMJ%Pjl2}ZX)owkF&FyD3H_5I_2A`eE-O0m++LC~;km!5_d{YnsSbFF7MAof zfz}wn6!MT3`P0tk_RisvSOI`PM8})y7%9)Yhr4gYlj>v8#IM2{9&@f43kXC%s%Ml- z9{YCv)`&97OY?&ix%__A6DPY)? z_pJp7cZoO?ZB@g$Y!qWX8|2w&+`rL;sHD2FEt*7Y3Si9gCoBq(Iy+#6$6`etHQHLP z^_bkKcDK{&8!I~Hn#gWWY^~{W^DK8=Oh3fYt1T4a$uwW=} zPkh@C;xGGwdZ*kU;_vm{(q0g}N9RAZfPqpmCRcdVrVRpLR*)SnxoDi!?_Bn|)`}?1k_|o0knMnYSpPbix zS3|c2uzFOac<5oR__i)Ze1X`5-WFcFu($gRLnP2Mjt4{Tu?T6id*NP%v<1OZRhs(N8;jdyAsDFbW1#lfK>dhl@4Yw3Hol5uK>LSIr|jP54LM>Gnk>bYiV7 z=avuuIr^#j3yAx>`>*7|h`gWRH;6;x)qeBE-u|=Z(a+D0Uehw&%udTrS`$pO+$i5C zn%msi5X(AY71lKrtC5wb(0h;JZ^`F+!P@*XR^XgRQ>RzaMa;{i%J%+IWC|mXK{7S7 zzY$%io_MElT;y$O8;)umXp?}F9-BV4Tln;*ZHIOVj9$_f$l+Ko8Ji}H-g~c``_KNl zy?Yn~UURe<9{(@l8tnR)k7ez$P0&3f53Vzp3#fIyp1hex0{3DIOD%T0UTd_fB2R$~ zJ_r25t^{Z3xuJBL1v(kZP|B_Sy}g~S*UeX(FL#bo<7L>RR(+E|ox7lQo+0IP#bDg& z;MG{z3*LK{9qvu>g9TmU?^kv4Mq@A$E2|az53&QK{iYCAd1IGCRAAa79G`?Ee>6rl zhOz9->kg3m0EP(|HeOnz&lqagKsf;m-PZfC>xO53$M;b4fyIS$<6?}jHtH z7}0PsSr0CmtEXrZrTW5%S$S9;9 zjxBMZ3*KeR17`K|=$EZBz~ah=>;JR7T_PeJ#`BOl3%$(Up=irdZ7@&@V2(F zfb5pTKjKAZrNw~!5VRjX4h<(BzruQc|26iaU# zjoQ2DcZ>LK^n!mb>bM9HI9o0KTK^o3hkoZuKbJpsw?<`YF_MSbBP;TxCMgg`cmhL3 z)>=Oh{?n?qQ^il&w{o>R$y2oWBFfhzS!MrZoTBq(ZA{lM>0AL&j7|Q zO==PvEH*Z2_S{pyMZ7PPgQ6GBR*zx=O3`;p1}nK?{)Bki4*cGvWD040^2NA;3ujOd z`xf`=xP}@IE*zrK(mU98@#8w76s=#{SL@aWO-iYtL^Xs_W!9@8lj4yMwveq;#nUj5 zd6m*()E!lUG}eZGIt86%L8WX^9XFJpc7{%55eA*Tp=D%mFoI8In_BAbT453yi<{S9 z>1dWhVxTr9cc6w!E6hJGb57J*I2^EJfE#+J-evt5`51gB4TvMwg$bjvP+e*)0!aWs z=A_c*N|n)-O+R)(MI&`uAjpg8j`<^(R#$h>#rViE&{DUK)MUK9os-cgb8L{P2&}LSboXN&M;#(HU!9TLAFJM(MF*bQ&Y^1HIyeG%>>4Ar)FL6NK2T$|wZ4 z#~_ahj>2IPwFA)9BFmvf#8FlQmkjoUWuU)6m%sU zxA4Z9lynY}?{qwwlcoh6VkD&}1ziK6j}jC>0ldLRSHk#wNeq>WL&(yI%(#HxRX_=Tlt{FPM=a?KvzW%$O;S-Uzah^j=xHn1+@>_c=Y%7*`F6ja2Q%1$BF5rejIAd=oC@|4n^UWKoiT!f00I{ z^pYQFC%S9HmHeZ~|I#%#g>41;t_~f{{NA9eM=^ZndzyxN)to^ybBG2hdn-i6~4C>FU61p-mphJ4JSH zRSRq${DA*d2)nLRdsF5uae=XCaUitw1W4KuKd3(|+O&Bst+Bxcd{j<5BZVj3G=~_9 z#GfYHC7Jclz1Z2|1~PmPlY^2^Gm32&Lw^Jqz}KnRDZq>V0%j?JY2ekviAOoiU`25v z$S#qVzTSNC%jV%i1p4i}MdW3!c(s2Jjj6f4^L+E?z1M1Ncs#`g^Wd;{5@4GFW?!L; z8{SsJJls4)THvWD=5QCv(&3{G%uy?QDxu?YCmBy&-D9 ziKR!ic1hR?#4y){o~JRD`f)so*KwhE_|o)CpLJq3Qs>VK+umkMd;u`cgepUGPBshE z_H5p^ijr4 zG$4V540t#i`TQ5(ci?qQj%qg}qzM|JHFNCWjJn=3A6YJJ>F6>6Uxms`HsLHL9kr!~ zq`poY>0~c=fjn+@`xr#a)QVoHgo_I+iy#1xJQf|gE-c{^v)kwjIT$jKh1EqMZJmIw zxG0G-2FU=Uz|C{?Kpo1uxbS#Ux%hyrTxAHa@Q##ZcY~M!aSgq0C-Od!P@}6}>9I`? z2q8n#ZV2733&`T1_Qe8uE{La16Jk*^ycmdh)RYq9>1 zVtiA@I$&nW>?Gd)Cf+Tnb#7FpbA;LHABj%IlveAdV{E{|Mm*kz(~!sgnie3$>?-rv> zH=(>cEk!ye~~XV^}U$a;3+bzVFN8h4uv?F&~TPTn;3lROV!_vhi!RV3|zf={Q$0h?nMu;>iCSWAV3e56b;`hS$)B~^U1fQk!*K+D589Y%c7>={C1du@K{7dci%040J@0>nFd@3fyuK!-aT3aqvrCjawiKLdON<=Tg{{Ziq6sBK7bt zU6iyJtHy~PokiJmXf~KGNXi7LeZbdya@;LcDs4X`Z+~|@ z3MwGh!w41)8+0yWY;W)FHFw?|>>s`^#THy9X@!N=IcIaXkGv_-cnlH+x&`UBTkK7* z7DYSzvX$uNPtEOr@9jS0EED;oMLxv7`SHP?A=XXAuBU626WHH_P4Uw~<>xnSImhwf z%g3wuG6EqRRRu+KB2AQ?Qh=X~r3Kt?(b?8eLbTwREnn{)35??Ck{HPM07%=rq|#I; z5X!T`z+HN}hSx>&;?aLh$b~t5Xz_I}A)L!Q-+muxj(_>~apk*r#**&xWAV6pN!VKH z0K^&rR55|#)a!dgG!varW*(xJRRcme^4xYAY3tDI1}$tEC!t7ihvPmvFDEEK*bc(> ze@_PkV_5%0Z(Wtz@q)uRkgB3)hk1H?9vpD=UmmxC@PP=9NqrOdGzuD_DPCI0>z+2{ z`jw0ZSG!lu!q9}zrVc*Ih~QGwTI!DiJY`G2_e~W3f3M!~P1lQ8KZ~tLk0i2s9A_b2 z$5pJGmRW)_>jM|Qkq6Ts@pTVIcDKj9LFODH98r+t=L}Zod~NCFfgY&g`%gE#eXpg2 zi&XHHf1&gZGTnh2hGu^G&`M_}FRj!U ztJ#v6DThrE_&&WX#&@jQ%}@Hk5i2LV>y*M2Cfx#>Oxb`lrMbTg2cDf3B6s-?Cy0Nn zEbG5krr-Zeo)mEw;s}yOMf^$kSA0q{rYU*FM?|t4bBss-$zT^i&qHO7kb-KKUc>v& zdFgZr%E`FjraP>yAG6j_AuFfOb~%N%ba9VwQJyq9<0dW87%TsRzZYXWmWe|8T)|hH z>7)}V4ok-Gmrla=QsuNi#vd5;90pzBLm@r0btS`ZJKEWKlmm$&cL^gdzkS*SBw~+# z78@l2L5t4642{sEe?VMN0fHwu59|%C(ZWe<{bFm& z5EFoVuPkc@?zSjwfd+t@5#@l>8ZOKS_Z(JXbi;{tZZWYv_sqM(sHxEqh}gH)6^$RA z@1ERnJeu+53`vhEI+=r0UW&nK=bLZjAKxvjKO)VGkQ@fwMPl;;*xn#Y{wWrgfXFNn z!XJQ^=#P6O>gnr4q#=xDn6W?97oTkq>yS&~h4l@0VL;QFn!Op@&@x!g6lYx9OuBVOl{s zhUexOqI30_WHwX|VB^O9$VRT@w?I0YpiFnqqt+uPUYM&%^}UNQ2%k<6X8&afvs2^$ zUs8FXRyplnno^u8uEA1>s+hr$?*%IF-|A$zmf%ODoW-=%3_&Ema;*@mdoo%$_l zsGr4SX%fml_$)p6EKTpT^xg8x=kZzkZu!ZB&(hz-XDK3xpVV7Pe|9QAC9CyR9!f@! zgl`gyHL0XnDL4*pu7hE5+PVUNrpqB&;)3dEW;V-{c&3xpEO)0I`9d1LGeis!VUwf2 z=yE(BycqQcQpRM?)ktAo{J!Dbz+1|8dNxK{On!SdDP$^Ovxp(G^W94#CSWOySOuMR zU1pLDlGU11X6K~JD~X_hRAEKu;a9N%adu&n@MH{Al8(#!&HJR{Hl>V}TDM8xyx1I2 z{306gsUD0r+C?Q^v;j8323I6+OE89H6ht~(5J|ppQ_es$z99#g0u?nIh*Wu_rsWL% z<7~tV1F=y0?y6vCk83JE6Ynq;tFb#JxXpSF?N<(`QDVzG3`S{Tv>{~;FcVD88io3cU4+-1D^k5B;kIr4$uTi}9liQKgbeNd=A<`Nb|?$r+K%biIaYAiSu?HjUBu zDfdQLLpKlZjrsa05|=VF_eVa3+7n913kI_zq7x3m0=9%tIbW{%Tn!hW*-a$%u2xg% z{(Wkxu+me>4YHkK`F-Hy4}AQAkN<7>_|sV}t#{4GpWepe`oPB@`1k`KzX2aVbBAp* z@q~2;5S^2o7zMDhfz%QA)e&@x==jv^1}(G@e1-3fYLfEuTxD6|0|qo@Ovz57p6K6r z?ziDIoLuRgdN&m`F4*lI0W;0VsgliZf~hs9qa{uVVJseFc^rki{fH5}MyWni0>Cvi z0FlHn3NWi!)HNRzRu27`fN|4r&yJ4~gaiuOujH~BaT>;J3uk5+#;==)uXbO(SjXbn zTU(__7*M_%jbjoGOT^b3$8?EM`EQ9btYIppe&}|*#K>js?Yo1H#kz4~5xUorSrmvQ zN-@%SXIApM$q7)A9(ar*X<3@A7m9n^i;?IYkJZXKAGZM;5AYt2`;`0*9jfurpG^NaG^`ZJtUuQ%26dR~2H1L&(;}vHS6)^|89tt}d1MV{!n- zJVR(Dzj)Frl?j}S$>uQeXGm9IazRLElzJibYEv+OY$fU?DlWCT*W7>p{AdSrx;@+5 zX?|2so6q0wZog~7cnVfiR7ov{b`^2-f$AGTz~-A{QcZ@8+DW z1ujJd9aMa|gvO)xM} zSJ2f5;k@hrK>~UWKB0f8{pMX8VL71Kc`T%cjz;m5I;2tsQkoHzIu`}5A(m|cWrNuI znM;vTCmtpPB%zpNA-e(mhq)&Fo(h8fmFlknnzJJo0H^Tl)_4eOkK5pe;kYNQ7ZwFi-+T*H2v-u^Z($P0CxDJEulFj6Rs8vd2p7eZ;lX9~c zXF`QWZRQY4&W;ww_+Bza3?-#BWdsyCLb119rde)n!A5oAy+MmXWgK1cOz@2ijFib@ zWUZZ`7pt{{5g=Wa57AHj@EVD#TGMs^pRf>*#j%*#K!1nqXxy6>(Lh zT-ha%h^>yLlvLUB{A6%!KrGyTrxY84CCHVGR*6sYszh!DIkJI1vr2Mqx)=@vdx$aE zu;c1X$RIPE_Bl=YIEq(Uf+cK-QxIO37PA2vbw8m?L%dyHc~_<2riNIpzFn?-XZ&1Q zu99~c>{E+4xC9i6@A2(Q1O|Uqzk6I=uC6x3pa!~pHuFTYjeD_CaOr^Rl;=m5IO+1 zkZ@9MwnXA6XlbQY2i*W`d{G{CqJRiSrBHA&xV>WULni?3lr#U*-4LdAa$y`%QgvZi zI>qNq(q(DJoS0iKNTifXjvMLmO%C;BiX8?N5Ca|J~f(7Aw$w=Kiu| zttj@~{|3XGKsem_WtTw=y>lN4&vZ~W4+Z>RQ@Kg{Cwf=^EFNyY!cKQ@CZ{|O^x<#ju0tbH!k zl4Kec=H|se15mTi#51o2RQ1FK?)LqEhbNE!?*xsca3Frb>z$B=JxTnicms&Z*gX1IL6iF>b_Wf~P}=_Z>6 zBP72|`yXBdVx83A-agyfesOs8?yY!NLxUjv+gPBxV5}^=BDObQZz>aEtmo$L>tD@& z)0z^eIEY66yKJHQcH9S%*rtC9y_F`>H&gMsr(Ol4w?*ZRWYm=kbjLv=UDQwcV9b$9 zNSFJpkLV;u=uY5v(Xe;L7Mv*=}RNtpHh&RkwE*w9mP>_Xy=&(`l8x3ZqkE!|kQtj*33)`xle4ndimt%x&l7_t#C2{!4ZM|Qo zl!{S8!Lq#9WH%XhpFu;T%Ik+ko>fjkp!g{%1yfBF($JFAE)-W}+3fnQQCUV^(?JZe1PG}>J+BuGBVf=v9QQbzYg=@N?kP&h z_*-UkLyoK>CDF`9YcTLz?*Zx%`UJg*9j!ijD*oj^tGHeNw2woI=5peVF3=9ReECF8 z2|u`e`SkhoE&fUL;k^b%sTGBI8Jy#2K!d`21YseJPgwKefb ztUO*@UHRsl)o+)NJdC}0( zp1LtNAA=(;ow4HQU*T&s@GYj76ib&Yc4m_BMFYkeIi09+viE>m8k!@%a@%dbM5bSi zN?ai&$^e#Fi*kxyE^~h^&cT0)++I=1BV5BQJD;+HT2{hiE;ZFZmzB@8kl1hj9O#xV(d{_w%(x9Z5z@PE!nQ&94kCenlR@W&(t!OqGPBtG-c*O zORf_%WJ3Mja+DA4e`m==`dcMVZ3XyLrnHfmTu=YNb>pmqMkOuuLxh(};1yrV z0}^P*1WFnE;$T(AuUUYjZVJGf(dhk-nG}#tMLPHtuyI(N$d8X!BHLdcekj=1!B!`m zKwoy>wzl4>0U9~uWSTg!(DvLele5ci2RJ=&D`k?H46GW1U_vBVk=$N8XO4{8VC|5p{9+ zf!s@{bQjha%`_qi+LK(4;d*Jh~95W7Aj^9?^TfC$%sViNjZO$e14iws^H{YnOh@XnN zo1BNayFCi`aTsoK9E7;#+Qu<`8YHK>zgB`xISV5MUQA;Y>3bv8R4@%R{RMb!sVG?d z8ds*-+}V5HY@)D_jB!U)v^`P1O2ibzNjEOjGg>FQVN6*nnWi8z9`R(^i^DSb-0Rg? zy0!0aJ|c}nNj;Vt#gIBi)RH+1V`(*&c6J`K_&$5SEmj-VZ&NQ?X1rs5eP-OHtX97T z1uy6TZa|U0#P7Rxop8QECI~sV$VWU6Ra1g4VdB@x1Y_DOB&FM^q`4Epn1+cQ~2t@?&%wBwAhIa0DhZEx z4WJm}S5q2xpE1e-&FcqEuRj`I$rL7zMRUl%=fW$g7#liv{a%>`Ff}mg0u0k~DzLXK z16HwjWsAJk(2K9U9+{w{kKZb-9vX&%0pv$iB)WiS8@dRo9paR2feV zLz%53)`CZWt@?KL@w<=uuj&&1{q_kH1eEGvXkBJ9bblm2h<83x8ebr4QB;j!RcWYn ziIjZxYq!j=7cDz(`dZ36AOV!lbKghyNxW~e?34+baFRh2u=HX;zYX)3<_;9E*G0+A zQfi`*0lu4J|0XJmSf<_Two&)hV2H3`SY#JVnUVsmicoWeWkBgmM_6~7BNY@LxGFkK z!@`0Sz)6N~Pi9r1opUIQt9ZS?MFCwMkO&;CbuB7AU{^jMQe_mh024Hvtv7FI<7!*X zb#Y%$A3ds}Ll+EzBZXU}?K5(bdPWYoQ4vJ1&xJZMnbsxskh3iF$7yp<{8Rq6Le6R- zCUV%308iY{7e8!mU5g6QxeDS_g`TTM$L1AGr6cejIO>j05_AlKep3GU_-n<-06~N9 zIqgN01V$s7*__bFofd=6$k4-)du=^he7$a}nNeFTx@b1b6Lt6!ZX`OcwD^Fe+(sK4 zX8Y-OEep~Go_WeB6TM~tr13d#GNIq9|@cXf);Je?B9Fkc80j#D}d5H7m`h8Me#;rnH3;y zjwM_EKj6=$ud~-#uC2wSsc$Gf-B6yGx5Ef@qz=S)%htWa|aR z;X)VGu5c{q)s4F^GrO(FXI-KhDmxPD~nWp6V?VOFlU~iH1P@)v16$P zxL3#(+vAoOxlOAWt&9Mq5(74iWNv$~Xg$iPV3aJDgoo{}QK~EulLMLX!|fYDC}iCb zWuhXRD#<$l4y$LdDBpkI+}y%@fGFv@$`4svqI?`tbD(=mwL$@SNdbMe#KL0X17aT< zZie1yJnW0*jly+-A!5cbfYj+XTTPV1XyF{0m&nn%Gz*|J<5ns&TE1%BX#2;I~dYmJo}KOYq4IK$F)sbGAgevBm*MdhcI zoc>lWEEPx7Cs%-Ca-`0&E=GYw$5n--SzeTSfDBYE|vdQ<&&aB$#!{ z7uQSn2NS_ZNt@^lHm{P?;M)L8vq0yhnECYBaBBIGcJ8k!GTXUSE248k68NkxGA-l= z@d?Zd+VPL0L795cdLt1JWN;MQIx?B-PO%Y(%2#OJ+E4ZzN+Wy@AV)tys^Xa5Mdtp% z#9)K0ftT)Qzw(xS$^~|`L~tt#K9@?n=N_o`1J(ZGsrK9*&}&xwrV-dgQerD}_dAf) z1kk30s3w#YJp|bpWwtEZX0(*eFw2!x1rV(n{fM260mp5ei8dC&WY;M$?3| zW|I?0wv>K3&k^ZpPxN~}=DUVZp9L4BJB^00o@n@{7;UP;MgFNNsZ8#RYRk2g#=4BF z$>e=g2KkO(Ii-6;7NuiI)y=$*vJ@`<;~|sBLnecL$n$)R#K?W zSo%~JJvFoPrMJL~DI+DOX&FtnMxEXPm}co=$vV!x;Ykq6ikYzNb&Sv`B+eZRb}CsT zVpOA;wib9c8%2JvPG>_)BaKA-ioAQ_d!t5?ye?}EC6zRa7|%jVq|nm}iN-d2LA&^Y zo`GzFKEBsXWz2NXJnBg!t(?G{t~b?)Q$Lw12_vy7aiW8g_+BJzGC#m0TNY>(KS+V+ zTDjM$%m<%;^*#0>`C*B`~hSBjgd7|6TZ{&Wu7bS z3sE_X2g*(B`Z|knH?99`XXtq#$*t%yr+9Fxw!pNY^|PaGv07c_OK_FYWK1_bDm8TL z(WBvLxf<}@&`8#E0aP50(K$~7i(LGlk4ISHS?3y6cjy)uX3d^5mvgpj{TT^Q-)oUm ziMHvm!#jHQhE)2=?*KfK85g7)o*!f*U>Lr zrT10UE?BWf_wOi$7qNuUzKFpDW70KWYEVO+2tAiTOr37cJPs?%x#vMt++@mn9pR7@ zDq@}m6{ci{Y2+P{nJ7pqCQEdUM3oH8oq=YXNukm+`A5q#GZtp|po9mHPDFN76ITQBe|cwk8Sw01ka>m zxtsqn+ME=V+gzS7Xf1InrJUf~JvSATi85utWcnBK`3X3iR)z zej5x7?SBUG_!c*OCN3ZI4Syd#sSP`n3D0sss)XK1rQebLjn>kPt}=U#2W?P(nnUl@ z59z*^eQ7L-^12oVO|{BqRPnrc4P9hx3@*Ja3FEb!s&-jhMq-t5x%`n<;;}ROke98S z9oavmlB|)!Pj2!u?hZ6I%Guo0C9$NNE4scKm8JN<5VY5(3}>i2DhMWWEK9ty*;rye z^t2NMd8?;=LZZ*yf&UK%I>Cn*F!SxA_%Nfp&ppJXe|d;$Zka?O?fR7(*?fQAI7$36 zG118r&1cK39!noJaU<+KNL&7tm7k6p+yRDt0n@S3XUYsrskdIG{xoL3{2E--Xx?@) z%}6WA37`4`@_kLKT~hG3tgo1>&Q7+l#o*$9^8!XcgN@`KY;Jw;A`HT(_kE|3J-++E z$*I$G^hW_DJo>#K30CT*U53yKbW;X(bhE8>+tn~BX{RdqNs%{So;AHHkEc8e$58~W zPTXCwyt5rSv(@Ui73o#xMBdudq==tQahXh+X9t{}Or)F)yPmy3!gQL14&zE>-1XgJcNudtP?I@@`S?fHK<)q)rat)P)S+=OqNbG7r%?;S z=&I;O_nb+q*R=Um>@{S;L3$Tz2Su^_YWMZ-tE1POueNsb5|6^il%L@C&e7K4?!jwx z5o|cBMZ?L>6dLu%YCqGpbi~o_s~3Aa;?@4Eqn|bpcebbegsu&f-`MM2VufgpK$Bo2 z8vX}e$SVJ74M+6H^i(4ou-ft*7b_U4j}H0CI~4^d=>eSbg$OA-kEc`T^ZdkN?T~Sd z`!bAL>W+=2QjTn&6|VBv*TPcsMrABu%G%x6vV8%n#h0i&7)OCB48Xr!>A?;8cyJ;d zH14=E;Ub==Rb2e4LV1 z{FsU^P%e&+aJ~-3*I}d4cam05r&08oMZ>4ixlL7Ci271Tr*cLWy&a>eU2rXP!D-w5 zKFl-P_9}7lIKn5k=8M^cKgpp&4!lI!m!1WH$6U0&b$J;jY1Oqk8Pi!;>t5v^jd&LP zTaw*u+8NKgofdos3M5){OH+_byGnhYd61Cc5B`_(Zt{~`T<=YtmtSFPdh&f$y)rHP zzUrBkVm~?uTwG$(Y+uF?z^&FGhLa`{O;m!B1z?;lRryFfsV+OLyva?>s=e?c>tNr+ z(vzj(f5v^wpJTMbH<)j1hpaox*wINGFq`LCsqL~OH$x>CGu}Z^QN&q)+Iq~VR@29yA-TZi z#xSyPOrl)NDFa@5d62wgYx5mj-)rUE=iYEPbFSmeoiH}S=wr5^JG$ulA;%+@Cpx~M z=yR&+qN}y22S4}y%U^*de^aF!qqi%|@5~A>-{%5b?sfA&L_EM8A)xtqH;1k zcAEXoM$_B5q%p@S-CID9WI~iS~b`g7D(i z{%i8dlU4^b=3aQB=bxTohV#(JT0Kgnp#bhq9--4NG>^x{8w zvw(>$D7lJChJnQwjNpm78A(xy{Wo8j7u!^kL{&{t5#!w}W)sMUeuQ?k%%J_J5mEzLtUkED1^;Dfub$wVbHE%Q5_+gnl-DH~Yf50g!67D)e#SF{AlZxr;BU zgDFoC5MEq#Pn92PVxuOKDKsA^oXjIW`2qf)cMh1qkQz>dm!siiEJ(vaAo4Q}$AR(D ze1%vbIL6yWyz9U>@CeOC3JMudm-K-x&n`Iot>JO$DeyoH# zvxT~9p`XKfPko3yqn_f(uiGdgMnAad){`}$F1m#|YzA0F09Cb%_sLKjZ%=%aw znVMZ%NN2n;!6B=WK{QQCOAZnqvEcP3|92A>CB-^jI~#-vw>9#HemL@5VGdi$?`W~2 zLXK{gaoHv_zAYlLaW6mz9G=#l+HYNz7G=FwuI(Mx9JN<@EgdWG8R9R+c{Vv!GD@<1 z&CX?S_+3-_i*yFSoH2);4OQc3Q#>(}e5B5G7_5(X`M! z+Bw)f+De6P3V#N4-HaZBqP}dc*0%+YUYq#jS$_nNn6(0*gXc z`JAu<5QLSsERuO;CMc)LVof;I?!zY6Na~BUwWAtwlKrd80A6I-u~v)?(Xj-zoY@hW zjF%$+6NMNfOC1^ctu+dBcQFJf(v_)hT`m&l0hM(S3(t05?7k8o4v*>%947G`{;hp% z^qq}s@qwXtf}jo}5dUZeMUE zJ1$7P%n zh0~&}Q!I_tbtIgiXg#N(ma5&IuvkukWkP5>7=mbfsXwZ1c$j{_scdtFc`gly73xE8 zL`EX*y*k31jxu{^gqV}iNJ$`XHcW3I;Z9zQh{WaIc~Hiyk0liI_o_fs$=`O-BfAuX+Nzp=D$+G zVvrQZ1Kg$6>UU47m*uGDq`bYOWQUk$)8{fT=(8jtAeU)-xb5VerDf@=Ah$WAg9HZT zWH^ed$<3>((w;b;|4LL#)X@*Ei$iRp>dCeBh2Kag`K0foZSlBTDys`b9Bvj%JeR*@ac2QPPD?H^*hy7=y!MUJs#Fk~|} zAI!sg_?;5kML?wGdZ1?1F}6=BL9LwBmG5%W;Lh*O8yZ8$R_9^?cH#g-ltG`%rx{VM zekmPu_E0{W>gHBLmiIeUHpQrvBo084fWI^d6r_`%i?Br@Hw{3=C%Ii|ua-4h0PE1p z5`^8(I7(nTTOC4PBC15rSIvn^&hkh8QR$fgHm~KA|Dk4VSmq&yAF}cW zo2^xmrszb<^3Z_An7SNjcx5j{qx!m%1EjqhX@2zq z7hB9KqY*WuN-wU!@ZGzFBQG>ai+-B1N1)s~Den@T!Gm?=Ad zR0IRX;6wq8uYap9)fx+Lf2+M)YAiM)h{dlPD_>Jtj16h6K71JsvX(xf4J`TuCvZ5`^y+4vjN*PBI`o3@4sE36roYh69sykCbz03RU!J zv-(Z8aB9h+pB?vaN}fzru!M_%brSE1cD-UaxlW-#3((KJUFrmit<_|3{n z^aD+mL;r*yq$$i1_*DHd?E_Ztc{_t3qD2*_2m&XHGRjh#7z}2g!`^DhhfnG8g8Iz` zaL5S(C}h-XkzJCJw~s@<$0@L@-N`5jx>UmrM5PMJO3ds@IFhAdLWz}ARaCOD6`Hq$ zi?EPU((cHr|E z>L)5KBDz&kMDmS)LN^WV8Xx!@EU`C=?Jn7AkOD_A(UMzi135+j$M8S$#P@mPXFjKtAV!o_G!9ByqX^HRJ0?D z^$vCdf5a~8>E_mI6#pPWR7{{z{88EbI(|uSUCd%t0s!4^*0$g_JLM#^2>R+ zxN=RkI`JU=j_>iEZdGiaof!#gCtNp7z=^awQzF2o!^a(b zW5O*eQ*Qgv6Yr0XI{q|>;NW5+4NMafCX>R!#T`<@xJ`_`g7bu!JEKaGLaLX5Pw>8U7FYFA}ghbN-jVq5oTu`40y8#+>I5x^Ynt9{j_ zf_j#K%0Q+!_D`>5k$Q7ojMmgtu%f3^DozP#whojoCd3zS``;;gk|CFuI2TK`$ko)p`dFpdVuyt0ZZt~Pl>$|Wem@6>rEe_BSH%s+SY!52{ykbD5!E1yjdF!M?|@vT+7 z!H$1SJ#0ix*L04OsAb~WT6Lwm5^DlaCXZWU#H3-viJIp~&9&-NfmIn$3ebe*&X&ip z;hy%#e*vZ-*}KRwD&H4t$XrWYJub)x7$HlMslQevPk4a}k*n@g>5?@Z1pPK${qPsDaAnThq_#iM@U_0Ite%Ees48&tY4=F;otHlTAZ4#7|H~Y>6@bX~L&-O7KtD(!f7mGdwnP#o0`$IHF)t zDXkRj?A{VPyHj8%VBSx`h0@x{FPSVNM?XQU2mFojcM6;txU0)eg*2^JXg+lA09kUe zxvizm@*%U0`Y#da6euMVNP%Lqtr6mz|gA34( z#*FX@M-nt(_V9k~$&)9D_sQEKz8-3o>z&(=M-z zcwD`dH>fLO;b5l>bA0b%U6sYDu8Ai}wYl=qq&jV>%BRu9-b?)=(m>6;dg!5k&cUBi zjXxtP#as$v$n1FbD;z8)y0dV4N(8#;?tKo#n^6Hy*(|-k@$!3!2QaWY;}89rpvMdk zQ>^u)tM+PdjT1hiXH(GkWYs`u8D99K))@)IVsD%Gzw&tXphe0awrg()%T}N@8s={DFmYRMu-%FYGVD z6|+ds{d-PT`ZGCCO+xZ{aYTtVV4dme6LbWWZw7eMSOmn_m+jY>R!PA$YhkM3LG_%6 zR+mF8NEZ%AKCV%S)J3=6aMIEvG@K1t8&O0h4>41Kiclpm`;zMF6^PKO>)Qn}*Q zCApYR;+me|PqMRt8helBDK#FLSivWe@W4O{4jUp0K`CMA?m={1VAE23Ryoytyn=UI zEpNd7{1KiGJ*weKjQ4~S_b`@{D;yCy6Cibz8DA)ss&wUNwT86T3}Q+>H#v66aO*=K zK8)4UVb**Lii=&a3(I*USx}BT8paR6`z{^-p<6$ufX>=)e!tZngGNykA7uKQg^+7J zERY{90NWts{yH>K#VLzMadmNVLxk^v_tw!1_8LH7wBlFzXi)|yHj2x-4Q81riSOeh zwC|PYt4p=oM(ww^bK>37*+t78;9s@&Mp%2hUY>i0H}>#%{q1k{cS}WR%6~&+L9c4R z6>IGhz#I)lsnIV9_UUJ8NT=QqIld3{q9kuJ4kuo(oh#b}>TlD6hol z$I9Cn#iqd@vWMRWg&9?IwHKp^?fpbI-&(-G_55*~iE_2pWZ~f#NDl8><@t2Pu-k?e zHTaQP4>*+yPNShaSz9C}RnVl3TTiqOVWMy%B9E(&g^NKPAgL~jr8b}fWuTOeS=^wD z(p0mf96mz%X#A)yEzZRqDI)vh9Q+qU9@}*CNl5Zd3GyUd`Q+u5BeP&4;5#Y?{Oxyk zabWmOwSgyKc9dv!Qe#S6A5Y7wS<+-uq@zVuRo$+YC`4un$qV_3BY!FurBRMpoMimS z?jO}mFVw7XR~~!kv8*_0RGy3m&83M$YJwv@YzYgxfT?IUUE*j$`*dgCsV0<3@JlI) z#3aqPf>sOa4B{brC3s*`+(tFwBDKzXAHNYC31x)Uz?Ri;%{@yjli^gl!HUcp5AVDf?;z= z*}v)zIp7wpB@jhJmT>YDXy<`0X1~M)b0n}CI=jq9De)fOZ_+KV zj$R}Og7d&{tIy#oqIEhQ96oPlBMrMw01y?wqok86?Tp+D1xV$bi^{*K zOJ42@KFzW8PHaN#VqB2`%|#up>LWU^|mY-VLP z-IIfocgw0vDDRXpp(i4kLNpx;&S3#@yy8_W*jYz;yY;GJ_-3>j>Y6%%5`+;{w7?&R z>0k4EJ+JM%BacNN`AzjjE4ifGzZ#v<=YSJZVrltFLKodkeU!k&P%-}XabNoqAg!65 zk;MQeI9ba3cxi@2le$D)>ueVNJ|M9_YEoMMI4hbL&t0lAMo8!)96TYoe9;7jbgXHb zJ~+rE;cI#{IZ~1;b;ZNd151>{GO#meTsl*J*0?~zM9Wsh1FTZtvP-**27Edcm*#?4 zuXVQO*z+cqHOPJ09)H$%sJWE;=zVEgr&32rQjl`o0Nda1Qw$8IWdZ?Y6i^Vo=Dk2? zp>;4MGX68*HCCR{{#oe8#+;SBz-4I>^2#JIRH_6%ft^uC2Li29lk_R0kjk@ed|G9n zCO7`UfV5Z``Mi%45zS_6&>e^Pe+A4f3tw`!oC4=jF3{lQMlLLF#N0;Z$c*>5_9IO} z2RfL>4#!^u;kY-~PsX2gyt)~uOPN8k##4G5`{-PzHvr6 z678qckW{w^4e5)c8*)E$D2LJFjx{6&J6l82E&i(1!<@tf4asbluOUS(rywAzX|{$$ zR}WeLV>{v5w-Y8vzMQbG?CjeKw%_a9Hv6UWFV(jRCTPA=;J;;ZD%>7bL%8nfa>8u? zvKQ^lbKBk!Ky_OECf)8_$~43&07PZ`r_En>n%jHNw_Y`WathJsRFJu&5&`hXF1q!! zECQTzAT@n}cZoMuP37NVWDhXEMl?+lGkhu^Bz92|yc=E{T%3878PQd@@pRRw)}1P1 z=dgq+dS@|+gf;TUykX9~dnd22rY-?y-5@582U|g@i*e`G?#g?xI+rAFcl$we93s`J zuc#;J7$%>sayPs~8;67p8bX1yLHv-QImnLoUN@0+&Qp!amF2ayC$O^Q@;x4UK&DkZ zz7sJf*k-KEXrgG;?t4P<>e&y9!W*x!P)mTX6mK|uy|>+bvA6$hbFVNjuy_!T0*17` z$4}?xtR}QP^SIL3dwb95o8H@MqI#z{U8W{9WHoYNy}x3%&nxZaV0PTw{LjCe`-ja} z`@gCJ@37-Ns-lODV2RjG0=l#X-r}2;aVdF&kJ&?eo)~o95oTAeO1|00>BT=1O`O&Q z-y~;aw3lnA+C{V1s~3UD0b;d_fLLRZqsxaBZ)w6Z24%s@h8AyWL(A^BY;@txPW;e+ z+SowSRi_^e+Y4Ch8YL;ezP7q?T_B-Ki!4G=%OyP4aPXDVvs^au?PGjkB-bDyKEcq@ zI>Q^1=`A2sWha66Lt}In7v(f#05uuW!E)%`p@A$22GZ0};{79{qaeUJ zX?I)Q0O0WWHV}{T&9%vF2V;;Q;VUGb!dflTq?8SuzCyyBBuTOq><4CI%ubMn5l3k_ z89b#y0u2fq4adP8Ajmd^SRf$k6=s>C$M9QG%pVOhKY?#Gia+9V=+2J(2v-Kwk7b6D zsLE3q34$NABzSG6F)`$pg=$T;-k_RJ8)6Z^V>VYeYUUiI>_T#p9EbL$zKo&3V)}KQ z(1Dbfi9MgTi^SWHm=Q49qaVaF&l3`If!%qT6@)!lIxfgE?To8KC9o->Jd(keSa6(O zXij`2Aup%4U`Hc)9MdFI*)rxjb2Hg3(V9JH8mdOrZ3Hj|MMZqb=eK=Jk!%KdQwwQw zzMo50Q;tesh{*P2ZRJ5^dl1NTvU@^_NI;D%M zP?PP6J=Le>QcN0w+Qw`E+2e^he;dO}3rkWZaO;HtU3K)Yn+v`KV}MV(I=O=%VmgP= zhoMd(>P~==D%?_t(9!F|-2;beywjhe@(Wku)x}UTw<3X0<~>y;4AcD-&BY*q*6KJ4 ze1#rW+TO|d)Ug0qoijU*`Wj!YLjV*@KxDyko zGqPY&PBXxXf{GD4_WNRU_f0va07<_sEeys(s(XzYiLrneMTrmGmRHspVlioti&>Kq zkGOW*!R}T@k~!DEd@PSdRt%P^Cn}#CvP_K19B#e>p6^&x2BUC&5C%A-Ske6XXG8V? z>9reG08geEQq5F`A@e}<6yC0>N-I`~sLt^ARh=q_X}K2$;$MQ?=wUqC$nSYF7E=a* zTQj)HvX}%%N{+Lil-L(z$0YIgF3(5| z6f&+j;xcb1u*j{o6MPeX^Hon5qZ4m=)meOJ6IQ*2f3yYzKwJ=|*%w>6t9qPWevSUdIJY5DRsOGIBVJktwb1VQ9E$Q&j!A-$qd`>VYuIcn~mC zii>L=${==(fDcFGP6ycgnS1UBL+H4LM@XNaN`+CYG7N%IrRVj>75GMPz&X56foArr zrqNg;BDQW~>n69(uo-jfbGKVBW^~+O=AbYfnmSYjXMt6sMXB`aZuKo`k!AIFV}qNb z<`i$KUoI_b)p;juxdUcnMG^X^{m=}pr-H=nc7>U%W?M@1ize$7 z7lcJCXeB>V$@!s7x!)+(8jWJHcDhl*SbdfH1jWV(Q1L^?T3^$N$-o{yXBAGblaD&` zNOIGu@y6-+j?cK}@?{5;^Vn(GaYCiZ%LR{jSK5U(Z6skP0$kVr=bttr2V; z(nT6UP1QL7Rs;`kpkO%tAP~J>>jezvWY+8sPkP z*`P8IMQnizOTfZhL`ALjXR_d|JJxYExEjn#PlhfZTH|5ph4yR_6H{B^i{zr1EsPbR z#~>1WT_svrV~P#@G&bprW zRdB&-E|)_-_hdkTEPG2b`E0008UMA52Z9d&)_R|1;DHvXwMj82GW38vkENShEOB@I zVMyKtZ49^IFcqWQ^=Yf+l(DS5KT=h?BG+b;zd0k;@D#LutV!1%_j*?%4bBECocN`B zarFkbBS@@^62gR-9Mvp86o=fFwzh8Uxnr$1DA{_2E%0@EhsnA;Uh#1VY)<7^($$}; z4Atedfz93LNA)87&xWACFehO1Xy;(_aP#&4VFBj|E!#e3R2KBMKun4n8!)U374AWn zP5!ganYjoWAt<9AfGm}S#95h59A9{Ss+l4AAziMkvT6!=O|5*<0La%#&;VOEFDEpH ztuicn@uf^dPii>PKKWQUaaypaGSHc(Lae*mc{&Fghgw>g-jHg z-PDCh6ti#fqv)#Yt}jYd#EV(R!=9jx^CR4&BE@Uv5}6y)lrNQpsHxu#AyLp$$%$TN zqum2(xix8tmi3FGC()To8Eb;s$FSyRA$p8aDM5Ma#r;wn%VRnEY+YO$8;ARZo1|}{ z`KB!9JG-t0pbK}1#hd(o0Yu{U#p&tBubYRjc3-_%hjWEwfvZF!NOr+w7KEAWkXlh% zZMuf{M#&YVuiOqGdJ5W8Qm#^3B~z$E_+h5i)D$D4+*XERI>aXSsQ;#tC}))^??|Nl zLfOHCMEO@C`>7J;m&5@6mI9^ns?4N4xy0mVwBvzPOhYQDGxZ#L|D`Jmbdh)Xsg}OVe@gX+IN60}KdCo>Tq^@xhP*Y-)&QEd0*MI1a^mbRSx_L=(&?eulvX zu4wz6jyJ?xeq}d{u8(10W2{5&Rb{`Qf(sl-8EMU#8%AziCm?Skt)Y?2u0da$vFT&# z<4nFNmWSrCwS_l^{~d>X9u=q!?I_k61C$O7jmQ~~Ma?pKy5n2=VdYUtl&*{a=V&_n zH)bVyTx2TARni$;61oQJVr5H0_$kC%8>l)2Hxg~rK|S!S2l4i{;%x?!egWL$Z%mhP zC9FB%hSJig<;bI4F;i+fjcNxIuX1ilkiJ+7^k8rOt5YU>S-&iT^uK3xEr_%^MI?)s z>%la8*QQxqdRl&q3*fSUn0}MVOLHC1dE=PQ(nY(po;AnJ#x(wz*JnR~6Wj6zL^H&e zp)k?uLm*78jyw z<~oq+5a^TDqdC_bvbhRaHQzqUY)S9MfiUmGcx?$y`l0tymUU^VRI>TN4YAw(|92>_a!qRgeZd zBU@{-k%c1h0mY1iFMu-|%Y;9r7)CNCyUW#!ANUVKEPTn4P4XrGdyB(^{(8*qLQy%L z;;h&mrchd1t>)=%ay`?0LC_@zO&L;or_Cn?DP>!&q-8la6dC&{7tpD&0DkwU@6Jw@ zId%hG)C5#K>K8c!lLRDoFuAdXIcs0$zRXFbZ_8~-+UM?{c7if?=@w*FuUQ5~wcf{w zicJ{fWtSC2v?-)f=rjI>7&XqVdu`GSQQ2R$G(DS?M6M^(LQDszRizsmpMXqD!E~hb z8L@k`FSfq@ZjwPNr|Wd|zV+>Qx61BsL86;jwW(|xyaTde<<@hDr<8XunQzZ{bQRVp z6GrkeinI6>KJ_wSahqtDQep3oXIBZeMs%j`l z7mkMG)<~R;J2GF|C0djU&v*BB#FAK88n!}8fG!q{mP=(Jf8l`eC-hw0D98YH%JIMC ziG=~Y;2Z?<+0sBJoubTa89X`+{=aYMT3S@>NBd(aP(ZP zRhPvUP;U2k(W01qQnEu#YJxQtx;@yR%I2%1T_Xe$mVB4)IdKuNo)@9MF07!^TZ}uM zGOY86tRkhxjpdWsM>sphg z3Fp9v0kJX&J8MV}_`7czps0kMV~l7~lx7RBY}>YN+k9o)wr$(CZQHhO>lLPYdM2Gr zCf&*YcW&;#n{&_E-(D*al)?v@%0OFL6+jLF$|bk^&+;`zw6o(Y42{r5%cIFhTC3UI zu(-~=qvjyL-X}}c3>G49-%MP!33JdqBV~~_`yz5W=l%Ql_rNjX4SMuf!=^{Y=r^iv zM-V8d8e5zB(yIyS=+?#`bdE?mh)^POY*>lCahRZ4Ho7>)p zkmQh{_Ok#DR0$Q7RAl0>g`~ECn%QsP+_Df~pg;C8YJ-5Enf@J$nLP4XqraaI*18d$AzMC z386QcSlG->5(V$89j~V5bPEC@HVocy+~)540ng;gm_KYZiGYrMCCW-R7If zB2IDwd*K%0z&*sy65)>}*vA0dQ4(|C_lvV?5>)KXrh+^c95|$3pRqn0lhd8z{H!GR zfKlSZ3ou`wj-5~~S{BjSX@6Xwd`q8Ooy5}F7JYZCuM@=VllPrKF zCZQdX?!Z5Xe^&UraAR_7{O`d21q-c#Ob|fS`@!(veT)pEV_Wq|(TlS_a^hg~&oMA< zH#mjfnYCDe89EZ!C>Zs6qItayPtyxG*d*u*EuCUSwHmGyuRD) z&^ry0qqQ$-_%uOmxJajaex$XWw!RmS3~07KjG7$tO{Uq_)VHZuv8Y=7$9$x+CF0+h zxc?|J$;&73jKfFVIFIT(XkUwR2U7D*HS7#J%EKF z9^S*`42c~0xPk0#{m6eY7c}RUi-QB6CxR)@?u0CI{g5P4H9tFsBttl1v}5Y11_xmC zmna?1quo7kE`O=#Ofe%VB?y27ZkL%R?uFZZXMoP-sA5^CgCC7Qyo%XiIr?GF*z%pq zXv|!-kj?DG{pgCe_j5vWh$Gs#b0Uuc0O2MCId?8PM{+z#0P_!FELE9pTiBlFgm+7O zjA}>A|B&fhayKnrRtosjLJ;v5Iw|L`9JJy2pe2(X!bWjcN8-UZI{REx>fRsrd2h|5 z)KlU{vfK-Evm}JV57MlIAc*dlDL+XqGnEqih=W83eWs7?)<6G+C;z(~Fu@KDnqsAEFZL?Y|?@i;-tc#Quye$4Y3XmkV~sqO_M6C1uN&7-xJW{ zOdMU&e;1_UPei=(;;a#8eWCpifYbUf;h6Aq9tC*~dQN4{2{iWxaTK_`TDWbt=Pars zp$CZ*Dt$0&&Zd>`p#w3*35wqcEOBiAd?)15{${8sf3n{hJnUe9Kr5}p2Z(M7q>sDH2}~Jtg{PZr&0~+ z2wAm){KbZ88`>2W3Kvb&KDoD^I66dW(Y7{tY_YQY-;F-$(T=V9iEyJhw59MZ zrJ@c34Q2{3GB0$oCu?VppUJMc%aK=D$(JM|jShY)jfiN56Z_|TLnmlAC`nZI&i4Xu zW#omhXBejWPbZBaLaYuY$oUfABqd9z?NP|97nZBFh=PvDOjXZ#+-$bG0GV&W1zJ{Z zyoP!!YwKI=uC3jja?1x!5m$BGUPE>D$2Bs|^{`J2^UhKX103Vz(fCIm`NEh;G8X`x zdEsALymwE#Ym*Y)bZQh%gzG@-`PbU{3Ov-De8}M_{{G*uwnd!4JC7m|CzvtViVy1} ztS7j-+`S}B*-Jxa5c0_^*2+}3gUXfFfy`(xLTJmeIy}*%@fB2%>?Vz8Lqo{Qm^byb z%)|tMkC2e&)?V}Hp7)xSs%#s-jUUux?>7a`5gHR+l?^keplI#6$J-U>#%1WSx;48V z=-lC}Nn9qP&RLZ`!4?99A0=`jKEb#x{vWgE3Xp|n=*VJp?Kk|V(oLAXPMio)7-*Eu zYhd`>1=HpZ%)0rwblUMMN|slYN1O6BCHCs4Xw{UbpyFoa9`E{wh+C zfdfS*4_omwn67$K$hocp=8q^Hk3C!TzB{}w&x%dcyx;by`@irB3sQTkj7hp*nz>>a z(ELg7&I~fKzk&7cKq)SBbdKhnRXcUF{BvR0XD@!Evb+KgStb!6$bU##GoYWT2(p)b z!y@*ajlG>A&nh;8LHw71CK!n@*UBg)_$&~eFG6oe)y5M@czRU_MCC^mN3w$l2|aoQPyn>3Ox98GM%Y~mc?ef26j4~nci(z zXBmPei?~sZZBI+bv|z7fb(_hCF>c;+H554qzun0osh-(ulQ8vrUE96)BMSz+KcF-C z6N&(2J$#xZEXW;d`V;WO74*}2Wy2Es)*Br9#O8i(yVKQP_{m1fyM|ZxxEU&pbW^Rg zH)mj?N6GSys3*HuZn)TL>&XP_zP_Ts)?J1t? zsOBUcI4PA^7?W@H&cALWvu*(O&lrLEaIFM}gC%n2T0F~N^W5Eu7olA$bA>tGsqQaz zGOP{FTx+NkXZg7kvJHdac@XDCtX#bA$P=aK82w|M{>Z=FDSE@K0IbtA20iI9MkJ;B zpAvTyy%b%elJvEUUHh7J^rtE-CW>j32{z!Y!6`OizG^R~1=1i4)1%z_ET#_sk4sf| z)19v0DF5npe5=!jYs)bEZ^HT1Fhm-1FQQ? zHn{%b|196$y@Rd9FL>?G|EaQ~XlK-jZWy}UAis`V?uXlR#~|r**20ORcDu$Q8D>E2 z)EGvPMAMOspm`PxqW0}=(&{f#qL@~A*2#|gx8MK2<=?>5#>MyF)(?r6Io?)wZ{GO- z_~?KCqTf|tM%U9IB0N|h0oWfHKL2zM+qraM#D0)^z3$P~Gspn#*!k0H2i(yM!}>DV z5kW*&7ac7v?sG0_0UDk*3O)xqkZ?*^*o+H^ zz9x+u@M~PkZl1qvw!ZOfx2|i~{%YlZE}AU@!ciiNls7)`%Ta(4w^mL4$;Q>Ne%Kw}v8qVV zFKTw*#p41yD@2>3Mf~*<_8i3M3#n<#K5@nJ>OdFvrkVw*?aRy|ev>?#85xxrF`D9| zf848zYs+^0fwy%3hDOsel%1ptAg(}Bb8PFui8lr4Q!x38VIxt`Ip{n5M}jMG@T>ad z<`GA4!0h$L!zMQtKLbJF33m5iAfV(%z1%;HLiyYf5h{&E`V|SeQC4%3F;{Iw&xE5O zc{rr&smKo}0JelbzwWJY(74!e4xYGMu!k@H9=x&FAISF@L7-Y@i)xTKhFi) z8nX`}vsO_#H`6y|5SI2HqB%@57Mf(13}Pss)i{zz1E$sfQRv^h5E!(3Dz&jX+TAW| z!roQu)(XTjeB^E0Hg@wvf&)V%Vb2R(ZjSppfGgSsAXOMT&$0nFWt|dncc?q`Mi<4s z(jK~r(c2ZNLCZZCojkq6yO3bGa3yvpu$yl9nO=0YoWppXWcqVBv0X!+dQWr2NEQdq zt=T(-PkzN6g?i|o)1*(`L#~5NXY6)jrqhn8{{S{uT*SAdqynS8x}SXT-u(G2V9RU0 z)}S^HYfP!jyyDc&hAK&~a5u{K{^fttW0XJvPEBt(M_7mR(L4n%W%sf}?L}4?Tk#aL z&;+>)kR_Fq69bfhEKH1n{gsv}_ET#+0^uLXh_PLar!|V*lR`WJz2Fv{^%l%(%0V35 zpuk_-tj8VWJE}Uj4SJ`9Cjcm@6hf!A2T&JqPo0fX&?1?+2Kr~Fi@=8aV&^WtawO?N zt|!K3$g2&5{|aVjG<+-K{3ck>KLfo|Km&x{^_DP0wM_+BWxsW(srfY0Ucgt^(^!Lw zGluC9Si?0?SLmRxvyvy8i=PA*I(V-)gbSU|hB>Ytmcwp;KZ9VHB>z-4=8yRe7_Uzr zZ9sbQlpm|SnFxy0F*`(M@E1h0V}3zVP}6VJ7Foc+RF)godGt2+jJKma64gLDTq*4i zX6RoM+?;(_UMf6i2M}E!o^h8hdPH&SEvi38Bj4S?10nq&qHi@9VXb~gadD@Kk+xIr zZO%b+&;r?*2!$|AVJTFQq0$<<`lE&aPbOL?PSuA02og9Z?8KEl{tyXxTm-$mFCo86I!Rup_$fn5IvNYnK^m>)Kt;(x z8goIPWzbCXhhn7*;@&0T_O?L~(k;xsLgX#u+`Aihf#xJ~>`?%+i39zRM7#}>f)=dq z6Gq5oY=K)-BaLM9Zbb7-NZA)@3hwd-iT`c~+3x?laIUvIGVcZ~))}8$8V5ZWTlk`h{ge6Mp~u71{@BS+{~I!A#~mv@a{=?6>99GE$5GyHpz~N^ zE+Y#NFQH2$?prtD``39Mx0pxx_?rH9(6%Qr+8a1>>wH;vq)%&`WVKH}A6l}S2$s`= zs#Na^AJ}33Zu`RQvE24A+IYd2PC^XkLqZ3$2x|a59*z)mH8zqcB%uGH*@dCf^}WVMgS_uvsWecD{ZVn3&~5W}`V~ITb`HT)bySJrD1d27 zxz@Ibja0@pqKnhx7vxXU-8r^INbD~q>gXW_K!Z=S-v~?|v+{3TBgV?{o(`Oiz|1Ps zFY!D(4HAkeFyQ9BPvN+ViB6UDTcl^&{C!E31c49+nb9fUBps2wfiA&*?8hg-P}5uk zGOH1>W>xlmNAv_F3UM@AAR`i-^qK;Uw^{&~z2rxYVgZ<;MN~wd{Em$;t-Ah4%;GFRR2*c~B;3oCje`B7^tZ^!e(p z_VCi+O!8j+!@c!ex*p!20pwmdbX45R@ynYX?y1llvjyUa;_pkvdDi!4(Pu2|wtk=i zz(t-UCB(VJ7Tbpb@A?jtX*A|70PaJH-To_}BuF`dfI?>^VymCU1Y7_u@N?ImSDe`<4(3y}KMK^Z=G8|3%5b2c{X37MDkIwpNc%(K-HE@hsCdSv=6 zaVy^Oy(vnI*Fy_uyUZl3IdQA!!{g)qJ`Ot_XS7_iy~o}hK(nW348Sb#xr8t|aVG4}(ZmuOGj)5>jG8*RFK zKI(oLEE?8aa>j++pVzf|5go9vSn=z39i$RNk?4IZVBrZSMM9dR^~Y;O?AP`tr8g9N z>ufwzS&+uCEZ8(i(&A8;$LP;nMFz0~D=#8@)x-wHa!rYo2gXC_=a$sbmv_e5!7H>D z_L{X~Aij=OWl@M3fNM_g7RK;{*fp&KOpHJPZ}wc|9lN=8=Ymc0`y)_U^@pLl5NcFC z^vL=8aRRUQuLc95-yJX-V&Ch;y~J|M;X?nUKR6s|$`r07&UtGAP9tMxiUWPG%BZVU z3z~9xHX0iWksiq`b0eT-fRTdO+2uV~=I>XGs?ZoDd3joqwHXDTOD#MRI?7RUuj&f9 zR#4Q*LSMx9#2H+uC<^O6qezmSw^yi)!inmTJ>|S$M3_A=-)>udJjU4{@r&ykU&07} zpUs`T@&M7uJNR!{3Sod+*gO$_pArS6>Wlho1m%hwXA)>}X&N1;$Ok#-Ye4Ygp|pcl zlw2RPPwXS{)mycrYn9*{q`G+TN|b3KIpQDHa^id<=My@VcI_s_c315N-(V~iBcj7c z;-L(zsUCdKP2-3AwGGP1NZKy7c)ByKb*!iwXn@~C973m?<(x0wrX(6LTsHm3P1y9s zwnC+nxwg*4m?jFZ2>@Z!Rj#4e0mX)=|8A$nE zMD3!77s$FddZ0T7r)F+hNkmplZ!B&zdcmlFUr*}XKE%fr8lQe3T^vi?FqnfNITtYw z9m;K7+24Q+N~QdYik>}#o#)pdL90hvrHFR|CY*27B zBN7=HHE?801-j#Z9up;+lbQX0GXjW6UP1i}DgvH%{V(F(FmqqXm3M z$P*eJ9Lh0(VU{s2ksWSW*7BD?G{#Z5?0Dp(IY%hC6=p<=E@MG2>^tg|TSaur-lBG8%dJV4 zNzWmyq8J*ub;rz?t3j5acKoEkdZIBib)$;tUjYQYAZX+{=F&*Cp3lp)b4ZE|`V8RU zLqwOy-Itawo?uFWkra*enftTD(RDz|NuwSRZR9(R`Oi{|>HOC3CQm5ATA#7Zh*&kS zif=Gyvsq8C0dOXTXj3KLO-(kWkajyFke1M0Kvz7MG){{fDg;)&lpgJ|@C0#00oJr# z)w}cKZCmV1%^Bjy=U>o#;Fj2WRW(mUvLQ+)m&}*~(X&^0Nj|_aHFXZ;w&(^tbXT%( zBCfD+B7wea4+}iM$>tb;SfT_tpv(v0SImYmwUC&vgJ3lIy;GPb)w$mc6)=}58@KU> ze%unj3o`)1#-M%3O}D%xIO991O1VTgcinp0@9u#jMiLnpD+d zxzf)lOacU@rP8zzD8)*wN3Y?l9&frM0@^x%Rmf0&sxY54by5?m18k(y(c|{Otk4ejOjXx^JbiJ*DGkzkV0f!%POX3Z}%ifTk>aKZf@InR>w4_Tk=o{pl2 z;M@B-zX#88uU-V$c9>xvrPV|r^wf5S>AwvTYj}hZlSL6>ITm=rWJ z26uYp9pa{yAUS9vb&H1YC7vO0=(!W+Ue0E>ry(PhX1n64a3h7_77^T`gAhsQFh~>L z3ncY_vH`ZEig2b6pQMC@#RZK$F?7?eXa^p!sLi1p+9ODhmQ2X#R%2mZjWnUaqVPy7 zvq#z9(ve3j`DUi^LTKZ6!O= zAVU46?v<*NXycMv)LZ=e7xXJIA7V&?W%`NJ17x&$UL`LlY7WpDwv)+n_6c+kYLlwy zY^h@P(_3R?C=)KiXXwx7BOP10L|gTU*@Uqeo(qioh&Y6y%v*>*F_?}QEJ}nmoCW0l zany3|^1&c^quX0HiHf{qN>+(XBAXdG86)6=+c#_{pXhM7-~9hxpjJr1%y^B?f(3J| zh}24f9AZ5mzO=EyC+98%P^u=*BqsB=JE0^JIma}oB4}eomRh1PTS+p3SBftvOF%1> zd#G?7?EqLJ*GOR8XO>#JGMM$yWRbwpll_x;chb;P+8L@c=Sa(fDSTPI_st8IfGlM$ z&K1|YOdzREy_(Gcc%;JsQb-~tOJmk9s>JdS0<1Y=UURdhP?V+6594BWaPSr<0$hixRlUvXHaNPA}ycBIID zupZ{%g`&g?}oW2u|-L54Z(ixKTc)XHCa z?9h;KMX-)C`h>FusGmcr0F0YX#ZkR&F!dD@LnF0PG#@;krnOhxK|@;H+JjyiIM%@q zAIqC=oBwMNCsm;>oX^7E*jh1@E^QxON9fQ&Pk}M3p~mV9;W?I>PJpSKyYB9$S5zux z>n_Jt+P7F@Cu7&9+jq*J5WkZK7CpHi1iy)pE0F1V9V2r=7|V-a7!E_tCmg-W@jwyQ zS8yk~<)uP7i)kDHJTGlgOMMa(ETQ5_L9QeWr9`2LW+$#l`v}IRtIG52-ff*um@_+t z+3Cciae$`kKq5$8538U`q8P;iuUC!!9U!Dzn2C`H(0JD#I{RcemP)~6bD8L#``&ed;cn!b@}9r*2OSOhB&7Sv}fR9U8LzVDgG4O#F0eg z;C2MlpX&iC5V!B-aHn6e6}v)n0R?0AluZXQ2=EF)nr$zdT&bZj!6V&@Vi5pg$uxcE zuN9Mu6m$mlS5lNvK~B#2B{|!%Qu$5D;_J1Ra2EnBM!AhSfDbq-i<9J1<503m2xp2i zSj)h({Rh4ozB8YpGrrHr-FBGGE}F32aRn1H8%yM=k@Q;StUP!KJ+nJc`;&im?@z3l z&ufMZ(ESq*_k%=XbygHb@(**N?3Y!Ex(tZK;Dhb42}WfYah3Ql!1*6NTLfN_n`d>I zS91UN`@8GDkONjtVd(tUz-8CAgf>aUSNCLaN2pA$Nz4Fu+|^qQhX??f=14_-JEIGI zqZ}^$^(*dOQ2!jCtC&_LwxyadcW6m4l!NwpJ3&`9==_vT00)G+s~arJMnrd{Q$v3h<&_Bv!KmzApRIOv(?MAFmUTw z-#FXWfXJEchrY!~_A!z5cJUm!VZN+rnEE2!gV-e0F-EpAXHTMz?NiFw2h83i?=?d* zZ%RImPg|FSIC@YOPOwf*Un)+7Mi>UnoiGi#yw#M_UFHX*hU?_x;@GEKNy(rHj3ue{ zU_zy%Xmu~iUUt`3?9nDu7fbpU418FhJz5@Z&5y7f0*0XId`IH+8ETdy{zlYA^~bLL z6ByRTxYPw=^XAFJbtSK{B)^3XBacVTXj7zgLUVE@9mY%}NGXiRmP5r7grXZMJO`pP ziK93rmuFJUpbM8-DYdBEB`-9bA5h9eOq>RA8}ZfwpMIEpIM@wYct2TneJ## z$d-<5WeR~U*{r1=_`eRsY++rrHY6OBVhx%RQHWDC#v%~IsEFtL+ESsqU3O{KJL3po zDD!F5d}&J@!PF*kBUwz@R1!Xr8Rkm)%p2}vg+EThEWcd+%$d@nj(c;FrPMzi!eP@@ z1p+B{d3tgwQ(wHGm%2UP)IxzwMnmmh{dP8(1lf%PNkkalk`V4TI-f@^JGDwdoN#K~ zH97`u%pQLfQ9RQn&|1HVDP0P@Q5mLC_OBddqa7B^q(D-E(I{Bp?OW;20&)_DB7=?P zb>8^w9fIwS{MCtPSf9l0gfVyZA7YD;+@{K?9X%3$#KIWTl2nUMp92W`{eS(CVqI{5 zkLGxWkr&=HQ5l8h>iOGF{dY-IL=$n}s$T)@z`X->F!rndOI3#K_<$A2cQ1-&maW_4 zRdC|BtI^~2@%fJWLu{J#3J&J&yO&4@Jh8-#OP|VA5^G%jzQR-V#7fAG(W9%bjlADy zoiFF|%|HWt#4C5*1o~#cr63%GbZp3aB2yJHlA!M0 z(b3RCiW{ChYFSCO>(%&i{ZPOElyc4*2oy26swulbL^2pDykoL`@1*p=oa_i@2X|Ri z9tJ0N3$cT-hbLFs8^!3HTZq;vKC9?uohXcB_({pbZuU)q{m^MQuMkP~!xO^@c7eq$ z*@2bW2D8*mN3%v%j^sKSepHt2#PM4Re87*;AEolO% zTc*5jCW(5fbHY$<>*fG?uio-P?BQ`t1I38m0S{C=&Qs8Xl?CG`Rbupq zMU>zVariVnw1zk-Kl}Q1YlXqSZf0j>3!dN2pD-Z=vZRH8^1p)DYVIP%2GPj!mp5kB zdH+mGF+pS00ccRaFF1>4zyEg-QOp_6{fz?il|0W3n&PigB}f4IJg8B}jCe_KL0Jj3 zXfQE?B_&Q`Y9-_x|FotEm3zSwdGdgU;r_KPRODpxEi2WJJ(aIlo6o9xm43{_uL=b@ z6Wf;F|5*;1nep3_UN-E8=^=16+QPXUw6QjySFWGHwGZtuD!$9;D3A3HQSgURPPPQ# zxwnyh{hWD{p`XDM1CQF?_pcOozIqG_tUO3hp&@j1pdQ&RFaZdBN+H@JmsfgACk7$b z;RfIREY@*Ax90deMrcn_#BATV)wz3t6;=MRRLfoME@o34i|14ANrl<&ndpZ?S5Jgh zF>#h{Wz|$CSw9B`H#{X-YX25v5r_UV_c=iM0eSP*48_gH^`B(nJo^sy5qL571)+Nx zXAsRZ!zw&W%EB2o71IbP)N1ox zU&_;VtH6FT%!z45w%O@)HPxiSu|7O$-7{@+U71hYB`judcI#)Y%lE7XPO)pLf`iIN ztpVGa^p_b3O?8I|Nca-cv;`f9%j=HH*&P?lg5(Luqfh9ilyi9-XcpHg*>`Fz;zk}a zmal$_Gj#M0_YF*F#GFtt`UYC}9N577zJe)<1w@5plAsNETQy3#GR}EK0W~=0Xbd|@ z7Nsa0r~008OY^U?fmlBM**FuX-6xThe#Ya=ow?@Qq!cE4}41v_qpyCap3=xq`k%5l|qTvXSS z;c0zL%4J#3&Ao2Vlq5qe;U-OXR3TL^}*a zGu`$)%y;*dsFUUEy41Z%Z1Q~%J9{6Zs2f55zH{S+m+Pb;quJSQ_v`*Tyy}rGvh!zL zyqMzho|yrUx^pI((vc3SjTh566&m(CzHDcI_@=h2B4eBr2VpzpE`Bf-$O7pE|r#YITVaioJjvbQ-+HPm8SHK>+7y6_fR1 zalX#C?ZRuuyYSHML6l#~RqU3B{#`$$^wkR(!B&ak{U)SRGd{k;{i1t(e<#CPj2fuO z86Y0r85O3}#WKH{F4I4fH~XMpS+q!_#h;#Vu+rD6s);{d?Jbb=AU~2=d_-8sU}t z?JDyZw|kDQ#jR!aunE$kQMJUW+cmZ~zILq(b3iNT|EdYM%5}ctQV1EtCDMLwFtX(; zjvc8aXV$x+cL*=*rl-Yo8V#;bNI@PIOh(=BE$O{(VaxOAjq{Um7wHQpB%dL$7xFea zfeirRZ(H=V530`>>vhg^S~Ln4hJONkS5~tV+SjGN6!=R%cmJ6vCK*{k6vBP*0ESe_ z&g}Usk4kRF`+AV*r57nD_bIshF&I0;FelT~lsKQrWD?pj;<(;UCYV4*v2~?0E>hu{ z;;k>{v&q}W6h=J6P?js#JG66IbXM-Ff~sSi&pAj>?>nwzm);>qK;Z{=qn4!t{g-6-;$+qkpwR%<`J$cl0J zh{R_G?;{9>8r_%himA3a;Kp_Jq$p$K^a(uz;C5s^Wt}u@Xjj&3)%T@R7MxV2?YlBk zTyx8-9~B+;RPnB!oJNxnCDEl8n^1hY+N|^jvwdoV)}E=fw`(srNM=~nDz=fs~-PLMs0R8-LY=b4_;BDx1Q^3=lzBV3v@d=F1{*{$&c=%~h zduvb|dw2L8Zw}L^cK5^Krq+oq70o(q)VBj*kPDtuF*vixjY%kIrxa1C=Lmk3gNtMk zts|kEJn0{4WU-)*p)MPEHqSCnGPVy=?3m9{q1h>P^&Kt#2H2ehE_r^&Pc zC%nq1(&`&&D(NnP`h)aBccP{(PX|LdoJ|_>A={y3P-dLvs%6b zz=-7wrTRI?TK>_$)x703pJ9QM&YOO!7#-E|&R_txMgc_ctZcD*CJjLl77^#! zcBcJVY|qkf*yi#N-iTKYP>X7sZ^AmWrsXwWA)q!itvehE$$I|B+LP3mDqEW=2XS6} zmM>}U+Fkr`kv1Aj2nS5AXdSvf3QK%%x|4%2m6r-yQHZNBAYD(J7KI-&q6Cx3qUohA zWh`B$+-X++pITQow2iD;2ln(h)B886wG4_o{yPq)8I#H#lRV~hlAcWtaMO`W9kL&y z8TV$%A;0)Qybxb4cLl`S7u`WT#xyjXviSm2ApVGLh>-4!p~HuR{i33*Bs93tBV5?= z$jlr#ZCNkL&58UC>cxtLB;V5#Wbae)i|h#^^@nz70;U-#YkMYh`HXQ`1fAehOQ}OB z%AZKSoGZAl@7Y?H-LwBRCFo!F_`g?oRsI4eOV;ifxO@6Wm+DZsYie@%%4vlPmz&F8 zlt2Sh9VrimmD@IsI;0nmw%88qBt`L6B~tlj76+1Hb0l65#>t-3WpnnCt6c)bx`Mu= z&Xv37-e`KG)f2clhNExnLsrOctTP~-*rFK2=12!7dULZ36J|Ib)LvJHYk$8?cG3{A z#tbwAl^`g&r_aSk1XW_N8I2VQCpzx*6_9*<2*ddH1?%K+X~cBnQKy@|ms;g91|`{! zp8)q}KPMu1T6viczn*t_cZd2O7xM4OjsQ=fC!|Vqs!J5_KY;R(n3$4O=mlU#uaHgc z+Ed0#Kn~FqX5w^9$K%{An%pT#$1l{sT!`}610I4D+z`HXz?J222XU6ycT@&s(;QD9 z6^=l2PiA;G;#ByuZ)IeC+JB1TEJa3}`V=YRY&oDuv<(b+n7H!qsxJ$i%;PiR?9sjj z+$aEKp$XG6){GK^Kg0_4{$ucl z7mXh-^@nxk^>H#%@9q1WPW|Q<*u&vz6->ctu*8WmxYuLH;~w}kvK8_zldA7ke#EJvDNo~x0#-` znOy&7p{i@38hvs91j7aQzZG4!+Ntfes`nXvMEZHqTKzB{gi>=v!F=-8eMApDiwXcz zzTuet0~~^FrRrY)6)(g$?;GV=4)!CAb1=^>A7{v`gn6eGkds<_Z`uIYiB5rY_#eY>_pzu_O!a|) zi@1$U0M+CX68Sg1O%pkCyv{?xu7cEs+?wm%6I%mZ>z}n>Q+4)UMB{{EID5B@1zlOA zA?P2MkX2g3_ZuZfV+1PyN-tF5B+ASB?w ze-D>C;p|Ya%zhNH&ksl_;*#wxC5N+%RM)v4KrmqVd&r@c|IUU1X=$-5$;Kx(sxA;; zoJ{;3;_Z?3NJgxV+6`w3gCrL9r3fc=K!}pX-~ItiM1PH<`6EC}qLM{G;v(_;H1Q zfs+R#<#2}%D1&XR4jLgInfYFIm?<#5wn*SpX6x*C4I_DHVVRkbg-vF7tzeNjB-FoM zP(9wCGBsZ`1|Pm()GEO%15FNMId>G!eBD$VGYQ{X3olV0uqBzkZSBm{3MU@$Z#F$^ zn-Y^@tHSjh#mHXO-1SwCzOH3MQxk2+4jpXW>MSrs2@RqatC#}hAR4O%uhgK?~W~192}c5g=a<{sPBMQQT162U)HTKq3J6s zw5cVPlm~s2!8~0Wd*;?LM+w~|Q$(gM zXN_?hQcJ;?&)Qa|)lJu$Rcmt;eyw@^3x-AB*MvEIUsw0Mo8N&i;RUYhD!X+?xnyjZ zyadg!&vjDxwtOSALz0+@DQ-7!Glf4X75v>G+fA`f0EUkKfFbU#jr#<^XfzSwYIFQe zS=H)CYi&YGL%!2=;Apxq+Hzm@SexElzI?%C6HoG?ES>%%@l+}&0`F8P$$roPk-qEj z)2^w}TV{WJUoB70i=>B>W<0kyytaoD2WfNi2QIaa%Yv}b>Vi(k$=xL!4Sgy1I|SIg zI9lK0Q2BDoa^9N$q04|6CLu9bne8kF6MlvDFN=P^>A7~bYA~xMiqkhFA&F0YtBHdGC@_;H!K9h;yyVu9;)&XA2a4|SdXr+vpSacphFI4Y zAUZsG{C*D9gMjMv6+p)ss(8Dc4qgPa9Yu-5p_`LMmf~GNf%HkdTPBvhH0Uy6{?^mn zju0_V)pO@`eZrhN?k91szJizsQA;Gi8@%dp3v^=W((+5LxxnFx5(QLcYnmILuNUvn z!3C2_!o@kX0Y`m?T%XRaj;YFMKzp+XY4`(19nayt_K2FoRhihlq_LGiJsm%6lEZVs zkZ}~6S|d?vNi~%ifvb;Ol&a=qMduBcJ=;jgI}~{Pe}$u!1q+8W6 z1Gh}V4$A0S+$Fx6I}{-BWpr^Rl8lXb8TWyAuWsN${!hwX>mUMMmD3iA1FuOz{&9AW zZf-|ik~tyxR&50^IB0XqB-cz{i-orW^`Wlk1$DjZEU7Xl=n z(*gmBQau0JfSTClKNl_W9(B@u5+c-&SPj0&&U?=RX4Cy%+WKZYDIh~Jd+_7x6V>>` zz`9fX;wu;Z0rqI{FP9D$_N}5ruKg6Wi!XdiggHk-w}mf7{^c!Ev|M{*SrV*cwXLh+ zNf)hDXBVr0sCEi7IH=fyKW^EDj$50U&3OzTM&bCcr`FZb;{$)JL?nf^Y|YZEMg)qH zZ1V#hMeAWAGG**f7R*R$BHYtr^8`dzd7zB!m7sD0E3huF&TuLM_<9*-nHfU^@j3;_ z+jyEB6Lg$-MF>zq!}i1T4uTnpbuE>xJ}2?V#~1DUWaaVXfr4nVqYTRZsBjEZs(>&A z0O{Ujg}Pq0q4djha-3?)sO&E~BLa8Mzpn1}1V6p+%i8}>;xw+Jd-#i8)T3HQsf*L%dvWLWqr~1T^65DM_*@;XY+Czt=9^d z)(E;bYU0jdyFW--<_JcnQaPwBN~Ce!(fb`uobUr|OpBj{3SZ6k`u3Kk)fLX%=Fa!u zU}6PT1f8#Ydm)~!^**0w_^DIsneM@E^`wQmGtRMli6i_&N0VH5oKY1d<_|89A}uh- z+bbQfGve3Y?qcKlA)mt@tdoZ6<~*@6Db5>cNmF3r_OEbMefBdV{)3~--KEJo+oq6c zVd1t8>$|?8>PKT-Gj+_{FaRiFXJp9WMZ&)LvOIZ*<$BK>h0pz6>g|lLJUo6|j>$iX zQj1jkXY9FciTY%?@F#6ch$prpWQu;b3c9>qoEQXZ1PjB4L}S;dl>2sXb&}{l5--Mh zqb%4*Zw!n8Y5rRUpzB~jhv$Vex@`O?iTMSoOIg(fo&8f^V ztC#bbQ&xMF&9T6xf;-*I3TS(dN}dC7c@Ws2$d(3?QHZ%wJzNO>tB^62m|NTDUlT-C zbbLT_uzV=T!hnixy;QlAGbdFD0|Z~8tl?iSwk$V_6A@mj6Z8Jq3vltzDyT+qPEQw%xtjwr$(CZQJH*+qP|6 zr}zGToI2+sH@QnyD#^?{=6Hl+(iWN&q?wO58R;MPi(`%l2SO*L#gO0%SFoc-J>5`- z(6j5|K<77hCzT1FZy_AoI0JooaDc}R5d2vM3ST7QYAlW}NC$-dx0 z%QXjh(62syeooEBRC9C$W5&l-J2PJG$mUTSQ>0+;hbgaon;Jvj#Rqz@td_zkgsU0P zae7ujVN$PqNbQC)N8d+|={mO(kK7UrcN3u)<@m7Au^l1l=u;-tLv6{qrJ~eQToBS{ z=JSKneLBaq$vAeRxoj?+sKGf@rOFK==3fxLMIc86?7?V4R7$wRgbwup8drIjvn~^3 zV2{?y0>tw#GTx&u|5sdWM>X;h)#aP<*@;nSdJJyI6MycXA9b+VwFQ~!NQ||T!p~E^ z;4c2-+Xp|6GT}^v&kGu`in#oe`(Bwi7zW&xte)K~jZm$AVVwwEow?;*XfgYJJ zY+#NhGl){|8(Lr7lyP-$kZUM_93*_v3;o?m;1MC;cU_DLOco^ zp(5+y+Pp=#Qxq)P ze1PS$>M~xfx23ZMyOSGwA#cpxGT@iOO*b13?KqR3=#pMuEj{*_9j1Of?(2Qx(&Z{v z5i<04u`Spt_4y@#avZug9?!@lT%TN}oPLi$2JIW9#y}Cx>g5uZzu&RNIV>Evc{OpSf`Lea39!$yWyx22hIR zJL&Fe=zr)qm8o9;f;zExA`VRbIANV+Zw9K@X;e;>d#F1z2FtO5r-Nv0>2kL1!MUSS z>cc!xm`2dMD}(^????V)%ic|(Z(a;F!0QA(4kK-#77cN7n5!lWol)Qb|LB{Lx6K>0 zG;oMUp+yhhfjt4^4NRHTk7-N${I&v`RO&T}*D*TzK-AmsErvnvIMGo&HYiBbe2)wY zA6#fs=PWmX6Zw%&vJacAw38lZM>M1-omzRqF7E*+NC?t3@$HgruuW9Stb?=G;Gkm# zKc$yRg+~b%M7N?mpXaM~0lrd7Fv|L!%9FB(Pik|-$A%IAX{Vsd$J~iCmI{xF-{^eC zpI5Rr!LZ*}#KgKB5wu4B$>utgx~rES%9`ht9?DI?MW(jk36)5*S)0ei+1N^1r5wqC zO8%Xs?2GecWQ-pRrU!Qk{_er7Kq?_FVNe2gD47BIcinCKF{hc3vau{{gAip~$W=lW zTjv1KQu50MV&CPlA5+En(q-FPUu9xC^CH_jJpFSUfZ4LW8XKo^>Y-*H{+BC)*p*y^ zuG#1nOxOOep3FQ#w<}!bdtXqhY=xsoSYPQOX{_!#{7yLS^m?PDjt-S=h7)Z|(=1)q=p<-e!-upR02 z8sr&~f}O$R@Ip_TaRdF2ffOh{j5Oig;5E$9zQ)BJ12c(gUl{Pmhh|fcNc~2mcqaJ} zo}%VuvbD}86@#%O2+(mN!u`^rcb&%W+4}4<7v_+d+4Y;W_=jKFIbEas!)+cN9G*{cuL)}+H;w3R+0mnG88-CFzQgw-|8R53N-OLIr8SUr( z?ha3&Yn2?g;5iB1lF;xKz;%y3B> zuV2Qi80A!Kq6mA-Ff>p~8;-=)1&!~jtj4_7t!qyT@R6}z7^)EZ@-}L`{`xs#$7tlm zq7rkBIEQDowv!4#W)vwG>EmU04knuhE=)SR&}}aS_z=ij>F3L%R2JxAALr87SNE(= zP98EPdHKcDS*DDpZ*0->@DD}5i>SjC41$S%2XyjUllSy*TJ&^#w={q4-=1!1-qnPR zz<*m)$6*OQ$qYUpUrhb-6l@*~R?ok?0h^e7&yR0|z8O2Oh&EY2?_3;To@(Ezm~b34 zvXf?M&d}3RWU?{x&v;%zXDOMO;$0w%r}Q=`pKvSTWmw>TS=6kivxc-q^@C=AzvyqITqcEYyW&w~?(^?%fHkg>Q`L?JWRR2`UjlgZf5NU2D zfdh25T+|yxS0Ud^zyPzCvTSI7eIVQcl5tYTV0LCqaVbXx^NyRVNpI>upVo{FFXdstWoxd7p8NUp34)6O`!7R42oAPUi9# z?X<9Xu)~z!+P_xmgc>+Mfs>kerK19!i89~Z7SlxGDH@wdGkdV6_2(>reM|n~8raD~ zpf6TP#(1?t{R1liABEsWu_7iMDSA=Fz0!#T{t~-nR%W;V5cecG2L94(=7CKSUz+H+ z2|8l~rn45?jJX-YsxW^<`uv^C&lI!36s?gl-jxp+Qou(4BFx^X?NRyG8?N<`MoEhm zkv>HEw`@1T8ORT1UoFu$HELSaxajZnl$?mhVyisFUnrTtC_>*yN|s-^IS26j^*>Z3 zJeeSK1W`JlvdLi`MJ2-0h_|G)Mx2CbW??0u3c{%;sPc5!iH>Vi$M!E^D6pEBm2y>+ zzLZdMs8@m^BM<7!4l0WJOGW}M>z>D+SNu&&Y?AN-D4uh#U=<(Y5R5If%&efkgpkfK zZsffiZA&YF(n38gS_h`4H5z?`?9ee47DOp7#>~&5C&tYA|dp~*027?KBaCL?~DJZBnRVtzK29zj*3d1D1DwW$d*H1 z)x7>l3<{t2Peuwg_>uo8qTyax0{4Mbv;V?5vAS`)F_^F=c0+n~d|+z8S8=R1K;YqI zsFqPT1OwhKRi$!=r(7q+|DS88j%8Ct#pGRZ)CPJMLEQBr3CJYLyh^hr_W;nS2yqk~ z5=LAiAwC48{-8|9|MDX%B-_+?;WEpbT;#dHGj$xP%4f@xNpQKKy%pdiS37__OL`QT+FAPyU$3q0^)f{S?#YOuz%>Q_ zP>1JJ8bpL*^0BqvftHLbKUX4bm8-Dsv6TdMJiqvyMz7bX?M#bCPXR`1s;!a5&!lm% zhmeAEWBx`8CQ-qeajv2xm;yROp4#Mk);#=YvAc3#4L#i)O}BvwFFI6*n}x-Ss<=2s9mUvuy{Lh%dfZBOSZRM%L$zTjxF1xr zvZlZnM8^aUz1)FF@A8Fx3*Ya?oS*l^MYt(yyR(P`cm~T2&@5idP12YO_U#zUQi76z zpZY6hLgF6D#B=R@*~?fXAXR!0rq2m4(hP_NzI(5oOt0ThVRrTc*--!}Y1Ed36I&rc zDUGL4J%^|f%5fj8El^s7vE=Ke>SbU@Kq z%Y&jHp2lP$Bkz0MN9nhR0Vh4fqd1vGsW@HG-|+2xHcI&aFq3kwSR$XU-Do*^B+VPY zU$FUqw`I_zlLJxp~6EaA53k&#ObcUX$?X%62f^uJ66Ue1qIRgK7?CCByVWPFuXoH;=@2d$ow>0uYGBV6Y871E9Aa_<;sPMzUH<096 zw0?_(3szwlf;7V~(wbldVi)6E%qOd-1e?;A&C5T=f}eb?v5oN;om?o$z&3z{m-5kQ zR_alPe?D@=*EV6HSBTlYjWnD46(@=KWFBxYLB7M*-o{2PSt5MnYGp}~%}{(7!yUg8 zwmZ^>DnI}_wyLcAtVeeM)|E6!u>Q7I>LB_mVI!_|CbH7GJErAxj4vQ;%~;zT`0^W7 zoYG3p77)KWr6+fTV7)4UO1o&qoVH5=it7wE?~o7NFPT?6RjpH4*lxdtHvfm5l)P$k z()!F(mq~D*A8Dj$Eh&3dX5YN-ogtdd$d7cI0h4Sve$oBJqM0%~wLtydkx8rg@6r2a z;rKD~kU(KC6}4)ykj3tVjYheaYj_2B8~3e5#qm|YU59FAymZ>$>9{CQbrLH8nFG$c z%Ubz+wc_(+%cD98H<2rL?Tj8$vG?gltgP%J@=b6$Q`B{xvFpTm zm}H4co4=iIu7gsiNdtyZSj@NY4;#Q9&g;HAunwG7@2eh0iiB_B$Q7YV`nf`UVqL^L z;rW#kZK7H};DiMwn$Z{x_uD}{{5*?JBux1}Mk?tMIbbi8`bN7|?|s=hJcW2(;C^wJ zuLoJ^(uEH)Y>uO z7Bf5I-kYd2K}zWs=vE&aF=wLO>i^}na~I8U*oZOV!)Dx|QfRr8)V_Pd_Eaz_$(Lmx7c3 z?0EfOs8UopP3k{Tr8Sp5V6wlI?Padc7}3*l2S#;yxt@q@sZtiwtQ9V~wp1A1_H&Qo zBe4)I9d2TfGEG1lYY0tQWW}Q(k(D4Y+_=;uTUCj#gH&<9gHwLOR9diebBT?C(N^%r zR==0SmFqE$)RH$@d3_siL&kt4mIqbtfS~9YxPrmyi=!UPdrkai&!!%C1r%f75iqfsp->!5f}0C zn~26C^KTNL*Qd3~jDKKESlJ*79pf|Aq15(&Bb8^&|3xYfCprkGybpA9rWmgHPfPC_ z4eiia;yW`%)-eiS$_t~FiIX##&-9A)LbIX`J`&3dKMO8j(r8z10mi`Vy6@K>0hs6l zk#{tPI!|6l76(KZQEomdWw+I7kY|=FsFsq|klh&FH_|O+0nV z`h%^TR9qOkNsJRpJ7<3_`HoVvW}LCb;EG$@|LBxy9{P~xQj>Xh)! z?mqw3Db*5lKhnI^xX;0LesFr_-o$F2C>Okad=kH`uTh>*pELJm!TEa33l1b7j=rDa zwzYfQyDZi~NU@zQ!gBM3SCI_g6}O3nCbEz|7n+%Wl}e194&o^^Qzn+BumBO`cZIq} z&%c+KGXB|q?tJ=N9O;R@iY-xvxp_;#-=eQvpwlp$OGhPw87frF_?)hO)a_~xz`tqs z*bl%I3}_Lhv+Mx_au|{rYTq+&R?tXy+QaaaK{;wz9_C(}@H%WQKNn_`AlVdlTo0vI zMQ-H zoQLt>nFL}nx3^h4rcVFf|9X^(5qYvm%givG_Z8e-w_?>yNFhVptT(<#cjqG{;NPn3 z_^FgUi`Oc${W*NSrNgp&7!|HwdaqR{Iq%h+=;SJ+%4bZE|6uWY$IzDp56O1bALCWc z+LU+v@!$W*t{|Y;@jZo?T9OTeys9FxJB9fTz{6%z(TkC0Y(l>9^yW#<1P4pk2go)d z5k!dRttkFtxIln=eYD*Dzl8d%3Hm@4>K+(J>9QX7I57WI3NW2zH>}5e2Efh&5><9@jf3<@32? zSLR3whBA~uRfB()R%KgLKl`up^C{$_DWrO$iDb~x7=u&R6`QP~D3G^>M=^UU3 zTu8K_Q0u5=G_bbYWb~T*4iy4=-n5JLg-IS-ycglbSi$`!P=^2cxSj7>8& zbqbLHACnIUv;7Fe9WcLGjr^ML_MkFX zU#^ioa4_2UPaPR0F6Dx0=wUHP%XqXn91~4n$1nsk->VdoD8^}DKA)BlMq&RMn&7Ww zxvCJy8UYpip{1GZb^j*{*CRAG}%$?FAm;zGX zQHa;zI2} zS*rA$>q3nG>sLA%a~;PZrIsf0KR z>8Tcfo0K5lmISfBkg@Igy4G$I`ou15IU&_+(H3?^5(w9*1hI`EktP-4+-HJNRgTJZ zPowb5k3(-k7W-DBmMp}nR~vba-{PxC&nZ$TtmJ-PbhxW8gq1BVE!XWz{v6(<*l9Bl zsv7f@sg7RK$ZLQXa?3%TC$+eh24fi8PQSXKd2w1z5lB^M9Vrw4)D=#DO=vp-;jqGk z)5%O)qy;4y$DXTkM#XwFLvOed#MjnP&F{eQ2HW`Bq=uMV!)~_0u;8@sE3D-I!(z-h zBt&_PR4ikkR%F}_HNzkc@uk^4^T?}9*?^t(x_Qy650QW!>aDvaCB65Pc0fs`S#g8^ z{YiNrIUCcIA1kx4w@<7`NkoGIDwJo4yiwZuB*T&~6`M(lc*n_!Sg0Dc<1>I0%Nl`V&2qEdjuB=}IJ5E0oU$YcH zvfl_`(tQ#{v}OeR;h0VOev+Puv&|pOH+l{&vi*%h0WnUP9$vTUHPF#GZOrxoMce-Y zGnKCJs*gU=$UwRBqWdB7cYCs`TxzGq59Bkf9$QbgjNm2^pCHXmWg#qt{uTjB|6_fK z8QD1|#ZwiT6qJlv{~s?Cv+EqLegA)XneX

    U75T*f_uFLDuqz{BVFx`Y0^|2nf zYr?Xj;8%h+Drs(r?l@znlImuSyH~ISj`JcmMVOytWyV`GWirJyp0>F ze!D3b&7{n)5YsIbM&Xq=bV4k;K@zF*&aM($m9V8xuAcpsncLgfzlP^ijrr)qMDZtF z9SPcX-Ab!}3s>bv+S7{wbxsgczS^>hhx3gz_+=M?%Z_o#eY>P;XU2NM{iZ$5UpZ*SW;QQ1g z$QEo@lFB&gK(Qzj`3_n4UX#aSZ!Z{_`U`-{*R}b%A_MC9rh6a(BU0Gr7mHR({*}13 zMg({o;cd<$suAqF7#nS0%gKl+Pf^8F0c%l;O;pwWHC6ptul_dUaMXF+sgc;gl>dO% zZi@VzpV&-HGYEuWlbADG%5RR1Sl-7t(};|{&Jq2pbiey?gY5v%9;%})_a1v&1#s!s zP5>grCbzd6?;{w zBCDd&oW5}D48y2hQ2WTT&1^oam^JCBag|QOpHF)UIGH8Sf#xY)xu$nDlKqlXp!pbK zRT0OiJqeMF-P;yhAj!ofL_R`qgiF1I&mY>`ARt_!O!3suXKVu7c+_ z1B(3kTGP*ME1gIcH()*(gv*hYY)R-5Nc|w;0xT1$m=Mr9IF~rQJ@t!vYp@VXhfv5r z;@Zvp-t*XJ4wHi6@9U`Td~g z-To1q0|GYVzT;SGNIbWAnZyDB>XeWaqT`iUB{IRH01ccpj{;{`DOq`bOykb zJuV#i3|5)>A*Ix1{gNJhB!c$$y`KUV5mLnFVam&C8&*DfzDSW&z>;oyL$7ks?qQ6b zpG0@$q%EhVLDw&Wdg9n9;pKzDj0<;@88ng6gb}GlxW5%zc2343PzbW?QgK=0n<%nY zj^x^YFx$BeR6yx-af24OpSd=^6s`Rixoq&?PX+DGKj&}P&_z$gvYe@}sSzwKtdQ^e zW|dvu_Atequ~I&Do!SH9R1Rfq`B`hb|JV&8C|#QR*-FZ&>BRihD%>{A7RlchVlO^V z421Qr;DP1Ce56R5$JfQ*_@GV79)O>ui~of$O$XkB#vO_0`j-s%MwUO+pEdc5w-PLq zat@QXe4XcvwFrn}LN1{7BI$ztajcA<3Z*>nP-tLKsdngzb= zMBh(sx%VYRO5e}PX!Z9`?x_tN>?9S zDlNBUtF|=1@5g;^C&Cl2zKC2vZvI`K=wAKvsHct0vLB@mIQ+m#f#*qY%l3*Y>k4F( ztfBTkasg0f8(lY%k{DY04PC(uS#>em5*!Fq2UFA^_2&*|pU5%vR%%@lHfw#=bZDhz zW;+XWhjDirsU=Lmszv!ygmzCtjT;D*C8o{W74OHC`HEcdCrgQQhR$naHz)y>bn*l_ zIzE?Y7$#%=^jJ5YJ9Yn68=Ckr?p)fQ&g`t$0L)X$MCGo1*Z}ujs=iY0O4H41h6+_~ z3RNE!jah5w)|ZX?8a2(G6&2BKqEV_(#pi=s&vzbS#GT`6K&lq2)Z5u|D*W48+e6z% zk6N|iKfvza1Mm9X-uQ&&+q}E7qzrE>jE;6EkclS;G1m{pa~DPC<4cdXCr#t!oxV*p z9P@Uzv;@)eb#>3>As>uB@(Mfb+$dQS*rqAPYKV1MVwr~Bd9`9aV3W$7Y& z00=KwKleO4k_4nC}!ZB;3a-Cb!niD3!fH?D4?h6wZ!R{yZ0+9xnAdD&0z0 zl|ei7CLt?0n5fn6P+NW=-|l9Z;b&pDQnt%wSi73d$T8Vu!wbEeC|qa@_3Q<1d-rHh zVa_Z%Ji%&BvAgdN&CCjrF8uIGhq zNm)DKN1rwH@Sj1P3V5Dh6A=zu(vlaHE5JtD%0nmzMLruYCeOoJ*}9m4#)3Bz<-b>OUcNDiq6{si zOUw2lsxl@TES|#-i!bSClXfCa|D>Z9H15Jc4Rc%WkB(@VQlC_0c-|k%#m3yI=q5|? zx$tv3wvvjYGd;)Yp^s1V1^CtDOYPz%&R9sIk8`Bg&W5oDyVzHMelEYfJvUez*!^;T zu910Pgz_S=Bx-c5$fRAbI&5+XuOoRC7or~TEPU@ggI%!nn6sdC4jVCRdUL`*bS4T{9 zKA6_+78)|9uA~ay)^HOED-+ZQRP3alxjSvAQi!<9l58DoyC-Z&pqsUoxs-bJ(*=i1 zN}bS#=j4`Z{+?g1-#C5isw93kv^PJwKN3SwsLBW6vmSovRwT%(B#XO#Z=6X&)EYp^ z+rouYPYb=Ie*ax z%Ig?i$%2d5v{?9_JpcRaHh6LViU5OJdF+5e`zcdcnD%LgFTlg7N@tmpJl6)nc%8C? zJeX}TLK@Bw_SA(IhinZcho?TZ(|E^G`frXS(>t1W$HKZo<P?Ah*pHxpc~MQom9k1|genSX0=xT`Zc(Mj)!koHwsM6A0dZ`Jkn z)!w3dvtxVw@#Q*xe*we@Oemukv}j4xcRhaDQRR{845fu3aIQ)!RhOyonn!7~=dI&I z*=Bi}!x&xp4I2vYKz}gbt;&0~kue`HI|p~trOKRd*}RE_H}F&6UunR+2n`_!xg@L{ z)tz$J8$5BuBh04|l0=a`1$EjlD!L8!M4Ftrhz;gItXn{jv$=*Ppnsdit$*m?W5(%M zrt_`ZapY)plV_+2Uoci>c5zUzKP2neN!enhTk}dgXzj0&Ejl2&rzx1&ejLEwjkuc`4>q`0A8}3I zBz@wOVP0J_!9bXrAro0gA*}(k0n#(A(FC`7;;Kus!z1+ZmwY0$F>CdsAbfIm!*#ph z)=uLVeMQpx&l`cLT|i$gtdE{LytqAwwt_4bpDj<8ygu*sU38P{GERKQ$fu?%(SbcXh91wddj|7ODHe<|E^fUTZ*zW5!-%3q-9b0cN6^MbAVr=RcbzwFDsY3_I}#6_`d8()3I} z51uMpgO-$^v8oNH*qrKb|&ksD8n9D17UY@a*udS+wR$&+gK|U>A8g zvyxPAPA~8@w?8NdP#~Z8WBBuc5!ztVEV=C^l4F~$ocqqzC$GbTeeG%ph@J-8T2f6k zAK9+>OMq(a8Zcs3vtWJE=L|k=+iAoOcY}32LhgV^M~>y~0N_}(HOOlfh5(qu>~G)S z-|yh9Fu(^Eurm)58$Wkth9vSw&oxGxZIpw$J^C3+0E#iM|3Go#JnC4&R+fEFrW`bB-GhUVz4(n(BS$rwFJ5@wXZ^#;d|6UaX~=>^p_#GI20;J z46yqJ`Jo%MlOG#~QYyio6jN1S7DtPPX`AF##__L&pLd&A(H6+}ir8z-DI{P=cmvZI z&eBs6!Gx1lHxv!#USaI&3he*Wh(ws4~zuqf_$A;oP8>u}7_1J~bMpY=& zOjCKcgVDbI@HV;}R!`c~or5T2{FI)aaa$Btq4PZ|te(aEKHJTu{f4}q;rKq=%Z2_# z-p{T54))!d|I>7Z_X&4v9Og^($<)txb9#mwwTWL4W58gSBO~eH1va#3iuj3{jr|*E z!iMbc@Dz_Djg3f=`0Gy&;e!d`V|_skLTzBNnUc66_}o&gZ6c(N3e_UmmwC`C$cjbB z>T4nR78t0FfO)h58-ZlAC;gl6f!V+S+470+35|C|n)~kWl0V7b15r2Su?}vaE33K+?H6b@>n(JI;$-w^)#{Rnjyw#3HM7Neyh3aMMA%E?Jc*7! z0?)T|){sKwKFW8XU6_7iAkwyAN$_B6wa=bAjb=$&o!b9Lvalv9ZKhOr=e*fF1dmrL zw41)w)A3QW#pAnQIJlY9#>N0 z%8TnVc=|^uAOi?Cek(!Bsa-JQn;m!U#+r*kk$xe*l@N96l3wd8Qp=$&vjfa~5Tn?&!)0aK13)oBMY;Rup4Lve>Bj-h@nQCi2)mWcUf1hl;1WC z>YC@yZiY{?x`Ab;;(=DQwZ*kTs$tm&Po@sr<3;6PW}@ z-h-3{LBq8_$oX4n!z38kOvDteE9(|Ni`)T0!ZHYmSVthqV5RxwfPd_=U&IW1*lv^kt&bEP!swoa=%R-GQ=I%>{;?}%$Gjf{kcf^V8|Ko}&1L}% zVci2vhyp$*`o!&M?U};Gs_U0H$ZAr4A$pMrSuq_Fkxlean2r%}$_`7MI2zJUj<*B2 zrcjv&);IyyH-Q*yI;3=#FW%Q4>@l9O`<1_FQ}jm zkZY``^y_8LjomvOj+q<@tNkPN4G8M&w?&MPKS3*YacIHfy! zJTIaCL>t%$aEGGe3%SL?KwwNXn_{f~K43+4+@T#aKV7^mVcQEVlxf}99N#@u(El#ly`T;*%exGL^*JeXqU6t(F{4iJ z45aw(AY|!>wIkuoH`7{!RPqY!R!EEnbp4dfpSSNOY8@zd&pF=g~vq8w#Tqx_c&#GFd>-lJrAH}~SE zDcxTbIafWeF7a>HN1U2aq}S*9t|G79{?zZOqZ3-sd2SD~ zu4BR-5y+DI1e`{C0^r@XW&BcP;Au;PJoT4{Y1EY)ZZ`DBfd5^Q>>LG>UL{9*P23uW z%s|Azz6GCED$YZurlYvc!~3ce(&`15waCP1OsROj=uw64kwgiGTd>-jC7?9LXUXzD z^iR!BfgYU3LR;V?S6D$fMN_m2IBD8ve?!u>0jz52EE3)N_W#(7;I6aFJB6V{x?{-f zPjlz$JwQ+IsQ=xy9s8iDXOe(JvNMNQ&pmJ;F2Xm{<@~V%|S|KPHBAGxS2Mb3nI^v8y`=+fk% zwD>1DxUTKXe6Cvx=b0cLwIA4AXIw*kU(AIEx^8xY<+zGzf~Rbxg=HaHf*-Vt{KA`Z zLO_}7R+k?i{B(4x&F-q<$GTM547%b}(~N zHn~R|DTO*P5th6K8uB|mV_7KEG38R2xH^=bqiZ9dl%q9bI_2 zT0DVGCK7VkuH_$iO&U;0MQ>uz ztKY|(GMb2~sH^C3a5XqQ(-HEc z+w&YsR#W>KbpxB8-ppp2#=+Wh?B(a8Z9WUl@Hz=3O)n8f5!+^>^iAJtao_U@qhbB$ zh(nY1uZW-{+Or$q9S@`TL+BbYHtF<@YO#m>!x}LO!=J$?GcZ%hS}~cHwTt+%XOiVV z6_-119Q_Hojx6)YaaAZc4JT48IWaWv9n&L3c zp)yqgwEHft!Rh=n+P;LLjguWCX1C4VA~LDg-w|njFyg#6>>NDCpi}9nN9;!*n=yfJ zyZ-deJGOK&SsjEhfmDxP!0?3(Rl+O6UY)L3ZNHsuvqh?3kefY{**3 zcLn8HvTBTL(ltF{=R475Wb;b$x6K_EhCJvVj&ERUj?6io* z9absVrKw}QF+nF%fSHb-HG;D*t3g#xjMsDkKLjst;}bOfn?Tmsk-j%lk@x}@UUp3s zV+*T_GmII9(lw2&8XJKnJL#!+x|pq%dF-B45g7tB1K>K&(Vr_oqXR$NP=cr(M! z_F07no6z<*CKP|TeVnN5&$qmOkDyCNh**Kew^n4r1diXwm(r^FV>JY&MDQk{f2g+QydiB8XOBoj~(4MB9NBG2j%;4g#M{}T4JNaYI zSXmqF{EEH-8Jv36sD`mtSD`W3Bq799mi1)-m%Ig4 zs^pJ@d#`{dQJnHERL2e(ac5430O#-ZL5A^eJeGTVIn8g{DdbpRw`5=!e~?7GP%`<9 z9iJ?GYdR;;@{AJErv>&Apa=I&vBR9~(ogQwX9W(>qlfNIu|FQ~&Q9#lW(Eq;p@(iy zv3F$#4s=q(-5l@U(xQjDI@;Np`GO(6H%5j^Oob;NR7ZU&48J^O6*xRvP)d2MkOWgg@$R5>}S2&lp+*N#4baY_@jdtQMYIC!pu2-uFkJ$y?q%p7s($s=;w^vnW1wfocTIMPj-Oi>EN%i-j1Lr4)&@AjOcvOeOq z3?Wnfy@n_dl>cJL`T*GM+FHU~mz%2=R^5oIo&D8NAdJR3a!+5R{ZE z!#ko7s(|Bgk)vRqxlR^%3y|Y=>4(WoPAv9>Gs}ldL{9Bsh5P40dd*TTZ3Fd`is^uV zupAP&kPuFQ)C2$^7DsJ1<>-htWE_yV?rZZ2kuf5|Cjl?HuHCQATyB@4cYd>Ln`5A} zS@!%Jf46wa+2HCFr8nA#*{I9G2VSlo$SEnh;bWCCT?hOK9yRF8Z;xzFUDjTlf61tL z=S|hG(HjQ>X3UR@#|0!*?RjSeFWBK&l0mRTV)QmnVSG^UfbKSXNP9lifg7X_c=6-k zuJPI+-Ggn6Abz9)+I?OaTKVZ%d({zuxq+=UCj%osm^t+L2~A(AOrioA;ubsle$qS} zc&-4$3Q&wn>L3RGaWfHWAp^yPZ-?3$xu-PsF5nULHf6FZU?i3U3G`~VaA9u()Jv2+ zQwIy+t$z3~%R%giK@4-u4G+X;+C}xUgVePo0>V@}=Nk(HKpep222pDDY!%k?ztIcH!)1@duMCBi+aOIn z_8QcTZtwjaVBbMcTXc%|NLK?PU$K8Vk86_ct&D@J#M%BPbGh;D+AwI4z-~$@>%z}R z^TMMAG{W8I+&4C-(%A1! zyUUtIw5UFP;+)g>&J&&IgKYF9vrG!>Nslw=l!b#2f&YAF5TqZ=$^f#xJuHx>qI2?0af83xz^%6C467l^EKI=l9R z^uI;W0J+a{*IEQN$!H`r+GH%AsQXeotX^(2!$huwmK}T<@Y-;^1@lsR8UjmPe5}$^ zDr^9==0%Kfo(dN3^k>J11Q)|yN$a;rUQ2j*4KBKJra?fnd9rd*6s(?YuoYNr8m4Q; zL54c+T0uI9=0QyC9@4+U2QamacAQn7U;HK=8jU&W{+}HJpFkf+OE>tsLN`hgu+@{? z+V!YuX8WIc`S}@8jCKe>PIPEH?Al-CB+GgH5;$VBT0_|eY}{gBINgbEDsthyj02cQ z9g=587OAule}zhM+gDM&KpCHs0i)LmZ3Vo)oED$VV=#Dk=tl$YPsHNA#J&_8ucPBQEhT+2ola->9~;4})FVR;QLUgpAWH$X5U>DjTYD;!m~uM{Sou0~DV4I^~sr(1`8-9{__u ze7~7D%4%kO#S^-G(jNzY_nI8{`u%>;t;^v&iO3tU+MgCrPV0?&V;vsrQL!NpXa9o7 z5@!x=_cDSI3k>weunKPor`5VT90w!3@nl>8V~kgvVpA-_#{{B6`C((FzOtO;BoOdV zi;2h`M2caFC>meOk*SXEfLC5Rbbm=SMRlVvh20|Jk&J*UD91H1wFNrB4GobkJ(*X& zPyzt`sKi=e9e$#i)arS=$4>IZeDGX-ar0%f`SLhnH2$F7<}|Yj{VNqqjlV*0A-j>#j=Mw$mX@v7zTa3f7~ot^CHgSr%)QQ}(aM z{ZWm3`SRx0L7uxe@8!$C+V`2;=W3`kO-t#jZ`~?W?$2q^;D#0r?%JfmpVy}04Q(3U zwN1l6uT8xh+SI#in|gmJX@`Lu&39F6^l|sq z4KQK~wAHBJDMuKm>@-7C^|Lv2-Seo}#<|~@qoKGh3U?{N%E-47#l_R6u#HE zCq8|79pkk$BPe*iQG?FCZtdl-*rJB&$3!9)p^NJl8ZnED|wk6KTa z48+n#34cqZN1H^WiP}GCKi@rg+HRdZZ5=zNc%*|@wW#8lp&LEw(kP0|uPY&yF7$sqZZ6UT>7>q$C5mP+Z}YjzY;P z130GhmTV1b4s4ivW9*!jf?9)LeNK=DY!wluu|Mu@6j$^~jhw!Wd+zaALC{>Pc=vQo zkjbq}@~nIJ5aye7zWNepFsQw8&WFtNEbyoboB$DZmBxlja03(8W3@Bgr!XIC9m{r^ zGU*H@Pdw?QKnWm2Rw*DZ2(t5{b7ZnzM%#q`B_6Dg(PL8GwzGDvl4W`N$}+TuO5HrP z`jjyZ$OG8rI{qoGt7nu%2F&Y<(Ob)`Y&fYoIF1EjZ6OFBKFAQI&?>EC-+k1fYSB{n zzWO;JD>y|*a#c0)&q!H33@#N4ja8(t5r{Hj9FVZ=qYXee7{dzq&uK)gEaaGVsDp(y z5;DI>Q4H-E@SY6CibD~hFNfj&8S+7@uLjkjlvdusfR3#;A^h{^?vLscp>;?>%?e^X z6Qy&@DvDj~h^i|~FfQh3X;F*ccot$`+X^8N~AVJ^mUDIaG@>0FfqEOPwQe1b1tg|@kPbXrLffr23 zEP(hI5b}z!q7yojPmD)sqCu18n3txgPXx*xf*#&r!x4j&T<_KK?#6wbd9{c2Wp(oN z&OXX46`k14GKf8EiedSSI6SLSpkeJil|4HG0dz(AE z^hYS%iX3nSJEbBQBQ}f!i@k=z5Q;*otPL9|PeqwF<#JgkGv;061DnIv%0{UO>(yav zb))nHJv`bdeFG0@FuvPT!znPHVF%CLcPUQg#+H_;`Q6*y+<$(u`Mha;kQ9WmwT+Fd zdx9^&&cTs05Yx8R9$SokWDu`>-2ytFWTRk=}OGaU>xPP&j{8k$4>pJIJOPTpgF> zArBhcfr+Ug%_eRyZq~8H3LA?1BvPwo+Kia4kr;2tq~y{u(m7um)@iC1yi?1<^(5Ph zEn^lRrQ}4`qHNe2l|u1h;bZcRLy>Ky-;1dP0(eVJjSNC@75PT-k(Pe4IvOYAYN8^; z&P-bEeN+w=SyTn2rn`o_dNvWU={qXkU_AA>=q=7U$L-c5Vu5u-?-f@pWRhGKnIr16 zQStD$A5)5K&m1zL*tiq|w*VXXk%AQtD5F4IW;Xx8&^3l`uE^sg$2Np4-vp)ytp*fV zG~;%V$CLzZp0q!09%YfnT_xKQUMrJLqreG*gErb)N$j;&)<1frYoqrKtB|Q$j;H}B z{I`43oH>Hal0h z;k672nwt(pwIs_L2HU(;{s1~6{EZB?hXHWl-Z;91;lr&pfJ2i3(gJdm;;J2Lm~g%x zg&-iRcT>MRrdX5$09P&)Kv6{V!}k=i98EaQ3KrL`@U_hTQC}r1%f{-uS#D%)fOTeN zHE$cs3MhnAa{9lFc3rH z**4TIhlV=J>S%7n1_CRBa9+t9of&0h&s=;$-Z*((`3J2hbn)LEFoeN(rKyw;o8{7J z**~q6a#noL*pj{EN|xatMlmhH-ntB948=&F@p4&2H?2#7%p3T}Y5}FOu30QR%4UJD z)l?%__pzcA5*~_t7@}rfmUX5v?~_~8}e&a zt-mBS(<;e!OLo%=xbuM>b5Z&Ws-z_9@dnx(HeTa@OQ)5_Qn92?KcIc6dZ{zLJS{gG zr+vDb(EfoxN1V4YarB=Xdz?5&txPeTik@ zKg8v>c`MMuxmn`|;i+KHj(oY5&L{_E0GH$-=ac zvEjz?M#(?xzyi{{2>{(W#{9z>%!ouoq6C{^ga`hmXE}{N3OFu7Qy8s|K;_ zfZ#%&*W7w>(B9fm^t&&=#~Zx6f1?$HSE8B6e_m}!_Pkb(($)28r}T!e)-QEnvoByu z_e$&Q_wLIpUo#l?@HD|cBRAgEp}1GSx~?cC$dmw>)*1kF!y33A*jxSWZ?x5d@z~sX zsUFu?-l!jxp*c|qIn{fj&s+BhZE0w!HZ19#yk%ZlEXq$kxC-SC;`Ur!j!`5StHeuz2DUR~9FQPm zx}kyrCQ-Z-`&WE?(;2DSsKjMvbyRu?472{q8aX5kqk1%b$lysS&Lgq#F!YBhm3j)W z_M?*h<`@X)QgDhQ9l{Mk_8jc^DT<;;=iyTKtn_Ucu{2xCX=8-&isWa!L+x3!pH7x#s7X2jFIz z!NT2^8!U8D5J(Wdo%|ru1D3c+F0iuS67XW829I2pW-U#$=%SN+iMl&Zh`YcGiA@t9 zjmVy!4u0CCh?ToyW|HXobs1m+i3&io0hqyDXKmyTp`(K4%o`<>)gWSaAR5Jb13p8; znH}Mq3&WAExzH5|>~o}Mc0jXHlFatuDs0_q-Q79GnaRfO-8SDN-PlbtXX~5RRatc= zTUcLUBcJGVWPvje5Z_0rH&1d}u{j&^=&+s3<7_2ZZwL-aS6AI>jYDr+adOBctVQ}aS`JyXta@d z`|(I&#`{^|?s5Tl;E(W5G@DyQcoogZBPtNFw?G6yPDN_~$FSWfaJS)Hzy5m3m4ClJ zbS2=g*W<5W{p#NJ`nvsfuT)qR6LZheMkl^VVe`$`qtU!NJ?t0t7$|9$X;JE*wok%? zHafbE&QrE$q8grOu9O2)?5KX1QnT-&NS=2% zI^UP;IcP*ChbUEjAso*QNd*(3B#%~!Fd*mCJ}YJ>5i7>%*t;{C(k)t4uk)2=>?1+t z+0JgWrGiPPo>H5Is9Tfl{yA>icpAitu1d4ow$ny;Ce)vA>_@Z4L4A|T7kSaxa$7zy6 zr#nSEDarAoxw#FrZ|9JtB+u^7{*Ngrl$7L<1IU(@Lnooy9Y?76#PcG&E`1Tj6A~z3 zq^B%d3@h%sO;cp$-5alv++a7Ce;s!bKn20ZZ(&nM)8&hb1^TrwNB zG-U0$a1LzAk^^17*zjjj{5*nx7McT1*PQ_p)c~qM^ds?zyh&I?6_{ z?s+HJrZuGQR|kj3I|uu(al`uxisJ*$!`ej^xa>vHABi%7t-{Fu5mT$Iccrrs$o&)M z)}C5SZk+&&!&xwP9CC2)h}}l)Lc@RBBZpPDQ#4ioJFNfRG(?M$T8#~FwHn0!C#T~K zknH!ccZD&>2&szz$i7#XK=%ydu>%J%BKuGt42`RHw*mj?W^151%0bUwjC z_F>G-6F>-d13BHRwd3aA;qK;f^L1W3tf6J{ak`bbI6^USdD473WQN1Ay{$~8@tRk( zCvrNE%-tlHB&74{>6>KKDV}%4OCp&zz~uRU7@^4UWEj!K(0VlP{ZLP){lYAaCq37? zQApiv)FdHZsw6hMhV~2QH3sT8~l#mW`z>o0!Z3=b@*X7@d`bgAiLW3dV!bh^8Gttcs>y zAe^3|A&pNC4!hy`HM+?u(1q&JWp|@gKFBSQry>U!YQT3pG zE65IY=)8o%}eG7dD0K^%Rl(HD?s@Mjp+qi zu|DvF{PK^%K?axJ?2%-vXi64+WJ1U;=A1fDDXG1pluDJ1eu$V9n(`y2`dqt^@}HAB z=yx_V1yxG0C>1nKxN}_84qmcmQ#a6~dD0JmO5e`p{?AgikxPkIM5F}6XW1b zWKmoWbkA5=B*Wwn&S1TarrNdJngX$XrQ{uh%mz=(0;oinG3Z`XI7D*^mbVKA9jJ?Y znaJ^C)>NR)fjbl4VF40F34;5iALN&R$fgmVSZt-V^rLyw5Aw@DHiMB%XEd{jztPH# zHt$vdVL3o>dTu&INwqg5E1f%ao>XaICoVKZh(l^XPi6&JtVCmQVc1<@w3woevX4h+K}iXD$rm#u9u43@Z6e+kouZUC0x zVY#HTBBvD3$8Z?cM14)qP{WiK0n>#_ohB4Ko({=E-@cBx!PP^yCH5Py+|L?4&s@l` zKkL2*IqJ!6`e}~zL~y=kw@!QolkDW^u9h5uT&%~9dZX6p!SAoIYi-=Wuh4r9JQf@3 z{{6=KX#EQREAegArw1=lb$BGrmdmE1Cd7~F>5ZOJJr0a>=K)72i#z)}$2Fr>y6+|4 zR)F4;mjV{{r&n}Msj`6i>gnKMFfGMCZdD z0FtxQJb?6J0f3{h(}wL-V8haBi{phpN7~|BDhE6J^8&z8&)TMowKmKobwN;RAd6xW zWzmQh!GT3S%z2G`=rT{P|Jy&@PVe3lwjr z%QqJU@GK4B*@6Ieoxa;$r0e$g?4tX7i`2T`ZaMYB`$FvUs@)lM+aLtFywW5u0L=JX zvq2?J*cMSnhSC-Tv%kCAI!u9~v<1M71N6(> z#(0S~BrADwU@**a4lqn!02untJK1yECrJwc=>{Womfj{28pOECMdWalyzdKu$31>~ z;P+r*gx1-B-7gD(+&r?uY#uFCw9WCt8~~iQ2+KY`+Hty_5*7e(w7I{#^VEjGDGPvz zV4WF7=o5j2f(%LJeZK?v>F}ls+#Cy5;g35P;rk#LxczMbuv=R;pslS%ie`voYf;kZ zh~FF=h)!E%VRl>be4%Cllk2>1$JcS2@14No;4JF5N8u<)F~gbpK0|ersNLxXo&IgA z)OkNswQaO1X#3qRo=M)eey7kMfe5-WHU4hzfRj~zk!g1JFFMq*CKshF!tYpPVevam zSVT~Sa*mt`zY7%K+kC#W)kgnB77UZP*ihj~bz9HK_AqLTYnsdge^cI1srE8GDbk-m z1^CF_Fz0>$6!6(C`HUb!M0LXx@wsO{D-dnd;`&YaL` z3vEG~+dIeZHUv`^*^2BOIx`F37ZD+k4-TAGP{N`B9zV)}c>HLQ;SbMJTMtfI07QH- zh5{Km!b)CfD@3tS(X<_Sah!pg_kEEqn=E( zxTE}wHf;dsa;_lkWcrkfX3_QBjCUmPS%iHDaE#4NsMhC2lrd3v+RvhDB`*$a2BO)o zi_kpI%-(R?c9oV^@*+Koo&?&{p*VHT$Ub@B7g=eeIj}Py7ttd7<8CMF1}F*REsor& zKQq(ks3_I_^YVQ{b;c{!yt+)LyHv!7TDjo))7^o#wdFat9}CL*=AAMObhA>@U{rbc4@VMPG5vZ zazNbyj8U^#BumaK@>DUYJc~&4*Y(=&<9gK;jB3gFz@?aIwA$uPG9WwHw{UWKI2(ex`x~2|Fko&8*Ah& zpLq6lV=a>B)6c+etSQO%>1Sa%mCefbiANFXnr7wstVa^*N^e)K7PUx zN=9_c`Thwq~&!7gHDdy(nyR$kdr~gx5@2(cgz|MYNTs@SJ@EtLoh2ovH zBx&XIEr#$8jLh3TMl1Rv{*>@Vtow`l(YDr4D&1~A+dSDlrl3XtM2O^eGw6z!$C#rq zNeHG^b6cI#H9Gid%I`Dz-NkSFd-$~9Zo!Yf#Kezu5eXixn?&#?H+bMF@8%68yZ2@w zVe^Ro@GTa2q{}Gq%U4R^VQUNj=+C;LjKs_f0CPTTWBnVlIJWDH(+tIcHGa-M9!n%!BzVi)(jeyPT?nMj6yE23<636Q;6$gc7((rJ7DPx%Es>hM z%?bnwvybd?jI2XfeoY;hVxLEL7VE?g-t40d%$hvTT1ViM%l$FIW!WZ+^(~$OQhJ6J z+IAj(y^T^fpW2+bxC)lKZBCxQ|_L6F4f-j-PAgF zcbP-ore885UzW-Zh_tLVhwS8YR`AG@pOZC}C!SM{Ziew!PyUZi-|$qye|m-Hms7N+ zDV)ABevw{@m!mi6DGxHd7Jp;nxViu&MP)WPTY<9*RCs@Bpu!8R^Z2TldI1@`9x@Uj z2v2*i7xzjx*RCteD@_h_*ip`XwM{NJYE-jg{~NVAQh{}yS9na?Lc&UR?HlBStzsmy z%3e4~<#e>HdEZiHQ#Ish9U;|H7bb6RmYgjb6Q9|j2=%2}ncH;BHUqiw3_AtuQ`WK| zrvruN=jxM_lXvS4TEYu(;+Q?glSY;;pS`R_hEvz}=%>%7@(7ba2O^;Pqw=J&Jk zsx}>|b0Ebtzw?$u1cm1mF`1k#e?qQWE)4*-i3*YN#25Cc%yT53S-vsM?p+(ppu})>~8e;|7*Qy|I|Ec?Hue& zu<<1L0=z@rYX6}9eD~mKyLIxkbN!v!$XuabyJn2Fdco$;Uf;&DQZI z`duiRXa01w2Wdxp{1TA^;!=@*p`+;E-JPI%u6s=r4p4#uryRpktm}-oINQZ(P6w*Xe=pTC_Na-Rj!2VS?^!rh7 zA&}WZE>Mtm<6yiH$aE0{(0FFPEx4QlIlz#v7KiAT$^kpL8{EN-fQNSjJiHNb?{0v5 zHv)clH^A?*fNfuviJ#1H$gxs1Gb1ONX~tA4sDeawE~sxUKg7IvqgO!N3p9X3C(szO zePV}ACFgzO85%zTYaLLc<)yuf5!lfeK8Nvr&*J6J z%^!~g9igx_9UipQqxwqyVO=}vbX9F5FrtvYafBg+2awLSj>ZuPx`P-==0y~}r8a~>saocla=;4m@7xP9!pwcO zA5Dbd4AQ=e2R;Sy9(F;X0_<46B5E@obQwYxoEc|<>huGD7g zxk)JCHoBqTj-e<+#; z%Wu>p4ts}=BiF=4g9^D0l7J4OfMo~bj$fjD!d$We)IIT^d_h|Wu7P^tj@j(5iXjK>=s*!3msp(bPW0(`o>@@?r2RDLj2o$DSD*O`%F?C{TQ7j171SQv>!nZ-=;XImae)pc?iZd&zA_G}L7@ z1$F~-4aQ({t$dF60w6{atSD6sR0V(#2V@04p%lgg4t1$_aY?faSF|otZ0D=Q9W!zX zZZ_<7VY@j#<#=l37TLdiOC5rd7*y$L^ZCv`Oh0ySTkucEX9e}Kq`tS^)Fwon)LgWo zQ6y`>_&Zhl@yv>7ZC8nyBoV>wFWd@Z=N#x)&?>1Ph_oBH?O&-wZk#e^yJS2TBau&Z z@LJ4^S&iG^0#Cif?=UG5P^VxA7^yEc9(+}NfZw}8KO8hlb}@m3-iobSfLYi7#P zFypKn;Bw<`=-hdxt7~HjXq^r1yG#bO$@(>C9ff zXZ_XDN9#&+7^gj-)FK{SY1GCWQdkVp<9&U}bna=f@v;H@FEwIGLtmnXLK9mtfrnwl z>@Kq+De6#`6dAW@b%z^m@vhCX<1*?2C>UJ6GEb_VBz~n(y#!=ULa7}*SGxNS5x}@W z;WRxjzW@Fd^#nMplPMydU-B-zxbbVF^{PNYbiM*&FTCDpcq6ZeA71_X)$66N8Vzp^ zy1(zCeg%HwMk#4vp;UzL6GboH+OSU`Ps{bw-&Y>}?eybmrH%pKS1=Dcu3v$#uL`H9 z7^dezqldNr+ThxYkTir(SpCpDimVO=R<1gNYrR`W4hoeLa6pD`BmGtR(* zF#yJyA!*_-9(Hn}@VbF4YaczVH%^C8@FNt-41dn3XJ`jw=PXP+OdoSdC?Oz4D{=X4 zK-{ENQLT0uw?Qy}1xc@A8e)u?XBgJ6@c$`z&<<=E#TkSdO7a&h(m}r)qc}h6hm$gX ztSU;Zs=|{3>S>9~LH}$}2@J!qfq#3Gi!x<=weq^6Q3>JO>beTm_Zl?3eDh63Vk{%3 z8w~zc_*y49AmN>r!x-<}X^#e?IG7_8X;Hc)O1lW#u{30*ieM|MP>?e4;AFt6ztK2+ zqaJF#G`$*}sB8tkJI(&)oA9;HpY#!j<@uN}A_Hv2)Z}3RU{6PMLrh?7^uXUaS^#ty zk})uGUaA`npca+L2tTMset=u26mWf>MGV6cAsW4c77YMB5Cs5!X6^sMO5zj>?2#k$ z8omxA3^J^Q<>CF;!0%i@zl^V42Ct=x`|2lh;6L!MWlJ_0(+LKPqqtwA)gsp7nuM;4 zBgj%LbC9eGZUKwG^UFut13uxGCki(A<52Gdxi0Kq`ieWZLcLI>1H=&wuiuqDBq|}s zFdF#UiTV_s5QCVaVnPSc0~wXh*qLAfC_{%0ZG;<45;_4+nWLS;Ru`~`DscNe6p@rl zf(Vb{Y=iN80mbnJVKkveh;G zq4Xj@ubrAMT!WMzC+UtfNxCz2!mn#f1aWN%m#HgS2)I6qm5r;wb5D3KEqEImAI$%e z2b*zU&Ci18|?F31(XKMv$Ne@vGB9WY_9urV5 zxC&!~4Y!N}4+nmX%A^bHScdd{eQMw0(z}+`AvE+}(J_WF*C?a}*VfEvqSX4|Q^X-RkgUb;5?+|-uf_ghC zfhIeHU_ya>QMYK*#~2ako7VHeTuA+`Ak# z{Pin0TK7^Sep|xg14pO^<^|F=EK(qPAnx4Zte0ibVj&KN2fG^`?Eq$fMY`lSQ%20|8jm@9>5(LuKh0^3snx4xRZM4bwAo z^EtSkF>bQE5H6~B7O8C-?odv>LZf%Pjm6@d2zO_&T~XWfb_O4D=W{wClBSB|mU?ZVuBY_eaKZzscnW+R0PzYIVCU4SjE>Pv zs1$fu3RS`OP%2Q{@<2s~!PO+)UH8=yY~Zn```m3LZr~XW86qeXA8#0RFbwqgx=Iuj zT=|1hKd1^2IglYU1YquM3cl5D9h@9(HLG%V0YJ!pkxV;D{6%eS2uT7Y;`0<0U&nNi z$GTS&%`G|Z=ms6s?ZR@+&@lF`*%~GUuz^wg;Hi*o5JgkkSc0ySzSH@o?_lVc8rrT% zdW?zWBkq$0!pBeEl+9bGoo$Z}TR&stlP|>T#ohBfQYdryyn<3|&y;(_tJYqmMFMQ_ z+LlV&T@*YHlP40-#P6kSPauUYPS##Md$GIqngVK4I4$|QPMk0tPJ`sc*D8-$vv6K7 ztu0k3|Jv>n@XfU?OqhA@jD`8c8J_aanGxvgT1A?$QCq7e$x9|#0IbO`h@3XcsN#i< zS9|AKYoiE%APFDWJPuTNrMpAYi&lOwi8ctSWKTp9dpR-P9nufGgjXC*#~sX`AZ$Wg zlHqYU98D)N#|oBFI%lRB2|*j+=h`+%DejB&4cVPffY%hnZh%hs@2g#Xl8JMiBD|i5 z<2dISR>IEfDDH$WpU>U{Fl9N3A^Z4{<#2r|wnD5XFz=j6PQT6qwSCa4#gl8~I0#Cg z@^Vx3AsI`G>dhMLitfpzIA*6$}3o=(R5PjkgNB&;RyiVuQmkGg9p09 zoOCIOB%P&4Rah^x5N?9>wQ^+S#YtPdGYtQxBNM5Yk^>rI$ zIvA-%NjgyNxx}bt0iT&Qh|Q%K_EsTbV{J-PvWr$E5}pOJajk z6E{jpA=2oS-r&Glow<~pGJW{<)vs$H$ba~-9)DPq=c@Y9D|z?cl#)sTdcCCABO;XqqtCmJVq-CFT?9}TF7!7!=`8GT$!EEy6EFl1+@ zbbiLi>mQk$gwpBz!E`bPM*Ca9mN&4rbS``}WTzb&8rBds&=_F1k?A~17_|R4ru7Lm zr&@?5?w9HN(&+=__)DiB_~&#3nfgxE=Klt#PM0Jqg zOE@cZwUr#`X^^(bvDFxR`2t95wKYP04VbK@gkdI2`cM2fR|hIb|H-J>JR%cz+6n27 z`-*VP9Rm+!^--%Six`1VQLkYf`j=KZN29MVz52EB8unccdcgmd8cW5JI{g5+-^(e{ zXuyUIvfYqnE{M|#eXZMP*9K8C1h5<6nL%y*YN34EIJJ<5=VIe`V#%;SBZVS8zr&x8 z_=gH(A;!PHbnEQ51YEfZBpqVcVFUTD^oFHF6X_Newd+D6WHZtp@#xaZi`nWP8>^e_ zNP+c=P(VALo}*J+5^kcADTe3N8+9jD`@cm(B4d0PLL;@#NX#M4A5ZJJmcIV*ftqk% zZK^`OUf>M_h_9~AO3?vb7bRI5y=;Y2z^b?L>Q}6G=|iJl|Ih>G+z6SPpM zEZ8N)9CE+r)zV0&qcPZrY#`$}S*h&kva7$P)7^G^_o+Wo)phBQySP^aSt&dVVGDb` z=B3bZ@e*W(Sc>}80{a4pMUk1KKNg9OY~+TDcz0dPnOtPUyd!8y%j*H1O*h%f3Jv4# zA(BBZ`HwYuBvdxFB#3M)UB962_RM-7Qv5p$59t9tvbY=WLubC9QEN_L=3;VF@3>{> zcT&Sb(xxCQms>D}%B(%bGo0P`X_{IaLP|3wcJ^T_ySvLJL`-%E3Sdg64U=21{-;wgALc*;JOW*yt*~4r0%<4<1p6BXq?yg={lhtGmur8 ze}=bSy8gr;M-i<2<0^)SC#zGkEq=E1a<93jkAOOFVK1nKUp^b`qWxHKsjdSbge*4i zT&+J|=JSXIZW~K)tgBRN90bD+PedC1VWZ?VtW2z~!)4_iYW<$zCp@BSjPNDunCEbK z9+{VZ)WHjr`W5YZ>AA!VhA*-eM3H`4I4!1-I4u~tMz$OUy4<#8Va9`*Y0q^K;}T^M zUHY)3@x(`sCO#)v;+r5zi`%WG=$|)__ILK5ucgt26-b+$_l9U)i)2u%S=gdN0LAKA zV)y5Pyt@AJ236EtO;ipQ;RYstV7m7~QJx<3)A;D@YwK!Z@2s<7uA2me@nC}et2wJiG4 zalBX5h}>P@xHf?a`pU2UwpshX_G|sHT>Ja$r6-NA&b;`;lhh99$p<}MlWow4b!e{# zBW5r3Pafng{SPu(h4-eiORC8(wgHrhpUtOa+2ha2yHlB+C3$zCq_eqcCac>*{pLV& zv)Cz_3bR@5RFhqnMb0HJ=A*1z{83)`V=-qIdj+lj?b_^@sOhwjYy>s)MMpen4M0jS z*H-5TddG$AMys89J66wg4!6??r_+$tiv{rSNYc?XIYlouQtScN9YGti72d2{YH= z$P31G2A+!d(U^e`{p0C45cQm7xb=GUr(lNb8T2O`PTD#XTbL#6NEj6DN-|2QqqPgu zD2Z6A(+zpzO^o+;;pAJgfBQ75m!pRl8JU}pTqN~2>Oy^zm5f|tDXT*RAvjSl;WZoN z0ws5D+m=A3EHB`5FRigkF8qG7(n@PayWzPr4C#t~m|>N;koq&BlNd;_bKwtrvuS^3 zW~~ObY&X+XB*})5l6F{4JoWBCuq0_C}1j=%7J6du9#OidAaAL9$fI`aV=3U zla-ZmNnw)Hh`b@SX)%?ozELZ0(pOq}l<1})<|GY{t{4a`tD!aDQW{#5erpYFszjcK zHYdwm5Vz6LCJp$n)X+9)9BUWp(f8zL^x9Ts0WK9>1)ZsL_+q?g%;Hry6d{gf9R{S= zO;;IY`)@$Z^(wTvx7|E!A0M4Gc_Av$JzCgIO|Xou}Yp(f*8G(ASTHTZBqRL zLaN+0TDg9mu(E@$qr(%JX0489&!pcbK>}S#Vz1Jz#fg~f z_(K{X60v&bh*Mh)D?pMiwlfI6+}`D#>;wcixdh zkPfjuX!X2~4aTEi;Jjq3j#dPG$yph}5{N`&@q8SNO4`ne4Gh>4UMzNp=tO4CsSO=Y z)kfn8O_Kx)oikXN64CfwRG|%nONJPs{qP7oopKX0=t={W`1QZB`n>^S^SDNz0ttddfYLZ?Ypf?TI2Bk{1J{Ibhz~J4aOoOH^C@ z6|%PjOdyUeAjtFq%Nqt^d^L&dr#DDmC8k9Nn{1uq#;=^DHdF(5%ilBgF#gGInKRLT z%V~*)o&(fMpAXr}m=B%Wnt{!(|MDOMOT<-b8uRs?I9z=@99Pu|T`Mvdz|q2LDD$=x zjf3?>txr%+oElGN)btFkfsiM_3Jhxl?5+XwbfT?;=!QgaP3xqzu`6sD$4Gz_%iOsY zvAqh%#I(`yuT3_5`dNJ4TVqv3;|8k29Vis(5VGSxgWlb-H$k};;v72%!L9($+ zg!`&H9Sp8ZbO|yiA8iulM+@$jS2U2xwcXvPd*)*}3wh@=GDxCPo$H%V&2Y~r>lXcX z&U^uNUq26q)7XwXJ>wiHObe%0#$tdb?J?&sl##f9xcsT*uqn#t`dLLHDemlwx*pT{SQ++-D}Vp{<0}6Bj{g3Q{{FoR!tU}i{avBI59#kC z`ulB_;JE)F{V{$0j{g2lJsSg=x1#gOB~tk_ya7RujH+s9*r^kQpU2?@wh!2)&!aKS z9N^rO-@@Ko5XuRU$Aa>)X(Qf1fQg5s{e1sKcQH53O2B;Qh(Ig|tgGv2N{(G%2tqVr zJVTWh&?C&CMug5TVK0qd$RLU20Wk*{4`RKwL-xUhvt`iK=Qw;f#!L;}y z@klzW3)W@Vp(N}#Oo!;4ot$ZiRTNFiFnoaaSolB%@5(8(PB108;hW@bN^CiUt4=`K zwSs>(+BlBD5wK^hK1m45PdeMjyPCbRKR~=>{?L6)1QC<9(L{tTYZ$5o8zn9+8YI9? zC!^ypqTvVucxUTmck@Uco*W$>w3_6&E|89xLt>LR& z8%5_;K8}O;q5W0Ab0w@(Vr3DXAXGz&_a zlLAMX864`7u1C~#9ic%3t$P>`f$tsZr+gfcGY-&Hg!U&s-Dn}-0Qhc9gq7JR@wd8TAe;2e?u9K{-p^ohXXo)AFR3xAL#-Ss95L))aKUvpje z>iYzQ#tt6X@Gi6NwVK--=mi>n+3i7>OI!r~5t5Sf-$&@tvxB$ph7%HGfHwk})5Us} zaLX$dBX8o}ZIDIk9=f~UD4Z5Cpbl)iR$!<1ve76oex#am5TrZzfTMli9;5CMZume2 zhpKthWHn_lu5)}I%F#4gpzws4mE8O{nV*@=&yvhfTiZ3HiM>`$o6`10D@%H5D7U{y zh4%MsG6D&loIRkBfaNi|1fu;G(8kz6R0JOk!SYrc(76f+(}DPm;q_6Zah$SO=oY>W zA8|^W7X)&^VPS})vT>&>52Nvb2BZ)bDs>O%!qtRK9{CZ=HR-5;H0CqPV$t9#prZVX z{xI(U*Ppfhn1 zE)M;VQI&K7dLhrDu%AKo1fM=~dMNM~Xz<+WyKk}x{jy$Sad23F6F4n=k3een2jbwGY(A`)`wXeBqq z6yAkRf=t1nxe=$R5;sZnBngE8jov(>Y@0_WFqORXi?AK;C~|-^!pUc3EDB-8d|aV}va6siQRsQuuwHs* z%#8cx`f|zOfQKa7^Q(=D8&MAiSW zV!aV=$t(3cb|IaF4#Uxu%=v`_b=5ZP>7KFkX3goiCel81)Im$Vtefa@1YEz^pxLrW zF+E@c8AO}u?f~QXb0UA>;|v_nVKlTPOh-J7a|#*;v17pm9uQK$+il>b+Ms{Vf*Vs1 z%0qtVqIRIp!Xb~31BasD@$!dH^C3Nc1W+dP0IHSc`T&DKe7~c*j;WWxef)^zp1x^L zj_l&2@B(B+!VCX0ty?>b>zs1+m?S1Edfx_zLNV`p7AC6FNCnnm8wdD75s*m%xi{}# zeZ91swJR^$6V;dZf!x^X5P5j^90%G{QgStfBIh9k)6@QPjF-5_##b4;okN93M5xel z`dfuYNcA}p_z0`npE-1vk$%Z131CprjFL4C7!oPg6V2j>se}|T-{`c?jiM+taLhi| ze)CvWN@FZZwEu^_AvBT`+W59nwBK?l1a?K(HSBmmw;#mE=}?Ee-Y8lxIS^7Molw~u zMdy`59N=h5n&OaGs2*T1?WAvl9YqaqC|G1n*{G&}SQSLjwlQqZ;aD$Dw;P>lJjsvp05I0 zAt#wpL{5jKL~-%KZ>bY_qnG9jxzcM!a-9X=h^sf$kR$QtOS>6~oTImqXv$nhlZ#U^ ziBU#CsoOE%WNTsGJytmvtfWF!^v;Mqh5glz1<%KRkK6{Z4Y`EpL(8N4>?r3Vx*XQ+ z_@8!lWE$q~*p0T6BSAV-S2mrNF3JRq#1Ep2%BD%b;U1ty9E24(_FQ%OS$$>{JSMCe zAF-aJ>2T3Hvf=ccTC$(*F6;JTS1`m`X%v{SO{K)Pq!`5*C+Cy~vJ{~)o&gDDh7=e| z%ZJ5UMOws(GjwkOT~v{Il~`KJEo-3{7p_Tv+F@nQo>3=w&KHxa`HpZfJ*imFXTjcO z1>Ej-?i}Ro`FrAYTttJJohVu{5IU!RPaJoghaGEQE4x~qAj{K)g&*GC>XQJS@DGXW z+JRnu&fDQFdnZgfc+}}c=jTe|+p6>Fki4Zrn^RG5^wSl#^^5 z?Yei_&j)=;ykS#y|ck4l)8=kE`x9!4yOHyKMbO2+`l#l(zOol1Zt61&Hf{a5!-1;*6uVD5;$L9 zj%Jj#e#h;an^gEL@&S=JaW*A2zn*Rwv$;Y7TQ+lANTU=|p;4FAC8Dr>Y|tk1ls=Vm z>9d5~Jh>ys_<(fO53W$&VFnV{XGTpH;XeOkZWYF5u&Wl7brr^yw-&OmtIrC^Ocl@g zW_PzUxjWHF49aL?;kaTTloST_{4mcB>u|o<9(i-v*R0Lb%&4vz?&f@T{Qo9uk!-cJ z%EMMj8z<+=O>;xX<|C5c!_DI4nYuC@+~M9i(P*7aR{Gppje?x_XE`FTp451*n?ceF zeM{9_?>Rwm?JOw-EqTmwHewEu0b6aLZp98~!cN|48^e6xpYQ~YGu()Qn#+eq$HD?7 ztu6K3aOB*>IUn3=gCQ`(4k^L1wbZlG%vs@-PEBA&iEMgWZ|X% zJxfi^Rzpmh)rjkW+{(+Y0_5G;(F>B1PtIvB9$!bU2C+|^DjWiv2`B9_E9IP5n-OX4 z3Nb;FO%j_q-5~4=w7R#ZizRf^4gys*X>T#CWwaaH*bT9quSc}M#2X+a0$$6T1(zd7TF!H#(+j{m)Iw7s) z0g6I#VeT}anOlis{5N9T0JkbKOVnbYRO6&&s-OYpHj+l`N-HbG#?b+mN^^ue65ut3g|)}AlyCq! zcDFgHkF+V*6BFyl-9GtM7ll4CGg8`;ep_}{XMtwZB&vJ&lSrRww8(e*NH$hxysRYB z^k%ZSX#&MAZpt|Y%#_PHd0^>}PJD;js@>U5+Jd3Im6+SbhPTZ6sBI#f``a0dNU`@% zt~rZk9bfbH!>fl&73+Gy>5TgUbdfWO>5I2HbwuCf!tQgj`RMndKUa-;i=wC}Sd`A( zFy3%g?rG@z7+VLsyUnfRHVRcO3`HG|BMug=`EXUozM&cc(0iY>?`)tkJwGS)=OB6; zSfQL=VkBk@vRuaaYD2w*Cvzvm$%8J!nf18o7)VKXCH9tmft;@buww>)dWBTqFxLYL zbi>?)$!7X6n``WJedUbev_?a<{lCu-4^=Oi@bv~JsdIgko6mX%;T5EA9W{2J(frwc zR->EAY)7V4D@0c`SQ2el$h$O+H#)?>!nlEW-!YtsZA<@}qe+h^F+;#PO2G9Ngm9DY zXG~CTWDbq`7et5e@LpbA(=q`|J~k$TRYQ&!5o&}{k>!SzeHVmRU84iVE(&P%!axU& zcX)4?d$iyZrnuqw@IjTe+Y$Xq-;1dvq<#{H{}`4T8^Lmgq84(Se_#1%d@iH=M>}Vmf#OA@m9HC1AB(@Qek>&3 zJ=DzH4|O)00Uu2l0ht7*k32U?uyPV@1n%EoYJ4nMz;v}h-!9;}oe$*95$K)DagI2B zM2thWwwmm4jRCHWcY>52xHYxFaC+|jotcB1JG807GX~nt#P>_b0iGtXKvpQ`3|WDS z>CRX)Ei%%JZq7{bF7(v!A^07<9*aZ3$DSn2ffV-^&o1NZVdnxkI$aW@#lprBmq9%` z8gQM~jNtq{>|lU|Cq4$&;51Z~12y~*cuheyq4uw-M`woabmW5lZ@E@wE<*$gyjcDM*M z!#X3YONdBR)#db ziAlZ9n*lORkJ;UZkJ&0RT1n$&h+xWh-@@wjZGE-A@+i@W0l5@^fBALsmyb~MSPlws z6AqJ4al3!PjTeK6Vtv?^gi)hFn5gsb4cY7>f{y62&c@_oe;jo^fCfE1f;iA~KIW$1 z$6^0iSh(ER1){!>7Og}h+-3mDd+w{lj!h~)Z6G0ky|MH$`xV_!Awe!}*j4nSRed1h zB?&VpP`w{jl7dN#R=$QWAM3^6**yQFnL`!28=F($W9}MsMeH9WWPnqP#x;($;#uG9 zrc;W8#L`E=!-5AADC#=#FG|0i8s4F+*M%JUs|}G-48(F-6_-?{V)qwp0r>s}ZX}P7 zcJ`ms{2;T930@2o?drw#2qaXg2us=3zYL}RUTS+u?d{gUP)xmHz{=dV}75myaItZRuP!{)7_ zKxsj{9Hf8txWr%oii7p_*9Cb!B?r-~A5V*r_QqnQpShk?9SJAK5@Kz;<_)gNw=UjZ zqXnjf_uWp*HHubzTG`-0#_R7&PEK5GC@1IJXf#TnvZ~D^>lA`Ct#g*X+k!ynes6BO zKxP)Ud9`3Z2lOW_cC+h2FEI62zt%B`G^~Z_Q0+4Y&r`B{5Bhx_2J9}111b96m$1#KP2;4WHg`{&dg;Ri)MB{@ z5I=1m>AvMM(q;}IP+a+DSmAunW0sS7P=PieK{kF}}P6@5OtO4Ch$lx^kAzWFTnl^XgVZDXnH`4V=P zv+MeEZ7pYxsFpbvqJUgvJR>VA3OcP9};cH zC6zOd*-*Hjy7nU$#N7+I7@VIK4+pLhy);&!IuBO+aBf6pigSuRZ_rdU7f zRke6FBx5e^BD#+1l_|N^a1vNL$Au@lWGBWrfyfam>#{QyAczy(KTW1Xpwa$ym5eqI zTH=Hkoyb;|@lB0I==S{t-Qtox6gdO9kMv=hL#8G!VwcgdM4Z_dd6Bz}0t~Dp#&|}~ z9=i}cI?laDomB_81H}?-aZnxLB<%5(&e+W{2p+Kqu&wT3Om8#*?ME@YgGzc5qtr~a zA6jE7S{?@#Yy$2k$dL|rlop0{1U}m_LviK;6uUIxPN6C z!7}VE!d8?y1X=T9z+-*3j+6-mIql#&v9Ts890H9o!sEFZ&3pw`j4Ync=}|j2(xcPtyKAln_yg$96(*4%rBb0wEf_)NfYgi2G`f| zv@?+q7DWeLD;yr3ub|nq;~XDyPlqtYq8^z8;t6X^$0jlwq8MeBF?(vHK+Z7C!^n*C z;?YFyO0`0o!y4wGb3^>k1z};tPIT?>-5Tpz80he2w+6J8xW~t_Uz-IuFW*8H)f5Ie ztqp?V6dA=}G+9%nBBr%5tu(9R+mu@n5hh_V#8|`0T+%TRIc*Lyw=26KLNEg{npZcT z+5PD}SV6+Y5U+dZ6DmG?ZeN~_TjDCKKv|g zAKs?z!`rm|-Dhe0yIZyW-Dhe0yW6z=T~6B<;H4vf90w*+#vF#4lQEa8@*eDy`!UjXyX&aw%H|K7n`_Z=BM5Z74PufL0by>P zGfQCo|MS14pI)XXH7wp2^PE5i%gjdPG&Ctw#Idg@$c{G{E;C;M9+WX8K+`+WZZo#*Vj znqrOm{V?|B8vX(x4##-d8ki<{n_KO}qvlcbpXFDp^~c}6u3*Z}{?2iklohWsv*>k| zKMWqVgZMf|BiFe6s@@Qj?1m0=6<@rr=)A+|Eb3lA8Ag|MH!d3YxE`&xINI9YIV!(0 zb{H3;L5R&=2CVjqKcvDqVQ zVtov+>*EET@8x2B@H3*uZH(NkSyN7MIC@-5!4Xcf)k5cczhAKH06Fh{1vANKfQI_&Wo5m9cM;o@k=kyeINJUl$k5&zSW zL_??TOZe>2@4WSUd7$_@l2%CSSVSeKxus0Gq_u@&Swf3iJ*hsB-T2tVuWg*37K@GE zdP!9ZFdQ`TDad9y={W4~;_owh{3A}IJW3Nb%c`K;lbKU&gYP-nqbdikcyCB-1w;?U zQ_dnaW?y$AvZaD5EWNJ2f_Ck-pj}5t2f+Rug%@f1?fX_7We7EL24>0BZIQ0-8STto z@XS(fI%Af6(>aowQ$y)wy>z5>L9}u!fiNx(1Fb61ymxw$#_Qq@4eb#8)wb8e?(DmSc$d_9jMo9EGLLUju+ zV6FiUnqcXOyd0;iDmHc!9i4omnAOY~%2%mVh_#evUQ^5xw4FNq6NGn8CT6cEQu2Q+3=S+-JCw8>hG$XXFy_h%bU0v)rO;@~+(0E7*& zJhr#m2g#S0FKHVNn^#m0n{?bGw_D9)`uL)`^&=&>WI&%EHjkd^A?cxmC!8;>_RcfO zz~%+N!M1?1njucfx+2}82Q?*N@&FZz?m(Ku0S)%>$LEYTKCqZsmgR<$cbhM*=?q=5 zOQ8;tj0&|~RXbF_@i-?%e%ZuMv&;Nqm4U|fRc(|MTWF}ZXyB2nQ+!ek#(II#$i_5c ztZad$Y=-!=D>d?wDIvc;m zU!7HQPNIG;_#R#u7zELI*N1)kTfAj54tl6hLvezK0eTd-+jplHtR%RaRE@>7s2T0m z!cgq<=J9d!<#FD?^Q1B4qGu7>4NcloN&BKZCbL4O%yo4(4*a*Nd5i`)Weo_`PJ@sx z239TMiIzHT(v1BOf{>U$&$T_0i-pZRxEa(*Fj-5aCpT)_ zKR!L#+1+mMAGG&(Teb{&U(BS{_gVaZpvK;D$Ym#!3^_}G4@CZR#DrX?$>j~l#M{5w zFSw}M-7F-ub#l~dw%RcBbay1*1Tj4HZ0WD~j5i%O&`9)YtB|B_nBqB<$V)ZDYsfFK z9i5U+xXh%$lYX!VB|$%jkadHSZc8m(NohxGlPYjif2YOOw6aIr`_mH0W%XL1%83mU z4|{_Kz2Yc*2r5qb*tLUf+f#S7888RrbOuc>)tZf)ys#Y-?}8ySkDT7<+)#d`g8 zhf{(7%KoO)sL#{g*~xK7{*r1|4v+aXmZBFc;U+BS_xO-}2J?WecOKW!$qu`q4IPOL zdk5PmyG@(&pn#)8oxJ^~wpw3SJ$4;H&wx^|4;bQ$of*3ZRRFHq;6@^`QD2BUo*)1C zjonubI{>ClE4?|if(SE_%o%WvV$MkSKL1F+n>*6)CV2xbska{Icaul<82xjyg%{WU zIe9(};qSv1ySGV??z;)I7OHX(bvBaP7a4J@2@4JQKaU^XYP{dg8ExO*WhhzEw^!$AS0G#7VCiIMw4ibAr#tBNbK^}h(Ye5A zs9Me3@P%C=?1SH!^@DDYTWTZ%Mc7*lN7Sjocq{mImxH9rwITwVza-#BaxW#hV~=7l zE;!}wep!eDpx|u>IyJcY6I&<|=QRzF6x4~Sx&H2sbNw(FCub!bLf*Q2ZqprB(1v~S z(I&6asJLyq`4cZP`V8HOmakRCf!51{n-8t$f^(q_7KJvL2W_}0wBbBx?-qsjE)DGu zP)3tI(A!~jsV?z+BB21lgegkM@>Sj)7>hwD`$QY(nle1+)vP-t>7qSdc2?2B%%X#v ziVkNM9o|&*-OQrztfF^VSwo5Me$@?qyqs$8GP6Gb?PMsAG34G!F$RR>P)(rPrzq}+ z#hFAam`q2;xDF?_u^u3@#nXl@^a_2vbFjZDy1G}G(zZ{W=Uk`4F_;NsFdN9=_E3hi zp$u;ir8gT&@AgpM&4%*s_E7YQrT{skZ9`gU%%6+homi@pHR%X%IE#gp-0yI&&?ow6 z#%Sh+iQC)9f`l>Z`{8hLt?ILINXlKy?i5|1x5}@m?mZx7^307dDBw1-DdE8H1$iHI z_vU=!j&VOEHoG&DNgFle+hE?u;k=K%c^}`oA9>X}I5|E%IVOPx7%`4&9!sTB6%qx{B^=2{hJZ70la~hI+@6r<7=46yD{0-~fjnyVs z9&f1DTv(i4ZSK;L4{dPUY6mx0JG_0h!`oInyt&$Ux3BiyZL59fR-2}`)Wx=0n5FKu z&8>0a`(`(^Ah|4-*M!+uyCCnMeIMnoe_!_B?E7C^2Zz7x>_7hubZt6b;Pm2+^=Q;6N^H?a7x1cJY#ldK-*~ zLEq!32Wm170`Y62$lVq2GVT5;I{WnFE?1Rz$&(fGaJhiXRC3AzDV^E~wf zU3oywiUj{4S5;`P30XrE&Jc|@1ulB~Ifr5N*-eUI1%L>PVJG0|Y_V$NCABs-6xiLg zkIwd8VEwQY4C6qRLlAve$*l{*dB0j;MJKcGAJ(t%7kAA86s=U%blAt+Z^0GDIt$S; zvlTdJ!fqlx`^FBNd#ZO+Y#$fHQs@+v?cP(pOK~F6mf_k%_pf6zB4THe(l_MZ*(sx} z5y=ci7<+MmquYVeB5$d~XjpR#;-w)Prg+-9s5)K4zH?zOfEps%4a}n;^2Icoo`EcW zp&i@-N^(o3N+H1fKDl3VkW>kh8U1k(KUJ>!=VVqgK#oo4^SPzkb1Nm zqM6tkMv{WOXMoKBKjNr!zlO1)iEh*(ueKcHha9Vtr#>QF8X9zqOr3p?yXbHn_yg24 zc}g6*5hOll7y#x#iP9PPUpK&eRE!~7SS$b1zgE{ktll~FTo<`g#DWhYFTP#FNnNR@ z9BOFn$CIjwZNTv@`sxq~v*YbbL(ta}ku6u%oBGhb6Brt-O3kYZzj+$xT21@Xit(;1 znVIY6;4N7kY;yW0PB*78YhrO_?765Zjhak3^3sL37?}~paV-Y>J%mYAQ{zsv$LtywDN0 zBOa(tAPIv)2l0hhA{clI$DSSOgo})cOb=@*yM7=vXc4h2a4Cig482@}(Xc#Ok4hNfe98fhnOsPviw-}r5}Q4- zgGBO3iHsVSd+f^zJAu``;*Ie0gj`|<#9I>|2^1?6x#O5yjE+c!9B^f%Fd)?FX5|bi zig`DDA9knYZZlaGU7)U^zTm)1fvb7_6jM?K6BaiWkp zwdow8b&sj7!_vTcgwkH!`~Ti7FT>a4=FwhDZSHR?bI#FH&kl~1XdtR;dj~K2Jw3rs zlyUE1d*|8C)+Qz(^2>D&0+Ays2{}?{Lkn1rp*Rr|Vv?^~$DWT}gKIDOOYSD#gEiZM zO%^ULv41V1Er!TD3oKUN^^&a#_o0@P^TmrgcYEQG@hgDz96-laJ(5`r`m`)qZ9wd0 zPoxUe6uyZm(?~<}1_7*dDhN$%pTh(O!Ua^r_dZ^)<_=-xlLq(w%Qc?UA>YRKaprN} zPU4O`4OyXij%>a_1n~p`vxmSIAb+<>#u&|*wYjTZanp!-I;t58q%VLo0wX{#)>Tsg zDKS>*y>X zMAEM)Sk0OjP9sT}M8Pw?(G_x7XBJCR*>nSI`_uYVW#VaDQigw zuNmq%8RDhb=x(HlX9?@1UJ1{s!VYcR`5~T!6Iu~fhR{4+a~as630we!j;=z`)o=jv zIWaD1XAZ`dx|al=5+WN<1GyZD7j(_KV;YIhqKRFt)LDq3FtRspShcJsU`nwq$KdeV z!ZnJ`7?pO2I+<=b1wl;QrX=#Ohg~xYJ5vt1Mssn*yqsK8Ykdbcf@B0i($3{2Gfg;; zG@{e@!vRJ@J2xx;x_TP~Bb*XQ0V3UbTrAcr7Ro=QkFhx+@BCQp6!U%Lb84Fb?O`4g zB9r~0B?!1(M-F13DVniKJ)Vz&S4D11a>G!WQR1Br39rWdd~|UgW7rO%Yo5${yT&!K zfOjoWe328yF$c?hMm)0QFI;r5^v+xh%|tn?3FU}uZ7g4Ey4a~Oi=KwaEz3E^?BI^%Jc z!GmZMJHUXo`U^ToW|nMiC4@6;Kyd>$B;~GI)+sIKrOsAgy8}xws2qvi(Ro#(eI=3- z`dH#xeC!2H&m0dB=fb#apdbOwk_7b9FY!k!T68yEuNV3u&=tv*Ak}u`BpwL`IPk?Q ziZq@>B3gSw?n-p7>;Xt}ISqVXIotxoI0jpO)a@Tqj$~$1C zf^Gj}=#}bBrUz|Cy%1#q_)hxzI1t4Pb&xM%+C&(dIW?=aE=lYIm;-TyN7dKtpR7wl zi!FCxX5$45D~Ltj8$chw$9>oYXM#Nkd1O)Ip($ELJr?PzlXgb1v>EhiDy0|_={x*5 zRW&M|rxR1aOA%d+_ks;rJRL#SLwihSG3E%(UR1pFqC$+-7C2?mViY<8;vOZj2`yAO#SztO$U7>k3Bc zf;J9GRkXeFf~#QM5eIEbG))no97O%x&bBsC(HO+JzIdw=`pXjqpv^l&+**WuxHCXb z=l6QpOB$@~dAJ>PQ#l8amzK4NK}xv6nUY8a-+lEy>Q7Ore-69ecoK~Brm2~{8=T}hUVe}>%fzMO(c=!tiN7M z&$t!BVO0)dX9!Wi3{YhzbBa|O&;yD5wAsN+7bvcTlSJ~xw0=Nq-I#UCv=9zpW`G1$ z!^ND;t4V-LHX-`hT+dodsW3+p1AiO>{ZF-GC{YsPqQlbII&@*x zNMzZT`DQ+m$X%6_c#^DPj~!rK64bwOyRHL&9J5PFy{#Yti5S9lRRnU8poVyy#R}*l zALx-_Bqv;Yhk&bJFxIlRbev7ERa%9)?+HS>$E`IwJvh!dkl@D)@a@K6cK>rr?l1K)a>2#(AX&baqMbRmltdwYML zFcsE_O~l@#^d24>~NOn4Y4np$^fMv>la@T^UX-% znJd)p+k%4?^iE;CJY2=edc*fHk{*tDpoQ6Lraks_p(8$AHAEkWr+IWZXjDB$sI`lg zaof)7LV=87<~i^$j#DL>2?PIMBmoS7qDeX}>nm_oV>d%GA+qs`w9vx{TD)nEuj2`b zZlq*F#_P5pcS^A_86liaRi23LzRXbe^5yg%Eb`|WX~BYyB9=7+@U%wsWJKr~pU&rS zPTC+tLZb6gG*JVosYR;Qr4)+mz?u=u6o3r%X>pr`QH~MVfh_>a`LUNLRytgg%!Z6j zljiNAoS3tcb1;HUlVwz50ZFNgtj@qw1En4%G6VZVMMV&+YpNKywXfw@TWWD+36Cii zsW-S9p(2+yP_oo(c5aC(c$$d{CX7@$@ho?}(ah>+*N*%X&y|=4>8!|&Qj4odhy&@I zd*-0!nR%!?7)5A06f(?}byn0F`k0-D7gq=^p;InEd9`j%_E6>-}2Du?VY{bM3Nj$QhTsCM5UxYoF>u{a|>d&ruiro z6N%#)W)HXcthRNJaz&*FEPTempgw34r_Vmv_6B#nzTTCM>5%RsJPXC6Y~Q~$r}wf^ z%(jQ&j49Y=6-{6mA#(L+3)m^;eOVNYGnMQWR_@?|W5-Yp*YAr`*BRpp39#fidf4@} znb9H#dyKI`-%E93YKtSL4v*`6jzYnTSwNX5>fg}fiEY%7nm|JQxJA~pQL{8pA0*2c zwiMw>?CKJ&1AdJc%x>aE6FkliW*mlU6AEEZ6jq$&-1F&}&Z``Q6WN0$O7)U5n@wS^ z!T^Y_gD&}G$B2vWOcDzfiJ=^zEZE_Yk$MKok&?xZsU4{u*>`odbIuDpsZ%Hlwww&$ zA^^Mge@(kR(&e#`V(m`(%-I7;6jz);XF8Yh)aM7NuTf<_Z61VTTPWw%FkPoXT&a2% z6_PMa{YZp>v{M%Q7mjI(Sb^k65(#XVb;Sv%uIP1oNbZe06Or^y6{$H=<>NM<%eY*i z@)PSdOXKXaY;qy?Pgva6=|>`sW9W$($SV#9(>_eofDeoK00Y*Lp2(F6*Z1sW8_QZR zfUzX?yH!k<{>&hv=&cEJ#@v%*|Ey(_uSeHd&zL*zY$K}1(KT!nu4`mcU`=jIPSCXg z^JB3$A~T%G9I(j|3rBkGU$ffYyumh-qzY&UH<36GZ7js(Q}NAv-MwcK#%-R6BFbLp z^mSU81Hh5TxM&%55DoGi^jU_p4t+8TsSsUv^-+@M%`jTh4S7-qiJh`XAQF4?PB`vN z2QhJN=5S|zKVjj44c@Xu^;jvX&r@_J>sTUXxhe*fLna~5t`<*FcN~@5XgVeimZNin zk(tW+Om95vE$fpwF{|JRwUcYno{_pv8|sO!jui*tDQZ|Wa&<(+Ro&aY-cD3SFHJ)VHGi@UN zR@aAXX+1?ltX@+bD~v7k2|PZ~#-X$^B2NvnJ3YHr7WJQ9CnsC>KAm}VB93HiiI6MO z)+=`K$Zi9Oqx;=1>mB%}iRuNIeRM%5=uQ(YqZe4$_$wgO(#5zIQKu~a|-uXl!gIE8*yt1d4FAwPl{j7KCfF?0(>nCBQ9Srm+N{D`rT za@EOyuahOrOjC61DQ$f*4&H|`hsnkvN26xB84`Q?YDm6GI?Dhk#o}~A54lRUux&OB znmkCDu)>GP+$m&7I3}}ot!BboEV=|=k3bAT?nKiCD9{Zi80i^VJR2NQ6~=;+k2&xL z6S8d*uJz>>=or+mqP`J_5XN{4jYhtxa}1}0vtXRqhw8mCX>-nLx1P$I*+?*}v<&KG zr7a-yMnf%g*``oUc5$?1Ya5M3d2T6CU4dE~iRlwUbAM;7tp=Q`tm{N#ribL<<&Z#q~&~F1ox)-*yP>GVAG}Lx)vU_4XQOeNLI+$pO7sa^IzKv zHJ0-`X9lN)YNj+gBQ^o-ll8$98+sJqlby7PhGrG8uJk2r?uMRERX1zCuG1BcXb|8e zi#=KojFK@n7SD1`0~aysckNLhNWPokf+pj=$nVqarnxtMugQ+Z0*drbGzH}oB>*Mq z8$Qmx8HN-MBC}`5n?G#Z&;gs88YxAVl zRL3ux3SDF!ZSJX^mbQxBR?m)_O?B{0ZN1n$dfu#JzN04QuwkK%tOWpa9ngF8<#BWW zSRFQx_I8es0ov1F)aKzK0LPdbYIpNz=*{NKt>)pe`uRn3-#b9?KkooOt>aBBu(Pjz zKH53n*?&#|(Gd4&=lP3c_2OU`9r>aWZUbtkg6eSd=y<2u@&J#YcDCI{6*gOdc0v8T zbNu4qmx1qk~G z$IwsEGQjirfVxKK)zASMfbZ=!kD&kdk2jz0?CwC7XgU0B=Xf8gAp7D?#(e8!cM}?M za&&mmYNGxIyAXgthac^p4=oi&$9{selh5g_i zH4is;p!?BA`sfIu9PBf1S*_#X0hKg=LK-;P-^JD*HUD`6?a848gt7S?s0};Q8h7vK z9jF{fC_VU9Dgqyp!T$xw=s@jl{=$aYzX*8%n#OY5r3xU5ggQ5$9$+6l1$=f0EkFc2 z1czvQb8qu`vsLvB5m41)OkP#3!{*iwKEQV%Js9gl6PRo}`!pyXwwGq}&e67>Pt?!q+2+pf$x(*JpymVULIg>)W(GtPS*ubd8c;jW zpsKAGGJ49HwZEtrFceRlkZp7Oryb-xT#pBHp|vA@av%_-AM5%WEX)$lpJTv}w*Q#r z1)E82(r%PBtjDzeL*g&UaQ8vjkyS263YL|z3kz#M8o}Z$(okYYY29xVD?M2(dvyOJ zo_MeaVKvz_HtP>>?PSM|TLx4nkWTsnw-_w+u$?=tLE*%6*8*Mx&4nE_OmdW))>Tk* zSgh5D`bL~q$xbG|962STkum1gk|V1jphsvc6#M7cG{o4H9_Y+u-$!Rm_(jfGC={!{ zEXp@f*k%v}g!jRQmAgP;h8_$4F3PM`LZ3|}zfK!IY2%BFA>(GG}A zambR78am}e2fE#e>pFCj7(srI{YmAu#emfTrI@1@GUzkddz>p+@_jZY@`(z_D*Ok6 z<=(IU9xV}mfEow{uKFbO{J{0nzSO!v{>}zvhs61zXR-}SlNbML?hYGhe;SCm{u^H?12V1 zGGpT+dMkuN^HJ0euRT5E%dAJ-8y$moL%J1+h+&obg&|4AxV97a2%tK^BUC~ zc;ZIq!LUms{epG%DHk=l$;5hkn*V2kH;4datpgamCA9|mhJ)!bh-)?NPesMkkk56^ zjeogAB8?@}JiLrdSpwiF(KUKK*7x3xF|w2%1mlY0o7`hB#tnR*PdbKd&yGjUc#SSm z%_SFb3dubcEq{dP-ViU!$9!M&g$chL(;><_+fY#%BvZa^@k?|ab+3nkp5wSCo?V-Y z*g7adfMy6vD8hoJasc$kqVp0SkCDY7#~Z{8y|MBWPtbA2sMMgc|3z%n3%~O=7!wQp zo()Ox>Nily@iok}X!t`_t$?gH4*TSq1cesvCWEnJfa;(ctRa$FKk9d<7w+~x}S+`pVulnd}K_3vyyF> zU8AK}kBwD|C&0A|iJ8KsHWJmBy1O9I>H9M|zAn6cUl&=`=AYyLX}15b#8c#_)`4EW zzWesu8UDZMANv1#xcc4dqlcJpmuHyYC*O|G(Ac?;bz;%m3e(_}5tS)KW^y zUR_>ZRYwtsg6jXm(J1Jv?|-A;Cw+7=R~tP3+uM3H?)`v8j{?*O_D2YN9Y|YxZ!BW3__o9B+k7cS?y?b$p7Q&EdQtW4t zMu(C8b{)j_D*&}$yTQ46g`I2i&HfO>9@~D$aN5J*(yl+L^P`RZhO&`gH(eakJyQ}$ zH`L0yolGVsZ6umu=39I{?6eIq>jOn;=nN+&k@^|6QmJEMgDteeBh_0zBcd4P8>kA-qRHvtYQ}6jT!7aNM>B_)Iydit}>e zboh0Aif6A_9!ius3*^B{+PH@;>rx+GEOEY!5_%%U_)YKu7}zy^tPeID{Xmt=VH}VA zPEcNgIx611d!ui@foy#)0Ay9hitfPtb1uxt3l@FOv`vy5e1Ynftp5DS+r5XnW6i!T`u@%5nhu1>U0SG zNgZf?+=86}Sy>@vHbnD5_9AS!hV~DcLPyh~Dv`Ft%&!t|8K$Ey--c!{>U=b8RU2G| zlQMPBN2_IqN?|rYGp2#2t@wIy7WH8auLo83*}=rS1T&6WP8@-AwMhX%e>O0QhzwuL z@Ir(|-GpB-;EdD*pDIqv%KOcqE8Jk5%rHroUjx9>>9Dje2`jI8Xe@|f+$Ielf82`Lr`$%JN3y9vcvINCS> z68G-elt(!lOX{4>AlZ-#7C?iNVQX0Z`FVdDU%;4lfx4)uFnnw^?8{gGhI712Jl@oc zvjcGPr~L`SptyRe?!duKI-=Fy**{)0FE5%elNUUy+kd_`dqnaprTVNQPykWJ5=ns^ zGUnxaK7+JK8%7BN6UVRZq6thix*b<>4Mi?rdtn3c8*F1z6q!7UW6+ z8{`4Q5LY(?gIp`PuTN(4#EtCpZA$< zFrh0PoOR7IzS2D7!w2;hfbR@ORl%@i>be=? zwFU8)6hsUYc}whr_!j6dyWp8ra%O>MzP$)UKpgt@6hpKj>j|M*U3UIzzLOqgglyJu zmucs6LN?RBH8ZTza@%HB=oIPz^TV+^iy$kAdVn6%SeAkEH%QD8Gi6IKM_M%O+bl(x zx#RacGkDt^7MNvtmWboBIC~a3OwHzDANh9T@1MPPXDK0>EPpMbs(3jO#*!6NXJemP z!H7uEa#SR&PsKwh$6A+|`cfm;p-nxD0L$)HfL`%fu1w@+C<_$|>xxNG=}+_vt0XR~ zEXvTF=MdIFbs<>^F(jGi_8b(3%Rmq}TO6WJ=qRTbs;ab9%IgBDK?EnK4w99i!L*I$ zDw7&f5R*RBm2 z!YTo^I8_&9uYKL+{<`%NpI+hDWQm`#hs|zcXYOLTOPR%LnlbY!MKfKZU5$4}g3s(_ z^JV(n-E7WwcJ6-Gl}zmI$TDw7{&B-@Bs-~+^?g|+2DcxGRb!?w?uNZ^VuT<&vp7%UNan34Wvx`cGCog|}G61PSR=?~+t4Q;NDgBWyyo zzKAFGVSBH+e_}XG*;dVOq!|#9BW6_WR?^PsDEwznBO0(vP_DZ@QmG{~mF0xRIM zA1i5=V##TG;Y2L53sg#oW&z)ope5C`%xD}s)A6_t%vg5L*6w0Gw=PH7ND%I#akMpp z1}Dv*tUky}|CY|v<+9SEikIdAcj3NXnsH>IGY82%iMS)v_-xEUkVWR5r`l&(f7Z5( zXDb;NXDLeSLS}4na88phBw4-Y@C7}q9qpGv+Ekp?&f6Mmk;of}DSW<4 zF`xvSuk`WYH{Vp83PI9bIvwIMINRWJ(R#fOiRL^92FEZko4NRSEsx^irX-p3vMEq8 zY)oeUU8y%AL`}m9sS3TxjZHLaZo_l@3U^%43BMO?@eVqd{Pni|aZiGN@jp}rR~RE?G;sKL!l&N;4B*B$TV2Zf>|QDdep>1j{OOudobV97Z4a|H zm{80hak@+HqvQy_8;oXjkR}wX0lI>8^;iq+VyNSI9j9Ad!zc%`nKkNrA_*Z+)8%Y^ zECLVvdF0DD-)joWbcW4-4Ahpsg+B;~;Q;RvP;|6Os`CNOnSd?MWOag#DqZfPI0K{P zzPUe)F9RJJKED%ezIA8F03jc=;c9mV4G{7{C;glYnmpwKWK9G}6y$k@Ml%Ow!U^q( zk_L&n(EB6ds3Q(Ivl~`&RMnzezA`ykh03jI(#sJ}C=i3NY%4Nt_ zpS*7aHe@CSmFuLbP7|de_CXn;Lq6=QY~I*rx`9~CmQ}@CuWD%S)J{w?TTg` z5n5u0EiTxWVdPI0@A}#XuG3+4+sWKzr!q3pjZ47j9 zy#+j%mO?ebc#L|L!qO6M!Dvr~&uYtA`lt_1(Zs1h7nSHn@>g~Nr|=<}Iip`-x(8>i zqqrXn>b*Jub8YaB=5*3A!s${-xx6Ni)#P!SJVukV49F~kp$mrZ%Y`3B4Fan!KP87>iEd@~ zq%uuu$K)wbvbEaV&1dbCR`V!_?an>IvfHk4<=wJK{e^YqvP7qA>>`jlr%cjyb{R;W zQzq$Jy9}hxDr0rMU4rGcoI+ZUsj>$zxr1=~Au!r3283AX`fmj2W=;XlQNh|qrunSg zum?Wjr=VbEO;a-{bpN2Wv)kN1J~`apJZ=^eZM&vZl18;oF2(IxCD+EYU}P}I7b)Xv zt-Og7=XtyVw5_gP^9!wVyXW2}2tfdvT$h(g@hLAW_RDHz{br_|7B@(#4Sfaacy8O4 z4Fq!5_Att2A+BgL4*=?4^B}l#%sdEq43G!G6?*1D5c0`FakY88O`X znwBALW$puf!S!5=PGytAoYvlCq*fmMKF>US;iYHR-UKQU<;!$93HzwYiJ}n)iR+pG zEId(TG1QH$6@ZVz*)Z4ABfBmAsANxOipcq0O2h7It@Ih+Y%P5HkY@(Zfi|Y~GNDAl z=uS=OqO&O~$K!~c&Rt-~iy{b}i(|36N1L5Z++mZG1LG5c!m9OUXnA9jdsk+ge_%cIl}b zE4R65ViT7=`f(;*YT;l+&DR+sW)9vK+Dwiy2cu0iHI&&$9M|`NB6mUj%)0@NzyK8qdz>ekbgQWXaBkITdmg5%@#Z@;l>T$k#P* zfA>&dvf{jyi*w*zs|{8gp$L+0J~W;iPL7ZLu7n=Ih;!&X6b7TN)m(q}b=m*Af49E> zy$3r~8VY}~XdUzKe=jdT{O+N?|Nrp2Zy*29^6JWWtIL1g|NavH&cb0^dkmC)zt~Z< z4o;4?nmV!G;nc0e!)Lpj&oQ}J-rO_q6{Su+mHJmKKW`o%H(wrC_&uAWwo@!mqER~@ zce>%Y(&&e0af5V7W3F#^dvkl6D#L8Fe5W(wvyd?-)cby>t|Iedz~yMOy}R?YRr!mT z;J?M^e>hyUj`{Qd(W8~`9vlB3s}FhpKm5!8!x#B?Us(fdL|SsF%<*>K25P0g0{>^1 z=+-h&_wK7FS}FRE%+fS#7@ z*eM;@wBbes!`P+w`4CTnv!X*pC#oQY;n88X$RkwZBvU+C2k0pC{wI5Dyg$=dV^w=7 zq&UA5D*yn8y)wQW0meLUjyHO8gz`DQ96j$zt9jhs+x)Q!^z+l<=J5;Q_)mCEc;b!T z_Fxo1EF9B1AkUS?6FCp09O8*XXG&gE`CzTkdH6B=9pm&_dF0j3=MUQL4jx=>Z6mT9 zg<|pd|7*Qy|I|Ec?HufXQ~y{j2TFM2T}1K3 zPR92qUXC17EH_^^QTXuUsSLWirg`X{nhbys_Nn1o3bB}6UTQe>Hn-@Iy1n4Pks?|_8vmxFv7sQ)qkd68+@ZQ?m-PS$i?e6UV_&M-LZ47|fGaA*J70X_33 z40BX8BSl6ok54>U0pNj>=m}ExjyI1e0Uz+ay{osOPs|IY|6-^AqSLuBmOME=K;}g6 z^317*`8`SA_zMaqI-P}-&7Xgygr9$W0>h4vTU+=9(|zw?yU7Xi0_g^&Ex`w9iCzy6 z={fl>&yad@)B=_P&8Kwp247yjq@;s7Vc@2Y9EYoD%5iiT6zBc*Z$I)qpAT2x%ClgHrGT-lYhaNTiJ?@@UeuaQ4K0 zPrfDs*^^XKlE;W+PuvtM$1%L;!E!!4@#KgUM9Eh32swuqG_lOgk54>eM^ARQ@yQIm zJVIKN=m>u38A{44JW)y;wh4zP$L*togJbz*CqbT_r?8YVRDPs1oxpF%)g%EQG41ex z6AlmHZNJU=;TPVHZJ5UfD$Y7&ADFD4A@xTf#WoG7JVF{zm_3{+`_!rXd-&Ac-Z|zs ze0t&mT%=G;l1EAt0^%n~(byj_?)3Bckx6;{=!qx00!%X-1bJvbJwZx4I6AhzCW%SD z{mnfa0KF$)`IeOZol}w=z!cLUBq_;raMpO9Uq=} zR=Z7mf7xV?j=%6`CXQZ9{Il3dXP9ok^H-L_^f$eY#b;Zx)8Fm1B$o>#Nr4=lc4yLN z9QCtF<+Z`Q=yZ!OI|)xj8fPz-_%(UuZ+$+GX?LTE{%$34o_Et|VoK8sr=wy`QsI%) zrb8>0UTE(oZRMvYy!W&Ae7qO*`=KA3RDRXpI-_aw1zvP|WEF@^?)R_s8RP`pSBJ;`MU6 zJDmo(CU4t`T$Q}>7gJ82S!j^(mN}{uRlDxqeGP~Cw^oyj^T}}I&PJr)| zHVR_&g&&`IXa&KU`3X{TMk<{Kx!ywN_J}_6;}dU~Q!<@~xiBy<3JbSkDve{a*9#y@g z>itO7@&9N4@^aOcYifpaQ*?{2%CX|zd%}TfMtH7J{Kq=REjz_{ZhT20w@?Z5o^sH) zrD74%mMZ#Psj}*H(>;V5@nRVTHBn*Uql}e5sMRoJdjR~;0;90Z?`VHRvBYcVs`!LX zZZOVqI8n>%Y@oyDV(L6xS0C4t;*@7)T~dPB@6cm68V2+bbS@%QN>G(9V?_1tA2m79 zJpl%enQ=y1T2C~9oo*!yjp|n^g`z$qWs6rTvyy4uT1Y5gW-?+lt7LG)RM&^`zyh?7e$;?qH2jrpC3Iv-|FKImZg7g7neEr`3=LaZSrZHCW5^Ilx-x zT;Sf5V%a^Us^A4ewdh=X141ifcW@f)3JQ73+ zfux6)6FIBELSf!WmvFTh4}hl?lJ2kY$U~7_er<~A5+I)U1AmzA@tga09?AwO?pOGr z>%@c%Ay@+@U6h7P=-hU|a#xBsx5v+O%p%tGmP4P1>vz|h0Q!t!xHc7d$hforV`UZ) z+7`)t!>tTPA?{!EkjSAd3`dPYFImU-9@;g{%s27RV5jFj+1vvx+s8*I%_ol1(pEy& z8%QX4Ud3V&8weamww}_fck0oaM@i>CTBMJ*wiqs+Rr5hKu!+56*lNJfHvD%8|2W9jI!-ZU_IO1Z2>S2@(h&xeM!N_FX$juKPh2E z#7PwOH-?d7AWt{9er)Y-wq88B1ysgj!=OV)&vJx_FJe7V$$^~<&+ftwb`16R*}pz> zkH3L}`s@LM@UOwpRw zWX+l!3z^ag2bu+Z>Y=*$@BBu6sbcBwadKT_h>lxWGLU4NpcD7~5A)GUd()#h{d z1?WZNrfJ4%!N1`Q{-X!}69>^IVqot7USxdsue%X4lzU@swsl9yzRKmJ<{NFaQarY7 z>t-m|dAPv(^yLWu>|cM8{vSQ;jvy?ZZ40=t=y|yx$LFe!X9}u~e?4z!8wGf_Q==AH z)^@u)twXZ9gC?@!ZAG>kB`2R%I;RM0RAKM>ZW{0&B~0y6QrZV-0Bl&o!n&n@f_Ld2 zel@*9AB-Bp-jZtdk5>E?ixm1{WnB#+*I+cc=C_Z@UX)cU1n$ zn`9q2V{rao9-a6iJm-z9X$Gls$uPCOc?46qSX|O0r`xtBjbdGBva^?5xRy!B6^n#V z`#ijow(5F{#rvw(qkTHTG+HOBx}qO!?&2m`C?;J2NIWSRO4BD%2G>u9pMoqScpiEk zCTcR_WkcT2N7a83Z$9x_^txr!t0qILgU%wh^q6m@$J|ZW${BORw!G&wteUr^&mWz$ z7-T#QfevQ!Pb&5I9@37gh4A^gg#Zi))>N=nHbiA+IU{><;H*?iJwM`~)-QYTmkj;L zkerG`g}9y>qjJ=PG9DBeWaEwK!}K5*5`EaK*Y#Jw7K^8+ORpQJ@b5vRrw1S!<-)KU zc`G=Yz!U8BX(OWEw$!fVKP^X*$4bdu)oUUC0JU0pHa>h~n>et3=V87LB z$u1O)f$pbolyz{b&&84sN-9hyymPokS!yM*bF`Xsh`B*|F<~PqSa_rHa<-6kWk2k!>0M*; zo-E2H?Ox3mNir8V`E*K7jPkx~0ClzDF2x_zEWp;~&pF`jT(CvkUaI1PP5J$m4mr*w)Dy#K!jt4YE31hhBL?P{F9?BBU~9XFuO>C zoywe}sSHIBdvIho5ADnWi}xWTM!!HzXvVyz@Gqsy!!WI&76jo~)%5~q}@0#p#*cB;WvWhUzqkh%>Y5EcS zPx?*wm%ZxPYmh@7bzB7OHBUK924pyVaj^f3Y>Q=^f_5O1n?}PduzIgSp{_WqZ59^N~ zR?vOR^ZgS=9)Bo$$poF{;!X~0c<+xxyulNrH=P6YjCmQN6Ih7@pvWzbD&z9ox{iNR zu&AQL^hrg>1qiM>LC{54Hue33=1aW)xb~L|u0Q?XZTx@H?W@M!>p(AG-+lY-O#grI z&-nj(i22Y3)T94V-+sPk&i?oRxc{%)kAIJkvF=dET>oz?E8l+m=sO<&mG8cL{CEZZ zzdc-j_?Q2;FY&K|u3@iLb8mC2rD{txjPW(S!b4GbUTU!SSacxkI(5StT0;+Q>WE_V zsNFDlk5Q_|(I9>@3HzfuF55p~$)kWmXLMne>SFw&3s_%*@gUZYZE@9kez>dNuhy6A zTw4Q{s_+~`oxj-psj2UQzksDj>C4LBYX?L>c=v%y!*eVm-wOS=o%%(=N(cvj57sV7 zOA^2D_5E(ppuYqr`7n9gfd5j7uq3Bax{$5=_HA$-Uk_sZW_?7_EOPU6cvCkGR%*!U zreVOGbjhyN?ll_sIVzaiZazJE?s*ir=y&g4YiIxYZnOQC@(eugMpTll1n5ZQr+xF!U zubHD`;&uDmWE=!5?MwaXUZVlh%=tvA^D#6nopaUA$+IMzGq{>08SO6@BYzm=;_-gw zmovZfwtY4k=6yrQ+H=2g3|SQ0bPmjN3hSJH@EQFIJyMJM1|$qDvVQz%bH2Eb+Fq8dfGYI#{jdt zkXMf8)A8l?+;r)}nr_G~GI7`?uj{5#}8_%Z7m{M8K{f?uU6R&u7W{mrk z3z411=KzeyovKR#svA#Ir7@5L4oKO}h)GqI!LO=%67){NU?!k+>Ur4jx8ci;Eh8%; z?Y3VU2e7_i}QZ? zMDF{EAjbjBv<@)!>0}ZO+aU~i`8mohFZXs~K3om@FqgV-x5xe^Es0C&61Zk`$?*+f z^0X$`lpN!)nI{Ssi8jX*GBf9DG$1MkaEIa5z#jo?rr&i+dm2tCZQ#ckj|1l=tjJFZ zFJP$j%jtT>A<+vP#$ceOATzc3rQI0^$R5zOa2slFcgupfdVn=ZU>~{qO~}`NIP1N7 ze*7cdqixE{{@TfiP2i3utTq&8$2(u`rzgk92m56b`P$HH6rbag5G_+D>JFjE3WPc0 zJ9*otX9_4oxH9@>{;4X&6-!`F2G>Rzrc9;u2h`{25k$s@qo^zAJYUv3@0JXir+Y(kq*p&!8hA1%1}NDQ>+J=Tgq|Xa8M1+Kx^G$Vnk#}K@xa6JwHcg zJGq(=Dc(z{h{gds7=U2+nBIi$DJM1Jt0K-0Dh`8q`JE|XX z=!bJ33U}34I>1E&AA>|<=x&Z*G7LI2YBbiCG&g&64L%6gNL_RCa~{tB{ucS)Tlo_i za!vuvgd#>#Wc9X1Rtq{j>Ww8J50-c+{3j6|=M-X!WV~#$rvHX95aauxtU*;-1n0=C zOi*)yn_WTzpW_M{$&_O_b*L6x{kQP*9(>(Fv304U7#`1i@eN_1E`|r~MLs_w1a>h@ zP{aQD5uuF~A!2O|ZX9_cmV24)!n`IxUdEo}r#K0H)b9BGKGI6rmaG^hVkyjHg~W)= zFuANJHNw12CnASE^T&h)DiG8%g}%a|Simvf;zFp9>+-Px-l)cCO?ite!PC{(e$a~& zFP}PSkeMS@Ro3fg1y`RowiS{7RM4wg(8wh}2k3`c&^UkqTGT0@T*ITB8i2p|gElgw z&(Vf&b7~m%VL|*{6+F&XK)W4*&oq{V`ZGF`B+{RymBC1Cx1nO)dlb;Arx(3o0PQ-v zCjM5IsSc88KkU2>x`k{=yF>%DSiRqVV!cK;v{4oD2HF>}F)oCS2<(;H*32q2fj81PHJT?VKP zg7ib!N*uI*ZtgsPaomP&!nVnyMI+R=EP}#nQcYv2K=fPa{OhKt?v^UnVE!OscrttuVnuRa3NcQmQ}faqC35_#8R*m~@TFin2mKK|uUdqSXcC@8=c#qD-}J$E4Le3b(;bC zBQnh$T6N2z&C8cFW_QhIhIS=?Xjjq`54F~;d^7V-2InW>jA{w_qYaALBJW%(yy@Et z`u!s`t{dZEkL79I0BQyOfMW_S#X*1FsbDMWPX|NvDu%zBW0)nBIFGOec&#dKo7pfs z`7S_S3&t@d#Niq6DlUPi1Nr&KQ*_{U0bIt-isC6@WsxHl;$$MqEJS}af|g4j0mv`e zyaFg;tDHb_9uG)I6&HA3=-w1uIsqyuC9OS)dMGUA<0Ey9a07-Xn3J+IhDf_7d;3yz zML2~9oov@;WA0BRxKMl>$S5-z=t)w6_bUZQb8USN(dlO##u#;|;Hb2%OfujFM-^^; zAN$=fDmY4Tv!>4PU|ePYqq`SdAT5_;3F~7bmehLPw*~8ybpT=H0hqg)8NnNVncihB zR3}Vae=_s93`teuCavafa|j7n&? zjoCShr1?M$u`${Vl&uGaB^;+f>*u+@duH{~2xByG2{js^UMQ zF~8iRF=!d`pU@bXIX~gi!EL6FHgZWmqTJ>aBTco3%w6u@exo7OCxFkz^*R3)9S?1khJ>u#Ph=jItD>4nW>0%Wt8XEScas@o{b+>?%Nn@ z0sY=b)O>%5eH+w*#t0{qupdsYQzlQ&rj6K-Fq(^?Kguz*(px9X!hrSMiRA%l6-f-L zDwwW(o@nfl1*Ou*AthU7df_XMkEOLJ|?w~!hKOqy_#F~UyHky3QP>vZp z{74&~t;pcFF+lvJY+06R!xXeoY~n{qqD*qgkyC-p3k{(g`uzx6ywvy4NH<3MFIXF= z{fSaW6GHYWa#;{?pM#y0R0z#MPczA0$L7*W9j5DOWx)U}$&nFb?5--tXOHiU%5y;A&*6GwTdLC0B#rb_CEOi%A zrT}8~y0FoV#sxZ1bS~MxET6}~Mx(c~m@;cmEVnWm8HX4uXl^I%s3?GxQ++$W#KWVm zg$BzJw?)Rr#>OPe*>wIt0H=;W>;(PKj#p~6qEwsb-dW^BQZjRa?#$4twAgfrvx_xP zhtzh;WAmW@G#0_#vM7(3*(qM$TFVQ>_Vebki^j+F7{_0ZWsnR;j_v&T3vmsXK>lJI ze=yrXG3)O1MBB4j8^uJn6$!VJFJxMTZzQ8Mb2GO}K85sij4sGN#=6)}+X%c@Nf&zC zJIBqvvIY%<#K+LAtDdI<&NmlvPZ*fF^mV7)q{Mbl8Zw>3S6%+7-qDx(zeM*O+`V(` zqlCNGFQ+Ac9s+WR@@WWU350GS{ZaIxJvw{=`Yw$I z&2UX&9na9(hHk*d#$J2oMgcE4>B~&fxqaQ9WQ$P{bZgTQ?!o4?W%V<)WpnpWZpg#W z)DZT8@&((16AXzYr%@N>}bL<7RF_qJ1I$2`YB zexrJ0e{>Oc{C-MC#k+Q=!-5ol7L8TlcPj~`SY3E#BM^p66j4tzH z$c$=n>IPK~>b*L4MmKmLb^_HM17`!Vix7rVHm>~;1R`WV(|#8n=8eWdj7oAf8DA^Z z)(E~WU{Goka23ccCCUde-QFm+5J=JyVuU~gB;sg#}N7YzeG7c`+&g8 zwAXC4HlH`!JNwTLtYr3m&}wh(9<-WORrorF{X)VFZn-}(8hgCx#`=7**ty-_BMT{K z1Jd^U{Y0y5^GN>;M*a_Ejs#zrqo=K)fFUY!H*Gwib=U)1uJg10s8^pL!|c?faqowO zEP<4sk{>i-IvkJ-z@oz;C`!i2Dy<(4AI9RrD@MNN_%*jL1pA&Y&4EWZ3><-!oOsdC_c?Lw0E=G4}299 zkfKb^7q*T1M>?hU1La&(hwYR7ANLP_-j|&bL-=X~KHydicS-Xq%zFGv6rj4;hDros zSCey->kwzw;;FzLx-olP!kQ)9cEQ>7vO|J9)MWcZv@ZF(v~m%4?K@6Z=bBEM)vXSe zg%VGj57@4^ zMpw$Ada{)qPHR61Dz}5hmmAar(`<$(Z3mcoKuFVh&7PXLGg*^ZhQz9p{KTwmx0q(i zR$cEL$!L-3DRqVR3@5~iM936Ln`7x{RFQB6EN&usr>K-|$Z~>AuNTYUpIq}em}_& zFolsJ6;s?L7A&_e)mSTtwS*AV`J{9&=^_V4A_2&a1sja`!nJ^8)?2!NFbj4f4pr>3 zwtRE1(KrvU2Em$o8w4YaG||At!b^KGf^EWa()%x(FOwH`t_sQjY>l}hl zjw%gVyM#+4&0ta^mK2bcd-ibMFj}`8todV=8LE#n;kpC0$T)p;y@T^<$||~QzS8br z>|-E(x7&66lXsPdeZg3FX=WcP-SvPdG}B7BhDPq5F<=Z`>&4niat#JnT1Dc?nr5=> z;#QSWJgmS*T=k+LRvXWP;h}(mTMK?7F|5ybK#(IKZ1zz-=6kRtm@Ee zg?v8hbvtn1@U#iT^nSss;YCH^_)Q0hUn&~F|sF*)SOw*(lZ3#yX1+oSzB$!dwI zXxe)H6GSIt2YgrgNuS3$Q$2CnfT&4lvsz+i0 zukEpUK1D2G_S?;CypJm^jw+ zpT)r!=4`iSX~H+48%aK9&JmCNj$FCLJZ|MMvNFi%q2CNK%h@w@5H2+s+4$DfW87?H zZaK_u#E*yVCR^J5ZZc}8nC$To^*uS=vIvv^B&N=r7<5%12c5x4H$xNRbt6dyR zXmi=RqBm)2nOas=6;IDR*ZfwM_aiyM_aiSN4uRQ zI$O-iihKFeo+VD{075qwaSi)zPk5_s*HMGHChe@VJR*Fq<+y&*{?o_)S^GTdOk)e^ z3{LnA?Ol8fmxJ3Y=Dx9|EWAbN9Q#Hb=Z1W*lCAvfTt#q7d+0>YA$>BEY%E&?qgy1! z;;aosR;`eT(xhM5Nc_ndzqUPAt|H3eYwSpl!ZRk9;Oxy7V+nB&O1l{3Ykk(=LtSro zIs&c(D4drIU&o40uV;CvFv1}A1MEgfhj`(~iTpM#R=*F+bbcNBp< zZ#|jQc;CVyH^^N3!2}b*8Hy%d))eIvrP>b^;7dK&Q2#$SYLuR`SQI7(?;-U818N#z zMTl{48TPv|MVtdhF`)oB;n45%xsG?wl>{jFdXlO+D)f4rxvD)EuhN!2=DI-3zyvH8V&Sq38*PrWWTI6kOX$qe(^1`4}H|nO0^_ zxtJt%>~jQ&%;?U^!tOxlGZ#Da&i>X7nN4>P#;_1LD8pXY zMQHD4oYPrmqhW?Cg~fFcJ6OQ3*{$N2o3Th|ncZ^<7I*77Gi8xdzQV&_ocA}Ks795_ zJlbd%l2cO#3qx}YxRA>QoEgC^Wa#c&K!#i{ zvo%7J16?zIc2UJrw9=9*JC9bt7Xv8XYKKCNPx#zt&UWO}gMvzE!!0|c?Y$)M@U+tj zVmzGZ@P`;p2E!jp_(El37m6ckD{!Gd@ym|eucgHKPf8GC3y&^3r-Az0BnKD<&Vn!R zxT7&`?Q~8Im`HIp_%$v&UugWV<4G_mS9I~JTG6|88knm7c_1xyjZN6R4EmQgj#chb zSuriIzotF15wf#zL|jLzay}ne9}k>Q6gk(Pd-g|)rfW|h`=i+BxODD-CM|(=?U@L} z${;>QrPHhr9GiF6VoUR-V&@l^+zLn}l}w(vZ(6nOGCJn(tTHkO(`6_&@SHNp%F|^i zhVYy+$kNkg$no`@GAIO@GNPI3wb`#vdpaBk=NLURvBKNz;=L~729s!}-4ciMqS>D_ z(`DkBd7h0g4Kvt8vZ1ij6n!FArS>SlEyAxr=PH=~HA1bYZB zFVHJRnSii#nX6Zwr`#5pkJDO4vxlLB9PS0)+zf(2XLMbDKtp8!F_8kUJz&&Hx@_yeS;{**&YLx>g*}-PZyXiWHg|gCuy<->= zOJ$v%BC#DysbX0Imr9_0O@mV!b9KEm`($ZB&g5H!cJN{G;OrRiopsn(&41d;z4A|+ zZsla%y{4=vD_8^8LWQ-9tsVN8YBOf)Uu!C5o|fF|^=f)Pw}Z^5p0~Rm~c~c0@pyLmfCAEe*PK?09@q)3F?`Pec$! zL8MTE1(phDkzEIxsW}GBwucBBr#NPJXn5wmjQC!%)w8U$I2NLF_ngi}4gubv0rEA; z8R9H&92aEHnxD5t?pM~8fj!B$axVSH3Cdg`>iIO$BQy6F>@c_#t>v0)4DzAEV2@4I)c5*$Sn1Q^N!Nr;< zmmcXu496tNC_ji2@9!s_Z3%>scrK17E6J?l$Jgipup*8IW8LUL8#-5+Y~pBkl@*fZ zba;1#nN^cE-?0K?YRJeS{ITS;q~WO7#%}o2NG!PTxNRt@TJOPMXZ9{DS?=ll)uS?X zv?m7Q{)vHqu}CN#GWR|Dbh;{KUQSMo%oz?b&vG_NTs9Euz?2`CyJ?O3S%o|??6W;k z>x!i}3}(SR6rtaycNm?|8tJRd#J*x{PmJlA;@h2e06b(1Gdv22ly}y>R`$~TGVEz0 z>&X_A*9hV*N9Qck5>2va(jp9x;F$Y8mt}SzVc*b61KGHdJPACGL9R3vt9Gn%oVR=p zmbgm*a{h8n?3dz8d{PFE1xo=sfHbIQ;CU4v^rl$F)^C6REZt$u5>Z?2lFu`|7~NYO zV)k;?)?4gCT-=m9D}gXmPbeS^NCWi1ZP8UltF?ULUH-VZrj)CNe7Sg7s*}?j&M;jl z4R4geZ6F6adZr#FUXwl>%`DEZUjU*4Niw{=w4F;9D8`G`)WPx*^oS94SAWKa{;c0p zB2}G|SxzaK%;F{+?rOEnK3(yAr-;(D!@Qc;pyEn26;*g5JTnBF>NqWnM)j;-DDq4s zL^`FGW_L*#cukMlHLy3y=aL!)osKgW_}IN&ZPW|MM9%T2?kzE|JQTFo3Pae`2lyR& zGG#aWW^Z7pZrFu-sVn@OB&=w_Nl+k!^k?{o6uXjInOFkBLK%U%O+vg9$2m~0Vvpe- zBJ}T?GA>JJbqm!wG(aACs&-S^S2D$K{jnj>?q$j9jg|6B&EN&FiP&=vo=WJtyt~ zc5EJh?%v+>I1gO$U>~cp8*_RjVmS4wq%Z*`i>Vm^d_aT0%Sgk|*2V_@ z&1`RG=r8=Eboi1@Z)ShWWVY9{neFYZElAI1Guh3bl=MPc?E4v_?W-t1frQtgg;&-X zxQf-CwcX#t&)Z+WblT#G^cNirLzW@+;t@`!F$m>#U-oK;3g9Z||%9q472) zz6OC(z_utDse0FL>l9~pFM4O#(S0aSd1v&yMw_$}yRX*jPst7pLO^vcw9?dStz3Lx zEKf$`H)Dx8q?3bIt2VSswNjjn4!xukx^Y2UQIU=ej+J|C8^&vAg@9oW~0@|Y0 zHu`(f(a=~?9uLdqpVVkZa=5GD+`JGXOBT~96IFm=X*JQj#A}uDfZ)KyjF0-}nv%&V zzv*3e>uF|dC$qf+DaWU3P)+3c4&&M-L--pvwkC}ssN(b+m^$^bChJP(&CW)4XJbp$ z1gkCWiqiDO6u7C;;{z-(X% zZv72|oM~JGpzVRxyov6^Bq9On-Kp?qlWr;fFXW$@3j9THLqC8-Np4Psy_*5{OHXh4 z|&nG3xE5GU)#e?7Tw%+8&m|8JzrpSk&k z=cDw&kLbhmaNCUYa2`!)Ia6^S8EM(GanZ(^CgcT-8s?LdPB_q|SsoZT3c(&}X<#;5 z*nGlDIUgE}vKX*hHIs2N8gbQ?jgQeV~%h)JI!LvK8?j%*ITCLuaY;O>vEL@p4o4U z;DB?Wy4f>)B>6pRPCG7??tEx)`d~kT3Lh}ocva5)MjCU|mN(Ah#f%T(s&5T@(S85e z&WT2{OQ(_br=k&d3rdfiRp&)8EVm_!hi`;z)@LG{<;>ym4&3ET;7*{VWzXKIb&uUk z^@PG+(yCHPDs#!JOTm%9r+H*-Di!ONd1PeMJK3$B^|bJV7{54Gdh*4o^|>!ju|S*& z@@p9xyytbQc`Wa;xXVl8#5@+ZWES)VmR<<&<)57QHs;QI{EKNkZ}u#J?L_eEB{5!^ z6}N0ZAb*7JM=;-f*=2L??DC%>sHn@k1Rl74W|;8|^FUi%#(LY+n>S|nYCp&`vd8Wc z@>h5ike!(fn$L{F;-CgW!i%ViuPM{LJx_>H9IsWzH{5k~Cc+FL%WECo*InoL#z`Js zpQ~r;6iikNpW{0^y_bte({Sys-qVcMmEmHk)!K~CsVYpTFN6>5fW6FdN@ev;qdU;u zwpHt;Vnxm4ZI{{!y!;#Vw$~?o!n_|n*zLhxo3~i4R?7$Zx^_@iPeSG}Fnf0B%Cq?N z{l4|r!=`fBw=5s}U8MW~>e)XyxdAjf!D+^~ns@m3elQr{YFar~T}qn?)gc*S-A z>^BWNghC6H>zdhOq8*T}X&Ah>v}>TS|5`v|?QkUtyjwK2nqjd_TQfU7t3S{Kk3tZN zM?dqZ+g|ldQR~E)lutCvQg$Zk86;I?C;HL$NmA6W5yFzSYgi#A;winkko7k;s-aBH z_s%vAKMb)zkD}$!O8~|k2xe3cW*037r+fB?mwQ1@{d1Rl)`%PXH_jm;gIWnvBU?c1~m*D6MA45Ht&Q#M!8ft*Yam-^)#=R3L$d3om)=hJW@)P5Xj;- zMhtGzp*smNheEYpq4<=w5$BXpdIIG0dzi;@3mV>VRyUVj<4IH%BrgmdBpgzI z*f#8OS0M%>7*-#OVOK$h!Z5lBtl5U%Z(fI!yu-e2^~DXmUI8q6IIH=g!q43{cQ#+| zWV5nAuD1eA*=xPNVcS8s6gtDK1wn?d$ktAJeP?q*MQ)6{>9xpeBVe;sA(PqJ*a)1* zPE{*7*nTB6!m)j`dlOpd&^@Dpl*J17sH_F3i~k^u2`XTkz?rTC z=CbAW5a}OO=6tdVDfa`l{>(x@#8N@9)Sv62(J9hDP-E-%%qU@$Mj)e3QyjtEJxzH8 zVTDm3gtu%Zvc0ppIdZ7uL5d{%NJYXb^Llb+7OzZ5v8FTLYRq8;Y^)LqG*HHAkjE|w zOqaZKSvZ|6c`L>D#rprM)HS{gB&iE;NU?K0hW!AkYqZS4j1tYdHTr+`&A}`rHIcZ3J-qqMNr9r4Mc*JdQ;6cmVtwdw1y_+k%7>$tS(0nVR#oqSv){f*GTg51(ku_@&LMs}U#eKtTNr!WX4AB;H87h7 z))3d}jQ*|BN=8H*z{0=k>mB^+meUe0B-dd6!-GD6lA*YETe&clp>13a+gK5RRX&u| zlj@nO4SMq>g%h%OX;jEmmE48zFt=cF;<8qCn zs-5QF6@h*t?@<+le#$Wwo{P8|j1-!qopU^#FF}~yW_#E&1d#jcg9H64VA$j6cjJrE zlwkO)45xQAt%>nO3x{MkL}RhP|J^vz-WThQQnm6+@@s4rKWL32v^TF->+vWBqHaaZ zE(n}&Uww78OJDv6E);!=j>7FqzX4Am&qOEonJs8ngF`Epr1DdrE0b%GE{ zSc!Oq))OwReutS1jL0-6mF{?sM_4F4jiUnSPNY^Zdf%%J)sw(+&MJN^Ukc)RlgK`T zI+(q-fic5#l#q*DTlPRs#`jz#$dHY#7C#oz%#7GWKI%TL7C9_IxrOTKX|+O47iOa* z=YmqrZX{oz5Zc=5hGWqQFuh4Jualh(q7?qBbvCq?(X&Uu9T}R`n~by^q3XZ~6;ZeF5gFQ^RmGk6n;r=3sO7;kmJ?mjFwR18NRTg7PPP-N7bDva8AG$M^N zK|2E<$E=x=TRr%#SWq2ONHA+RwuD@VoxGv=IK{01C{4Cw3PfHi~a>0Q*ZWh zB`{S?A4-*XR2EqIc#8;(TVkMJ?G*}aF2a-fjKl$RW+*Qb30&#jYn$C0q@6WD-snWNza;?6mfu}NeU0a|WaogTHU zaZ)Uo<39cfAU%=9acQLB8F|yzI{MuO#_kpg^tFR=+u>K@5-9Vu29!tz77ADzG^D}* zdKwfbLFqnwCb-li?yF}y==5Twtjfhba^$eB7`%P9dNW}lS3N|%kvc>VMHWPPK?R2( zJ9k||5HC-OGjTrQJ5s_enEKb6-ue$-7CS_`V}yp*RB!K3qj_zi|>1V`%eOtcPY8o2$Dj<5gU_bTW`3#e*v70G$nSe3#c>CO>_g66s{{$ zzkg2t4)y=^>DB$`)F=4)IR!m4k~Pm1cOa;9Vlj*hzpJz?#qAM%?HX-aitgZ0OfP_E1iz_P!#p6;%`J1jkuz!yxqn}aLMU}5kS}c~uH0cGj9#kSD2*JEm zR)6`W%K=5Jr7?}WYfpc}?7#%`9bng_EO!-wuB3Opj*Z^ zbA>dKD?ENyzOK-q$U`DJawQgfS=pWZ%T9gjrWBwWX#fK89KeWUFT2ZF@kmi+t8oU% zBRf*yZ%ukbX~1m`6q2r~7Z4=9yYW+lk)!GfQ=Bvz+_JzTnhJq_b%h5FjOd zc$WiFj*o=`K7nO%T0JbX1pWf)PL&G0KA<1ywN|5N_d9=v)U$d6tP^NHr8{r%<>N<6 z`uLHaMOO4gDRL#8H~Qk1!=EAb{Fsc#50ork$oL>g{EKfjFcaB3K0!+3{PavM(ZGpk zNIg5P9h54R$R2Z%V&SB!Q7hOJPpLR50!DRGR7g3l7pY%!CnV?8jV$OpILl5TBf(=Z}z9BszjW^bDB%6`m*suPUsasam~S zRrx1531CVGV9c{z*(0Ti1onoO3QxdCOsiE{LahpK6^+5eUwBjhpS^c~XyaBIhM!;Y zU!nNWU=!P1a%=5CA>br@ zfQuZ8N%BZ(!a)24DH{6&#-08=d1O+aJlZIT*#gsy1w$TM&tD^_9UPrFUu~kzx4*gP z0-$&M71?3`rTd*zYz`2LNf44`^SnOVb-%-_{pRpfA_?=jmKM(9ra+D#UbdJE>8p8j zzaVFd2uUS+`LuZ|k+e}b+T0f&0lO;O-g*P*B^js30#%9HZ>Fzs!WgSO<({?s|c2{fqyPIZn`7mq>3r;}+wn zpG_*y4dz9sJ961e*bp6-ta1YjRDRXp+QW(c0xvo}atcHy_hmTfL?io!-{q^u z#q>#H2M|9dk~mNI9DP5}x>q`fN!Tb@6YGXNa@r`0#!kAt!na8GKR-drWml)r(?&sj zd$A@=c3#alV~}$)m^72?JOSd|gV9fX?R#GbiLV3i>u-s#zsc9Du?O*zC-uR0tC(mrwRK}c1Moz;{_D#MBGwEkZjcn#f=d_IEyu!C}zbBm~j~fNg zguY?l@XJ|blId~7F+6j!e%mM*6Z-}~QHnLHZ`e2Zf)-6(rFoHb06F%)=>+&bZlNMZ zU-)sO&=2$|U%c4) zrFmR;9u;svtrw{p{(t(fLgvm=-8CP&`%q&1@pp&Hg}Dv1*}yYdyS^t&*IV=yC9~v0 zW}yW(RgzQd;`}_MEtd7WQYF>yBngb$m-8i5TE#?*kJ58NzgmUyG74cXaKI=m^E;Zb z#v#mY)iX7}LHq0j6<&46XpIVcfa2*W3_hS`s-ZqLY;nr7(vTD~f#M???dXB5c?%X* zAsHj8Eg@*B2J(d6^Fea&&(L+jE$7aBJq z``Mtm5o|OsOeJbPZ!6a9t-?xn^W^ohzrR|T`)mShgiRQUsvI1h;&Kjkr=z>;lym|ET@3pvM?zyD}LQ_&1>YwRTv> zkMs7sZXC6Hzk&b7mA8Y6s)+G^?uPx22JRi0_Z8Z3n8WRg&f5I^!v^hfP>#+!bq_L> z%}z$KQ>>_tl<#<@d23{TewB7b<{y>y-h|yx>3F*-EX3xh$D;y2TF z8p;MKrYn5Vb<&n)k`bH^6A~ri5<0VXSmsRees=r{z872FEL60IlHCjSyuW~K3?|_P zH>b0sKSwzq8m+Np?BPg4CMLd)(^+Ko5!y5kQmocU_R#1zD8BKI!ET0^@)7wTD6POLW3D%p`w{ zUU13ikf`9wrl_vXe7WP}R^EobeK6^@m*=*Lz3gF?)8TF&+w*?O_j;+aAPrlf>5wb} z)`YR}{)T3!IVM?op0K|K3mFVGA9+pr8;YG|yNx@`~lqFtylBni_0x-e_pJ zeJ9*tXh2u;Oxn+HvFE-8nuacU~Cg zeBh`otM&yipHn)c2yae6-~2WSnQYxG7EUs8S2M8?wJWU5uZEfFgJEaax}zfvYWD6@)p}C>C*m(E_C(T&NiURZ7rbRbX_4O z3I+U4n+92w*7Qo9JDc+esmY7x-$e;Y;NC`G2VDISp)rX$-hj zby+{S2X_1f2SrN?Kw_h4I8DoPgX^D$pMWeqc-AennW^b)0G|-}a$J4KyxGj_@avY# zubK_14$?igbf0e}``l01%II?=whAw)TeWOS?&W*inkaY}0_|~T@A~WS=g2#%+J(sM{-vmi!s7- z7|&v7oh9%vo}=uVQ+YOTkrAYjctn~dJonXU01i;4bQabYSIogLIrb%mq7m@@jcB{B!Xeb(T&8WzRDV$MnAYr-Al2=wJi(8A*eED80h!%%`fnEvoLRDh8TR)u+qLQ0-ONR_%*^)KQZMqmNhWcMwDkQ@6AK z={C=idqgrAu`+{oa4XrNj*nb>2y`AEr2#kyCpHW1Ch}j{HiMVxw;3>U=TJLiq>+;> zP#min=2ViA-K)*H3B}zv7ex}6b=>*Ot|qa4j!W*$GhSukhjdVqX+`{Wta7ayGobgn zmr!}a&t17ZcWO!Qy+3muF$2Xhz+3T^m*GyPdR6+FaFDSyBNlctI`e z(5&woKuxXrQ}rJz53myyV+wdTSE0}kK-YqQ;i#Hyzy=eI!UVOWKKj68n4m8CCxT?h zfn|%w81rWmhecBm#&{>}g@7$9b{t5kA6zTERi`@&RXhya-Jqw?G)3h{Az#9Me^GWqS=rjxmhconoVW8IMc1h{aB&wy9N$BS<`W zx?KSexBwQHT}F)l0yE+HiMqnylr9hT0-c(`k$D!$fTf3ep^zBMR)iQ6kdp`NbY473 zVsJ=E3tPe=yUoQIyKf#;w*{P{TVmh50_m0k^Eq$B&Y3L@FJ57OcXP*1=Gf00ds)r& zlO7j!l^Q8CGfhTGpZU_Tg=stsZ#~7!{=5HOGh&7SBU4S+A`68YP8IIVsJw{iy6rAG&^nVrOm~DQr*3yNyXB>N zcPQs-0j7&w0EBpA5PO3*IfC87Fk;;yni#ImfOHEHfB7uoX(CCr#3_r~UTPfW4y?ow z_>&_C$Bc{{7%4nhXgzKRf!JtlN8e)5V646nFMx(w7DN20Umw;Ue^+@}d-AZ1QSx5y zzg84j5oXXqGzRq=FD|5Ea~X`fcnmSdpoIspW*L3#f^r|I_&OekeMQj+RSBo^Jj7j}7TtB0_@AF2`I&!ii2uC&=rP6rTz>NK z>64YGkZ*PQ>C=aI@jt)D4=koZ+uWu@2XsPeZ}ZLbrarMtslWr>vx3gpPvq2RZ~GZ} z2Z_A;B<>(1?|CAxKJj~=k@vSmUVVo5Hz)7$YdpBmhsvVovS!d=?)#t38GYjB~GMyh*m+8c;@<{?X-Rh+Jl|X3^zFm)+G>7!u zW3~g_rLofy{`(w8POyd(n=iFiw^eTLwX!;VzLZL>+fr-7+&TFAIcc>{)+RO%vHeNR zKtQq^<3hIV0)bW!ypG`&3a>qQHStAaNa7eDg*}+@FT4N7m@G`w(Xw@eqW$L98E$Z| zEyR_7zAe!f?A!8EO-C2C*+4JgT$E>NvEqKj3q9#$ZE?v!Nr3=eKxbT9w7b2Wfn6pY z?;*f-MenfjmL=lpY@owuCxYwzylG7Fy%Wk*pLyjkxIcX3zm;;!DsUA>FDdKY&!gWPvd}cYloxNeVvE3~G zKK6#)zjibE8`v9m%VS^+K$;`{}hC#tJS2s8B<`Lmz@ujI&^!NIs&xMY>o5lpBcCYFS0vxv`>#K^zmTP8b8BJEpzt zXdrFYM;dzF0gxzTE2)fUAkKnrZ%yHE$iKG0f_%Xq!NW#hsrh-sUx_(ue*VmzpVk)D zA0T*tz4zhWV%eV9TKs?)^yx~d&g(E<$e%D^Mcj(RaIiLr_;e5**W0)cfqTjKtHC= zD!H&!wJp9{m2)L!wZ7B|FP8=rP{>x-@2|LmL2|dEA$pmvC4gwrpyR(_KmnA!MpUGV z=M^-Q-{+_*nG&v+ExIY=J&umRnU~0?$DSEhq||bh8RSF12^_Fv$t#>E`|pCf+(jh% z>Jf?Be~pm2mMRx&;?gA9Oy$euu7oh0BEkwfXFm8$z zmR01>1Pq(PBY#PVFbDr>k-{|lO%Dm?082&&b3bJT2s2^7^0zOuj&hb$CakyiY-}n_ zl%LfG61#1kZs0MfZ?@QD*@6St=44Gtwj(R@SZ0{O8RCq&LB`(7q2?LljCldY9J*%3 z6q^=M%qg1G32qJ_<`hn#dQh_D)_vvAk$v zpBp(W&H6T$m>&lAe^Yp{yPyBZe`bmQMBc|spI-+?d3yTzac=xK_%ZRH9%4QW{j>T% z>hYIrX8zBAdHko@`~UN!0Nxb;@9D$Gy8jE~LIiR^sIJ@kaiaq@uG zOz{doWBlJb3g8X#{~kSkyqbvrx4N>jayS0J#?M{+zq|NW zXtUG0u^{&|Q|sgiq|cujU9Xd*Y$1Ip62R$%0$+2DU396cXTTYIhrkI`;q9(^_SPCi zEcdEs{F=Pyxv+cURwto`(5ZSHoUd(daWP3Yh5dJ^s9MFX>NS1S!0qtn!MK-uMRg|L zTU)!^nnH!$o&6ua1pdA5-~)l&-Oj660B*ZPHg8ot_hMswnl*>^ElmXdOn<*ADC3_F zw0IXZ?k;HDUC_9@pmBFWHFLF4X%#@z*tTe}Myw{{ma4l~>Zjk^mPcNaA7E@+&_ z>TbI;W4rTz;eMx$d53;hPOv-ssA_Fh>qV-D|DXQrE)3p(C=8yzr~GAt;rTG{LgL+p z#QSd!iI;I*Z9TP*f+vUkZN0L0G+yt;q|YyA?AO@CiC!fO4JYb@2a&Ry)5pWCv)RS@ zc{~R?EV{?D55F z8}7j~iwPb`9ya1iZE>kmX$%?{3w%cTkJ{oNwLcd07~^bLCSwBs26Vqx`O5fl-hS7O zqjv8%@V~h7c2H53bNQlUCp>Sygmt-&pirz8F@i#|NQW!U`-%>s@H?K*o`2Y&2nv*= z^A1lXuV54f4w_Kx6f3GD3?LhWNjRe5 zZtBkd59NF~wBC|YM`twCH{H8|ZLOz+b8ays-#9ph1#Mwta}N;ZK;)iv*0r|QmXKX= zW3Ig9dQ}`ou1U5~YuBQBfs)RGcnoUC))qs?jd|X62XV1?g2582d)x5u5dOVT7W({R z?PM5{(-VbMoPU-Fk9`Qr>9StJVU%v6h4o@{_ZWc1(PY#Pfuo--C|Cl9ZRGBa1tmv( z)&`McAkR0qemLIUJbtw?160Oh&7ed3?6O;mFXAdu&VZc>&n00S2}ATg{nrw?TK$f6YXNiTm880V9(Jq&tZq7$xR4*6U3f=fn+LO!3rbGG85W*87I8i)j4dMCL#=vwNG8iFKYjS*DaZd>dHVFp6G&fOdAR!M zF8UE!Us`mf0DMM^R_e#_LnNgL53Bc;pEE3RNk- zh(6LVh$p92OecE^nsR!0BuI@%VOT~;glBbSrMmn?9fsqPdLB$bOsi+ZApUT@F=>CS zwg0^?Rd!dt9q2e>o1;O{gSFjOFuDwSps7N&dton9&w_S8#G{sBd)&PYY9K&rry~Th z1mjtsYkk(nHFxb|-AM{Zqe0{+owWz!o}WYmH}=zDT7hPz(m*C9(?&q5L|XS8TH>dH zID+Dddg-VhrrE?|??bzGQFIgZVH`P!10M_MqmOee2(U5UNIv2%ycRmw_QPM%p1a>F z6^aKS<}SP8$G3xGp;(n4dZE<=E*VB=K^yuo9Mg^9F|bX0tj@waeyL2BV-4 z%LSMMP_`lW@M?enz0g_llJ&5QVi9E><`~1gRYCTd0E=}09d;@hc?^gXjX(&hLj#up z^1Eb8^5kNA2zf;Pvns-Z}31E;;X6e2K6{i@zkn{;D{-A9VARq05kXKFo}$!l@C z#P8};7Ff4TiF<+LywQd18o{yvsltC43NJTfg)*|o^x3lhgah9q?(1)hPW!RI1t?JM$+)f#4WXHG3$aBPAb<>lnpEi`8bfo+ zrbhci0B`^YiZel1k0`Pt&P3326k9P4f18BxmM*Wmk+ivP+{I30Q2}G4eSu~YHij^C zza1XWOr%Sm9b!YVXK6o=BAu`}2hkwEJfR1Zp;aaKo3WdWM1f@|OolrTWDP`c_`fRY71 z7!0CooQA#DZ9+#?m^LSy&$)+O5)!k}7zbfI{)qkZ?3mbpy`o_VRjG4dg}vc=s-y6h z_zU>L(hIL!0EVjE+-D5#b35u4cg^={e8$l^QWxt6t!oIxL%Dm=?Q|^PRdikd$1P94 zj)G1%!hO3~fzo*qVaQW@EhmIiN;)N4DuTq0c25AI6NqWEA@(t~iY4*k=2lZZ-@J(u zGzsBupcWsZ-{#bbyFY1m6KZhv*;O-fVemTgpSoSEM6-3fX)5(Tk>K!8cKe^>bj<4` zm0*Z%w12=HFuKlT0Gc4EcC;UdF$ccILpBsjH_h9+zMV7bADl=?=|kb+DtWL9n4pq? z^E}1hRj>j8IKk)|h-!vTr$d!5EMF}s2}7Xc<|5jDC%zy>vNyC{#Uz8|sp6ITnwctp z%(ARQ?GEZ?z}RJ=#(oTYz2s0k0mW54kFJmdOGtY4GYGTjqd(Ga8fG-TsL5~%N)DEK z;n{eJmW+VR31t6iM}?q$h%N**QNfGKzbYRpJ#{u2w5g9s-lDo4x%|&^52(XT4q{zH z`3TE1?68`mPBtA?i6|GkAJQKIq=@)C4-Eopqn?1;j zY6h%``3Nv`)(hOeNU~-6$0%5AQ~{l5h(;Y29>@kDGXhgZ+pB_iNX~?QJhegND?}2s z2t^ZINCYv7Rho^uKA)->Xw$x+@_O`jx@TuVaaehHwZ%@uH^;)l9WBz(*2W3}OEu_r zs&D);(t;g2{a}C-CxM{5M}teAlZkWERU(1`dn80O9AO+>L{V&JQ)D7uT8K#P@-na& zQG6&U3}fID$wI4`ZzyjPnY_(0eY=b(P5Kz~AC``0`r1Jw0UGjH5_d`V ze~d;SD#D}j7#b9J{~ZEX=}lp6QK9Y=PSu!D{e(QM!n9;SBuIBipa4^~IzBl%*nheE zhPA{d#(+h)Kr_aCPJ(%4|KNlfimJK@T?;w^+1=T19#ef=2fMHL_K(HbPU-_Rj|NjX zxa^Li0T3K#G+IuZ0Q)HM2$C4-Svs3aU||)grEuI{8jd20Bq9JLVvP>kPo^so&u#pU z9X~BkESs_#QBG2Ztz)@6}ipn0H1CG!LtL?@cW)G_W*9*Q|&2rDFfKyEa8<;@eC zH^@=t3CS=+)W)@~rvt~Nzl%Z5HSAVo)CtDIlrWrwNpB3y(;Ihbwz=qrqhQp&xP}4~ z&eV5@$C&3fV29V@&_ID{ot{ex5ypaoSk+YXDnQBX7(g19*wTa8X1B-6;sj~{ALLON=y$;sn-G`>^Pmbk6{pr?P(m6 zb)0OUFrSSlKz`cm34rS3G3|1}kk~qWjm(X5=aT!k6pE7tWapKmmMv`B#6HxOYmB?- zWUD)hN3-rMK*B+B+fgriyguopG4~c6rg@B1?_m_PvBa+HI@wid3xFLkN#1}_b8uAS z#T1*GxGYXqQ&@nCtv#cx>zVz(Y1U=BxgvvsI)g}7dTZ-at;|j_h^+3IN|D+WrjgQ;Z0_sP~2@_fS!}$m=D&g|&UH~L)OZl;z9i)WKT_dGk z=fgw0UcV?%8E&ft} zN7?#AHuKAKI~XFnAU#LgR+2|ly=HR^wz#cq>D!I9;sO{VV%8Qd22K&>XkADcGidN& z8Q#}m6Kv9U;*v_p;#i}-Rr)F3fkP5ijD>;1CiP1>uT%9&|}~NqoB-qRIs#fAE2pM5myJrtnA8 zk%K=I=0%qI0C&@I>8Y{)5Qak-=^)>Oo}FcBTcO)}2DLuhjs_q)2V|><@_w*pN^oLml+|q}Soi1`Jz>?mCwumJ@x- z6DX2vDpxYKsQI`)qk%GJKV26GsrXcP0Ah(FU|><7##}BMf0DWK3{ebccBX3T?iYTU z#sR$mNu`HTML0rggw>#9L(i~RCFsO-hKEaD$RxX4uYoMf>n(Fq;PDr%a&BZhs)N>6 ztn~Aax#mRaPtA)ACdo{ihe!{}?l;y^XqJwz`={u9jRbMl>|G>W&oLIx6_3Jm)RAy~ zF=E3Pt6TwV1(HiIvQ%vAcw7AEi-Uu=MGXg~be&&rS{&T?BMqWf)D={teqHOoiD(f;-3NmWz7nOoGU%zv*m`tep#IklQJ!{i8+q#>ZcW2_d+TD4+ zb+q+x)lDW#MKGC;95{+DSY#*($foOE&;(Zxr9l{W*v%!>FmjNV zOvXjPX|MR^pinG(7#J?%`eTg%ZDeN>EJY=19Xf@Lb?cC2HaUsrE=SW3h+PyOifRX* zMS`}?Et(cmU%N)3_YiLpj@UYbi%`D0a>%>wj)TyLaI8g*G*vTa4yBE1$2XOZ0l%IW zipt7g@+q(+$0z-%bWJW%<&0XX@p%=aPHKRp$jiSE&=w3bG`tL;>D*Q1N`-2mnFl<1 z9J1_;>z*iu!TI|5`5Y|A*#`kVPlVGzF5#qs^C4t$$3Oo36Vg;xF=PKH%Roj+NSe!hx1Lt_zKd|>_G?myP=bq6`3s-g&D}c)^H2KWRI6^L=&eZraShy778-|BT%!2 z=f^~d`X5p0X{7134)>wa~^JjaTzdTrZ zmjD)ywYsS@dnhHol?%TY=G+>HMbO4YxI6W%ehW3tF*E%e7zm2NUr>tT0mTwHEBQq$ zlrKsqgH|=C5U!z1Atgq$NR4&ZTC7P3+ zvATlF-NM`Dg$9K@X|eaN&5@fG=yD!o$vbq|=!j+p(5^u)lPF1){_O$+^dGJ}i&v&9S|wXPP!Q1p*_ zpd}~DAwYd3$BfWAo^+)zP3+qF%zZ4rNB%Y=I|2yKZ} zURPrnv^UFeC>xmp!DJ7he5=lB=?-AYy8&i6RF)g~YAT_wd&>({-T`pM?>Y)8^95Bt zfbu2o0a7TdU=F||W1=j*eVTFXAbZK)^nWx0g(m5FxQ(89y(~CUae{Lvn@mE%7scwj z9U3fC!B-@$rmV`SjKK_br6?dkx0iw~M&FBDQtp!FHo&`cJIVcd} zv|7(q$q^4qb>Z<8Ryl#YRrkb0D3!LCM?h%2L9)7oxh+XkS^sKS?=SS~9VIFF#c=x8 z=+n08s<^0n-{^0S_D2+W=BiOy3ex6&mnuJ#NASd#Lj@5n7MTZ@{z?NX(vR3v;e?x# zhW-TIWXg)7;4+@DuD_zRRY-FnVx)v3MqoMG3(0}mT`k!yw9SR~O^?FdjJLhs+aoH) zWx%F0ZCZKIT&1v1_dS<1o5q4}z($uC-}PwV-}?xl|MhvQ<=!@R)b4H-ld=G`+SPKdQ9cy&ouoBSD7Y&dGeh{Tij`wPQ(!0JwGApK# z@UNj*gg}UK9thApm49ey=M%V0=m4&hml7Eh1uP@s-;H{9Mt+;o#y05`* zjUs6cozk1KV*1?3LKUv$cfva}l#^t*f=rUIc`>uUxe<}(C)mx(`~&TYvqUeY9A;x0 zv-~PUz{6@2MR8`S;+)Q|da=~@z@Z_UwQ}`^l$BPTXg6`K3m_hoYe<4=Et~MB!6T)z zWdFD}Yg%-wLl9RdS64nbUNesoSdIpPT%Jvg^F(5_M&euvjfK-YVm5*!h2~tAFLBD& zND|!iG?jqkp@OAux?qnn74D+l+9LLtN$kakvE!=bpHq=sAZEo*H zE79#OvIkpHt8xw+d+S+1IlhKL2;{W8qLm}P*{EOw1&OlxA)9Jy*pjRms3ieiNapO% z^!rR#Zu<8%3T-~tw$N(V_D7pGjoFikw~@T@*;I~*+99i>X)ond;I#-x%ue)%hg;U=%31{c}*Wd?L|i#TOcz+MP+eN&tPYG`(Vc^#{!d5=gM1KIiHdqG}5gZamKXWanEypFwC-*c^@! zbPJ2Ci5Ql%s9byUm-n@v49<>ehE>Haw8^LlxZfbatd}rKjLN_(lfWJ_zH2$ackX$W zk3mUA&QlFZhW93~V9L1~qqkwJ!m(gHdjx0`oJHcL=NYDdIlFWfpIyK+A*7vmc=3`^4vnJ3__xNW>wNt>EH`^e z9-N4E61E*w$&c5T&HEDvu?#L6?DvQ#)3g%=#_r;k8xKchqCXZZk(-EeW&g%ZE_*vE zxGoe1e+3i}kXCWfEWjcemuV;)hYYVvNOzgr>w+1ano3wo&~O%-q*=mFjA2TpYZw$D zaf*U3jull+qC8QtHggBs#H40pUjCYSVtXx4UU8A0QPYzfGJ8Zx|A* zTwrfbp+0L%qwQ0dgHnXJGHk-iN7XtXh|l6xLD2tV3Ru^plnfFgcI^h+9^ln)z{% z2PI)GuUUrdK_c6s&g3J>ERNNQ21u?nT5Ql5R~aQxOsZf)o$@<#_DQ#SaS2AdAXUNE zYJ`?tJ-d-l3R$Ix({bmy>hjMpgP^~*dmlH@TCmJRKTL3=L*QR=r;-CUHNxH6 zpsCYpYn<%a1dlaulkpoITkcgl!>Wwl%eeZx83RP_0GmbaGAU~2qRwy`HSk9m5$0sb zaBGeG1!wRY?Y86wxNIVCZ3c8gP=Onj-*&@eyYAz7!&SJeKgVB5^qgWfOyaLwAIo3I zqX_8wDy$JO6n(xAqZCpbAqA>Ura%=pFlXwUhZ!MNIj}?vyaqLfTO4lN2KP{Zg9Jyo z4mj|cq`zivrCBhHLrjDyj^3pr3LalDo0X2vEv<)-1IEr`~_17B*@0& zoj4mot+@0ViW|q3UIIh{n@+lAu+nqXN(^n^;M3IbSL3UuSWcAXB5jesGC}xUK6In3 zZ}48MDE&#MG$@TZx=f61-wZH?&Kor(WuxhU@Ey8+K|@L52iJ*UgT4C7dw%S;Fh8{F zGQKfN%~czX0$b?$NmdfmNUhKh5RVe8>E(#?#pu(01jsO9<6DDb2-J4WnAM=cUk zCaypqoBj%aoi@T!a0Np|mcIvQvEjapl{hzNgF>?iS2o^GjO;wB%twBSYvGp2so`Xv zK$bO~b;8IxgK8$iaUSSuNpiM12GudNt)sC_AD1!vbWWR}8i2>R2E~mIlRq#AGE%kP z+bDNGA%w^bY=9eB+7Pm%7)ca|D`p9y#12Mj4W6l4Wm2(O-6T+?_7u|7R59~riYc(# zbH%218VHyJLw6I6Oe==9`4e7w&0xeq!P}}m zD6wCk;$=y3w38F+Od~X%f7OV)9^k|_)-d_{A8`yl5}lh-!uPT6SzjQ*SfRFvTdVt( z*EBH>!`OY=7a{f#X`&(AMad>~KWSWIrxj$O%s~F?kO!vB7vL`4XPVw*u1o?oH?t<@ z9sL7rdC1MVb}*EbZ=~(Xk;?cH&dqlo6dGpmCSak`ihL^)i6+spXbPS-9Q(^3f}%^Y za9DtN^6~q$_WgH8j>gq*jG0gPpK;LE-Oa=8e&##=N$B-&_x86F!XqsmUEi0R-wXTn z%M%|t-*@l$rq{oHx)o_pw(Da~pMTTP^XvMQzJKq|56kC%tEc4fb#{F3TYdCItuv`3 zR#Bdv3Hg6D9z+;qXD4e`x%iSPGuI^#?^$7u^ zc^5EiVdTN-j#?3b`L(}j22cKOX-fd?c6x;yfP*`S!XrS~tzSyL=xL9_*Dx;hB5hJq z8wfL|W9`N9Y)Lwpx8qn6R_o_tK2-L0qe$r^L^ERWg$NH^4k1=QLAApoNvQ--Nbr&= z4T-YAbQL(4R><$&SkDQIFqGa-bCcJ=>E@J9ezKn(PZktRekQV`A`gE=!0<0L*VPKr zzpTuZ0>eb{jn;L)_3NS=rGOPEGVD;acuf{msRKCNzfN6Ejbd9rL}n#^9{t>wcCasG z%lp_pnjM{5I^Ucmc6oU_x!Gxjj9%xk&7L8x@8NgmrG#*9i}x;I_^^+87j=Kfi}3KE zqqiA3i*=N+=g%7bOLo_*l6!w+^v125dwdYD&W^vm1Bcn%jJVpg_wjN4ef*+&UUD>h zJJtIYxK{Ftgv-ZoE9As34;M2g%H=jct1iFi(z2dGo)J(fM_pm5rTPw4Sd^hmb`mvV zTfJXZkky}9Df70ru0A<=d4za4BN-;r27tUpFofXqAnRUfqNL@$=KH;4Zs*iODoSY8 zW$(W5uniw0-w8r_@5!%06(4Z;LE<_&06ge!hH?W;YK=md?|wnH|1L%-9h*ka`r9Hu zL@|tf?mS$w$}eSN-k~$l=Wt`|lBz?aY*Wy{DYD?}f|qG5bPBC;v{mt(pGYo#S?wFq zb9lJyLM&)0fUO}pzKrZQSZ00O@-u6kQ-{aO#_T9@u8iaVVGqWIna;e4i^lDbYoz$Vb$ZSL6G8q;2s5#d?!sw9z2PUID?5-q;E1eH7Ov2if1#DCnX?sH@E zCo4Urt9H}7?$r~0cw_16+(xLVU3r}V2{_OO1J+Yh9nCL?!IHOW|3%fwttE43HtK3w zQYqOSbQA8RZ!MQ__-@%sAuZ^S&(ji` z2-^FY-ee>Xs;m6QnSdleCx;)J+O6qwQxz>8*=TX?Hyo;Jg?W?Kd`iR?oE=^q-5K*v zS5s3*6{X6`=IZyZ^v?D<93R5S=4EFD=uWe=@x5B~!iQKd9qc2Ngwhy|Qi-=+_6-wb zA$4ubLG;ySQ9Ti9T%j6A%3}o>@O7>G#_Deef$7e#KAfMRn}coKa5Rt%)s2AU0|=!T zd4_nBANV zhi*Fa@Y&kzBEz^xILblZ0iA*s(e{G3hU>z^pRW3*m`V8fIKv15r^}xn!T$ZYgC_mF zgXXnT_=yG3Ast2kUGY4?RNC$&arkB?Jx_r}QB6Yr-ow_-nY?}hp&Yh*(#^S07(V@Z zl`gjzZ?hbv*B|w~;psAyuXdAIc#(mUbv#g*DKIu(K*kz{x096wER|al-3Ohu4|x_JKk^4B2Vcd&g&u z;=6N-**L#{gg6FQ)nS;n@#C|RB(OWyUyR#z@d&FVy+MATU`mZq^C(I|tKo&#$ZLv& zgOlHl$_DUoPaE8slzvE9aQSa5R7(Q!8LsUDlH=g@tougZ{{#cL9SpKDN;%FHy!GpS zLl*G;P_-8F?jS69^q=etFOU_VpKr?Ax}5s#UK$kvT1WCyNn(@8U7@!R75rn5goI~IqEa`O3`@8H+;Y&L<^FkpGF>yC{;nE_$Nb)%gu&rW0V%1Qoo3kd zIj*S;J+<>RiJGpqE$QyCU`v7T|LF<1R`A;XoN`?)yxY*%b#5n4=?a2Xyna1X`>@n| z)r!SE(abWh?BBQLudu}Jh!l%j9MNou~E2csv?G9jU-57cE3 zlcnlDv%B0K@byQ}!s7%bN_8g545auTdS_&OqMyEeePQ^dGH? zJ>vx&%>05bSj+n4Gczz0WlW!S+GTs_2p zQ)(44T&E6z`2`~kWGDZunzBvBKY~gPV42G>{2n)V`l%E|<8yl3Z2wy+zy?LZcvBb; z@mQr8P%9nMEFVJerMPI_yebiZV?IAwCHotLD4u1x#Rg^6nL2_gdd2O%*pSXVk!T@D z=YKsN{Ka!J<^N6H%=6vsl?{qO>Jo+WbA&cn=IeY8Zmrm2sOzlWxLh$AQ{?2siHa8rvOzLknhZ4BUztnpS_S1!vU7!5421ZTwBA zEWy$(AxL!n(;M=Uzb<;G;K604M$P|Gj4(_UJgSeWTlwM?p*Z|3Eq&YEp5S-8gI8Ox zqRoo9LY52mnQ}i`2@f@_B;`)MQB{edFv|j<^st-u@T*q>ix;*= z9rIu7h8@asfy5xT;0+4gJeIbXIGrJK>=ti%**5a>xAnhL6yszJPs~ndu5GSqJvFTH zeOw zgcj8yRXOG@h^uVyLjg2rEDI39_@A@mB$RJOt&f7I;Q&0N%*!!jnVoIFtK|qaO#Z3$ z>vo5Qt52{mboDJbs&Ypkt_2>$Fb2#U2<4M#3z;p!jb~DBO~>f< zy6u)`n1pU+vP1qo2ab#GCD9hJhj%jj4t3 z%=OFu^*@UM`Tto2AUj**_$dO=wc@JjI`X2!5icXWl?d!gErF|-Hd!fl2}qg&;=N$l z+AunA=p0u$#qoKO*M|7>|L01%IplS4ZIprNn)K&M!2R^yP93oTr_PczN7P(ZW38_B z6&`RcM|#v6AxxYZG?ZGB0XFzJ*w(5OS4{ra{|*B%nWqH&TLv(1&~E0r75%{dzm@@X zsY{9fe`Nr{yZRO;5yCw@8jF2-BwA=UawI?`On&4|;A!d*?TP>|qLltPLPG6CXAq zNO^4i`hDK3z!8Kb!7xpZ<+*86p{GWo#LPBb_UDYm7-rGfmV28cuk%@1cqp!}uh?*r zX{Kq|U}DXM1_841Y+U^?NaALn7iq`*OzBsq`QIq9?rKD*K+A8y(5*s8!?S7SyS`nP zyVpVnX4taY7sPUt&ODoLZZYtq`?zb9CFWy>(ONfmoJGtLH^uwLGoLm{^_Vpo4Ev-o z4>NvyAKoo1_RZ!yI_3j4AuJEQzs__jsDc#~U+dbM=+~Q~x{BUi0mcg-$6g zbs%mo*n-$){YKh1{1$EjPQA7UF5g%J!lNyvE)>c0>$YHKh@4B;E$dft!Xsq$pv(;a z(f_w^mrc+8v02YcD(Ul_-;-U)dd|};OIGQE9a+v4g-sqH`<}kOiqDz0S~^&R>%mJe zv~Bj~D1DRD$b3}|SAQB+mznv$;Z=FbmDze(u$lk$|3t&`_6m)K03>V?A@hwLA-#|C z{qh3Ics%E5YZD93-XZX_-kjBcjkc_hTwYwp57j3_RKRVP?N0f&rJmYyYX8h0i&>-U zDz#XyCOpjEZlEgMFo4|Yj65C9ZcoR%sWd_7=y5>^gzC$Ry733LPRN)!t3i`c|52ik zeVM+^;C+#mdvXqoj1Ugy$Vmg%X;mF@pTX_5x;7b?aC4ls#r%A$emdtrKHmPT_wn;B_6}&70#J0~BpM!EElzby067Hy%xV16($;u;%#pqp z_)w#Qw#_pK@#goa!PzFdwoYaML=ou#UA&Sl+W!~i~q zO~GbjKU~TfqsZdW<44glG|95!>c$$dog(}?vkP!|LV@C z)fr%3!TPLyB$r~#*_ojHtBgpZ@P4kV6*KijdoK-YO?iy#R3nWyZd^$tO+}SQ0oN27X!5~(x+85pZLs~*gAo&)ZG+G{<8;x1fPAS z*2AppH)xWASkT=g;~rF6eZyWfF5D#m9%^r#Ey|>Snx{)aGE|=tz{)|Ny}`grW*kVn zi?DiR__4tbUmi(cV%~X~p-!*~r_Xw9v%=X>v^z*Wacz6GGK%x=VMJe%CNo!%TdlNj zXo@yUaoV7X)m$59R$E@evHbhF+p2jSLEYG061xuyG{2&_B#(Gb{-pTyaEj{+=fFW6 zmK@M+N_i^@5ED)h_o6%Aq>e^;MpemC*)BCaGgNIzK|I)N%)F$irO0)t=OH8y%utzy z;CCsNqMCgz5(pM2i`b(;kwY1HiEW28Tw_Hc}~4EeD$d z78vYah{88^@v{m8W2G@HcoZbM(35m3=IK?_|7-=!uKe2y=z%xo{rg}LM$K8d%Y@-_ z`(Pc_dkd$J%lNhe8qBS5>%s%~9+AIMh9uWLynHK9w&j#|w4@w`vJBS`Cstf>iO=%8 zcLn(ITPL3W+V{rn=_RM0_#4wjCi=Ur{_bQpV&J##f2)j-7rL+G|D!VGqN>WC49K`% z-2@Ona$wsF)>8G@rUd1lED2uz4kw5cj)BfBkmuIKQZO8F;5-`n>;jGDri6B!IW{$G z2Lk;v#U9uvrFzCtXtWEM9zQPX{#a2Vm556_$Sw6xO|f`Ev%E_Lu!1CNAi; zygr2>cVY-V&*FdFLodNYYbNGD?1363)kPsQ{hZ|FDSQt)s|hwydPP(+Y7f;Z%AmYZ zONg8|Zs{A28#SsVT%9RO;ObxZa60lqNHmBj2s}fne>)$#C?Dh|sSEn%!f={HBorp^ z&T6W1g1!YR;MO?!AL>CCAEoEvf2xPL{FlOi)Wh3V(@AJ>T9n`#YYdRjV^rU7Mj6xvN}T zU}T!KX@>Um;YcgGsn9$$YD@XsP0Cs+T%wj9M5#ES4;1@hu#MI@ zF6zGUloiZZiP}LeSp7ed=tqy$S$}!L5AG0l`mHeI>L^jw7eHZN@nF56(4n(r+zMsH z99W1T@cXO`3`g)Q%>IE9Z7tcCidd(ZaR>U+2-%l4_xTxIh>ivByn|H zX2T*`$Gu_n!-9+9`X}$Y49fP9bKtD#Mf91pF8%4A$~xOM)z_-a+ex@UIO0AOv!~9C zQ8C_XA8X-J6?x?^Dtq!gkf z!3HEz2b<_5SxkUE)9D=A%XM~bujj0fOnn_@2bvB$GOz&@!TZxFT*}iDmg&O+_{qG0`6h5c{q`NGmP0_;G*U@np4eRBao z{@%VZdqE)i8yh3b;Kb}f#bU>1Jxut*u=^Uc0s*lX{VNa#?yUrk3&y=UfYJf@$XzdB z-574qey3CY)VT);i(8IpXrb+xzkHdr&-B5Sm(#P2w}PH@T?-&jgb3)E0UiSx6+_-S z!FV>ldW^C#@kwYW%sA!&TofjDCcy3Q2_&_w&;--4;x>9cdW7KV|B5raW&#e8cCUd% z=Nw`;U9uEv0T|%*YUx*h$~}P{i@1NU5{3|a`LxRQ`E57D`-arX0>taB6Q|;{#6dn7 zaxe&^ybvjI#B-_kj&OyqK;hdjpN@S6Gp9k|v{Rn1Mh?H6ucN4!^knt($heUuGW27^ z<#AJCtwjED=^sPyLHbc8Qz&ZFbQmwsbTV%)h4jwRs1)MPvoyGdQR9#v@kkgk_5@IM zwtjl4bYHlJer<@2SmS2HL8#EfKhK7WJ^y+%W@99UC(m^HX+@MK5!8eeB`cHL5*DqB zL%7leP*zxyaX2>+CxkzEwob{sse2S|i#drRUl&ghvqB1$!%lV?Oytcd=H6^-Of4*K z@LS+vlDJNVAyK?a81xYyQAs#ol1;>MjNV3v2O^N2b71HIAF`mNYL?ywA69^p3R*am zxU?(H6E8=G(LcC`Cs^M>hM_<5wD-wTbO||r!FY;3%$hZ4a6}K~C!0xg=qH z^xFBGsv5fWxHCo`^uRrBh?*}P495B8JGLQ^xRMGgk|4pE0!7ui$HWny;}x(yDwjHKv$Eg`GORyab8C)3fL-^t2>;AFTrzD}p7X=o$?&~=dm&TuaiNEtRJ z?}MhQqb`0D4z^|X`#-or<~YPr5ZD$<=X~96)-+U0%+Cn_=Tx5|(*atb!oWH#;8)W` zkf*L^M(cZ{T16MFrBs*#z*L9>X^UWSSf0WC2mBf8KBU5dFDNiE#w=>&973p)afOqK zHe0uHIRxi`o-&AfFz_RESRZdGGAXpx)ooC`DHP!oh(R`!r4gY#MsB_M3AX5jV{oL8 z=(&qhy+c~yStOq7Whr{JC7M$slNt=$KuZ_JTW+qI#UXaj-q<%xeM-bR^u^jNgdHhp zx}ny>EIohLNpfb$B>*;edppiK^tHl$KxeKmBFfq?kjI2%;UJtF#BnicqZ(fwJ9wk` zXcVi783lxT22Tq}pFuQuTP_J9Afm>(!S@l=o={*#6G5guA>+rozQrIf4?GIST5HCJ zVYqTnb4`Ob>F4LN*x3_d(NrcpVJpL5uRz$Rv?@-r_)qDz#X~`7CA4WPP8lHMY!IziQ4X?{PqFxg|v{#FHUE_=NX z8>Sbpdg0ujK!T@iDzX3s?01Svb2{xqj;79-8D0ym+=tV`G8{ICfi0icXi zEtQcoqQ2JX?Yez(^T{`N!IsPy1?i|~pJ*2iV^o=s(zVe_fJr=Amhdv8ja}}fB8o~c zLvH~!7N~_urxf;D#eIlT3V{W&j=v=rgN3CLv=XM+|dFyQ051JJVQKyr4&5v?|(f5ZgZ@IdHABm#q3~~ zad{x76;JOWax`=9gS*VT00T@joF1`oL2latA8qhn2*9d`MgAeA)?V$l^C8wgU3=cy z)GlHr_ef>gZTh5?e>DoONELItsu2s}BW<&(jOM(HJA4?&V5xiIOL%R_AX%E@;EY*H z$Iii8=v_tAjcD)kbNU*%Vp=pv;Z2`3RTScfHt z1?~1vEE8?6T%=i;&u*qJ62{o9GIM9{i2>w|zz`Y*RgZ8-S9h}YkFPXq88cv#>L=e^ zAl4g+ps8hUHu=ghD|Fz(4SSv;CB>$b*Tk*>Om9<Fk&~1iWo1D*}%(9o5ogDQZsL+|aD65YI5a)&Q=pq^@5DbGb93MtE zKQ6Yx)U7VgI}LV$r+>xk)y&1-;|+o;1hqsc>C(UPH}{Ds7e?}8aniU*vuUs^%z^ju;b@9j_EhKGt4D{qxeg=x7 zUNT<69hOn7|D$*fR>)(J)k+=0&a1m_Gt2WHY7_&qNQ0AytrWbd8OU4OSTeI?#VYVd zp;;_bS6%x@#C1KlpPaW|wJ!k>mW_~p+K&~PcQgQsk~JDRO>V(aJ9@6qZGx|p4oc~= zEG|1vq!|C#K#4F$*y{t4j%VqRjcTuAjFj`}ot-6jkF z##&ive^pmi)?|d`6;A(k7wrqE{F-zClptT1K%vmW*0~#7>}YUQkB0<#;@S3>UTQ z5~YI1#55js9S+Y)(`RYL5hXBC-St}C26)xHON#}y<7BD{0t-x0k-Ti#+)_4bvU3oS$IN5UM*qFF2|PR4M5 zqW=!58^i*3WRLKh9MWWOI*mljzbT)lXC{uFa+RHWEaoR$=#xl}yNa+_1~$Ub1DmtD zA$hRmnU(~1QM(BzCm1$coUuQ?y|gJ=op*W#A^RQCBM5OY?*xH+WbVfBe-9XH6irNl zR35}NQe5Zri`W5`j$J}e2-Df^sVZ9_X9)Pje1SM&MaRTEzC@8ICk7ubr^%I(eC z^H}COaoBD*2R&j3%LB-AqhHy4&8=Bob=zKMvOLEu793t@n|BM)galdd<}uy{Teao@ zxahMc7S0OCXru6v6cnjLG(vWYQl)c{mf=|)Sm&Ksqa>qQ_>HbLSG1_C%x`NL!G+E= zFuqAc{hUsHYJvAvi)>|I+1mrd(!kzlOe>hgBQm5}{6!I_g0H0Yxl=A0wK(#z5TZLS z`b6xMzlFn{6*bIpzM>g-Cqmn4IzWu(8u}dUwWHqMy;U?Kzj14jjIfe9JseEC)TKE= zedq?fR#$Fykzes?H;3Z=L_W#qgM5td71<=`E4+UDpTEgpYVuliW`is~oJ_!Nw8dp( zvV%l%2gxG9=0v0QWjkzpkW)^!;@Z403P=7bZ`JY9InQF$96cCcITeuQ?n*C%Qgs26 zshHcdG?SEJr|F)vo{Jm2g&@5!NRuyq5AuItax3^0ei_BvHNn5UOm5u=ZsN>Tc;w>0 z<+}MX)xo37+u$Gj`J{qB#lt6O#e285{`_A0q=>gN%=hbo^wHn&rU@rE_TG^D^<755qN6X{G z3Y{0XJGg=Q4ejqc;=Hd}dPzRG#ZXj1bPGmy^^cI@@r_J+g7#|`7s!Ju#lGE1kMHVbG9Jf?7nGx&OW8uBgN$mrf zsilkaNlunovQ=sEMBH-0=2e9YG+n%bB74sXfk)O@Ny!lIDweWYG2panR}J>OLyw6K zLSMQFx<%U;xG@@RUR^Hk259tr>twNozo2UNfv|)x|CCC_QJah$)!2vsuJjt!B-!k3^&PD+U^AIt z5RlG`QXDEy&EzswmI|NGdX#BL<5G%O9=0B%Udmh6vUvFji7!o_Z9Kua6k1RcBp6cC z%VeO25l2i9)7pa;t#>(t8c!2Ui%gSFm5oUs=Kd}jb;|1oA&I9mua2wzyE&0wc`ABj z{Bx`0Losz0@A}9G z1mxe_>pZKTi(IR#-+3MjTpK)`7I>E}x<4-F2%IMygz0v0>dVy%e<2F(IN$h>jE~Pt zIJ|Dt6c$}#;`2x@vaUwA*NDh5#;rZHLQ8vqkdq(ylfHQ(BGeFUHrkyB{x#!OsQL{w zVbaDSo;u8i-YiFHgRZ?Tm(p)|u~HsGRNB7L3>}>}X4XL^kD_6?J`u9Xe2Ds?2W1Fz^*Z0AQn2X z=yS`WZ^B9-cI8L&$StEuYR0B^kk%$-izd&7xkp^Gao9*!7Rv!65Bdwi;jLwv=l$Xm zF7QY<(Nr{=>r{qj1l;ckKPbczkeLDMVBc1LmaV8ov?r*CX@qaNyvvrXh6CfdqAf$9 z!jtl@t<~gFr>b+f50!brJwDyn&Zll^K)XM);(0=ts#-9blHQl2dImhLYo!r-vFnH&E~=61W;rA*i4zVgxC-ern8+NF4TYY2mO9 z5{JjsPGV=B`Vu>VY8)p?C&6X**QVa_9G|t@c)IeUQmDUQ4^s?9c}Z3_uU9BiZ%?(XkV01`HSUv57(r5pe?!<<+^PlTMHK9E*!K20cut<>x@>IN z*k)PtZQB^CGSFp}UG)YIMH>t2E{-jmaI}M6mVf49>n+TDGBoo!INrtaG@BCzOdCiQ zk#6ilOAXG+^l!?MGJPVLlK61Af;n4Ra#!;^&q2lTcnuk@{5&Nj7V^U;B)mS9!V8^F z%MS>oq`Ed?f;2A>mf+>T0}t0!iJA_N$$ys~5iNV{`&va6F17eOZw ztbQWS&vw+1v_m~<;{&F6of)T+gz0!v{8iX4cOSjjZK0P!?b^sRk3h*)F_b)Wj$VcV zX7PSk*cKYyz+wP+|7tw@ehE2e-(hs7Q)SQ^#Hgb; zNRTW7J1EWq4X~`B z911j6YC%b{fC6jY0wP8auoBD)bW=y=_)QbeI=hUQ$=Iy2I``n0dq-#7B0^+j5*rBu zvL(_f&c%e8rrH^tjIXl;;nnbw z3=w?AkFad%BsGc3@lGF;VLmf4s5K}1+o4b@t|BISDI9e`#@sffBV@KSQ|xWm1AOTj zGds!X=MA22@lcHV0rJeX(Rau$ptmDyU0NGTk&)^@anrO)mUBX3VDK9tqn1bY^AqLG zmAQn^FkXi^u_=Ig)NeGrZ%%jdE&2>Gj~2ccew=*Z@_&>>QQl43jQ!I{9eEOs`zA+d}{sYQ_Fd*n>HEL6VZ6<6XrVOLgitUuu6)fBhl1m zlQXGaY5D1q(hJQasYe!fcrm^G3#VTUG0&%YKD`;Q5{FVX0Lx$isZlQt1C@hgbBWY* zoP)x`X&eB1{t8|?EeNSx?V&lnGiBWLN4}3=b)QDDC^K&F8iUFg)DF@khNU5gG8gk?FiSq zFIuE>ZDlp)4`Z=5S0V8;h2%56%H;s5!9W`q8TD@n{q{cuu!!BJX`a+&JNI66fja%@ zqEf3k7wzeK+39T`?Tslv1C&wt!Hgn3e54D*BwSZ5iQqAo-gV^K9r^Rjm?eY zU}?9fRbk^jTNR09x=>N-i}$wr!(^6If9iZ1V>SE5p=gv>cA;MS;}uOdb55aT40s2S zi!|uC=OgKQj0WWB=J3>@!=ls}8UL_!PN*iXj-ZND?Qb;}b*<`YjAxEH4b~E$@dX~G zDG!&>U^>1#WFY8JFwAXcP0dHJ2t(tmINFGx|=YkB!(SdBFo?{854!h8j+I`dd>Y83O*rDR_jfOjt-xp#J$G zU4e@6oi1Fo(eBPM+j&WtK_MH^ufnE^`gtNn(g>T-g$XCk(c=;T* z$&|~UE(PDe#4nJ31g2mU6SpAAKrx1@puZKAaqZhE^z{#{3bKMin{w29{9P_-BK&?l zQ{&5&K(!kS(vE8;G_QT|)-QGUu+dCq(X~^j@YYd`*BGuAlL z_AI!uDF<*cThPHfCQWL$Qy2w9?&t&@cdrcYciK(_FSGAM?t15m2*^Jq{AI`B-L>i_ zeQ(j`G~2}vXoZ1_TdxoRUkJx{c803XRe~)gB(VtNpI-`6?*VKpPcYuo28Pj@Fd|b* zzse)sxv>E67&#v8$=d;AZkJdOAZ8TN`KDT$X z*^>aG1Tb&l6WR#s$@?ifPDJbR{F(nb&pzinD*_l?{mUbOQW_4)`-8_H++_f2vUqAC z83k@M+(InXbK>o|!Z{G0*ezR3yiP6L2h55vyZQ?;xYb0YV7M1PMpzj`Xz=>RY92>*tPD+OGto5P#03h8PUO- zdSPtD0+iMHC!d#Z^OD8VVmi&h=UZv=0#cj8_San;+4_8z5c6xK5Pan36n;%xkQ~dK zYP?KmZnF<@gshQ$B!r~KwU*@P1T>dx4WC4<2s(61Y0OzWA!GSfg2`i9rRJ?~d_p!G zOU6BBn5!L2Okb%wQiT=JO1fql88RdB`}r99Df2$s9(jt+2xZ9l^Msj7Rd)~*j4yq7 z{C;Vpq4v+xmOa%^P0T9a)|(G11pRJ_45%E`Cf9ZLQ?2~;W3P?r7&`oY zHHZL9Ql5MYkR)s(BvG3HE-iDPl0EJ(mR!%YZog*U^_Hkhm~;iVfw<1J(UXV_U0b`GAlJin>0D|EaoYZ>51+d8=x+8x?aoEY{q-YE8X0O*Oc zg5wD`(us+4MXQ38z>tdRm7qTV59hAf(aM<^&a~4?y5KG`L#vAEU1Ivw%$BM*8O6S4>5B2RQMhE!jEm#Xv z65xS%0>jQtcCdgXG^gyQ%GMnUezcF-hftGo z1QJw2cljqrv3H8;8hp7&4wVH+c;j;&Ou!LLWg=2fsd`3PaU0yCySqPI?`kxQm363?L3RYqi>j~a~s+TS(S?d)x~Q_9^_07*=0T~1iR)BAtQ~* z(^fw++lLc}%!HkOKq6$?g4st97o>8Gnm^BVC%(vr2{W?BYDML>IF8HpweM4=iV4w! zO|;fgjx*(mke}9~GaFt@8!CL$vZ~zsC&*{^9zfRV;4a_m0nc-S*3@~v0+gi-J0kgBly6; zf6H9;&u@Hme~nlp`Zte-pFZ{@QV=NH-l#+{SK($HR*CaU;0*5PXp-H^DEkRIi8%b7 z8~KHA<_kxk=F5@chdD^&Q4MHer%&=VZ)B)mxJJt)B=~&ykBgh zd1_qk|KRAPfk~?`G;gLN*pky_?c6VIPTR*`@vU0QUg5xXsrgbdu7xw`b~o$rG?%#r zUBF&7YRA@4v**_acBXGNGrWgAXXl8#0r@)%&Q3slBu+cs&xM3I1TWRAeV*qfXtiWRFq+4b&$7$25;OT_3Y*AAde4I236x(0ml(<5ag%?p)N&$BAd9tTpBZP#{l=l?NX#B~voziWNtRON9U~AL%Bd zw&0y{X#nGTAUK;Gnj8_)SHwI|bN?i9=oao_oO^!#J9BO4iW0^x^9K)RT1F@r=9laC zWtJ133-Xw{$|B^DjT`4{EVg5W(w$R)pz+b#yR{NAR}|G_;rNlcmfqW~|L0iK!D{Df z$p>H;f_Vmq`3hVG<-Accy5N2u`ju{<|8NP_Zh)qXRveb1Bs4`+2)L3m2oRbH=!H0k z?esO<`lX;g$eWs+|789a z4r5(M)%yS%Ldj>_t9faWQ_S51{){ep(REB@3x0(V?b1^=c&@Ynq;K zLGhfQ4+T%yo|dq&4+A^3{ha;HfDAZp@Lc^xa{;zcv?Y|;>ah{1SkvXTcBLq#dzYJ= z+vISyp;hKMs>A`FntYFC|6vCW()1A(opha!`gzcKfAB-^f^eXrDg(`GeXo74ZPwIM zV<4Ao96sJ@dJu0}?l!`nxP3UBBmC^Rf4qbE3i=`Ua(mk=Ace*KnHe8n2&tfy&Eata zJgcanoT&IINdAdOA@wFf^HeVTK?gYiPSI@|z-`NDYhJjy8&=7O(7hOQCadWfKx znm0<7PU%tl*oym4GPHc5f#2mH=EKA=dt`%l74}olf0Cioy?Ub3AlPlYD5RIFxJT}7 zKk8jvn@TAaO-5X%en!oLO!wo<1Tgwx8lyQW5I?6d>s{cb^uot&5d^psN{x3gzCi3| z7B^4dt5?2@#k;YtZ7cwF{XNXiCjL_i354Lp;h41(_7FqcfYTVVUAai+WuT%}CmnPv zy&Lt?9Ol*wPQ{cg;KxbFJe^hRg{)IsTLC#q?x+3kTZ8^Fmh(8Lu^*%v=XKKS?hRqN zi-;MI4;5L6RBuQL@g;2h^RTx_O0pFeGE5WKXpi&PrGq9f6y@#yKVoZ4JDZ46$hg#F zQui377V|TNZDVZctE}MjQg_x(0AQpx{`s8tfi4Nhe{wIT?|)B7@6v7v(1kD=$v zw8%B2(A1XKzXR9-TU$9UuM`!QP?p(ibhU3LeYzed4llb$iRZ+EIF*hvA*T%|C)z9p zgg|pyUjr+o4Y_^jCI!eRQ#M>aK6MM5Th0uv?DH!HMuPX(R26IkYW3a{q41RUVu_Z` zt^nr|u`gzw=N9EkW^iSYaJ}3}{YEslp7m`#UbpXokX$49`t`Z^nab`2#!m!g!@@c@ zHmotWK|?7t1*X??TGO9zrEiK4r>*3rSV68&T-$Kl;Dpn+SmWQiG*;d)M!c#08=M}` zJSI;Rr&(o+>70e9eb>!jo4*~xfN#+rY9;bD18*=fFf!>H^K4FR;lostwMv-=CO;)v z20&&exi$)XbiYB0zOnW;$cO@IQ-r>TV2sRKf0k@tVDvFHdR*r`rYg?r=YUrr&=PC| zV=leY2(>ql);5QK7>Re-!j{Nx0z2nCqp@SvT-I~(>kvkVh%W+mP>VAQGEp-c=bYsq zxUmruSjp(P6QzYe)!Q5m8#S-UB@9vuKCY(x;lF?AZla3(CO7GX#c`s@sNyTaRtUl3k^j5@M@pP>HD?YmbeP zO^WG_291Jbm=fG5nL9zYU*ENkps3MAi6?1_n1&+Qf^to}=+hmMaM7a1DZ5S&#Mq|iTj z)U?lRFoFc4v@lV^M$3{?woG;iu5Nd^!4a^xK5dfMaRk61GZt9WU8w15q5J}|n79)r z-b?GlyiIiHCxr&n!XvyuKE%g@na;~?FDGm7=s?x0O{k5bS(BpW>+Q-9)JEPY%mbh@ zt*N1dO#~%NAC1gxo4E`R*Ny-9TKDW(-l@TCS1^sH9~;YfPquzGOiThFu*zb9v*B7D zc&nIityj-~jYR=}0-$|IPif048)aC;AW<5CRy0sAqs^#g=3M4nJLCVLO8@YKk5K!_@sTI+{%QJvAr}kjdcqF#l*#DHdsx}%^Z%RYk1?8{ zw1W`}9#|ETHOvvjFcKRJQgplGVK$Ky!JDp+KFX*y7A2kkshxng5MbR7nhM=XqUXL} ztnnCxik-;QQOXVu6t?C|eu>V7Ky@kaxbAh*gi;5S2G{Cl|APz}kdFRkqIF<-66KjR z!NH&l{gV16m2x);O#SYy@EWRTfk2pib$*KBhnmnUAQ=<@Q@vigMt1Q@LFXHn0O&jV znAO^~IJUQ`QEs#S{&e0qe%~P?pf4ZP3{9-Z&9c+bYM(*IE!h>O_DHOX6bP?K8Axe3 zkgR}GiLt#!1|9~#ZNzJaJvArhbOJ%XmRUNhj5B&q&*Yci9LWD6fWS68XGSK;%s|1x z>WtBWbb?YrIE8U(<||SOjzJw)T@j6L7dgGrs;l#l(x^>1%@r4=TBT5^9jz*z3aVLv zRiZS)bn(lDiLdVWwOAg;Cy5=D?0=63o>f(WVoZKG z=e?@EE?&66el#0-Dl^St0wW0?FpuDyuA@v*n)YB#pvX#x40L=WXK$vUxCcEjQ8KQW zBh<}0dyDk*G7kbk?doZ$>3J@4hzLO_0G>vc7G37Goe@-_Nz=Tc%gA?P+;k?>1s^Hy z-vP`SI?gF@njXG%OJ)u%LV8^3?(l&K0*H{VT`UT)UJwdVPcGxfA3RYh*@%3M^~uBfpi)rE)<77|s+&$zG_$=>R7A3?OZG?v{A1 zw6Q)X;+GG_jq9-?m0{(dMF#g2UeP$I6#D}T1r%`iflX0}04cgb__E#*sRF9e)<}Zc zY977&2Qlfvr-S0YgcWnB!x0_F;lhKz!2<_al-Z3BUgFla1mcII&bV!JHbe`0gDybu zKd|v>&Ntd0Z3Tg;jkJL~SYF=i=wNfmlH2s8RMj?FqmOQjC3vH4)7(<~nFM|_)8z5w zqE8M0voD%p+jHLPBMSHDiZVRg>s*!`XV+%n&+u;iSUNIA^FfwQH3E*=Qt{3p>nQgz z&8ewo`;h4_HboBIlllemBd3a>|D-M$1e{Y@+`&w3#zgA(*zQ`R3Cv*O6BwlV$y#5w zBN+II5JC_JYPZJ&2>z06dN(At4Hi^R* zU!J?Hm1m5dlH^0h7Y(koS-f+u(@9Y~a_TM8oNbJ2=0YFvxD`Anp8~4*HQ+lZM4qCg z%SSEfrI{=rB1rj;r)B(;mk}I8;9CitR**ZTM2$T^dukrfk_@2wnyy+Pb2Y{<_lO#a z*l}5C(#S%Ahck+DuDdj2zlBUBs~=rUFEWPp1Y?di;NhPK~Px$UR@WQEOvAmJzuDs2IO*mnExjh~N```XC zGr!Q(UHYMCi}lRd%K*>NRwr$Ub-Y&Fy-d!^#F$<;P+EDI4eXhx8h5!s zQC>5q4j}N6nQyW8aiH$iCG9Z0(``Cm98dJJIK@PbbaK^V*uRxhG2kb|4gUfY$94zs z-r0HqCY_$7Pp$xrSK@dsZWtd+{8=@jBF-cW>{nMo*2O(_WbO4>;CKN>A{WQ^=y;;#C@AAnP`2_fpWR zFy~v}1ai-np0*INSAgRe615Lzo2%yLW(&EmFD_c3fM2Xdi@3Hb$%vm%O;vV}(}~vFZ}&z(6pPR_il4$?VuaZqR;&Isx@8mj;S9e)R<;ML~KRJ0ihYaM|@g1N!hT5 zX0$V(?Ocf&ui8U=ixRqvDf!{QX*TT3Km%^tQyzFCTOP$@t_RLVlT&0qy{o6JB zU+-*Sf+N?|R>TQru2C)3^+!6dwaJwEP&gq}PfIv=LsU~X=o&KwzUO=jp~KS<%4Sd{ ztiFNrbUn~26(a0q9%oP)nYF;f#3Ldw_oGzMPtOJC%}r72YbVLCTYGit(H%#6{PE7x z3H4nbRR;`BttmD0)m6iG%_Zs=yqZk4tJiz4b@Sn4$6@!S6 zNZd|>`cO&KISXOh>NHz9Ykc0pM}Zm2q(K>rW!4ea539W1z4v?MX2bT1$|Cc{!W9nB z{Dn=b3%4!B>?T<1#tNYzl{1JM%OIk#DPIYsiE)3$3?75Nh%_^a{mJJ>S)Bv9d#jlr zZBG&Gg_$23UeC`*`TftE@qwj|haR1ylN;CX6&wKXWs#lp^`Z6zq-c?VQCSWP*kNwo zvXv{Bk-8j|7|y;^uB7FQY?6i9msQyesPsbYFVfUS<4t^S*xsCZsE)v}2rlgf+*l;U6+1 z+?`Oa)dSMG2@KZ$z`q~6_el(m_S?4_D2}Iwh@Hj z{pOFt%Mz#>Sxi5-X2O_^9SUqVJ-74j*h8Q&TAZS6Jn>(ShIaE_@nZezb4# z2ieq`a(yN^tY?2xa;nq6eO@2$5F>wpKJ80>er-3!Sj`YoP}&%l7u(_DY8s?d*^AfR zr#a;XqLp-$iE zx-K3L9vKn_!j5Jp2<)E8@FV}h>HueIU0kvSmu{tM{m4W!GL^{|X=3M}`ZqnzZUB}o zma5Zzip%5DcUqq^@6iu>I9rXd7e;;xNMmq$neKg_@S}c`l1N<+ek?ve1=+tK(vR`5 z=9+j*RuE+O1WT38DQ|gcSF+S{m0v^FO(n@TW1HHbRgp+4!6|pVUP}FYa2IY!A3w;y zzLULuRQMwX7{0Xgc51_4LBGAkY+_Dd4Bo#2y?K9WyZM`&M0a`!K_{%NC|-TCKGZqG z*}TzCFe8&$5iVI<^4;dd{z-v4)o^B0zgSRkyj}b!RcR1IRRBO}`h6L!f)fyJR#@p_ ztC%9wKzc7jw>&=NpnOLPIG)`dQ-u!RPMWTtw_)1HV}$c)!l`ldJ?4w11`! zKT+>)52wG^Luuihtf3@4_ZWkX;eL>=T?4@a7`pz6*o*V$kS-d-KMGO)eXkhQJRZ`j zO@9WbPB=R_No{K9Xq{!AGe$d^|#R6t9tl4eHSQ`Vh#VFxE=WFvtok(u>kp{M#b)N_= zk~gMMGiqGy9Br<;w@K{(xtL=vruB|viVS5BGXd{zIt%3q9ZQbXq<3^24VsSXGG!4N zmG$hRi|TKlgRYd|XI1R}eP8bpnhBRw;-=(7)bqpzypYej4QCcGh(4-WDP;%~`Kk=l zSD^*yb$eC@hhc{7APqDBu~gCTu=BaIVD@z#hKtnxp{Sl5;D7rRlNPTnT&dG&NFe4% z1k56e5FUL#ON7~azx?h5-fnO-fw-xn-b&Dz4eiwKB>rwkY_Y^8q0G+vsr=%DBo!xr z800$gcnC~6$JfP0Z9c4$woz3+#vm%o+Mjq=3h;YL_)U+0(88RisjQ_IRGzpj(jD3r z0F;As$sus_k8h71!xQfUb+#mqWO5z*OF9Z!h?&^@7k8KBcefXsd}w9kKRwOSPb$xP zO0e2sk`a-erRbch1>}=T*u~M=JPs`r&cwbS6O%*pD%N}FnT6W#>v(ehE%MvB16PRN zx$NRu%Zpz4y~X|J_HCMn`2Ij7ukGnPSGa1IRD6wjLa&Xv1ZNAc|#iZn+zC?BWtoPk06Uo@Go-RB_Eu zM5)xVdwDqB-4)_#6OT1HVJCBeO2Q?VCcVWRXBO`jmEz>u4IBV+-LSFqeucClrI|zo zLKejihm~6XeITG({RobKIQUVZlQ_|dUIgdgI6TZPW)=p~eeJ`OX$d^gXOI=3g@CrBAU zf%*u6L~C3%G0s~zx8^+ncnbX#@faVcI-a$znuS zNYN}WL85Qq$4w;kY@dB5&6c+Q&Gxb9lH#ubH*B@1*tjeZG9A($JC^lABR#jqAko>9 z{tK(8+o{*x4=T%bPpnoteI_b4D?3|E851FTig=?@TtxBA5|3?+=>A_(XIc+|1!B3e89yd7c%_5w>>gr=VC(1eFL{bq zmcZ{qvGpYt8jbcFo33~>hN71NNieq0BIV2UpnDIi@w&OdyK~z0`l7yjVtsQ*ZpKz; zufYs@fU+n3?MBPf^87B>lE* zIR13UXq1M|q5k@Kk3ifKZ{P|H?i9aT9}nO0axBm9F3^jWXGjZfdj%xO82DYxNU}Uh zBgNK81g8KouiE`0daLXSu)oh4%*?D}jA_9xx{OK&Z;?yiCv{D?Ut)-H$ncT%xYc=w zswk7q3PDEqh-`*=Y*YZJk%wVXhN1Jfp!UGIBL|Ruva-M=D3+ShVW%}oH`fX*K15`~ZgjSn2(Tos#k%3-qw_q1` zt%AQtt`xh+`%eEP<=Ae^?cZum6Xb6pHH3%U(yoo;dyT+xFu&H3C2c76D(gFt45n*1 zY_^?^&G!dLaGaM$s$#gTt09VdZ)c)-*>CZ*mrzbAH(z7r-(v~O%PA7cv&S3B4=%lnXnNWyX!+y76)Z;BT-KzwJY1|AgDS9|KU_KE0 zRJ2BlYRfBsV!FIPe&gWa02!|GDNL^cWp4D!jaWd2NuXd5c!B(Hf}Ru+xP+xnW)7~v ze(mb62kB4mrfaYfzBYr$@WX?oB;;pUjPss!_y0eD-nh>H7oZ36<+7t}+OANV86^vLK7gI2naaP0nXuQJCGnQps|-c>03)A)bq^EO}QUkaq0 z^_7Fkb3^t#;N_~vCc$bf=8s-mh0vvT4AeOJj=^c@A8xW+X*j$w84%Q`zH&0XFuKkd zoKQuZZ4IeP^aQ{~{xn4{#u81UhJ)PHL@FdF!kGhgiM6GQT8Y;d@SNyrlSzT7-A^Q` z3BajznKD=d13>vx7Wb8XTN{c1m@F`%yg*T}p1QQ) z$UX3X!SgypTw)9Vk3MfCRNgT#nGo=>cw6u+HBKsrVpm>HZ{QvFGHYdub^IZsR~c?T z7LWv6>-2>+JBOA`*eDb=hG$#q#h87&oAeIR=Yl+oa?O$a13^VT*?~>ZgWbku8YC8$ z7l194;jq=)%BJe4rshDY08FPN;uW0}I(z9xU{%$n-*WHy|CD>LgI1EGKV!9ljVg1A zMRy^p`t;^ly}E$?Xp?CS{dc>!EcP{P#hXbR-I_&VCe0-=mdKeiNAIciO;p=|v3a#G z4Zy$`eYH`Q-E{y6`;J(`T}}LjXb?e&oB!4B4XHY8FoicbjZhyIZnKZ8IPIGaP0ue8 zBDD!z^79VKvB#abw9%HU1rWEr^E3|C6)((sUc8-{x6eV~_0%{2LGWb{y)eB~WPot! z2pUN_o!?IXDUHe7VyAjv6(By6W0vi;dWK`q{&jO)7rC3_S%b0z>D15PB# zrNhOkW44q6w;dcW)7@}wMbiJ%Ys>z%vgP|GOBYm9CJEY#!8X|tG#OLCs5C&0wA8;7 z)IZHa!?GF>yMFx2e|?RG8_!F`l*IisQBR}(->O~h8!F0rkF$*L(iCrzQU(}A~v2Rss^Qoa($&7O8^OIpM3Bw$q?S0^mxyP#>(xe$EuT9*9+@eE{ z)d+Q8I#RZN^1|oWI{30Q!IV2{Mwz{9td2zp0{kXvutX_h?ot3{Ipz{Dzn{0_JP$AL z0u$w1+#8wp=rEl+%ltXs4x?>1={#qd!s}pcgKA-k(IuOip*_!Du&R(OShcm7f{TYV z;m62YaN>S=_>o(3V4#4LG9V}@pLp+kig`xFLZT)I2#d-eIh@7tVjSd~ARlviJ0yRL zU1#Xii=;N^%_UaXHEhgDMi{x2$Se$wX&C+`S0#!wKD(Nq?~(zs^`$6ksBLbof4tyL z+4g&_`iHV9FbDSPeXq^l(dmvjgD|RW3fkF%D5^GPtT{3p%c{3*?hb1_MHj?)4oyV0 zqIN$HVPy9pl1{tB%ovNk{okTp+}tLd;P?kJS@ch4oUD@Df%ul95?5|jxok>G-g-rC z)jH}|X#okW2yV^d4PGclv9(Fam{m66OQ<28z7fd9u5p$iHg4N9+$k5A1duJ9jOECx zReMjZ6$tHu4WsVibe{9D7$K=zE}JsrWEl}*he}4njE1RB;1%pruFeXMNTMy~3=wo* zFF++H#9^bx-8A_IM-1_1%Oy-btIcJqJqsc8QD>IBMAKB9xphF#c31$)sp#cZyZz2) z&1s-z&pxI%vxd8qk;}`h!2}N`#sSZcqhaCnKWdEh$M}!qd@+LN?49Gm;$!u>YX^5w zi}8NJGcbUK@YgfdBXwqDz8fc>{QjVv3B#qk=VV4_yA?88lFBvzp%)BV8#ReI!S<_m z?XYzh&bf@nw(^SOLYbI{=S<5qBd-+zbMvX3?H@Te-z>ya#omrK-8F1qZ;+pUdFC}= zXcCN|LsL;NN3P*mEUkNtgoq(4yY>ukgb-mxxI+Qb%OEtr*b{Y#^*Pw;C9+SedF&tx zoZu_#S;f}ulKX;K<16(!(j4C1&SK(Wf~LIcR`SuMckvQ-kH&F}+WSh#@hg`=1NYWy zOOpd%MiH=%E0agA1D+F;egTgfU#%D5_n(zrFkQ6QOfDyZnz%HI$#yXZLcn zu_2r=rwwAm?A(ixL4jblinSmoLx`-ubceS z%lhDcg!qiUQ|x9-d0>@9O*7=R-Yo10_8}dk7m4hYLK6fO?)mW-?_T^vHHs3aa5* zJ^jUpK&NzWrL4Ye z;IEmV7(G6DyU6W6IEsgVG}OHAU*{4GKYv7JakqzlJ}`LM?|xL4-GjN3y zHMx$3`+lzOnc5{tfV;#)Nt%Q>M09wtg>mno;(my8d-uZzBj`>G?eo?9ej_d z1dPp0jgH(CouCh2*!2Ak21>{|Y!6O;hX#wP)PDz`nd*)FIw-y(@`3=5$9VrhDZ&!m zy9OY!9Lw9m4C;@8W!=zBZMgoU@grraRWs6OG^&GH+<)zBo&9l_+JA`InR)vZ;VR3t z1wyt$EV1p5eGqrO|0l^N$7O_A3&G)`D~M4Ef9%CZN3sfZ7nHKdUQH*Vb@ZO@bTF49 zmek%+gv8GQE|SU6046`&ehwYR)$0#@?9o9CtWSSu2f!|RqPDDDm-dJv*vOVoh+RE2 zZvRC%hcL4R{X1Wkc;7zSEA(rB&}{_ZFqYN=qL%GO-v~)@5*R`6J>=pAr$HoQgomv` z=T&G+b8YJ%B~Iv>jsS%=zdW&sHNKm-J=Z%O;tC=MV)mc%H@KxoKTZ ziUlKy=X|ODErgE~c~oh#w#DSy;-(t{EqWCG7R#A2 zzaxbNJ`(b=FmQ@>b1VrA5*(@blD$x{3r#MGE64Y>e%)xAT68I zFT4uzPa!hoNns2rIa8$`?HHclXx4RSphwnKspwx0D3M;+Y0*!B(4iHtPLrmg)J8B% z@E{u}Y@WL*HzWXO%JVD7>Tzc%7T1xh66@Ex-Qt&-J5gyF>{LL~VU*+3R5wh+1` z-+RDH#91Yw$&xkcy?Bq<2pjaidrY>?%C-;4dXgM=wUGwESd;NGDYdkYZ0L&Ty01j0q;|*dovL7{*a6vGViJ{+Eh6J zg>JiX5l*XiRz4Q_zbb2uI4feB(%#2bkCja@Tlsqh?&&W7gJQY}@^~c?waK&*a{VM( znWd(dIJtKm(xQS-Ec($y;DU?`?6O#o)f`M%VPh3o@$3Y%0|zUx!Cy{s(E)rz7Gds% z8~GFYw{g;5ynQ%>CK)JxtA}<}PaDHL6kpz-#)OIWaB9|~ePk1|xhPxB@9rr+hrvV5 zG&=4+{lhV3*OAN&Y+CqwkU4ORo1Zo*iz`FMmapLNY^}qw7J!0Q3EAKvU!#T?w=`66 zjSvWyX}>%VEp|&bE>><>k2Qi!wDT<-osMSMN_`{kfpjOoRM`15-EJ z&JoYcIJrh1!`iJ{*sO>YPb$^Y8C_&dY=a+3BAHVbgs&Nq4(F~>CUYh4pmpkCu%V}P zTpMETqDbI6ydU_O`iYgY7Sx8gYudYnoTk~{D8t%ty>O_r?9HsHuRWwUbi^3ZS;Ek+ zaH6B_S+Fb{^mrp_cCZ^oToqNqNZiRvx>bgh<(G^OTjl%~kFe%<08k}m{&-f^ph`E) zLi^Sgg0|}BsRjXyoT7xLD}4Afp$M|Vi*pjW933e=pnmk*J)LiJD?}7V$x9oqG#{)h z=D7Zwz&6s7$JG@95B80%kTTPEyrWn&k_J_tO-CZGP&{AH$Ysn3nE{DC(h|wx!vN+t zR4RL&lF;&MP^Vh)pKGfn=Ec-a_gXNL+^I}nVx?Swu)yGakiQ@ZMLf8y$8^aHGOB>* z=EE*7mH3#-nHYU=zAoP=o4^%T;3dx>zk+|U)X{*BSH?++h6!s!Q9|vIi0uRRHFbSy z9Pcgn2w<*9k&3x0Os-54kYT&XGy3Yz#{|8z4o;b}N*H{XHXvy zzX(hc;59xP2I?&Su7Sh=x38hz3;*jPT2EWO6I)KWoI~peNC%* zDj3OK;l?#A{{pYd^x%6yipvmD_QZPbe?|jApx@%g3Ga=f&3`7MVaEtoHjc9_94GL5 ztRG`BEfscg@qO-^s5Qt?q@RiE_H3j2bJ#=;#i59Kk5pAa&y_#pcT_I0i9FPKZ<} zA8wb1ltmYVKm-3>r)-^2 z?ldGyv#>LhWripW+@`Va~p`o+M zyW3@oZTb@#=Nc(4|5(Wyk4#0JkHEtoZb&gGXmyzl7nqjVod@9G`Jr{ zy@3rH#j9GxS9GVmphz@(lZM z#6X(KF#N+}{>5N^Gb2~Df!lWw0BTfT(1Hr(bJb0l{utda`Jk@#2aF$74c@VLFdjTv z6?CyUfBPK&x1Xc3fpfqfMR?>cFw3KD1~I$QWd1g$nyz%Ox{v}QJ$j$6mTBM3vJ4>RcNlmSWLUDD+yp-!W)8%2nk+*R5a37wUdB<-Ulcue7V zth2ClRbO|h&c?fTWeS)+Mv=CFO};Wlk{2Jt2ypE)#}a(`wY52|N(C-N!99BIG?c7A zC4}I=VZN$L+)lgSkX;?t?p93FwXuKwSa#E;vfZwjyVk6I^Hb|{`_RoIKsmh8`t%e?hgh5(%QvDOF+y9 z>bnHwsK6tM-75YYzB$6Wk9*3zkhHx_nS)oqGr3F&47k|qD{VS-@P|5L5D6o54}OXI zHxq;oRIg`}1+E2$1>VPTY9C}QM?s7|jh%ZEV7d5E+pS`M`#f3V+6JfZ^~1xuF-Gdq zWgW4Ga>)`G`;q-!`^g?0-G?lSE;4=c8Ch2q`WWnFC4=Oy*DyJ;KCY0>aiT?MXlrkWH!JWfMU~8eY2M#{hjWp*sTf zDBcg?=fS4_o9=H)D%Ej+NQ3V%(@<^*Y|bfUR0<^-q$##hMNWc{BNU-=!i-R;v2-Ic z8pxbFy(e$LbmPVEAbt3lP9sE3l2UEwrCg0@Ra5E9%iYqiFK)d|qq-W>Z(qeYvnh@i zJFu3rIXbj`l~grsuJXtWH^dS>!MnM?H)dI0ca_evNMGi9*pv!qZ!kOP53LW!-F$p;+#4LqJ+Fc@$E@5^636dUvEm9ia;9_vD+(5e z-IzEZ=PK;p&`(}&bVh<4zbS&tH5zXd+T1wJL2Jb>#9W!d@A)z1^!=K6-!O=6xM@Oy z%I=%FXC79LgpRdOtXe&ih~49)Lkb?7H@VHRMS1G~SMI3pAxC`NUGOZ|N>=z`PJ_aMo;ld>KZgN>@DJgeu$YqbQ{0rtp0T41dD~91tz)I+Jd-PZ}fJUWyZycr{EJLB}m!u(FKH zqQ8fKe5LCnWfa4SRx&TTg;G~_A8{&S#I^W{Dm8xB_8d^S3Rhy6K9@`6@m?u<7;(&0 zIsKd@Usqg=Sdk?Pnlb_N&k#)Jg9&#_?xoXKF0jL$N;`ySdNU#cTgPrtTGz}7 zraX99O{#y+0N&WPBS`E{qirQ_J7toSy}2T7lX$7l6iDHtUAYosy2%E_ZiH#5(j_RBw~>%95EDdRS=^$h#+m}h=}5}b>OqhrK0{>lF0e5g$fhxJ>Y2&M4f zfE00zmEq1^v*3alIIv?IOz@6vEj`i#Rekqg7p-7i0s5=esWRHPAycYi%G7(#pR8GC z@(5P=hwt#Rlog~zY|)Hi$tmAqORoy)$sUSVB@sg0B)PaHwnPTe;jm08sUEn*8TS!5 zbDJ$&-Z#DLPz|_rO(&b*SK*HZM!OwE@4*-@nW|vIft}%j{NA3GJWKhE& zpNnGEL1Xg~XQn^EJ{2ogKCd0&C!S{+l=${T0UEChP{FpWKPTbgSnP2PW65@84(HJ| zP1qVbtCxL_0{{~C{Z;I=LlSOKuE8whS$?;eYE)-x)WK^R-+Yf>D;*u95begWAhdEN z4ms*nq$zyq9+Tv{f*Q$c!^_!2BsqhW0BnI))r!u$VNxoFi-{sO#0riJW?D*GBf?9J zF3vo#1>T|4L`UmpOgN%m+>!__9M$U-b+{2!dMfe`HNb~u2eE-jl+>x8ii!l?P?A>hg+gqbvPVnL$vVe8@5Si zyPanx*EfT_E{Dd!?~;xy8R%*ezNt$&!*r?7 zFkv}6%Pd|dk1$b+(m7Lxo}}$kdI~qPwL4_#M`xNc6Cga329#hA+7a=i30RM1R}pf` z8@|aZ%x=aFb8IO2-MBLAP$KSTdZy#6X`(krsZ-N5IU%DR@?q6?%EU~3fb@n*wJzSG z2c~8;<0+blixu*j$gp>R7B<@N|0Z<&N#RC(jGW9whmHzlVIyY5a--5~JU95b7XCZCbIw4>OS5Rk4Y!5O=N%B4P) zm39M}jtKI1mK^!>_1lpnZ5^CNu9(*Ee?nB#VJ#0+1@oX8RAD^~6i%P}^ zNx7kbc(v_hFroxOPL(Ad(geX@zgoQY4y5NEIVZ`AcHqd}j@P=pv@=9AfUMe^K&@2IIMkD7OdYr`X!y`lB7Z6#eTJx|M) zYiklE41w7Wl#a8>9@Seu1l;bw8q0#h!ZCfxkOT|qbTPo2+^STx)^K<5vvpeM)A2{j zwOAXUo(1Y+6rQcUEymvr-xk-4B(%l8or%83dN)=H4GE+PHm%GFWFA+p6!4mtL(|Oq zKC^|hG;nHtPV@4*POtI|uM58yvO#x5dS(m*&ClmJQjlX?^t6UTq&3i?B8enA05!}Q`xJ+Of*K= zjKa$nbhg71HZyz+N4Ps?n89I%RO#6mAdSi=QQ|Y>Y$};yDdwiKzj;wSbo~o+0#fSe zh=)f9dxsPpF%hD2DsxHLC}kyRUrSJ~$8LpY_hU=rV<$L=1Ry!>2=HAB4_k5_vV-z* zbGNzWCLCetCg;7m|5H7IOEfeG8JL$G`XtcNBi`v{&U}mUo$lXs!?s=>>})l&gXl3U zr(_d<%o0hr#xN7bPadAG8>Y=Y8GIN-9|wj*H8!6|Y*V*BKfzfuM0B=<&XLwB%6x{5 z&PMW6h8!^`YDL0Lk(S=5XuH9g)qNeo`^Tg3ym>WLqp(!`_1XIUx5c+_2k+>BxXwEQ z{d$d;3=-EsV&g40IK}~FsNr$s(g>t|7gz}ohBSN;0eODyzOylEtejYQwm`j(P)6af z7XU|gD{7?z#P5w85<#(xG&>wo`A7_;>=9m9%68Q)`$pY|p zkPCsjJih_VAvWH3{vsv8gS1vri|B%39PXWo)Hk*mPGNRfq;Nyj>l7Vs2=%w1CF5s0 z!@3D4=qxu^GnBrviIBkV(MAR4lcn^kow<+S>^(o&ZEYRwAD;;KED|EOR=-U##L7!B zYPH$xNaV$_W;ab2Q)F&K&x}L6tEzp=(1qf@8b+~L7#$Ep*^o86>Io272q`HWUW;m` zeJ~Olh?ne!4fXEN&6{DfZiV?y+{Btre>gI0Fh;iGC!vqPc#aLlUPy^XQrn?I#Gt$cXKk1wprCF zz1ZA6Zn}88xee-V^r^WG(k>L6WreaxM@T7Ni{V8ux;@8oD~us2edU2S>H=TUwGbur zmi`GwTeltbct10-GfF0WD(h~I;#Pngu+tm`z||36`sSTs(K`VNFq&8voFNr1476nN z?6ADEj#XF@leX3}ML!?D9(lS3KEpEjkWq`@E4t&bp=M6BCMi_6t}5!<1O&YZF~k^7 zUA%Smfy^|s>}e2yob3!Ja2DUK#MR-lOOD8hi>_Kyt70UfTd-yY$JrftoZtY2@rmxm zUNh;#)y$P#6-mh4=WAH_l=KHOab3?0<2n}xp1UkzU(koteKClAoKp>7ky2cuUM^-r zw}Xu{6S)7#Mv^}_eYMRbrw_@o6g>}TE_H26UEiXV=5b=Ya!q@o&syB@w3OE@oev<% z2fEWK`7`#-5?#fUL-t;TT3ke5*1X$QTz^SCrMAOPb?9DRtZDmdF^wE7(KiW4t40@NF7sLyM|*B0IY&IY8oR9YOC z*=9te%V|>Lq@*kAbuQP~#BN!063Wv(2gQ$0>HN z{z|4uZ-R;!yXqnDYyXI|%yW!yFTSZ}N|-WlkmfkMk^&@!$f)~Guzln=TGkwUv=GxaQQ|>ODn=2|%E*_SPa_Ju= z6!o=hb91aw8U2+jMC3njTI<*ut*V|pLg=46qjj9gOvB2X%szK6vlGSV&SVyXJCBKy zw=!J^T**`dUqz$tzhRZbY9RIv1_cOuu12#`)<>npu`NqYL~93TA!|op4*!b3J?4@V z?;6?F6tbo&$#9d-imvdA7u$MJ;t{8U2;V8Ft^%rUvt*L|g03xW5k`Z{37bsvv|9v; z*^11AoS&EI@bCit+{V;^qi*{GlgutkaC$K6uys$c;9X_OdHFDz z)?Usd1X9wb0b7U~sIT5IYb)yv{~IVlIXI(!R3rrN(<9V{)ZRKd+EowC+0Y-ekhV~# zA>Hmpv4mB3FzQ7?CkLZl_>`a`=4LA1r?1&a?q(rrE1HHR=3?#?Ozj<%Dg2J%QvyHC zE%?#bZ2XS1@Us<7!w++L_#tyscrUq&1Md&$(OrJ@MN%;*jCBx|%GR@hmxFi5-Jqu^ z+LHj2A|=0{s8~FO5^6K9)oRQ^^nRZc@;KcEI9rQ1;}rL>GLVB6nooqI=`p)AUSuNY zz@3U5@n~L~F^zqo_Pos_!c^c+q zFv&t3Ke%|?jJat0b=`=y&YnUV&y-HV`2~E=LK&w#2V4SVm%{u|8Meu-SOww=PKo;tE{y#iBD9jO!w+2-zywm}Y8w=hBflf0|F zv1g%c*4ZPa5+G)!tW)IHq)nbex{2X_+Ey^XgJn4G!RXlk7gO7^RS+G z)$UDVyud-zOt(yDOI)`A4Kn9V5)>=Qy$d;~Q+%`VjNtXUWhUUs6)|p~nx+wg;Rj)Dmjo7|IVO_>4ZhC`$~}dZ1C6uf0F*`l7iseH7j5+o&_1i- z%ZawLm1A1t^CiZOr4nN?^G?=jWSYHdzes+)a?!&L)SSKERH^)`&Ec*Lt%P=#XOi&A zP4XECB^bHJ745koh8f33 zLtlJn2fN76C}vl_w}P2mR%Jo;^(+eO~PsUWpYCW0ub2>Fs%$TrD&!kA2JTFRN&NMroIXbk-q* zewcm>>iO7Z()AS?k1GbUCWRv(Z8!iwizBx(vJ?`V%e%Mmhe%IVH~C!T)L}xiWK_cD zRYHOYcsuCHFhLfiXJ*zA^v1+rM}f>5{#^T~62L^T`D?KM4}xctc2_Pq^{?7f)gDecJ9c`zPG>7tRFU`Ui+aP(LRf=uG#?jn3omKKY&by>yfQfbniAF` zr}Hl@rfVVBgfiVLr?!z6ve77+RIA*vtS-Jlnp*X!pT3ILP#`HFY6#Ke@%QhblXAd=|=BMJCG0djvmCy-F|}>&(3DFV@5EhSyX)-JKYZzV}>@ z5#n;^-P@4%JdcIWvG}tZ#gRYDRUK1N%A1k+MEmcljcM=RhqA-nI#2p~tmHKkH|+$A zLrG3HS&>g8a*o6|P4ZG1Ni$-+OV;I#zx6<}m!Kt^O_LFZmS-QMf_t@+K3e1D*D;wn zM!tzIh$l>Xu8)F57MjzkvEN25Ovmfz zLs&Plh@XRe&g?CMoS|pENOXhc^ziS_XP+W7ki=X+($EL$T-rFq(J{w00(daiyS6b2 z$A%=Fo3n+cgeP>fO}lsGlWuQrU!_9E>NvHzyps_S+r9Zw>lOZ86j@a8*vuh8@5a{m zZfv-LVeci+3Q*zP`kmZ_HB$-58Ag_~G1zfM_iOu2I>B{Q9?dZtRuTT9BU@U1R0 zChpRd3lMC-r7zCO#7jDPHa7Rd<>$qh)#EbLQPvaYzVd9SZr#mvU^X8;Gj5ix(Z}Tl zN8;Y9N8DWLTc2d+%9Do{QX|D9I>wc6G*A13-9Rd{05FuwYP*r|f9JN7JL_;1wRIT# zIML108a=3US-`8>%aW|va+Ow`{QNWaf?2zLId;_|{_oXc?!l-$Ze=g)ApW4xDI7Fq zRLMQ{U!8_$xF|*QE3O1F|H;Aj0Tqe{y=(RHA{?j~gX>;UX_ofnm7S;7q930=1!$gi ztZcsV$0+^UmrTM^=U!*xu6I=bwB)XDj#I0e@5z_TT_OD(j0S)|d8vCJ-oSGB4?nM* zJxf5?j}i%6!Jr-Xl7;zx7vi$h8uSOBF{4Nx$$G6HpyEk1=Ed0bf`|u}+wMY5qt0!L zGR9O~kZ)e05rY;l`aY`D8pS$w?{`Vytu<56*ANMt=sq2T-wTGCyi>$)T0PAK`PsP* zQY5Q}n`SrO?sCq70Q0ov;HYyf8^cbOia&?FHVgw?M&oG(;y-mh3WgWxEu9!vxN%c^ zJ9s-NqI>=e7=2*?)MdMPMFr}#7YshAQ($Jm2LOyizNPLg41niD)s0oB8cQ@-jzU{s82%`O~xPz0nZ2v3qZ5`GXZ`% z4RuG5p=C0}=>LR^G#{Y_ST6 z&(fSW&5BJ+KF38dZ8!j>6w2A)YD+SV1q2xYw~iDbCZy zcs#5xEkOtT8)zKVK7^w|*hAP$Uz|9Z#|@KK-I)#!&Qd6KZg7@D`NsxlDLv)XptUcC za(ODxUNc#F6ipa%iLBl%aAu8^Atq6P?EdNe=E52;H|;BUnKSJG(+T2ie1vlAc}|Jc z)_~awuqP*PF1V@-uDS)M*fAsLRDfp&u)YFhS9LrGoF#RJGH7c%>t0QUEv*mFVpP-@ zpNg!&1Ab(qY7gX2LcKlACbd7-tWB-)XRZ;ocWcVcC-?7XUIc3HIB}Nth}?q*w1!VK z*tz{tXRKBo6P>w?1;3Q10U%|_6QCR$1CS%Dd&7Js!cS02+1`}Xj38ydiPbaaq4l@q zrJw=O!Upt7T1Y`%M0sEn3WXH3D^%YitVb>#_t+@kz9CUz$MA&jdIOtcw-C9(gZ55#B45$7m- zap?npUE=8svtN3UoP)cvU7CT5YmC611u8>lCNC3T+qsAP@u)IaL`zY}$?P{i?>{r7 zWSD@<{73mrG9lJWforWgK1q^SAwxuCJbrD8f%Cu0E_itSwhp zmP`t>1^=#Hd`2DU_5I}0BmBGa^zjP)h5soXlO8^O^gk=`XLaT2(0vdKd#)S~R zyxf1SULNkM%hlR)jSNv!PRswJJ81VNpq4%R4d-!OS=BDq#fjee_|X4KZsyMCScV~f zomLwMeN~P>hjM>@G|5g@%w_YbZrL3ER2i_)Y z#wfI5T8W)Q?+q`7xBlFe9on4o^Ke`)Kh;vF;a6g&`XXzy9&_*CXO z(og0d&5FGtv*O%+i52(uM+lyv8$YbywevN;Rm^Tg#aX;n%)+c<${9eBIc$WW%oz_{ zCRF6;Ma7^t%K+PUvulEKvz)%izzPY6F8q>yP zT`WUr?vX)pPqal;?bE^`lqTZ0?tIN_OZxoNWa3x=wGLGdIPjdsPQ;0$GihKwnwImW6Z_V~VK|0>I z4e9T=3=t&gpoE_E2Tr+)N=y+w3`;4{957DYRttvnHaMr;@$HnsLh#qYU=(6Fo)i*N z9X1RS$@#{`Up8!ebXrvGEgG35MC~o*p!3cL2yfMuhIWlH11fz*mNVKM{}W+FnQD#G zT8bCvpc{uh9Es0(&Ny86_;OEnuSLxRADPyBX*Ma5p*x^+XvrM@i4=1mBu#d7YOP+-%qKjvKO&qdw5o>}VN_I^w1)BZ4!~em&*^DJuHlWmceEDj-L;OMSF{ zh!5E%JnO5aOMI!99+KS*CBlZazUc0{TS#;LCj}{>6L1Da+~}k zrp#w_H3nCqq3Ke#>D6_aP;oM;&=>pC$u+{&HUp`)TB* zR4)3%e%b6tSy-@+NY*y36~n2Oxa}Cia(BEHf{yj$VL-eG9Jr_NIytZ!~fuf z7)pGxA#$7#nW0)zi@VG)PYvf|I!=-MH5F_p(_X^US0g#5Fjyk;Bi8J3Is|S^3LJC@u$%Xcc zQRKip7RA)Q~n-DV1SINskT`*p%cb{7B&1()PNdBAd z9!f}~KYKwfSkh>fYsQ*OEr#rwH$C;W%>0Np)#&ncEKunh=7Toe~a1sm@78_HJa-JNHb#BQtW2pz9pj=a{U; z(4IIlB@!o^jdV<$-*qJ#r*CF5MP`|dvp3#1|FDVs$v*+%esSEL-DJnda+(lM%g1a- ze=Pwr2JfPKLe}G1o&?+WPR-D2vF&WVdHLJU4qRdYs6`#dfCQo5Ok9*8I}JDF zkv;vDG1^u#(pG8s{HOQc{|-O-{vSL0$0wV+yI-J=>HZ%NpFDiHivAzVPaZyb{ABs* z|17UOe)@Fz&i~_U{OrJV8T5L54q`_xc%U#Bi+MkI+n4Juvhv+`k1F{4G5vl*zrU-X z8_6>LUZLNs^!pM0eq1TQ?79b z2hgrzvgvdueN$o-T?f7KHSQ^2b~|`ffbPAJwigD`7!O7u8dR-*AITYr(Ph}FDRrVz zLSOgj?2O&d<7zjq6m(6{*ikTms_^sxAo2lZE;ROe5W^hmc2Qw1^+PmyKI(>Nz3U30 z7=z@*BQE_u;1;X*wWYQkcY!5pKlmWOq16OY+}z%4E-+!vqEW#s z6A!~Sb`~Gs@#;OsQ$6w;>#m_ph4&(|1S)WaKHAd7yGr^Y*`9jZGf9pK#E_{y!H;35 za2i5`q;);0ggZpGGJ>8x@H4({drZrpfDgSS@h*_}5XbQW3}1AiPjS?A#{v`2S9xR- z`qfY&p2Q1u{HdVN+KeUx#GIIELVN+ug9b2qBrPT*ioBqEL1Y=7{VGte=?Y-!v*4mG zC%;B`m}v-{Tmo92O?u>`4XlN|Lkrk*%An6WB$T3u9(H z80Y9YIHbYBEr90W(KY~!4TDjwHv{oFlN`suqC>n_d_Z?T!PkDwI0o%@7dskSiLHkE zP)`pTNjwQi&Y_(tz2?>AIMb;+6$@#8J(o=02rw&62{1lf=lC5l(Bed zU=;KX8wZndgn1UAy>E0MC#ve6(ID1n^U4&(0H81mX}ZE8?AFEf3eYVcdJ^xn$N3mI z%&E{cj|KytJ^Kh`@L0)CX3(}e7Fel4J)H&J<5mPZ(!gQC1rW#4WYos)?uhzvJq!!v z{^-v23tX|hxgdx;p#38ekc_udN0Y%IAx>1E^t>_Z3xT4z7(mvaDL%%Cvy=EFLs!gT zh=clkat;T3kIp;tF-0@!@+nsu9{3e7A}m&G>IBc-yhjaXA!ig)&WANQD9IvxY)Uau zDvJUd^{F`QomEBZpk$(>!6+~oVQ+wQ=c8P-BjjJON~oev1XJ2T6e5&JFn@sJ#UkaA zi@DXU01K-@g_>FUpdzA%20@v)Ac^tO3W=Ucf4-oxPf$oI4ge}LKFnrUD*8BJ>4@$W z6(%ghF)9b?uEE&jfm3@59~DwShZ{&|jA0B+dclanzyKVvc%T>qB!T=!4lht9;)#jL zSWg#-4VOpf3uxfE5bAMm#|b>A|6t+r(8og%`rJ3>!Lkn6VF zdJ(SzY7B%FbXWx9C2^f7j9FupK7*=hLa5o%F?RAJu{5oTVnVE8fY)+i0uZb#sto8- zqa@|3F1>L#_&n8PJ3E$#8_ybr)><5|&EYT;E)6YOa)?}jAcleDLxl>(Y&fcNcIjJU zGdYnT(>ZV&N34HIqhyk`lDPv)Ne?ffjO}ELiU?l!i_bVKUSJ3b)Vjm5MhDbQI=u{y z;d9zXOaK!{qYkSM&cx)9vmNw>#x(4B3bCtVVuhzLpT7Bt*YK0Hr)GfR_!$HE_@(TCV_ZbhM5r{wHEPZD~J z5Z7sj!lly|Ea~wiyKuSNn?%u~a>1XI!nmW$BErqx^wA@3j z*+WO)kY?AoiBKRIm%0xUbrcs)and2Hy0hFB4P1;Xv}4VxJ0&|PLGxaL%qet{{1k@) zBz0XBEw{~ETWjs_zEfK-b~j%huT{_0?#^@g+rxmfSCoHo9}NN9v~&eze$vR)>lJDN zEr5kwrr$9qMl#t0O}z_MtIZKCsc=gG)vs(e$l{7O)1@+34qZQ><#b}- zL|s8H9rl8@p053=M~7Ys9AwQzUI0zU&Otocbl5;-1se`(lntyvLMBJIF4zg|BTWc) z4UoiyR==draKEFxjwlsIS`L>}Wi~M&(K6PHY?LFho-zvVv?|PFkxNaJGy#b<4n|CE zLF|giT{xl!thE(?I@~;YRs8?id((zCj%5M#ePw<{TXuqkC9!!61P2VV%?$<~OX6HR zS01DRbS!BUjbzM8{C@kZt+!buft}^tYfg?ly;pZvS65e8SF!YtSHjP9Du$)kuh~%% zCJ_$k=e)BNO)gAn;7tY6HfFd4=v?*ypxZ+AN*Z6>1p>=_sZ(_UqSB)&2WlqN>9~fvQo$dO3_$H%fBA#`VDa$;CKC$+?Je2IONUqM0J2 zH!M5DwSy9IIHV+2I-&V6S}hqobWj};2d3c+X}u%O3hbHVUAHrc=h@*&=iH#Z5l#U@ zdKWFIVwFdOS(b0)T-7wQARkGJ>olT%dV?FhTO23DMLgwn7XfHo?(#I2X&b-Pb#qBN zQB@GObDV_|veNus~SYY-E5DG}uXD$;CsdTZv2!P0v#9X2u}?Pj^5X6SqYLeM_S7dtGI?%2}`Zll8Y*-fb%UZa@v+F`8%O{dD=vRrw9Tmv0`^gt71m|+W<-m}SR;RZE$FeXMSpWwM1281kt`Bmc{&Kp;c zPcOnmSD8By>9Xw6iS-zRcH2JUrC!39h319(yL-R$fPR7rCTT26P%U*w!I8!GdA8;i z!f3R-t0Cd2LxX4vi;T#N^idl0R)!XW zBw}n%BXyv!foujJk=Ieu4d+D?|U&{n%G2Xw*Rhzyj#H+^P2)0!kJ#5ou zuN8(bhPP_U(S8OOXPO&-%j zUJ>1H;0cYL zfyUx)tA~X4TrFC`3(a9_e%UnQFrrbAJ9ZeL0n8DZZ9ETp`cBkLke)K|tJxDcCNMUqBq6M?!2RyqWo$$v*z>*485zg47aO>K z+7p%su|qqJ;}hBh^vLoe2=W(!lI)XK0dlp_Y2a;g^N3+wtjt3dv8$OF z@h6?NaJg8%h8MGyGV(PpN=!yWd&L1~w(&WAX`w#NtmQOSiqi~SPLrBSvu7xaw~1W+ z#_{QMOsrdhnBCq``(QL;4GY>6f$gLF@!Ipo*2(En!#%qN9_z=iTy}GyZxHdCd z4<~rLYxExSK)~^;i48RafMKUO9>oOKC^R!`7yWT9On4Z8F)3?;`&x7lFnM#OsSbnl9m?eohQwngZp(Q}wS8NZ>O@G8~}2 z3n`(GJC~_uyBShqX+E@mj@yfk1PB$+q z9y7Ery`Qn+C0xjdX3x`dpQ3{|kmi?%wbR#CuhngIgm^IXtBWsAH5A^Q)D}1q0zkE6`@AhfA%D!zVc|UHC-p^}2Il6-h zlOUvCghN!DGZUdEOavK}KKE4eVBf*x2AsT#26o~APAaGv?2;b1;}|dz1=g%MgW@Tc zos3&&^T3$Wg>j#?Gv1*%*T{M^iXlMMk-x-K`gL+X?zi+#B75t)k%JK%)~7>PASA)a z6_9QE5CV%Kj37gUawF2VG=c$EqcNZcK9E)F2@G(P9@aPAYRuvaJMYJcCZgSIg~D=- z;j1e+r1M3~yT!9O9xdV=!B|yM;ntHgv5w&lmR8=nF_I{^u^>3MXLziNHy={)m~eHX zx#VF)d-hqxOTy^9q_!^Xk5wQGa`q-1b7GO&cqP@tGp}%^bae|$tVfD+p5#8DEdVbB zNqOXy_s1$8uE)KUG7*j*FL^msQ7PJ7ns{f^^n_wbcK0>PMQCk(JaV^GQ3(pQDv(M- z8qdy1cb@f55ggME=vI}l?K;dcpi~J3v>PYC92y1(mjna}f~Z5RG)fCux#5LTc$$@EYTKbMB zM!8!>d;PVRzL4ZYfM}cRRcaY^zT1|GM#hOAe|qSyZ(NWqMl=t!#Gfvpv=W&HP^wN6E1>QG^zPjZgvQme(teSyy5_Q_@Sg3@K2j7lb-DtGEpUD~80 zI-(iYrvYeNqD);Q{Z?ALvN9`14;QQEaf1FH!`6xGN*tkN*_*r}K_RK$njN8R_EMAe zbWsRld1Ir&od9L<^`%p~#F$}T#<_#qz&UMN85N&Qwzubz&Y;d|leEM6!23>QsCDmB zp&Q3?tNM-)c8dh-qSrptqv&IYw8s$j1D!h>wTkoNaeZh{t~h2ylC}@_pYOhC9`Bw2 zqUNa~=({*0rxRv~$BQqEgDrgaf$Z>_QJu*fe(a%0zP;i>Rw1B>u{9Z}A-15&k6vL5zQ~G}jYj5|4SYG%9wYJwc;*nTW_iPM3g`W7d1IKHIq=r}ZvTU?7`>l|CFCkA4r5>kVgIyZ=8 znKwZIbPVUG4^eSDZUbYU)zmAgc~NuBZ(H64al`s#K$mKXtvAv7exz|A_%@0Ms*4(L zRXNVn3bG*QSLUc(ifbVK+^)~6ftpzGsL1&dhvX-35U?>x#9=V#shzu|H-NOrwBEptSfoi~!9qcIBB4zPI7bTis45TVe4_9j@ZHaVKJ|W04Df z{wCGz@RK>>-mMnD@a`gZVO=KV|IQ*(Vu3R|>0`-Yj|X(cL~DW#^%{xMFyeD8@%MhO z%ZL;}~B+ z(chHy4r~mMoFy$hr+_&S($qaiIRTpImws6dk+n6eXY4BZX@!oAUnl1zk7aP5uZ>Wz z^uj)L$iFIO@cVI%c{@ai{=9h=!fU}0X`X*R>m^7P_N z_^{ypKmD=)hsP@qRx#i5!$%Jv|3B*C7ioRU-~aLV|5N6_(?bIMnP_nH`G35;^5EunDYO!^zh-Mul7Iwiod_Z|4WWrvyX#b6D>8pL9^Yz z2c?x21^+!%%cW{is;id5;m7a0@O_sN2ZJpPK3RRT%)t!CsE zR{QKx`{5J>yqohUDPef`%=v@B%~D!tXPMesEnNn}Gp5*f{=AgX?SJT{r2b|~x$9S# zmr@MDpO}&}-M2+rw3p^1?dk-ieX{ByEe9u{W_as& z9ZGA5*CP|zlzL%GahVD2m?Q@_?=N)w*MCiRDybY z@b3QoDJgvT3ft$xmj1it#!heS{$g}Yclm3||BjUUY$=n_5zUtVJ;bqi`F~CMk4s7a z-4Ywg7faSk!Q;X^eLQ+``|lW# zdff|C;R)e%{y%X*uA}5{!jQTjt~=p6kAMx=GXwbL2ZY_ReSsCD^n~iLKwCFq4epm& z5$XCe?WN(l(Rh3T1i8(Ce9nsblLiD$r~mnDrCv{m{h^T36T_40OSN~qwSq&@?DRi; z@!`mXl}d+Y@|-YD?S$~8`X;x3gW+%`Hh(T9t=E0TpN0*S@@MP&0@#5HeqVrQ{Ktg< zTt@}7-T!Gr&GoQ%i#8_T|H0qNBfS4xS$T+t|MC8BdHLbPulIj{#b4v~$qW^E!vp8{#PEXJbGmGKUP*B;rd^JdZAW5jh*Rw$|oYM|#UYTPG_9jLX8I-yA-5Ao3}2xK91;-hjEN@hIXH>){P;ZyV^W!L_Rg} zA%p9?;F|9<_`y)q^=j~me2 zt&@YJN=beDt!lNk9mHmG+1%MW*%DxNTt(Gds@79LEZv-kM+YyCwqE6Ac5@wXAMGBV zeazM zb&N5p;&QWjv7LUfwY_(+4RF7DKm|wfpsBNkEqdNl?>!(qkYKa-pxKTFNhZ7Nc7PGb z5KNOlr=AK#^HZ2p7_6PfVPk)%vA@0BIIgI-!Q8#Fg|HIz-phnTi%Av%+JQW(apoUE zqyZ%$<*C_X9Z7yN8lRu*H*uG`?Dk$`Yrlz)7LL`1A4x0LB(co_{G#FagOUjVaOS3> zgOV4+Cym#;`_B*P+p?$?Jux`(^0^rR#=r+f(HF$LI@vm+2>ifsbC1mHa-0Mx{uej? z7ah-qvE=E=0d|(c^3AbkFgI<8Q;?47c&2GvKmSM(KmWLi79!wtdmF!CUSA#TG&n*6 z5N|-*7I?M~4=H$fNZ&SHz9IJX=(us*gzi(k2|>#1*A(^oHGS)<=!;@pAWVo-Y&-G| zvA?{a+5VZLbzn2tX*{Q#_%DVI@y!E;@e5*(e|dF!vP%=EzajSY)#0<KJ`M_;mx&h9c-|GkC6ZJm(xQ8Yd@`MLr?!uyI6F zO&<`JB3!~!r%m}ZahjNKx?!7Y3HW9z%H}cTd()3`a-2XouP!fPGx(8LCu}{(jict? z?lZkHVVT0j&0uc_Gwki)mzjF`gt!Lb5&T2nP*Q^MMKMj_Dh^Linnwo*Cz9kwL7v@b z2haYCYvoUh(-9mxIXKvp2>isj!vl^uJb=)Clk>yB5IS+|JTbN6szdUD(fS)=e*{!) z(uB$<#PNc8g)3#B26g`xel>P>PdJ2Mn*r2|7>ZHyNpXTe`~@)@`U8fY{(1Dk#5{Vi z83-4FafYFgkLI&e#I%E>6DQS1+I;(4uiOeKY*P^(_FuT^9Ak3;QA}4MQ8v%%(Vm+Q zL7V2_Qz{DcxQq{HabqCIkFawP7E-DSxhaU5LP9c;UOvq&rlK|jU~C0P`D-&cZV-aQ zKlsi3CP!%AlU|)t6n;P$7Z!!_19(&0Z`0pjwwR*hzYsDDNAD%!Sz>ltjCaGF%B+G; z(`+w(ySubbcjIg>zYZG%Ia^e!;yk~N@wJK_g=dp>V&rRnX$k95q8JH9ACVx?kJ>zcL z5TxJ{L^o*y5|7t0UYd@8^idNTF-qaj%>Yd)aAy93n4FnP$3d?5khwXaME=|i`Z*=j zahPj7OrpfeVZ%0+>`G?x*x1b=Mte5y;Cm69!JvIE3H-GgSk%;5nSX}n9C;~FBGHv5 zROfFweNM+guF(SruWg7^OgZ`943J>Zg(60q0GyvKQB5>eWy`bfwEHoT!|XbGw@I!O zgi*(u&}P8Kee5c7!;q?XHD{Tpb0;J1a-Fj**IPc zazz4bsz87s=Xd{DUkTqKDnb*>0TL`7d$A#2^K#I0V*o&)oL(q!w6`CQ;othzmp+5bXQb6SNAs8*&Gzw zMNmuYD(V7=XTvCbzpl*~|GElzos*Ci%O!WMnD<9W4>-?cIaZ<254$4)n)bz6>ZMB+*ua$Pp~e zuT10*cGecWEOzd0J#TuLZB^;vP1Q(zYsDB;5lFCuV-|Ma+Z22S#C7R=pxfHgpw7S{^b_3hj8gm$KZwBYaa zTF9$$EeOynK=+zl>7apHG|;vd%+-cHT>lI8ZX5);iNkYM#|5RD_zN`r0w(DM+70jr zDsFMqHpOjAB)aTHwscJddnENklE}l1w-$qqcZA9%v-V2r4~5T2=aa=Zzt-RU&%JwZ z-!A;R_!j=YUA&loM_2@-l3Rx}hcnfK25L6uUFh@zK+wtRShDesO=z%H%zO8+43Tka z^xi#8!Eir<7O5;YTZ>dF`2$*Y;9UIUkM&W>(omDf@6O^M>D7V77+@kcuq7DiEYVq9 zK%{KlQ*r(6@)4Texfc+(yCQKiY} zE#xShxhuD8Mjo<~?U3Cn3q`+>G`;a@9w{Y*%)H5gn!hxB05Oz^d_AOCKw*2&H( zAmluMbK3o~H0N zO;1{)n`eP>4K^>Ov#2St=LBb2C_#*j?IKF`Dc-?oPh3;6@ow?Y>wr;)B;{^;)K?B0 z1^plERsSN_Va%`&hj>SklBVJpNgOtxbL&lQ8Bk@W$q1(qRieO?FLrhvHTe+Kh!zRU z`?RXnwvY_@t_;{;0f`SBR=7r9=G9>NM_G5?fl-Z$sNAZ-Qf1XGHvYD;hmTR;; z9~h)Yp$2M~L-9`d&)Vwy$ht-?{ejuI4n`Tgn@i ziCj;y7Z!XXzWzQCaJ)(yqCDf>r8w1fumbR`e!s#xBY;DVOG?ToAbsJ9p$7K}}~ zS-*mZ;N4kUYaJqk=Yl&yG*W>vGiP(XZKZ^JsV5ECUH6S;KRd%xmS*>8(yL86*-oY{ zWyuJT>z7j9UF0oj1Jrz0!~4^bT(Zk?jAWuFAtjdg=Gb^Q_$is7|QGm z>rh}Z4ay_T+T21-8cIXODMF!2M^??=BG5|yj+>dAEWf(AHE8<2>Nq!jn>Pv35kJeJ zTfjscUgaUk!Kud`q`p;i34r>lWd%x$HIUjVmKfbIkF1Qzoqj@HK}S)o58FM~p^F~w zS9kl)x8e!3+1mZK<)A0YD4*VsiOmVe#l7lY-P&1K z(kdaRM~q%xba>4}t>9f18{evZF@Bmer7mk3PPw^AxuI4D`;HbfdUSeb!p;_@P*xmq ze%qF&D{yi#LvB7d;t0$KK1xj|?K0l<0I+JA|H6~~J)n*kHN*9Vu*gyvGc~ zf@gi3w~YntgaJ=Kc=virRgC>FgW!^H$L2Ct^?v*M`^?H=l<0Y6iCMqM=Niy~cRHnj z+pM)GkQDM+x5m{|J`h%#FGgIInx#myLN-5lUsr%dcfPL-Y7wYsboiUvkA2M~LI$BBZDW6jR zluy)JX3Mp#P?%-gI75D({m>~p$3L^c$G)vr8od8^x{i@1>u2a4lkkRqpcLJiFIU3X z2b19dcb){u0mM?w2~RYjS6O9g3F+!9qPUyALwVc%MW6=1{Cw^p#2!NurRfQn48VPv z1r#@%p zuZ9FpKxSK%rN&SyH7xVrWQvu!BO^=l-QL>ae8n2qcAk9!5a_w>N7#Rx&d@7#pnOJK zGb^{?Pu`)*`-4`<gOf+bj}ln^(zBDi=D zqxhEx=8&{H&W8wyWtY75`rQT_93eHe{M*!axO;_OzrQ3IAe~z_s-)<+YmUn%IG4tF z6pZj$JiL|=!G4`A#6b}><}F*NLtx3*d4&WQB(R9>iMspPbPEB^E$TX472UH}NlN_D zHuK`u`@6hLP`cvB15H73^!N9zKx1(6OCKI&06&Ws(+EqNRF5nk@SkXFt6z4qe4$?5>A}MJd@fqBcLC87!&jtosjX|Sw-{-_51XTvoBj)!c*oX-p zeTty>zw}6zFmRr_2qwl0$}1en{TNp=Z{vR2B5w^atE5VNV^2t?D55}wU(jmPMu-}a zhQU(s)etjUnqx9b1YQw+*d$CRrH(X?fC-jxB0I+rj%nPT zjx$TEg?B?a=5h15|EL2IyyaM>y}ck$e<`ZW#`Ku1&9_vVyk7?q44uL!E~l2BgtTHC z(5w!@*wFS~=zy^32+JQGV(P0P?C5!5J^^ay2K~Aw)t{& zw737Xw6e3?s@gBm3OYV6Uh#`p;H?LGuh{ykXO8JdX!K*p7vwhy{d+bn92v04;5iEb z8-c|&)xJ2o3g|LYp97Ns$Nb_#ePu!+lSY=_E7Y&%g{w&)Gg*zUDJ1s@vXXD58lRxG zEA;_@qt#pZ&D8 z8LrY~4as+?SYnhtZA%oyjdWOIc#uxDpSSZU=DMOi2**Q_pADPQ8Gw@!tN$)(H3yhhj~BoD-w#OUYHnO0Su%ZU1; z?a~RQ9#DzvA-Yl>9U4!3JwFmGIcyfHj_qP6(JIDitoG~ADmKf8**Bl$xtLQeO5z|D zZXnn!68T^C14F|XI}93ae`w$oL2b)*BsEv->w{Mh@(y&&POt9YF`&OsvkPpc*w6KL zr9PcJ>VG)Ei=C=&Z%I*}}=nn+YjEbJLhe)p_<=&+d?>DTA>)$_Wj<{~2g3;ysH zuaX8fTSvCcsJP7f^OPqmjzZu{n8K^YGfPt}KU9LVz5Hiz+gc{RBpKW5(DpG{ej_$Z zdUaFug~sp?W!GaCe9SW6jjGo)wgy{^a7QEwmj0r@cT2z~+)6H%^^J0Y!zlMFbWzQE z0Ng=jg!!QMMW4rMo(}0$4=H82nfW7%Qi2Z;zR52Ne(Z{oQ5PQkMuWHHw%_iv)Fg-w zX2M^quSIJd+sA^2-TN@jL&-{%zb9D+T_U+>dGR5($B;??01Xmi8+M@M>ftq;hmV*T z5^iScH6Z8~lo|=uGJTeWltJk`JQGP43!og|%y6$ATRmW(JK;xmj$6|u3qUD~qm4+2 zahf7zak{)8m}d?6)r~~j2UZJkxEHJx>1_JKB+9Ntg1hFYoAhfQ5OIV4$&#VI*bDdC ztQOzU*bL@2a6Rl3^y&5bBTZJb~yTeCb0dW?}Vs2Ng;fOFBmTCnN#It_DuOCJXR|o z8upV|cmC@32jkTD$A|A7^O>RnU$LuJdgdo>$w99ML8jziE$W*{E7XoQN?I03N5@H2 zC%%}gOI}t=G4f%+7Q`j6%U1(70IAk(bb+KA^7M~UG--SVg7sr~i!rW@kH({;&y<%Q z*AD;eOJ*GB?WTa%Noh56JJ|8Ze!SHQ$cXIT;G637%Ld;{x`FK#p{9FZd@U-f7`v8q zvO4$q{@7r2x=3pPHKfn=L3{AM@kQF-UuXBa2XA4R4vioCM`8S2CMmH-z)u0?OTXP^ zwt8lAC;;mD-}~>Mg0#Y#8jip^L8+vnah;v*ru!%|(3l3B+1U6ICwooIxhyAU(W}ARE18oROAf_o;Ng$vLWnMrUrsCo-48QjhbjQ+8{H|5rOh^%-of81rEZRIFX&fRy9W2^Zs)y4yh)vp(=cC z%{r4_lgW3A#e`RmHhIJ=A6=OqpL70<)|bLc4EBqH&UTEIfdW6wJu4mU>$uoWwV1B z%E=2n{K;TRL1|U7AuaM_%G6%1Trk1u-|O^-7~}|71@KaO!2)K)h66kPJdP^kKd*YR zv(yuDyG7CF8xwNlAPG5F>sf_T8j3{Ku0O^!3sMOlwJ#+dK|R>yY0t8wD$qg~#sowv zkqR#r{0H_FHARyYusRew4JU zXjaSz?H_&IdI!TWF`i3pz?x2#%7xNI-xlLu<5~Tf>F{njS1BQLs2TMor2p`0meO9lsDT78Cl!h5qrTT1 zt`scxLG2XrWRs@5wUiC7(oWiJMb(OZ<*FLB6k>Mjs9DKO#;8Wc{r!CZ{rouShG^oe zZ)Lw=%_nj+?uvcwD->kJMYvYp*zMw!J_cvm=%oz-?iG8qG$T6-sj>_5x{#-P&~q^w z7w@>$nYpCY{~YqI1Zu#Bav$00KjhLb`5m75?*+LmUfUS+|0R0^jtijEG<3!Y2*MQ~ ze*O)pFkA}p%*Ee&f*7RnNV!-bP2ckB zz$d`vyux%mK{M%g&Db4#8jD$FveTSJs`cQ$7`~bDo0%Ne5@-loDML-EkH;d$3~gj= zY@w){*fIsm8nFs=DdZ)xwy<^HLh*5_=z9k0p?T5cmw_}C!fB~oRVXORa*`RUz|?*i zv_cY}#*gEAfP;ovcPa5h*quNijY%TRD>}H?->5?jVSX+YW!SD_c0R04{Fr<&Skns9 zojlBM0wr9Ze~`ryYl8+2``qU&A$K#}(i~|7xk6Zi%v*hxhwV+a!v46-7}d^r+AEi> zT)XPhrHun>=RMs)x+s(u$?B%!y>YrXaK(O#4q>nbeEB#JSvrOCk=oSjCAe3yv z6(gxMz>0v%g+&O7rfE^2Tlv66Ti{C6*=YIQ!K_rhvtShjbOkCGt04+!N`L`WleZbv zpY|GT$)lYU8XC)LHS+`FsED%*WmGPr;s3R+iIa$#wJij=7I>&_b@y^%R z(Z+G$TFPWcihgcXB8V~2Y+x7TToW+ks&3k^CrNpECAP!OYn+Q_Rv7hnvk7%MkII-k z71gAls^xBl<25$8OWavIH3D-Y`bDkeiAVbNit)aV|6A6(>kuU5Dj8;%k_IdAUwZ4i z0t1^csJWFfo0|c98uGgSKdjxUXOVbNj_LPlL7LqoOX@?GJq|49^wttGJmlo61w^IB zc!?8s&qagB4J&%@wf#2=vw7RW|B$sTT(!&8suuU?WJ8NK!w3AWAl=zNNK~RY)O|)_ z4@`A(2%DhXiZz-{rgjN^T+ABOKK#q!2CkIzSpt}S1uHD0^sVS^{nPb97hK+grI1=f z3G`5!3zMSv0$HRoG5r2hA%DCkJt_zLgWP^NC+38@m~Q@{z{5TfrKVZ-NBEP^vHfz% zQJ{$fF7>yCMgP~)_{zr8PmyoK_Rsl{7wiM#!nLm&0k2zP-A`@j{nPhL%_}N$Ue-45 z17hN9S}{SlruM5x$mbJ+d;3t3(6*!=%a+=ND&VMd;8o5W0e11QOYx^|#$cw22Zx?e zct|Yo(P(K#KPW2=N_ko@m~q;>?VMlV#0VumD)!RoxzF<1*~-RU=ih6_g+0Z}Xy4+~ zLj*79Xc`_Kr-={sqZ= zO^o@~WLi;%hY`%E*Vi10ZIbiHJ(`|Nb>#^UGwYJY;G{kn zKTOgK^y90+5)tA3Zzl+_wz&i@|`_Wyx`%@A5TMYjrs?^t`B?esP!qVm(vp&8p z7Fy(&C_~kZ(|{`JFvoK*Ti;T@h0%Wq?0NxlgO0t_?~!ELx@P zX|8*4rcYJj#Og|PTNNh_*a6gZt%LsfB29~%i{@o!2-}jp0KyBSECkJmMS~4=uO7F4oY)^+!&on7Y)nv*NSFdZ6RPwh~G4 zw#IuU(c(<)C4{^d#6Z_FP*A5?!k0V?#;x1bk;j1v-*N7-4W5YKE}f@31;HORJ{uetUoi*w_ro^Q-9LX> zUUhYSIzLbM#tV`lr2sz-kEa)3GkSL`F>!c8H??9~Vjb`ROjy*Kk}iCRzo^#1QwISH z1vcZ)Z2BgsRvg+t4&m;Kr=JetPHTyhbIBQ+X-xUyaS2TL&h5I55=71k9@JYwR|CRV zj47LHXZECG?eA=A$CAEHcpudkM%{oLSDa7f^c?MH-8a#L!@|4wL%SaJp1b#(N4w48 z!>1qfr@Q&`yPw+n_t52^^OdKcl+P`d>KUzycSn~hc^8SBh2)Eg+Z+(IGfFc8ff%}s zWqzuvbD2l<20X;-kl$Ohc4~|Ft~5r@_c5k402lydLAkS;s+aAdppIvq|if|W^ zv((8u9C2GOx1H_dsaq}iW_;@IH2>340Lg^Q~qNil5E)MUpDaBFRFt|#q1 zZw)VRQm!iT(`@G)GBA)eWnZ~_p1a%bz!VEer8z79sjGL?LsDVF`BIT5S7aDB{Liki(oBKt=)WKn|y9h=lXh_*-E^K*KOB5pcfTsFzveeLw$~2FNC9aEtzAs;>Ntz z;2JseiTpEm4R@PvFat;Kou)UZ(d=irFWXN9$%21f2>A%{;BIx`$!UMhDb%ZrmFGkb zpPa0-znH{2%ayVD6PLut9x^4oj9VZypjhKsd{?mImZUb&LfBq}dPO)6OHv^!H#IeY z!uOTFQT{Up6?NY6hK3miQ;uaXOR?nx8*bZ>cOk71-$gobz5)Lx=K*A-RU0M0TMg4fLu`;C?6`mP?d2#2b(|FlbQwe8cYaIH~h=m{@ zE;aDaz=I-JT*`Zi?$GfTmjr&vYWxpo!C79IQ$=-BX7L`u6X9bAUG>-v$UlWO)XhQ? zT`xq0V}D_}TW0|d{~3z<5glfplyrut?>sSZQmJX5msuNQ|4q=;d~Bd@ZDAqhLPt{ruGc~ zV=R79i^tmtK51nsa-mj8_EXhb5x7Uh^;bI(`r;HVdI6)P1+U&iz8I4szW7nkk@jQMe(Bw?Ym4ZFLiyI&3kAIFc>ZiteI?3h#}0Dx znL|;3arr?&$IlN^Ero1h42xr9r3+K!2)LCLGJtX8{uvh7=Qao;j?aJ{FUKP&?{HF= zu>4!l{?=NGNP>*N3;!=+d1d_{!s3-CyKrLm>Eh0tbv?YM?Ssb#;now z0)aYvhoJLJ{0divp3Ard!C8e9WS&vF_J0k_K^&zFaI{!h_FzBxNYsZc4LDl>Gt09; z+-K8Ri0n!2SjcSc1~e+_gkaV(cBBmq7{KciEmYM7)(z8e}gRahRE6C#o**oi9u6+QSyxYF^2&Te9r&lSZwkWJn@9}G6WaJnBf4?L+0e>^N~Dj zWBU8j)e*|*n7Vjf%9b-yS0#!cy61Lfi#xxcj20b-$DwT@FgXXZq64%GUSuZJ){sh4 z9q*_1VN3?mes?mQ8Vko0j~4cjvNfj}Wi1fLqXsrA)KDjo=4AXO$KGfplIDz&Vez)* z0wIlF&YS8Doo0KBFs!V#UI-=xC&g-)K#g_tir+0dgAylTjYBR#`)5`>@^p*-Std^A zq<@#*5IH#sgnhPQJvvDiA2491={PyA*2)AqeKSlR*41SQMjkJ1_Pr3Z1qgmr;B##=R>Ha2pFk=wNXS1)>BZPpU?Z->&5xNZR$;Vw(DP9z4PbIrJi85o2v{u zRDdYPMT9wZ-{vu=hCI%$%tRN#@|-;B8i)aU;-=6;sv2A{&1MIr11!3cfXIK$CAohe zudj>AF_ze-PY&yC+HRNMXkY>PBM$s-0ddwiY)h!ai1TR>JDIDJG`kJd~UzNMCm zN2n5O_-@lRXapYa!_!iiOrM6{q-L644#Z_u#jz|>Gg#lCpbm9AEMp3eec>h-C+{;o zhku(EVl4#4!oKF-dbhXMHff{ehWw&?YNS4}t(_CB+ti?| zc&$Mf*WW74@3p@_1pPlb)EnbnLGNRP#S`A06bdih^yM*jgH&tvx`PIpS7lWZpGVfy zq<3zs;cUk@-uyLw$l;nKuiKd;Nlf7f*MIm`wV}J5*EhI)(wKeHG_k_rK@qmF!zu|t z9q-h}%D7wjT%oi$7+AK=e%|{@z7b%~rGmrz8Qou;VH`^c?F#K>+lL~0wTr%&CUQSW z$$&Aw_>C|&4FJIu6zkIatSMFO&YB)c>9HmzklZYtA9YDNA-e@eNhzA=$Tf-znzlT)_S@> zg#x&CIPbyj^hFnU?XY|xQ1}a<(U_rqmLI0!*^YcK&v`ypR-WEwdW&**JHc>DlFGk9 zF&n`F#Y@)pn6#!Pd{P8gP-w9uXTmHt3Lbt__TgQ9@qoM;y}0HDy_AELq2PX#Agv?c z(f)LYg3i8q$pkht5hu!w6u!7xcTRqzn9mTJk(!SKe&7(r2z9A1eJhrg@Sk3A>)wC< z`g~I~VrAL%-$>&PjF-v9wV;{@y9mI#gkR1Db^k_T+4^e#?k2=Wqy4=J_d}9AAE~uB z89^yCcqxB8&%o|Z4DH11Gfel2sP3!h+S`NUsu-cFC)amvrfl~8S8CahbHRV9Edrym zYAT+0;RB?e-5F3^#fMpXmJ-CS?u~HxRxty3xmf@3H{*A*3WN;3=_&+B{;3s2<0r3Y%Ng(d%B#+nATiP z!?5s3Y*$+kH~1zc)&A;i;vE+@qes(f@^z3h5t*?p4NE2y|G0ZJ|2u;tj$+L^r_Sjs ziu&^6`pI=K`~^a=xYt{2HtLBwT6zCgdx?lj!F-z%+J6hrE21yhpwu(kJ)>*uK=>0A z{;(Ff8U{O2QhsD<>LhWRvfnOf_-oqk!2AHOtua5u_FpgE$Er-*&7|bZwX@`V8I~d$ z)Woa(EF3K9?gVo=*iLd8|71i>j&C5*r_S6%KKsjcoLcFT^HPX*SKn#6aL#2!)9^P! zk1O>B4LVc=H;`W%Re5a%^H9we-&9XQv*!)Bjh~k*q`*-(gt?r#%$_(H@b^4Uc4yr3 zK~qBW0NV+CA^x^LUD%&<5>`(vcmsJzHJf0=`NL1W?5x9jC%%081$d7^k>uQTEwS3{ zn=P$b=8}(QvMge#R%HTi`ZoKG#J?S`F}oJou6&Yu&fG88TPjVk9@G-fl6Hk>;otTW zQ3QK_<{=<{t29{B3-mPbl{q@T<)&$U53;j{g=85T)|?j;22W~-Q)0T1dM!F$OXlJ> zKy;FhqQ3vqqcH2Tm`{SO!RgI4S#2cvE1z_+i1+rePsa?tQMI#t{UJ;Qrjh_>9#fXxJ9)&k|mn4Ts}&SDSLoW?$(a;7vJ< zNi)$H1|{GA|Es`RR3t>l3wth3C0^`4TEIIVt^f9KG<}xg88kB3YQypNkjPbQTE(J6 zMDwM;PIoc<%VMMvf5~EYvWEEQW320bflAvY-)uF^uC+`=z;a9(=KWj2O672uf+Ku0 z&(G8F>S%Q<=|W%-NMO=f)l}5+df<=f0eP!ZJ=qevL%Q|(l;xE34})_DHO6U#-S)1N zB?+DgFj_Z-3j_I20lseFKu~6?*je^FUWwLJM$#nCQV^YCW9bi`bWL|@%^(%B5yxY} zQQoloJ+|az$SwU@0R__8QebVYsI-hpNzPr1QIKk)^K{UPxNp|Nc-0Q{dDC=m;XyegO%-4>@4$ZOFRp9_pJR5yo=~sTs!$J6#)}$=o|armdnqCM z>1OR%kZdn{^Y|x<2aZflyna93kfO-XitX8VJ-72$odIm}wnb}a0{+_UP2(i0H%_x> zN!Ua7h1nI&2ja8Syfe77zG)}k1EPv@ol%9m(3344$5?RheeX|!0qxdb8GIHd*`07t z^L*&21=rDeOeFRDJ)3ZHa|@qLAo4ueenl&>Ehs$fyJykk3(vhK>_0tG+ymmI0j1y} zu0dkPRQ!?VB$X*{fd*g5(xLy`26CHKXm3CRgaF6L70k@d#g~VBAWSEKkHpPdp<&!G ztwE47CJ0Dn2*%KTw@g(((^a5wL_CPdZ}3bZYCS6$UrJrRWsv%-AlOHqWM?S?E5TUJ zd0V*VT`-<|15N2TDDq$f2Vq@!I&0hlgGQnn0Swb#I&v2CoQ-*;TNtO+sVt5(RDQdC z6INrsh*vAB1~k(@A({Uox=k)H0JkC%KteE5U$r^a3N#@?Maa6UVo0;C=XWdzp$Fs# z#Um42=7j2EFgLd5;~R*C1A7wzUwVh;RAS)b$u?mv3Jq!Z{t8&JW*XxFux6tR`jUMW zGb6xLnsaHOU2hUaMVxAmu7BhHV?Buh1ft+}=`M`)P3`r&Q~1RF!}Cf1RQj&NxaRC- zyJQX55e;JtjkK?27-z(&o}4XXx_u0<_yY`A391ZfIkKYy?UTZ0P#Z$EHDBw+F<-D(3xUYuB z{L-jz{qqmVs1@@G*Q*B}@u~BlF^bvk{HU?-994Wix5v;gep-H?&(k@kcVA5%jkoik zvzk{eZKy?mE6G|_k{Lea!AKOxN8vyCM955v+W`ezm>nNlo|YGn|F)Ip(zy`$0ftSG zuqB)Do^q-LHqG%KR$g!2K5yMZqW_otVdi#ieJ!kmxP8!Uedv+E z+C%iCII3#@K|le4XRfN!91&%{z-LCbHe+&$giNujiqZfp9VNIXAr*09MJse~(jMj`2W%H8BE0KSgt!Ne^knU)7t7)e2eY@y%+n;Ik>ViRVC|4C7 zcx(H$q{UdS!%S|}=rVh|rYu@{Z&^9AeoQ8vF35aI`0a3G-tQ@pf@siV!*r zNXrGnJp1WEhpYf_XU>f9^v|O`Kn2odFBJ1$9CqgiUGW?f2JmUaxn@hn1AD`i5Obc_ znliE2g2Os9K}Q0zpZzGYbLMD-$@S@l)&xu6=aQ7rt;baI4OhW=CA=N8U9Y1(BIZLW zVLu}INx3qUGRMuuf&U^`%xR=3{)jRPuam`MFPobYNy4C!cb_spKyZ(_vqZjEoytz5 zc*pAITWs3F4;i^zyB1R0onvG+Kiv))%StZSr>_=p=;-pX@rHKsGt5x9$wZPPXP_f(;HrUE4LVwaT@QrL8xBaaLEEKGu#@e3c8)8^ zYF@?_9_um1-1@-rB!!L4AGqZ(h(OP5j+mP>glV)M<%R>{Aq53ni0OGmxQ)J@4y<{g zKS^y_fJa&jzDEWRoX%AlQkNo6FiccNy7IM5T6@S4b43G1Lvf*N)U=1xLbN_RgGxwo zqKGL?;{ej`E6r{%Oc1q4<2c1UfOmv~$$%~XW8&Lh(Z!rt_%xx2l&i9Wkj*0o=Bb1m zc96-&Uwt8SWnaoH53@v0%0HOJ#x-pEbC|06?e6M(vTKGLh#=4Yi&H>2btF%-_mGMe z;uMXwrecUKpE6~bk8?Qxg@Nfu8Va=U4j|da7kg;sFi%5yJU##V&&>Lbm|%ChyyRDFyxFse)ULL07mX9f zZ@hH)ok4nXPkA>F;7#^XOx<;{d5vbhK$MFB7GGpjh`fG$!0mpj`&~Mm$5=sajkI$7 zJKQ)yqng_X6mW-hq=%P*4!BP&%;65NtpZCt5mOWIllxm9~+&iE5IZdYSk z)lIg3ze=I^At5;+P_4aJoFkCB#*;;A{3m)9`(PX8M(Kc@>FHIxs0>`;g0?|4_bBkm zp5Vsx33nfn^++kh1=S;Lo{bRfoj<*&e!ME@jZrj0XIblrV0+2-Y7h9udyoBKbbSvg z9TLn1xfa0haK#eFZ~23gk^(G3`HlQHb7LZSv^GYjlsMe+KCR>7d{V}nB*Sj~?06rj z<*Ht#ujuy%w_fil{al?&MV#PA#{W^rLn)c^SeyJQcGZNaG#KVekwLxI^uqWVhH6ev@PWNwE+m&p4O z#a6qM@16@_Q6etF1j!13Ys}-Z0QSp_A)ZMjGKTbk2HDnhtz==rK zDYjq4awf@yysC%}Xu7^s#oN8_hdWWy0`CN+5wN}8LALmr z^H>-7M>qb5=8{=RTEL$t#>m3diKf@n@r%F%O@DTIJR)&+7_eX?ev~hBaILTL@@;Os zA06)QzAi0qswSW*tWQDc%W2*3WhlX9>7F_=i?Ivis!Eltkh#iHS`e*?z zF-3aUdP!&>iTxWGiJ9lq@1Og&85;%tlw(gTAF7rAz=TuQ?>M0_ungRmr)dXYy-Gre zqGH*FLqk}&gAO71Z5*MYoKC?P`ye$>coZ9}NGJg{OK9Z(d}`|Vx+5M4V_4I7UcGKa zttA6g)@XuBmoz3{YZMz=t1h!x%t=e$JiXO57%#oc>Fngj!H4_hG^V%p8Y3D??Uqzg zO|N%DFD4qD2mLI$WURK0kzn*sEFk;>eQ{&GX-eeRi@XXb^3th#?%bH z?*#TZe2Iev+=5L#EPOQqER{4hd|la2Kz%JP2wkhZ{Nm%Vowa5RR@SA(GR;OL+EBlc zak9r%W;LGvH3`4}50T>-#o2-YKYk3$NRSODKyi9RmC9;Fh?yjqr*#5-gV_<%?n-q& z(<6ReZ_>8axJX7?q0ziI#a!D&0J9H>N#2!hF(yhcJ?g*)AJ??JT7RiA6C{u_^|4FS z{S``~J)xEc-h?+0N829F^`OFBe6E-f_eV2j!11hor-Mc%iE>^6hjUd(e>E-fY{bd- zE^%7JAzZ@}kL!5Kq|mpTW(f61fpvZcegi#&;7AhebrYA{b>K$sFB-|9L-H?^OlTr< ze_!TTvunQv(DQzBUJbs)-U^s!$)Zr2l917UF63Ue8#Bl0mE$byhnEwl3oag!kaZvD zk6+}%4WTU%q5J13_B|VIzxKw!We)~QZ!Yn+%h`-dR|3A(awEX~jVCA=Qdioqby;bqCEGL79_=VfM+NACs#ci#MM(nb#) z`Jm%B2v!IdP9POnQU*s2`J5Fr^z3}$=wbOQUezTTE^-*kTSBt787Y2Tk4)J)viw{1 zPqFGkP@oSQVn9c--O8H8FBWekvdF&yF<_B->JAt}i$W})2r2p@IzuUt!330E?-SxuwptX|H`RJ?_!iipW{Pp7WiSGK! ziOELKuRAW|L1O^V?eHWHOM>0f*vd-+K8FM^|5;u_;b)ll@^447TM|rDS*_M*+`@P?a=XovjAaT7bVFj=;^Dh%U-r_>MEy3iHYR3l z?LoKt6_5pI&8=6xa_izk0PearIT-kBnn-UNp8dnZNtyOf!MEws4;$HUySe|C(~iVq zQkdR%Dk}7zdVa$B=Y*ON4jSHfQlDMVeSKAazRSPAdgQ)5<2~@U)U$)CUS!&F=^m=C zJ*I=c2s=Yf+p1=0Ba=?hAc}cge(yBtiYOvckB3O0iFK97SvV&`(z6Pm3}%U9X89z5 zUAxJ^X2ikk^Ji?8`ZBgR-g2<_njJiBy3v>|q6Gactq!9@i@-|H0U-SZjP_iCEp1}rmLW#l3Z&Luusa(m~(D z9LHeD`&) z_|se(X7*L>4CQg= zYBD#j(4)tq`&>60QB|1Z3Mwp!DBmu(o84UgF~zET4-z&u#a!kg1Lj zNFDpW9;=$@yUX>YReNp$XMk#4Z=QMn#+Z-Z#J2dNXBa+R~EP zEyT^@_!lEUM(V?2`a{m5IPA2UEB`j|eb#Gi8FU{_YCG)*bq?kU6vsQ=orSX8gC{&h zy|KnC?TRPd(ok2sXQ6L}Zh`{QCFUB73Se$7I&o(<3tlcx1gOz83SxVYY^XH(@z_;} z{w?036QyE3(7&KgYILj&ty2`5#@zhd#X#^q{5_35ruH?JV=$=0Q|$Sjx?_Okxga>V z*4F*T+y(Rw6~d&CF^+^pnR0Z7?87_Eer_hquEhHp=jp}~xvR}5D?YF&8u9Xwz4-oU zzwV_`s`Gu)-SzCh>=Qk^zr_Owt;uEox)Gi)ChxY6J8|W&Y5!94OWoVcp=4Iko@Mdl z&JC!fqO=;eGqPrv1Ln|uJ1y1SW0B=XfYlCr7u1kxo?NfITBnKhm^6mYz;xN(#JdnB zwP_mCmdCsRkAV^h()W_ar9U&A>iyL_TFtsPlMZn0p8Njr%H=G-f*F2HJiT?x@E6^Y z660nnlUkx{glqk6uJdc3|GtxUrRCuKVe3AEwGz?JK{8#X0K*ccjrYVo{d zf%9ZiqLy~;0pZKNaA)@S4^`qX!e5T+@#bRT#f?xz$2JQtF1THR+|4)dwv$-IPW-_d zI*LG#TrGvn(G!|+M73YjoRd>i-plT`wsa@rY61`0MHE8e*HbxfXn$=Z;1zByK$O4= zsujd>zD3@j^)@rSwX-bNpXqzZOD*-wGMHmTJ>x3>_9s!kvkr;kNq5-aR;y z(!~?@M*SeC8SlBB3LiG(3Q=`|nBGP1Dt1MAhTIo=T@n^~h?M>rLl70FmVF(b?sj%2 zV69AWY-+gvP%TxW9VF?@-UE#eydRNzxa8JEi3G`pK5n*P z&jimOe5s7Hi@&esrd|13iRX6ycFEivIlBpk@?h-MdW!MjH?y#P#m$41e+A<7{#mWn zoWPQlAVWqimg&@}$YS&L8~wuLZm}2rkRa8~)|e{H)xhzuohK{9T6?&xUNalnV>90a zAjPv1vHW75qH0_Y1O2sCrkJbq;F(2w)H8 z!>Mfq?t%k!C)EI(zX*)5>;-T=YKiZ;K8nJBnLQjH?9n_yh--#%X5@pb4Pq?pPQx~| zWfmmL31Wm6?kA$Rbd<%kxbChYF-7m-GT(t73|=Zk4Y9uC$kB@%0QPI?r4n4($&YED z{o$Tw=P!g26X^CqID7bROHg=Ip5%ai9> zlQUvEEbkDMk)R={)JVr2u*Gj?M2qiuyv3gGOb5F*72dWD1^Kr>OwWO-q40l^c8}ei z#NEQ@W81dvA9zQI4`u4H0F+y$ncumD=rA;F`is7T}oz>`omGE5~l!m+&ew*(Z7+9eLIxka9=%a zSALt==FN?{@8?zOHa=#teIy4XNHE2EDomFs(~-ezFlVzu6361-rhpnI6j^p|7k> z!0=p)trbX-&`15v_-r7X8KZEAnSEN+^>Plw{B;2?ua;15{1ovl=vT|>R0oRKI#0QI zRzp|v{%vn_*gJ9u)K%mRhUBA)I~7n569I+t{PC8i_wkuP;TSEe0iVou-2i|NCvS8o ztJ+@xtC|drrPF~t5k;VX&J}KmaEGi z!@PM(yqW5AIQg;D1o&aD;bVleo7%Rh8KwFPI68B?bL`SQ^b-9dxK5w55-*62d6$YM zaFSKaQmMo%MAQ;197AavyYI#p1NK65?{auJVEB?}fIPWq2Mmp8Yg@~wF+2XadXa=% zn6#f?hj&mxPPhZey)|-f`iHik<>eLrhpyaG5_l-40x(tQ>Y}tRj83km)ZO1QNr$Cs zlVhQ=gtPN2AxF#h;n?C4d3GIBW-5lrww9NBR&=!dHx0@-=~fiESCs{y!9uw!!nPcu zCO%aG$h1ZN!$B6>>vH$1b6W?2u0%C^gh(6HGgFU2p*zl@DuaodPowI3a8*+`T}Sto z4P~%ZYGzD0{0IuyhEb0)DWSbF+sHl z!%D@!1wcDn?DfXV>0lj};dO3i7|NP}2*{sD>O4lD8$APafR}l?Azzz?vr^DS(%UBf z{$hks=w!POyDBaUQ0neGvR}3IVF2@=_sfMHGq+t)0Uq0_{Um30l{8zcji#jR(%G?* zYCg+Wb#IxCkaXxAa}}v& zZL>8=oMX%9^H1y+ZizPXEu2}5@BO80?U0=$(>{1O5%2kX^lh&y!jSE~fYW$+_JDJl zOS#diUfVul#_yfzy)!1>A`t|!jVm3)ypnrBX61zLb1&=Om}F|lfVk0sd(46pyZZ=X zDqUHXL}XAo0MS|+MkkGt%4u6_)ea3eplD|0ur?`mq{MNJ<^~zj9B>G+K4hLo)yr-( z;w#1QF6>!n75KHsZhc~nQBtenQwci*WAoB+u zr%C{<9HGrEzJi|*>Fi_8#xwWlw_JM^`Zkb{wLJ#S1$gC9J!Yvk`#`tqKy;Dl_B5=D zUYeIQ#T2&um>Kl}9JYDQLTM_iX|8(xF-LhRCnaJ&@sJ8D8>PH*mM7hKI{AheAT&EW ziMJGR@Lft&dzN)FGd$UVWr^=+txV9$#ZB#L#XhtlE1RPY-ozO?p;FGRvtYq%$nzEREx?7cqB=oa@BXLnNU&24MWPB3DX##AZ{%zbcHw zT00W{-WUF!mkzlFNCi6Bp~dT@S8UlfORrUjz!AC5+knfDJ|??)eah4AFw;t}$(Y+1 z&1okJnx4b{#*KRbb-zI17QQAc7G1hrL9axb8)IWw|)sdtA}fW_BM_tem{WoaR^_HEdp7y^n*DrL%iT3@WXN1lTo zW00Gk`IzlzUpc+a0r4%iAjal{LQeLTYjzgA_XMrU!!A@XS8230sco=A%K7M@Pq^C2 znqSkbl*AMQ#eTR-Q4qF8uFyVkCo}h9EISF;NoWCd=l)db`s_~%THXf*JDJ;*K$TJ9xv;w^onO)P!oO^JgpKikN0@o7-o&sgPydM~ zh}8wDw&jR7T2P8~C&Q^&tyK!wU@Zt-7Eb+2wYCZsrzPGp+7esw6I}l%9XFMcA}p{= zh}cyKj&vGLt~+WPe5&K5ufO8Sff9ogDnf@h2q{P_Te=$OxM)~WkwP5%Z$LSkc0?2; z6dSLeTqK3H>a*ftxPJbxFmUD$b1TD0F_vC+tE3XamL}E>-0$U9maN6~+60VbE!bnJu&Wm9@eB%xg7v-e1k+gQ0D5F?(X&{0mGqIG%WMD-0tgn-?dF!lN9z;zk0*ae2U*9zIE{OJN z!!Zw9nFl_{KqccVu3wZL4GpUc1;TP;2=K{|5pteJw)a+23F}XDPAo}U4mI|JxNyI)J$?}7+q!MF0gDhgO_n^5p%BxG6 zs&FEd>>aP;?nFkzaez8FJVyevU*tA&DJ^9-a?3x?wbw7^W)ECIC3_c_G1STpC`ym_ zoTEf&1WuTIh)|n>!7wBK;|OW(*Z9vifeF^+_vhTAO?b>my?Y3hnHx~>uH^nsznsK1 zI!(6(isWD6P;gTd>0h!U@w$717@FBj!i2)r3(jl4{kHIh@`^oz$2MfL?m_}3BxsoBKpo~;J? zK|c^zWe9kh0919BC%%P&Bo_;D(>5F3A@p)OLWjM_{m#t*qQCkJ@ZLmiaq`FoYG0Q1 zg#yiy%-ZkH!wFzytal>cV+!->h;FrM6&Fmc2OZ-aE7Dk`K#-=cL*jF~c|@1U<9~^1 z3Z=_gH5W?brfOXIGrgjOq`VS`ZknYNFLz7oi>xS>Jww$o zF4*@kxehQj)_1S(UOPv=)T^_4^l@?iF*en8W4T(hXej^@KZ=^;R)!Gi0+Hff$ zL1ZYwW=d)fZ0O{~Y&Y~NVKdm;iKcRFjRB9Gt|fAPGg|+Je*lyK(W3)I0@f!A%NOq! z7Om+QUNlP_r$rOZtYP%4_V4`a2(M2pGrI04UqKmnpZJ+PY-wU(O(P0rn>a(*Ot$-^ z5apj|<;Wbej3qwPCIvhmPHPG#<&c0TAsm#3`S8p#YUBw}RCemGIN<4=s1aWX18?|6 zrz=x>F>u-P*rY2o5TW7)pOYOWE2kl#c;CwOB(W}{rai)rI(Kx$PJB&9*h?NuUfmfP zQ_SLAJ3A80o|u8B&WJ8*5W`^lSu3I=G*K;#C;~XX;o^*1xqf5|!L%5GxQw)8AVa{9?Rq~o#4zn>-s)Uz{BW!SI{SXL}8C!xw~ITEDgkYK+Zgc zv+%##aNEYYuj&P4`+(YRWlhC z%SF5)?W2J?KLncJ2pcN?8r-mw-?#O$GnMw#8!aXcK8Y3PxX6wqV&n;YAIwRM)uAaNCmgWT2VZ_=Ixdjr z-VaKO-)Qh&kE)4M$kQ;6x+LT99yVo3Te-iU#HblHR_QpFZqzGvvZ2L9b+jl?Npft- z{Wa>Chn&&N43gY*U9Lz^th_qMFZB)<Z_D>TjgK)c{W8wccgzyHr-S;h zzFzI{S1bHuh3D_orx8&nS(KW{{GTt=7VEGziPbpyU9VnI9c{jZQ}m6eJr>{6RGJDiAOY{ge zf>1Pm6F8r;xj~V0ygRM~V<1mkUf1ikq(rvLtgWPaw9RjOhl)Kcl`s3QDE|GjJa8(q ztLWui_kLaq9+&;fZ)WE%hZ%{`vU)MtGdi2_gnyfH#(C)Q3ox@FEgdUmJqO=EeW2G^ zvLctWhWXTGRKp|WvBcyd$yDWZsJNFId4IIoc6?&ZYotukDf14{RoKtVzGK|e#+y&$ z%io_cST6VYt>rvZ{jyOR{3}<{Ur6UX-<<5zzbX8b`lL@|?;Q$XXnAn^Y9qtxOGjIu z{5_wR7BQWW-w*E20YUfc{QH&hHCT@@&X7mWcb3xgwz}3Jk6jk629P{{To$j8|5Hf9 zFNUK53la#q7xDn6o9}5fX#7Xm1ot)bHP!jW^SRN+Jp6St9z2Su^>y!Y)IWYss{MUC z^8+n0f1u?w+8{Ap`~)e6)vb5%|4MIPVy>!0w3~&ea1qmmnx_4kg(vu{l_T^?Xghc;-VQ>JQtF4K0Jap;rH2gx0zWazvsU1+=>pt6(~tk+n2sz? z#mwEyGzxzwduAN~e{fy?y-7v0n3|Ai?nNM8YOLZ!Sv-~q-0+LQ7_v7V|e=^l6 zm+ir%y&vP>Gcj@sPq3R%XM@kK^^0kgcXFWwc%L!iK-;HE?jHx_{lUKD!&+388y>4N zIrpB&GgsMltV9yJfb<1UsJbN=$Cjgwmx^X=-^9H~fT-cLW(y+V(T$uM=!wVa+O-_~ zm`Cv@$vxl`cn(X7f`hiP_$|A)xBUGCcVbs4B`n51UP^?c{jgk(vcCg5jc}tRoZFl4 z>>QT-+T@K~fW+48aqp!b{kPM8a6dk$PC(46RhbPTFnq7UM- zk&mHbDl%m-hCnVO!{Fm!S}qW2d9jKDP0Jb$mB2L1F8YLXEzPA1rgr!bER|HM01T-F9_~0bW}L55{} z&pdl%+Gha`fA5cc7aepkrSb9s{_w^AS1NsGvzb_4h+l1#b*A(2J|6AvK0dquiNnv% z{s7Zvryju#2agyyf|JM=mUkmO9F3Q^#6Fv02T6v1Bx}|;ij!E<^E0bRzpu<*58YQO z1~vp*Dauyjr=^~b*5y{g;QmsRy^(XC^0JfAL)~0file8X1NFFqR@6bg9Kk2tqt4U7?<0{W zi3$-sHh6QY3y>kDQ0WbuCuKfaTvIjw6-vi`m{LudGG4ux6BrqD1ljBE><*dQl`tFF zwQ$_zvbw(FUw}lUQ^{z@zPvIF>%sqEQDMwSS|Q>M@;}9umPYEODuXT`8C*y{p6lQD2rysY29P2k5;gA}e%vyK$Zv8h$kw)>J4_7!|6`^p z5st@ysQy1OQ^eN)W~N0w7|Iv@s;EvXNUWhDCL}#R+BgYO>u_h zonKv7vHs3kwTjDyDfwq>ZsW=dj`FyyMH|kAsmu1O;vTXYK5gWFi8bNJyL6%sd-~yy zlB#5Z;Ke(sM}{iI;XdbT!q`BVTTsN2yjmxl0>{Axn1UL$p;Az!1#{Q3V{M>8oxZG6 zBV}(A7Ww^;UV2_a_T;JczqF`*-rVS8L#$kP{&PHvU#tx%wQ{eA?M8UF=`(w}n5 zdqmeUsi>Q93{GJ@_>djqH`!_Rjl}ZIM~B&^lH-!`l4T~dV_{@s2~z$tHa4uI+~s0q zlu(w%`Wh56Kd4*bSBIrYh7&=y#oMOKp$}fINOoYNh21~QVNLAgGI${v=`5FI3ZlCT zwd4Qy(zK`Mzocm_e_WUmMSScQ+^-BE``ey~sh?YMI@pg?4$i`%y*Dk%A!P)YChMFJ zIsc$9pE=|D%kH(i+XC+xMNPSr4U7^)(PJHAfw~HZBBP2bri(4W%Gzx)MO}*Aldp>#vakY;Sm#Q?Vn8^=?LQQqGdPy`^0%Givx6Nmlcz*}eG?8AZ!f1o|@vs4uMe zmjxi~lNfCf6ChcT$58lg+0Qt&9IEqY_i8Tj54GV3yRoCMON`89x6nvUXc)Z{(6E46QhPAdJ!YLbs;ZT(MsPoc6aN}iKDqv zvv^@9YK^!Pcui|m#<|cf3WH_J;m!K`(Be_TWn02A?#$ex2QT%u3)4g&{DLfKjAN=* zRgH<4s^fk!3-PH*2A-ihEBFN8GUzQ#=Wp95Xtc07WB%I_0n8SlM|J7KiS{M@73)c{ z)BWTa%sndauljtA{ULqzbII-MnjZ;z1GTu$=DG3LtEj<6X}l$XO0x`E?~Y4)-M0mi zPn{x*dc*z97?@O#Xuv*&iOx(G>k?yRNJ{ZUAXKvZ^F_VEH_v<-v57{C-WRTA!>Q>9 zzYtX6a6`~Ggx#SiRp3(cl2q`)1Akr>h{tX5HZ!5Xtu!CIIFMJTBl?WWa*;#l7arf( z1P>#aTmj;;QK``yFYu*^OoTX1q7WwlDpZV zT=1%lgr*PvMY%`QqSo1_#S**LrE0_C91U}2S>t*`9k}D%`VOa0YmPe{Z}ebf>_^k8 zAhh4&iirMOJ{k2q$N>g%ib_)bMPf;YQ@6=7p)g6n*7xg#UaW?uN%dBJ1L1I;{#4(s z<{WAW{yoS+6|O?)A|FJ97F@HTD|nL3;B+px$2qmH&D%#(<4rLIU55r?mm^<=yBtcT z$nigm*4913b1x4c6*|mmPt7Grsp@|qzE%((8zizc6PAR>T{z(SbowY-oyE3 z8wIBehd&P^ohas{(E{G7xg>8rs1W|2wD?b-QSWd8~|$;k5j zLO_e~VMfs5rKbH}Gat*X(y)1NZd)5iXbfuBTFSKj5fWdcCSKbw3vODYdvR#lQAx+p zKlh3P2!H1WgP18m>(A0zE9YapdIlkFLbgNvg8CO4%>5aZ0%`qUBvSF07o<7TL=EaZ zb|I9K!s=7S|3xCtI)t({6&7~C@)w8n{Fm^t){qF^yuX}vE zZZGzAUf$jAgcSsN|JDwk9m+noOTc3WzGlq-heGmGwhuJGEpW{JE|pFoD3c{_891`P(+-@j*|u2#)!^t{Tq3x9 zqoAXWnc}RZyjwkccs3|^Dr4l!evT!?kqa|yNmE0)>8H;7f;hWouDxE0-8~S8WWRTc z8cKaeil56;N)Rp;Le7S5ZJ_Tu2%nCwN1W-<=VYl*9x+=}oP@k`k zG-sqg97mQXb4#6)$-iD!!F(3X;t7hL9ESrVYH^o8+A3?msS@xtdz%W(DT1@sr6{e9 z{EZ~Wu5#r6UKFGsyRdBJfnJxO_uI=45bQXF^Tlb(2#i2;Ep_0#5|q~*^{F~G8EWBk ztTkyxCat@CTgvbD-u}+~c;*lE1Zqlq#~4xFck#4qvKZkLyzMF7ph$t+Oy_|pd00JD z9$K&23w8Cgrmi*8o$MIzOHE2+DItWEr`aDhPR4Bsq4g^7@Z>!;bTZvWhP(YG3%p`; z`Q0q!$^2^&gRW=6!81L|rFzM-_RL!pw-v56GP}BCGiPi$ssGDhN_S%h=@axt3GJsy zIYpD{LpN!eIQrYpTmONJGx+~4#F~cKUFd$fb6?F&ti{O zi_EJ;b$T~(*w$P(6tDfl;5B;t0C=;=GA}?-y4KlVuPaogVBg9uz5d@yjgC_SmAz}( z?SNjTJTq(TwTffDzyuwjbDLT-?D~96PfwGh>yLva^%<&52#=t1j+k##SxQ$Y$UJit zk$RmY%A;A!*KOCi)#scQ_>#x$E+sadkb5jMcMb(2o@V0QyAXaMXsu8%f_z=F(xQsV zl1QqfGk>qVA4{GzZS#Fzp=k^T;H(1j@iTbD+NZwhsjt6t4((l_hPdm+)3zWre-x1r zWBofw!1&u7{hnSx->?1cyCU46EIRr7D}LiU)Ambh0vF=c4dM^whQHU#%iMW!%Fn3n zQR-3sQ~p^ap)?pYsCu+XB~&Ug0L*5yw?I=*GQnDXZ0?snf&P(CVA zaiHHUiTrAi@6o8VH-*FZgHLfsY%#Uwr}q0xhsx@)xM;6|@LlPo_N(GT0=NkYfsw^A zmkSmAZ*ClEyoo-Zm(f3CLxG?Htdmvy>t6fBJF^u!R=&e_nD7RFJ+v32OlyugeHv^B zD-Jbm&U}JP9@D3IVGKnLnnMu^6=z22q}!sujMG!rZWo0R2^yn6T>x&#ZBS(xtHh^+ zs+B>}paVY?zlhnn1Qp`a=3?iXYxr%Mv;m_Fr@QUtxu*%S2y+nC@r&a_VA-zkF=tL^ zhG{dyWuVZist38oCpm998hsV=K;7rIbGM|Ar4nlg-5C=a{|&}c{QF7IgAfKT{v#K( zFk(D+2`~NZ)BR66o1U4c&8G|qK_aRx-;KTrJ4XS@6wvZ%Fi)%jG^itR%u3klg^R^Ef zi;ZmUq2SV}@`V6MEeE`y9j07A=$SA>FN3Fu$;bhi21aFK!I;L*ZG7^wZtfl1WK^Vt zwKD#`Pq-BUhgQeTA6_IV@nGIhwuXEL{c?lGBec!OV~@EJib%p<9#R7;fH%F%25UvO zQr8%nPDeJOyl9(6o@q*x|F_BF7@`L-J0PDiWMT#K19XY676Ltt`moJ(5noMS2K~{x z24$(Lr_UGJTUR-3uZS)&cHHCztPek{n($@o%FHza@m@|v3ux0oOmzo-e``a^Dp{!3 z^w`Z;cs`DXg$}nZ#4?y+VlDyzSg9wxr^JFp9&Qc+!ZmO}E6G5A$}u=W{#17gRG$0! zG-dHYl##KDRg@q1N!^+ffpPl~3PQ0Jglc$OIsCorqcC=I_}A!IB4J__;DvNg4$tNd zBeIec?3!cjw6Z0YB(xeubT4hH2d_RPc9(MnTgh%Ccw{3w)DpZMZ)bfN0?-l{ss@;QB1(0Btz0P@qmVFqMv=eHO{_92v&~v1Q z0#$T0|3naVi2ag1^EBFrTmU`EQeL6@mTZd8A-46%5cEfIbXL-w**I| z>39i`2exQl7o3GmwX}GNbVYIMbi*Z^bkUA)pS8PGiqipzv=F&>WhN+4+c%jfQI$kl zpl;U^qZY)tD~?Cj{Pb^1Qz6p^ij9>^j9zPk+LawgLL#|bBYlsIaKFuZ1qgubPPe&5 zDAf?d5{$SyDF_*csJwWjqY9hejrFfCi4ycc=V2~JjCAZLPn(hn8KTMuP0a}dU7Qt3 z%9gZ<1f54;iZGtdwNWZ*7>WD|81`h6t3Y@=v}NHODG-S+miL!6Dfc*WyEqd+DfWUfj;0ix2~b42 z$(f}~AAzp(;DhUaP@;rVhv*<2_FL`z0F<=cMSgDX=iKq~#PKs7WZ@Y8rEOn2sg zU4^}UkC)X7kliTgcz5wYC?VT(Ll-!1T0#$Ug{mLj6Y(QIR$91i%*nl@B_l_DAet{& z4E(ETlUZ`AY)~wdq6=z=Lyr5xlN41R$z=EQWmY8S*YdJH$pd&D@4Kq3@{t4$ly2s_ zYxpl(KSHD+bm3omIk~WI+!im0MO^^>Yq)r5O|@1 zbpVFWr3T^9y@-5;Mh9!Sw%+-H42 zqMCvMVf@h>THV|2$okfK=+$7|;u_+u?M4)de6>q-!RP-P?8EO_o*59W&ECUkcW*|% z7(-uODqeAKwxkS0i&j#aV9U&yj6yDtO9_&p-pU-GG1rR<5#u|-=dGt`6 zz}4pln2!PghFja}7t$7oKzpns^d<-iw!eNO45ziENSyyMp*_5-4C?CCJD-hTQKro- z3Ov$f&6t&*Ukr>pgAn)xex*>Nudord=eg|$nxyn9F(i^AKr=l-wUW{mCl|BeKLUnk zk_GyQFyA0e5Q4FTq^_+x#&+9%e#BLdse2BVjnA;;;p?&Z(?9{DzVb*m#!Be8SLc*3 zYLq;1l7~s2fgUdJm}IUKw1N$16QaMi?vIonB^9X0An^`h4d>*hLoMP)vl(-tb)Gyd zE)@}1$$4Q*<5G~!n%SOrc8S-7Hi${OkK#Ku8hiQawwPvc(eFl0*PfgdZzYH6FP`cp zr+7<}q6Ol)k7>gZo({qqx}myp3{rx{QT9GHxqHTswHjNiN0(6`m8k8`lj)0N%w1J- zoHQq3H-gA-nd69VbBi(r{;`P-7tytvCUGnrQ4v&f{)%#GPvCiFbvK`192@HYZO0VD z@3QY$R1Q0xHiWsL>X@!v&_2q?k1Z%?0+1mvbCPoq2G4TAU_FXGf8mcTZa0+}maacjsaZg7pfSVKloMc+Qgfl+1l?u}#t zflc4c)*G5KN37Y7)a256{9X&@+*{!$1g4zJ{3X0Qqv~dFAesxyie6$~2rmI`2RxCK zfLwdwsd|nFSL6^uZscZ2U{qE0YxP{aYmPr!+mUe|Rh)r8a$K^~4UhcuHSuQ-h2VGn z{+_oj_Jsrn3iU{M#BVKW%Xf>*Kb>1r5yDFV*SUko2i}IiP>}t@zN9No&o7q=3gk|4 zlYi2gN<`tNvBI?x=wz<&kh}>-@J1jNWg5X9q9;B53v-GlpOnUlBC~1`Y{?sF^`R3g~q;YT+ z%r$YfRR>3eeYg!okYixNF%Jm-73`DB6=2vuKQd_HTd!ufLe!1IdxEX z2$7SAfm>h#s;Mzu-3}PqI}W5j-)mV_|CWZE7~>?v6aAdQlAu-NJMhV_urablC4+z> zlM{x9KRX%pK>xb0(lzCy_VvAGXSx(K9C8baBSJc_jI42Y$X2E0uhjI5u^-bGOLnvI zGUUwF%ccU#eFCymH_c}XdFuhndVADrp1!$|n%CCaV+9H%Omnc(vHD{UX?nh)CuOt% zct74g9FVo)sLqm3R|a=MP*;CY+>^kE@pFi&RJ=&Sv=5#Rg=s-(v-y9^6Z5!j7OOV7 zmGF3RozYvf3%n)uSvD-&nLa26@cgyb19vDH9v07ODf_wVqReJ!m@VrvpGlE|d`*Uo zm1F)xUQ3OJ)h8_c<}zcYD7BJ$jGPx7q3zV9_ z>ow$~4P38(^+b&X_CzGP=4&NMk6<)pP9jWTq&T)-A!m;_#cYV_&W@sEqTb4`YOKux zT_3BDKIGx_8M?poLbc9sq&^YSPUhn>6E*{!No^FSc5G+AM9HM{r!XUes?rn_ldO;p z42LugQds|XV9!y7d1uIO;hQZjMD%akS0}vF8&9Mv@rK=hDY8PVNM-EIK`&(SkZ_vZ zH^O{LPMhQCP1#gz>eKxVCve=#?B0SKS5Wg`jB-OsxuA7lG7*JQtR)>Cub8g$)+#DN zM<`OQn@ezlzHBKcIL~b|!-$nr>-Z#v3GzayQRq{gLqEEOWd-t#J{Bm=L^QW!T;ox7 zbF$~~=W_mGkDRoKgo&MQ^Xa9)iQ>OO9<8fwIzZZdU)M=EpMY>3x>lzBhRd4V5Ej4s zBZV0qTy?~qO|b+SX--AKk@&9R#RKT(Mv-$9RYXcV=q||uj}Vg+<3D0RMMz2%AGtr} z884$8K+h7^&)r%q;@uQdddAVtJ(^46Der+@M7(3ezr&Pp@t2<^WM?L8;b%gSBVH6p zMA0iXAN5JbDknj{>a6wnPC*brpG-u4SEc$&sC3d;KA!O;korQ3Jk$N5Xb4G3C9+gh zg5ra_i?kOFGORAh`|=$It6tiBGD) z$FDZdE1B?S!X$M@ib(sHVNT40-G>KYJleBsb z{}~E#HE}~8=9at%+KFAE5YtMU3~p{+d2MQmiyD&RmV_)iIAqRRs~Xy$P0MR3E;qXV z%n)3L&Zxz4$Q%G-s2DKCEQ)Kq2rxIr#%`O|o~9bC!teG<)o7#4>Dk~W9s*b70n>#? z>SZOr0kRrLWhGg63q;e|__XdA&{e)S(qJf59V&~#z8WUdV`>7TDaJ+8U1Og*lE9{x z$zH+^_FQ0dvlc7g)_CklH}ecXK2^2iZ6e&Y_&SOnR+3Mh%1K__h0f!M;iO-A;hCIr zyi*`roU#nD-O&c{W6{Km4`Ehu*GIFX7TtU zMdq68sekp|hWLLw@V9_KvZt9#?JE;!XBu4AAEH3+v1AiO<18GwS@D-zOt#ZADbpYY z*yAk1TW{#FVVT|u{VRB2GuzCADi(F|K?b<}7Tk0gM3!OLI0RdxIqoWIc%)E5?w8>9}{CW?9TiIT{)TsUgv<-=2_ z>xCqZLbZ`^)!2@m_HgMPcLhyOV1C=-m!tkg`&aw$Fs#ZhhC8!y!8)S>xfNGdIQ@Q) z23z31BE;1>x#gNn<4~%$lr?~VOX1x*y&fW>8Yz@I;PxivuzlcR+)^l6nb762rJTG`L()XYp6d(mD5D5!XdCMrqnff-U+ zH;HNZFjQvAGH3l60vBiaJb&ygX&8}B?3B+_{?)5q1UN^#f8Xx-v((q`_j|r32ZDFW zKYnoP9MP05Oc_QDJ9a3jxRy;1DzBJ;4VYh{i*h2XYyHCw!d)uZnrc)rODs`)!PBjm zaHhJk_${#07n*?ofEI%%^YshYY{|-e$4}F2O=}8dHY$hG>~9eQ0-+&4yk5R2n46>t zoAP<;fL>K7KqWpUy-;Gf%g^RQ>1dHxa1P;Y|M#{Y+I3F8 zMEgdiv!RAX6s6w$tT)(VpmJcAB3OB zma<$VHsIVh_~otM%UQ9^z5yusOrA`=a?_^)QhBT72y%~^jeav3fWxMa>%2TMi}|Z2 z?mz@Lps(nLg_Y{PH0MN4?BuYVNk$}0x9wwRn1JqM+m*++Up;wkGS-GNSi+jXql#O1$)|td7 zmsW!KY{hoZhgp(+Kgq_}G>QS9RTxNTLP^NIP3a4AdLV{_y=Wp8UR;j7O1*8ZfY)2w%ST;TW`;hsyT z-l~AtP~r9djMPl1Yr<(}x$~?d^y(H)(e>58>e2CI-(N-WN!FjN z9iaj;TKGrb5f^1ToDdJYo%=CuRj{neHdxYG?e3ic9WF_0O7lQ-SFjx#{n7Q(t>nAu zTvCEb!|8S9lWm7(8kr|he)Uc~)9~9fF0s{R(H$`Xb2cX|a%)C&ikZ&?*t50tB6ZX2 zbdxdabyEYx1*V%KN7B#Z3{pC8R>W6sT=7LKDILPd-;t)(0#%K%NKL)n))EhvV$ZP} z$k_d5CptY?3iQPlkQ2n`^AkUtlYs=@m@&^rTd;DcR7!naF+knpB=~ei@BZkC)DCqo zC#Q!v36$qUgC*xhv^=PX*^^ox2WAtvt+M909M#|s79`u2^>Uf{8Ogyl@sXMRCU*gQsIUQ`nLS_OALRxS45P|2Tim~^vh?*=?8m7qt@vei=bQ7gcw!^w z9`N=B%5U`o6>2SI>dWQqRvnjYsSiSTA^v$Wvzp)S$mm(SPe=vn$q6 z+Lo^(#M;PJbw&n6cd#3=J7?);awYGKYaOo@J5Tf^jrF6_84QhQHfnzp`SZ-LDONwt zw0#R?e?xAn+MT=ue^b2sdptN;0@j!oIbxzrPo+S691eE|d?RkU%jrUA~*DDwbDZFz|rAFY65(>PLD z_C(sIClE0n)Gnh2BLMDWX(vhh-lOQg*)>!nA8RbHbrL<#Je7U3dcc|Vlv8m>OCRVc zWChYWP#D~(56UsZH?Jf@oEb<7c(aVERL_v+cASZVnU8hA7z7SSE3|WvF7r%fp5kPL z3XOJ*hX8+f!+mWsJ0s%WgExsBNdh(+?;mfb$%vi5C>}FWI8&d&sFY1Yt_yl9X>wP` zi?c8O3T;ozvbQb<5+zJ?%Vg$nXzI$Hk$)|rZihLX9ZdS31Ag~eQnEyE%-AeM5pY>* zQ2w!-F0OHKn5tnFNLOv7yUM2i8q!)hR@b{g-L@(TrUo8TH|1+~O4!8Iw``7}AQtPt z%x*1u;KIhmQ8DLHYvB>%bxzK@OEM$;n0SdIxD*uPdlN7T+wt|PH6Or?iw{VYZw6bo zxu0tUA>jd1{`E_p3IZyY^3sw6`U6Vu{qc^0>diJx4z7AyT#E#Qe&ZQZy@R}-zV1VZ z&QKhEkaqEtn*7pmgT!oJ?1n?TgPBTI%PY;CIx*`5j%vEXVrV3}8MX+Oal15KPrA7f z&IEd`J%u*ZrOw_{M*J13gOgG6dKBHAcznIY4+Q77Zr{|QA$F1y(B7x3<&MEW6Q;j% zCME}KgOK1dxHTJc;Sx}M)WRZDr|ZR23yxMaGaE9kZnC&T>P--|X)*U_T7lBe1R{r+ zv)K_KgXavTb{&*f#FP&O!jZKAPbhI?gVkL_1v)r>Wu%!24Z&mF`rw-1K){=?`bL?dpa*nqG%U3Q5rluZdThK zQ^3o9cj|xZjLM+Z{Dyc%+#VVw>4=w=_-Ua zC8|OIYRxLJR|iUTB#<8F!Y@(8c5~$Ac29~MWu3UiMx0LalW>!hIahe>%uia_d~s$! z%WF&QR4BoJaMTQkP<`pBOXPb>9~>}ZP8e#6Ofz12Zi;j)<9AJMY&#U0yl>K;!G722 z&-pVeb31$u<%Oaw%CDa6U?|eIic$CxRe^0A@1(&@51o5^48^YrA>k9 zOiaVb-S-L9CFeKGP5_%@lD@Y0O(Rx*8?AWjS{VHJP6oHgO#LP}7~Cxmt3>CQUSr25 zt*LC~BVD3qY8hcfJP+O|-}t0%hl4DOD^fsew$uQkh?c2p7i(UrNYDA6cu9DlkouXY zL7_aXc#N%}(4!tfW@9?8I4qg!eUVY$nPDnq+B5Pq5$1g?^iB6jAb|T!Ss;r$^XJA~ zxXaO84bkQSq1QbZCityUjBcGW;?Al=PyB@p;UCsBU$Z6YjRzaL|I!9s1uGAbTUIw+ z?`K3kN!yp1^Rj)EUR!O`t{KhMQ|us0FH;=&;Prqz=HR<-rG0c_sW0B2`bV1?{VGp(35wuDVx>9n@OO(xJXxQh% zXNT#bV%1fyyw@USkdpxyY&dwoqX4|T`l@Fa0KULeVGBw+t zGPUm}k#5IFk!+d+x{Fzj2@#qTI=usu96ani`-k-vL_1tJdZ6xOMHqV&A6=Nqo$fmi z?yD3W?~zqgV&0060{#}{n8&Qr(X*=hGoqzUOqRl3^J1S#^uV9BXHg6;$Qo2_ugR3H zWjElB_|86Sn-T{)%IcLe7h)*q3OfcI`VZzea;6@lN28L%kJ=nK`~_sQLOj16WAu&J z(y5Ut;|6sjX6DIOYiKe$dz4KU`bX)jw;)U#bqHe87C@VYILGyt0)K6+KD8yR zalZr~yJsdddIB`T&C#z6mk`HAL<%R0sBzT@>EAvE=+(uytZ`+}&f5VhdpWyNX^gh1 zsG;+e;ls!bPM94Wn;}bh$Z16eAN$?!(-b#kx|HUYoa3PFk2KFCn`>V$kFz-}3Xfy= zo<(TF>diVwvu`rz1><>J3&=C-y9TS@Dmeh+nJduyZN)#!ko__)RKgwV$y#juNQ(?B z5rU&%_>9v!`Q1{eE!L_!jm`KbM^8fqDbYxtS^CGN9spDbr+C$p*UZN%y=gZAlBPsKteBKt zFL-})$<$XjmsfFh>e#|}F>4;BNFaG1okYIzmy7PP$ zU9Y0mocHYZtcs|ob#IEe{b!)z%OcSe8Yd_SKpJ%kE%i;C!$)^`=~Iy5-x1Pc%?|HJ zM?EISoe$2JskMRwGPBTp1FLAtqjpaGWEP)(`}yFZjBRqssZ-9=`pR$CX*Jbp^*8f+ zG3KaF(_EakR}qLGy+cE~_89YE@Uzr>I02RM;>Z=>0mj+1d9N!;SoQlxADV~ti+OO7 z*R1c~x7d!P<1z<&oElVA`y_>utTXT;czRZj32X;Sa+(ZHYnxHXbrh^s07H!5(cSUW z4_ILu+nb){n`8Q>1QC0ZKJoOciSZ>aT1qV@he5DY4n9501VxhRO-WMILHl?)(a%Qp z0n!@Qv#Dow?y5wi#MGLUnX}W{eiZ@ECcQ=Oc#UPo5wq#m#EO)t)3|$rVLA?;$oeKx z5}IRQWS|~1LB_+q%&flXV9Hh{3Fp(Sc@o_{EMKWeyXTs=MKfz?cg_w0g1%G4-|EFX zinZb|?{=6NK^|u7LTj<2MABM6%S~{xcNu7l%x0TbNpeXS&Ss2ECKK6)@e_#AbAQ|k z&4Sl12h$56?9BMpTJ=4)8(v7*dax(+@X|GwmXutcsBf{CGCZL$b^lbOe+(>}R_!Zz z#lH6p`_R+okA{4J7O4&#lOhiu5UC%D`LummyT_$cO%e%?Gh;rvM;lC7G_$7T(G{BY za0tX!S$K+oiE{7fNlp>1nXNeMfvj?^zm8EMFvKr-Je z)czj~>E=elFOo|>C#WVvBLd$&=2K!_XWrrL43bFBU(d9frn9BD1u5?p2MbpeRahaX z8x0<8H+sV35S8L1W-O&ZWBe{pMh|!q52ET;mb{wfXz4fvbc@-KmnUtzLH&Ywacq8= zQ2sL|ZmHXk3Ma%s1BC93Cl6y@_f1H&bg^PKc%RKe&bwSHnP{XgvRrPHC~@rvl8;Lo z;uvFdSmJKf{tFVg5g6EfD^oN{P6e;bN%lH#RH6|a587V+BJA+zDap~{ET-YHh4LMP^m!kKdWw)3$24ork7|jNC)l|+qj^dA8DlcU~IMsS3~av(z&sd3c%ig!s9Z#epAqyjI;cCzQUB9kXejM&~EcioM}q zXAJ<_0B%7!SkNvVz9PD%N^Oe@wrzIcIb^o^Nsj5RCbH?~(ZnuYH<|`Sv%tZ2#EuBU zq)r?wGV<&=VG)e+90}fEHn9W>E+qmAG(!HySbYSl$$n#?|A_HtRaXwp|G`#&24q?s z`Ae-UJ=h16-YQV-Ow#)SGIE0&x$G1#n;SE`TUGNVxz$#ufe_Nhchh@2s^()u`_E!S zwR;!+&jY5?MH1a+56yB-GUYpbB*X@(M}ALqN07O?>+4_cS*vmo{}k&z(#ZK6^%rg4ze7F! zcQlGU#!df;OC2iD0SN-gmpDhYP$icZSXNX`F1KY>cV|)f>|&v5qkf|kqKCup1JF(8 z!>SY6?Q)g`D@8EoXbO*t(rW*%%>VFS;eAP$WvD5I{V!DPSbHSy>P*CjwV=^T_)U3= z>}?+^>=C*u>P*ZOzP5MDdcOZH`?1~qxO!}|{vJSR`M#a)TaNr}J`~n|?|w)2_KyB+ za_A5xb-flV=)~ib8d)~3V>*vQe)9oP;`H}-H0cED$biVj`nAym662VBjajTZZe?oa zropDPlNT;gE&XW+H(_&zqJ08Pd{)MG)O=zd*%nEV(>`?*YunGudqlPtZbP1f<&aeV-b<1QB%}x+J2DBJ9)&izJ|@1{a^nm=N^h*m6mnB}Tm)HYizB46 z1n@vEomAy*&M|X{_BuKlwjuKxhYwk_!B^5%33kwq3IhfgEAtPbCZKGXN}2pq#Z9Bs z_5cjNN_>_!ycyp$usf@Wev2zlW@lT|rC3-SdFT$2KkKP;)6jSv>4}v`rHG^h1RqEj zwXPktaTkk_ycb1IwL{Kmq{a*jW_Fe{o&nGf#T=617NT!UkV#5WFh5~Wrt&#bbb*dL zaJ&5v`Rml=kmcJ6M>1?sD(Q+;xb6(8*vLAMJzW=sX z9I*^QATRq|_57v|&GkdwlYFOWew*raos)-Sk9z?wD|iEnwLS-Gw6HCLc{s2y6B?pwt2cBO>2}c z&h4iYFySmM$B|^ih1B()QJQww*;j{bThSzO4*?EXQ(?fQ^NJ-uztL3ZQoQQ3;|Wm% zu2?_N#B;8n0ns*n!?`^z<{B^CQLYR--^nXFjDA?NNuk#T)|t<;d$g^~6VA02t0d=` z#1;=d4$(G=f^6*g8{MbBFfYHZCb#9KttN#88kxFYUR83X*|CMxb=5Y{lTcoS$Rz|f z%OrvDVIJKhXG=*12Rr8q_lihb9fjUaIi(3cWS(1c3%=8yH0gQbJ8xWAwWTBX_b)Cc zSOZG=P1x3apO3YeBX4>8)l=~VKQ%3pe`sWMr@zuQl4O=2tZc8_ZgFZB-!0VJIHK-4;yv2|QYT93RmfeI zFk+q&08Ut~oNagU+dUW2vC z8Rhk_WMY!Rmex48lU}CkEcL?$rO<-GG{2AQJhs-XtS@Od?o*Tvrz(Na;dc)`aU?7; z+{WbXn+VsjKKUHjOp8p{da!}g_q0X(@;63V0i6f!BP8$p$ar#M;;vEw_V?uh(Uu`=#; z@!3Hbi@OFfZA=c>kVIhyWEV+-@D9oGJ;OB6*WyP^=rfC$rXJJqf5 zIG5(nH`_lPc|NFXjju)|GF}P~Fu4BdZ7uCJF3M0os3ZXX&K+9HwDYM9IU@SRFNjW2 zW}Jq!V2Dv61u_g}(?U$j&$!&rm{uLM8Yn+$*&aa`(t^uq^_O*7`G;#>4S zMa4okDE|~Bab!Du2OHI-e-i$T+pfbm*PdPL`pnw9UiU1H_ddsfGetFWGH>SP=~biJ zTo9$~imyA8o22G|Qv%kjgpFx(y-WgS_Q*|tzcMkH^TJ~X$GDfd?zdr>QIgecqqB;-UyeY@^Q`ypDwa{3=hW#IrBsexkJy6nrHuYh{LTP5RJ{Y3Gad70F`S>Wd&{;mom_9WN- z^Y{Au70GFt&OeN^R|G5R)-UZpjj61TA01sC&#&k2*V?zw60BcdtbLKD`ewf_txdQd z#1-U_+vZ1y-jJ|)%!i;z`{H$rB>f#@W7Gz6s?yAkB4f?whZ>2YFQcrC;f9$t2y zz{BRh6Qk^sDT8hmme~Q6v*Uz<^iz2zroN0wz%@VmKkqkD(zVWTH=44f-0%vZbXZ22Ks|sF+$>eFNw`xAdAl?!WG=vMeW>^ z_*q94D$`JJ!Q%SiTLaZ%jiKuE<8)!LwNy7Y6fJAcPH4_j(`bEP*2L-ICr1de>imXs>^&wOSY)e)N2s8a~blZhzv`aI1K|!$0)yZdd>P z)V@LAAdPlbNHUI+P-QCieg$6kwl}wa0^L$3O}euWRLkEqbj**!VaKX0Kz;hG(a;gT zk(@uQH*m^#_$~Tg4Yy}(^3yD2bhEQDwX6`Y#~(Ez+P28{ zGCf#18-9I^j2GuF#yB>*9@f#!%cNr3e@l01h2x2`h}G|ka&Ay8oIB;n?nVfAo5YUL z(d`$;{+x+6uKiUy+mr|Td4cWoJzA@A~s&dD#mWoB3Nn5*vV8nPUBM)06Z~ zpXBTPF*V!p5x;|lR>G$u#cMo^Nv3sTTw1$Zc>%TTrvE;tQ;6w2h!|;MIgW4XG7}IJ zlfZNh%eifCP9%YcUv3rR&$Oqk5Q_P->3*}Lnx?Q88=6I+hOr>JpL0DbGHAe;R1J#- zI8tw_)>+0NUBUwYM9{%6BhQVrNbmfnxT*4Q$U$J?VF8OGwm-9__fwW+wJ+!ui9Ny_ zfIm;OiUCmm0xH~LdU^r6)}ie#*O$BEvSi9ewjGjtY^Eirz%=QLtcYlN5%xb?o?RN6 zTMhhyOAwV65J`%L)=x_`ji2knAft5Pbhba3d-3@XV6m=#%Dq(wGVJ_-R8l%2j*D?X zT?v%0194H^vb{j`t)UKrZrSc*d%P9?r*c*`rkE^)so-;tv5{3w-lC8w2RY1Q%vLhr zx@;CkYz|qnA$Jc%rQ~2=4Xhqn5@F%XD5cC`Ukj`r)(h_vy)z`IjGRr!u6@?3p!^*a z6aXI?6VCu;)+NeZ>pLYkv0c0bsn-O8@g2<7Sp@PR0zlxP`X<~0k|rlQVnsJ>lg-B| zWGFm8vKIanDp^Jg!vT<9Pi-w(YM}mE6@f+zDpk~c?q7T37lq)U&)fpd8OmZUx}{tV zT@P(#c)k{~5-BCNe_RIWW*N#KTHrGzWtnu?r*DNkj`s%_w+_l>vrb+MzRvasmjf{s zw|_^(-uoxq;CsBD+>g0RF~wTk!^E)>rO0OF4P`_Z4JC&*knv4Okg}5fcZLV=2rHU9 z3=)_2j6u0nn3*G$T-1J`T&EWg!K{qIx=K#VR7wH6v+?Z*&srV8+u&r*GR32335C`N zg=sER5(!>q#88;G>0jJpo81&m%2<(~#K-85ntU(DQt~ zdv&5_t=uvG;xc)oLs)~Ra$t{iy9ZY+TOyFT(}v2>bwG$^!z(O{wln`qVqaki3U?-2 zFSK1pCxt7EeNtk>8Gw_pTz4pTR(Tw#f+$&L652G0v$mj1_N!vIEJM6|EMrKd$XS+| zo+T_%-ogG;4Nft_xpt54kf^4|xc@{b-5lMVP6|3Xw{2HZIBt-VAh=S|RH%l6l`D)3 z?38b^is6KPIt4-DG4E6v(gd2MA0eXy_#*d?la#mLfc3KPLsvYV@y8Rzr5V}T6K~=g z2gOEnh_ZtnJuS34`)YPIKqxHX#Py~(YgfD!l@Q!!!bV7ZGmH6EF!W`kkW9Ik_s3WJ zLr-wgqp1MhHFplDMR&lW{dVz^bBTXa_Rx97|Jc^ufxjZp?2)5eu3N9U~R zB1WMTmAAb%SZu zIaGvbH*Z=i{UN)%bDV^1p+AWQt_*3S#`=hLi>eB!gF6q`U`+=RxTuQnF&U(45hD;V zRe|t&7f?H@$5gm+TcsM{vzc0(&J6Yqoxeh>z^zV8%jbc|%7>1mE_RpbvlL{TbidkU z_(=!Op0y6%Fk%`1M!p5w_41WFrGNx3kYq+IILTmN6njCCSuJ%YNcou{h1spUSCeDX z6azaIXSKS>i6oHB!B7_cM+!YRZl9oOa$X2X108G_%yNW@2tN-4P+atF;`JUi+3U2; zl3vnD@$q^Mbtpd8v{UO0@jr{lW1}Mm|(7PnDbh3m#*0)>(^d}5!n8yxCdB; zfC0*w_OPV3FC|L7jj#i^1?cHLmRhRRo2iRA(FbO0q13=>t4${bx)4OX2*25>TN7&+ z*1DYjvA*Et<=_OR&Z@hEay+VS)xUYwk6ne6K+E?kFezOIb^sH%Y?BQ?R&-qvT4^_* zIS6h%x4|V$cR71v5((lkJH10n2<*QjmAje_iY7D$pFs|cy)mleO@}VR35;U;&L~`je?>g) z&YfH?*Dvugh-2s~HKuBW7obC7u^@!jaY+s?X=s_P8MvpyEEh-AJVuU6Fb6=B5`C8v zH>gXLSEW7;0H-pB4pvfjyyZ2n{0xA>}5{vInes zWF-%ibzQxf@T+{Z9Ls-WpK1(bT zOW*}#a`6z5@LUDO$V&~U2^AD2PkR=e37cj1;D+;-5Xmi-x%uSvU|`^N2z?F|yq&HH zwr}?L8#&b79iK)l|N0IdoMG%5@tdiKcTGbi?oKSnT0l6Y2pj2?YfKTKsTvfZhRq;h zJT&GJzZVrx^?!6`)g$}fJ6m4Cz3KvT#6v_zKlJdBPu+{NE*yj~+~)`G7C+D(qB9e% zKky!NuT_C(S7ML;f{8h(w5SQnBUZ47z<)9@zBd8MWRXOFgftUP8@p1;udGH$llGP^ zK32v?wDN}{KLnHkCi$l30g=XDtVak92MC%$EC;*@p0$4xu#kpL)xS)qSSQ#u$L~RV!{q-w5mAN8*6|&kj-6#@$vOP@P64NAnXS)l5^e3 z&fuT1yjkp^TB6umo0=RzWRxk-4mOD|P&vGY4$S&h9wKIZYDiN>;JYu$z(6<*_Ao6g zM)P&HvUIpqI;l7?^Td1vG*71r2xE%MdVku7bo20T|E=)n zCEgo9_2x!mtfYA2S6`GKk4MnN%c--M*iBa?_3R!kVXn$oz~Jj|N5$R-;7$fIktNwI z6%&j3hwL*&gS>hcD>l5(*XYM*{Maiox<{<$o2@>bscuE0EjV05Pk@}9?M^M2MyY_K z4t081lb_HO_1DEP49*nRM20~_jbvZV8q$hSuwPHlMdC<7ZT9^JWQM_>wOD0$mc!}e zaB1t)!s@n(!RfTzh?YyXR3eAUEBtCCf_tvnno&yLQ(;rYu%f@(cDo|alN+%<=pP0L zoi)BspHKwB0t%sKX6;jKcWhRFh;2VE$sIXisObDdEj)!}tNA!$nOdq>p+x}?p!-@~ zR91zJAXH;jh~!_id+)>)-bqKF9ay>}nmpg@XhFKYyP7K;r*_6!H<$W;;tsjE#6Gi( ztV8YaFD1uv30i9|tq%idh)vi%gYKG`mk$3{t{2B#y6Zz<1j<8wNTQ@G&Cb7abcdF%fd6V7AuoO$ zC&z%77bKsQg>QEC0Ru3+umL9VByouu83~%InGkR8SKt^0?ylmp^Z1sJJG#D2Xl%e9 zG5Hxf^wRU+Npc7ME3=HVGIb`>W8lJ4O<|Mbz;QSfzKYtGcHO(^?P`V;LiSQew1T1@y!r+#7_(`AQpKcJF}ws zzP%0>gDMCU%g#wzHb$qxuTz&uY+C1XV+e~N`FVc3NYWp z$;tGNF2UZ)r_a8K{oSyPbd*JR%8tF)+|4(l(^m&l(%V(#cp2}+>F-xo-uma;JGYQI zqv42*J1ffc)CAw3`k2}(_TI{w*C6SN*m)H9i1ppDuYa>PUkQ&==&ge0je>Uvx{m(muqrK`5zG_SjAADUvm6#T8hidpb?rYCK zq}Rz+sHscwP>#gcCL(_;OZ0l*8vE;&A$3BYsk@IBL!AnE*PnNGmyzv)g zJxA+ui9@z`7M|ZQ+ssI>3&p?ZTu&ACk}a@X-kbJzTsHn1+4k?)C<-g-=Qq^<6aW9$ zX|v;PGoul^iB7qzk3p=T%$i^94G-h~dppPm-oj@&;gHYGe!V^X9UEEfs+^eo4HDV^ z4$}WcJOW+J$+b~$+takeWb5CR?qP1S%JRK!0Yk7ab+e~_0Gw>el(~D%t^T@k$pfCc z#WZXAWVtBqK)rx6Et@8@2PR)xEKclzEfXf(d_{BV^@0@b&ey~TSroJ-_-;Z1YxgUy z6GH6S!q(gE+-%a_asYZH0_=h+j7TCNul(?D&m}~CXop3_&kT9>Sh{a^5ESf=7pBLp zP$rxxN<4N#qNhyANDYhs2ss{=;+tIzK3lI~0rMli#rO3>*Lb$C*^w3Bb#9L(ZoUi+ zXxMpySUl8B$CGz$(ixgf)yp`gZ;@@3L=~;nTDWA9IbA@vS)EsgZ?I+O{+(tr`m+)a zYt6=a?&y>JD9fw=I9`FlDK?F7De{N0=hxx~vkjOs8gBFswU9`ZI0p#E5tak_oOm1F3WBW zkGC>?u(V3H&*ep@OQ@&Yw3@!`>@Zi%EQeWVFrX&P8?nQqA<%a9|0I^3s25#8WHZX1_ePW91jxml`&_p&?m1ikR5i8;P(NjiDZctt`ktph z5Gzr=fy84k#l>>YNvj(0Cc*5NN8#cj7_PEDSN~c05iCJ~o4q9$K{;a`I69&v2 zSB*7`&b&J72SEsfP^4XNbJUagd+4okzkB3)A#DhnU@}9zEf)|&>bJ5Dvuj(X*4Zq0;G>4UD$JhndNIkP7&>3Cp}R6E;Jq+Y>FY_ zXZyToa0nO9q2GP4)jD$KD(Bkzf~`nKT9qvZVy?2yU^tQ5oWf&}I?Os9FjY$cHtj}$0jX2}uuYITN^7h7w>Vi8bOd6x<6rt^%_4!=}eJ#D4# z@fcnE%Y$uAodk&M-7{S~cP_kp(kxyQEc?WDF6C$xWmhvVs$MlGI$uXblcY7$(>9r8 zLmq~7qW*2(#mlil_(+h$JTUZdM8~eXw-|^07j65E`igW$ikVR-qye0n7c++Tkd=o& zIogF-Z;p;RlzGT)#OCl1g46yToB_SOB*OwDoNpM6`76PNn|x0{U23*kcH1(r=`w> z>w?@E6F6tEbI``(2`8ZZw`1D)@l`g1ZisoJa7}Wx4oC+T_fya{mJ&8m%^oL zuiXfHQ{mpqVDm!R%jfM!l)EyaQQ4Yz4?qJjtPY#98T=w{B0ALiL6TN0uZffaiqD6r zN1p&ILuPmx1A1PdmmJwvkg&@Evq5jnE-wma#B@F&T-JR{cxUPY#Mj!#lDe$fu4Obc z9;wkOX%yyLsbw>Gi$MWoL@vG@ynn-u3C&O|?ej@RY0kU(6?wS%9#ueiw^OU-Wui-VqG?}(B^Vu$mK)gv zyW0l-vztwrq|w}tH{z{=NcXA z5N-n`e7x=K>$B6YMd@%&GH6K_JZqn0Y(DafFQ%I~Euk?DNyG_dj# z=kL3j!|>yrsp)a{cL67l;6{EPHm3lq%lR2@#vT3{NBM#TEoF&EAEWj=xm9#NeGy_5 z31f=@qZOjq&K(`6u-{O-E69L5ay+w@)wrIBly_6168chgGo-nOiTP$Fj|#{T$xAgD zs9`6?xnq^my0vpO^DmWu22bV4Oh?CjmeqFQ^OBT-F zFmLjgVzmoOYcnoqpCnpdTImYz#yX_bE9S)E@aRc?r>t`h0Nwk9AgC}@KLVLWgX0?g zUfeobXL#^+%Z{h^^Kj3dwOl7n1$G`)Sah?X4z(6(# z+<?XGT6ogT?Q%{63Bl@5z zzfL2AF}lKP-tLT&!)JWX7gJT~vj|@dFciWF za6xmOCbv}?vUHlHM2iq7{Y&_mP`AO*uZm;l#`%e2LJ8&-~pj*%23tZ9M(36g32y$vmX zkIu=-njm6yqQ9bmtPEEk0~lV0yM!*eIAO^#OHupKG~FU%ny9YGS(j=<)fzR`IyEkh zNX029b1l#D;>*9!%MqGOiAIOIu!3d|q1N(@*n5M#M$DREk2%uJ(0|6+mfiF&l0NCTth}TB+ zNqi5ZUfL%_{Eru{WsB9E0(lCBUCPVQS&}64wrbhE!cE!m6pz6~aS2S7nPhx&@3LW$kM@ur{Y;=}gyF!~+#k zPFGbs$LeXzp>bzfy(^PRNvW#h#H%&pqiJS`2_9lx?Hl2=pPX7bgN+?ZlV+yO3dsGW zJ~rOxz5nFk=0yc#TaOumm|F8{tqYm$;eFd-x_4bWd&=$T_RN7CA)WqmV^=dbuK&;; zMV9r*y@bdXua`*pP@QdUk%=fiv_qmR1Jn(AS4|E1z~mjwd$j*AR=aCTY(lG^63@e% zG9@CRvjeki;V($Mqk@-B-|`CBTLJh1-QWR74g;iiO0|+ZMvWdbAh#qE(}uJe*=fgD zI(1^|;`BkSCC4xs0k@^sSPAXrc0WB*w9=g!k5jdwfcMry56(6RlVe0%-Jjh@o6ZU74N|M%zb>{Rv@@eDUD#~xn1JbRKH=ZG!GUzT}3jJ{^o%wk)ga$ ze#4SXgI&|jR>V9mQx|<5P5>oZDr-uDehEZI$KPV*a`~kE<}7BPmf{x#Z#N{5bf4;a zpaJ)tixCN9x|})0C@-C4qKPr=GDbJU9hJ3SL4A{R%Bkz?teeDFN;4T_{~emAG53@3 z4GM6&E2@1AiBu7|vf?r2E{t5ZVq+!cl8LJUxn7~)BPtd3AnLl!C(uP?BJ@Vvax0WPjLoZ+^Sdh;_c4xM(C${_Ds3D^vgoQ zseQM(M+RE#r&3$n?>9{GNcCDo1+Gix0rw^TF!pWRrBuZaq*84IvbeJ}5wG{WDAYe7 zq~v3%K<<=7lL5Y$nD`hv`#jRBaIx3?QHr9K{1nefEJK{u6uHYb;M?&ko%*)*4(Hj) zOW)2_f9VjZQjP9gft!}v+F^?SaK4nq7&z6X6-wJRJ8@o$3W4Q9(_Z`qWoV1*oD`O( zpNS+Lds+u;Y<}so8E@K{CqXy5>WHkUwk+3-;4&=FZqpV| z?7=7O^YxI${%;aWTku6$scVt&p^|PsT0r2c9loG_Vi~)WZ)xzOJ!0|qHTBV#0pob! zJq>mJwb^8a*9ghwj<>5Ol8Q{(Vcxu-lZhLT+sjiSbKPK+o922R{8aDZh)qiYjbC<7 ziCY2Up@b52?Y)Y?HXBjL-LU!y^$1BPDDU*SjtX?@>*0Znt|)w{tv$iS%Ua-4`Hb-( z=lDPQ6dBot;`3Z~*sxS5C7~uXV<#MAtLm2}o-PKMM3H*2WO#l`^nBE3?HD9@(=l z+=rq97#@81lK{9cSW1t-sM|}P1h>|p@;>IWO zU%Emzz{`>rN@duy)6`&Kf)rRPFR7!Gl+3lkKC`Lh;`UcO`2$U(%}zX(2r<-X8ZInc zo}eP@h3O4$&@Q)Dl`rv}i*Vo>cuvc#1X@l_nQi$G>;w+UsHZg`WvX|7JE zUzhv@!xovLPq(KyXWH8=bfFm|!_&Kmpv-rE`<6-xLmD)z@vKT-uuF7eO>&nC9FWu7 zC2}7Vr}u%X<>zD|PaK@kWoYI{Cl~@07HwgMlajHqhMXdA6RCr7dSjLXr)lG(!BUn* zgal}&j@jR;+wXfe_cUXvxE&$VU%W3=_dQW-&SMFKvJZ19R(HU8Hv~LXH8G&@l%)?p zhoh`S6C`Cdcs;92|5T`Jq5b1}K7dE0kef%uC^LB!T4SkD-of`69O=^BiT-Lx z$cLVY{|vum81O162`3bl#TM;vzH;uG&SgYnQ$&=_;MHo(?%t{Mk&v;mj+Y>wrx8As zT8&y82cA#$o9Vz2It3i$K?+gCE0q>FYqQW|i~NX5c*8qvv;2t(X#TprU7+`fOSHzm z6Vs)3lyOALNxg zwGs?AVP^Z9=gH30v#V?K9!A3KTURg343wL{0&Z0e~_wZgR6IIvg>q zNI0BsnE1ur!5D-#Gl^T4juM?B?xEvY4Yq%JJhU&MS+HDXaQ)b5FH;z`YL?Pc#!G~W z54)FH`BKmtlb<-+QlytPJ;wDJpw}K+dv3Y0f~^L23G?<;sKw}Y*rDfqmW=Che_;*@ z_B{$wfXtMD{ftYaDk{7sid}kz#aKR}ibJd=m@c<{Xq$C3knxv zt$WP0`N{qKC(~iqHp>~`<2Q{FGRISURyqq@dY6&66`M;Lu$17{C)5pPLZV9P83<6T zm{))i)Y6yI^;d-yZHO*zO(b7p=}fsPi>J5zSjyQU+Bfuyh+JHM z?pZAW@i&`BDK4*PI~4wOoYr}Nm#Lu7mlQJW$^lxk@W!4AOqvYICf=XV3>Mo}K<%d3~ zSKytu7F#Yzrt$ZyQrixfN*ke*hS|>Xn?2iRh|}vI51lZtfwD=Nvynl#cO-IQ z>w5@#Zs0>5!0D`Y)ARM^ELI)nN@Lo0dyE0*n|gMLKykncZNDnl|1u6`px1U4EBOTE zp{VFuB$G$6z^^8Lf~%9a4z%U&JJ%u+Q_`~go-Qm!`3+#QZ1B!lwJ=TNiR0NLn9L4( zD6q0ng8H<(doQ==(Qs`v2|Q=+iL;hGLo)7GCq`!_$Cs9wFG#63pQPSBi8?X#WUWxn z66guq*a0tFs4RYUEC<(}UW0&cz!>!FJg2Iu7LDEw4aaCLBBar+rz(`7l>4u!k#<;c zoFG#tHC%Kdbw2NP!uA)ZdC5hDwr17l{R`+NGH8KJXH@bhx@-ZGI&F40Fa_P8hHCrd zz|J8=$R032E{8x7fjo>K8|3g-+s%T*UtZw0=kRGj&OD2-#!w8=m{jdHqUSAe%?6w9 zFff9%FoDf|EHr?ocmSi>%c$2hjWAe8#$dM=l*s+29X6H)3K1X&RE3HXfsNbw2&%7- z?|15}j6G$rP9av3fw8qQpr7o)=K%Usw7z+O9xCxy3|EbIli-kcrAm6Sd0~dcBQM&* z31=@d$K>KZ;hYqUN23t{1csc0E*vQMU`H6KD;~TE(rD|i^SED+h2woYL?%cbeB_@w zsjz8qM<@%kW*RIs<3NUXaXhU2ZY_;+GUS#9#KpwKkdRRJA_-@HxV6BFX^;U7IWX)a z3+9zS8GVt9F>|D=9C|EgT(S1pILH|inrKIM;m`XR$-XU(y?!4DZ+BPk(6CM)37u{g zn4HqB6BlM3nVY$NVCtD#VRwyz5zU9b&b)~5TI%ZbVMC3wc4pYxk6Q`AhPUQx>*uZF zh1YtIJ=#yll-RwhO3|&jRatK8WW9eH(NQuF)PrLWMQ;m(*HU!F7M#@L7Y9^=5rY60 zD$Vy5A16%F^oblH=Q|aKrJbH4^l6nq^CDTrk74kB zsK06Rhk3}IIzEWr?R_Kp$=a1rQnqN99hHoLy-()3GZ+IsSsIDLKadQlOLG{ClUV#c zd71?PQWpMD%y0qO8*J|PE$`i(6NKPK*UoK33vx)Dbtw?D7KziiW5Z5n5@bFKd~%jf z58nx-@7mKp)d!?E=m|tV@@=|Glrd&%E?VGwD~3G8u1Za3Ho&)POPpcYcTz>W7vE6^ zDb!M=0u!b z1l@BN5IMw#@HLa2Iq(npGr&T*W>BI&Lt23sIvHrwAJJk%W@P>!0A)a$zc31thanlq5y)0Q)4l;2qtbHYNU@VTW!0NCJZ?=gU{Ryn7`B6pf_4G-4>tfh>&x|7UdYm9 ziY`2~@D=6sE^!X2BlhO>PLOxx7#o&@`c>Vyciln%QhNrFjDR36JMT$~7vBPj=O=0- zi56E)*p*wDdRAtf#kx4lIzr7l@%$qZ<{xTvu%&>&a9+})fsy;p%}jbK;bh%?tep(! zARlP#P(#{mh8=8MmKe~Ex{)Q`vKzD}QTTLStP?}Ilo7?$o?%`wdI*i8j+4-Ihr}0-ahV(RB3!NX z+QS=sng;`PvJg#sjCL7fZbe%539OAUm3VoCI=szc5nIt5v)xldsqT!aLti1O?!2TN z76sVSnxg^7b$rC}9W`fSm=|3ug%!>{LU+AsWTiMyo1M`FK!~fP0Xo-?M7}YKXmis2 zKov^^Ow1`Qw?;PtH z-2niM4vRWS&^-HRYSX;qGc|bRd^=H`TE`KdD{`z`mhocIpbwo0j;(hkM3J}-FomD$ zr2tCx_?9A?a%P$$#)5Mpp~XpTb}5EH5WxwW_hr)bm}pP=EY#yvs#)8t)X-rBNUU~c zCHPtMwscdSr~z5QJ?9u8AX1ht^*%Yaqk)4V&X%NHCAwu~KiAgJAX^TRa4%RE#Osd6 zuD0*b(jyX_0Q~HQ;A*t_PT%emq894UjP1Thio{?qxInW`Wh`} z6Fs90Q?~kEVqk8!Wq4Baofunq+r7M8wA)QN9033x)MX`G_Y4q4Q_eMbOE=<%=55)_ zM_!u|(=io{Gv0{CHMLphIl4*Zhd6^eHWaz3N~=nl%_Z)r=YaDDVaA zBWH)ACfGf6gl|f;23dPiuxUqF*QNWVp+foOZR_|+Z2;!OjQMX6}G8bUHr zupPPi$ahZ4{cH|wfJleb+O&R?ETPbyxZT0~2cTCZ0W>LC$V!YCK3#O&{a8rRqe(WI zDXAGX8aAy6)k}S-U{d)Bm`3}BpbAtC&hZMtveHq`18Pw0rPVr!P1`x`tFMhA@;s_g zqBeHq0FM9Z6Ks)a_Y0utdajk~TiI#{%v1u|D^s$I+Y!h-*Eszz2ej>nHTAt1s%f8@ z`r(r$Yn?_&qn+h{g5K7_{B*4?FvBVxPUqo)Bafg(9{J4!eCngK9kt?lLf4A8tz{`X z*J?q{kWIGYyWdC`VoJl2y;1eGOl$LRV8c>);ap{CW9ORYO$p;ywsJJP_z#@uJ{+w@ zwCiRJMajzzcfEEXbtO5Xd#7_iD{>0_!Q%2(pcqxhxh zo~_R_hWJ^|DEKt#%Z8GHc!Q~N8qr5b6w$*dIUAA{FGO?QJRe6LQEc#-2#{+ znRa)Ej!=id@>Y>^bi|osVLERb%9++n6ut4-eekYHjt3+!N8?tR&+_%~NsJ&lA42W@ z2a5cIs?!fmytIf7Jx8>WOz2L7=WQMj_pY4WJB6<7?VlYdE}gXLs+vpOIB9OZvo{d= z#J?=}5$WT7+F`2;3H^$9mO!DB%6}VEq)5sPIEG#RxR9#eoI)K(=EkRP6eBAoGX@I$ zLL5L}Hn>iqAlM7|n~7W;g+-h@qXpe6ZEF(;iky|5> zjYk-Ex4<`a>0HpW{rbsCV}I|UesEYw7AV%`Bs!%5h-z!bv; z$`dr?Q>JAUzW7lF{Lk)HYv?%XT|a8>A1z!)<5fIR(hBOh$d3Ia83MOBkHiCl)~e@n z^rThX6eO4z0DF8Ay8O~tyb1ujF`8ZiFkcEd3-Z9R zY7c{^JAV?eacIU@W~(FEB2(ckJmFwYuZRK?Cu_=p9lW1(I(QBtWQCHc11-XUb6=^c zI{S80?|M@sHW}H>oIyI-QVsIRfzKO^YO*b-icZ6G+JZB%hn4$crx=;WQIw$=5A+mo zsg*-)4cbMuwQiD+)V1_gv<8O0iZ%s=Z=2Ge2~6Nh-|2(hkh_5)XP_Ohm9 zoS@S~Nc|-z+fy`z!Ox76IRw3?rIO@8BOxIDoDar$`K=}%l_YM> zS9kJgFie;n;OUi=K{3mmN{2+Ud$72|Td=rFyRXl=Kk7#7IMA5BX$+eJsrYsOEw+WPOmy}(eYYuW z#AY|H$_A%!Rj*Ri*u3?4mn%8!8nx`6GANy20sb>|x~xiNcNvgu4X+h7#l-*seIUcO z7T(}9Xw&g0vJAH6?hSeRHaXfbDV^}(j|Y^lVg;PCngiVfn-m;lAXcO%JGL{Ooq~GH zuF1r!?Ka00{}^@E;?_nSZ0F!)Pwi3#yLa!>%JqTzh4McJ;qF}a>2w@dJ>H`BuXR<5 z{MG>h)R2-K!UKI%wXkiNP*HX>i?OQ=0eegqYwdv!<7X<;yWQm2=^z^x*)%-Kp)?G} z9Yr2AVmn@O#a>TFBGYvgiNl+mG|U*?(7jysbms|d_8JE}FY9!*GTp_ScU!@0D@Fb{ zN6?9DyzHeN&OHOD+U5I4=q7;-qkDa+fC0@6EOaeQ@-h>{k0eCfV2Ib+nj;!gWYY** zI>xwKF-BQbe186?U^Bt{L+|AimuCTh&c z7f5S2$alakqi)%TfuywnkJR<8p(vqK0LyZ6pVhd)ZWUY(gsmi0@oUt7Un0F4roTSg zIepQ1x%10i3X{NqE=YBSqeHMTUrFUhd95(IbAi`WP|UGAyiVzNv~9!dDOQ)*ngZ$q zFd#_7L*e9j_w=}4H%E?;CKqDFqC(NFA|1-=w{gCtsI}AsI(fFOa`JM^+6166qySHm-5(%>c=#gbUzg>C+Hv&tcmP-CrHcA zM>?mJvrs3QPCGNQ`*(ASsjj{;PB$lX(}^)Fa&U!G0^OPs#FZ#CsGjA{m|Tdwv?(o+ zd?Ms62N97#K(gbh4nxAqV;u%05YsMWa2W}+hnR14QasYcGpK)WP|ZhI!k}@A*~w+z z;#5+8g&t{S9ahchu}J75G@zkFAGZ?@a%xG!qcjmfaQsyAa#4l?A`%X+k}UXRDqs{5 z(qKqiy1zp%?YHAB8(A$r+}o}kID5ExJ7G>QLgg21x79W%kP;C!{+#E z>rG!7g$j+wmRkBYUXt<9rDlyuc2;IL)3AfzMJY(xfCavB;0anR4oYbZ74?l#8ZAoB zIAps`eF8+8ZfW2SRC(qutyIK7CopC;?HSGYM8cQiA6oZasoT=EaO5<%S#S}lQup5m zI9awdKzzzb0}1}3d!B+B9?{%FX#O||M9lFEk6iltp!qhQPR`VvXZXU=gguZ9=W_hi zoYqZr6eqF-vN-%U(uew z_}{mKA?a5715zV)#_)7~jXuq)AHlwH#kG;4WALaI=X9wD=Ttxf;;Ugax>y-Ss0VVN zbG8yv+~>aisO07}g_|tJmp>}HWi$8f@3KGI9SpDe!l=S-QB~L0s_J;qgYD`+I>TYq zRp0+czuUk&CLdRNn-AWV2cyf!yk9|sWmrP+d~zgL0*!jcQtkP{nRX^5ObDhZ}YGL5WqytGNb16eW6Cg!{ETIH*}-OJjlqK>wRR9q;_miVzL{3kUe*>bs#GxG#^`Anr8bf&-O4U|!SIJLBWB`-vu``G)5|~eS6V2u*#ZHFr9;uaN z$23;7N`|kj(M5_nhe3?~!eRpKm|DZ@f*h7Rloo59QPD%*UG42nX|K(Pw_#MecY#mG zq(8PAd9ta~O$;>awO9MM(0~u|!fW-W|7QF)*I#(Ov+|GT%5Q5c4;ycDxo^MaA>*6l z*JM^AA$NfMpw#&7@;Bw>H~ocA@&=E;hj+o`@8e$&`PqWV3AnphoYhMD0!qSC8Ph5H zqXcijYm95bthw*y^)VFrz5kg&-st*wuAxM>3UYsE@~-5Re3lZi7t%6dN-Ea;ZOX;+ zx@%v2wS1sc*^0f;rSj$60*`LsKIH5RUQ-u>!U%m&c*Nn!fA?M9W`TY}mi(trPTC== z7xD!+<*0tp00{L1{8Dtj?Cu|))a|D`&ZmPzybd-0$VsaIpEJ61Fn`BQJv-3pZ}Oks zEKz@%{0-e17Gu?|f)csunehe4N+2pY`hX^tK+?*}3dO6s?4!#&1yBJx{`7ifwfwgD zhmdn7xiN+R{lo?=fqnjZr07Q+ymImewTxr`-)Ngc;_YOqjS=AhI-z;FJsBd03LSy~{9sz3P45tKPN5vika; z@C0*|YWySaOLt|VTV8&y+f-hrRtai^Q#hBL%c%2*7Uw->I#?ZtZsjJ6P#QooKu=@36_3O!M7&S=T(~eb%_`ja1{%<=|4Ge4G zKs7zMf5~Yo8ZRY}RnSb-J4eN~mDJZ$)UT(gUr$m0BTiAZ7=+Vzp7YbtEdRgw@bvFK zu=@J%5B)di`7a(<-MWq$=f9Qe+FJ7bckO=V>-q0r@$c_BYGp(F{U3K5FU%1rzd2{5 z(Z}J44@o8ek5A6__MhU#1PA*kxo?znVtWn@vrFf$q_Z){ilo+ZnIddeaQoQ8z~%(pHYJs4sXPw-jnEK2-#9mVnldE}`-kcUyT z4>Upt@TMlLsPXdf>Dhk$WMQF_`0%v;OuDtdcXGN=O?<8&{IsyJZjSTKamw#mA^p%lx3c+v* z76FmcSPpYC`f;Zt+e8y8qE1mJI(>x@P)iAKa=RH4bs4seCQt;RWx{=g(Vvs%1n=q7Dl3*zu!hl^nox&t0bbMk?NXx5W1yXy%u_0atihmPH zbJPQHZd_BStN0}hXud}J(0EX$!gI!L4uEW8STGBa?jMEzaPq>EMxph6x)eQtn-N(P zwueE&gD_gTWI;x`_9L0$s9g2@d_9wH>H5X zeG;Z*xEKbSgA~Ao$uuA`i$|Wg{zd)wu-eC{hcatoib-N(3${-qS_A3Q$>4H}UwJVN zf7joF3@@Ds`3Id=q?h_|F%KP324w@Lqv_>>)kUp$Nb>R2B9?s-L*SExIT=K{Vk$$8 zW=<2VBviTXERG0oV%g&h#X#}vA>PH52d3Bho5aqznG7`1O@D8>hwKKKAqN$}%w zoTrN9=c27s-@xuyc|L$_mcX(rYF(uUq;&;36CGrJ>SKlSl@x4biql%qiKPMapi$dt zoxFPaS`{HnKx2}GG5t^VX^P<^}qq!=Zf8>Hy{X@$oUEA1Pt0wfn zmG$bzSN-o_@z3*T0a=;+R8ne(qXKWaks3-UdX&=AE3k0MhQYT=AbZWs)QBk-M>sFp z@;e2z;C#UpJF^1HKVL4R8sY3DV%aR0R>CSF|4e0YM6d>it~sZeL5wC*DqQr7QpzvZ z!>eIXN0MDEC9b}2l4PlxLxSe-$&U)7!C*|=Y-fX0!hA;s-m1sEYsGs5sXHpYMdwyh zc3dd*9&wKBh%CwOX-sAo!e%#;?VhI~Z{2QO6#IpGK^f9nwNTc%dSqqJ25DkwK$X9h z7zJfmQ+yP4IW`SLaEg{vf*c8h&Cw{)Ui6`%HZwg1lrUa{Fl#Zey*VmKR{&jCr9{=G z*CG(S*g1KDrYmom%&c0KT5fusffn?e{5E-$-L5{Q1C-UU09opyG;-Wd0z z54c}Rf|w5nzW!l6^6}si*6mtD8xm*(hB(Ru;g7s*U~u=UiPP?HXBXE;0JkkaWgdo$ zLRqt2pE^5yMSx~lR@;75z-Lt6}PfI$Lrf*!jf`+GlQk6SFDWp2`re(6_tvY` z4U+%SB;>37{}=o_IeYeO@0a?CdZfyi=(C^8!N526Pxtqp9Pb?O(HBS&I$?S!cbmCn zTBF-+oE)AV?@|ejJ$O;R&b5JMH|oEf9`7`!7mz^SS5%G~q9o{qO8?`$&K5=FUn9AQ zj^5@K7QrSZip-gmv#AaCX7}jm+5XORY~9M!wIfv0 zNBveOigQc^gDs^q-+i=LcwRq64;E-H4|BP-m0N)1qx$i)qFNcNl@$)-y+Y?Ii`#0Y zsaAH?N?om7s+D)DQd%!9E~=FwW?uXrTYBn6eH=~jTCLHbJ!#Pe%G%QnGAfm3Xj|)* zExIR30V9AFNc~y{+F4Ra$; z+-|4;4xf5Z20C-aVMIBkE1jzWARfH3dNScSvHNJaBOWi%P{zNajsLaM+J}``Vyu6} z8>+v-FtHyZ={ZLF)~vwPW+=DN!R~kZikXZg7ZC_Idjce&$H0UYZ#BoQD~UwQH<{3# zD>#Hu@PzKv#hw#3F{&!#smobutIr{J*<@i!@k~|)nI-@P@8e~w4{Tkx6HOv*5;qui zE)iSm`no9B+Bnhc#RUjE(2enOXcUHk7S7>Yx+i$aAx0$SQKD}j=wgeDW(S8uha07v z9QeWu9K`-W+@WChQUp`Ho~4{a!ldcAU;kzI@a56oejVoI0457K^1=jaYCNB!GZd zb;WAZr|3|CpdtFm#<5(|P8V?j2VRAx8D-v42iP@oU2Fp_!-En1VwC;fpxwFX@NKp+ z2~cFNL4ldshy!--*h0E7dGsDRv+e`PHJ5bLMeNkm)}gPj2Dp>O0M*FvF6U1bAFH4DPG20JovNLKSL)}T4ZNbLrX+ zSi#Y)7EpyD-sv8)m-XY_7XWeR$=?3n=_~B?v%S-U`pJoUc6h9Ipgc&fr+d3+`#Z<# z={ z?g3OZ$UZ!9sY36NitOu6gX=Ihbo~o_Krv2sN!PMV+Sw%o^v25#0zV!M8@gDtMONtL z-Ud;Nyf%6pWC)YWZun@q*<$iCjMd~1z`-8yj_?dn`m}yjKX_U{*oAF-k$YiVSj_d_ z30XjmahgopIoYB*R5GT!CIIc!$hZYqAIGa@TpHr>bi%J9F-rC)14 z6!i3?UGm}(86xk=?LaOU)rA4NIMm?s@uz<-E;<#je)^REwWhBYqf(Gv5~8@-;%X^x zgK18~#hMxFN`&qFXL%W*>4s`-_nIG}%*Gle_6K;+sX)_cz?$Ym#p>&~<=4>uH*c0d zy{j0>5LAvI;DJ0jP!O|4UT z^-{liOjM#~^{JL$Qmd-G{AP9aPK*!m-)c?8r8fmkEv~-)=jz+##l_N_N@+=e!36mE z$D&%ISP|-X-rK&;m-86iEuUAPP1@pO^{x1)%1a*px42l*gn$;-cklKkqwcjcrp2OB z1O2W@gAB#1B?n|p>Ealr#;cdw@>u}DB*u23OE=P2hrQEbvNKdj(@^2@t@^w~gW?W} zMs;+=!q^gr?HoBpZ-s&NJ&Sk7d0sabdl(B{)R-cNK~Gz)9qPj!~$e9l)eQW00_ zSPW~#_MYrKeag%u^!@P3|6AWZ4QVXl>k2dN?jQ)-7Nv2Wk|nEY2R~9_XyfVO;Xd%w zm2va((e5tN;LC<2lNwA|v!ArGf=&*PNW}s?eRuz9kxTAM21s;EPth1+Uh}vDTxmP^ zwEk@8Y#&$V-Tkwtg!7fX@-~elOtWoxo6YQVu;Sp+3ib2kMSXw2m{`RE3xrORvP3%Y zOymo*=K35xxOD=3?O{j}__K166CDIqxVwwBK}SyH*XvM`L>l{yh!d@&Ak4mo(F!E# zRyWr;CI|5i#-*ci`#&G=9HoS?DdcqdE`<~x}wvIza>fVSrpX~{fSKjpKJ2&gyC?aEt=-mpy~N8*&SLVi)d zng%TvPV2wy9XvavXKobcC~DaqcM$TporA3hJWvunLCVY1onuPC2YeSI;xu`o^jB{B zE1k}TvELNZG?HFFSZ_e zhSXQjX+!WcCF>VjswgM^;@c5=_tHB)LCVRimuIJYG;sPEQqNum~X?UJRDfj^I zQiMy`ZSJ-_nl!By*mmFTSE~uwP9)hpMh~#>tMJZ;1>nID1gf4a>CIeyd5++Km2a9JZfN`8mKtykbPjXeumT^ffO4wpz;W5JYinqOgSK=9=yb- z`qRBre#58j9Kb~i#Uy#8G$9~f+YTn#0NSVSyQi)zZt#(W#ZRd`64unSeX*+jPCjy5bd}h@pCulV$iN}4nqr zNJmoPk<%u9CzW2da~My9`^rz-taMaX*~m)BX1CLfO)9_YZ>{0Pet{RAK5z;QOz!tl zzdab)FZ?cFbz97skexUSEt{V9_7+i=>ko zulr3Wz<1a=fFMR+_;EYeYwB6bPmmHAsbm`DdIy;sL;A>%+qr(AWHJqNO<=bYJ2~vT z{Th87kD94GHg!8UfC2E3?LGd6ITY+kl=v1O{U=Bi{e)pm#7Pk|g})zPa>d>xa8pQM_%?Hrp@ z*;(Yi!&kkkInz9u=HwFi{#xj-gYFubwwL@{%q9O`YstUeT=EaGm%M?wqDF6?{S?&&08UKI&F9ie=JeJ&YPr2N4 zOgW?Qj}oC>+jz79&vYpB10Be`$t@^8JzEMETH+HmiW|DTxCm*>Mg6W+LABb+(?UG& z&O|_O1;*%N6u~0nfKgcHcRXnsN3dwFT&TtE8XL%AAW}Ru!SHTuY>EdcHTAh>i&LIT zO;YHj4j=Jsi5}?CX~{NKP{s|_Di&0j0(zp(WnYC%pq6T^v7X)wxE*eO+b_bgRmRpVCX zyuN*1o}qxLAZcvyWi^B#ZfS9I1?Gmcif)CD1Q)g!3%&_T5%23lPVpNaHJW3`PoJa9+f^?O4kGQ#z6Z?pj3iL2A`_%7&_Y~Vs&}g;!v2FkTDm|bCIf?fHTiR z?zY98&E;ISlU#;c^ShLxqx2gdF38D(Am5q;6&=eU)&*jLqS9?$3gB`{xBjnbLU1^# z1)p=dNk4<0T;efiM#V3rg3QrpVmB5d#V;Qz(=j#bAyI_}Vs&xx;>!jjSxX4lSWDiJ zXD){UjQVMGulN(w!!4naYY0yBDPxj}a%kG4eAo&{8-}1Ijz$l)4yF?n%VTUju?YG^ zaLP4zz__7r(8doweqN0S4P;_uy$SNH9StJ(IDMn3+vg={s{nMM=@Z)-!I`sMo|ly@%9pK zU&ez$_fdbK7|4^I-5*c(cTQde(3pbCt$1XbL)Im7MvO0FAXE&%4#IO$*dj+j#P|8X z{$Py%3I+AybWtHre*HQG!667?3df|IJqe7-)n7dgx_`tVTu1SL#wfUGbWjx1k{K(= zEn~!<&K*e!x0%x>vjf#Wf!q@Hx=x!dbhVEXk9{Kl2syBhqLtS z45X*YcY4d_T$XM??56pe;-_`{KXESn?KPKzef%N%i|J9tc|LPXA|7xDufAw|t|5da9))W?;{arKryZ=qIzkBo9-<@Ojchh6j zojNu%kUrn+@6I{#YRr6`@Z@>d|)2GdU>G0RN|EJIW+mTjqzRQ6N z&UkGS_}?+-O~-FA>!r-}d2a#R;nAqg7@%30pKta%t(*6d?FJmcc3~P1FrEL(1^#p{ z@Fj#6ikyILg8w`CfOPr>T!2bU=K&h19T-Mw#;{Ds_k6S8v}(Rn@Egp0-Slbm zUON1B*8l0V{&u7lobP1Pg7ckC{{K7XyL9>n^PNgepYIx|9TY}s#-L2c_k8o+v}!)H zr5nt5-SlbmT{`@AzW?d-{dT04D_=`6U$RAg*BN3IXspqM?%^;f@bta9W-~mr9N@<* zwYUs_uFDdZ7~bS*Wkqo$5^Z$gTLKC>xE6jud%568baO$c2!-xWv9Sdg6D)DeK?BKD zc#v7P;BK&~Y4+e=P%3MAnyk;a22KK>!y?$R2bWN5WD(weBrYxOM>e|KYTj6YD-$WL zZOp_aRvM413Hnu}=v@mRu8?@~axIP!W?NvakNsefF#3xe@p~x)FOErZR?$q95{05$ z&La958Jl5irkxn-nP%Fz9vE!rqhB*)(UFn9AN|ga-)D{Ru^#TV?cADmFUqqoR3P`PkA59~X#Z*)O0ov$zj<`xtIoxko=i80zf*Xq#?CRU zoQsRgdgOH9wxmY{#d7j-|u zX`)31G-5k%D9v^I`D5TGAj=3|baE{wY6_&q;k5oZs{Ts6Vd8b@b=Rd=O@>ql2`9UH z%y*Mx?kDU9#@w*2+;bXM&0CT_s-DXpG9HFN{(E6>R{i}FX-BPe;PZ2*0Wcs~Q{MIO zASyGWA4P2g&Pt`!^JD%wdG!+hQn(!o=SIb$LR`;GXg6H+ZyW;GiGa%kFc=15IGvme zjwW#1I_;E79{Y}P!MAsW#^N7(#*-Zr?u8s4S0!<#jJFB0P9;;Z48!T~+8R{*F>0yS6>LP+`0oXtQxOh7LkIuT9bHXog@yu#- zsOTF;VzzV7aWd8z_IAybYP&5BxJf_trVo0mACW4yl>6p>MKcBa72oiy**$J4yOG3r z8ur`VWDDkh)$Q_BJ#<}6r?sWEJNDfQ1SZY%2u|M? z;5!8ezH0zw^~e_kKB+9g&W!_8z`MC}xn2|GIQTCbtt30J%}AqrSXzS~2BX4zSUMEb z3|0-Cgtj0MRzwv;6a zoR&uYXFV%TmrNKGw}@?{N_i8j6uA+X@`TbHhOvWIyzg+s=ocszqoi#q{7dQbu$80O zXgKXJ2Eq;KVJnwQFbd0`d|j545i53HJYHoQlHfk=)EEOO`pau#Og zt!q%^=*8i|E72RsJ`PJrZU&=Akf*3hb$brpLFx%RJpTO6p5`{iVM6}IS0dBl)R*Z` z(_PPbn&Nt%lcFgbDLCbmf`U7I+!t=)O- zLSXW9Cayn+ed=%udgNrt!M!3RIoW7BWK2MJ`UIy}Vk!lS8G67DO0S?d+zZqUAZ6Ha zC+^hBo>{E2%9vbVZ_NFAWA4`*bHCo0>)e=&)D{7jfVT0X$XLBzFW-AuS}$*|7qM&4 z56-v&fFo=gkTGh`5V7x@qYlO`juE|wNH`xl(5NOLFdhRr(KVDz*eBQVPYN~?81iyl zr2WJ>Ugg+=fubfJ9M*rqsP9{WD}3j>|CP;$Z+pk+^!s1e@7=q<#`nKg?%&_sg!JlK z_5S^@_rLxX|5lfCYB_OZE8f7Wjt3|v{G&4*MqTy&Z}hv}Mb@;^+kEh@JQ!U*#-hg@ zYPAikW*b)on3m&c)Qk1hMH+v8w6ES*%WGvQunMz6hkgIPg_^?h)ng|KWHsRXsWhO* zWZDQAHm2FcJVkEJ=W-ac5%;Vx=f=o=ko#Xn-C<)KeH_20`_@iz5m9vAs=`mOSit

    <5%tHT>&9?AvSo>VEaP7? z*r@sGt;q-&7c0b}46a-Ruz`zl!K(rPmfX%QU-W>T!7^IR{hnKR-{f21n!_5sAc2ny z&0$GFwj!im&{@?*0S%`{qms&h8*hEv-qNeS%9p63mB-kYmB+|UbqWwb)E^*__em(! zhUPF>!JB@*$c+IOQ=m+r%_vbvw%eRpBb8TQwG6*hbBe5h@)o4p z9xOwHRw3^E77Z>6^tFh+>P5Xc8W)%d*Gejo0VxHl03h(!q`+E&mkay-Ghb;I*l#=y z7F?=>uOuBb__a{P#xAEYl8GsX)dvnxOXFNh;V~~EXJNr$kdan6YMi`!`Q&iFgq

    zgR}kpVglbV+JbLAwx4~@v21|igQb8(>0+?`UXu|iINl4RXgnG9lQiSy4Ybm)KD(|U z&JuOFqwCIV={TArO2=tqh=E@V-nWPvfvCR|A?Bq^$Oac;kjO#sEWpIXwW6qgm&46^ z6=~U!?MYJw(>}Uhz@OaBS?;Je61wcrkr87If{TylmQx#Uc zx~wJTrQQ-t?)dQCck1Qg(=)v83|7wtLX>U=%`zA-rqM=k&_)Cr3__I+n#K)~bqm1O zoD?BzC^Er-$Vl~G^JKrXB9B`rr z(nSG{FNi=Kw&rlVqe$;=K@{(C8WI5f=1Y8LLp9Om4?j51uz-Evx*Bv^(PJkg zVTJC4u#GR45??4$uf>T~*9lh^gu9GcijC9cz#Zbj#rIAe51Xy1AU!Semjx@a zuz-@6+lgQc+!;qyM0GCv0~lD61{TCNHw_QJE%3|TyO{H{)SSQoXQ6xKz18cEBL)uR)GCk)3?%#!;RPs+y$uayCbGg(oUyMW@ro;n8VBWC~p0(;WDyA^t9~3OfQqEw_+n zv3^g2TstB3a08$Qa~a!RXLh`!^IJndx4q4a2?JICIr~nEP z#q?eti}2D)ls|p%nWWl)@K&v{fm1=~lmr^et?XZ+U*4>UWG3Vdllp#rm&g8weZ7OddUAM(wnH*O+%G^hco9r}#u%r^ zmCrxos2jD$e0Bl7a|Rm^2+jusIuk_&<)}lqr=`c*Wq(z-X?9j?B2|K}YPfGxv(4F2 z>e^K^Rv$(KB{k@S^yzf6*=j`~NCCT?0HKUYi>y11$2Cq?jQ|3f_gGRb zG~&lQ2hZzU8RLmlIz5&+r9-__`4Mf?QAONm@p>PTb&4 zHi>G&(PpUzXop2+(tO@KA`Lb|QGnzLo%_+}!NhzZP_(^TNGU0`jt#%jf+!m&xAiqv zWh!q^W!FS$wbju=|IAB(S(s7_zP=?cK>s&7A`;aHK93@_13_`i z#Z4?oxOG1>G`#a5z#GY2p!bP>Q|}BB2E}462Y*(EJ?q|x8XyV7|LpHmwUnDxrp?rT zYvjo!(mgR3j0)O#pOVh!s2cILH5gtOO!HuWBiVyxBRtXWBM)m&hH=5mYHEed^1<*< zGj^7-nI2g|QLl^XJbG)cNo|Hq>55W>y*msjsEG)oFs*ecrgDc6sWGCriHRZ!{MkJ7 zO?Q7aPqn;(i?9PUs8iF!;-JXthgje;>?FbLqj;(W27?#FA{M}{aw9275@^|1~duKs_{cJ@o=_<)Z(XUxn5Icu_{l4dzqk4$Sq_@V=)89azv;7(G& zfcu*2zhM(ru#)j4E5le1ICbC3LUzfblNBt%MtNBUE(d6@!)IcFsiHAG1Itq;Zvw>z zy;!8G%XmzI8JrI)`gh?wY6JeQI$178QDo<`#S_Rl*AcOfs+Ms40s_Rr*yj{b&V$(5 z%BK5;M*KDm2H{Y}l-kE<%@^ZiTSq*E7J6RHG4&jobm)IoU9iGW}QaMWQ zGF)VB@GTeOsX{1k&~OvrvG+S(&ISon4v!PeWlBfR>TuCTBiT=|Jdlo{vHRk1Z@2!_ z&c45K@gx}MxQj*nyeIII!s4p=9#s}xN;VpjVw3U=tB{ z+Gw~K>n>f629sgl5mG?}KN$2^%--3TxKSYYzr-|RwAox1Q)SrllGrXq&m)xFNvjEOW|g#x6}uJF~?hA+eyKi;TWdZwPy*J-6oZz(<8#T-h}tikPK1Ayt3TWSB0W zCI~bv$ITW&wQS`Qa6qE9Tfek14Kowpn8wQH$iq+)6eh-cWZ6P7dI+K4Ssh1B;TB(U zasi%;uAv4shYBwzM`F;AU=Z;L!fl5@FnSYrB-|BA8z{weF6%Qy)P{Nqd>*J-Fm)rj z+UaGXrra-yMM{sglN?$}nMEhd^4KMo@boH}SSADC!~khw!NGyMdeQ>wtYCKv&Z_dA zUQ~YGIXOI|Pz^Mcm($uWT$Tqiago>i7DymJzv@8H_YXsV@=Dt+QJ!e-a>D$yxx zsxoyKmC8}FQlN8iK4l*wydk~Ka&44~MSTW_`%2ayUNvKV=AF_MS_849z#->e7fskl z)yy#%lxGVi3m$MJ&CCGrrM9j*-FB8v(yWmJP#ccSXk5-=7>;3qA$;bu&2Gz++1#8k zAz<@>2o}iwflx%6LwS2jqBILxQ<}6tvCXpM2^}??)cLZT%}KHwAyP3GHyZFA-9K*_ zbLL!Fj+ba<(1VZ?a4nXS=qH9tBb#8hJlaZsqTi$#o+Kj5lu!gSZw=00kVhM5C-vi+ zGkV-T!z%seLW*nhOx0t*XHJm}B22GCP_@xMcv>{CggIQYvx`}L(6kj>h^9zvU>a_u zKyl2PGeI$X(J?7I)=Dza!$DO$YMQ67E_?v@x@H30meij1^X$VPo3&p;zN4?UDqZ2s%2|_ z;~&&;{TLUkr2bV)@Yr~Ajt{RNye(PdbI8#Ub9w;UDCCc*$}RP6j8^rSWG$;`8A+8; z>ZynU&9Nd|e=h0nvm8_Z+`@wU#hU!56e9sSSJ*2wp*h6ujnf3uAi-v7OXXR6L!d5A zb3^85iX~?so^~hrY)tdhJI0!jJTl<50NtZR&{5y32jK~Tb;@XT?%sXt+rxL%W3^^G zn!xqG+;YE#tt=Xa-@gFHMoq1(Kxt~yztr7Fsw(_a+FBUO)Oaep@tdE{4UaA6R%vCU0R^jghV1{^*s+ zTF3Z`7Aswc$J0MUwR-Pq(<^C2LoDU0Gp3mZbT|R>6d9zF*_$*!wx?)C%}~?EBUzRw&(FU(-MqyBwqjo3?%eM%d!p-*-uzFrNoH}@hT{8?Qh){ zDs@8k7P09k*JK0`E#akR3(!n{3iERC@|g(@+mOk@%m}+Xj7%2FZ3Z@eex1of)BBZK zEHw3jKUookrW{dI)FsXqyAx7RK%9Y%=4h1RZ(!#mfg92J7FOMlK9GA42aC-4Y+GQG zCLz}TQ2+hxtOWz~m# zgbBy011p1-HbcHJe2MuK%NId}Bz7mR3}YNK)g#wU)7>yxfrP?WNr6eQ`>kR(#F{ArsI>!IUpLBpw(iF302aIpB%?_xzjB|2vjTV{TW+ zbpP+o&B|Ie>HodCzW&w!`>*)-pXmQR#n;=WjiSrwV(b@edy zfuod3*n6b%*Jw>z#v?NPK<^53ea2+o+1o?0!-JF4PxA89&i>xhQtop}!^UWrKI~os zb}vsR_P2md9qcgPP+W5qoZFnQjr-nC@WkZi2pM7bR~T zT(3q_=X&1Z(}WA5cKoG8>OAcU5JuFt(xhzVDAjjw)ETw1Z9=m7cL1_zEhe4j=g$sy zUe+7OAbswf)PWAxXcz8yL2A=^ot)H#?VOz+@;85ca6q8i@`zaqV}%qvLYD;JC;-V2 zFT5>E6_S>jR%(Q#j|4s0B6W_gwd(}P=tCbNcOVJGU_gwhNoF-lHcQ5iDmPHX>W;Xr z38jy}iwgFYDM!2ic#hMiqAf?=BR1Cgn#rW`;pQ?n=QbPc(A*pt3-dA>IT>KH=4QBx zJ~|(nPTcRz>YXfd{^RDE^xyRdAKb9)vx?oM$#J>A z)AOADvb3k^_8>p|qQ+$H80!Z=eL=Hio_<-=wBdz=D4KA-GAw+Oka5mz54_#tcamo% z(%sLY9=q`h(j9lz3V-m3kW<2c3Ua7*o+t*^P0Web0NnfF>5}F?R?FkCAYmH_ z0=iitg}UcTXBdahvgu}-8k+#xJLVO4WlVE)>-9n>wv&e3TSb z27l0Ljo395dA+&u*7e8ylTqSEADF2jBaMO2uxc2(rppS8S(wC})l>yYHdY|Ao-4K( z9s5Bgj~@}TcnZt~%a~+XUk4?Fq4o47W&{CMnnIdCAQBJdH?sw7RUC{cEv9(8tj~kaYnw5IP{v)<%9Qaz1b z>N~@d=z?oKYWtZSgLKwf60Mm?(#2$5@Db&HoC8@7WrY>G(|h1$P4z&Vx?Vc2HbtJX zBDQAsQ3DS4(fv5Pk1%stG4f11Z)u-gnW?C?ZHk>^nKPnu7uwRgxy7!M1IihbNrr)? z4p8mb#S^s1aS_vm>l$aWs>Q6@OmTe;RxaFWeqF}_4)@${K7@GrCuyA&rke>B-r7qKwg#*zBm zrTcLJV;Ex=tMLw9qLQw?c=P5`TQS}#Tc!yG;_#Vq!-h^5lsziL@zHj5eb(hf)Hr8vpDh3;IiM954yx_EtJ%!J;SN!R6$D{{u{ zAx@952S3FIq@6DOM-p%+N4AXpfwcMuJQhNVHdb$jkR9>IE(*C+TU_0iyBf?vC!AIF zqYor{4!Ui|%ltH>ZO7bY+*vdd)~KYs^j7?!28*&G9Bz;vL&U_Ka=s_gr?es5Uj}Ow zvSkLJ+7(!JPC#{&gw!9Tz&JaHlsM}ce+36SEoKMZPqZB6qWqEi|FmuE@!n}&bd6~V z+0H1WLKB7i0>}~?6N6;cy{2H)z{`**O*65H)ceGc__9S;o?#Qrfi28w!CAMTJ#GCMUZT1l06xJ=hbK%6}MrNfmV(e?fxLEdBVD}0rVuIwt zTr@$cgHn$aVn_DiB$8oYu&t$IUWa0|OM{0T+HLF{JS_y-ChkFUj&FkU#zlLRk_R7A znx+unT_H=Rl;w0*f70{7>ra9ne7%|`h?L>VOeAKYDJ(yc+?2pnaO>vc#le^#NWyjBm8KN5Sqp7uStRzegAvW?8125l(K5(7_@Zm)C^+EqLZWoUcH! zy)b81@uEa$iP1vp!&L|P2?jQyHsbAT@X7abD&$Mf(Am%=UbU&#&uoSLY+}YH1>Wf{?j(uDW_HY&>j_b+t-Z~>KDJ}KWO$tkto$|ON03@Pr?}4ev?7OK z0U^TQABcW9pmcSl(q7bS^@fG-Si)k@ItFV(PV=W?(QNZWoB0Lzal!pO zbMmEX+kJs&98b-{=?#+8=rlG{pzz>$rWon%Ho8%hH4YrRZu+6RYm-NX_;XxfmYH3% zYzNGVHutX48ccw{SG1DL4WyV$O<_OGqT30NsBd`w6dW@dk=pH|>iPbqMJ?bO%X(cI zdPF!?eNOesopXQ0zyxN$cDlf?#$gDZ13Uf9bDom7(={Fp)`Gxa2)*5;BmRe7kc`bi zGKyR{5=&AH0XbhC_GojZJS z+UIMou`>zoRz2iF<_@Ohy+g-I#?3N=g0NazhcX5%?Dwjrj-sQap5`=`vAli8opBC# zXYi2@C7OPSF}V^6zQ%HW(+7q1Xhp5|)kg@7NQ|?GYBk#6`O39&j<tRYbM5041AcC$TIR9j%>loi!7ONPlp7*^OpTz|fQ{IcgX)30=KZ z_H0~e54=dOT*`^!+8=D$y$8!_B#ijMA0gGxCfk!lHc0iev0BCE(p#h~euSJrn&|ri zDv5M%M?r%q8$}BKSt)Ej z101eAJ&XQRaI^U(xY_(d+-w&A@M-Fj>J({IM;{8$>N$bnUZOUW3CsW@vF^TvMWkF! zXYdDES?P)jC)pew@~cQlXz3 zIt@h!=@-_krH8Ecu~4tPYx!t^kdp7-RaCYA{&A`1MHsy!NMI2Lm8-sdZck`$P`@8G zLi>;){NZ)M1&-P#Jg6X5k6JE@@>aBFbL~hnOtNI38^?oIM+cK@3V&eREGJyP<{LmF z?Jgg5istQ6pXLY_==9}yhbB$Fm&Z$i2fZjpS1tCW4xqv!Bw10KZ~EPxm+;w%rQ3* zZFx+W3&u&ChO$(-N_aH`gg24b8HbjeN|(5iXW?TyL*s*R#?4$uvstIH!HE2*0-_^&|6X^r@S^Lx9BPj{ z;|aO7ONkE@OEHP*POL5_BT@iS&&Ug3N=PSR788SaLoLpA#+AI;D?v`?EQ_h7;F4-F z>qtw??_O{}`IuG_J@@Du32dH&{KI4BO(`v?kRiq19S&G^fC$8qgw_kGlT9yO*xg54 zh_=y*`D)my<}eg`GIXls*ep8AimA<_MG1zCgeFHn=Pp;7%3`mQFBgJR`WdAivB+V| zDr8K0&!(dW#-v~8MF7b*oN`<~YEw3L?pN(9mUb@-_>Sd+zIW;9Co}Y5^K3__B6l8D zS@sAx5?^uhdPNtuUn_qnQOs4H*u4vAgLX-mHTxD~!vc6f} zten+MK(ghyreY4`A=wJ_`%i=mymjp(hDKPcJY2V$LCoNK<~jY-KDplhhwiV&oejy# z8K-LSYxY7Qp*6(F4~ubq%tUOgApM4dE*^-`bLFi*N7q{*&Y^=$n;npj`4$_O`ha=cf2%hMFLq8|ob3IhZtuhpOc-GVOTETFZ)=jIe@z}Q z^r|pePDT%GdzgMlglqRRNWs)1o2$SZnI8;rz4xKtoR~IkanMvRLm}kC&(U;YN8xD| z%{UW|^e|gDC2f)97!Ep_bR<{7?OM$oJ1|-j7ld=Vdqp^>c$b7bnLPB7LR=G}{$f0% zg-JV~%r=l7YB>iSM{-GztIp!2nS9P}Lnnmi8{XEFnr+!r%wkbbEJmd4dUfC$&(1zK zeX0d#+N_B-Yo5)RW*pRN{yFwXOtJ6`n`?qmrqsOgBQE4zGq2CV;pgpU{o@c1L^*va zrg~x(_0FSq8<>5EgQ2rHAbwturY|rns}nX=SVCCT4-nhVBRsGKu(-rr;aTfBMnjKy zS9pF6;`q|yQdym`qq{~EmqCF(Ct^4U>X7g#!R;fL@x>K4Pp6;Kl*OZ#SsExJ6lo|L zcztl(jru%S@X0Dm0E#F|IMS7{2F}KZTrnN1sHHckrpTGY9H@-Jw5~<~ri2~WiV?Zx zmdEzBjNi+hU-s(<&re@a%)mrJh4zU zYT-E!>Zp-Pi7C9f$+_9>PkIGJ8D7dpxTAxi2A_&84@niXEKo4P!GRN7gZPRu5Y-X; z{EbpVPBZeE>33K*HKtX}-Mw)e;Q{?!{lG*USY5@331 zIw&bi405vujJZa;)J*kI^N0jF?v^t)u2x9LDoYW3+-eS^8xj04P2wT)?`BiJyyV}& z|MG&e98pZCZ-l=Z<4cYzTJf-7z(8V9<_+8P4p9r(HPOn4`XCa>#XU~WX_PZb4e5tj z*nD%(MJhG;HjVYB4Sed}unT@8fSrw6B^%z)U%)#h)xuctd}OddA*hIGutzNlzb{H;6qaC%aPqD*#0@(0X|pqDYSE2A z1g)jS0Llq9&?OV!jquuT&R8CjqmNOGTWPYA+{fo|YsFwW#28E!I+R0oGP4ub5086Vwbx{C zC8H+ium=lvfHaqp6doQlXJVN%F}_Z$*gH}}E22n04Hb+2$sZ28*T~?*0_-*PibLqe z;uva7MkrjQm+`HoFF+#I4@fNf;wWRl2qZtFO8EmCZsBDEI9rV)RPv4$^5tow9t?7V z+z~h5lYUz+|52h59}u`E1_+^RN+(Ft-RON2NxpwEz@q34M4E5ZFyf^_9Z`d^@2I^M z2BjIU5a9Olo-EeLW9JlX3^h|a1{z$wo!T~S8HB9&CEW3TbVBC(BEo#Gg>(tyXSC+V`y0k& zZR-YmFm*Plk49hd@VN4#uAy39s52A(bEA-I~sFf*k*|InY?T} zh66I+<#QKI5W`1o|5%8B!skAiEJ&hK7|(Fv`sbey#^XWHh2Rrm>iTm4(lBjIvLd>4 zC2@L_q>mt#3I+TA(>5xrWhygh*;dwi-;nCEjXOk za-3p~>W}f8Y^HNtJA?8Bga>>T zLe5y>Gy6hGRUOQTv;*FobW(9g&ai z^i7u%Z+(u6Igb(ASRrY`-rJz}7M5{;;P8VCj7~E+kEU4zFp=Ow<=voj392R7`Fn4J z?fhBY{-Q2rxdCVPOs3nnu^mp+S<}7LH5TSVo4>Jpf!REJ_&PD(RW-&%)%5&7s+%|H zNNhva|L4%6wb62fvq#D-*F|qJ*P{5WfG-3}UzQseeCasTl}i@dwAS0`wWH+GXuWZ0 z&TH#vHnHVt&XNuB+%Ftunrk;ItE98V3P52~P7Ow?KR9&5oz7Fg6r@WcZ8zjn;80gQ zD6wPyI%g;R_6q>1mN)jn9)zk5hgp=FkUty@<2&lb-~$TDyc_+t{R2hC*MnF~#}ERU z!bxJm-rKg~rtN`h1-YWDnW@gjBu(h0G^O&VY&GP3Bx_@6+=7Os z2|9#%mfxGsHK#LroN|}`^vIrEzo_s2s6Hw8wf>Zv!1dguOqv1=TdO zoWHkv50}xF1S9vU@Uzg{ZE>6KknK_G?rcKw2k1xsl@EL2@T=6GTRBhO6%FL7UhiG7)Em5i-k8_GKzm>^v$Xw=`om1zO z8=68-tEvtsV!`Wy&!BmqP~|>}z%7=Uis2cHfla3mLx-^^40gHj@sDna*!kN5kmuC%{Sifz}MgK4v+@F7PQeV-&SQiASzpGJY6n5xNu2Zi^Qz1 z(~=Wi|Lw?5f&^v0aknsgHR3vrY4J?U z=O7j3*#0Y=3-2m-&-g&|S;R;;hwNG0ibxvv>LI@3WMQ$`yN7~y z@=g|t)bHjX<98QEa&MJqx^S{gH#WA{S|mDjzW%$-zxnR}n~XcRzWs03{eNrs?yYSk@Bdq0tA4%z@2~imb^qTA{JA&xC4gDw zPntb-+mvoJEU~S?RCil}@7}h;WUy_}T@m|Q+kCH& z{6Vjv(ipF4tY7{x>WtZ?(VWNf@WzVIsjt<$^GT;mc1hzAZn-@TG>k8~&tPQ)ivrNj zY4u+svCKEkNGa$%N_e)nUsubbaPs^D^xcbP;nL+c3X^D`1>Fast6#{M%kpX58|E>@ zt+{CV4&-w-324Nt53%4&i7qLDO*oZSTaVP6H)6eTTLN>^+!Hgd?9CX&2dcuOJ)|am z_jI~IAou5FFW&UOjkg$bPGWUH*~Nm>yP{kGOq)&=K%0~CKyIO=tq)6R8QM2j1WRc9 zvVxMiq(ZYd6zS96@}|RlGTF?Ml$Gi2}s81G!nb^57H+H87+#lR6Rnvsq z>JH)vv+=-$Hx_$M*UkdkRUpudRD++PHE28@jGC7bsW=0zWn;Rr1h{sa zv@C9oNYIxt>{XGTDHp#{BjCXv>EJ83cFo|7)lIMjOsiY2P*2pJh)5-I*R+=aZ)iOO zdPESn&GD}Ad@H)@v65EGg3Mh|j)gO&Xj6NqPsYVhjN~O>%oE7#E>9&yc@NFW+q%y) z&|vRC%SOXR52k0iTqbP1Z}K|bG`fcPHF~zLy{#!|&3OlR?1RbW6%-Kf{01qu3(X<$ z{2oo=_iGJwK&%D|mJj?iHFy$;R*a%G^iiI^D3u7Xr& zh#8Pf75v>Y{FnTjZ~u3Vxo*7yoVx$3R_?7=)_DJSzq+x0?;h^|HrDTd-T(a+|A;lH zC!KiES3KAySg>Go1VS?IyZB4Byiu-{6>Yu9tp#>$V@Stq8YsdBMHC@MP6d`?^{Uxw zt#mu@A^{uYZfZ9N{4B@u)cieT<>7;k68?RNe;>kj0XC5Qw?cob^mm>9ZqVO*^mh}% z(Qyc-89~!l&r1tu)vaa;>3T@3sgUbu*4o0AvvQv%v(Fnwcqse)<(^C7LR@9Ga^D)Gf_=;nx030ll z-SVhI;aA=R>JYc5Vrf6pWZ8wb{>(u~N|5pGL zI{Bf)o~f{Dx|noJ2m&&zpZ88*9G;!3or72E=bhu@orBX?H9CdFok@fqun3B-@Icf3 z=4jOHkMU+Wgz&O{j6uOqcb@F+@14GaUZ`h#rw8?u6BHML7LRt0Pxp4u_IHle(b@6Q z;Yl3`?<67vd;~BB#}_nABk~Zy&^M;%uV83nXkNF?9t5MP6?NW|2SE$SaQ5&akY*Ry z1E02z9ZW*&SUmu%547_8tMPcawYvJ@!-w)^e}Z}rV5I~kUVUum&<=(-iic4PMa}4A zD;n~!BNbvmp%yIqw2SRFN0%^|9|og$JTlrU6x+m>lOvAT%$;!OvWoRgMZwS^YXXEI z5r`18CS;-}J|Zche*|^A8QU^IJN+f3kT~jIsHU_7tGguRfmjDLLsA8LN$4ifm5DTq zkSsJ^Bauf;8Wiy<(QrW6P8Z$YU{>HwPbEA-CLGapROJ3-JEo^qvisati`~?$;gf0_ zScDN67>)==bE4JMmn3=k#e`85^W~rjg@*!W#c;xV{#d-fg&N8yu*(7)M^XsWx2iO3D(PL9BSCJs78^lR2%QuB$kG} z1vgn;LXez^fW%1?Bf3^STFUIDSgwyh;Dc)FHCv+rbEQ)byEVcE2&$j-sf8qwnsJL2 z2U1j8VW~+70dV(KA2?YYH%AzO?0kg3f}a{UOCnVvTK5i~VPK^Ci8?$$2pHQ>9qhcU ztCORh-FlueX_39xhJ_vHm`ld|`5USI)vG6aCx-{BLIpUVUUfnl8$Z>LPxhcdo+OIA zFHPV;B#WK=Sl_RoLP=_9{u-o;a*N9yO-4qzNEU;YqpsE@TYQzB?c{~Y2DFu#ZGT_- zct(7UcH1~Y$(;KqM~#De{b~KFfIXR<$K%d;A`WEcFb(;|#iZY&Sw}G?d{Ecd)E1@x zk;MchIa#{VN2UBMkmO__7ZpDPCAly#c0d9KBsn=~N95J9?TK;kO$Jsi9+2-8eJd7a*I&SGwJm-G+~D--!ou1|+>n{% zr}Zai&l@0xoz(eLHAm`j0s2VF)pEJ$BQDGoYD&`{Yr|@u`2v$J-F4;}FQ6L*HaU>H zK~y?-_F!(Ck)nkO+Sy%hAiQ)->iB-3}lfG^aDcM&0jAn6u?-j{+U}6m7p2+${IqwnhjfRj4-##nMB61!cwqbU z^WpJRN~(BCjsJ6YcuEi-*zSmr5T!bUv=4I$*>jy?Z#XT0DPcd@p4AT-i0u|^v@yZ< zY3G2OW&306w%s{6B>X&F!-UT@J@1mUP9~T`(m>E|GABKBk~B#JK|85J(m>EoqL3~S zv|rw&ue+Irq=BHlRH9rU=tQf`hfU`Lku(r=B8f;E2--;o@&$tSn}uoj-A-we27-1{ z4M_t*JIO-QK+sMiku(sr2b4(~2-?LTlQa;tlgK0u1ns10k_LiKwFwE@O*}w?b`prB zfuIvfLefCc&Ie7>K+x`RI3x`O?X|#=G!V3l*h2*3b_+-v2--caWr! zpz$9p7wV4LSHj+d5RDP|l8KEy43ECM4=sC|LpF}9%%qR9yyVFJp37+?OP265PXB|_ zM9Or4y`55#9*iAHK#(Cp; z6{}{Hg19wpkD4F)H01-ZHGUkC#1r-72pZd-N7hFrE=j;7!5&jj(Qz@8^EG^UL1LvzMw+(8Y^t zrBZYUsX^m|+mi#_KQs>ZPpCf^%1^L8ggrY{-JQRSwhN6yFTR8=v1(sN<1t#a74qk( zCtDd!`r}S7%9j-9z;eGFi^d?X;L8D9*Jg1?oWQ1g`3@fpX9!4wE zeK2k2{gmeI_|WdSYB)hxm+8c`VDD+653TE)#{KDRQ#SqB4y;}kn0a(`3sT?dnNlpC_3apt(wXa9&M zW%W2?qw(ZyZ~t`fpz+gAW9Rre@bKMZhG^z2m%YK1^=sJK`($r=;3FBSQs zIjQ$(o_v0rB5gvLRt_~=coy<}cXugPzcMT9T&$cA+Sf~(LkSy74a~FSdcANo9>FRw zP`|sZu%^s~kIV=#ROUCzGJdBadTk@T%Y;5Wk%OnpNfS@mK?ol7yVnYjtuP7Y>r0@b zaaQ;`+1o3&9OT>-KNDr@b23|qk$CZ8W9{K4tQ%v}9G>W?k!TnnH!q^@wFbrPMU!sf zfRxe)bgmV(84Lh8RZ|6KtYfy^m5u?B+V#b62P6{6x!uwyt~@IJtR{z&Uypl~`B zCl8zEu`@PVWW_cTZnMifB4Ueu&G&kEErFOzur})Ynh6}mNO$v!YMz*diW+><%AV`% z_a^mo&4`V(AjqoGYkutXCOvi89K!lA{t!idT5WWTxFy;g2E9QvBTjI&=Q~Gsx5mc3 zs^GO6c5bRtOtqqk*DH+h&NZ}*!X<(&iRq%VL6D?AtHP0jHHgg>v zd39Pp!39eOwt&yews|fJ$&y>r1%E|T5WWTaS+p9k-NUnkQ#CmMSJWEE?5X_h`0yq6 z;q;K~P*Axw8MW9{pdG~^5VMU=o9sVu*+n|+Hix=1W{&S39=($FAh~@*a;vECeL37< z0SgvR2PO3k8dQRo!XDN3$qME`Xf5c3leHjumkmyq3;0D=0VA_cuWDgI*VP_StWKCe zzv~BOH3GO5GO6UR1Sw?PkDs7>(j0odd$+hC%NA5vd<{t$cbl6>Z#9DSSt{ZNgru^B zxJZWO;&?%0&EwdC0Yx&@Mj|?pMIVG0m?=ECSPPjGSz99M9*wsU55421B5W&#v<)8- z5Q|A-Q>m%i-bO+pUKr5P=`n$bO(RUhcuJF57KOo5YN!3a*>6Qsj4skl@f=ee5w9n? z3nVnNj_bJhIIR~>C@>7o?~1Eq5}!gIc+2*{9ch}X{L`w7%&sKZ#cXy!p7-;-8LTv}Bs3~Ybr

    4;H)B+Lwxf?o zSg&5uaeK<*2{S7`L!r_KbgX`Y01j+3xCz~q!IaLe);Fd2!D*swA3YPYieqkdZ%xV` zpY7KZrAK&YU8)#ogdRW0E=j0L7o|)2u_)fGXbGI{$1KK=(LdlYj2>&jbE>NIw-`j4KSN!hk9asA2$B z7*K@)RTxl(0aX}Kl>t>5P?Z5y8Bo;#sxqJ|1FABhDg&xApmhec&Vbe#&^iNJH-Ogf zks9Nhj=?5#R*6=2PDhvk%TL@7XD!@_2&sh}C?rlYuUCz49S%#yl zI4IeydBd^kqFp1}VAw%ub(D4>6LF?l0P*(hq;* zZo_^=17ZYJA95QW(&u$X!1~%c|J>uB2mC{*U+3{%H=JahnZ`Pg^g0vxI?w!d9`JP@ z@bz_09rf!^R3)Ggxl&HI7O57q*S!Z>7kSg(XzB%H+N zN@q!Z(+k3;o4MlQq2l$o>Vd7?PXLmILTC0mBV2GL)V|GRi|%`$g)QngueFxMB{pEZi4qzNe5q6A)rUy5Y27N|tNZ6pEdGWP?S?|H};@lK;E z2}pS)lVD!*O@_-GciR))BCb^=vdzsSp`1n*G_}gM;+{(@K^oJjPcBFIL+rU~xK;qr!^Aheu6g5B z^~gyjIR+&rCzHSRO03S_+k;S|oi}=lcwFJZM&NCIBl}y`Fn|B^y2sh89*11_213I# z!!LWg)Mxs(9{83*YLJdhE=OYA-#e(AZK0gLVvu^grDznT_JJ5yLC#m_*awafQeY!k zVaYi8bI<$X4F-$L6&5Ti6+QZ9f5b(Z309a%o88j%9|4p|=RJ^Yw5kG++rR@_VQQ-I z5LVXpB2wY?!tA$XGsO+NFF%~fldHn3M1?0x#dyqBm}>P#OYg9Fr^1_vYDKn5vT5Qi zN>w&Tx6;VqBe&v0gL<~px+>%4VX=N7FShsJeo$~t3moiVx2h+F4f_d0Jz zH<-9KxP2Sku#JkIvm3l(Z!jh|7?T@3#2f4Kw!uGC*9JFpgC*yUdzv6OSgP6J)nntH zeC9GNlW*{9xxwq!1}|6}jQS1Z0J_0_-QYE0gHgZ11hm0Rzy|ksgDGc&$7AEcdhWC5 zpkW-O14cfS;EfN9Zm9OWb;Xo7^CXU!c|>?# zdtCA-cBnMj+*fg{)Gz2XsUcW5O8$zjlJ*ImCi!jenSrby#WPYv(k_wwkv$>#8EtKJ z5%PQF7j}2#XYz8?ki@-_zc5&NmS1#Ov`_51$nWB@s3AG7iW-{sP?YW*N_!8F`FH0) zAbW5Q4ym1s%@)Rb!N*R2IH3ok4u0s3DTpGzaGWBFnaVKmt_(=POwM;R{t{!ALJBkt zNJ-^F2nC%8!&#j#x(<1js<>s`6epcp&LI&p5}cBLdUJG1)$r{c=80S8y|<-eemCvo zSFe^ts*`Zu9kkvtoX&-NenhEBzbF_XSaZb$8v@< zCi)hXl6f>GucGeI4iUcPIgm3(ZglV}Dfp2t>Fabm<7jw46D2)bo8b4v#v#kg!XjPlOY~V6(w9b!T{p+ETMS4 zFG^Vkq}8w$SN70KSp$f54GAsn0|vzM0NRk?ASu^|=(u8J-xJTU!`{0@cBmuB zMrcV-tvA<7BSC5g(5+ox4W89zYi5u>~Ce?$)<`UX#@ASy4dLNJ?Nn?OHuh_xB|5!LAf@5d0N-si7{ ze!OkCJ{$8kw|3L}V7)Z+$J>UBe(}LQXFFRp^Z6h#kz?|r8Bi=Uj-Yjg#-eej9hn19 zC_Bf@uFhe!RSCUin0F-(w>P|>bq~Vy9}Q@(%z>ZvWQ*3lmiljV*{UVFwjS!C{M_@h ztR>#UfU2S9Pj6Tl**?6D5TNx$T~mkOFS8zo5boME2*E6C8C{#!nG6Whz62f3VPBDi zkib!}7eTD}GsRI<;jU-*^fg(cuHZJ6Cizpo=Zk0Wcz|(HCoK-tf%dy(&WeqYVrMV; z@@=u}Rqa7UVO=SF=*2a~rNroymwe+U0BjF{A^am6kr394nte7YZ%e(M7+o`H2Qr&+ zV4>F7XC9kQe=BSLSo!q4>HcWrfwd$V`uGd{h($sATi8-Vj9|nXLo78sn-@93(55eD zU8s6ZsrrN>f{!Rr?|E;s=H4?)o^S?Pcm$rxM9@g%;)F|s< zW!=l-cA;W)M&`5MCm+kK9jt7IvuKkK)&Q=pX9Ak~^WZ^v)b4xQ<$Jy+TLjUn*V<|r z&}N8Me2b_Vbo4NT+VJm&_e}&*Ezz3cU-wX`h2#)ezb-3^C4@PV)I_q9L=g^!oJ4{W z!Azv9sxO08)?_N)^V%Syi42es7gs4_kO`}1?1E%~MAOaM--KdYC{74mM6S&wLHgWe zGyRi6N2Wz$2^0ckdKdyEdxM8zg47U1Y?r-(7`JIs^9XXy;>c__=*Qb@B-$Xtuy>NU zVd&`InzxudKRi8reQ;Voeo4FWskSh*p9b!Yx1@XQ+duI1B^hg&r_4;(=RS5DsEJ&d z+lDjDdeE6tD`HaSZS^X0j=zyOrmF~3zV8|`$Z3Ygp%A4kC>sfMiE)`8s|VhU^>$%~ zV5<(1SL{)y9B&97?#UsEuqJmosOYVax0~5?hV96a0E`C3ch%7v>fvC-j)PI$8eu4# zOHT|)MLPz_jf1^|XKLl)+Eg+ark3yx2gfT9-AN*Ef+78lmj-!TF_vV)wRNrsF5PR% zK;9~5lDLUx=wv-zVT@NRiR$L~VL-b1n{L;{SnxK0zU0Sm5l;d?m)Jq-H*Y+|B+>#B zIy8M^RBZ|!K1f3sZ0aAw!&fR^t#Y#Wz+(ZtoK$$BsPY`D3JX{lJv~desF~tpvs+HELq_>F26?l&xv`VG`b-Lr2xB zO9gU_`iD_=H8s(v021^{i?sc#wgJ57zR6IEDQxxOw60axs~(^YZ^FoVakAT*Ah|{B zZspaDP)FB2VvxycR)DEE+6ZvZDadx#f*UX3!{qXvXo^-`d(2vB;{IIZv~d#xa(*@* z{7D49Qk}P`G0|q4-3+&=lCTgJ;~i!k!U*2tw5R9p1(dh6FO=;=jQ* zzl2Tra7Cxota4Cs^P2Ck*t^i3AW;Et#q5upAKmT00`!@~eVD?polp zU`4z=lHVRWZ&tlD9V@Q&mS_j`u2Y16b2L+7eyYu^1S?`nRTYb>HJ1vsxqUTAkg_yt zWrTRQ$QCf+N|f}}(sM23tmU7=WVvq9kJ(_(;ku>Ij67pfZLn|kRNlGJdUc-8_&w1r zlFo?CTA8Oaeor)@P-pxDCYc+uQS^uvC!pTv@>CT0SSZ^&5Rz}1KSJ4|&q`a&tp&ab zWzPjD3D#|`)@5i9FS8L4E+ZRUk(0bc|3`Bt-WIGF9GTCuyA}nIt54KA+=s${#Q{v_ zn%(2LdMe-ZOLs=}J+gGO^1%6#7NyctKgN@6BmK>?+M5wE{#3nH#IV`~5qt0i_0!;0 zjCdoyZ9Y7+ixZOO#0Tzl)SD$^Ltc3xT$KmmzHA2tf;iC0I_{}u1)f2+r~$NbsHa8O zj(?u6EK|AsV1q=jX_80lDr&v+wHd;b+*MkOBiet_v(eYa{+oIve3tRRW5xPSEPOrN zY8fbH(5zX8a47lln5@rceAV{4;Y%8^o(k@Pk2Tj&+$i?_lS!*>o!eb_-I$u&ZX>2M2oVW%h7HAgxl$PpS`_ZYMPCPH7D(LW4f#Y1QcD?UmzjSWzw# zv`WXGkojf|GBSd=Y2U27wNH>i%8|}|0gikE|HE*!?nC#SIh;eAO6c?S&iFmiEeZj; z5!(+k`fBK~IN=MPG5gnDM(U5+oE@DuYFhfa_os|nxTE%*-fOTfa}(~QTQv8AydJ`z z6@^uZ+A8bWo%sS*n;@8%x8MRcI#Z$wtz(gkk3t zBTc(K)1s-^ND4Z<1692<76CD7dFTry`Y^xZV%c}f^BpVi8!vqg=wA49;75j1YBnYi z8jwE|ydU2nH4zJ>s%L|D`k!#WoZ}~D@93{on%W)&=B?jo9g4=Xq&ehA&$dQWh@82Y z6=}m*I?#{sfqOFv(!$epbUy$=D}HKm zU82i+*Y_|nGW6rwn5Gt6QIXvD9KG**fV4BW*pzsD!k&x!ByB}{$|Y^^EoHq`+q#M; z%xXg;ZOf$J9wb{7rrxScm-jMq8V<=Jh}!ykE!2>|TUaR26LRedMiyNwx;O52qvoj7 z$2{cqg+UwZFON=N6&4M2|J{To3kh`48Kq`LBK&#q*=bgzSS6Ab)0p8`U^XhB0M-lqY#C&s?j@jSgdjl|v zb5kx=r+|>1WawNpIHYU4&7Gtria`5(cb85i4l!;myx7~z)fL`eFc}WJcr${%a=udH zd(`oYgUf-w*2G3b-PzlBJ4;=)pO5RihdAYXCRAi#wRGPWcwu zpPJoCRFv?XHqI@E>g-TtX&z}a)EKB4Z+PxwTE&Tx`@0_)Rw+XyTvf4_{7hFo!)INC63JaQv_>h}0CXt zI&`ZnnevRH_niT743-AB2>#kzRcLlUG_Q?2dND=RkPjMPIKGNY>PNh?37(3te|%eX zF2-`Z=SFaL(+j(NS#e1bsDtUjn>!a8;RnT{y2U>e|62$9*7X<56sfI2?)i$Sm%FIA zj}>adug!;?GH(`ZH)=^n_dgXhBCt zPc&rB??eW4gTQeAWZjXufQ&yxbfq&wfX5F5w3I&w zpzrwN%GRJAZLvK))Q30Qj3Tckv4)^$roGzD?})yfZa;A&gnt2?U#9S^gEv#}4_ZY_ zD17BQOhEpa|F&KJw!K1s^Q8qdG%%`I&Y_o*m%?LIN@h3IQSwqacQJHVPIjBk1#)Y} z)LnMMcFn(NO*9Nj{ARngY=yKxR?qDx}gyQIe;0L{_o+udf^8dQM0)r7T?h>$KXFGtzav z>F2dPq$~OCH8X@XprMr+|H`>fhO2dAqXI$;-@~)hqq9>WvroBSXMw@Vu)4f+{QLxH z>8a4=UvdK?&g-1T_It#o#`&|oeIVxR>%n9^oPa=KFIX*^3u#!LwQST{1YnrBMsZpt z7Q6;+fncBfM${Can_`H?FPR0I{0U9|Zp zQ{~@BkJ%(<7@2KVo_B-5JPY}fi8CV2V{ zHigdqhctXm5l~w1q*0zw$!d4L-^yI{^W^aK^zbF@MR5y<37-JU>ERJ7^=V6*zAU6_zJOAXuuUHiGG~tu&H*rx856Ff7W@WPE4N8^@A{0Crz?DejZvaK;Tjc69&zgOBE}pzZ)SGW4O_A8;WGTts3%hG+~sIPC4+W^G?=tdV~ zpr=m1Gww9Io!{_I$N^1qtiA^#W@p&dSCO+4zBPzGc4E0Gl8KL6UE>Kt7k29Seg5Tg z-p2Np+t9g~=?vVvSBp9=74^m5!QSc9`qAkN6et8S-ldw1jHOtvt@N(5UvSEMx7r(^ z)wMPMHn^8NznJRueVtUDxg1aqKSqNO$Yl%B#YNOYZxPaW;W%};VRYf+3cI1ew2nTG zqduLXU~Gs%8^?PRql|-soq9SDecHQ-_W>loK@9`GtFy++nkWV$h)G3eq7*9HpQ!Ma z$KNaOf=;AN-9?)05!OQ*JPCGjfk=*4hNGy}q2{86#bq>tIw1qJz0*qR;WR`S#|Dv= zwKWIH|BntS>BW(BG(2c>G3rMB^d+48dr#yRPUl8l)b+^q#^wx=0VoTHmI}IZ68Dp= zT#Wjc(BA>yC4FplPJhXAr!Qm7nZ_2}NR^bDSmFXjBpbFNRXQQ7nY$mMV9l-sbVkN& z0hD=732$qhO|J$3dfe$xXamI?at-El#y#+69EYvp^^L~SOMHHCCP6im!;5g01+Ryf zZij`w9`EuMdQa;orzL4K2}LmO&2}3mQJlKp5k4=ySz9s})L_}am?(Jka;Ad?J)C%h zZ7Dg#qgH}IQpI&a$xLJEK&*ubXVmft$K)qzMwd#I;mbX-WX>Et;KiKnyLVZPkAalb zokxV=Bu%+Q)kc|SCRx$8cr-EtPD6bRtPRH#0n>G^dSa{Q1&lHBg3fSAfnz^3uYq^= zBeV}|j)-IbdosXlMKO*S9*@S|W_%UJCB68<<`mbLNryb_XzsYj^R%VEiY6mihhZGZ zC$Nbp`4h;!g0M-$9lN!{a~H`_PFTcF4O>sg{CH3EZ~z|$!z);Cn;3Jf*DNWh*)&iU z22dKWk!=#qnhz`H3HQ&81#DCkwG*`a79^I%7ZH)yp>xvyq}wIeMO=$ofZZBQhzAkO00d`bOubJ`i}G3vZT+`dla*5M=;Le}*<8Dq=HX zy1G-5c>{E&*}tZ^Vm0-z2@v%tyLw_lJQdF)Dc_-;;0~}Cj#LJcG>*BM+G{u{fT6(% z8jDQIvmnXS9z@Xgp#u%4pk{&snSxsE1VDJh`b8I{-U$I z{^MX+NcNP=6%sFc8>*0Y?UCGn$Ly8)ETp)s*bX1SrrU8Xb-?C7T;#bCnMMye5BcJDmJ1D zOqLT2UJm2^3toP(Lbqw!SQRJ+H&G30Q|S76m`kvwS)i4yzWbv)J7ij(N0%LDl)(64 z4fsK=;NuqZ39s^NQV~F2STg%<60y%g1l9hZBtBcoGEog>>2`WbvsPNP`>5wjun8bV zYK*m9j{ouoBK?Cs!p<;T#+-mKu<++;6TID6syGV#y#$Z}0c~nyLrAKHm z6=F2v*7+l?CD@IcLUHdSP=hv8MK@W@fx1tWqNpUVIv-Ig)Yg<%05vAA+@(iTxwVnh zpy+~!27FDf9hjCq8<12TIZvN#O9h{`B#CI1n(p59(fjeOkvC~oGIdk;!wcU>T=kqn zcHR2)h$KP+^u2ub^BVXSlN=b*9*rl@HCx`9dxMckv6e81Xd8wg9EEqFV^(~4)N@jet%d?8e^9T|;FfF3@fC15i>SY`RJt;dJ4d_?`90hy|G<7DJp5zJI&Kv+)9LkTD^a z1U@PuI!EsQJ8^g{b=Q;PAf;qxMF(aClGp+h5#+4m+h<)fiINU1+LUo-ew3W>^I3+| zZiIje?D2+Gp(iis0mS`3w>V_vGsdp*E9gbN0c;4GaXf&11MiVsdzD)qG5+ngRjANH z0Wzt5?Zua2>y_o{1}hexzz7?vq$-3o4Y$5+Z>e5~d^J%Fi*;svO(m6uR zO4OB~rI#zPo{a}MAMEL)SS#)v^OaXdgqw86XM$H0^d>247rjf|bO%H>#4nDq*ZbzE zgLKE1Bs@g4KSCLkW_1(xZlCdHbrLDX>|c%DySw^e;W1K|k8w8!JmHQ$B-5*q{*vKY;U&S`GXvq9O# z^R{q+ew1vprB)uHVhTAESuOnaSLXeA@a0 zZPFiK$#D!!xZ%(;3o#iKQw%oq){e!btH(C7Iv{TH`+I(Wuip(RlBUAYHUTr1Ua%i_ zEp_=GRbq~4E2j<2dFGm$Jx6;^qNUQl`fm0$MBr|7f_{8L$=VjR**1Iv{j`jcn;1xG zE+m-zxfzeqrV3bXm&HfGdVrj%Fc;Cs^)NPQ9@4xvK8&co=zfnoGrIW8 zIT*V=gNS{BI$Auklo7q14RAt)ajM_aqlnX+HVScx3I2L8QJ2w}LKW~WzFDIdGv-N& zMCX}kFQ8DSA}pT_=$VW*WWXr=0Se=>vzmDWf{K%zgLQ1@vNKdN5=NO8i_T8ZpA}VM zJ9Q}GZ*QTu&m%r6mR$#PUDp^9*40Qi3pEIal>Aevz;PZjAtmjp)Qqs0T8ClNg$+Ud zK6%eJk!51|hSd6OR=~43;?rML*^@?z{cN4-qP|;-Rhv|Lz{z#QYXFB6Fs3tfD#&Ue z(Z_k~W5rPZLVBgHm}x?-uQ!24y-9D(vWRj~0zqx!HFv|}m)g*7j+=;DWHFsScY%Nr z!s+x|N6pZyBCww(m2Kf=s7Qd&v*w7V2oWBQ-G>1hX^xuc3=5-oJ`wx+9(u@9@pIqm z(it7P!Ha#P1v}0+j>aG=wCLj%a7SP>`J%Rc{*G`|()6&b7qtQtuAA?DR=)RsK10yR z))$-wq(TE^)(>;|^4ZGp{ejytG8#6Po@`2bTqlR*x|G%NK6KBz&2z`8PUcP>?O)rL zFx6lJ%j<_eFkSD=mg626>(TEYxziK2^TEovs5_6BN!c0(nShvFK6OT;9Qb`YO)pIP z$kMK_StdbUGTJGT*MH(u(YMlN4+qCM*KL?qaiEdR5DlRgGBCZ692RD5EF!UlQ_RTq z-pTborjuZ%@bpkGXoguqMLNkM)Fhqp*>PPewhjT-9LFjKQq*M!&n&0RlZ74I(Y5Pq zB7fxo3B0T=`QZA*l+r?3wk z4o8FGs6!jX(Lkc4K`mY!GX@PKDVXuCDS{cR*mV4`9x8U#&&G$)Z5v;6Vo!(hIYt~QwJ{^(Bt7Vd}yNV)M;mEyfVTcC2b=E zl!s%*auv0BOOgDq=b4e{_v^nTEcWCh8Aw4J{i;k!H!u?9s!eOk0dN5rQ(PNhDeLry zlW|%0BV2R9vEa<;w=1e8SRBR^$-xq>~ygDeLnu~2`j;wKYGGFZ7B+j}_LBA|5VO1-l z7jc@y=<%_#RsGrFL>S{HnS_-U zJ*iLR9+)VLfuw1Pir|UbbTSft+KF4ukw`z%vjl@mY@_|nxFC?shxIBbT5f|*1VVl_=c$d`*{qt!~dL8((Z6+;7<}}6*Ttu}J4RGZHP*x?#`A`#vL;1J%mf7Nh=m^&9lDE8#_P5#^XO+H^z+Qqg?&b1rGw`I1#DQ4DD)pg_+vRXSB5<@VR zyrX=bc7tJ~u$->9(=PHMFL~vMYF-cbuG43kXf}ST52oWM*>2rP_B>vnjhyPk=}qJc zGTXPlW^pTqBcdu^hF?@}U-ufgAWen^AAwHWFeDu8?jY;RI+glC|pa2!n?0 z?8A3D1aG$6e1czq>{yD9@7o1(x^2+8ojJqD{&djRmNq5aJz(`XVuhkk;KO))&um}T z@UB;E=gkQ{H*QADAR{+!o|a`+U;PipJr?-W@xN{n;962p8&@8KtlJxssax>F%42bO zIBLACADlsV#F&lRMO`c8h2w51r$3e_>HQl6L^JfigAO*5WC#mh1N&A;a|2>oF&REh zZyA;Uc2X1t!>qv*E0`&jg_~YYG#yEdu~|5RMd=U($tfJ)ep)x5fTfR$GdjmLd=bvq z0}aQjq1h5EHPmiu+|*Vh9s8Kv@Gyy+qm#zj!H)-rKOY#=po|gUxXFl%-1Q}co~kd5 zyNv+um~#R4PU`#h-P2Mw^V;y4*KKJaj=He)e-RDb%ccR?(Lb+~!^eo#lZ_UTT%j%> z{2txI9#Q{Oy>UJ{-!{y*d3ri(_AjF^>gWU8Q8xUPFVpuTI~o(`T|U8R|#8vz$`EjIxvU5$P`{Q&~O8@B`9mCWNeSzQK3&e`c< zrbv;TNDQk)h~U4ogg&y`{StD&=PXKsSu(@~G?>;IJIo+}gj^zmb-zuNnc&eC=9wjR zYWjNGs2@BPBo@gLCT0J*FiWbq2^JPUhx@Ua6fFL?tj?QNe*mV5Ca8NkX*@YR+^_E( zpl)z>=F{Un@}73aW^R$|1~S(?>+dY7YvHqY(a-_%Gce|mY(iR|wKbU1A!eM-?iY>a z#%Fj_l}o0)`RK{tyXc4vA{c;k?Oc-M2WIQh(=SUIvih#hT5UP|4h%l9Y^l^+nCpQ;9AA~4* z7P;*nz64CC*8ZDP97Y6!s=kEi9wcXrr+Nt&*_>;TuA=U6UUJ}+7!6XfSa#L-GgnzG zH&t*CLwp!gpt#)nW}+9AjL0v(|0RR+a5K=T_no+N-syJ6*M)Q^b=$(=9^6C>tt2s* zq|%x7Rn{uWofTeB@hDIQx)Ws_I;>Uy2q5c!1dz=n5bFN)-DPF%epaarbY=p2kOj!m zj)-)Y=J8tjkqJGuc@97q-An!dobBuf&q%_`m-RX7ucUV2+4Y|t{3$I+QEPah)@Kb= zB}K7;t_=DS^yJ_$#r&OVl?6XV%mMi04+DUYx4Wg06x5!s&#rf4?s|6)p8k;)-%D03 zV;NScI7IK9%_vW)l**G`d1}_*v~sP@IXpNy{epI+_{enamNrw=1{C@Org32Oq#4V~ zV}%9*WW_S7khuYwuNX5HZN=i=U`NN`MYbjCT0a#(1~3~+iiZuu@a$K#`3l+8eNexW zUCfdbOwe<)5&Mg$5r7@Br3xgb*!ZAUqZT4*_pfXR!^+R}}5JbbjLl*pXM2JBAC2uxdKAU%rbFM7D$ z3HZ1%CbOT+U2>I#AxYielO@hH;4)@OY(V?fWKTL)#-#yez4=f)&Wxf@T@MA{0D!YF0X1MRh764+SmvW#4NJaZFYJr zxMKZtSyG=%Wz#>zpjH|X<- zp{+5+8gzLW4c3=ZQ<|=@ezrVzeV^BB#&ePUB6+H5Tkdw$8i~&^j)7rHCcw1I12dgb zEDP&%FhIv4MROQ(4bWi%YnoY!SeXuB>x+{da?lGh=mbIw`2{#J(s)_x7Zb4nDL9$s z?ni@R+A3U~M=f#*?~L^|)K@Tg-N-U0pD#HJQ#|A_iE->YR^<#X(<~RIe9LbU!GqY~ znLXWxj+2OYF}DGmrg+XheWnPn4%zAF5{?FeUe9nckbd-aA1FMR-dd%61#a&Zz%$X@ zc8_yWdz#^-jQAG%8_YPGSq2`@E!pA;2Qqg0eBa}IEtPhjgWzwQiR5vcR&pB!R-%cO zP!nmtAilr_>(N+b2OWPGaSPTc?9h?E=tdgPhqy!R@fHJ;>bP5v;eAGMOnWZNvS2V& zm7pZ)F!eedhsNAi&J(ZhB)r!A3BB8mn*GVpm7=V)!}B{JO8vpBDU%d=+xa=7>8Et)XNZ(UcF9`uV5^gj4fUW81Goj z_5nugCAz}JD3#O2S>n2{5p5!z;+T6hyN%r6`ie+M~D~8ksJ(iLBlNEal-=D zK?iw0nn4E;ptF8K+!DwHi&E(blnz7fYj4m73W^&k8!xuDT1(_H7SqOFCiy+X)N3>t zjIri2pW3)5!igj7kpBnBq0bt0a+RmRc+_jUElh$0vqc{v zQ7a@UiBu$5BKioOuNcpCuleX5$*0GHYj&3$U#n$&!qzO{1Js2-yb*RyN*ri%;yf6x zJVq^X@VLXlc>d+#)3g2hNgmP8N6aa_0shhZ^O0&4f?tYhRGT7L6*K@u7IA6e>sK=Y z$x$1u4dhN#_)cdeJI4WaM7j|dI%G`4m_w{$WhAiSQDjV}eMMsdLnDDPPL$Hy@TtRu zz|g!3gM?g04T@h&UjRcocDgfNcpeZ(rBlm}cF5#8B#up-Lg%okrDh|7tpy#4m?A~y zYv!w%7C0HiV8F@42768xw!!nE=u8fnRJOfm4v@};55W6K?8o{3w0;CxPMjQapzGxM zY42q3$-di8I+^WK3qG4z%=zyLMUV3?p3euscoJqAnFhfeewGf!WqreUU5-YB4SdC7 z7n!d4N~DzKthMxQyrcuUe;ccFm{IT8#46ynh448LXOc2()7X;Br%r>Pi)J^D7&pmq zogC;B8?ICFJ}T8!Uz72 z5!;s_QQ!D7!n?C9ZP60w*kikMnmSZ2mx*ZJHyhm!d}y`nq0c=bau8mEfxH#H{zZFw2}2fD}z`BEs%F&W2&{F^uAyD8N!&=p|-l%iS@|l^f#?c+GJ%tsvj@ z=oMq)n^p)mQeFwUl5|>;7xiDfB3IGJV0Ih$+2;M>haZA@Ka=pL3L?cCskf%=Uy*JB z`zQ(;p^nptcJ45J5S80|5EslaaaJ=<+#zkMwZ(Ho8Y(*ir>P5}X-zaDU`5j9R^1_~ z8VK+@ilttWXT&&z8el7gGHzW9R9u#vba5x=XWeX=cyIbk&KHea-A&mIIQ_&sr*&8Z zxAt`9iAw)Ndni(@H;~`(6z8xF9_^)yvx{E>KkScpGxW^WSn{|_R7Ngwe?ncfN${(p z33Ds*o?fFf>l2(*8OJr6&EK}~&~P}D(ueff$hOS%(G*ptJ+F?u{-M8~lL1T03Tabc zudHBn3A%O!+D#0?`O4quf|FF6+1^%|zh4gpvA2>&d(s=)Rn1+(k}FhLWs+J2^==oM zX12p9j#(Li4cRp(EF_jl-rRbNF7--pmubNx?ULrZTvQy?Wddh0Pc!M*=z7bY?6_!> z4Yfbz=O!@=$1870BSqJ?K#H#az*=3}Ua-9BHr!BYljhs;#PB5iOtVI)L2r@bu_1Re z!a_xs063Wz)>LLpHJP>W>E#$UaZ{%IXyM5s`rUUPVQF=pj&M-)aqqf3cnglxMnPt< zneKpn)@8Ii__$d-K&P$`23Msk&`TFlx z|K738y>c<4OQ+lM%6fUdytYzV?RL)NRSr+IdQIbaeakx5;NRxP2L4v=->c9s{GZa- z*48)IH>&?rsoY<$R_@>5+=TS%+Q$8R|D)Fa(4J=eo8aD9ss9-Q1wt<`2O0Se2L0%- zXwP5#@7v#VtIIjX_Y99PNU$pG7FBg^t*VX(y=Gtiqca>vUG@EM^t%na^2x`Q-sXdM z<-zFkF&33Ow%QbRb!6@bHiuNt56;x{qkZ+hT3##X6kj7EGx+-!vZ(UaV<#ydx0|EO zR9a_{N&*^9rs1NK%7>dlOmtb(yH@!sZ$s>hPfV{FzbmPW-WU}##IRd@xbU5#Z@_v* zY=JyQTbvHco-Qn`eMIUu$&QN+f2!u_u9lWQvEXtbe*jO7Ms%A3%Q)TWqrR=?Ci<~J z?rEy0K=!a2r}k%PfNQ9BY{;3p50MTQe#SPkwV1l_mR1UR6-! z+t0agS#PY?*Wi_c8IvMNtA*%>QY{mbR(2Wx28BoXwdr)Kvy6YkGG%tC4AR$p%S!L> zJMG7(jh8!n2e?EhQd22%4&f)B9G)HT*8Mczp`{9kl0~jeCLTQ7d!BAiDE&o!|Hz~; zMjtCqKCSz#45r{WRJt`blzJ5^78$ z?I3`IpAV0pW+XTM&)MOrfqSZ*gKWa?{vqE%R6nqZhk%-7TK#Yz$f+A$j4{KpdE7a8 zYMu$UTT6e?r<)KV?cnef$q{8m(?*scO)8Q8W0?v%6-oawO#?p#FOzc;0XsP7-B*qa z&_L~;PR2RIMRDdTdsCZoui;BJQy7N8gJnZ~7>pR?qorBx$$~{Jw~UOj++rVvcp#=|7{ZrVU7`o#I!(H-fo`tSE8dkB z#=k}8^KFjIg|}3{%M4n5;$LR7Blyy5cKRIKV%$SE)*JH~#V7krndNy)Oq3&_n`<&c zb~1`3B!NnN;7+GMn5z9`KqKroZWMOXE6fTwP(klJm&e;_J(>bwWLNhYgm)WU##dc^-5=<){TeB z28q)ARVP9q&u5f$r5}{gkcp*NSKVquFS8;qEmr?SB4y${perbyVcJsZzUm|yFQi}W z=bs!S5!&UDPy+QwB1es`O zFzf?P%Ek2=4Zc}Ku~7T;YDdk=ZeB71sBIliG=qg1K|JRjhg(JLoH-P-^b2>)?(4LO zoy;od7@3kyo@^l_|BvkIpAm_!i@baZWijybUK z$!v?6J?IRJRgvvbwBs{vN1mgEEo1I!_M0~oBmVaV%B<tLZ!*|t;>)zip5ChbM~CtBfCr*LhWc$b=BBTIU*yhE`?SoI zB}oKE<`$tleNp32565XcO0$2;!$nKxT%YGNJ^Owc-rm}GKb1!Pv|F2x~GM-xgDh?52{v{Iz#K}Pf7J4 zhdi2-@;GOCLLpu2IH6KU0zSNIjfMsp5P0W`9O_i|M}-I#)r2N*YP^jB=&fgShz**Q zW|QIH6Ae^1(W+ov{k}s>LX8MU=cSnbXDSG+iqLnf`NrWXe zayqF?*<#IAl2Qt5M(Hr}_VjE*lg>%fH;h4AGp#jBPwq{Ul+y|=={^Pel)ex0J2lJ+n;<6B3{lc1OA=CRnKLjEjX3VY}a5Y1T_O!m5{=6jSBn zmUVkWk?25W2&c5t&5}iL9{!XuVfmVij0Cp};Umcq#R@U>$*2P)&z3!RF(jU)TG< zX*ocSGDkqpXQ-#&_0OdGU5i%f*;Ybp5L6q8q-MVwodJP>Dp+J)usPDszxLosR0Ucc zVale9`hiRd&+92Da>j4qWP&mANPR%Am4Tj4jxmDYXUczYc&ZT+sLcr(Y7bBa?%{C) zlfh7+e*2{8&cV}JWhtDeQ`jhqEII13?vA431m3ix<)8XDj~x{F^!1JrU~Lj!yb4e&KIz}L_K zUqb_Y4Gr)$G{D!;0AE7`d<_loH8jAV9~$8A_OSlX{+I3lkKt@_*I#b-zOatz{{Q&0 zf&Ty1>b=Tl1@l!l?{D1y>i_>&{M*^xKiu8fZ|uB$w!icI1Sayzo{C$e&Tt&BmYb9D zARbRHE>?RRxs$UePxp>73xZyX=9vGT{ukCUeg5Cu+~E1YUcF!4sIG6q z{J+1pR{c8v|B8R#C}*72Wz>&G%`x2?r*QK3Fs6B>T!H`dZDr1?P|kg$wwZh;qo_gd z#M`jMCqju-9zNVC;op1oca#3!r@s&A@52&?8(E{j75ZB(0TlRMr?(CIdyoEZ(%<{^ z_W}KVsMNDj6seQJ#rOk=Ks=TiDK1^yGGX+KK6KR>e}RM*8n8NC4ro z^FE4U^VIG1I*6blUf~zV6mox{TF_;@%4Kyh!Z`mR-=0s#cvT3t0Z$_^_P+Ld>kZnS ziwnqHWo7I zHb2yK(*Z{GUalhQ^oCu${0dM7J7zR|xlk|b$Ga~8;?9%3{k_vy*y(3`rw8?u6ZP!y zSnWXhqn+c^z1_3@onv)$c6@YrQislMpVZMh^2hpi?x&-j(-*MDY{#QkyEEF(4c}d& z2nf$;a!`=x;_CL%&hC#p&+C*!q&}U=z9#a)%BA!0WBPmaF={z^@^xKbd%YA zij94gUtIkCA15#H9)Xj+!-Ko!&x-~8&^W0>Z+A`)kBfPfzgz8G2VL{=aP+G2bmw$O z8mrTaYNe%CdJ34OoAc=S@cHr1%Rpu~*U9ej-qC3&)84_!>CXOs<3)YvY5kaT=p<}J zF*k+*j4uYG9(@xMYnapqTNxZ29=`-hL5f1wt=!RZ-G4tkIrS2x%-KP*R3Zh-`AO%K zPPYwh=nT6No>6a8!glTo1QItH-?ww|M8>t8d%AbRR)mKK@O}(^ep!cJ(V!V-g-6dt zNM#}`y27q{lUoRUfEl(}7!QUG{lx&|0`8}P{KUD-R|se445lCmQoDyoul5d}V|m^4 zKuMh>*Med0skx}0%SjZ+^JN9p&BzGI!pdjl5~5p)uV!TIj?pl>JTsq;%P~FIb@#)l zIm~G}_T>iAusa&f79MkU%OJuc5y)$!w?R~p%5KKB+-&92R73d#aFCkVt^5qgn-AOT z2fKUqlOhv{ZDEnXa^?n->n~J)(7QOz9@;r+h{GKa9W>o$QL`@Vb-+&~er`Uo@i9KpG_|kC_1!bzo!*kaq^42Snv7ytdllJ?IPdNE9p?>Dd^PU5`8)lKf%nSfiR*`7&V2Cz>Qv2;?8efy7YxBm$gabyEFGptJ{n(ofakpq@v}4nPlvyL;Wj!!mau{PzW* zM3P04`EZtx;lF6KlK7O{dD#dJ_+lZIx@Ai}l8KbjUO(p;ZOu+`N86&uU3!M{*iu|7 z+GKzXe^&6iCu%?9H&;L9ZE%Fea=Y?IK!j$^Hh8fh&qey8=kH>{S%QlCRY)D*PwT(z z9Xvav=lUX}Vg)SIFfH9Y^33dH6!ix0Bj-B~%kOF&K{xNf zG*@|BAWt6^y1)IdE;{|h#}!fywy_vWf@%fCY(*0RCLsu~YI663`u($7sx1j1`UesY zX1*AC&}!;4+B9+#yCCzv=j()-YDR01ejR>j|5~H>IBGX8fSkvVmg3Ss-xOZ|bM@`= zo8oGDd2zAyrczq6*+4SpT$E>Zx#WKAHsxb^dDTEkfdFY(XIx#TOprxqU==H2Z>0|% zT7XSN?*BrTKE6HXnV1%XBu( zmC8o=t9ngXOE&?#nE!Q^zgP1$zxdj$;({dG2fi%UfkI96n^B#KiBLDI)KA^#RA&R- z4b+2l;a8Jru7Cl2t_DzY(Mcglqh{4p@vOm&&V|KFx zJ1XFHC*F)NkDH_N}xIKwt1oSS8n<%oz8`^2K={@zf`)uS;=xsm6$#DwrAz0pr?c9$n29tl$abth)iPjHb znaq#dx&5b@VgD&UnW2|QNUIYa!4Ew{NqL1QN@*OPogST?HqcmJKDkMdXYa}3lmC~Y z@*}0`1b#a`JlvNAe8jY)Lryq4gtvnR=Z9Z-J9S~68mKtyP|(3-{S2u;0x33VK;;qA zc*4BInQ}l#J$Q*v^{0EM{Dx24Ie?24ib?WFX+l8!1Sz`phun7h+1xNGn;Y9Xk*_e# z=yl|w@#G9C4KK{JUu~kzcd+x)1wiliD_erO-#NwR0H&A(AxSpR+3~*n9bWA>hn^Bi zn8(#WaTYfPa{TyQhoQr-=FRr^Zyr}d1rU!V(iAC@Du$^=IZTgGXnqmU}!kd{mdM#<5$7V~5>Fzs!<^8|@rnQgw z>~4qkcQ?)E@?qE%$kA%F#tm+xem1GRHkcQk?(k(Vfi;l&pc}v1SN;ZTIo>ndXb;Bv zyOYFu$QDC?r58@e;}A)OM^2mcom6_+&Ygo~zM5r{`>?f?>jn$p0;yQAFn1Str8|XujZRMjB_%WG?VKx0pikw(Mx>o zd0+d9uYK?9zY|~oEni^==-|qE-OgPG(49Gb?+QQSy@N*N~Ha zlP^L{`dLy3HuFH|w1nim!nbj+D}yDE+d1!GVcWjpmy3Z(rpIkZ9nZ=7Z98WU9=7?3 zQtVN~wta&ys8`fgniokY3uO13PJr*@1`1;Ig&((by{4X}`~)e1kxHgPu6K~RF{F?D zxSi_8gDpsZQuBdDJRd{Ib;|TB3f;mm+f3^nQE-LYJAlkMQwN3 z{S?SyRvo?C#Md#IPD!eH+s*;Ax{RDz*5ch z1zJ#wEFhPHg~+9gGAXqTJNjt2T-5JMk$PZBwc55Js6SgQ=-p}&HuO+w)Vb`FMoP*_ zRqf&&<*?KOd_-?awdMe!gi1|PqPW?jN3Doha2w~GjAU1&QOGTI+n6X$6;6kdD<2)# zclQp@PPS~Ce%K0)n>m@YM;6{e2n?T$(+_q~mc1-?Xr%9p1(H3Bs_etEW093ZqcsK6 zpwl#y5gG=g7Pn=vfpSP0)95v?&!eJk!5;*W8%$J?%S}b(R^|z)KKg2))6Ch4fBc0M zk8?3yh$3E zanwC)V$SSUZsCSxKJB#fCQZ*GJe6B0OyO`$eyoQ?)Bia-I37$|S1{T+tA|~=YGYXY zmCVw*p;IB}-19qFN5_Lf*Fs$`cL%v#@Z;!0m1*5=;9s|0DJYU)PNv7kQVB2;;nf@0 zOE4&8ohj2YGC z0IdVYSEIq?@`_ET%$k6W7$}YkK-Nm+c|z*v)IR;xLQxoxI0G{ZWN)F`rc zcps1fAYLp2iZyIgwWtPAc=VwYMC}ZTic$TGD6q2SH?_Wk5L>IBhMW z&~(x4bRQ}F3;7={v9!R;4vIk+*y)dIanUfBggmskc;U)EkCxRZVDzu=ynDM`teMqo z`5ml~rV^_2I)e2zQz~hLlpIG<|51NH?<~2>Nee7)e8v*5TFG#Am5x{z@I2$ul0B`3 zzF;=(Yn_qsW8fkAl-<-7V^Kf8cdG zt4gn`al^h~JBp^Mxz>M5yIP5c<@TPUG|RFY8RIxMI{SMk zM`Wu5McI0-=rr8sb4mw_FejSyJO7?UkAB5Yc0&ELgbETB^s}Q0l;_D}N2VaZnjJ8G zFce30@yTqlfBvzkmVT#DGV$xh#WnP;1wPw{ToibW-acEU0PNS)@8pK4vlP)d2;%`z zn+cFyeyKWa)w9HNwfC;mhL-O=g{E>}i59oW{wkNlzgx zBoKtvHTwG{SqQIm;PZ2*0eR+kc~}2IL}!#A#64lzqf+YmG5?&rdI^8YB7&@jwO#L) zm;!5Qf}7>r?G`mw6DGNU0D3@$zePHR^HO2|!(Bl?u%WRz)O4cF4wvH9*Kf+I3M>M~M_7$+5#W6P=Y=DC3j3yRyg zwEAXs^-jA6ZTMsd2x^NqinaQAL zcGAh3*{dcjdcs#XvcQi-o1S6iW5LQWrLf+g0f}t=T81~9Bee*;* z@<_YwQ_WK@Qqrq}lIw;R><@wZSlA7@|?^8DjQ)u3zj2)(rfmHlIS zU1$jA)P=8(lhC|$fyHJLhEI{Q|8ao8_uK*jAN@O#?s_UttHXF>{^g`EC)RR~K=#dY znu^UL$p?>3$9#CLI7EfE3!pF_Wd$H2j1vM3@^aF|h!_zb=wd7m4T*wvV89SMJnmks zV0ctK^`ST$JwDE8_UTv`AVDkmEZaDzGGb)!qNNY*AZ9GimZiJe0x1JS?N-{MOnnmM z5)O*6J2CKJE^B}?<)}td4ub&#TQIAbMpH{;lRs0jl^zo6i7(x}RiUbe?kAF=bm>;jP}I zav7f4jA!BQi~8=54IBT#74@bFxwF2v-*;x_AAQF@8%J2?XB~ii6QGR-Lghh0?hk#l~k29U!)1e#x5IC49C79?Urx z)g(bASG~D_Sm$O-K)4ZE6sBQy)!g<>mD07>%7xJ1f%sdS-RZ%WQ~SJ^rqm@SNYW z#O4_DE*b6N5?L;|?e{Q~pj5Pk9Q3=_Wco+J_q6Cq%a=hGw@B%Ov4w4SxI%9I?odVl zR%?d%vquVulh@3)w(69@Gj${eZ(8kcJ|CSN;-=YS7msEyCumKCzRB@d$3eh}g|ih7 zjN@j(vijX*PiLhqz5VV-0y3G<0nldh!wcmsZ3jc|7$8oUacWLoo4Fwv1JJD#O6I&d z?k(kkcGC&T7IM09Z3!27)CmSX-HXCJ(*f(I74g%t%10|P1Nv2;E8>wWeujBtO%#|y z6OBU={1N5Fgh#eu{#V^D&lsBQYdftiZU1cF?NOge)4DA_=u8E?;?p_3Ar5@k0Lo~4 z=AO=dQdxkVpjlJEySezbY0rkxc3_*4Mw?u11Kf$}nvs4RRuo)-Y;iI}o`4Kx3U=_S z)@}r?6`nxb+Flb_Q}pi%a0C?(qgJQcRcH%NhUQ)f zDkO2sZ$dGr9L+>_h_#~0W!Q%WW!nQ2EJX}X%2j(rJD^U&G~US~r@!wzTYj)IN+TXb zE~i_{k0i#a{2e_@w-TYuI8}f5Sb&>?)doYGd3pRo!daXYZeTd%nV-uqryCxMiRS0> z%K>dVZ^QP51>!|E^YZv0hOtv74i<^M5@yv&Pok}9QOs^aY$UmQQ3)}+?#4Lc$bM;( zOx25&>C$PsWkRH$-^W%sh@0;lf}jKJQ3d=*ayc54#8{XyK-~K{*SNOJAH9}wr9q2` zEbDF+a!*KE_`I>v^_&HfmbQe&Ayj$v;_%?r&FkbCaL;uBIoyp&eU7)OY{NAvF%L;_ zHnckMSOtfsOZLgrg(|C-*X)Ll2b9sDE29clMggrv->tOn*03sSr6Hp~g2N@nR@oTo zqKW-GYBZSb5Z6<}If%t6VF%8rs=(+XuS?24E~j&eLaK84Tc#LA?Rk@k@92D&CVHGp zIeg143ll>549a0i%HuhD;ihGbHy-Kw1tu#$fa#B#d_x#UUC#MkXb%AHGH|SA;Dqn+ z$ne^Dpbp%oqm7^LRylWq-oLt8u#9uiejbuYD_pwQ8b))7cTxcx98-kdF0?v_x|Nbf z&^5c4Vx0c*1fX5B)dhTkMfn4;!H(QBpxfOfBq+SP3HWFqHjKE>M%d%QRu?h5@{S`q zy}yKkm*E?XE_1mTgAY*8s3h*OBN<1$aa~4+D?!xy$U~P^lt$v5b_P}-BJ^>BFM#^i z00Y9@Q7`cWpcI(?bqVmIon~?O8mrzl4Q-CXaw_8iy@DqIZQZ|;+9U3N)kN6}jZ1rg zE*PL#QHud>Icj^k3?sUO&dRN;l5__fC)XVVBAeBv2wj zAfa)3ZXlIoR9md4({DBV(lX5H9&RCt;L^%N?0%5|gO66YA8KU@&4^5xn zIRpH2gR1gBTZ)5I*>{SWBZT$NR+nF4v4`vAUoC6kZ=6@j2t$unx|hQqqMWFf>amy* zg+#0hdhJIa=pG)gx2`&?BZ}>)y#-W* za-YP?7ff={9N;tmXS{yGSxdkdp*V;3B36a{#730W4)X^+ePI#}J8eCSwd997pB&!F zN}NTmQ*`>FaVer6`gNMdjGAaV0i_F;t}i+t`Qnmld80&ElVF2j^nkHlN8=JXA2eHI zyarnue;I20DYR<|roh!Tb3dH2LUn?A!2AKmy2BpOg@f-qsP#gxdYW)J0zx-!rNa@l zpur^+I&;nv1fWg7d8q)#hj6eds(syW_J~ffRWLsX-R|H6GU$IzkiQK^?_#{=Mc-AQ zo`rZ23De^*lt{DXKOI@(%j-ZP@BY1enfJfJKXd=nI_9fvZdC65kGl8eRnPwSUoQX6 z9)BmY$Sv!*@%UHQ?p4;mj{jfr??&VAgvYr_9n<%JmFoQs_x?8=f7k`Cf8GE675`S3 zr-c`Sfi5fc+(e_HQ)u^s9DPsRRn%<5-Tz?2}xBJc-aNe;6V4G zaz?h0qDyqmThq3mPTX3ffeY}(&QJAuV16&nxq3|4a<>t@-7cVX1eKh1$D_{2Vxr?t zHH{ZjE27Xr=f6dx!IEits=-hGQ9nMM3Fdo_@QH0^TA`D~6fg;yKf77qx4Rdu{w#1$ z_n++^%mWQzjk~j;0j$&gc~AyqJ?`|P!9}}yJq2?Z@P6-Q{qWh-omaD)*y)ea?_eeh z_YO`^UmeYdL=eq8b95XwHGA`Q{d?LL&uruV-pjqy`C3TfZ)d{8(0uhwcq6SJzM@Hp z3TEhei+1C%MZpdBuRWSncC<*Jf)fYetl3aosj6SnOqxv-y{Lz_WK+oDW&P#L!=LK2 zaRQ(Qqw85X0dR-MujV0FfEP#O=`A~{pUwdYjVPzVLC?F{{gY_GA6Dn%83)WXe!cs4gs7Jcu-G>j;U{0StIXs+;E8>Z0e>`i@&}Q-A zbWV6MOmo1)n?>f}0P%Q)J|(TGV{meMyt{K!-<@k10N~X$R)D}>%;p6IC?57_Ksq@( zmUGNXe}&t`Y-dpxD>U(TF^eBH-fvzsB#2XM~u?9Vlz2R9kf;rZy@bZ|#cj(?mB z)NJaQn>=Px$GpTb9(1PzIz8N9(j_0 z&M8p-I>9LVQ?Pi3x7*Ba+@z02B(qv}cCZI5F5D~x<1B6XN?yCaHl6@?UrNDhAS+J* zA{dkN6?;6|=_`)ls+Hm~B-6FvR_krl-HC12{%Hg6EXovsU5A`y^1t-nARyL4fD z)QjY75P`8Cp`_Yen@mGI-^3z0@)bhTm+U~{t#|5jH25&SqTV z`uh5<#}{9{!t3}NM~5Jk){|W8SG;iw<489eOQ_5;?@P>m4#661fm@eC*TP1J99E)s1Y z4Z98A?(3BTm|VBnqRC-ZbiPu}#S9k?K$Wf1Ex}6ZB&H|*xO3U3v(hnP*I&EMaVXDX z7hv4^EozLXo+jQ%|9{IP!JD7|RI6*%ujfC1#lKsPzf9(N>zFbA_pA3S&iT(KjQ{$* z&3j+ZfBuSp-`r8F=bip)e3kn~{XA+8hh$qfG7LKwiMP$hxWtA5Wgu|{G0-ipYNvyqIvs(yb*;W1)9-fc z`m#TX%g~p{kXgt1kh{Ndjk&-YVyVGiKrxDp3onT?(A`x$u^GT(a?L?Lcs-(hMTANs zvB^RW8lRVS)zRd<+i9u&PAlr8l`_0wPp9h9hy@K>ef63v=O z?BbZbMSy~9Vz)WAS;JkmJ!)$MrK`b^tzsOJ4Ob-)tnuCpw8{B-@ASpt*(r!Juhh>w z$HzMdr>|<}3Jx>{B1kA(cFPukr!j^tB;_Nq|NGVf@RF}&va|c%PQTZR z1)&N+p-`wQ6beqjWBwiHPwuazgn?3L+1IFUrh-bJ#*5^1Knif&XqX@&bPV)qSOOJ{ z%@gk?VL0nlt2Z|{2Jje$LslKe5mbTM08x)(spQ2t3_Pb9Q#$?AeW*x15>O<#kov-@ zXo4sT(2ORSW-*H1H32pqkIPF`#1D(Wg6V-^$66KQdyJ7(39=P`OCAl-3QA?LVV>OLD-zgFkdrR{KR# z{Ac7Sus+8sm=tOP%sW+2m&H+i=m+Qh1bx{BRkTnjBin>?kE7&zM~|q zIN?Ul@DI6?&xCqs`UG>*p5=1iDWVT3kpX=7@P(Mrzyn=8%SWsgx?rvvl8ld2fOCY= zYo>oWM;$ic7-QcetC;NNc{l?xkcepm3U9F$gyJmp@5ugC(W@r()N`!JtVxDk;*#g> zLGmi<)N{9^SOWLy5ZTt}mu%SufP_1jw}EjhIv~b*fo+T&l0TZR{QF!yTh}yO*K)R) zFVqa>QyZQ37zWDPlk>1&-Q0-(vCOcW%i)XxC39npWK5+tfZt_O1ICEeIbEmZm;}dC zl&x3FEyW8Q1DcU+&{d3fV6sJA1#@$*{vIJW0PE2I7|noa`kuH!>f+5K{1YY^Ah3INl|Q$Ey~3Qih6i+m&*7gXzNgJ3$T#>KPzGzs-zaN8zlWmZ zvTJCv9FwER0Gt77O)e(DJ_2~AX}&IV|1%aXU)N-A^&~*)#Y)r!W`xM8*7<3ORC0Dt zCcaJH*B&L3*#hhv-W-sC1-UiDUWjSFc!PA2#ym}NjJNGxdsix|#w08tut2ne0y2l` zVkg`UMXeV?;aX7FLko{$UU6Q$E8x{=6)_4I<&q=kpM`&vh0O8D9~8M6QP-Kknnvd; zkAP5|V;BuBt%Whj5ZECG&&s`tT#}62l2Rk?5Af~? zmUn0wxe+svO1?ZwCLb;Y_kS2=N*Z;4zb4?@iK&0->Hj?I(D&-8G0ImBuUa@K#gkA< z0?-Xb>CZ(45+j2J zH5CIN3dWQ8n0Q{2dX#(XUJdqsaDQ1iH^w>GL-3-3Kc^hrETdFbB#BUa{J9KTNkbs= zRkV~G%bJNgFDB62w~luI+cbWI4~Sc8Fcz&ZLTVdk%F^a%~E@CLb!+vS{l=FG_9 zr_lTdQFS2lFWQen!dji2Hmi?1GGrm-R(Vm1qnyHLoI8H?{Jo z*NLCh4>`+8Vf@M!9)^D|U`_n=80O^95q4ZNJmz=?a=hQbfN-?ic+@REM^D*75$0U& zfGo4{UIlGeP#8>fo8H(nIVDj8%J6BS4%idpu?`!@l_=bRDP`%{G!+D*fbLnHo)bhn zBmSn-UfdB{+VIoTl~_T7T0eE}^q*>tDSnI%`1q8mNq>F;UV+MBEM|TM{f?3-ks*n{ zZ9u{Q>r0zI@W1c$|4?}7<=hH_SG4i0|EJzqX*X9g{-4%ztM(uN&%fipl>es(yULU` zZ<<>)n@!hq>1L8VO(pL;J!iS#&uLWfvq_&V`dp^ZHhr$p=W2yLKZGIj{?zHS@q{O+ zO`j|DxyrsF{H)gq$x{v#=_1OZBq2f4EwE>*p*L%V1%vc^JV8(ZX#V}4Ak{?VF!0b) z&$@>Gha5xb7DC6{|C(b6DT~gb|09l}HPm6qFGL%t^6$LlyR3-iI#e>+kdcL9J1*gIsRnVma#fcwGPSF(rLWm=ppelI_w_^G)m; z-iI~t!3!rY-BH+=4uz!SsEFgTZbKr-#f4zyg>H+!lUrognZ&{Oax|t`rz_ms-X-c* zZb;UJT5XatCd=30MFER9;lX(G*`KAJ5}ps)O2dHv`3MtP1Qq;3Z!-nSkQZfJ1mPG~ zBZo4-A#GXO3^l+M<5 zlgL2|g*Vo)`hM0`8iXCLncbn|4F@v^xN7a9o764VCc`eCkLPmJ*b=OzpP(_yReXIW zmz$$Et*f0Xw_3g?PWJZkoc=7A+ha%7VxEFHz#}5w>3M$2C(!6eL8+PBn_03xs@Fk> z+(Ts$}`XSbj)!L~37;RJNfrEFIXglZ``TU=d=6%MknBvWQ`IVkS4n;{_^p{I8VgbzgNd~EO zr^O6tXyD%yRv@OM6JJTlJQA$wGo*=L3!JdxUJYfFDMCCBb(SSQY z?1!Fj`gba^Bqm~!KEN@`EV?(RlyO{@L(B1QXveZy2f^qnOreLcV+;0C+QV>41xi0k zpK)OV50E5(BR<&}w8`OU6>**jgvnhP(p0Fsl6ME>ypu zD#fukW6op1eH&Xd&@xRv6M@C4`VvlO$%H#NRHBp{%;+|w%$1`QCm<2&Hh~omMxy~N zdCp$nEl95z&hH3zrS56|{hBCp8o|>%G{Yoq#6G(Eij0wve|YK--*V)iKwo*Xnp{tnyj&v{D5j03QYpnU6t$PzHRz9s zT3F*J5HU#~o>pDL|D)BnV)XVcZ(IC`S}{MOx0Sqw9*q`Wbe8G1Wy0xX?_gjfE!r0N zMJxQ5as;i#5A@z@sX?Lt_BMevh0^r~N-Pd2Lluq4=JTdXrCiGP0SQCDmFdUyZ<2cI zTv4E2l92*pEp}z#K`LdpLkUJnpXSOCFvb2I*hnCy_xiV-)CQGXY3_gMf5Z@W+@8s| zQ@os*U+iC8Z)EuM@Dhp*Ydj}~O|Px$jaCUas-kjyR}C<1(1}FNJv{@MuDF}W&yE5i zJ|ra-i)q)QD*}U^-ukDl-3=59GzNW|S@ZYzB3)C4>q_{8jqQzIKLPJQ1+QwR;rqY$ z4>xvV@E`*o!^@g!a2cf=!(TtuysD|-qa!KLN4FAg#P+32MuCeC0y1H6r44<`xXD>* zI8P#&qL_J6MLB5suPG8ebW{QNIsPtb5EsZ^J!ncjEO&OT5cs51?v&~DnZJsnI}FAp z`E*jCd@Myix-@4q2l@@W9wuM}LxZyc_y|ubtTepBIaCC*N|g1o?ph(Bw494_CGp(^ zJGNXwz(k#qcX3fB%O)-?gI2zYZUWgO(p=EpgBiRKJ^=k-G~q?EvAvmWq%3Zz`+?=) z85~78;Nv;zQ#sbUN%?0l5T+9f#L(lYc#J#e<9WV9X*+g!N1a4plN*5gf$_jo3v<5N z!Ia;Oq!wjV!xIfcF%h1)Ly}+J6G3NuT8oXeLjG5-R&?3{_Qi0T< z*O< zmtg-yI``^4@Sm+mTZQaR>0HJgWI3B!WM(C-ra!fYC6)85OJ8*r&(E<4RH>Y*vrr?L zG%Y8t5=@*&s|=G>9;vaMMzZW!3zZTbd30zg0FH}zLpi3TX95_f&$>4|q_9A-5OEJV z{Oph}L#Y*jICv363xr|}$>A%vhKo6;I(#+V%lCG3wS7NruU_4|L9=mn4xgrz$Amx zo=3T}b^Kn|^MWqdz~N#fPo@~;8x)~tuoUw^{K`lYd|}G_FkR%r#FCHJ(1x-6efOv; zWrAd+fIZzN`7O@bJzT`|WdB}+&~#=Kv$NOVtV@(^jio?n(Ue<84c9|PO^)|ryfox<9He=3B?@2J z&75yOMC+lvY$S!%H=}AjEG(_wXaowc3>IBS)#=KLbA%mC$Xia4WBbTS>uDYmMi}m2RocEj3;kS3A>=vAX_2!adVLfLqPN^|mG4hi`*hKbCMG zzX|SbPl8q9+uP^I_%;PgbZI_M%QRJ1jJFcz*>+ZBJCUFg`>x@}YEMA%muyi+VHQ;H z^Flqj6K5+PK3(y`w!j`up1Vqz<1CB|Mp6WZ@ua>@cfB2oICVgea|pCK`ZjpAV1EKtq7y&=-Z?hxLyen}7eb_3J;jcXs#o z|LdTCc=Y+VT5CwBM8e12a6Z_9AXX<*hzx*JaU*Fu`eIW%SvAy+hGEQOJ{LKbq z_9htY9x6u!D5o#6I-f}^evTp^LMiYw7FjLn|r0ppp2+k=k<8|e|2N2>+JIww7f|d+-d6tYZ85htL^_-54o%fQy#92CM3^sQ& zJyepXiE(z8Yn^5(1&Z@=W4mtHG?p`Tn%b9UxpTC;bv$5$aPYYUJASNXpkWqkK6k-& zE328D^vp9vbF$~1o%DmVSLrAwLU_RfuAS+b=g%hJglmcri@5gs)#lq;5`*1bspSVMp(Af{R`s?LR-8iY$ z8)tyw9t(Xt7}>Xp(r6<6scwSGqcFlfVl=n1^hd|oz7-yywbCb#Jep^q&r*v z#qa%{{lUj|T@};nHLon|mzx>bp0%cNGczxShIwI3ZATP0Odr&{O+)mqtP%X9Z~; z{bUDrpvsj+z}jWxtQY$1JW>Fuxsq6DdL=%0U*dBJ?gK8R+fIM(rulGTUE`tw8_NWy zY`koK|6!b!rG=RoZ!mXTpJZELeRMK3nwZWHX`-BL0=F=8Jo6l@{B+9z^)I(+z>|1T)9%9n3^A`jNw~!v2M4uVi6Rx@b(JuQ0G;CPIrMs1S z^Ftkb@%31CHj>38FR8JstliRw@B_Oh14H?<Ghkq@ z6UV-?=xh+H8SEFsS52%a%RaV64*BSgB+H2tkv+`&TUQhoPVEZfEO~5*hh0SU!W;X7 z6ONeEal3^#P_THbKL8DRi(hq?Wd%+>QjkwKFBR9<_x2C_-4{HXsycZzQ+N}{YTPR+ z#^RZ|U2Q{sd6y0a6bUJ2Nmc6sdFDs1l(v%ODGNRhS*%3Y({OtE^#po`25YIOe8%B$zE_u}StMl0G?pv5FtbE^Zl^^lTsN=(|zvNeQX1W&O-c}DSMbD{8 zw{JQwkcn{KGU`TC{}r#wE{uKddclhW*QV@NsPYHGT&@bkfEA>jV^iW9e{kbJp5Ei5)UB1m~lKzz*jeengRq z_U<7IbH@%theKuQHX}zms*?r2^vGDGkN?{C|8SR+2_}^=whvg!-6)TFG9m`Q2H*B$Uu2Y z6Gro`R*g0VuF^yiyN0o$^c9=h<-}l z0QRJs0I>XAN?(>p!wWqH+~iZ_@H`@p#DU>z9^K1ztSN^uN_w7HU~?f}sfZ_waZHaC zA1cmDSwO_)R82>?7wi?RS6*zm{Bom9uWBvoTGD#EFdg97bhB|`qT#sk2aFX1^)rpC zqGXe*?3os+%In8FF~_iPq#9O5$%a+gGYwOfZyF%U_?LBx%1thDw?C-++xx{T-;9>XSVS$TfpF24E$&jOJr-N85)7TgQ(=&gsF1 z=NtdrJ61T#NhH_i?W=J#YK>ZFeVcm$v({)eQ7z1q5Rq&Cc_ieGHqp~ z6kHVPP$cx|#HC!t*K$M3JR^$um+4=QDuVMO!r#{?XC?79_l9l%xGGn}3MHYy)>2?= z1V)(#m)^wDz@j+uf^dKopoq_?7)i77p_HkN2fDxSQ*hR2I$h&Ih@wXPK_Beb`6)m* z#i^@tw@&J3C267;YbDSc9_>qn{_{cWMfBHx>pRi^H*?S4-?ok9-}a|qm2746BI+$G zy0)%tD~Yy|t(9!o{W*?IOSG*5o4mB>e`h1YSiExiENe z1Cso(bD7J$zOp~;qG15OtX*?F>=B*<)c$;}GzG{-B`Y-7mFjbEhX1y{%3MI2j@28j z1#~@!>q@PS{Hs;J=&2{DU~6MuFGB@m_bCPq3g5+A`+YSNK>?HwJ&HkajJ`d+cOZ+? zE|+?Py2a-Su#V@XKCasUp~0}v7fD!9nWizODx4&T7umCm+MdjMt91SmWdCXTv}b^V zsR8y?QelF5HR#Ye6kLir#T8K6=}N#|#S;*V=YUTRh0N;K|QtNC2cy25=NUn37Swzm{L z$t9Zi*E??;r@e#balP|LkD|xEsUJ4JJ|P^;0*=rd-99n&9|A*yB-kfx4J*nDT$}Jt%dlLn#J7SmPt;vit=hGt>1YObA5QXUswE15 zTb_4{3SkV`HxpeDG9o3eX*u#n3)ccDalH_>3W#-GYP&dMXb~yi2E9*<`4n~yeb5n~ z!RK>BuNMN!)B?biio`hSj~XJ0HV2YN&eWW>!_JFP+zT5c4ZJFmHg$1`7^#0Z%nU&q zT1%~Qr|UKL`A@Chyx6Z@<_lL&zE;?!9SKEN!6`U-yu7ks^6(2>%sQvp_8}Gt6$@NK zXQTsnVYqBR3!8T9ZusEQ<89Tthl@Mem!Mt9FdU$z{zwYb8b4LiLQCXdr&And8vB%H zx?j6m!6B$GXF$)qPnxFKt(2tNw52moR=_=`KD{Nw-VGj7ng=bI({qW%@JiRgLyD-P z8}d2E&9vej!9@X-V~f~SVYdtPSUS9AHla6DzgQ@<-g9X&%Z0_5SVk+XQv(6jETL{~ zNdhTmfgqyp-(p^mZTO1PQ4Dw27$;#>4$5$q$Tim3T!Xkz9U)pf~ z&B#mYt6Zc)^i9s@bbMJVSFT`ok!;ZHsd*$DS&e+?hLt%)kD@@wWM#UNi5Zgx^M3_8 zNA7z4GH;P38;n-Q=Pnk2paDemIcyT`Bxp*~R{P}lMkgIReuN=~J{zL4hp3zr1RL;w zbc2d6t+_WP2Ba>Z#)59f^96{bCDH|d5&W|zRKqG)rHgjSguyn#tIU*}{xPPF*3)De z9cdwA^n$P;Ff*HG#(v!abG?e=+&Uj;F-~hiJJdYt4A_JnoODeyb_4X1fo-MD*-`r< zTiDO#Y6s4V({&=c5&|}I#(>jZpy0_~+)DY!+ zxmX0%2!gx`K|T&av9N3Yq97>5_COi7G@q-6jX&6~((!_mo1_Hgn|~^$D9j_XL_``% zr=y=!jODzrX!BV4oKuJ&iEPJV`X-!H_?!7>-WYo@OKJ2PD>30mAvLLO7$qpJH!pZz znjUe0?#Wr_u%TCxRe&rdUTlpZsg&MMsOsC*zI=`#3p8FkJ$29Mp!h=pqmV*i($KpN zc3K2XUjnY(ia`dO%?goOgiYcEfXx8O{JpFl0M>iCrH_!YOm#!nEEGhoonY7Qa<6H< z?*`z!2Ap3X7&c<<+vk5v9yzW-q(XG;tP61ek^4*=FSgSRq*%~FCM!UA`W+o)1;khL z2U1m&&ijYBSwXe8VPe*7*+`7W{;wp9uLhzF6}xJ=xW?eW<7{T47aBd5h2V|S%?1&M z@tb*tlw29dL3~d#_~t4t!Tyl@h1^(Ce#J1sZSFQGpilt1pDmwko^q92L~(CA;U>%@ ztME{27|VvEDHflo;^|LEg0~%1P)vIGK(;V5Kgq z8EYJk!1huNT+r`ZjuIqP)cg6D$UNlpPN5isCk2T9>!{8qdnLwj5*WTfAIaTGx&7Fe zSdxmGVF@EFaw}!mLMz9c`RYVu5Q1FTAA-86f*^oG-a`^7IWpC z%`Ah(h2opu?zT*aFut&DZ;5jkbt2LkxAKVFB9@0XA1p=!kB0rqy7Bt%k{=??E{F}i z)?uako8`^t(}_1-`lDx|MCVFp40lb6boIo8eZX<>vOxFVpUyF)3J0HiJ}^RP`JQ>o zvb1D8NQs7lj$iII_gUz?m7|#{hPafu`UqAmvLC&I#Cy#cBIodi7z$b+3W%Y>wK9S@K*OsE+k=>z;XC8{FNsDa8a?`Lt@Yv;(o(NrZghNdGBqzRV*ls zt*jr_SI*EJs&Cic4;N&yWAMY6Wk&c>g*(jKwZrM;!FytFO)#T<`ZX-YDxqOVKEuA# zA}a!!z*tDeSP142yv#Zm*|bJIi2V|iXE5ig6^1gT5PDug=ewc!uZqQYNLCeSKII(^50_seV)M`WAg&0gTWBz=HhygB&hh6yec*lAm8N_7PgqDC?z6OLHPWgT>AWFN*hVSz|Ae8CIMtpB-E=jR)-NBum8AVvJ~_V?y- z0-^Mu?;eK{ujf|t`0eirkmKRx?y*>iH2cV0&x?hCEo?~^EBq$!TPeViVh-`>jzHXm zxgNwc8P{GrsiU(9lwIQ<{$UqalNr!JNM&W_Imx~64W2iFw<{6T5~WzoUq42tqdRZ1 z98Nq09>K4TR;6?rM`~-f(5y?;N{X2c5XcWXm&H=~3fPYb9`L$M3@B1uH5Q{qe_$VE zB$!Xy#iLqLBNYVTd>%|NLoJ2_bfk^byBz;-26t#KC^a2wLRk?CMI_c8@17y8ak zZ>{?2kEhldY&<6n34tg!4+nt-$kIgI2aWI|^KzEF+n15OPP{H;6*Qr2`sG4xVFZ1d zn8(b(c(}z$7`V_3IrnBpPw6Q5-}OMXYj2Owf*=AS*9lv2-srV)5<}FlE;CtR!7nj; zM9{Ch$ug-+ud*D-(4(v!^l3`ODWXXcwP6=W!<#nnjp> z0UHdx1(GQ)EMXM|fpZXP@Tr;W2;G<-jRWJ%kBBdLC5xDjA+KZOiMv?tn?_KN%Z=^V&?eu!&RrkKvQ=HF4 zv07*-<3-zB&>KAlGi!|T14Ek!<~9!uZ5~A1JcwyCXc0d~yx+c^zyV!a1VnfO0*Bwf zQW%sce9;Qtt*AUo8}b_#Cy?pf#9pv8iL_?!VD3dhRRu;YEIyXVbVv_LGvfy2CIV}r zj389dVb0y@C-G!#krlO&Z1@C&z;gK!r7yddR%IA%LHbKfPy(`=mANel`KDdpvv~|A z@#+)lwvbKgRkX3s&@n0iqy#BA0#%_kS=*O<~-KNdO(7Q;&^i^1YeB{MX% z*(RJCzWYkaHXmo3@7>Y%;vZPBGgA%jJQ3Kg!6_wEkTB3l^tkF{RMT z4y9+CkA1lr%C?3R;uMyT&;u6B#9gpLo1yh^OtFzjF?f~0pu4IV-}X6ixaDV4q3DEytgvgot*kW;`Qemh` zyHu^%yX+ZXRdx*FOZeczRm0|*Wxb~T#Xj^#-W-!(YjrEUE*EiDZ#Q+mXr(m;+#0;c z2I?;e6PX}Y77_zX7wKpFHx5o!uS2%3gj1B-wum9E$I{;`)73Uz;r!ZCWv7*hpVjFY)9!J20SeY$`SODR&Y^L zm?*;Xx(F@1*<1@_WrHqS?fG;Ar16`%KUJ4AdG8kuzOf*ehq~(b-Yp#8crda=x6;8^ zlg{tp4Ui|C#>z+keA{k|{88yyKOIOXyb_2N6abF$QAx;nG)U%dD^exQM((raySE-@ z!E}9pIi`$=uyR4D&>Dq-L}ObKSdx-~w$8ez7zQn{eh1m;k>@Mtktj)M4110>Q*E;93_Q2<8jLefV^zvrTF~z$p_k`yBg;gI6xWpNJ`DwRXk|ZFJIWxAvQyL?Y6nC2CNqdU zzqBemYRLIznGSUVW9QJ^!UaCBR3(j1nuVZ~BZi~{T~FW;KySwT`$SVY7)TBd`6Ba) zt(yv8*{0I0T3TW;*QJ7LSuN=PRxfEKN8N&2@b0ZvuvgCIrG{YiCtW(l(rIZTFrFwT zG93<(A;Wy|N{(~}Uw*W%Y>WNLV?og$VLT{&tqL*0xu-VPRX5Oa$x};#E(f0RbXKu+T5x#5zH%oEM3k{3c>IZRfe^6U+z3Pm z7z#rkjp*YqN0D^JGd%!xjEFAxND}2Kb7t@{Dx$O-$EVG+7UR2IxP!|&RJN`U;W{>N zyNi44U8`-ubsdh^T$=QFSt#&sLHb=t{8s*X0m3uj_^C6*_?82w`*4FVsRw*KCYd*qnZ~ZYIlW-w)f)`f{MMVhqk;9#d-R|e_xRVZ znA~OT&Odnz2d*Z+IKnQBWw;F-RENx)^~PH~VuCo7G8aoo<0~+dYT!IjTXCFicR6z2&Y|DG8gNF5hU0&TCdt_l zwLS+CjL0wTT0MKF_;*R+cN0@jOuR?mt{pdi?`Fbu0n(P7PM$MZXXim$2sSax?MzYF>wcdZ{PyIgT#{mLMv`s=G$4C)0s< zFny{Wcwt;X{C5!h4h~Y>d8Gdzy92rjA9$~6Z=h-Xn~5DqUnsweDHF z(aET^>_3&*(l2M;Jc*bAOF0Hhc_S>97%Y{Iu%w5Lif=B%wLm)Ey+fPF_3i?C4j0`kGqY`e(m_=7+*Dc7#exw zO?)r2a3=$AoSFC$r$`-FCjr-dZCoIJOefvNbf)npI>hM|`71M-PVkvkHySzU7Er1n zp91ARapU8Mj6d|oAQKzZc1PW;F7B@4LD~aTCTT?Nkvn-Eh-P}At z&c!DhBU&y>v>a~i;K_r!5eixA*AUaH*swwro8h$Ra|IOC&E%ETk+Z=pA6~9u;r)Cr z0@gTgT&w`{CZ0wuzjdJ%YORptjN!NUks^$SUy{pI{AiYg9V%!Yy7=vVCT~Dhjz{(M zX=FrY$AidI5(R6XcH=>Y3q9jxqe&Mi`1|Za&j&)nzcMl|<$bt&Z#& zX4ftnENnh7qjQ~+KY5Yo17;lZ={do^1Ya1jl6j)9Ro7e0ORjr}Q##&A$a-|~AvJa54^pzfTZ&!fQx3@T9!bKXpwW0Dauji{M8>4y3$%SwTS`9d5=snoU}1yAb)edK?slh*6G^Rb%x1&T21uU?4x zDt6^Q>-mABV>h%%F?k8~4^r7u#VkePT?^^4cX7&y;RmV1D7!aL8;7T7okp(*-$krW z?Tbb2Nppz7Ho37PZsQ=vE#=A~BWXGFieqE*sHV8LqFGo}=8Nd?f+GU>{A86F^A3jo z4^;9zE&hkSH*IL+N*0FiSM)17LKz_6BO0lJ9wfD*mRMr^ z{Pwrjvvjuvb~1D4eeU&4kkoxnovlutsyemMAHdk**PLx8+vmFWih>goA{2r_#pL6` z%%0`_w|ghM`&;i^|A1g&u<|Uk58pzWzkBP+s$yW#k`e3Gr)?7l%J%--=`hgppcuxq z8q-l}_U?e==f~rhh&~QvJ(M1cpJHm8nI{&ZvtZRMw|h63x}`iYI84kjm>>G1Kot&K z$u=WrIv!0r<3MOLoIMi4l@6hWzf1-i(-l!03J*H{A#fi}!L52w{`)E*-)b$`+zgg6 zfz@2`n1|!r)oecz?xzQ!uXxar{J(qm4n>B)uc)>44;1xoYO^cTo1I!GTcvm|f%B>1 zDd*BA&VPoFgW{86oXuvXK*+>=;K5n>_S@y< zXR~3AqCrvw&(fXZs>O8}?c8s9@--WXR-9gsCpceq2F`~)y2$fSJ-jOMw3mprOycvJ2PS4WrDqB%DtEt zzs)b_fSV4D#0TgKbLM|p6`s7Zyp9VYeg&Mj+QE!ci87R@ol!g-*MlCWx9ul@%`xnR z$~f)=j)eVToqRgZ!??$a7$bO;D9l7g-xAy<6EcRA9KE}gaXsu_$H+htjzEbLW|QqD zVV6*|4_p>{xBzfM9%YsiO6D$RkJ3+0po{zMay%ZcFD+ff<7OIOhl4?Q*}ND`n#t$_ zAKpY~OFs-ZH9jw(ZMb>XOU~NE9tap4=jIJg%f{u|=1)6YFH0Ew;7{zC@lIl-;C#;x0+~9PPNX+tuuODoz$(9 zKCaHSTj%RbejttCo*joo?rQ2;>qLXj+W)zR3#yL=9 zdXNTH++7XYUdS`rUu6G0UJuG<`)yXsehJ>xP~_|NyT;ect9|^_%@hLi10|^H4ty>B z$3Oeul@KYQ^n)?9o;KE+Yt7}x%95M`OU-aH2ArRqpPNUP=02(o5TKTyKYfayE6<;< z&?o$#p2N4bCr_UK$I8m{wbkdVPgd8S{m1g^la=SI{}C+zlgCc~Cb)7z@E<^>Lm1aZ zGNs%>GKl^a{rMOFoBv89#W0&mP7i$cz;1}U{1sMuluYnw6V{+fLdJG7yc^Nkx3FD9 zX=k;Lf7j^m6Z-p<{yw9>&*|?A`ulC2AfRwv$G~po0v!-IG|SvAoh)U9BP!Af^oWH?jo_a4w@P z(usi?sF6aLPvEV+Jq|A=O*E+{y01jQFLWYgp2DEd4nHgdDA;szaRF@$$9{aczvDpy zK*+bt5l>|VOfx`sj(nR@10DB=y}MjTurhQeI}nUPXv%C5pMtG`xPZPF@!16UJ|Kh8 z=u$FbHuMgqXkZKn#FoI=#?h#sDp!bYzNUl`z2ME{tQU8Jy|@z%QgX8y;*<0eSk5y9 zgB7N&2naPX-5@G!wyI4CJaobV7z@n0jskXcs}b+j14hl%bcPKq)CGw4IC49{uF7KQ zjm$F(<0D_5Gh~>f^GOd;5S^8N-aYy0@a;*kb?{5@^VZSP*1^dy8+6}^28M7PG9+9B zWY=L#Bal$$uD?+@M`zuVCVQa0D&~v3f^oTo$PME-P<|} z-n>0}b9lT1YkM3K%Lnym%F-xpKteTwlabwfSqT4Y|$@#gY zfC1njp8y$QP6S7Vv${V$muW0Gp)0X17EFF{Ja2_-SF$B4oII+{B181`J8PItZ12sW%J{NdUr2C!J1&-e$4|k)i^> zOZAa5rDI=~Hqt%`(a2u@GbG&%j3di*xhMg;zt`x}tjLWDPr~uZ$ zxHfc!Sa&rTDPvJD2AoU@(E(pMYDS2bnLtl@x)*^~FXqn69lXJjrm?4h_Cqu-L4^tS zj+0?hfQri)iqdNPIFj-iWzIwz>}U*lkB2eFQ*^EwRTG2T5TH(CVsJvztxQJrO6tSI zg2rgo@Koo~^)Tg7hDbC^!UtR=fH}J8x)jhrKOCA#ML{E(q%3fZHP&cI*_sCcN4W>t zA06%lAZUVAk$RAOCyI&@Vi!hvG>=WymWh+57D%jQ@`&{+p{Gs5!)`p%{faCo!f5bvvVeZD!D^Cf zFmr!|(`PQf^yOSWaUi7`9R7*;V`n(uG!hyJXx&lg_Te2;85n6drhUltgQM*n9F~;3 z+aMZ4%pcbK5;hO!7m;JLTsj%u1+CKx>Y50Ts+PBNw0&3sj{OidNNSD(992{Tl8Dp{ z&zQ=5(6|^=%+79760Ln@MfLL@+TF`fG!$!$17m7tK#G8B$qLjz#uJAsj20zWC~qDsL%=M@bltfqyZMm{i!GW0c39K?g7;H(^L&cHxbOm-e9>Ky4L)64x0-tno z$>Itrn3S%wO^(-kWyNd4G+;aF^q#IAx(OgdiI;qymVCM9j-(&cj2RA!2ZFa0B|8!X zw^Adhi(c(gkYeys6=)hoS{Umoe1T#K9bHJ6w-5KK||qvipeo$%Whm~`;Jx!_B{>5Y&4WQSc7JDnBG4ekQ-V2bjM*T+TGE7o@Bq6Bq>uB7+Y7CO= zP;eI}t6|1XPtL+L?z9DCKWipeG^YmPsxrPWqCQcNk&(2#{3*n1bV7&nWLp_j4DFg;Z5WPQ= zYDnq6xQO{PL1}?}L>eHI(zEAl%ggj-O}})b-Z?09OJGG} zD&0+bL%=p}>*A7cZ{WuTi8~1PtWQ0q(tS9J(5peG6}?($thWs9YA_jJa%aLjUbfCC zIqQYLM~D!xci^wTd*Q5_(|E6Rl%Dk_5o$*eh4dj(l+NHvks^($PaTZZLPNfa@#7}y z&__Ht10L+52Inx~(PUiHUpJ#vsx+=|aciYBssf!DO;W*g>YY58K0d89>Yf1=b8Eqq zqH2M(g}EC|J0_8%8NxGt1>c`uKg&VN5H+@#e(|gU@(-EAk%hW}_SAv4)?B@Q`Ul}X z$-sN^2jKyX=KCjTtSNw{dXjqerKEgbGmJmj?zL@qK6pvS#lT>rrbe0CSanJ?Qe;R- z_-+2tHMxHF-_Yt}X607@2)s%6ir{@Q0NCo3e>hs_CXT1**e~sSv&OY$hYh-+$njiRGUtW*+@7gNEJ3EKf zqi>xjxA00f5I^d!EMLR3?izpeus}B*t~|TFhZ`1zDS zhr>`lRw%xV{8()++i&j&H~JhVkKn{>&#?fSe&WZs{9#`YSFiBFZ>U1zN4>rd48Gt@ zVYUSMAU+49vQeK9-|^$c3t9Vqc>5bZIKw}N=fNMyq2gyWq`%|vLTUg*8}P?jBwwO4 z{nC>!(5xxF^2~lG4B;mmj*@mC zjD#Gdv{U#i$`I)#N;^+J@YmHRA42<$HVS@UBLW8BprAaIk28MJiyTn$V=d~LhN#o{ zVIB>cN=n3h`|Zqrz1FWUp55x#UNkme@rK(1yMCcBuD`Y4&g|D~Ej+-$;latsJeF7Ks^KgkiOhRW{GcK;0bcuS)uOVqV;rS zzC?H|&@WW@+^tYi3cJshe<#xS`-|l~8{nVR4HJ`s7zv=6ghlXq+0kz+tL6!Q8^REv z?vT0NeUZq6XD@!*URhaMSrq(JdO#W7=7WXR8nHYep?1+ZpJ0^(varKD8Ppdc#Ixuk=D;?nIVA`BMP7D_ zbV0)P%&Ekf52WIPMi0;a5p~8WY0%9AjRWS^DhtZ-in*7Br2FxZu{LP(WWH|LZvYb=|xlQwhmXqHT@7Y*X z61FTfOrNYhvtNH$)vpG@nf~$P7caOo$h7ho^0i!429>`VF4llRk7-TQB^bwCtNq$D zUwdA?m1piR*(=Jw`mdN}bqXjCn<<8Tt6PfsSicZ4g-#)168%E5CoDgkeT^)vSA==m zT(Pxmv9+RNPnR>rn77Rp`!-uF*L7lBO&Q^Fa|K43BBOjEXFY`1%@y#WFu$8C1T3y! zig@09F=TQx1)1-4iz2&g3Ni0%UiV`|BH-xNZ^Y^9FJyA5I&r(^Dc}e{9dcKR0hVuT zt7f|>c3D1{$`B{a-~J&VjPXN8MdEi&H3=(bUQk*q@0U<(o5glf8D#^6S!Mk>g42u& zNeox|YUU!nqzB6G>JQ|Y-S4ttg@4xX#6ims^Tl=qS!oZt`HAebe3kJrKW%Cb`P4G( zv-|zb{c&x7ym)qNe*kao0Ye7cdvN{27QX)0{eI^D5ctYr^RH`O(De2P1xY+NJtVH% zJdX7sBqm(HJ$1f5HD8~ZZ}t=#$1+j)<-)8Qc1OP}6R*FKf2S(M$n&?*)FhT(f85GR zB#E@>D{}b!4Wke-B!O#O zahfJz(xlnX6fm-_t6`innb?|VYbXYR=~!56vSl>g728(rD_LqLa6Y1K3tR616MT3K z-CcX}>@4l(d+Vki5{ZPIKB>2Bq#bz9nh^ZJOG;$T#^Z)O9d_hP8lJ;g;0p%x7?)m$Kmsto4#Q6MCuF$17W^yv#ouL}k&)e1LbzNWLNqoQ$2xDXxU z$c}F^ZAf$>t`#ugAC*4~d*PrHO+;*ifXMrT&;kZ*pLI$s}<}G8-XBSjmGIDcI8*I#LFv5iNZfs|sWFu`pIGjNTZ}sWrJ3(nLYo z-(0SxRzY0Bm~Bz(P{2HxGSm9nZTv;iN%O)ltY^)dRz!R+I5eKQhep@gOO&sxpu$tP zf}2y4YYlH#X;tyF2z^8lJmWCOwC$7h)~UTHwHK+(lv#1AyMv6*`pIBAhh$kqDyWrE zX_v3Tx;*-uqfczehr6G#yWbBBHklh4Oe>}5}MKma4Z@8laUHJ>rrR9r};KwiX%*;hnbfWk?36_!Kmut&U zm&vHmn2Y%}H6Mdm6qbt2$w*Cl*)KqAR-k6;_EWdsEgS}qt9Z-D2G@K#wZ*5iS|kI; zDZ7?m7N9dlF`P<+FNbci=}aV*^YNEza6H7>RW65yjeP)!NFG`XVHH)z{vyPH!+fE8ku{%e40Fv-|rT3O{#2xDRGvtq0?UQ~iahIUl^* zeYd}}9*iQoHB&7<)qMom7kJCELQtKr@O&AyX8hcK#q!TzeE3$%o3HTv+ckdp?b@Hy zEt=z%wP(*|%-)kn&e@C1%Dwo^l^cd+@T>-68s~D&DUhTEssyhyOlQw+og%83s{y4f zGlf6M&`ax>ojb`4{fsk-uQgYH;49PX zB04<9JkPiMGvr6oZG_A5V&?H--GYz|+L@Ss;e80k!ztBv73CnSPSZDZG4Q-f^x6 zZZZXq58Etad5D01D^hGQ>ogfhSGhW>5b%8pvMrih%i9SSG=s&I=dU%4wm7GlLXq*Qv1b zWfKYYmips{Gl|!Q4V$xzTE5nH2c6N{a-mQni9HL>2X^k0gg+0GQ7&z(qNR9Luo!4h z@}$=oMQ4#pj4lBYk0$(hPJ$VJdtttPTQmj}Mcs7e#@e6bkCnoq_bK1z%!=eug;%6; z+M&184uz>OI@iw&nudp%c`8rV#3`)5$nIfN#)|KX4N}eIL4;xQId4p z#h-V#M#ZEGNEssWf0+V9^4L$&-MHvt#gHMgtpyhhB=bz?!?@bCrTjxo*zl}?d1Wh# z@i;bx&Zf+*QwE)4=_2_lYRIQ?TlCsg`L;kAY7ay$Qv{7leeTWXP!dW*FVWKWivB#K z8+1KWP3ZiM%2sJ=@#l#)YKSWm$J9pX;h^6k`#PWniBDu z@{&}i5HqYT43#ZVAEuX6FNM;}r$r-%$GQE57OF)hbHu~io8FAbl{)UHiN=a3;Lx;a zDH}U3Go6GkK<`xG8o-j?#}gmf|}paCKTz)PoC zk`{1AUP%IurXFivwSqM%uI6-VZCYzrGum34)>f{P)6$c|mY6Z0-qe%ArV4AhZ56BI zbJcvUJB|#I6h5Y^hrOkGpl1q`IBEWZ?C&TEyO=h;NI%5e*w(%-pjv2iJ9bM95wUKA zw6RoSSa2iiast%EP?r|Y`p4MXSeAf7I~9;5HebG*7%JXZm&xlFE3As`;I{(BCOmaC zn~nqRb$DBF*(jO2oZ~`^7uj_9rLWDweLWm5-e2Fs|BI;B`P%YI<9zauc$_M3$gw(I zGdS%8mS0m%iyx>reR-x;ym|Jt$P)kA)5cA=V3u!Qpik;_<(I^^Dix>*Z_knfb*FES z=HGAKQUnTi4awIOmyt{8+}%w?+zD2?>lYZYp<~E2f=QktM1=D7e$ShM$9+?8c}BhE zsr7I+3p8Em_~mFF?VLLSB2Bgg8}-hOpoal=otQNec{7m6#4!e2w!x1HN;2r(c_8YP zq6wYB)4D`$GP$#c$#4Rvd6Ti=F*sm!%Ma<3x!|+qDQZr?APPbcibwroyMA=cqabh! zi>wn1pt04Wg?C+K@Mq}-386@vu@J?=A8{NX3M<;_!D?~EL{qS%Grl#CiC$r2R(Rnl$Sbc%T>zp_fp8K$I?TkwydHUG=Zmq! zHvR?lR&+uS$)Xzwv{g2t1l__b%TEhHi;H-+2E506wBZf@4Lc3^HicxX&jqa^R~t^P zp;|4s(xT2PCDbz!v8e zJQV00gZD|8jxKvYGM>0O5hz-jig$~YTTt97ollsklIMEM^9{YK}W@ajKeJkSohyHS0^`G z0_1}wk`!k5%@n&gVukIWu3gx{>2f?(a|=MZm=eGl%=w^UZvib4oe%^Sq68FSZyb#< zZrybh?7uxe33d)%2D=BrR7V2fg7h+82J%Dqg2bL9Dz5K-<`n~ z7sORJU+^$nbOEBJGdDZnFt~W-N}s*SfP?IIFQkYfpBmJOfEzjFLs%_hdL{W0pE@h@~W%#^;n zxRH(wB_y@h1@4}|u)HSA8}&0YCc>F?)CuF>$OeON_;KI8A>R(KnIuHo`Y=)g(7o~t zQ=n6QslD$DGLJ4p7=hq>Hyr7EM4zYtrOX;9=~X;Q;r7eBC(B zz#zu5A9BU64tsF>j6a?e?1-_jOGYZ^y}QgDT-`}0F2neWSANvB69OGerG6s8&?EA7 z#J~srh!eL&vks#Njv_u`f0IbH(^y36u-XT3{39$*l`~e;gK<(JJpjLSOwSsc2%+XY zn0=%}fqSXtvKkx;oc+K&(t9f*$jQD)agTTA^@|rHf9@qNuHf%2(Sx(eg^*BUN%+;b z{^pXE@~|oFn4Nbcr}9NCQSAG|-!R&t#TxHtJeurW0EpRh0R`@<9cL!|6cWln`A@yF zvzwU8J@I+}^a0+G$|#Gtnyvlp5w)Lb?KP*i5FZ^K|D>C+}{VEXm|LSUhL?6SA@-RX7Y2!jOUpwcoSANYsa9mIj_t8PB#@EYXl5vEz<{G_LiY9L92Y!FO%2T0W{MzU(Ui zvn)y3O9fbFQFtMRW&unYPmXd;Qqy6sQwr3MFd|9hL>vpoK0vFVaWEO;Od_M65RgRp0_g+fO;na#s3;7tLwL1A41 z6RH4j5M5)6E6n_vNb+2mrg5`0OD63z0f?cBS7ePy z6b%rwG-0YU%-StEHkG(UnxMB%d82P6RTCz1#_B>Gn)D-QE<#Zo5=9i-u3HZCht)8ZE_V) zd2=~5U9?Upi>@PtIyxvSYOL8si5a(uHV6D$VxTR$aZwf>SHlAKZxM4mnaS`XdBM)P zFuUQx>71mED&l)MR8NQP)|jExY0r3<5>1&5LIc(KOu4M4dFxmX(kzZ`cQ7)L+1LZ8 z`vdd%!r_9*&CW77*QwWoYzNlNTe9sgoI!Jam1n;fC1Od@oAko0FREnib2eNp;vE-F z60ZFGYJ_AlmIx$Hvivj?bUU;iw`RAwt-J^VaN!HOJTtQwcAWVp7t|uwv4AcUM|2)f z;fLtVySbDXct6KC>M0+YZaQhEnMyC`y?Y?ek2j1vSDa5fxrjM=rc!k zb1n*f=e;>qhm!7NP5{#RN)Jf?A;Pa;hA&@D3DmCNldjz>#TVtK)LE1TLqQbHds4o8 z?y!Yx}Zi?{zg;!?awLvO& ztCyTLZB{8Tt%N3Hvdd%a4NV!9DyP9Hz8g@jp;wcwhD^;cJ6n29ZP%rrKDaDa?bOMx zPY&MaiGvo7c$(WW=g`{N5&O!&N8kUJ(R6cbGN2#DHDjPXz^?a~LNpdME z`dJUNZO;c0h)CqU_bMvSh4e@AuY#YFEFF$|!6hBvvRdRamNhSoJ`P&{SKIUcIS6JRV+5xk)oU<&X{F(=GT<8IW5&d;OHI4zYJNi?xM zCUI{pKWVJKXs)ho1oOe$lWpAixrFkXCjQ~n@ZWMecuW&FH6gsna@zTPYIsylVE)`u z1oR$cOyEuEA|JSxB}&cSjnD4@3_O}(hy_+oM5BJH3ar-$Z-dt~DZSv$aHMuX zT@_$2;n)@J&Y0CAXO#Eme9}X$4Kijw@1Fd0`1T~g^nO2Y9UW~Qocyw3Vu4d6ZG;r} zhrJk;Na1J{4#prTo&$jWouloapvKmZyL-DQzhL)Y?VcR$93Ka-4v&JZ;LX<2$?o>s zy{)6*&D*0lhsQe@&?$<97o0JdWEO?eX*U{&aWADI{{pKgIyBNRjiOEzUq>7Xe0cZp z65(X_P^Pt}IWmK2DSD1M@LT>3izT7Fzvi zDneu2!|I_~eW;774L6>}LF&sn?LFud9A`KfyA4InI6wm_Xcy}Gnor(+x?2hTf-NB6 zSgKA~-w*EqEjqnPH!|2Q7@A^&Ak!Bb1YtZiighQlAXs<=CoE4iywu6V`8b4q9SsbgCHV2zZl}{kGY>d+n`fi%jT&u*RcFc+4k#|f+ri-s@*XgUyi zgKhF42y$i+^b9I-gII9fADXf!QGb|>!jUaEVIg!N6|&Qc0DAG+I7xcc($AL>(OZ26 z8;*?p7VcnA50V;8`%#1jWk47&C|%cg@TGx#P(Qqi{wj0;kQI@{AXVjulEtZO!l`S) zDaKyKql$M#mWv=T^9=N1jJvGyJD|QScsaPgcb@X{W*+hamN!TXU&=JU9{gSLNRXqh zD~=+&;+5(K(`anAkKB~7HsGbp1>m+zCud7%;i#De?vJy71Q!YHM#KSl)&%$|y?K)~ zOR}b$m5=gG{G!bef_p?^y8O9+|7)wY^kK1bU#)y(Y-+GazWJuLf)C#SpbGrGubzG?SuBDU?GMwa{4U!ICl}^Y^Q5)1gm6lue$Y6F3KmAW zRFb^4ID09kS-T4Ufpgf4uOfCP;8&~%L6ij+<2=IKp5VL}UZkW10Vo(Ar5~Zq&+if4 zu5gWXjOR8m6=S*H!Di%qKZ`F|6+;Pd@kpoZnk(IL&Hj@h0vQbXn1rZu1g+USpPMLH z1a1gUy+!I-NYDU`G;cER>e=u z^e&y4v{y| zClOJ(6bNUJ4tTteV<_%xfS#V;S(L&O&QNj7r1h5kt1s0r%I+jNz2`|nY;k4*&U;wV zHQ;mSalL~z;x!4CQcKRA6OJ&qn_!-o+pvRIrg)i()d8JvfH?&e|0TTpiV=OCX%y~I zIQmlHZIt}4G@lR{y#B*^MhG$8gEsbG!hdhXx|gs2aV8u4uL6>Yp@pCN!1X|lx5#gd zCj-F#-d&xT{U48C2Avn*iUl(!mq31r_PPuR4xV8$!0LR>L~IRoVh|b317Zpc+6H>f zgk9FCG6XqVFQYrG9}b5R$g!{!8S-kASXsNpiN6El&`oXz$p7IzGbh%j>dbJMJj)3Y2<~|xTwlN1Iz9o?`!zD(qj6_4PKhQU#!*_H(FN|$MEEG=mY&; zgn?`4X^wSqW@7l$zs?QGsR8{iQT~j1 zvJw!lDYYTE3GZkF;%%I>5riE(A0>U8qK)8Xf~b!>MwuyG2_^bBQMJqThYcW{Qy)sh4+Ik6Jw7_K;2{s}A9g0Z7V`n1 zq$pUN-Osx@>hoSFwXT7(3CP$&eT_K1cP;NSiet0a{i7 zUhW*c+&S3Z-8pW9B>M)0*{FbfCWKCj!~oSWJ09?Jf4@%m6L1JEz~MT?1i{8WqnmV6 zG#;omxyiRkEwLywyXZlPaf$=x_G}y9fXEjtkQ5D^K`Jd$hE|##s8MS=ct>oU zoO+gza}UCobww@SNk0$krbY%I|A}a=C7og(0~f3ZtyVes-Y-J_{+nArZok}l_4=pX z|NPtD{=wm!|8sPF^7ijPzx(CC!m~~{I={G#|8dpp50c?;BcQg|H@A1c%Lak%4@8RW z&Z65PNTQ@S;d`kxczJl-NXK_Qk#snt7#;215gOa}A`nVPM73<}&tKpFy8dBtJy;5s zszFO`jxLS3$YSZ^)4<-W^o>hHaQ&dVWA7pB8FV){>Zra^d}#A5Pt+Kr$`M2th! zG-2f`O4NX?e72B-3;$+cRAkw3)k3$9Bue9xAm!cId_%A3NW(*i8mjv{83=wz%oj0? zu-UpX;Hu^MkQ~KCRmOKiyqD`?(&IpO<|sOw#63QkxHC1r&7%=YwC+1RyU3zuKIl&R z{X3tI;MqYY(ava4xK9#bQM$BM^?-)Mg-*+uYfVzK|42+61y%fCDZe!LSdSQVk-JEd zhoH%N3XLB+o=wZ?dKGPpn88LH&(R$>t%oU9;7v~{=PqG@b)>p@PAfps0tu}SnK(zi zUbC<}SoEhiZ{Gzg%gxng!cO3{tE6A)0G9K>

    (AyyB8bdr%wKoI;0tPSx-$iJY- zHNHs*imj5emm10^;Rtn*?1koRgjTDv1h|dAmVT`)b>-_ieRad-R+fTwDENJ5cNbF+ zJmS!X!mzf)ABdd|u^rIeo;l%AV(Eh1IA&3b{kQ3!4i%~hq?aT#R9TKOZZeuefXxCn zqL68cw4Q9d1yU_g={iA4(Xd#2ygQds=L$wgtPI+aHLc9c10YKPOGe8T;USTSzl$99 zUAPjY%0Q|o!!EFe^~{VIax1Km6wA#V5!!zx4R_C>3Jp}?s9rdfbN4xLn$qfPG14N)87cO;dI(1aw-9mY5Bi*?KalM1*NwDx_ z`P*m8?anjsXU$b?pdP$f`F0g)vOImNR1&StMo}NIjre~YC$+pGP;kst2l%h5JmCn%g)9gughsyWJ))ODkAd`IZxx4(==3=XvtSd=Km*$&`9)SpmEVK;d z62Z=q1wn%EiTaPxm*yqzshs zGV045@g|(7R&qR(m$5l6~ZW-?TtVw zl(HLiyJXeb?xh03_`6)$J>v@n|!r;B*`)fVU(C=Mwr)1aijQ zR-hUlFz`(){pBwN3(DYX&x8rczI1=D_zZYov3TEV_UPy7J}t2fEOZ9o-1X4GBAn2p^oDCkaqYd-yglt4*o&lDSNz z+eq0^5jF+;em}0N7_jAFA#d=*fQN2=MuRkOS{!cqC zV$@|34}`(oVXC(sJwIMJQ#NlP%&hWz#WF7{jglMU-4ebZfPVlgFr@$sVMX8pUnUV& znr|I$aeF&>-dtvW|D66%EoS~yPGhx?G$F|C!^uCtq~|PTBR7dQ@yx`b>TF$WnT{1e zEO>XBeb>oBx?Fcgw!$OhGj`etGSJC;1#8`m!eKym56s<8NQu=7)~5n$Hk-u$&|3>O z^BjJaN>-4`YjFSNTBy$?W-JT>O?FR1ed=KSSFyTIG z_&SR(&_t|ScD8&uEF*djeh*phw=|iqarssdcHhGGH{aA~oql=)L@f@VJ&`#PeRN&O z1F?-5x8Z_~aE2g<@|*%uCbdMQ6Dj6h1V>F7glMOPy5At_?rxCf7GB(@IURgx^_*RT zQzepD)!y`o){+)d)lt@}qs|ve*L1ZNGDW#W9pWHmp_);Ae*%D1y@DE+xF4fqp#U6@ zCeNM_qq{+7Q$|Q7_2K`syl=OV9d&u!uFvE0Vm{3076Zs3A@BRW9U89?TYOp>Hwe+*FUEFN|M-VtRu2)9KwT$RpXyY zxE@8h{w&gkpdLZIaGXEmp(0D)fmyi>@&2EiPRX8!RFP~K+%@(?p#eY{?mK8Tfwp(5 zTkl86;lyd*SkcA4Wkni|_?R+)#C?oZBhn2#Qa$*xn4#LFFt&zn)I1rI(^lO_h8w)N zl8YCBm8Hx*KobLN8qBAB;909)^!a6VZI@l#wCo_cF+i;P5|zJb&oz$BRIB~$svRnG z1jr!X*lBWxoa!*L$etY&3Odj!14D|Kmn^QROTOI`v=(CIAs2rJ2C}5WEFyd7bqmqv zj7)~{W?jIGVK(qQ=h4W3@%j-Y$Zr(&-nn)}Q+KquiBkiFO)$rD3E2VSF+k-#9&8NA zyX6G#2M?x;0c`ETg#n_100v8-o^p#JSw0g?o|qxvbw@EIdrW6BDc~yugNwOp?g`H2 z1MQH5ZnwMna4AW%J9C`*w`()sJ}G#sG9~_G z#>3%r9$<9b5q!St&ina97$Kh%(jNUWZC*h`!YVz?D=D+|7;foL(Vl&d{_IcHpt*}V zlRIMeXqx%}IimSNg6s@4GVYbM=+amS)B_Ez7sT}21Tt}~^h=p*Hfw>eM`Ox1T4;So zsx4$LOODN`sLJ{j!*oDC(rkK1rhl&a6CFl@+#=d)FS4eGZ%jx~q@}QuCthsF zJu$||X6tZ}U4$bvnIUyRgIFTkZ}<1cAf3P-@dYJ&d}AD!B-mr>;~Fi^;6RuZbE$Wg z6^h+keb;D^WvC3Kx?#|s&GhKI;k2+;v4mWwoKm4ey&Uu}<>jkK1?`!X57O=8pvD@RR7wY{3w z2p>^6>X7~uC+Bp%S`sdSPIu@H41~17fiXWO@0Fn_C49>&GOS|NVd(CF6m{bSs^O)pt@QvTx$krPzd%(;4nMQW-YmPKp!Gk|l*hHN&l>fRHIG>K6xofNWDIPM zg8?3ppCc$}m_yj1l#Y~5>|6&>o# zUMc}{@wy5KN8JevS+}&t1w)r3Ag6IKZ`OBMUpd}Z4J4g4X9k>!Yb@Spj*CYf5t;G2 z#GkzI+Uex{JieWxC{Rn5r6y}J#|hHi>}IWe+~4}!4jV@|?2tdf;YR?a4dAiQv$~|e zemTLU{;kwkyIFjGl?*=HgP2uCE8Jm7vvHA6ol$tw`6PkFD%5Torf&Pb=$><)t2B{9i~t z3dl#c4DUj`APkn4Hb~`Op)a4!yEvX`|GVoR+I0_YuFNU_$F^6w@w#8WFE7#G#_O2A z`t94-lWCl{liyx;p+EG-ROF0FoCsDS7g|a5A7-1 zQLPo)O~96^k0c%&h)a#hpSGKdc8U;;^y}d3Rx9}WLJu*yXQ$51neCptf}%#}9=9nU z(^PAvwO-WF%neHJu>U{z7T_Sr_%P}yJB82b5aDTl%fYjZ*S&Rz^#oDjih8{U4-13XUN&O7-6YOuJy`vdqHOt*ejXKQs|kO8%9Nz9zr$QX;kPH- zg|WCKa?t;Th+O~Le_s^;3-4A##IVapwJ|&X*V^jSwQT&aC#x&Z{x|;DzvAEgS2p~Y zENjp(-$EPknAe`n;JPqXWJ~(USYJd|6OIamm!hN%f48!7^fXxL$K$2RIPPU}tC?Qb z)PCs(-R30l)hI&!CaZrC#Is=GwzI@Y%zzvK#*zxEpJUAE8$1F!CiEEJ-%>E9W@)}C zD%q0&eH;dOYR8j4m3b45`Y}74!m!Z1>Fh4Jz+hN-=SX43#4YGT3~~o|0cM3kx2Q9; z@TGHzx&h$KA*6x9=sqP)lTJ*gW8I`faR4~H6W!6WBUD*KiBY)qgu=JMaUg0j6K6~# zcwxAvQQYAmX>9!)OZ+Q*-HTx*Lea6{e9<(dVv<&;-qs~78hl1HI0mB&4>DEM^37$^_eX<%sKNPUG~n23=&TAnbwaI* zjz{iy?P?D=^$4Di5`>@ccPt(N*N^_$9I+Ndf!QUNSLtQQLDR%;y32`VLuXVJ^9EH= z z0&I8Z7{O(Nwqewmhk~|27hVG3gWZEyN6^mB{?5S(GFu1mFxdG!{0feL+S=R0)=H?+ z+&(-wJ_IOl_k$mIpgUVX?(Hyi7|ZtF*6w~ic)7K|^%}c$6dXdmBPzyS3V!}+haT-7 zV4$^wU~Bti_wWFF50Foe;Ab5McXVPZ|Gay=QxCR|c8_r$UL74m12~UR;}F4My@Q?Y z1}*|Z!g= z!6hq#T~HKb@kPdrChTJDmY8g`0llo|5;qIb&_o2yG(m=mAEj_REz%hyf&eSPtGpihtumgl+H0kN#(iue@T`kmb zMZF%)DIaT8CPo-!I-)M_=+&-%60%R-PSX7_un92+kuZ)G801Ca>KUoY0c2*8WYGn1 zXM`CvnjjhUHmjv-No4EtTxHOs08%KhzC7GL!SHGnT?2&#x^qs)?u=3VEpl1KRbOw2 zVDhB7hTTCr7KNi8hI=AWAVslOqT9f@o270Nk2fnHwW-FZOsFwA7X=@R1^3^>XqO2``}vcbnOWg>Urjd|zt zVl+g41bV*x)9a%*)OC9L30}h4WM1wczLb~n6kmdjWnLcsd>}93DZK0(p!)){j{wb6 zc?i$?SKW9dkN5xfa`%Yd&{KGMt#AI$kFP(KMtym9v`^1Q{ZA!4DHZnd$CDv zrD2lBx9y8wa<*Chp;{6b==k@j?Y=3gnPJ5~B~?%P2hu5h)LWbd#Hhx3%~fQ0S2+$; zR)bh03+L6kz1;Z(cq_f6fp2mwxHQHMOEN4_IN1=Q_iC0%`-C!ptYW9%-Q*?1Zxyq6 zyi)YGe@(A=R$(IXSGmFyigy(}k5sgjjyjvAZaRiP@u&@q7yaTdB|PTa$)L@&YV$nA z5e||z-#@pFyCxK!V7$l8a!Uh0R+fYJhi~wl_<;T{?;9r{g5#s@SG#bCy*xg_Pn?)! zlq)Kwj`2I-$<8($Qol?o+Zfv-ZpCTEyQcUqmn-cuwOs*>K(U*-HPcg|AJW;TmRudM z&E?vtD}|AKY1>podt~Z783O?(!WwxUD3uO}!e6nk#EKPqtkEs$MbM3=jbZTF2*V^R~r9pe(~| zZQK#|H|~?xrqOkQ%D`PyVX-iF@SO}RkVD7eH7!H)jCGEb)e%c3p!;?i<7GgRi$cMujcWM({?MCNt37ARrzo?k#UC5L4PLn^DP zr8Y%rQ`J->OoR$fXt_HurTR4@!JC!UlBB+16N&-)A1qdbD&?c8&dFz~x;Pimw?%pK zgM7ZPYDza7csG_*Ypi3eu$q!ms8KnNtGiK>90Gp#6CA0K_OgSb1tU#sfg$Y{G0p2S z%%#wF9Hn3Pq!tuWc5l*^6N1YUE-f z2o#FBc3|jy2WX5h1pmi@wmyT!WEL zR6#d1DK4e8O)h2PyvdTf!oo>c0yYouMj%XKca}WPUtBM$K>WEj3 zZq-PCZfsL?%Q6t>KbDM)9A&g9Vb8@JbLFw@4YznyV{|^QF38@h@h+7r6gEW`~>j*p?b9^NrN0MD9s{9!{vd93wb@L67i_Q4j|jel)W4% z?ln0?(?u=D=1f_DMbJ${=#_9XZXt`)$9TMW{=g0}Aw6I}KYQ{7sN1kjz200|Thkjz z;CG!DtE+|rykBlS|De~P-lQqz(^;FFv@z*?dvvoY#fd?89#_A{oCsBUEBG1MW=}Cd z9!z^Rc>er((2#+B9jq)bF9+3HHK-U^r&%M1KiIYUO<(bh;4|M+(9khz$M{v#O|C=394cm2Oq9kfdJk;&z+){4X#t*M#-6GDL!^$L&B5cg|=O|ZZbhdlm=*q zGabu_ROGLiVyi!S-YzI$o6JUc7ExwuJ=pa+?=d>r9iQDmcGBVT(y2xu5%f9rYUzer z&MGG;cl9}HI^z-6W~JLXY3akx6?&A0tdNh#l-lK7OF|(^BjR=Lv^2M%?|G_fzU{|7 zjt&UvJANCi2i13IHuF8i zh0?>^P0u-YeVs~;3+b_-B=7tLHIzVoS&7v~K37yj&iPRBprC$j+1Wu%0vuJC zB?XwaWNtp#W~K!LL5%uQHx>O9 z&he`9d1GZ6uU_E<=7XO;PE`=pT zg687#`{mUS_#cRl&Fpu-A~QjAmIopnbxSb6BAxsuSY0){0GStlOxz3neXB<)2LxiAj!ls=Ltun z2+m=c?TXVhl$pht%;`Llgx}~B{{$T*rptR*nnN6)bCtA=+JXu$0xZ5?SzUXI%Z%&c zE(%cC!{gm|3^-^EQCb4b{pRL2I734#-+7E@jhPOuPd3`wJCi&Hlccf0o%&0#w!B=U zoz`S9x=8#BZN=~``FOHV2|$+M!6&@(uN-Y1ygb}*R4P)CgpE;zj-ngEsE=b{Q!_Yo zx@Ggd>}$qZIDu+aG_jhKV^TWjE*5Y;m@W}5yDH{dKugfZh8b%#+%{{0L#|i9|I3Q> zR2DbS@yPnKLZ3(?kQC#y&8uT4IPL+9sS!&X{ifFV=}iMI=~tSoYb5t*08(ApzFFG~ z5T%BVAQ@>@x=U=3phS_=Vcl`9hoK*RkyjAjvFA6iA*OL%?PtxEe0zFZK+GT|?XfyR zs^3f7y>469{Ir(_jb7KT+$k4goOX+HvR6I^et>_CA4bHRsUDbj$@Ar9N_pv)YZR4x z`qY+#*R+-N36cj!1^D400&GtoOa>i@bN;AM-OjgHrjFEH`ncsO#ze)3Q0DTVsD*r+u}?(HC)9>FxZ^-Y$67Bs$DBcz@qoQ%F-`#>iX4ub&4c|fntq$W zG&_5zxdhV%e;V%Y*okT$6_Lq{)v^^{J1l8=Cgsu2?{3sW7{R*Pdl9l;FL21^&oy{JG?> zHI@(f?lY(BlWw~@zA2TzId@v9V6)l<9z~RH>I0lB_4Vi`r8$R;(_S}Ta&Rv53{?2D z(shn~-1Gd{IrVK@=CDV(-9hRN=MY&??MeoBZ3ebB21kV>Ip$bQD_JBAhi95VG-|?k|x3mfx23D;|wJOm;q(S(f4{FIQ|G?~hkD*g=W^KQCHm5Np zvVU66I=9?~Ha)13yjUPUxl2+cBjHtwFW@^u)kAueCx(_XN*NRHS2o8_csazD&}{ zwoX?h_G&)MKZ|dQC?wGkgT4TD@L6VV4DD#y4pYZv0tI4w6k?!csTEA)&|tAgq(mJm z+D6j>Bum;B#g2-`j+bzXH?{$-4BtSp*%;saL(xgxB@sp<7+dWefjF1Yi?}H{oyS=s z8PskrlOE*~pun$CK@yGG*v71W)9AZ&qvZmvb5KwUC6ZzuCb`|R;$<|B(IYbvIAI|ZrX?3voxoTQ(CO_oB z&$B(wOMLJys6fAQdtvw2E3503C+n4`>y>Buf~eMjg4pLN1@nxO+i4}Zy)FwU0LbgB zSlr2!IbO=^OPdqhIy-c}Z%< z{CFKr#xKKRYT}pmuf=6u%Gt=%UXRD*v=;TwNfsyoLY@IelF}63DlQl}>ZRH^*TH>6 z_Tm6Id`T`sd67|A!_Y-clzQTpifI&`dx@U7$dk_M=ZMp*(4Eyy!nx?!+7y<9hd3GZ z;=z>+1hrZ?Sgf4hfke?y#jxJDA)uD|D(fr?&L$~m_n^Isbva36$|)ko>X=uT#l?GQ zI?3Q5V<5ys;T?b|<`4#7nR7TgPM>NlbtiQ1dk!m${M1Lo3w>n}p)4$tU6 zRx0whdq(e`)87~L_uD$!w=C1&75ckIf1l9br}Xz3{e6yqUXaS!y1Kl=*e)S^z3mP< z&62%PBUe3jyW_CsW0RVL4kKg%eIGK8)XLr>2Z!iD5{}UI?{0(58Zf~p*39@;Ax(bB zw~A&Pr+Ck%rO$K`{U7jrzt74dL^G_kuUh-N9qibbEWDvlP$pk#R#AtlV2vVE^ zb{PX+hKwL^ON#R#I@zfM;fAsMBP1m&6ZD+I__>0^&?Bh)C8!$&$Fh5%|E2k9D0WUr zIwHF#Hp0Lm{{oXEOd7cbjiOEzUt?5g7T6v{U2?=s)I`UbLA$AGxwa4A{IYxSnnicm zu665$tAUI`ChjF+SBc@}csyKRTDrNpX(A0vMi)!s+nO$2413MXalcn*rzLjn~96jt1ByTKCdA) ze0#h_WJCQ`5S563^W0X@QJ}GP^csJ$3-c(sMk#>fRQD*Ho@|H)Wpl;Ot4M)r6Bx5B z7XE8Am}v;yf3Si#;t$K&!1)c|--yj}!?aE3Z5@>!!es+2M|Xu!as z9&~Or8MyV-XGEO>42m-)B%@~_H>BP&?Vm^Cc!K7jc{pbv9Cb1Sa8kY*cN7DQE(jfm z4fscHn8QeFlac}pm@2A>YIG+;E3 z%Fu(d&XX3wEUVWGz?Nk=~tP_y)PaoO%{g|th`tR=l zARrml|0gCjp&1IA{|}tnrt)NvYg!h@wkuj!$Cb%hAHf79hsTKF8kUrNtoc}Ezbe$2 z-vy_ZqzdXeo4(3^3ht4HjYTXb$s`K2lDJi{TNJw{10AdfLyBi1wa#!7NDo0*V3b}P zI?$bTl+PodZskMVI0w#NaWVN44vq#YTw#^h=PLNqydyfhJ~vl6{%L1#FN?b)e6x45 zy`6gzU|il*UccJgdVTCIuGD-PEWnxhLr_7Y+=j31Ubkinnt6q?MS?}}GCGUHL4$ua zR!v0>#f@#~_qGrWuMiS5Erj1~p%Q8e>1=})AiL@B;7db#@K-tMzlW0*y~2*R_BV|X zRC=?u{kN^xJDXCt^!J^kV>oCx%f;O;mri!~caBfC_TOxl%cWu1xdMXJ9!1wNDI->z zaE?F6BmBn*4*AJw5IJ7vCGSG*<9{9h)Ry+XfsOx(u3r|S{sj5y0OOrx6sYFv&6a^5 z2XFWGw)bCda^&X!0*bKKyrr}434FrQg@{Cfw7S5N_dvRn%~AQd@(nu5d{R3vG4jH@ zZDyvE09k$VPQ&cXoEAbDW>!G=AAGykQG3>YQNq){IPxf z_Q&HBbvmbAamr53iD#jEitO##Rr z(|lz4iB3#Lqy-kr&c=cB!Qnut`QFySYg!DxEx@YVDB&1~t7yzZEZ$Mkd4_@~#nncs z&vDd2OMg)$V-Zq&ibB?g%S9Di^P)-3Zf*w)P%=cjlH={eTC>y}<2~u9jVj?@w28md z@H{fVaW3E)&{3Rz>N@^;3p+&n4 zj}?YXh~C0`1o+~auM-7>xo%6z%~nOeIR*6HHW?W3T52hHk{MsCY+$uo6$0LpCmR8M zb4s_$0>PaT3t?MoIB&7Wd0ZBCCxIK_s%^h~vvu-QiT(i-|8W~=MQ4ak?w{!Q&h}4- zn`Kn@>VwxuJ5YuqH(kI95j1w>&8ys-SMnzFLZ0pc@^6-VgP@Vh6O0zTSw^a=572QI zp5U#yKKeWSzP24a+TSeG<&6A3-gzlarBPR(;Tf|DRBZe3;MMNyHvMi$@TpHy=pC9E zlq*ml;|Q*#OTWHbT7q{dQudNFUpc(OF8|!$J>K6s z+5Tzs*&2BW{s4FcUp2D>-oC(gA#PiF&VHQsF-iwzK*AtEgNvp#^|#$Oo6n!m8A#8c z7eWFC?>n~D@>$&K@kTa2G(DnpHf!vnzXHtdbPt!)lxlqp0M9O{qpZ0>Su7jNzu zbeXE@WUQMJsSl4C&Q$O|bcN)A-}MYAjVyD8v4_&TLFaOmaAbT^gSdSx&D+&634eoE z$e^E}$9T2axg%4DZbC-|W>C5y3%$$LV;s zP%C{T7GmcXW&JU_>sSj#YyRN4sTNH9=4l1#BSyRZxbg|jz$))F%}qs$mc1m8?+Vus zZ>kxDbIKI82PACmlb5TnxKzQ@%E#4DCVyYiGS3{0mW9zUMKp?gR+!iog4Kye_=1-J zWe?0_%7MgE0m0$s5sq*cwXo-;!0e>fI z228Tnk5H{#S+3I#Ao8PgLR6=&9_UUWE}?{cr-?ENO3|=-%jJ>;i?f9(HWi7~NWUa3 z3SPQip*IJGrE*koXRw6^k~=o2HmY@Fb`p@X=`y@dI`m$tF5^ zp%VfMn`Tquh?!oJP;FcEp4xifYQdp(|9-3SUzjIqz13Q*ab)O4ekFd%Sc|+s3bvSE z;K-G3QAbLXg9CLT$ot@tF-p$x zEc$JdjKwl;OhkrUQ_%+sl|QgKLnk2-0YP;*+hxGh_&U;k%dV{r1c;4~QDRD)CE*T{ zz5GRtw!Tft_Djx~S4{h*wG3s*b%z<GRxocRhPP`~8_W{0H?Z(G zDW_*5YsDY|_Gd8ZpJ7_D^MIPg+mkL`o>VJU(iYkJ`4;QkBow89bwhT2*6R<`bL3i% z$>=A-tm+I9n<&9sTY+8eFSgKwR#II_r!dM|=Hu#9)y(m8~)LZ&Xt5sUM zpx?j3gVhSx#+QFtqQ@-^>JC3Yv|2T{1gtmxJWKTngJ}(xmM-Y*I7aarkJ&`SW5Jhp zcXZc=$q=eMZYohNX1qfI!_9q-`4xF&eN6YStGz3L=dEoR?cRfyN! z`!e@{CYQo_uEchdD1@A0#xCTd?@;&P997J~ft1ZmiynP;KO zdUNm@Jw`OvYV0;PK*KE$ob8S?Z%9IIkBz=b4Mn$51&F}mEX1_!J;`0HF(1!u7#oWB zPuIvsm|+;?PtM#B>762Gg>V;OXnv#sCQb=l5z*V9ncO%wloUn2V46)b#sBtr?d>5nz0Cpnlu;=Wp!Q68!dmb{bNs) zp}l`PqaBK{ZHCT!j+^2+1@f-(pt=iBDEOHbK2t7peoh|et z#Je^!{l&y$5{Vnv8D`dcTEbx_VQ89aGwlTblYln)7G0Je8iLB4Cq2L!CaEkL_7jZ6 z8IRD&2lEI48}l}0uOB#fQN4oE)}t;O-AXl@mu!D&W=tR+=pA$o^XxWF2i(;y=a;pF5Ia0=@JR2?MVTqOjQi|qLnwLS%5r`E-2u6*HO<}H4#Zj zDw7@R$cq~!v{lzlq%Nd$1eByj2R>ogoFn2nz{<|#vF9*aE|KlKXc|smAr2E_S8eD` z=V=X@Bj&!Ph(1&sI95nq{?6}mhy`zUKQFV525^iLbN z+1fwiV39`0i}2;%rco<6&R%8V!(p~kEsMds ze+r<}8?M!R7G*z_j2j@nN$Bp>_02{hkc@dcvKy1 zX(r>d&`9j9L_?vwCqxK|58#r{X;bo10;w#2!r3u3WJAi@xBU=9T8LdZmzSSEFQfn( zNy0B)DFUrTGWM3`CaQ|hWM-uS9g_YTQH6xb;basQZE}s7@xbO5hZ-m7WOkFnZa3iU zu6HG>cV2sZVz^|1wJ?B4ZMyx&_;VnSLT7k_*{hceS= zh*2g?GwY69r)X1v3go$h%I(R3Cm??dvy$N(GJ3}HsbxS-)Xbo0eRFM)0FjGX!o7b) zeLFr3B48I0@yO&MAv0dOoXKimFpP@=}GiqzCLdctD7X_|uj zD0PXMlVqllt#%23F;Pbkbv9?v&nt`&WRm(C2!I?ZvOE|-NOdb5YU_?75JjkW9Y;NL z#>4WzZ~foaeCyZNUs{W;g;uTgvGu8S-`Z$>*ZRKoL#x^fT5}&3?-${}a(VV5>e{u+ zk6EKu+0welqKSWfI2(T1B2O`0!DZ=wHf7mhUk0NihsuxBk{37s@Xn-t3B(d3C>L%$ z3G2q3drpU4wp%l+?47bdrL9?8kc<3NcNy)a!j1O-&@R%cZk1(93pRzF`$7z|dx9a9 zU2I3U13m%J4fQ=9{a6iI?6(6BP6sTe7|A1(JDNmdBrP{F+xsuss|)j@od?2^B4fui25fj5P<$x4Il1 zATn;NjdkUyDxEXGOx@LVSEKup^z1xqb;Ac99-#>Vd%LB!pln+HY6n0 zhU@e$Ar1Vd;g=t((-jiT%d#6q-GH5Ah!R-b6s~R151lY=$wsXy!XmNM`~NXAv8su0 z3eky5281NVLeHX{4*P!u=J{rve6&1_j<&L6(OLdi;%dpgKofI!()k}8kb+O~ z(|t&8DDr~7+m|ot@k@RHE9Lm3EWsP+XSphinRP6Ia;FRW&`lxZ=`(4vR(?D6z__j_ z1`IxY9GF>~BER@zuuQBg{3mx|Uve>M!fIWR-8H%ipye_KkS^t#D!L9VO97ky1@TwU z69u+O?v$UzE*c-KE2ZNbJh6xovog}iAyC>e&5~o&xq|w`ca6p%X|SQ0lNje^4BYOB zZ4sRkekW*dIy~oNT`cJaGco%L$J~Qb8*j`LVN4$CV+Xwl#$sy$e8+`!r7E;JkAcR z`*+{%9KI@57EAcy-H5BvJT{8WqJv`jMxww1le%Zxda9;-E^Ko8*$j%TrN#9Br>+xZFDPkUNCd! zmP8k9wjbIR!&cYy7PmcG&zit>q@7C!XPc9%F|PUw0~ zd8cqgG<182qvly8_Zhl5C=e}4wN0ApHs^Ts3?F<)9i<1p)g&$cz5$jk*wL>47IW7hSX6cFfxkMTo7CxtNEMak$T z3V<2#C~BWY7xAETzFCE{e|~;G_;Kg;?m@7(`{T*s;a*is0d6>D(0Rj@pdy%1RMY)A z-D+Bvq`XpJs@V1db}CxxZqQSLug~f&48iN4p3({iykh6^+!UlHRtJusTc#(W8b=2e z_-^iNnfXz6sqA$QJ?*(O>r@E=z@D!=eVtNdnC&<=V&lu^82}A#kXc<5^FV?+Xr77e zikfm+^Dt!1pl8IPWv=kZ1->oUk@%S+<-dzk@8U|}NTi4KG8~zh6LFO0V);q&u6U3Z zmlyFU+m(d7^O$bnF6(?oHww$^y-$8MxS2LaPLMT)H-85*elEAXu)D3=8u?%eS~p}5FuHQPLYn$CT?!tcncw8sF~Ew1-9piZY`lW;t^Ix zobQ^H=)kKrkkEzBHKN=tBD3i|!Rq=z1P!v47mI>b3X7kvV*)5)#Q@z-mDHQN2ZM?k zntiHDpNdo8D85K3&3Kh2m#vbg6@{-D432mZV7JOE!}xlC_CgoJzkrE89D02jZcQFLn2!+$K!2| zvn#oRHd0XU38|BypyX!GOoG@4-2;`b&AB4;x=xrDRkpVlxW~La%oV2n1EV5pR_34O z+#2B9FCV%?{O0E74EMsmFAi?eOQLqQIm$^iXNa49AhTv4=n(X`AiRBmyRJ58evTr3 zpuf!)p-0-oZ3>$Z4(@E6Yce7b4wj2y0wwpf6ZXkh5-MT_%2r!dp*}S;rN^Lr3v_eN z=>pBdkz6pgnn814nX;Z;UUJjA*YIn#$8I%89kZV8jCd>ozFvO`JW289!vwzJ%aQQm zKIjI_3Jy5wz*QMulyyqT!A@BUbTeg}10;t8e=PSG#(mDCDw~VQDq~$yUfTIEtLz$KsB*!uUnuY!v8Z!* zaT5;~fub(<0c~#R+wf*>mA-VMi%!SL81ur6ldHpk!WqhrQb$gx6ageWqvYvm?h~g@nn%G?kVve7 zdWjR12t`B>+nZ4`p#1X{rE61tyeJQs;zOJKmQcqz5WgY57eNb3$tL;)c=gUG5o-bE z(uI>Z;WSd#LI6ppxN|nlpDOk8t*RctDq6B}%-B1qLhaj!j^@Qyl>la54QXvkdg9+_ zm*cB~@BgwIeD_^@@1#vv1}3^3s$2ZHKCBT9Oc-dRdDX7fHI0A^21Im9!oijqq&b7O zb`N$>M4Zy7gGmqXTV#5hE(j;iEo@tHO6ZUwK@%2_to(Te8Cb4kE-+kTit?zpiR8`L zEa?o$QD{|J|4!3nVR`HN-#uF*RXdaRr%##gjUcy$>Mm%_WAV7@v_Sn0_=o0mdQV-b z(5u`iA2r*)($ovqRkGGu^Kd+xf5H4bK7oJx2#!vf`GPW~ik`JzW_8bBWtGoUFO15X_YohlOA&{a#S6GA%%#ah8a)ssdQizt zOGe_E;psf>Bz>%N1al10p*Ef&hb1kSL?;=JZqOuj0+Uk`Qztl^+v(*fx*cOsJN|~p zRoc>86td8bV@R&5a+d~!AWfREYaBAPS;}~yX5=~7_moEkvnXYL@}-SCYzE@BuxFIL6cQ*5tleX!a8x>U3{24Q5jHV28vNm>+=-y`#z3{#$d z_m}11JA9;<7Zj|NfweIcRIn1P25Z5S(j5BRB5aJXYKs6qJLyQv757D%H8ZXGmPN!C zU}7sUn7A0!OyB7wAc@P*H%ihLXAxii?k`WV(+&4(Q}aDD7`f1N5qf+xLe=}I%`5mQ zq?Rfo8T@OgK)#>8nS^c$($*A>&&C4(tTB2a#Q&A!^!l3_t5>LTMC@USbRzW-X;hP-X<(!{{LJ z|7KZ=QPN9#SFHwBT&(KUP@i)T_q8bW-BJb4B?{*D(Qi`Te*%!{r2usu)pP6n`BVhY z#{c#`H+`cSszVC{Qo%z@>@r=-q$2ZcQ;m?VK0HE|jPSr?VA`XGiS7|>AMWpO9lShl zvYj3IZ=g?y_1+*(n^ZZIp|v%`@}@A_j^er02q|Ns7p}{(#50y0Q0J>szTbX4CBCh} zpX7WUpQn^hU1C)HUpCaD3|M`FURiOBoG2N()>B1;cwnKd03R)LQSEy+(MzO3;z5E% zOza0AuIrs+^JQRMHU5PdSw|}ur>eG&l2w6gq!oO3X?FOpzlY1VC;js}Bi;7jzRj6f`k zVP^TtT=v7c;)zl5Izpsc!sq9CIzy@bQ+E&Y9R@!;TR8( zF|*JT)6FEakhEGzh4mq_(gF@=7+aN?;Fl&2w*i2ykgF($!<>*!j!7*u>Ic<}P6y-M zR7;tOnYIp|fNZ7$t2pv83I1vn;;BQox7ly1yQy1{uoXVs8lfcf5sjoAY10yf;(3}@F z>#l63O6;lGnjiITh^cz1!3QQMdEgwq37sMa2nWfLKq(}Jiq%=4t;~AHub6@(z`NfG zQ+&kZkVLNK*uy4%zgIGbP_AUIEEIQghS``%ON5!H9QswPuE-^6b|0#h->Yb6`+!*? z7aO9Bjp^-anOk!%kKUAXW>31Z>|XspDy+tp*y;K)Q8kol-Ze<`J;_8Uo?5_3fX3t5s;MW%ODx(cXUT{a+Eo# z+F0UU0Dh~NTqKi}6~yIcFD%omnhl?kiB+ZHjJgSD1M318O2^XlZW@-syoDE=m?|K1 z$@(~(e1U>6T2;(V(5hxHz?>ojJ=gW>=5y@s84i@t#@41bCWUg%xv>CSK%~FITn}@) zqpN&$r{vR#xQ@*S75912C|l=zwakb(V&z{<<8^V~#|}HrbXLi_F$lNvA2Ta1 z2gGb{I_ltSI2PH^1p~%nqOqIsE)A}tXo&i1m>NnVBY7w=*^1N?+snz2Ldl{L5UOl5 z4~a%_b1+aEAYkdJA2PQkyHRx3aIo{&VGM_IFT9Z8tHM8sUt3e>X8$Y=yLB-;{v zr>uUeWsDiYIao*tHq4(pHKjQW@5zyFn2X5v+c6Ttap@; znWQ;c$%b?4AiHD6OFT#;p)=nKJ=_5jb|mso{v451*v1#)9Pif}NtG|q(CD1Z-{}-G zBj7QX$VO7fK<6}c0@evlMbGu~&F+qkV&g0$FtqYDFsxY~nm8;0An_T3Z$pZe1P!^r z$WbBg&P2jdu-FN<+!5gW)90pptP@L}fkAeeIx z6YVmx^2ksUb{guH;Wh<%ePV76T#Ev*jor?>iLRz2ij-v+5 zo<;C`x({65yky`TbQ{{^`NZj&^ErU^m{P$Zsb)Yr2B^wfIN6@;RlYD)a`qXq$2odF z$~}y8sbi7EoRP&hI1Kia-!&WN45KrM(F#a>*Obz}8=q4oJ&`E*IxZ5=V-v5Nggmu5 zO)m|;*3Lk9l7vFcbUmeHi{WSRyXh_t>X4nl;_Y0qA@|p5y z+ILEIzWIipb~^MC$NUQrluLJpL;k$Ib!xpofA!)0^0yy;pm&HJ`1z0Unw!Ml;b(g5 zp~WrfQqB6vD;0oj5ibkWwAg;xN$4edvzn|Xwvmm%0>?KRc{7V?dAt?I#9nSH3i{~B zn#9W#Ax-UJS^xS^x~?A7XVLEN_`HQzzF~u3@wb)){{a zxpoj%L!&5>`D)W7BP=G;#`MYNJ+Zab7^?dI!~dQCb@Ah;jqkqyp{p1sNJ7d z-hZgNAXu>=sZ`3c3kWqW4w5Qf3=)w^6OE<#8#^(4-6#}O?!c*=Z=i%sl|Sv|Hh zydCyBoOPYun{6Ig(oRbnIG#%wl~Hu#jbllBW?IFgp3d|}b{>p-OQ)UiTzKOX)h2Em z8(Y_~$zCRluQ5IF*I!rVSF8E{*XD=C3OqTr!HV?gO*&V?B-<96_%w%}P7hRD5Jg># zpm>$4Ri6VeGmU!*MFB&%^-)aRGq6lzO>(YR`4OhPlL|jafw>J+=NGXy5?^-qDkhdm z(j|~umesI>=!SKI{w&)r7wz2%91y*nhO(!*82S1O_a=|gvu|aQ(b2B|9LCfaa)s0? z5~rEBI#8myw1--))$FCK6ICqJXC(Z^4mRg**HqyzxY8;uE-nT;M@NT8b*DFE<&c`t zX_%j8y>yDISX;)=a==azk|SI5KMuU49UM~iPRw8@CX6Xic5D3QsBL{mrw%Cuj4^~{ zQ;YG2gYHL5cbIw5+h*Pd18JgDC5Ws@8YdT&Jc^^ULgf-BUk$~Iz&RdFh_`eC0xX8n zKSPtIa3J9+$o&2?L}kSoPRbt8*)m81QjVvhtgFD+YRf1zvy-zq*at!s0j+%LmKTDknD_IP%fBhG84RC2 zoO^eMo3`3~xy%nK4h+1+jiT6ZPODxB z<_rz~EbX>0<8G8p(sp{;#`pjQB1-Yu{grcI%?Y2C(_`q|1ym7P6F+{6M%Cdd)3f|x zcuqJKmowD#YUK*DnZjk3v!fsu)7c<82)qx%s0nu6*xi-ExSi5_4mjG0ZJW}aT$E;0 zvpi>gBZ8o6aogz@$qtX$DEURoA0OziF=t{{PN()N+UPVt?o4^)K|<;0$Lh-_mDWqz z*#Dk1|DGp}AvFJq;sn-VKG;w;X5z&9;UWpxG*I`fdp(iehy@t0qPF{(akA&`)r@&+ zm9IhFN-R*7tE>a5l7eTm^25eMrM)Rd4 z-rUytC&uTWG=^E4E_pfKEhh4XG=4rfmX)$3L!?7F?|W$fjmf8!9VkGFT!WR&`WIVd z=Z_S}-R_GRuKztp{`VaDH#kTB&>8W$N5r3cLb&6cX7e=NM9f}cm9y$mc_h&qbsFCe zdaPlIrYTs^+z`v;Ce`2C9w+a}b!Pt=x`Gpt6&lUZKjq>AXsqu~InRF2ReaO%3MRaf zYl37W`2ZaI+D~^t+9OKUj=pIUK$nV;hep`BRQ(-RmV-_bMtPPyZVDtZE{i)13B7nV z5TrfpITr;IVZ2~>>SoQqja`{d0&Md>=o5Rj!Lh;Y)Dz`wmCBsUA+R3l?+@Rc>>eI` zXf~Vbmd;TWVX@vH?Khm)mP$vo$^pk>GehAc+Q}PQ0uW+X>#9ICP`6UfL`~-y z9>}0cCnl3TQhd_vW7DOD@!e3a(OaiWXYpWZ)UVcn>X~jHlaQ=&Fc*N#U7`g6kje9E zO;l;94F;5kA4mJp$K4_)H&N=>mAoV)?RDM6$IkY)M7>4bA{uwnh`P<-a4cz#CH5t^ zHBO`6IptyGauUi1I#e!NO9|{&`jWMjZLoc~{|1_Fh;JH}I6i!Pw7o+!TiRAjKG)KM zErD{gVlL77q~y?aWWpg4Jt?j_X;r(NhZabSiRJ}^0G8j7AfPB=j&__H zXNzC2DAsjspm;jOL@u4iOi^@&NpBnvd$Rbr&0MQ2{wFDsjfTaQ<8kRqx%GU zttfX3_Mh}xx$V|z6Ap5*0B~|~n#j{+Gg>ltr4FRT<=P(!r<6el#(rg4d7n_C1~}mz z9eL|iW9WOa5K4vwkb9$pScD@5%SxDUJUh?sSRbfXu|-~e*hI+!7ID#L&y%X#iobNJ z!^RXiDZnq$_QbG7nag-CRL4@iq*}NEHIU+$ky8zoqI3Oz>*)3I2O^|f>Mck_4R?Wd z4t0$(ND8T=^yd%kI*G`ldoB?BQGdRT-wG8ILqNAvZu^)U<_dJlr5!wV83GfBOrCNTwhAksSQo!ky;2ls zWIj@HaHgq7;vJ31#%VZ;uYpWlL@8&qD`AJxQ$)hLR@I3mCP^pw2TB9zokJNuB6Rw5 zjYM_!3ujq_nSR+cYqa3qgX5E}y*=k-1#Fgg7H!iY8F_P*siusQw>C0|oLSIO3o%I) z3HB^1iG?jsl|ZOsgRRrfuT$VGo}=r=^bxMtCO=PBeB? zRfFY0@m)znw+&ocXjj&4)<4aewdBLm@J2LuxPN%32p`UEl+0nnyuDf~x?^|%m%QH0 zKqUC)Gc>{$!3UD$?j20EWm`}tf*Mp2H4_>^)v1U_T4)j@%J~nZLL=Q5o`ZB80g};) zBpf z9Dzl*sNHGkpaYJnW@^$}xO}r(2Bb;vT7{)<4~j3W)f{+Q|M-`E;i2>YgpK7I%u$l? zDOFLPXJ*g>$$)Q+fM(wYM?0@~-hD|EPppk#U~^A;kpo7#Z7s``2)3r8i3lp^A<#)BLV;$JA#Tlm zL-yia!xT2Oh#Z(qSpwh$TH#ul>+PIaY1#@=rx$9dSldaXMkE==3pnN=VNNs?y5l~z zF=cHKT$XnT0)3_1e1?IiLP$7-q`{+v?9HnC1y69X!*k%lUg@Bne1obyh-d6?$$BVP z@F+qt4TgKPv$wN#3|-acCG@3WI{3+2G$wI6-|YK>3D7t=#F>j_Fl4Td z;Evu0A3S77q9G52%M_Z!3^vT7hKN(Wvc>tFq)A&1$YYk67BPMd07E_o$8TT3IZgn8 zoQ~pdr1~gMqUIa>24WpFjs~erQch5vP1~V6E_YtsH3Hd?cleo3!GQ-_DugblMgtc+ z*nWF-v~zIse*I|Y@4M*n`F?%t_0ES6h3zTY=w#^mLy+E+0?P$^n-0co;^)+$5t!0fw5=i*t>OVm&|wvUmYgaxSG6w9i85{EAeiBj z?n)WXLwq7!k`$q&VY(oqVP10;r@Bq+CE6Dm>)l|1wE)~yO%r$;I#<_Q7oq@FOzy2` zP#v(J+?Y7(h*g?^qy$7Djs_jq-xtO(rT?LD?oB9cM`ETWKa>)4c&*cLq_;vK3Uh4? zCo~9tjtAZ3CJnS8zMI(x3U*1IF!rCeE6lqPGP_D3XKr~>QR`XEuR5JC&a%4~VsD$QvmKet=3{2XOg z%=Y=HGB=*+U!wOZba5vwE1tr+L0;^Vewvj@R(FLS61_WrTS>CsrUq{G1KB#=4T32h zMnY`+%ex^1ofGUGVT4*yH@aII+V1wqxrTfb@eu_sNjLQdo7Lgc8G?0u6%Tn(<}8^a z?Pi0+a8pifnEBvmH0!YU#aSn?X3oRkb}{GZZ(NkjQX)v~6S8hfrGWbRl5#cUU5uCL zUW`t&6dIXxhOdz`V#GMTN2kx+@EML%24J(Dk-aSc$^n!EFvE%PJf@Re>Qwn)MlfF<;g=3LAA*3doiJ9ttd;z7^!}?37&&xg|V4P)DwLjv#@SQ{j@Y*cL8xk)g zj9GcQH=eO*P`}^sEKPbyE0IUDG%vsx*!9y+mluQ(aCp-_^#~1x-=mWBo(C%rY-4yf z?!Ml{8qiRy>>ISrD!X3LhHrFX zy%;58s}WPin20+Q>@{U=JJH6mKTv@I$2cpZL%Oz7%!)@gra6^V;}s?PlFFUq6`NCp zNpbAm3|WDONU`5R2F}^o-2+C(I)nT-+z@<=HMToMxAQ19Hw&>CVc65a9tB1bJC~0m z>;$3ptl88i&!^BF+yL*gSQ|W|8#9KbM>uVE^1;G(i4aH!hyXnp%DAW-g;A89PG$P~ zK&0Y7VI0L#y%6gE(Lj5G2@7M){?0kd3M1{+W`|aAt&t?<8D~0sOdN$wOssdV=@uF% zy`%hW#SU15?9O$Z33gafN;(&xq{yBZO=<=}fx+Anw1q4%1_|jF-p;BPg~C&f5e_M+ zwhms?pSPIhWpBH^wYP^K+b6%gq2JqwdwW|a^mTvd_!vqZE3=hoFLkU)l0H(Hk_xx* z4bYHJEu10vl1c2O|D@<>bAGgW*!>I1u4D~)Bp&c2wnX}cFBw8#K;YF%_96U` zDHgvje;|c+cv269qm2EX$|jz0lS^cqk#yviIw$DJ^J#Jpj0NaKnvq_@Za*Giyz9+E zhcARk;jr~PPOB4CS6EX7?0bXZhCt^Xi`BM$`4$i-QGi$+>kZ3rbOtWYUZ2zY=dsps z0Fko5iT2I1J57+@uQzRsMmO%a4>qXU83N*_-%C{%_p0S8)7zqc(OhNvMN|n6_nvl# zN>NudB6!N)bLM4>j)bgXtBnqxQhfH}ZYnvTV$@S-x?OUIWHaW3lM?Uwj*J8F<`MOl zW0Loq7O~_hB@f9VysKb%*Z5QZ8P97M_MYK*Z7gK>s$jibdH|uky-b9YUSnl zEsmEI8kd~TXtAc?+b2xnMY$kzH*8*#CCo)5=3j;#uFEAx-6oCvPb*Q)3IoMEN*fpo-XLn4dbb7ZirvuvJ zwHYJHwWf_L?01siZkjtWI)ackQ0%?d3^*+#l(_@7Xi>qERn{Pk0_)jR)LBDurq3Yl zQ1Z`6@6s_w)5bb+ItI}PZ=@$gq*H7EwC+GHZ1_A_ipHI#UbmShO^mSfrEU9*+d9pF zt$NKfEpT_ram0~LL>r57*SVE$(ji9MRi5TzWdLzv`1$;?K>+eNluB2d@1H$?@$H9u z^Lyp}a^u?%SuKA#tFf&Is`{qw-(6U#)q~Ec7r__40mV@+yub^a0Wfct2^yk%U9;>+ z5{qBbT2Ui`!d7s(Bs~AblcU&8BEy#nr{J+=@@yJcruQZ}woG5l)IY;K%8eO@;T(z) zYI;dCXd?QtP-E{SlXHO}ZM0Da3>G3|E972b9h}s%ZiX8974ym-|FpBWN1R0NCEc*V z(C_bc#nc&-{V?bZz_`EZC7w&w)R>QD_F*gQ3^TluEAI%<}S#*`!u5{d3Z)< z1kEg%3iszs!ChK*9DYIxT&w(m-je-z{LGcpJ zCdm_0KuYWzin`g4tg0#(AJ{vbuvzP!MlG}I0!0vfSDK@qafC{vEfw4{`hcRSaNU~p z4CB7p4CUuF3E5i?yy=x30*miktyZw~p)+g+tUjBA4;ntf*Wj5B@oijS2wV&%NWp(i zS+@v=w$-UA!_Q*XZv&Nd8I9epUdT#dO|cYa$3QnYrFswGMF?V>FZW=5N8sW0G zS+8I6O#oj zTgjP4_%@o~gRb zhf;Q+&r2UL;@~{oFe$qu`dCDFO57`za-mMfX!|j7R}VWv7lOBb86(nM9!W zA5NKUgNCa2bNMC{?xE0h0o6Ux?O3m^#7>hP{!~EYkm`7}nr@dX_D7&MJ>Ko{e}hRx z#)f06O+?n(LBfpSvrY6vM}fbs(J`hQLuib1QLLd8guiAs+F*`8&pEd~g7zeZyi@g? zWg;Z~QWmx*V_Gb$%1)Dk%~9UhEdJynXj4*$`7PyDO!7lBJ~rVbOqEAXr+YpMKiInr z#^>r6_HBlB21ksYX{1SMDUNqww7UGOd$wipJJxDnG&O zkVCRLCh0(E(Dbavqoj*WViR zg(|bkXst;kK$9Yd=jUklc_T7;v)e;)d0H#vjVW`n)NG<09xMnR_wMRqVn?aM(TPEl z0&tiX0GlQl%2hl^Ii<@Wi0&}am$fcpUe;M1RtK1cnUzw6KGxOzNx51>ipT}tIk+%= zxiNV*igwrJhY&H_A3yWmF_7IWBON>Cf-ZE;rr;nQywN{MvT~2KSuD(;eg+x;nrY~- zU%PI64Qx8wXT;h$<$?dyrUf$5f~@fu!(u~aUINGdz{x0^ZBy2_I(31$f`QtqTAy&# zYF=AI$+PG@u_#PSJ(epnGN6mBk|R|uN6zle;s3m|O8G#aZml>7f(NT`tSg+Df+|Rg z3VEZ2%D#nNc2)rK3+kK*HBvv-`~XPf$$n1ariE~w+eUXOd`Xn-IHXa-lP=lDb)_(9 z4jbH3N|mt@`YZCSY>p;3$n@OI7}FYD+9o|T4V%P=i%77Vp~*OCTQ&(7vpM_%?+nXq zb*-PdQKqLboq2mdckZ-Q;Y@iGB)i2*T_QXz`=sS%WE{OQI-9N>yDo?~7X~{9Mq5)* zqM^=RaM~LLjr6?An!UP4qasM~t|}h$Fy|MSV>xGn#I)<62}UoIj1*r5!7*$5Spf@e z7)La8TN{yML(n*{D;y3!9`@i<6?Eu3IO^l)mM+Q)cFW6{V!rC>xH-pM?|sGC%!p!`Pg3I1QpnHA`EFY)`r%{*5DAB}`BFrb zm??G7VOOLC^`H74=K^nKsf$)~_DgoJ;6V1nJL_-W;isG!H zGCUGXJ2Pvhn3Wf%tfN0L%}!3WOpOdIGeT3bSPLSYB(8Zr?<8H#8n{(o2a?@_nYysd zs2+_{a?hFbmz;$tFKf&6UBt02Z8d-MxLv?A#5NyM23Qy6W{3F{!K-l1r>(QUnwga> zOwIG~fLj$)-F#<-qE7?o3NBVNHtqkzHmqE#@Rm#A@K4e3tFB2pSrr-vO*m{QbT5pch|7o&~j}Y`~*m4KT$J2_eX0%FWO)>cZhRCVnlWqC^S| zT@l_cZ}kPCBb@&^K=<1U4FSQna{xP5kK0)C2f z`D~qrx>hOz`ATv;f#gY*`*{vTtQY?-xw4F{A*nbr(_m9w7HNiwgLQnAjT%Upb}{tw zw|C0$dL zjx(LKR>D@$`^xlv+J17K+Q{ASQheHSW}cFb%lLEgP-R^Pi92?_%q>92+1SY8FvMNZ zl_W77iC%VO@+!^NsuqQ+m99I`We_>mKxDQ4kkqM?g8>65!|zj&(29kzYz3%te$GDGuf~C`7!`tbw{PNzp;G89CERCe z;0R_ey7I@P{ZFGn7nKXSsb+N}x!;}qRYqjao>bZWD_nhM0M1V3Z=ZaXsn1M{21T68 zH5^wLsOG2_M znc$Wt>4=mwDlSv#8nOrPYB(|kfOp;D;O-{8Q$EDyvFi?3l7+ZfS4O2~b$U3ibzhzn z?rq)W;pPonlw7&0I4LQm3^Qv0;%l$G2XzJ?;>mn2P(q>Q`w^v; zlu{rRX7pNK-13K{Jefv@;)%6}j%5_IIkhbcvN_dlu3fiOP|%(s3b||jN2&Lm(Pp%G z*zhb(p1-V)H;;EWo43ny?qB**|BP=X5#ju>8f-tDfmY2LXbtjr-Q|oeEGy{9Sffif zY^dX%7()jS=b^8;n{a3(*My?CI_Oo|9yl<``0yM1iMGkZ(~KtrshTxR`W$yST}{vK zS|1h|UMrX1rr>?4!>R&SYJMCc!9h@kJydM^j;t)zu7pvv3e6*lG9XC0V zB!CD58@G_b1SA)Vy?3@h(@ehmcWsZWS}B{yrrYp%)jXylz>|+_jY0CsKBkL7bKq4x z0C?8nNe5ih`(MMx?^})kLYINB+r%pg1ny{&@1H~ysn`i}jl-c{)I0Z67!=TngZ&JN zxacKkAZzj5!LWvw_S)XSIK3Hy73dV06$*PKsdp*8GGBT~vVedaD_C!dNXerrHaYZ$ zVY=pTMM-0zFTGp_j!%5E!{$YC+M&F+q|MWyer|>YnR4J|2Ab5?B+Vd#o|%^B08K~p z6c(>lxPi(?`uuckzMZh~&YN(QI(kJaEHUeyF!p*u0lhv;(9XpK=gRiX&QMXd5<<`K zgWPy*Elf?bwCGM|LpKU!{3nS{RvRaz6m3)Q)xQ5PD|Bsa$4z(jacn-|+Iaot#q zjp{Aq4OLP)Z$J;!>-gZ#hdnE-?oR{%9E?$`|pD)&l$rq3I&g1M7N#ZgnYS&F5Q?d_e;8*9rB22 zTnFV~Aq%KhDVrs8R_~;mfk7#EytfmAG^o{oXaOZkytTeo4=xX|Vp(t^*O% z&;yr|36jd~MqLw`buMGw?sv=^p8qOOel58HfoC`clgykD8TLVXBZX7$c<1FOoO;x4 zEdA*A;X zBxD8>kDYgK4v$Wbq5T3{?o194&2qIEP!;owS2IJyPzf}u8~Pbc`zGO&D7Hb zw-(-iXueF!9rit z+u6n&Q*l#iC>^2eL4{%S6nU%ZoK<$DPNu#`9$YYQa&{GV2<6Nx%r5~1_9o)X7VGCX zpp?dU_Tt&zM#$0vob@b!@%SV1OU^*4TDTFsa|2DbQrNv3(O@!&f1AYTcN)!&F|a8; zu9&U>h4yyiy`!*4ctPVTSPQJ z1+wPoc-s$$LtNjpXnYe{>75Nx5ea0=Hv?q-(eD&l|8zW>fFOxNJcyW>L*z0X1&d^o z2G1zT<6_wDV*0F&(kBc7MQu~I!cxWxQ}wj7&tGR|9v&SG?&a3WRuE(6%(2j`mwS6D zIezaRtgT|dtK>~Y12DFUcsy%pbPP+}32mZ}VKhQxHDuBobU)eaR#QKi0aiy#Ha2u4 z06cZV73oB@sntzYBq!P)E_YdKkEd?w%pfd@(L0m9H`FGSuKJ_UMke+QX$d0Zn-FTb!o zWhfrI#xR-7?$muMecC7)Y-Ohm$xlmJVa|Ghy_m0I6h-JBFJV=H*od0p)zQulylDS? zc=Wfeqrp_uyw2j*8U zhXDAYnV#tm6kw8GW>a0>HOsT!bgI*P*<>~-FS@>vISM&1dJ;X4T}>-rwa}K=UU-wu z^+PkwXOoLSl8gY=OKtiGO4@@S#1wVD(ZkT{TvkA_yxZfeKwsedKghM>EvfOWDdlcBvwnb>mvWP3Z)bfZ%l zByF@Y1x}YHt5P_fo`Snp%~-T9!$m+oh)B1D7PNf$Ko^W&@jhuHV7fa-y+l{-NREiU4 znYu-p+~iyo#)vFw&cnEeTQ0B8Fp$LJ7vtS)LYbx$m;z*Pjfm*cRW9(wD;wA~z=>CR z{fn2h03P3v%S|^BrL|RLa)AfL2s-o1?>SK&1C&}(2Tp{t3dO3Wc_?`hQR0nWLJIPW zBthQilJiU~o&j&O$RZ>08YD;}#I%ITC{oFl5=wMv>&S4z&xdS zX1Y*rn}};T@k3;0!a*Sndx%cbV(6M1tK6V__vg-g4iKfdTsAMUl@Z=Z(Nr|{g35}k zA;Sq~%I_8D3*5zU)Y5PXEt!y(&M}<#^8uxdi!mFAyr%WackA}WGX*3C`LdbzmD>zK z?PwG*3=l-6DNHBxjCvXqf+s=g{v)$pQGtI~w9 zD;mi8jd<0}hG2l%k|L)BGZdH3Et(m|hQn0s`vkDVDNDUg!J7WJw$ z$KB%V4JOzt^_Au2kEOY}rC>K$`bZXsL6Fv)i**^YJQ~X9Z}2I`l%J})&)lV>Uf7#= zh63~XxaDwYq|DO;^>{VPdCDl}1H81bog_d^F*JDZVuJNAAVfH$D3Q3^G%yP)Wy-cx znLO~C%~EzUJUj-#`^PN}|JMrM?6iX20bs3(UGqTa@^KmIxBOC@lPr)jQY}NbM7iD$ z2W_1~RuAB{;Ts}Qca+iJZqq?31Mi?6=qbk5XRp z-e+h={vt^W%WE?OQ!bOdQtip6*4O=giNt>08NbG>!Ha2{2jITUVj49~#Xv+&jk)j& zN2tVbY6627!)E#>SRrmd^IWWcsg`5$YkS)p=U_F=^vi6XjWEUI^hj6vVQiL*#%71) z&KeUDgRDz#DR+hXR~R^XC=1ke(%BTn>|Jbh!;x5Q`&W%S_NuWWcv2RRHu7s>JySQ~ zi>W(~-2z00cxz+mIpxBR8zt2)2ic+gJSe_&1MN4Nx=5-vTSaDRQ~Tt+>P$u+EP0HW zXsVsMH=!QH@@b|OG7{R`eRCLauFzbC>^&wiEn5zElKLg?gYjq*o#rkVy*52DJlh*N z#{3E{Pn9kqe-y1REmco*AjBQZU*<}|ERpk4AND{z>_tK7jVRN&fW(Vz`y6RnreI(V zqOy288Nj*Gs8p6J9}D{OsbL=DlTXGILzV{d&TA`Zh)d6B0-jQe6h8jK+dg25sW0sQ zGbU(Cf!IH#SmD-ftrh= z0LJH69b~%kI0RvNJdQ{r?4!PJz2;#n@`hwpdP@1xbS$viC^eqLw!t0TT5KkmI65AT zF{8D4*fUS<&L~%O(GxsFj%%Qlo*6@4lqPPbkI|>PG;Xt$fwZ?@Gl8dFc z!ECo~*@Ki8u9)^vE^Glm8l!X5AyIod2&HtnoY9PRgKPi za5_aF95e#-I!!olyFWR&y-fy4t1K?ff2mP6EfJ~+wQ;pjcJgmhv^hyZHK824gK^vo zGGReV^O+cb7+`_pGLh+o7lyAX?Z(-Nsp^P6pfoVhI(i9qDY}JN^m7<6Cps`ig`i*# zb&7L=N>1!Lr;aeU8kpy`gl=EmAf240<9I9v@Yq!hm4X?m(fenVoFQ*0zSqql*oA2b zJ69AO8AE2E8qZJZ#y~h>IC(1qLwe0usxgL`nw<5b2D!L)DKNtTqqn1~a zU*7>oRD$Q?4@(_|GMOh;9LSGR@MAI=4cG!6cE%Z|y|#!+InMs;_@}n4w5B)%iF|=g z`Z3B{ZHhrv5ZE&CO%$l-ga1k|gSF-@X*Zw1rx>@;6+H}a*o()+ki+b@ zP$I>y{Iym7R7dftb4f5zLzxW5tYqZ~mlI5;4fFjnPC243qQ^NLDZtU8KpFO8VE7sr zLDhp=-K@%2)F8kpfiwpPhwayUhd;KD-~M=fQW6aSNfxcs1q_DQNNO(I+d9Rga*?!c zcmYWzSoyZG!893m?vJ|%?c<*|Z-*C8Ox`zs1|!0~c`}+jds2G&c582Y>v(5##gx)V zQf~im$2hUF_kMcQc>6B6!USY6qi+t6ci)M&iYYdt{TL_+#_;p9dlH=lAh7J)FW+pP z{6yMejNGumN$2=!ZjliQ+ybRi#&^7xb*;w4HnL%hlJdYtmvE*j`#N|@w3`MmaiI#s z8B^}Pmc%q}S)U*iY=yINqxB5OzBRd#Y$OXr&RIb!U?cUz&M48}h%VWv8r5uoiK-&c zeDE`B+c6{z?sM|!A^QQ%Er%VftJfzkq$JA2;wI`&L;?1Tro+oV+M=ubg82vngo*3( z8yb7HRP_WrAp%>L2d7IXao{+g3$@$j-Vo z_0f4y;5Vgvw3p;EkD}5Iu2MPWZ_q+vtd2^QYei}|ONw}>Js`_)D3gv?J84}pNZfCH zA1o~mxsR+wa}O%6WwdG^8zZonBnxQN^#xf|rR zrJmoqA#ZJ8vtEmo=h&1ssw>P(QlRn_rKeeGud;iG;+Bx_ONC|KdlQE$JYott77edW z(VE(3AG5k7QJ{=4kFmGbr?JG-1&Gxt0z?`CspG`x9K0gkJrW)Clpbadw}*fUak`6AZ%54sl5UH47IIA0W;L@pvlOnG*_4)u z4sW^!w*|h2AE6+clJJCzm%ROKThRMI*}5Wx1+^)(+E&c$HL3spS0MpRw{#a=rktKFAC!AW*i=l_5G*@>^lXc^i%N6}cmzJ$`$5Sh~&znu} zRYrNvWN+oS*6Bvj(vTGnKP3c`&Wd-1jZxfPnjD{XYgHOfDc@uME6jZ3bTWhKmHoeA zo<*-fmN7zYnm>H*s&t}U^47}i5(+P5ugS4TgQydwDadVJ7X@>&QbRV5f&X6Y-C%|2 z3OQSyWEGrgiRvWh94Y#266!*bum<1%Wfh7|8#c$*)KqktNCoKdR8(s!0{IsxB}Tq{ z+ZGAT%6(o#fIOuKRuk9KgybyPeBRD`aLbho&Kt*Gb80tn#W*a2q>iUVp>En)1fx!H zl!n|PD7GL*cNoQ8R77%OSfMYO;O1T~T>l;F(%K`cT1b?#F8XTuMG;ysSA++gXFrqo z+-)SE1l{D@O8Sww+@yhx$}5)lourox8Z1N;4^q%BYYT)8q6!@D6vYI|m<-REetRcYw%eJ5YiWHQnCzt`!(Dn+P?^G^f1o z5=}i9eYV%LMQ1OV51QA@u=ggkfHDKM>IK_S5shkE(o(P`QIqs+?0EwXNti)(c_5B?n4r4&4cu>$@k{f+VGU z1d9zPBY`(Wk$2rA1pm2bq$lrcq-eG0eE`_f!;r+pHUp?->HMx!F2;t@*itrAmKz#;w1k1Q;qZ==QGqZ#RSfCm7 z@SvTJI#>lL2Q5AahawdM&`Qltg?B^KZvD{2p}0$EcQ8#2FsqVdB{)vnluU*WFET=h zH`~boxSlbcXmpOzSs(_+B*jlsQBr79oCIzC@g@v+2#WVe7-(-{p)$sVM@t|+5*BVq zHKw~a9%GQC5?#q?8bYf)?E}Zcn$sHDPD`LbtA6i{k~D1~I#5@f+ktc)o+2&dH|8Im zZTw0)gpJhf@8EsZyl4j8>knK~qH36by655F;vl{azQMyU@?P;U=`mhg{5GMOr8dax zDZauLa;(JdbL2~TC(fZAKWpb01A1j#O?(=DOJIjvnPi%0C(01ZwC4VpSmm($3ZVd^OGp8m)J;|F*)qSfZ-UjnnLzphjEV`HIZ(Cpp7Zne7y~@mvJ9TjWB;S zNJ2^1aXvQ^8{Z!jI`ODLV8V-MULc-g*!tTN<(4nt)IC8?JK)$yeFDUxSmznwk^)Kk zXOe?}&qg%pKxYYzsGFmZg!c;ooNLztHyAlP*yD5(t0=SzPD>;(qeybX*@KY!(UhFv zly=;ZIyzJ&)Udnf#JoW$n713n4tH7=wS%5Q#|UMM3>n1*&f1Ce#%;Xb9fW{uZRei( zZnK)+BM-I+fA23g()%U-0w4I|{=!BC;qWWgxuaLLlek5fs2aIgu8AJm>vD!h#?!WyV;z`HK|cj{Imk_*8|rnN z&8?ELHQ``>Q}ih#fHF)t#ppOGPk|By)yhhB+S_fm5THyw$mC20Hq(UVyi$?^u_ts5 z?*f|-UO{PGko9a6GmhrmT;}dkd|B89Rmh=JK*S<0y+`3DK8sUF!9Ldj-Y+tv#NwCX zz0l*6q7lJLV$Tfs%}4$ca~U4*wSY67<=KcsEoRV=S+4!}a_l7xq6V8WX@>}_Z;<4<955ya>7x7hr29+x{eh0k@W{+sc-XyZe-x4kIrYQQ;V0W)hG zI7XU?I1Uh4rzVTHs>t9JL3jw_mKcm_Pt*ftx6nD9cAyJ|f@f5l8&&E>b)#8j3nOzd z#utNR6mdP$Ph&zI({TCMtoY##WPPDFeL$37M(Z%K-6R7Yw-OV+zi?NJn_ zDfA}lHqoRNl_zN=k^j-tfe9?F&uiAg zpHhXplqv5WK~uU>!0}EQ`V1Jk%ClRZ&TQxE7c%S4g3W;O;4wY5Uj@JlgqSaD!+E{& zSv|;zIfajM5Aqo4_%7Qbk4LI6ldfhj*h3N)@_9zeS^!S^-%ijH2?R^B!+1=AQBbLZ z3WVV0;j!e)?T&!-c`&>Lbt!YK6zh@&4%E^hAA|)Wxui#4HLNX491d(&6s0M{U_DtuL-W*!pa$_PEwRL%l#=uHHR+_Reyi z?s!?r$k}5^$;b9R`HOCQ=?*m?xbmKI;f*rngIC`EefQMv%l$6~rvL7{ox@iY#kHb^ zWI#oJj?Rdt`8vWBf2p%0*8Ovw9fRPrydAk=$J@~v=jVGo2EhPHK(@bUxI9APZO$i# zj3ty#W1zh}K)!_2J}t5}!6NJ+$yCPERIVcsR)b(qp`!yyij79cqcfTv>8!?AQq@&R z7nyj^7^qK8eof7^H%p64CBzqYXtz-hmTOMi`)TX%JMH70lbwUVQ#q-7d~&qAebU}KINk*S95x*ta`?K^4W?d~ z&)P-_{Rd%|qro*4aUa51_@Q6V`vv8oG<1Oj8_(;fe3$|B0RfUuZcW0`h5sx};rJeB z%b`E4|Ez-n6#PfP;S4gXe%=9`&H%ehmoT0fK1E!R8SO5habJ6X>s`&R>fT8kpTfgH z-{QhLmEZ}!+1oiNu4dmGjK~*SSzdkOMur~XVjj15-yNR(WGl#nVA)QtE&2NBjb9QT z*pdY}?-YG|d=#|d%g(!z{XzS$A>4o<=s4i9QE1Gxb-Fnpps_PIev?=a>4YeEg8H^X0 z&~`if_~n1Te)C2iBWvWmIy_#57q)%cXb9xTE#R8k7%Z}V{LAsl&b}@4>hR6ZLHp+) zgYwN;+0K?Xs`jcgSD80KwbiQHIn(<7&^-XzS3z~7`nX9aFal-wxb3}z-Cqk9=ze(%ixnsJH;duiC4%nv7&hqh@>s^JKf@zw}4wzjKC|o8HVA z9}g6U;f$gPt_=n65dLDs%B-utEi7NoQi=9q`^Vjbt)pLTar4Nf6!Pxf{?^{!;r0TO z**bE05~^{5o}ky^Et7P3LT?v=Yxq4%&gp#(7f&H!Nb?2cbD|msPxwe%4ukl~vyTBr zO9wa_)t{el@Mo|YETboItMo~{LKl{6(9a2tYVSl%CSUIS`1bXiBcM>PJjy`NrI1T~ z3+gRkj@23nXlji|q4nry{v0p$QcVqj9W50X^A5}N{npJl@EgUZ;dVtBtxDFeo z60eO}b6jhn^|g`MD=8Ci3d3K3 zNZC2iE!itea_unc2v5@wucE1Nv8Uc>68;z7 zTw{lPkbp)riVsI5?tD%a$>Ls613QRwf|k9Ug@lc#vqhP+U0e)gruc_WlD0b;b}?lz z3Zr@Ec={Y?s#E@xO_77=VAai~3pRTFdKO_FcifK+*tV{~vbX{y|dGfb@4YLz9c z9_7?)*>d#H*L4QH5p zZ+D>F=0iH|4ZF-XvYIcFKiGl`L~@MfGGZ6Fdp&OOzWdfg699;iTW9>8#RsR{KWUze6VLs%*oc#>m86*S%=ov9`(izM?V8A0}SqEGK|hAbmu-uf+p;yz}42| zNB`KyKDQ+teqKXlcv8y~9lkl)Jv@N+K%jkRFsj^W!0^fsm2ZPw{~AQ{;Aw_33VXzd z8>WP6_abZOwD|zMjUqB@+0BH4QD}CsslbX)o9?7P6pD>Oupa18P{#5Nu29ZGlu-&} zKu5U_^PwRI-vrMKhv@(d9-gqE4CNb8p4_DYE!0nv475n6C09`8^Ca0k1G-ulpDWDR zkR%cfi}EdmloxF35QUjB!+gXLS5~Hu(Si1;F-rN*8RsCn$&D4>R6fG@Pcw(gOqgBJ z#|(9O>QF7T$1Nw9|Dz-2Vd|oyQmT*suM5aV0?ba`a*WsSKd^+xPZj|jJpCOzfTaWe z-PtfD#&D>rTw$NG?}WMMpc2#HYBo!ONU_^84|^D7^WwUVHrvt}RSH(m;IBwB}{sf+l5VyK8ayh^#?h<>opY<#j1w*y2($W9P_J|-pM7x!b;t!Xllre&t)<(=TEq~AW(fl`Rf$sHz!@x zHXbgt%7rA^4eabWjw$g8mq&I7#)M-Xk)j#lLkDRA;e)$Lpm0v0SLE3cZIEA{6%V{- zR%T{P2}A)3Z%dtb;XH(c|0#YH=FxRr8CQSF7KMKLmqJ0hn%qk(g znxEOZ@O+HU(hu~ls3W`=N#~a9LP6h!PzZfk2weIw6}qGFC@NGhY{l$ty-TE4#+q_2 z<=s02G)vWGWcA8L2$oTN%&J}&6qRY3(%q@El_md~jx6g)9ir|Iw9z0^AfX;4YNy^a z(+LpteMTu zk-8+E;a#v`yOZBNqHN^CFa)o#ZFp*lrE2{QT%Xt2??Z?-+uJ~%v)qx;gsYi=8wwA&)H=ae?&1~-$^ygZ!R9G*C_ zMCC|L+b*_JlP(8VupOMy*8^{Jtjr+8xoKk+ySqZ_DbY?+hs$6lqgJ$x%+`>uGZ^x{ zfLxX=450;_y33J2b$IDmt6@|cd(tAHxkao|U8<@L)2FH6-0AsDfS)W+rA*BfmS!q# znL@qIc9~7xOM$ClFLR7$AZKL^-3&Vh5y-@AHrQawYqVypv4X|5{QmLZg7nf<$SI1m z>co0RFGgK2Qc!2LLiLOeh{q(d%I5OMXY;}XpBZ)}@p@LqSJqe=){o{JLlYqHGu1v| zwd!WoH*Npu{R;e>6X?7E1EQJLGyoah$W)$oX)&z%B|ka8=-T(eZnu`JsFRI}!1G+r z9>=tcf z9JNL6!RI1Irs|)899bRB;}FDLQ++m)6b|9fKorxZ{|;nvM)ijg#wvfZzdsjU{F;9T zwq(>?k3$x{p!{rHDeC{9fhyXe{|-#CWBNmgGDWvt&nVDmVGCUe+@OK1MrasOOrLNN zFibVvpQ3v7=NWkf@}6VY0(ST%^Vvb9W~>QjG5{tSli;FD_GGL!to9$V&KlXj8-+cN zT_G;qsEq7Q$b8;Wv)AeccU-U|F_fYPglGnbIKrElA`TH>l#0+u?#!G&xEDv)8UG!q zbtfLvJ(wOx`n&`w_)6A~y_j;vi=bo*X=un*UP}-SdXkP zo2DHODg9=AF&RY-YKMF6Ln7;UQ?40y@Opq%PNX9CTspm-;h_H8!6@n^7lZhBw6iw& z13SVDdOfIqomScKIrncWLJP{*@;d_%IMFplGZ5Q1W!k^_Mwq(~uBhch{8XA!Ud(u= ziP!kg5wTsd$Ea#Oc0c$bTdMpWw()(r#*(e!J(rpHR3&A7#3<+y4Cnclm^4d6CYMdnU^FbA~1j|a%Q7OVKnD`Kty}XX1u}7EO z8N>dq4pFq}FexBJ(%8IO6xnVHhJuEy^Zxyl!6& za|-SKsE^SXqua}HfRBK|>s-S8YEfsx&D`eZ8`hvUg)7Zcj`D5GM79MD#qLNzFcczBe1&>lp$V=-C~ONg_{`MJb!h9k6d(`9-^6~_JH zd&dU|h{FdpI6(CiFLqCyv&R+kC%G;hNx-3>$j;0su-#T^?sIcb zBCU_LhVz7Z+0qOoxb8oYTgBs#hM8nux}cO^e`biiZVqQcU0&MSm2)v{v5+)tWfZ z@=4Oo4ctk=&^=O-jiT!U=LW&uia`D6DBgg3oj}}`DV5`jfn$~M_#2uGfN~)kt~h%{ zKsy(z>L(*m4=1REx#!^JFe4+gA08I|BC;T}{LvUcI?erNxL@HaW%Fx#ZG`(9LfXKx z!EZQMb8~_w8TYt_#ous6p{mS~02zwK+HXMvc}nvX`-V*G;%`PB^#c@IhyU1&W6l{g z!(fvb9P=E@MHEAlENp`gdl5TP#bJWy1P_G*;%!*n@qVmXTMxccb(mwR!XgPSfm&qn zXq1bEC-TnQ69O-Dv8&bnYg*kkI&7%fkNU(tJ20uX0g-R>y}bFL_g%tJXW>9APB-d- zvu9y*sf7<2%gRJQVqkw{SVO5^Fr>#0=%L{}iWC(R)43VcbdCwY+$VRhkHwS*1O`O1 z4UKxw+2wW9f8rzQDC%(#Z`#!NesxA`RmPhG{Bh{~5He3k%4?oK53%EJQPx^T8;BOY7IWwKh`FTwQj9`F&b9l55IVqvoBGf&N zy=#Amb2R*=_Fh;_xn+0I!CDR=U-Ok)>5*zQS`QPJ#pJ)ClSM)KOd|fv8ot?G++*p( zw|@9b>X=Ik#g_?(;i%X_)&a}e(=am;D`v~PhuA05%ph;g=QqZb!2o_NhQQ%I&bX1| z(G$=a>@ChWLGk1^q+M(0@O_Y*{)Mj!1pZ-7xu{{IVc4z(Vq-oRf|(O$S}1XgSNb^U zMdxD~Tz-z=gRL##DBrMTkO6-R{%OOD z6$nJ<1v{*k47ZC9zuUyx{*+<6-_UbpETvzTQmBD7jSFEaiCARhV=T=~AG{(e@B3PF z{IYfjHw4-6V-$4?PccdTIin=o#$~Y3%hvc|4<)i~*2lX1HBm$mfqe`0I;HTYImI z)z4>7&MJa3k*sp$>aD;a$pimmyub*NIM;Fu|QWjxP6= zQ(4(iv-4fHLH&hkkIA(1RMJ*jaTpcmCH(Dcj7*)=jzL-@2e;h}f2ph?v~5wCcf}^r zKJJR!Num=HLkOt~QXN94R$Y?_$F^AK zsGy&PC36i^mkMsJJ^PUd8uuX-w<-gl(o@S-ING!PWZJuN)1q^}I0zsY27ffFKpe38D<90cUdr6f=sEGIpc3wmbpw$E?lI!p zHIQUdw2;)@zi`+8B2@6J9P=mS$WhXoXFe7>T;f@14WfiGRI3o*dX@uNFdmjXJK`)Q z&2}Txg&DIrHP*)G&18;D{+rLSXONniXLk&lL*&Al|C%g79s0Xbv^)lmw?u^xKY!h( z1w8qGd)ZvG&_B9rEB}I3`=W3$4>P$Lur(Af;`2Mh@1EVM@=+iC%UNH+9|DN{k$$lp zQvtJ-N5;?CfA|meJeg$JRW}!Qhsgpquoip|ox)KT z+_jiu@98l7P%CD`vc){Pm$BY#pII2}ZpF-tPX(y@d7+6Ojj9Uve^GVg&sjFIK`Y3( zoQ?LJ&q9o`Q=1ZD**;y+U~?5bX(%)u%X_)>JDBxbz12AfxbhdOSKM1IcsXp>P_g2IPs$~pMPqtL)O?}c16qQCZdlpESrH-8nE#Q_mY97 zw$L(9qc9+oxHoPF!7CW^0K>W8 zM8*W0L-XGmAdNxNu&pKoH^?=wHAOR^LEJ=?Mj2y@M!3Feq)wuEgIdT30S*(2ShpUWS$BVZWcUi zkD`m{mfu`x5P37i|)(I-{FkuyGUn4#>wwX zbYE$w;kg;%bqpkK(|&Dp765&H6NOi8J3Dx91V}8CRIYry>3wQ=4|zM$K?dMpz~d0} z7CM`cabiCB+0rTUyJ_&$)bYUu=N$+}qxH5`L62z}%veJ_P)K>o!P8m{0nn>9LC`><4HUh4ctz4R8 z=n1z#Ys@B2r8$#Hq5=3MqlJ?=_pKpa!_Tyac@>;7%{i58azQy`T$$K}nA`?8sG=e6 z(y|*ljs~t)^<_<9XX*EVZl8TVfgFu6J)JvK6u;&?c6&%M0B5$|?SWJqxp`j18Q9mN%Kdn!6HfMU3UETlYE;`djXXsoWix`J}w5DoVyf%k0 z&(;x&KeoSCSRhrdl7&^J*G?ehzJu?>6#&*(%%ec1zrB@;oFlp zZ%_VO&KAuwTG_G&Npo!rGjVVEhzxC%GZqQrAaVE3e6S_ykC zZq8+wq+p20zwD#&>|e|I(nX`p6jzQwHYaah{}=$~xY-L)kZbmm8cdBGshHTjM}k)x zQI%AaQ?p@fC#q$Gi88a5pBl@C0h+*+rpBDn=f|X%+E3+R*!fD_hu!cX2s76S!Yt^5 zUBSYxn6@Z&N3JeaG?cUK5<@-X9|CK`n*MV}zc^#)h2v(n7{|h+V?t8UTf;(QS^eP_ ze`F8&9FXmHJA{3~yD7tPmkng559dPTG|2P)y~{>P&N|s-qz`DFV)?43t(Fiz68KJf z==RU)4>Q&Uy%LVw_H8Pp^AWI;=<->!n@d$H)PGc#bi)zqRBFc9n_~uwm=$o`z_~>r z!${Jby|IBBloxB%&K!KISY~VH%9ly7M#d_|?0Lvig0wPX``}EhK>6;k*3^MIG8+@c zj12dPxni1#b|^l>qD$_gY#PELP3Idj=ky3o-$))8G{l^uG3sQ3Q*_QOSF}#~R2Z71 zG%tfRb;}j~3TIy2Ga;b)D2;pi8wk3dkqsQjD4~pKJcMS+7TZQ!O45=<5$iN){?YQR zcgH!sRW+iOt^G4$b}vLpc``tGsy)oi#hjH5(aPJG7C|t^kdj9rjnN?kG@SMXJSE7I zGfkF;eFS_Sk>QkKmobXiw|+~R5`JZ*_ybg@dL^;|xRe=JP_V5fr5Z(YBvoy4t_LZu zw(N8adr85pVdy)kwL|OM$(eOAptN-^r`FU7fieVFNKAPN{zGuLjKOXh%l+7C^N0Oa zZbb9J8@Y2OPQdLG#fK1{AT{RXO{(TBXt{!2ahoZryToiVpE(R37UJxw#;$Rh_}|md z4YzMvOt!p|H?!}ZGv@RLNdAnWo>MJ)Yz_o=kHR>715h z`=_1lzXhm*4R&!~4zA$yjNGben>Im;K1|cFA5NX+EFU54-W%=_uWPR>5s1wWpPPA> z=BLn3pzZut@Md@01DRpqQHg}Sdlnqa6#i4)FbBz?;e)k<&hFSh4Z$;1OOQO%oEqcp?`<#Y|Yqr1jv zG7!Y!8>P`5X0h^U5^}OFnW7 ze(pL1fwu@nhokbj5_c%Xd&jt&p{4$k>NirP%(;wy9z5OK!~@lk&SI+>EOAWAa?RxX zj5gb{+l315N3f8hz9tx|$}Tq^QBQoiSj|n8=O?v{K$f4`WFSdTsR7t24RQf+gD#be1gHFIG-6Lu%O#5-!K1U`$5E2No|jGU zuz#ZN*W$d~MJFi*}Y8Z{nJN(h?={5(dv-Pez*+EuUbREl#{2$>ry z?@H&f*Cni4$FZtmp57#p4FqZZ*m;3m&$`h#jC-uUd|-lejXq|k3o0SauyePuQF6wc z+*nHl7__mt7)6*7n?-RN2ilHNggA+3cRm?oFu2lO(LtMqTn+k|9bM9WQ|u_oe=dOl zDJ)TR9uiaHbrJ8Z8**n29rW+8N$FQOG?vY3batYkBT~+kvQWq`ZsnrF8m#PUi0-jQ z`mmfba#l?>*|^U>Y3LE}p`Wi@vy6AaOJ)Te{LHTp;oHF+j2hP)bV(?F^WPCs{^fF!E)^BF!qp9`apjc*B8wNG+H{fFFKti zt0o;JOQGZ|uDJd{;&#bz_ZylwyiC+f7*m6<@*6PWkFbm_mIpJ;VJxQ81-P;rJF^-oqo2U7hrn~vz-j9!wy3wq@OPbH{x}uzz zH+NuU&6_(=^k(a&5pwo|w1{dLZ0unhdzR1N+uIKOys&_ZKfzC7vPC`&o`AEgcl%n4 z2Vu*tIu=_a7}65zFub{4bAt@~jy}ozVdRj2ihXE}g+I-Tva<3*^-Jp)&nV9Zjg;|* zlY5AQJHpMVKA$(zGAZZ%3r!vovoXqcTeGK{9^!Kb$G)~}pyhCM_5Cp=xbt-|P0x$* z+3?B^?|wnIQa3GnW2z*Z@2sW z*6!^WW;91q3T6aJwKMs7#=^g_qEFdV*-gy0G_xAkKY+HO{Mu70Qm+Ljd}B6n?7SiF=s_G1*?^ z0lu(ht7=?ub&r5O&wFO~M_rKJGIi%?Ty!vPaz`AxQCe`aD3g<8T|Han8rVPMRT8oU zECv#o;YHeih2bk04IDo$ZGgMrbTpt%!&Yy{tQDj#%dTQj&ctE)R z$XlTvgxmnFV#v7vg1}*4p6nO-`MAK2u~E*PS*=9~ZTN|+yK~-BBN|r=r(e}_uG>9Y zzL#teH>d?QHPx`5csU zSd1ZD6u;CIJkmmM7M6<2&POZD&etq}ez+y3A|`r95F}r|j94{(knpu+!X(Gobqddbz`ag~s0&03 z`{lF%79+tBMJa-w=QxBEBZJeDI=`Qv=NPj7Gp1@lQh4{^S>04S*DnT!IB_xcDpXPa zb}&pv7l~qKmXzm+nxKXkY*XJSTgMXlqXsU?={{Qemwr2XlHs{`mN_`C<}g#l(FWOv z^E14_4<0@RRvP}h-)gs@b#&iDb`G`=wpWrrS7S?BjdN|U`j3wc8)y|eX`@@>qAO0_z{pC$8v>g7^7Vnv3eO-y^e`buKT%5nw z6~1>bD6U59IuWijD$jeIhO#Knl78Q?!}wgcSv<&OgO_ySTzY+d{bd^(&L`#bTb;kW zNU||uy?*^==M=a@$}u3(F;9OuFk8S@pHemY&rOLr&PDnYcock#MJ>ERQEwlO8*eyA z&Hl|rqnMAYZG3+JF4X`0{{2NYe|!?@{I{DNORk|pS|TB5W96R@zW*swcZ6e}J^%8n z7xdvx*@s&zXwMaKJ2E|e(?qqmAMV|=9X#A2zT}(&rsyLo#m2%OBP*^tB@op?l)yJ- z`NFm_fuT*{7VdQVn2Ut~06S-}G{~!Vg394BGQYE{{0^7x9j@9tSO=(j^IdXcE@_(AcV=2afQJ8_zq9Z0&UuY@ zorgEyeRtE|mLGRQyjGTo+Oe{=61Ns!P1Lugg-YlH_W(add=(12x7&$TP%@LqaDRSn zQ{xbin_cwJW3JWn05xu^6fjMxt&R4=tv)QI=0czS5A)Vv$xq+&IK;12PkmAfS6%gG z8be?Gg?_87Gg;!TZ;RBr>$^o3`|F$K{xFAq@oQeoHFU9O=rYGp&wsAoshM~F`d-ag zZ<*gdmRT`A>pDI6m-_6hv$?MhcRYYU(nY`Ggd)^JyisK*tm~g&H=FT5zoj1fTx>NL zeJ<<7yE(5AcgW_MVY%Djv=FQ?8izx{xy zE_2+E%x#_L{yN8U{l!@1e6yK{apMWhCEooDu_Yg^$e83 zTiV=M;W|T|VO|<906Zls%njJYEZ&W@kro6d3%!kpXjiE|>nay_D~^)V^O8ts(?2h6 z?TpuX{>2$;dyHi2Y2JSxBY2HPP@ufarvwOv zzIm`2;@oYwyYH4;f#Dffijd6L!+o!lB#VNpiK}>0U*n|VzQRhP>dJGAObz}EB_H2tw*#INhF2L0eU4xYR`VduS*#

    =Tfgf2 zlSXp#E;%vod?&4PXKyFjIX`KgFshn^yk2cwm%;XbRrV?)fOoAvc6WzYbug@{?ERqC z?Ydd6L6%J!2fKPbzV+h_gs=n+*+uuz1vzt>TC-QWw$srocuHcs*F!@=e(rnDEa(D7 z!Yq}gB5Z&Zldb5*8jbC`bAMILIch-A6Y-!s2xNMM6r#}F^rYBEW#c{{7F%Li5KfC~ zN}PhHe|Jiy&M$6#=P@QQL97?#DXviLI;YJexSMo^Xp$42L59nrorQ0c4h=$}9wl?8 zACg|gb~=h6ED*-D_fxEc4y1wrd(#LZr2t*OPdLMI^CmSCY^-IERL zOd%{fB3}B=s?}&zP=`G>XuBfQo#x}E%{b&+&y^BzD1^2&@=@GxATnxVqy&1uhS*AT zMkusWiYtOR`=%)+X|E75t_=_7d%_+;#DqL~DZ&vjiYU`pUS^Mbhy)C?SyQMzQg7=A zXaQX}44Y;j!L;cYbaKK?qM)k$#e%B(GgabYf>6t*p|aqO(>X-OmN3oE3fjo0vZY9yna>0z z8dY2U3?a1*;R)z-o5oAt!q7;Y-d(BAmWf8BJCW>|+n*0{&6lq+Y4A@0mc`uuA*0o&+v|ok$e3 zrx*Cs{RdAD559l;Ckt!Vc*c>faMsNHq0;slkX4Z9Lf*h7(Y{C8(l-vK+`NU|mT>z6 zp+p_!m|QS1XQpA#fajG8J}E7EH<_(ep?+J*0eN+j8rXFs6Wxh_>ugwpeCkrm0Jq98 zR7x&3n0w*zR|hI@(H7Tox|wE;up2ENAwB;Xr+s(BZdgD|0!__szGqzxT!>>>*g4Z^ zAx;e%`Z~>r=tQdcl=fho zOUNq2={9V@|GJ6_IZPKA(WMBGtR|J)aR*ib1YPOye!%JdpyTVD-xUtH4Tt+$n$Fh=#Hyy-oS1q`qTESJOClHoM zEmjFM|G*oj4ur;I^&_g=IByo^Jv}v|=nVZ;ci$|4lwW%1`m>-nX0>fp_N>>od-wkl zyoPaI{G->zQyaVT%HgW=iq)O~fzo|mJrPK~4&hiFg%Xx75>~B9P_Z~qZz>jrdous> z6Xvul=b{jm_({?1mwct1mul@{eTL zeAa;FrSuCMD8$Z^!F)8jidVcNDR{7`S6wh_UuJJ6QwtpB)ooz<(dKS)a-)0mWE<6d zyy)ypWt}^u@(J*Ix4+pLWUqI|^Wo4{7Vh5q4biaZHR17tAC4Y8fu8P;0Phgd-Dkk-eslNK;S zpH(ly|GL~t9o$jC2+-wkZYsLWd{3k6xVv00-a6x4oIA9ZW$XVR2Ea((MOz>qMH42b zQrCaP;=-M!#%yU9G1Gic2i}%QQQEeRXb=ql=$p@p33NS;Jyz+D*P1z&ei>S9T#KYA zW9ekXN9#x+>8xUq$K>~E?`_YiTojl7Y6jZXWY79!FOEoaC@;F;!p9aa>3q!D%?6fa zB4{Lyrp5l;YlaG1xBPgZAYGD#ZW+yHrDLlJ5s=m~Y+{kdXrZzQ&DmswP@DI@W8mH= zTN@?f-53V?HecCRm!EgT1knr~|9k6`L)ScBqi~@JBn{qM@`i1!4>!_fK4e^3)FC3a z2u#E@M?&wk)y5^11mVRDhrzk2=ttgn-mkgw7^a*W-76m5ltf7Jb`fq zdeE?7z94cH4cr|K_z+<7dCtS}DRZLsIP-_{yF>x`m9v@gDQcB0v|Od}|;Arhb? zzlK%R(S&Q&1lQPNLTHyU782Y>au#h`SCAcA#{-uEsc;`&NFmd@MvUvA-(CH_&o8VN z08PS#(m@G>maE0(&bAPT$h$_WZw3-WStRLzVhJz`LUcPST|1fF(IvoEHzolIo^#)c z>xP-&`MuX`1CQBI{drb$omp9TxWrvsmCiZ>H;1C5NLb5hd&8Au>=TiEu+R1iLXbA#$U-p@C_&3~It20+{DMw-+Qz_yhgd~oiK?N~;cPH$l}b*e zYBp8J1*4cOMyCmdh_UA^b)ctvasfm_NM-GXq|~Qkfw7WOt(>GJVByK*>D*ii-jFEn z5`aUf*;8Jh{%!c6`|=~>?n?m&dEeV`?Lks#&d z$Ij5jd59r@=NDLLl%HR~`A(4)k7#RNGn2WhBCWS#`&Qo3zotBGqI_SfF*E2dmaF?g0FRVL!##-||Ug#DTHyL!E3VVMQbok0 z?bQNlxkYP1m(=FQBG<+hFJv2*zd-%B_*#y#S2cd0RZLiW`;5{nXGE)C;DokvhRJqH zM%@TB*f%ux1hcv1Ncej9|MuwaPY3rB$vVWXU^Swg>(~(pH^}vP|I^=i|4M zf6uZBNh0OU4*`fuTR1Qh$h5kmurjj1X@*lk;ID$%KfE#*G%|3wwr=u;a3N0!#i(jA z)T=u*B*xzhBuC_MF7q;DBo_+P7CuLpV+bM!^E=3AB93*}XXQn>rOm$XOiQ&0H?gFm z5-$IM8iqoaXS2do2OKI}e+5*bvW9Sdmut7_oG_PTQg4R}j?~E_Edm3FwkhxXWg; za$QvxSw+YQh9Ncq0l4yX2diohDj^{F5M8-e^vp@*0IoLKb?!ME5j)~m@+h+u+gLU+ z5I%UDZ+(>$FNd9`0L^VReTi$;u_IBwD>T1S2(2w%Om~>Ab;cdKcWCL4bCzDB)Zs4T znjQY_W7Ip`Lg*d1T)!i5Fm{W^WIf}6!zUg?MwjS%W7IIn+36iX1K0T0YI-Nca;T5C zJ%skOIw!VTxa|up4T?c+qjUG2=smWU^O)Uf(0q@o?)iI7GRN&z>=L%dzFXatuiI}rQ9strjzO4v`YNAzkTM3J zLHH<6!lg+^DVG5{=o{sXl?wt-tSClHn4E>)qsA3WW=-$p(D$yk1)4dp)_&NEo2t*B zyr}EO8gIm`(c(8UtU~;iB2CaM`PKF-?fBC2;+OJ?Nn1HSLo1lBxR*!e;&2It>J6j5 zYWs=$fVoHg?cxhwJJ_ftR74f3gn`bYQU}?c6vh?3XhJ_nIy+8kU`C_(MbIdSujgBV zOvtAOJI3lLH#dNxbBW)6gdn;kJ1CAX&oTOzne(WpcV~xvAqVCrpIt!U-!2$H$fMO# z<7%EkC%ur(E#xH?}&z0y6W{D2S6BKixCyz3UD#^Xp!kdXAwYUY%r+9+_*SEV#a-UKwo(?g$F1O7>DgpDb?=GuJKO+u>e$!M| z4Z~2QoXAgU4&!nAUW`*vMFO5e6Xu89bf4qNWO((i(oeora5ObCc%}udz zDqqesx?A)Wcdr4T!hhmuK5;bBmlCeGqP!HRwjRO@_cWDye>5l?{>D1X&yl+?B=b{Q z;BCo2I-dOARVu%-8$W(Tmpw85>^3UDLS6dtrMT%EKmDfsA^?U8+d--!(IZNl^mEMU zIqSmz18tvV(=%3io)^UcEvkXUU#C$_Zm2ln)NM!^+-FEqG^%9y~O4fKAWpPl7z_8Xlhm21?7 z6fmMBzxavwb|(=+YGz2+)Y3s+9TEvs)KsupQZuh)jBf31Hckz!`>DYEp!+%o*M#X< z6SowyQL4exoLN$_B_9mYt&2L+k1sD8JQQ<9rJuYWn?aqSN5;#FJT90H}J>Qd6 z-e)nni@cb;*T~atXvfwi7Vl2t)+L~ZoO)o_JL-K2!1E?RsUCaiII~8==c-gX5JM{} zZ|jP0Je`=~c1cz`K)?>s{_NXl?20Vk_6?b4N6vv|*@d(j^Kze{m6ginqfs`jieZG5(yhb#5%uTxe=OvwJKG|)lyG1j^TaN{x8yMlI zlE}7jqI`@lGm4V}hSSvcWS@N2CXok;kOrhP7l8LI?%ZSWDSTGptLK~ShLDKY!BcanmpgnDXw^ugm2hLO_>oXfoI9R|lW zJeYJ;=HsH2?QaQA!#M)n*+zIi^!Rs%P3NAj8Bd_d4v9#m=laHJ?j4F}Ltd+~Y)n>H zqiUXh5dY#ud+Oq~3ME`^f!z4e$RuO3`71=&Cz1FppO%hGUq22i4DxhA*ylW*?dXHsuqLp0HIb1Uc(r6i0kCK4R;H^Y#1e z9RdY+O8VkkRf(cSW7txjb4|Y(ljO!L*Kn?1YZ_wk(pjFBArtRsd~n}B#F@h7+%qz_ zDYoZHx_f>bReMgQz9Yw*XJI1?jf$&kp8VHT|Cg#ygzm%INIuxcG*Eo`fcgz|$OhCnf zcn2D*2AKg=A;-H}YI?D{rubi+XVn5#r{;ihSXMr` z!xn7@dyah9mtRN>K@MEm098P$zhh?)x0CaERwCYS3s~PX6t8oe3UI-8`AF_$g}Dv5 zSD!)g*^>`oP8LKrMfOeQ8vd|LEaIMLZjPGZ^w<>=Z)T}m_@SBj@aT{XZaagNvVvLm>L5>iFu+urUn2Lzw0oNA+buvt6 zZ~=@;&&fD`BRhS$J0LFhF|N7BfmNN3YaBmSq+ZkM(^OjxNZD4Gy`QiwvU;~+y=cGT zo~U)Ia5u-Ji2lG|o47;AXV#-5biY8-G-Ko)*2;tyN8_)k+e8et3jX98=v4n8@nQL_ zYgDoS2f2pH6g>!1Rp(I544xWSi-~BZzN=tT7TSt>lWPtl(kxl04%aH`d)W)Ebu7S9 z2qFrc;Fl4dl>q>XK@klZhbU<7x}b=HW(7hqPXSxW}h@LNRNOUcF;lhLa!Au1;?$0Nc+ z!DtiA1vv%=iGkiU932J_G-v{H%QU|1%Eft^4T13r(Y$yBG`b%i z{hXY_?FQ@5>7>%+47IkL7-c|VIhZe}TjBqzxwGY}2^`WlsMj^_`3OUellm!- zmvi3G(2l@MP}2{0j(AT5LseeG%Wy-}&Ur}&0vNvlcA&ys^J4_PtjDtqWP!wtLf|Cp z;4L>2>(JpLRN@Z=gkl@XvLbo%_}JY{aC;fw}CfzWr_^%F^IJ zD+f_H4lojqWbbc3F-v@>aDtp@+<_bENzsV4AqZPZx7#JULa9Wn8|#CjQ9djf;=gSW zL_|{+i6ZjP^j+cm9Pcg4G33X^gzmqq1Bo~aubSu}i4RiMd1Wpn^|hYt0AWkZ8(8+i zB0%u50o29njQmf|L)@B!TK2N}_UVKB@A1N8T&!RH z-x;5^xpT6+Gim8)f+-xE#dm$Q{n=y$Ehn{_Et)uq1?-sdY{^5DVIc5T;hD8D?ozc8 z+OM_A`Wm(I!gBUliSO&rm&5m+!4+O@?p#XW&?R+#8@4ud_?s2o+3i-8UlvkLKJ zgg-1eKegf9hWv!sMqGP2_@QatkT!DFsO`rAOE-O>PPi1G34+K#H>T=5H8v|5AYA3C z!L*hOHoTiXhE5*4Dcb~lTyM=q9GMXS+>4g)Sw}jMz(e>=HhU#x(PUPuP4niOl;Sc4 zMJzh@*Q)+*5h7nqtrpScEovg7VN+Ra*%59yV1D&odOiUaU@Jk3$oWY(FV6`1Jviz}z5c6V<({gs@i5*1&>>Fvb(|$ikATo{> z^cpyw7O%3gxIk~2cko0#SHMFknDl&<`Xe@X4~NmgtX(B%*(E8-hWJx%gr*6(Qunhx zXS+s04;GEZ>_XCRR6|6z$fZyb;28BPEsOCUDW(~flC{^Q5H2Yrysd0g!=o;8j9%X$ z&E_*Zy(BlJR?%BbZEak^5myk6ct#MHLDu4 zkL8o0Q?uxE{6e1skDvyQO=1|Q8N+2I$vtR4oienNtxNjgi}bY#)s{+rT>eu;OUAOKwcO?Qg7x+nzxMtupL=tMxV5_B7Ms`LjzH zIM@k7{}8G5=6VQ+1txfMIE_ zu=R;9scwchM>-5J1Cmh5vOqtx(jn!Ox#7YoJMD(Brs|Efv}xt<}3qCM2X zcA0)Q?TIjwS^TMfXY{^y`8bsxDcmb1s9gnlq}VJ1*Rj!pnO_ zUzJOW!^NA}My8QNDH;YTU)azQ9lBC8ZcpXk_@Lk!wp1g_7}8Il zoI~bHnU{h=A|ZV)nxXhapcho~5*|Og`_ltNx$L?pMFzuBzj{)jusI%eK$*7Q60pn- z4uvI4FXoG;a9B!bO(A!93#oceqh*I)g!1NwId3?sio*t*(kKs!ql!bbI-$tAiHcF- z&jW7(=L+qdX6NX$f~@cf&QYu3iLHdFf!7NAAXaQa))Lg9`gWekJ0h8sJg;a};Z@YL(9?9lO%lGQl%%~Ex!jxq+7iCM z5h(&|7?4N;*tJ-Y==?Oi{sLAc(qkPnQq#B)H>3=xy?&BT1%g*y5pm?x5qr;TCN7wD zQc&k-IOzuupTgFI|L(W;TJVcKL^M0eE&M;s_e5YGSgz63>i*mPxlw=h!73%Abc}d4 zsMep6ilRt@Ic_mVd|y&Q8C$u&4bQyjCd77ij_bOWNZv43YU2)vcNTw9+Si(YN<80Y z=yNmUn#P?JkH&yfIs(U)CZ`CGkLnz3Zkk=-mc~5unn-}=r^jO=;SRPK$#wjw$KV}` zhoTSjF+IHPKAdK+b9_N~{ssHe@ToZ_)gi-G)2U$<(q)mnA|T~X2S#0#>^ygtnk?hy@WQxUb6y&F;it{KF!~7arS<_ zP!%S$4TLux3}9zd02FR-*e~X_WpcUk-t20k8F$%m`wnEj`I~n|dG<~~Sl+=cmbp2c z1x>|WhU9bm9S1LJ6`rIhzzY5jZ;eu@Q%}^-&VmI?C7e({j*BfwH~RFL0^7 zqgd%}e-I6Cz_lH@!=Ulq^18%%#|bHC#bo~GpFJz?uftgn2iMET{b`1Ds0NO%KEjov z^YBX8OXgz^xKQRsDFkg7V6oio)AA-rwNdzOTyTDRvjTino%i5l%5VIIudH$M7vizW zQrP7p<&d$2!9&>6E`+PAq(e_9ZtPp{p6_=4@`C^S{FeVQ`n~=k{b$?BRl-;)%$DB! z`RM4uqhp*N>EFm5h~-m^$Jsf|^lLnCGmv2=cR|ddfJmS5C*XICTsh%{@yi>M^oPFv z(S!duczW>o5x%~T;GgsUNK60FSHJti1AJ@f_m6&I2SfEdW2U>In=i~u6&WmacTRB% zQ#Pr%7aITR5k>YlCR6d9C(pKyyMvNVOJMI+4WZ$%hPk;%>P$sdzz|TO8$8ZX*iP4>1b3?=QVqq?kW9PM8p)Dku>h(6H^Va{2{kYeBOP#&%-U{~~89yv` zvATDm3b&X~!%MqcOADY2DXX2(7Wi%a=0l0Il`%i$o-oabkS*NF&n1R!wGt4?E|e>4 zbzAME%uzL^2B1qy>^BzhZL1E1|J{H5H2Jsg7p#n7RPNeqKiuR?_qatumC-xQa1ChE zx^kp1{|zaQH&D0)$Kv7iHj$;*~%lJ;(pVah5ctBON=Z7SEfR9_-e^_HLq z0{>;xJU4E^UZc}27?gyjIha$>>u+;}cQ>g>RZXleO)&o%`6b~|M@(|{>2rDCs&wyc z{#)H!QOP{8c*&bpp=?}++vOA7ovnSC1P3OypSNIai4m}2`30G0(Qc!>gh^7+YUYSE z_{bfekDb0~@OJh5mvCms5kXkVfGHg^g^N^uIz@Do@_jyr{g#gnCT!XD#yT7pmpxOa zVn?Vg$r;^~T3iZWgIyVfxU)f%?0m>kN1kQMVv{Wh0FDO_GxS3#WQGC#sk7*8BuVVu zD33w-zC8D#35(uUZQBSOel;o+W65lIAFr%>K4K<=nn?fPOT)8FJ<}r0C?^8&!SzG? zWi9Nh+2eQvu~DUDVRArIB+gTkc$Kx{OuvyvVSNe($6a-r8EoSLJFT+y2v_^b!96Ee zIyZ`5ko#y97)_i98W|8+cy1!xH@P9Pcd}PW838756YDqLMI$5HgWkdC^SBKid;v{9Kg;~L0>nBDc< zJ4kB>b{-&-mpuk{Z@xYH>HRc0aSKYS?k7No;(KJ>;+ho<6z#=+Fy_**WR9Xy-v+?_15C zL5nxYu((}Nl}CrSpFVjRnb!xye3Xw-Sw-x5hH%>Cxa+{ z)<2_Xy<0ukR_pfaxCg7Rwo}jd4fgWQ%J{4gu_=xD3tlza_wpBB!!O1=#{Mae^P~r;G0d?0beGU zU)3TxI612^S@*nuvHh7REkOsgvQ#OV2HKS6JNRtu$F%qBA&bU|3mF*fc^Ht2?J;sL})-9~;e3#BpCYZ!OAQ~wr#twc-n7!ArVcRh{{7;s*I(NX?qS?m8Ms9CdVQ3tD{Wz3 zf$nWgEZ`;!&@Y-1K);*J0=6^p!$P;QY&t9XePrn*sW-;#^fkWoe zzJR~c>Iy<3$3*GAgd;M}`dL|8NVmEJ#(t*+6w~0ur7ns}bvJdOtO$pZbZ;WmTJ}k+ zk(G*3*W?M&Y#)~nW`~8xF8lfR&=qOF$q9>$ODR2*Zz!1%=Pr-sn`5t&AIx_#>B(c! z5X0@?8qw|}iVJgv-)ATpslTPPZ1b^qljMMW0bXH!{aJJh$TcVPiLQ5NnB2(mpYze= zt8LM-F!3N|+N{7fkgLcU7xgmlXV`&G6LKWFOeWa? z<5x)Dc7u(44_G3Y>H)j$O5Ikc z5y1%Y6}bYzG^5#y22TtGdNB?098x473>}G1!Gy+{RGmFl7~;9=iQnb6GXb1A8g@}x za?m8XZi{Or<(^^eH@M)?ac+>G6W(q<6IU$c_d)swR^SR|F$39#^8uEWDvOYMxl?LSdSjQC)Rj#WpX>ICn<(1+GHg0b#dcOZGKQ(p1~CyO8Lqc$AB*e#%r2h z^``SNa+1xXpOBe3!>Q}``Qn}>-#E{bzy9^XVm$cV;{*ayJslEk?G5pCv5elvG8rCrd$ zesk9YHhP)8nM_e&Hyfjo>?MuvO|QMiOSX9Vs6)%9(4fe`5FENq3Q^X53Ff8w97G7n z0TjR-8>gH0``Khh5zTJUK;CUs8@n!C*09}=2WAahTnU-=09}4_pq?&9D>fNvP*e1# ziA&RyK|Uau2E=7hWL=$M^#4N;=@OyPksL&tCCEHk84t6K=yEzU7eR8K%@ib6U{rmG zR8fnE;5u|h7jLdbAUW2$vXwj_Zz_rQA1DLEi0v{TuwaK7CTbL5+AW@ zD%9Mg=Z2yinr`s27SQ#zDf`FK_7$mnoW5TVg^+L^O|#mE8y%9dQZ}-3-w9-(d3n#CQs$BJp!r93{zOlvSG3&S`=S6b>mlP8~Ne zEk^x-XoNu5SCz()+~XCL4pEZk&c$a|8WRf}ORwSzz+zT5n`P5(1jg*w=s=f%zBwzWs|g-T{bs@T)L;i!&w(s1LH!GDPj+Ap-B(HXClIek#(W^G)KK$ZZx(*D`Kq-wfhdvRaUG z2PhYML(CL)jof;Y4E-88vxZYK!<46G$)IKwC)mbUri}$RP5-JtlSN`vq>GcojORGQH2OZ@>`2%TFhvFx^ruO zbo?pMJbL3SH?4Kl{?*=xI8;Mh}@`{!?r3PxCH>s?r5bB zqq1+6xCXpfsYiEc`GbL@Ec z)^GZR-8&l1kRUgrxXksphD&NTd`h!H3cuubxYOm0Ebja|6sXEFL{e!uX?lt2A^Ku? zOk&YcwMw^q8N71zdTUN4V%t=wgVuRI`ru`jWNnKz#%AsPV>&{P8Dn$Fk_ z-uE2UL*R%TPH&gFnE2^7MhY=Tpu{os4U`ZwwoP%F=Ho#(xzX)*DJ~cLqkT)=Y&TrK zvbJqhu8$?v7O$o01dRve{HmK`gp6}m&MLeaL(HYl5V{NiMh|GRvcaB`6y?LhjUL5h z9N+*thi*W;a3U+5KfhfU+YFli0som@ObM7z@b|HWuJUvw7vi-GH^6vZw$7{kiL?8} z+5MN{>|(41LQH0q$O-9LhshiBTF{og5ff3Oxi@daOw2Q0r<(tkH1_%r143YpD12?USUp1wk zn>qIbJK=rGnA0{ZZQyX_w0)O0eSes;t!`oa474pbj<#93fLt9VA2;h})bzco)aR&a zJ*upOQqy(JGTvMJmKCDM{LDVs4AU2_<}10CJRVzT$!W%Zbx05IIm%*zT8Q~gIuyZA zbWyWw@#H5v5!cFOhtGW!Cc~NR1uPVJXk9gfzx>Nu$!7w`~x0 zos&_TFo}e5t5AO)q#or!qH2pDo^dqNmQ6vrEZ=CDcy(DmQRm!74)OJ57OgaUE$Kxo zt$uWl(MpRSk!Vz@)@n&cx#v|;1IRP&R%Gw)ldoHY{#~pGA&tdd_wiowE~c)(Z+zBq?pFq$=SJ6Q)~>c2q-tBoDMW~ zopI4ILy8W?BXxB0CCRcOZ;q@&GaBkZ7AMzTW6S?xiFhThdV~CcMG7Duf-l9-HciBr zb5&N6{f`mEpS*n2@i|AYVeD$-tSG#w1ei!*E|Sxf1EL#Fk|-#u@hcGq!KOD{`zBv2 zMHT1YiKo5_dixy`WLaOFd-l7C=<^+5BN5v@}&Urpy3=sW+rSYq5W?C_s zEB*9G>|lMKk14j?m+!SRyd9+-oA^k!*TMkDx-=j+8yY64nf#pKCH6v&XQqo+Xi4TgelmIYMgQwk9`-pZ3Jm2{L=QLtUjt{B=C}UgG`C&bTWm zGqUO(iMs4NQNuTU(B*{EK#5UzTccfvUT#t+5>9^DH<527ZrA}FBV8s3dCCf8;^N_w zL^ufA$|#EwUjugt27^)(r#NLFE{|D@M_5*1pMR7>-l3oqhQFI8cv3ja49s*-qfnD1 z9s|m{jwreSMptVk&3#7So3>^U-0H=)2CB|rh(!EI`yH^`3oD7gXyN4G^_cl^9^6#D zl{s?KkXyCd7R7_0$J~5maR4Q*QfjiPUv8bc5mv@hU(~wSFKCV*ESM4F$tiA`=6mGD zS09@*M^4+06TinvkTRc8Hcl3-IKuyL*xgCSEDcE(I1Zopfc@x2c+SUIxCcZb*gO)K zI?1M^AVwPhqH)sn!**h;?0fZt7-@4QIy}+903SV_pO&+HHkVza6EM(?W04uBlE8Z9 z{SK#5`mZhRN9qj~lfF`Fox|A!anhe+O%E-TwP>B8@<~Jywnhslp2TR>i1Dr9Lnzrb z^j?6Rb2KDRASs+iL=$bvrk?@RHtH%^b=xp?gtB|8N;4K9fy;1u+HZ0BlcxK$btmD3 zF^TtT_U*k)+C7_`$6l+>VNzC5qAgIw>{L zl>(-Mc?~29iZT)OD=S}2^YdQNfvb1#6`V@dq9z!`1P2UZwaNNN?8MEqu?HM9tnjc=qJ+(eYFNKI41{IR-C1dVFl6ebb~n z$j->t*-d_;yafm&h!|T=UQ0GQ3ynF?(NSE1&~P^o(phRBASPgXZYz^^O5h;6tcQhl zIEVL~vwLYUO-P@*wz~f-#tW2`Znn(N$E4K9G@Kk`JeeXN;bofT1g5qZt9EPPgc@&I z$@J;e4R(4mEYPWgJzZ_YHwj#kZB^MBhARlSA3x^Qs9`HchvhN`9#Z2Ie&vO48c@k# zU~#a#$Y>OeO5t!K`#-Y9$xG^WHa*2e91TI4BMd^S!h=RKd-Bqp?P0394OXQFN(|yL z(ZMLWAa1k$aQyg?e~zb;`OlVRme6$;nI){_vPoes8J8V|vUthCKPQ&^#~B*Jk!ny| z<~ckPCo}j|=U&!?-x^70Nc>Ft24A2@k1S}B_qa36lFqIX7b`$#IDn*;y#blO`7ONc zM)@j7wY}_x{j=2Na9J8+$8%tpM#7YETIix++ZLIF5J;9Bq)?rTxlX&hUvOtQc@_2E_J=8OdwYR^5-eTI#oUYc zP`$0bL1;Vw;rru8tG0`u{v%qU+Hxx-TVAUAk6|;=p<)$U>!iY~l4tHM)>5o+jJwe} z7Y;2PuVK&($My}*b+t>JDQ|A-m*1bE*g#!H+OfH*xln0tP&!YTw}_oB;Oh+2pwkV= zU(kv}3+J6r`E4=XCIxqTp4`8Cd{=vJ@Q5BBJp1XvUM&itG;e${(axlxU&8`HP|moW zR@qWwQwnDyXsmFG2OL#+kzxo+mrS;}3>NSf?Ofc>>;k=~y2;&PNw#5~ilpqP1RXjD zF&L>CQW0xum$V!@8n&xDnKP2V7y0Cgu|%sjLXzqXEyC7Ok;{u>nDrDF+bXAx-c6VW zlkXd2Sj!$?#TJj$DN8)1N}8c?!(JdWi|lN0w#nR}qA?}DE7d;|h}Yx$kN3o#2eYV* z@_&d~9ZFJmHEkN%329nt*Sz6=jb^QGLfki@%UmUAeOE`}r9WXH)ljjJYZ_L*ZxtDR z!&N8(>pUwaRTlWIMFD>QreVqwnDYRNo6kv;n^2Dj&Q8ShsN*cPkhjl`rZvQSjy55z z>U!^4;Spe`6EIw_OwY0q2$xpQ`8~RBo{~OVnAgIyWwTmGzZyNgXy6E%G9^3xe4_I3 zd>k5juNYFA)ry2QA7WdF(AISf#*O|UpnEt6B-6ZAmDT&7=^5~5MvLYBy4|Aon58$b za=-9WyD9LxUaZ|<%+@c@Uj+V%8~!-ZvE{RNc*tp0|P8veK<1(v;|n+YM_nERHibEMRgE5Vvx&95;zR)4z= zAvQ_&T)6yYvZw}fs36L~amggl`WXs|+)6QR;~KL}id^JyK$@*Uf|P`7du`4pDzt=~ zDErfV0(Y9&%rxu-mS#?BFO#?$nl&U<{l4IaH28>4{?ieQr3mYAW^U1%n+7fWTv@>e zu@Uz!L#>=Rh%qjN6py#3j$|-ilop(klHWboP0MmVQgsx?n4ojnl$7CRUCSPJqPilm zbi#>SDA|Yxq-)Myt`tw-jHn_Ost;!vlh**v&ffHap^^L_g4m=Z@U&zuFJ)C;|M*yr zfjJQRSs;>R8{lIh^uyHA{VNQQr}009c_3@WOW9pEVM|qiLf(4lo~Nhcw|O?F_!$vC z#yQGc$YPQA861qRO3+L{i2W_b{nYsmjZ0DlIN>RjoWc|O_G*83vqB=>30Xzg;b7iV zsL1(vjyBq=Yq-whTkn>9Z}=jZ&G+5m_!XbVm`<{9#96Ps!iRh%$%o9;?iXSztZ36yNw1jZX1 z&8*jlxBefv+{+f#&b1Ecq!BES6hCSBoIw3%h-ee5s}tA8maKl|nm!o|a+AOo=rrHH zdaub%JY~4Ypm0wfe^SR-I12JxwHk8bIZ7_D(T;d3!29Vjsw7r5cX1^u7K3p7k$>@r7>@|(5 zK*>+=<}c=@+eJ#4x|YLr?<9W3=|~~an2>QV0b4@=lg#y8|;6ckdPM+ULvpUg}dspGkbxzYdPYl61zap#=LyC zYJBy9*Iu?uY!lV(QnyXGhR1K}<{*C4-8|mT@knU6#ojs(-mh{XxGnFNuq)+X5vz0= z+qQa>n)O7#U?Bn(NlwYt6Sl57Qyz-TOuN+PdcF4>3TmVS=_gHIFYK!o)Ot z=8$EKBjLasd@2Gc?a<$AH#y&9hVqs7&&E=6xOCf?g|BCAm#{LalQ=4V()Yq`C>(>v z**l9-S{18ce~^qRX6_j$NWv!8a3iqOv4S@N?Xfb)&`4b0x0a}4eoGKbi)oK#busGm z-A6`#*4p+j3L&{+4PSwqB=74sw(Bz>gBZ?wsA=49e!EF_^&?oWVw%+|N_pCHkLjt= zk-{KuB>h3?L#A2VSZ;!C)Nqua$NsNuzqYDTv|Jm{zhs-Q72L0+ER}Z&rlH=_AK|!b zP5rAAum3J4{>{Yvtwx-$!yAAo!ipXNKJ~a3uYlS^aZR29;gz?l`Jai`b+`aj3F^nW z0r1GK#}$Cvx*m4`ZtFT+0=T7Xa0}puYFz_jd+!f+4BV3g_S34$YIWl{{dc!i~<;ygTL)Qd}WY z0M4Z?UbS0}d70!EDpGeXFCaNC{Rv(0)#=L7pJC##ctbC!CH6v-jB` zZX60nZ}UXj@vrV|v4X3`5=RR=0GGh5<7KhZ8RpQaT5+V#qd6jfL_L|S0*PTAY9$gw zxYiO$-ka_giXzy!CynrZy1GE(p2B*+4g6aqmMBkLFPSWtN<22OBAdKdC$XwLvd-)N zt}ZIa3td#~udY*zDe610EW9|Q)O}T>ZA2R4yx$Ey&J~$wL)YWMvxDQ_)1U9%d+_wB zp-%T$T|+SDsv@W0JsYN{0cJEMjEO2yWqJVZy4XE|#yV578gAjd!Ht@o$=lI1L5~g} z^`3g&I0ax0oTvbv0u%0baF%ogRta9GBNCsc|3J3^lUBNIqER_EZ-JkYb^eg+Pa2G% z20Z3epo}3`OstNNl7bQ^kM0?m;BtT>1#t6p)eJOdkpl!9enw{gaOVz-wlI0yv2@y! z+1R~DoS_fkZXKS{ido1TTBJ)xFH0IHF9nXMMJaC2#|5GkiQx%vwQ8#Q0IY-DQ2Cde zCx~c_aB=W~Kr$+w4O?{T;nQJ@=Oof)92vz4NH!62!D2J;A3q+vTual0^%y>Kw7g!#qTVaztc zttJg|;f6I}*P!g&hglPCb}=+@vWjgI)uN**R>ox8dF(QOQI?Oe`_Pt2-btmYiQZkq zOm{_X-Cq=d>{2Z_riDR%b_OE+n9MsY&^$S~w}Uec|0-x+)&lCJUQL5JBl+1zSf5Y) z9SlP!K&>}0s2=lh{9JfbQ`@!jz+3^tcz7Qp`6*W~sdQkPF_AQ-TFM8gr_j2cUxqww zbv|E6DK3CGX0!_Cq;I`&n1tpp|B*eG(&DPGKrH|oRQ@&PW-Wy3X zeD6lGwY5cishsDtY>!+wlQBczp?pF4t>LS_rf6x{Sw|;Ry^PypARjEVh|dft$sjvR;YjM7B9qGq@p&SeBoe^EZ-qvYqc}196BzyvgjdJqCh%qhdDl4 zAlG!^?OI90cewLtLOj<8*7I2#{&+3SsL7CiecWig$wpK3Wh!@_7)ze@!DRuZCxD|^ zQjz6h0M%k7@+>bS0Pt>6kI{8r>hQRC@aW+9#&fRz0_0IiL^iPsef%#`E76(=|Le9=2;xW&yzZQgADMY*uf5haqkyvTR=Q3bt#AUFpQl>%>~B@CYuai+YS%E+(*u z{H2OHYxlS_D;{)g5)6@NX>FX?H8EnnZLkm~w&u+oq*x-Tj$L>~yjYK0xGu<8VK+V= zH8x0QeO-XD^^mDSMD9w6v33JCnju&$M1G$MLE9sB z_Tw$pQTzXG)T6?3`sBlpcd0~INAle`nsZ>4r|Gz)R6ePn2*P3olMyXI5bj#hT}1?I zRSAAs87sIVb=W4upH^+t%%y8YQQKB;FeErtRkw<#$#+kV9{+H3_owgR^SE$QWuU7d z5vPfP(;?W7s7{@W_%4t!{k2zcfdcz-im|g(G>`o@&!^dd5LrEn=&QsW4oKJ^RYKF;%wLt>k`QQlyhM#ZgCCsx3CEq(3dnQm#xgRgJGM)2r_0 zN~3UH0IKhbA@)6JD5rkHs6ZPHW)Hm+ag3i{QV&oW@-H++=JL*}>;InNk|madFvY zyA|o-=jHybidlv|!0gMk+~Q>Q-0=K3tOc8K0vrzMEc8S3y=k9z$tsRk-$iyra$8%m z8Q=2hjC`@7s*3v`Ng|*_tg3r_!2grg+6$8boH$xMo&4~Q@&>(Nh!MR~WsIwhsB$4x z9n)mY*lc)}I?tA}J3d*DrMOrn!G%q4u`IboO==5`^>bg#&u($jh^4oH$qMrmjN`o9 zwY*WJ-IZU>Tb{Mvt?m#3%`bXFjw-CrFJih+@Lq62np36l1~#jXAi@xq5yv$Mxz~y7 zqvBG%RY`c&rOoyXeZ@W6#OZD;IiwWw@f8{&Cb7~Z8)oD}>>Bf0d zvX#orK&`=iie=nMQCi6Ip`G9}jA=Kg;WIy%=%P0d=Pi=Ztge>|kWnzlRc>YZLe(9D zlP0Uu^ zIun4fkm$sur`D&|j%$fyEf=isDEw(S>o~u9qTVW0$}`9~uomGh;51u>bg*y@+S>oc zxFN;CLwc%)GrTU#i+nPn0K*s;;%yPfX!Zo77^j5raOLD@BqK6{6{crrgt8}?Vn8Q= zDbI^3+s&W?UD2i@WqTh`Xp<6J6X#)2u~64X*eY1>b2u*VPZ|r(bK`AoEn48=tT!Ly zp~D|2Jc>T;+l*82?N0KZ{uj;!A7&jL6zowP=RR-+RLkln&2J0G8tXaUrxK7bB8+#I z?QKCnm1r`kA>Lan48a7sR4yqDt9d!O9K5Vl+^$|}_P7Uq_-YjRAR|Srp;@DH;ST8E{RyEI6EUOfv&Ei4KhI;FjigD_i>@?qqQq-u#Yt>l}P(# zkYPu!;pWeWWpcSw@Zdo#&&KHUSXS(ZR(U24DNr8s)?qz2v~9uYC4|cko|C`TzW^!6 zr61>wYDea&_3W77I;55{PF0av?UW`B_+Qr>SI-%kR`B2pr5IZSy*}JheN|@_^Jzb` zQ3kHhj&n~_uibvbuUx6-l!d8L^i$*!{Qm5BE;55J@Yah8-f?|+AKpDU{Q2lXBiT)E zC%a#Hp!B1B*3(Kbh+aAEqu;gPt_kTqcK8NIc7l_H3dWg$IO7@PMb)ditqtgg&1V*8 zgp0CY7%>pULZJ%{DN8$A*CIo?hj9sPGKjmGKE^_>G9FQlW;}f zn;8ZstzFNh(b?xy#tRN}x#ukBa3My(}A-(n2#nM>F%3V zXT*S7+S8+rj*E4gQM9%9>N)_lPf4Aptq9hEAFp-1{QDxPJ{-GQJlkpdNT4y_F!BoXlCCHD%3@X zR{T&55(<*0qh9U4GfkE8VH;j@Q|k6emHi;n=6A%;>;S3$eX#4rSrr;sb_j!6#!&u z_}-G>J?Yoo6Xq2cN9u*IV*zti<`wYKDsWEZ{c*NTY~!>T_0Y3b(>N^NPL8gL(PL`c za(C(fO!StuS5d>@o;-ef@GKc*9N7g#(RifeT{C9S3QT1n4PaCdBbvIc5&vXirEl%!{~Y!7*E{1ma16J< z`Pbd;Xtok*zF$nP$gd$A!a2wWKKQg*Tr)XfSAGyy-C7pTJBW2KyCd@3;^vId=E?(SE}HKd3ohj4wAf}ItD>9FK_ zh%!G+CujlR0P=@`2*X)ZCa0r42SD-ivtV=UOh)0a9w^g#S2%|JW@?=|J#RjjpeFm5g*7d>r_Tt@I@l1^u(InF_jT?@IV z6jq`4gr3k@J-Yko@ZkIXCjX0%=q1Z|eC|G1l8P&2GZv4xXZh$lN zWEPQ~q0=Q4T+q~^-)~nXFN7)0&jpy?Zslqgipb8;IgF;Es7*m((@(5J2E7~-=IN3& z67-feF!{EPnj8?m1hXWe1fN3@?R{5bVl)W|TlcHQSj8Y+Nic;f7RunRyEr5R3R7PZ zqWORm?v-6pM~>Fr>TKOms{Os;_T!sJZZdON%yQ}O&;jbMta+2z47qti_-EGm`!JUQ zprRdem@KBY;D4Ufos2vNnH6)njJaAefS6qvfeB!yM8ezS7Y?HZIE7Wp56p=HC&{8u z429`tcbKaCqWJA1!>SHTi~M?VoNkqdft$q-z)yQ%BCA+2KiK3b{j6bkT;1yU$J!h} z+~W9Q_C`GftJoT^-O?C$u(!7CrIzeP=E=}Lhx!-VU2vSw%cO(Iec8U4%bP0P({JB# zTr$eHZ_onq-F741;YV6HW9~@vSus*@2s~uEz@eLnAw9mK&Y=N%(AiFxs+n$qh3<@^ zRMb-ljuFV?S209JQz+tdhh$4pyA)Nv#|lk<8*P#9~(ybT4n zmgqo^1RM*T#jo-MW1Kg4PIh-DEgi*6sO{k@`3WPcaC#>%rDjXL+|tB{C6cS8!Gc{l zWh8n94>hU=BpS9*dQnTUiI2D9hqTj$ZR9gIm)!EU8g|JAy?xWJwOMHXsk*??)lCxT zl5-aM_gmo)T;4U-)*##4FDtBNU9F`H7pdqjlG*3dTu){d0;}v+!n^He@({n_G$NxY}_n3K|=Q(+I_WFdFdFtE4F* zh{+916Vm~O9(v(?a`)c9-~Hi1^Z4MW2Tzah{`6!!Y5vE9qo)UtA8l?y-6sUHmfU}w zJbHYLX;9ejHs|a*pFxQO&JUjTv$CX41?$_WwiE??lYLmM8d<V!2*8tNM_e{||u>Ml8SSC^aX|=mIvyY_;E% z51Z*Z96R{WCg(UW#t1*lpRh&Jj-of<*j$;F7{6~f&7*yLMzQu&*1l01`RN!{b91Bt z(^-0&5A)fTXNBX8EqKH6;V!@3WbGZSDHhRmCD`yoWf6FD?hsYNPn-Mzr=Ll3Yt#Hj z50!e+eBGxjzL;J)ORI;IvNDV5(-p(^Hsy|P1@crY@G$ViGLYS@1v`jF4Ma8}B_1sa z!S_dZkN(zs za`*U0)u%E8MYxUx_o#2)jVsPtwW%uH$jUG!0MK7QTHE{Pr3T<$UH2RMQ1#P+8G0Kg zoS?~Zj3+@JiuVW#U|wp(k^HE%c)R;~qxoF}nuMKYe>B1{OfH%>He)~C*xr0gjj|pf zJDs1?*Q1~C)-A^Hl$9RBQsBqw24*_r=nE$K;w{do&IInEQ$n#i96hP*pwqGV+a~-X#)+3p zaDx%QTrJ?}<>`FwC(pXZ`O6H*jLwf8GX+@VQz_-E*&Qi}Mk>E86ot4*aLVkFKz+6| zhK3vRG|D*D9is>0JW@(06s!=Ovki2Kpx{#=_Vc0jT`(RfWjIA<0DWMn#$G4_qI%PM zdI%>0^dap!S@wpO_Yeym$3fp+3dK>D*>dKCyhP-1un`^y$nbQ8Hgn8lLU^RsK@)D# zO(SjTA>d6;2VvWDZwW^0c)4uhuMIVgTTD_oYyAr-nT;mE?K$F|;ApZaWe<@YquPNF zBqvblV&Tq%qZ?T?iyTd;E=uH_lzXVRh7@fFs&whZPDCZ=X^jsgNWU{n;Jg%qhLVOD zF>Vz_iisW{#ep|RZ*k^UX9uh}daUvRZ&0cBp>H7@O|rI%VSk$GV0hy}lW-M)96_FJ zZgllk*IitTAgH+QCIe2CXs}XnO`5@!;RvKA8XYvxBL6a4f*z?BI$t%RsU~uU9jRoQ`Owk&Zrarmhrh2e>Y%FQ zD&VgAb}Z{0Q9s9jVO+qrW*wEUp%Mm;H~@-obKG6xVPbrF$*vyOg@!F{#)&g?2DhNC zEg38+$|(>Ib1$n@f0{AeE(ayZJet@f#NoBIQHr+_ago_~UeQ;Ri6BaoO+rV;Ob>(h z+T&((X3%a4B1a;3bF7$+dWzRr6d2?!Qxq1!E{~kzRl{3i^R=XE1UGS&5y>Ht%@JG& z99krdQ#s3to=eyn?GBFnM1E7{6B1<*l|WNN!^S8X-2#uiCa}WXx>TICh`7lH>^P1Y zR^_FavpJCq+Qn7!FSRK6grA|dCbqtIQJm04=d9^P%QW#2*P|VQD@<$=Y>%o$y0c{!_I9>cec7Tnq|)%SGOo$_xxdb4CVza-T%c zWa5FvfM-Np#Rp=c$PsZp5yEvy2;Ylp(smAol|UM`0(}*2E2iqPtV~tkBZ6Q=-D7Jx zIv=Y+;09ppp+*Ol2I}MvHxYitF|VLjNPc>J|3PEZYZ@t9kFv{(ilWkvrZ1B8lLg0t zV-7z2w*_k)q;!@B4b&aYI6iiN-Ap1ub(=^^s`IRx{o}holyIwH9u5Te8)TT|9>kz| z|H7CTIG-Ixs7kJ+GM~+9*qfO20R7;hH0~@x4?Hd4?s}D@+8wBj5wN;R@&kx;V-u5r zK^UthD%fiR9LG~DhK0uo~P zK(VPA=|IDIH`#1VX!mLPN|NAEr^VF7{E~Fw!UbV(5>dh}j5K>70t=;6c!l{eouYMm zL<6SWf63j0XKmA{Nl>+=O<{ZuGR8EGYHk@+fuo;uR?EIr3JJI7UQOR7QzV~{3kxYQ&rt=DKm zd0V)a?5Tp|xSU$VaM*E?!3&eKegEKxgGb5X!S~0HA0OhjP3}E@^zh(^yZ71n3Hy7=Y-n|Ccz$3o+X-b38y9!(5Y7O8L1oJwx=3EGI#%u* ztzktU2*iJ=rg(32izv)q3G`;YyTk!YiufD>6cmMp= zF8vGtqvyA7-TwOa7hn9#?(Uzzxc%qbU*7)W>wmcg|GD+mza+PQ&llG}xbMT8i1GZve_Nj=L{>XNUjVhaNOYL+ zAmo3$$-6@s@crAjZvCZm>&wpVf9u}fy#pNG&&T&RsgKDOqpse#x1H?%Nis5$yKUZ)ikci%&vcy2iyb z?6Z_U?G`#_rdo^Ko+b(ch9^?j9Z8eRTY{J4S3r zw>fsc9ZiOqcL&}9R)u0-p@E+s9Nqg7YTW();PBx1Z#evi2gi>dJbjuxe0-GLO`hC6 zIzG7f^Woj22N;C%WB%2A* z<(|(MGA`3T%9)}T>soQ?%q&pWP5Wjx%)?&V-*-!FlD4L{Kt86~7?tPy4W;t1PDCh5 zN{R@w8uNC$s9)@KV3-&iWaaZYQoY~ioJ&|1u1)+r8TB*C0Gy*F(eI->3mOe^{^6hU zB0s~#a45c_G)bjzZJN}tm{%CRT4G;OKZJVdeADd}N4a!pjW((*#{++_S+ghPlAk zCHQ3bdGzu#d_KRycPq-gWr@Gy2bv|2yHJFFIL`lTA2K&mTWIK6w1-MYr2c)Fbfu z-J>6V#=MdEbaV4ZSm_~(_R-(@EYfP|?|2M&r_sGM%`jy;EXpQZpILsF37cl@IGk`o z)C=qjwODROnWU642Z4~_HaDLdtOlJMimRd*N&7<*akz^D)fKcUPhQF| z-O-n*OiP6rSIe10uEj2Zl)zz#7VBOBDbRwWFJZ8@y#UjdR?Q$)6Q{`PJPuQO6(H-DeZFfkCGvN0S=@ZU8ERn|heN zNh+Da6}V>9m~ym%#the+ifX z3o0jtW-nD0u@@?|bd~n|)$y)3x0~w4$smhtJ=1-fqM8YP$x4k{;36k4VYnS=o<6i_ z`)|VM7AfB}|1#sITx5OY{mWjVn@=$;`*ePesfFR4sLQ{?_l|C@?}TUiM%<4y<2Zg6 z()Jo?8U24o|C#cCOZg|)e+%{30w1Dl>G!(PyLWf0r7ecyDNV%DU2YcKg(Ge5s< z?zV*eZiEF_=3xvMqx~|j7ur#v6s5G#TZVn83!Z9hu)8Tg?Z4#LZSG=JBE}@**)Ml~ z#pT=Cfs4g_b-&SPL|Eq7V!hfgCHDqm{vq!#6b`ddCwGTs!3ALsBmibhz(b@G(MU^& zFNsmbD=)c0noxuhWW5>i>{(wlk@}X~jz*F_d+|uPk}9bN=gh(YBaR;NhQD-J8#?AU z-{IMjb;P%vC4N)T^OZY%Gw!al5#WGI6Jc_PhI4288{omw(c_~%*aJ|xW!Vn8Z5pP$ zU3$lZ=}q%CPDQE$_iO;SmkW?I;edC2G0oHJ3( z+g7+7kyrM?!eJpvAVNbw&QVSf+7p`=yEb~-4~UU4kp9#<-OP+KD-6kviSZ#B<83n_ z8BUiDWp&|REQ_LN!e{`-mK&+kx06i}?jIdI`e9GV8_Z`DSWuW=N2n&fHz5rY!O#~> zSb#*`2L$gEDwq@IJAePZqnzwD?VMGo$u{H8S8STt^!}0{0LBz&`8;`X z^X~I|KfUO&siXJfgS+=19Nj>r!Zs=uj8-8DUWefVEO8cVJCJ8F@at?iE7Wt`_Q~rz z>hdiPMUEHi-py^VfkxB$mNb-?I0O2;xv{aK;m;;}1H9+2doOP8?d-JV!5+NUPV1%X zD_`G1^9%%sMvdRR-F|MJUXEM!UEbqtPC8-=6Vo6|6Pq#OF3d{cB`)rMDkF)x*&~H;yaR(@jwe!)k8? zKjKz7Lk{B&;A~|CYt;4joqLf>2g?pQM{BU;-LO2Y&$#P9Nv9;eD~;w zeZn-_LT5L=9OOCYI`3YIv+2{Ldk+r|ADAsErHq7G?p!r@`a7HwDcF)yH*kl8zy8Ge zRbRySfm^BHi)-lj!tK`!rjb49!AeRU6OV#}`^H^?`bvGTQVSi)Z)_)TRabiJPV&B` zZS|{%faF-zjQzfM9-V^WqEqk?#_)R{0&ah`GoaeKYu^0Bl{f$JV>iEfgLQVHR$6IC zd2{4#DOHnR*N)lg_*(-ppVS!cNm?=(T0d5(J=5Y@C@9 zp*RLchw%bc@tmTeeWnI}-gKlI!qj#1XgG@GNZMm~aE+#)+0-fc>F=S7tM; zOOlSh1a6M_NZ7=0?EA@00zzupd{|gXh55~monPJdcPM#Ev<3WOg8%t#a|5Vully-e ze-)r+@AF@~ zFK#y5?bb_b&^`2|ee^P!TMYMBI@UhS{uDlCsi>X|(Mm<2vON>pD9} zgE=HHPk8^3{Dtawb}x`FRS~VRMzd*7F27TCYZCW(lIprr>98osbRu@R9W=uk{NC~F zf^QZZ+dV&rS0+ogG%!NI8zZA53_rKzD5XOU`nJ!GNcoD3gnQxNIA5>H#SNb2Q}l^E z-$w(Hc0qILXUEfW%nKEY9B--{&5%6MeOB%iJ3GP&@knfmU{of0%S}h-_j|EMzZW0Y zuguMY+wDMn^UEw730w=qU9civ%sK`gj=cn+<2j1JWvJHxRwuj*kaFXg(H9Oq|0e01 z`79rnY>p?(gQwu|pweweQ4^xE_pGRqp>W)Pl13&;?&-_Iz>Xf=z5mk#;Q*ZbekMLa zj5dO71ltD5*i3JMMr-1D@EYU}tuL#4zY_nWm#VG~-T#v;dxfzHv5U1$cw=elydcd3 zb0>O}UlRKx{&(UcCTbF%bTw4QmW@q8vR{o){A<@I9tD}bZbqCc8&gD@%KUg|5rnd5?#5E#s2@hU*7t%;{X5UmtTMK z|NkTYJpX@Q*Q8?rnh2*ad$U6>MV8?yugBZ}-yEO+-CCc2_V)ktir)TE`WK*bNc~T* zl4D?-kAZj2u9Cmb=-==9SHMw~UAQ2>;o|>GeEVas`aj*df9sQX|9@rge%X+WUV%bl zPGjZGsFtI4GGTa8_6npuc)q|l5O-9Go`e&D{h1X|=dW6>Baf{wp?J8HHyl~LTP@co z5PkR_6~e(1B#qf@^ZyDNgR%!lnZaPX7AW zlLwCT@`*`0xD(PY;eB+$V?bPRH}G~)b z0uLpSc|+O&E_U&IPMRU7LB@fhwN(8GXlh*5r#S^PIvqTCOoDTingRx;%!2M z`d9;vws;P2ZJRkY`&qW6^TT)kuQY?xY_<=_#>S4pgCKegaYmmdW}9r*X3(o1o8=vP zW^KA#q-EhE7u6zg1drqJMH+a92a>Ay#s!RPzcDTvo1QI6`&X}8^XS4kYhDvqh_|k) zFg{2F173Vl3{9pwAx}aOdX#0rsGMoB-dX>!_Q?%87bn}#f2H%$Y@h75NztyEf0}fy z^zI)V3C;sDF1g@F1$AMg=EYPX*tM+7MQ2mmVi zeQ<`C$Zd5x+;E;E{`2j?8_{(COD4CdQQsncr6Uh}R06P=+a>?)ixeSNOm!f@<8um| zAhuX63YZDEMDr}?I1~9hNq#IYGojw51-Km0^pek@(phqYc_<)g)akY!gmieBUX{ex zOvokNPN1T;SVI~xce8xV0)vQ3-7DCn(>Y@XyWJc2LEz-z#+=UFFeemE;A*h;Sx)B* zy8*Fd5L;fGp&7F09N#--eD4vbWtK=KA+D7y-mKOqymOl>D;=7Jt#X;gb~G(Xr}AR(v3w zNH=gz4khmStE(=0ko2*C(*!Bi;SycYINcX4W1i13!L}Mu1~`0T*bA-x@aXYR*1m(( zLzYURviT41m8+ffv_Hts&M)%6zZ#Cl#pE~G74z4ZZ?68abNBmu_a8j`;m3pj^Y4d0 zJ$n4){~kR({`o(CdG@#ex6`UNRqj0hwZ6uSo!-v5u?wTy&x2z##@qje1}N1u2i?xE zTRWefHt2KNZtB(7ZktCq!R_X4c;I#^KjKofoBX=%hFOkp%=tpbLU}P=^m}fMj7t$q z1|G9CX@x`WT_yH}lO3-=nk1bvcy5MfU9Idg!TFhwg#_a->^J663v(;-AJwG6;?cz> zoF7N8y~_SLOu6uibb0{s%-DidKSF*oaQZn?T6HUyz{|y9&mJn9PT|JDV|F1JR>KT0 zPJ_k8?kWuu^E-nEYqUB8w++fGudWnroBW$juNjUBx#vaoi8-{Qv6YS5g|+D0IzPC3 zcB5Q`6#?xhX5GigVv(pPvng8;nN~t=S2#h#xpq+s>2@~*fkt8Fp#CDrsbn$cRC4>1 z9q!ZLr@v2spZ-4mefs1J%f1mz7{eAlT^!MrS)8D7RPk*2OKK*_A`}Fte b@6+F>zfXUk{yzQv0e}A=Sf%;10GJ^F)29}m diff --git a/misc/tools/kconfig-frontends/.version b/misc/tools/kconfig-frontends/.version new file mode 100644 index 0000000000..a512a0944e --- /dev/null +++ b/misc/tools/kconfig-frontends/.version @@ -0,0 +1,2 @@ +3.6.0 a0d271cbfed1dd50278c6b06bead3d00ba0a88f9 Terrified Chipmunk +0 diff --git a/misc/tools/kconfig-frontends/AUTHORS b/misc/tools/kconfig-frontends/AUTHORS new file mode 100644 index 0000000000..ca1c7adf1e --- /dev/null +++ b/misc/tools/kconfig-frontends/AUTHORS @@ -0,0 +1,14 @@ +Authors of kconfig-frontends. + +The developers of the Linux kernel are the original authors of the kconfig +parser and frontends. The list is too long to reproduce here, but you can +get a pretty complete list from the Linux kernel repository logs: + git shortlog scripts/kconfig + +The packaging uses the GNU autotools build system, of which I +will not try to list the many authors here. + +The initial packaging was done by: + "Yann E. MORIN" + +For a complete list, see the commit-logs of the kconfig repository. diff --git a/misc/tools/kconfig-frontends/COPYING b/misc/tools/kconfig-frontends/COPYING new file mode 100644 index 0000000000..828506f762 --- /dev/null +++ b/misc/tools/kconfig-frontends/COPYING @@ -0,0 +1,357 @@ + +The kconfig parser and frontends are extracted from the Linux kernel +source tree, which is covered by the GPLv2 only. As Linus Torvalds puts it: + + > Also note that the only valid version of the GPL as far as the kernel + > is concerned is _this_ particular version of the license (ie v2, not + > v2.2 or v3.x or whatever), unless explicitly otherwise stated. + +Although the above quote explictly mentions the Linux kernel, it is my +understanding that the whole Linux kernel source tree is covered by this +sentence, even non-kernel source code. As such, the license that applies +to the kconfig parser and frontends, as published in this package, are +also covered by this sentence, and available under the GPLv2, and not any +other version of the GPL, unless otherwise stated. + +---------------------------------------- + + GNU GENERAL PUBLIC LICENSE + Version 2, June 1991 + + Copyright (C) 1989, 1991 Free Software Foundation, Inc. + 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The licenses for most software are designed to take away your +freedom to share and change it. By contrast, the GNU General Public +License is intended to guarantee your freedom to share and change free +software--to make sure the software is free for all its users. This +General Public License applies to most of the Free Software +Foundation's software and to any other program whose authors commit to +using it. (Some other Free Software Foundation software is covered by +the GNU Library General Public License instead.) You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +this service if you wish), that you receive source code or can get it +if you want it, that you can change the software or use pieces of it +in new free programs; and that you know you can do these things. + + To protect your rights, we need to make restrictions that forbid +anyone to deny you these rights or to ask you to surrender the rights. +These restrictions translate to certain responsibilities for you if you +distribute copies of the software, or if you modify it. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must give the recipients all the rights that +you have. You must make sure that they, too, receive or can get the +source code. And you must show them these terms so they know their +rights. + + We protect your rights with two steps: (1) copyright the software, and +(2) offer you this license which gives you legal permission to copy, +distribute and/or modify the software. + + Also, for each author's protection and ours, we want to make certain +that everyone understands that there is no warranty for this free +software. If the software is modified by someone else and passed on, we +want its recipients to know that what they have is not the original, so +that any problems introduced by others will not reflect on the original +authors' reputations. + + Finally, any free program is threatened constantly by software +patents. We wish to avoid the danger that redistributors of a free +program will individually obtain patent licenses, in effect making the +program proprietary. To prevent this, we have made it clear that any +patent must be licensed for everyone's free use or not licensed at all. + + The precise terms and conditions for copying, distribution and +modification follow. + + GNU GENERAL PUBLIC LICENSE + TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION + + 0. This License applies to any program or other work which contains +a notice placed by the copyright holder saying it may be distributed +under the terms of this General Public License. The "Program", below, +refers to any such program or work, and a "work based on the Program" +means either the Program or any derivative work under copyright law: +that is to say, a work containing the Program or a portion of it, +either verbatim or with modifications and/or translated into another +language. (Hereinafter, translation is included without limitation in +the term "modification".) Each licensee is addressed as "you". + +Activities other than copying, distribution and modification are not +covered by this License; they are outside its scope. The act of +running the Program is not restricted, and the output from the Program +is covered only if its contents constitute a work based on the +Program (independent of having been made by running the Program). +Whether that is true depends on what the Program does. + + 1. You may copy and distribute verbatim copies of the Program's +source code as you receive it, in any medium, provided that you +conspicuously and appropriately publish on each copy an appropriate +copyright notice and disclaimer of warranty; keep intact all the +notices that refer to this License and to the absence of any warranty; +and give any other recipients of the Program a copy of this License +along with the Program. + +You may charge a fee for the physical act of transferring a copy, and +you may at your option offer warranty protection in exchange for a fee. + + 2. You may modify your copy or copies of the Program or any portion +of it, thus forming a work based on the Program, and copy and +distribute such modifications or work under the terms of Section 1 +above, provided that you also meet all of these conditions: + + a) You must cause the modified files to carry prominent notices + stating that you changed the files and the date of any change. + + b) You must cause any work that you distribute or publish, that in + whole or in part contains or is derived from the Program or any + part thereof, to be licensed as a whole at no charge to all third + parties under the terms of this License. + + c) If the modified program normally reads commands interactively + when run, you must cause it, when started running for such + interactive use in the most ordinary way, to print or display an + announcement including an appropriate copyright notice and a + notice that there is no warranty (or else, saying that you provide + a warranty) and that users may redistribute the program under + these conditions, and telling the user how to view a copy of this + License. (Exception: if the Program itself is interactive but + does not normally print such an announcement, your work based on + the Program is not required to print an announcement.) + +These requirements apply to the modified work as a whole. If +identifiable sections of that work are not derived from the Program, +and can be reasonably considered independent and separate works in +themselves, then this License, and its terms, do not apply to those +sections when you distribute them as separate works. But when you +distribute the same sections as part of a whole which is a work based +on the Program, the distribution of the whole must be on the terms of +this License, whose permissions for other licensees extend to the +entire whole, and thus to each and every part regardless of who wrote it. + +Thus, it is not the intent of this section to claim rights or contest +your rights to work written entirely by you; rather, the intent is to +exercise the right to control the distribution of derivative or +collective works based on the Program. + +In addition, mere aggregation of another work not based on the Program +with the Program (or with a work based on the Program) on a volume of +a storage or distribution medium does not bring the other work under +the scope of this License. + + 3. You may copy and distribute the Program (or a work based on it, +under Section 2) in object code or executable form under the terms of +Sections 1 and 2 above provided that you also do one of the following: + + a) Accompany it with the complete corresponding machine-readable + source code, which must be distributed under the terms of Sections + 1 and 2 above on a medium customarily used for software interchange; or, + + b) Accompany it with a written offer, valid for at least three + years, to give any third party, for a charge no more than your + cost of physically performing source distribution, a complete + machine-readable copy of the corresponding source code, to be + distributed under the terms of Sections 1 and 2 above on a medium + customarily used for software interchange; or, + + c) Accompany it with the information you received as to the offer + to distribute corresponding source code. (This alternative is + allowed only for noncommercial distribution and only if you + received the program in object code or executable form with such + an offer, in accord with Subsection b above.) + +The source code for a work means the preferred form of the work for +making modifications to it. For an executable work, complete source +code means all the source code for all modules it contains, plus any +associated interface definition files, plus the scripts used to +control compilation and installation of the executable. However, as a +special exception, the source code distributed need not include +anything that is normally distributed (in either source or binary +form) with the major components (compiler, kernel, and so on) of the +operating system on which the executable runs, unless that component +itself accompanies the executable. + +If distribution of executable or object code is made by offering +access to copy from a designated place, then offering equivalent +access to copy the source code from the same place counts as +distribution of the source code, even though third parties are not +compelled to copy the source along with the object code. + + 4. You may not copy, modify, sublicense, or distribute the Program +except as expressly provided under this License. Any attempt +otherwise to copy, modify, sublicense or distribute the Program is +void, and will automatically terminate your rights under this License. +However, parties who have received copies, or rights, from you under +this License will not have their licenses terminated so long as such +parties remain in full compliance. + + 5. You are not required to accept this License, since you have not +signed it. However, nothing else grants you permission to modify or +distribute the Program or its derivative works. These actions are +prohibited by law if you do not accept this License. Therefore, by +modifying or distributing the Program (or any work based on the +Program), you indicate your acceptance of this License to do so, and +all its terms and conditions for copying, distributing or modifying +the Program or works based on it. + + 6. Each time you redistribute the Program (or any work based on the +Program), the recipient automatically receives a license from the +original licensor to copy, distribute or modify the Program subject to +these terms and conditions. You may not impose any further +restrictions on the recipients' exercise of the rights granted herein. +You are not responsible for enforcing compliance by third parties to +this License. + + 7. If, as a consequence of a court judgment or allegation of patent +infringement or for any other reason (not limited to patent issues), +conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot +distribute so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you +may not distribute the Program at all. For example, if a patent +license would not permit royalty-free redistribution of the Program by +all those who receive copies directly or indirectly through you, then +the only way you could satisfy both it and this License would be to +refrain entirely from distribution of the Program. + +If any portion of this section is held invalid or unenforceable under +any particular circumstance, the balance of the section is intended to +apply and the section as a whole is intended to apply in other +circumstances. + +It is not the purpose of this section to induce you to infringe any +patents or other property right claims or to contest validity of any +such claims; this section has the sole purpose of protecting the +integrity of the free software distribution system, which is +implemented by public license practices. Many people have made +generous contributions to the wide range of software distributed +through that system in reliance on consistent application of that +system; it is up to the author/donor to decide if he or she is willing +to distribute software through any other system and a licensee cannot +impose that choice. + +This section is intended to make thoroughly clear what is believed to +be a consequence of the rest of this License. + + 8. If the distribution and/or use of the Program is restricted in +certain countries either by patents or by copyrighted interfaces, the +original copyright holder who places the Program under this License +may add an explicit geographical distribution limitation excluding +those countries, so that distribution is permitted only in or among +countries not thus excluded. In such case, this License incorporates +the limitation as if written in the body of this License. + + 9. The Free Software Foundation may publish revised and/or new versions +of the General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + +Each version is given a distinguishing version number. If the Program +specifies a version number of this License which applies to it and "any +later version", you have the option of following the terms and conditions +either of that version or of any later version published by the Free +Software Foundation. If the Program does not specify a version number of +this License, you may choose any version ever published by the Free Software +Foundation. + + 10. If you wish to incorporate parts of the Program into other free +programs whose distribution conditions are different, write to the author +to ask for permission. For software which is copyrighted by the Free +Software Foundation, write to the Free Software Foundation; we sometimes +make exceptions for this. Our decision will be guided by the two goals +of preserving the free status of all derivatives of our free software and +of promoting the sharing and reuse of software generally. + + NO WARRANTY + + 11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY +FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN +OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES +PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED +OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF +MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS +TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE +PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, +REPAIR OR CORRECTION. + + 12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR +REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, +INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING +OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED +TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY +YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER +PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE +POSSIBILITY OF SUCH DAMAGES. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +convey the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 2 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + + +Also add information on how to contact you by electronic and paper mail. + +If the program is interactive, make it output a short notice like this +when it starts in an interactive mode: + + Gnomovision version 69, Copyright (C) year name of author + Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, the commands you use may +be called something other than `show w' and `show c'; they could even be +mouse-clicks or menu items--whatever suits your program. + +You should also get your employer (if you work as a programmer) or your +school, if any, to sign a "copyright disclaimer" for the program, if +necessary. Here is a sample; alter the names: + + Yoyodyne, Inc., hereby disclaims all copyright interest in the program + `Gnomovision' (which makes passes at compilers) written by James Hacker. + + , 1 April 1989 + Ty Coon, President of Vice + +This General Public License does not permit incorporating your program into +proprietary programs. If your program is a subroutine library, you may +consider it more useful to permit linking proprietary applications with the +library. If this is what you want to do, use the GNU Library General +Public License instead of this License. diff --git a/misc/tools/kconfig-frontends/INSTALL b/misc/tools/kconfig-frontends/INSTALL new file mode 100644 index 0000000000..7d1c323bea --- /dev/null +++ b/misc/tools/kconfig-frontends/INSTALL @@ -0,0 +1,365 @@ +Installation Instructions +************************* + +Copyright (C) 1994, 1995, 1996, 1999, 2000, 2001, 2002, 2004, 2005, +2006, 2007, 2008, 2009 Free Software Foundation, Inc. + + Copying and distribution of this file, with or without modification, +are permitted in any medium without royalty provided the copyright +notice and this notice are preserved. This file is offered as-is, +without warranty of any kind. + +Basic Installation +================== + + Briefly, the shell commands `./configure; make; make install' should +configure, build, and install this package. The following +more-detailed instructions are generic; see the `README' file for +instructions specific to this package. Some packages provide this +`INSTALL' file but do not implement all of the features documented +below. The lack of an optional feature in a given package is not +necessarily a bug. More recommendations for GNU packages can be found +in *note Makefile Conventions: (standards)Makefile Conventions. + + The `configure' shell script attempts to guess correct values for +various system-dependent variables used during compilation. It uses +those values to create a `Makefile' in each directory of the package. +It may also create one or more `.h' files containing system-dependent +definitions. Finally, it creates a shell script `config.status' that +you can run in the future to recreate the current configuration, and a +file `config.log' containing compiler output (useful mainly for +debugging `configure'). + + It can also use an optional file (typically called `config.cache' +and enabled with `--cache-file=config.cache' or simply `-C') that saves +the results of its tests to speed up reconfiguring. Caching is +disabled by default to prevent problems with accidental use of stale +cache files. + + If you need to do unusual things to compile the package, please try +to figure out how `configure' could check whether to do them, and mail +diffs or instructions to the address given in the `README' so they can +be considered for the next release. If you are using the cache, and at +some point `config.cache' contains results you don't want to keep, you +may remove or edit it. + + The file `configure.ac' (or `configure.in') is used to create +`configure' by a program called `autoconf'. You need `configure.ac' if +you want to change it or regenerate `configure' using a newer version +of `autoconf'. + + The simplest way to compile this package is: + + 1. `cd' to the directory containing the package's source code and type + `./configure' to configure the package for your system. + + Running `configure' might take a while. While running, it prints + some messages telling which features it is checking for. + + 2. Type `make' to compile the package. + + 3. Optionally, type `make check' to run any self-tests that come with + the package, generally using the just-built uninstalled binaries. + + 4. Type `make install' to install the programs and any data files and + documentation. When installing into a prefix owned by root, it is + recommended that the package be configured and built as a regular + user, and only the `make install' phase executed with root + privileges. + + 5. Optionally, type `make installcheck' to repeat any self-tests, but + this time using the binaries in their final installed location. + This target does not install anything. Running this target as a + regular user, particularly if the prior `make install' required + root privileges, verifies that the installation completed + correctly. + + 6. You can remove the program binaries and object files from the + source code directory by typing `make clean'. To also remove the + files that `configure' created (so you can compile the package for + a different kind of computer), type `make distclean'. There is + also a `make maintainer-clean' target, but that is intended mainly + for the package's developers. If you use it, you may have to get + all sorts of other programs in order to regenerate files that came + with the distribution. + + 7. Often, you can also type `make uninstall' to remove the installed + files again. In practice, not all packages have tested that + uninstallation works correctly, even though it is required by the + GNU Coding Standards. + + 8. Some packages, particularly those that use Automake, provide `make + distcheck', which can by used by developers to test that all other + targets like `make install' and `make uninstall' work correctly. + This target is generally not run by end users. + +Compilers and Options +===================== + + Some systems require unusual options for compilation or linking that +the `configure' script does not know about. Run `./configure --help' +for details on some of the pertinent environment variables. + + You can give `configure' initial values for configuration parameters +by setting variables in the command line or in the environment. Here +is an example: + + ./configure CC=c99 CFLAGS=-g LIBS=-lposix + + *Note Defining Variables::, for more details. + +Compiling For Multiple Architectures +==================================== + + You can compile the package for more than one kind of computer at the +same time, by placing the object files for each architecture in their +own directory. To do this, you can use GNU `make'. `cd' to the +directory where you want the object files and executables to go and run +the `configure' script. `configure' automatically checks for the +source code in the directory that `configure' is in and in `..'. This +is known as a "VPATH" build. + + With a non-GNU `make', it is safer to compile the package for one +architecture at a time in the source code directory. After you have +installed the package for one architecture, use `make distclean' before +reconfiguring for another architecture. + + On MacOS X 10.5 and later systems, you can create libraries and +executables that work on multiple system types--known as "fat" or +"universal" binaries--by specifying multiple `-arch' options to the +compiler but only a single `-arch' option to the preprocessor. Like +this: + + ./configure CC="gcc -arch i386 -arch x86_64 -arch ppc -arch ppc64" \ + CXX="g++ -arch i386 -arch x86_64 -arch ppc -arch ppc64" \ + CPP="gcc -E" CXXCPP="g++ -E" + + This is not guaranteed to produce working output in all cases, you +may have to build one architecture at a time and combine the results +using the `lipo' tool if you have problems. + +Installation Names +================== + + By default, `make install' installs the package's commands under +`/usr/local/bin', include files under `/usr/local/include', etc. You +can specify an installation prefix other than `/usr/local' by giving +`configure' the option `--prefix=PREFIX', where PREFIX must be an +absolute file name. + + You can specify separate installation prefixes for +architecture-specific files and architecture-independent files. If you +pass the option `--exec-prefix=PREFIX' to `configure', the package uses +PREFIX as the prefix for installing programs and libraries. +Documentation and other data files still use the regular prefix. + + In addition, if you use an unusual directory layout you can give +options like `--bindir=DIR' to specify different values for particular +kinds of files. Run `configure --help' for a list of the directories +you can set and what kinds of files go in them. In general, the +default for these options is expressed in terms of `${prefix}', so that +specifying just `--prefix' will affect all of the other directory +specifications that were not explicitly provided. + + The most portable way to affect installation locations is to pass the +correct locations to `configure'; however, many packages provide one or +both of the following shortcuts of passing variable assignments to the +`make install' command line to change installation locations without +having to reconfigure or recompile. + + The first method involves providing an override variable for each +affected directory. For example, `make install +prefix=/alternate/directory' will choose an alternate location for all +directory configuration variables that were expressed in terms of +`${prefix}'. Any directories that were specified during `configure', +but not in terms of `${prefix}', must each be overridden at install +time for the entire installation to be relocated. The approach of +makefile variable overrides for each directory variable is required by +the GNU Coding Standards, and ideally causes no recompilation. +However, some platforms have known limitations with the semantics of +shared libraries that end up requiring recompilation when using this +method, particularly noticeable in packages that use GNU Libtool. + + The second method involves providing the `DESTDIR' variable. For +example, `make install DESTDIR=/alternate/directory' will prepend +`/alternate/directory' before all installation names. The approach of +`DESTDIR' overrides is not required by the GNU Coding Standards, and +does not work on platforms that have drive letters. On the other hand, +it does better at avoiding recompilation issues, and works well even +when some directory options were not specified in terms of `${prefix}' +at `configure' time. + +Optional Features +================= + + If the package supports it, you can cause programs to be installed +with an extra prefix or suffix on their names by giving `configure' the +option `--program-prefix=PREFIX' or `--program-suffix=SUFFIX'. + + Some packages pay attention to `--enable-FEATURE' options to +`configure', where FEATURE indicates an optional part of the package. +They may also pay attention to `--with-PACKAGE' options, where PACKAGE +is something like `gnu-as' or `x' (for the X Window System). The +`README' should mention any `--enable-' and `--with-' options that the +package recognizes. + + For packages that use the X Window System, `configure' can usually +find the X include and library files automatically, but if it doesn't, +you can use the `configure' options `--x-includes=DIR' and +`--x-libraries=DIR' to specify their locations. + + Some packages offer the ability to configure how verbose the +execution of `make' will be. For these packages, running `./configure +--enable-silent-rules' sets the default to minimal output, which can be +overridden with `make V=1'; while running `./configure +--disable-silent-rules' sets the default to verbose, which can be +overridden with `make V=0'. + +Particular systems +================== + + On HP-UX, the default C compiler is not ANSI C compatible. If GNU +CC is not installed, it is recommended to use the following options in +order to use an ANSI C compiler: + + ./configure CC="cc -Ae -D_XOPEN_SOURCE=500" + +and if that doesn't work, install pre-built binaries of GCC for HP-UX. + + On OSF/1 a.k.a. Tru64, some versions of the default C compiler cannot +parse its `' header file. The option `-nodtk' can be used as +a workaround. If GNU CC is not installed, it is therefore recommended +to try + + ./configure CC="cc" + +and if that doesn't work, try + + ./configure CC="cc -nodtk" + + On Solaris, don't put `/usr/ucb' early in your `PATH'. This +directory contains several dysfunctional programs; working variants of +these programs are available in `/usr/bin'. So, if you need `/usr/ucb' +in your `PATH', put it _after_ `/usr/bin'. + + On Haiku, software installed for all users goes in `/boot/common', +not `/usr/local'. It is recommended to use the following options: + + ./configure --prefix=/boot/common + +Specifying the System Type +========================== + + There may be some features `configure' cannot figure out +automatically, but needs to determine by the type of machine the package +will run on. Usually, assuming the package is built to be run on the +_same_ architectures, `configure' can figure that out, but if it prints +a message saying it cannot guess the machine type, give it the +`--build=TYPE' option. TYPE can either be a short name for the system +type, such as `sun4', or a canonical name which has the form: + + CPU-COMPANY-SYSTEM + +where SYSTEM can have one of these forms: + + OS + KERNEL-OS + + See the file `config.sub' for the possible values of each field. If +`config.sub' isn't included in this package, then this package doesn't +need to know the machine type. + + If you are _building_ compiler tools for cross-compiling, you should +use the option `--target=TYPE' to select the type of system they will +produce code for. + + If you want to _use_ a cross compiler, that generates code for a +platform different from the build platform, you should specify the +"host" platform (i.e., that on which the generated programs will +eventually be run) with `--host=TYPE'. + +Sharing Defaults +================ + + If you want to set default values for `configure' scripts to share, +you can create a site shell script called `config.site' that gives +default values for variables like `CC', `cache_file', and `prefix'. +`configure' looks for `PREFIX/share/config.site' if it exists, then +`PREFIX/etc/config.site' if it exists. Or, you can set the +`CONFIG_SITE' environment variable to the location of the site script. +A warning: not all `configure' scripts look for a site script. + +Defining Variables +================== + + Variables not defined in a site shell script can be set in the +environment passed to `configure'. However, some packages may run +configure again during the build, and the customized values of these +variables may be lost. In order to avoid this problem, you should set +them in the `configure' command line, using `VAR=value'. For example: + + ./configure CC=/usr/local2/bin/gcc + +causes the specified `gcc' to be used as the C compiler (unless it is +overridden in the site shell script). + +Unfortunately, this technique does not work for `CONFIG_SHELL' due to +an Autoconf bug. Until the bug is fixed you can use this workaround: + + CONFIG_SHELL=/bin/bash /bin/bash ./configure CONFIG_SHELL=/bin/bash + +`configure' Invocation +====================== + + `configure' recognizes the following options to control how it +operates. + +`--help' +`-h' + Print a summary of all of the options to `configure', and exit. + +`--help=short' +`--help=recursive' + Print a summary of the options unique to this package's + `configure', and exit. The `short' variant lists options used + only in the top level, while the `recursive' variant lists options + also present in any nested packages. + +`--version' +`-V' + Print the version of Autoconf used to generate the `configure' + script, and exit. + +`--cache-file=FILE' + Enable the cache: use and save the results of the tests in FILE, + traditionally `config.cache'. FILE defaults to `/dev/null' to + disable caching. + +`--config-cache' +`-C' + Alias for `--cache-file=config.cache'. + +`--quiet' +`--silent' +`-q' + Do not print messages saying which checks are being made. To + suppress all normal output, redirect it to `/dev/null' (any error + messages will still be shown). + +`--srcdir=DIR' + Look for the package's source code in directory DIR. Usually + `configure' can determine that directory automatically. + +`--prefix=DIR' + Use DIR as the installation prefix. *note Installation Names:: + for more details, including other options available for fine-tuning + the installation locations. + +`--no-create' +`-n' + Run the configure checks, but stop before creating any output + files. + +`configure' also accepts some other, not widely useful, options. Run +`configure --help' for more details. + diff --git a/misc/tools/kconfig-frontends/Makefile.am b/misc/tools/kconfig-frontends/Makefile.am new file mode 100644 index 0000000000..c3bec4596d --- /dev/null +++ b/misc/tools/kconfig-frontends/Makefile.am @@ -0,0 +1,7 @@ +ACLOCAL_AMFLAGS = -I scripts/.autostuff/m4 +MAKEFLAGS = $(SILENT_MAKEFLAGS) +if COND_utils + MAYBE_utils = utils +endif +SUBDIRS = docs libs frontends scripts $(MAYBE_utils) +EXTRA_DIST = bootstrap .version diff --git a/misc/tools/kconfig-frontends/Makefile.in b/misc/tools/kconfig-frontends/Makefile.in new file mode 100644 index 0000000000..049f42eb50 --- /dev/null +++ b/misc/tools/kconfig-frontends/Makefile.in @@ -0,0 +1,778 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +subdir = . +DIST_COMMON = README $(am__configure_deps) $(srcdir)/Makefile.am \ + $(srcdir)/Makefile.in $(top_srcdir)/configure \ + $(top_srcdir)/scripts/.autostuff/config.h.in AUTHORS COPYING \ + INSTALL scripts/.autostuff/scripts/compile \ + scripts/.autostuff/scripts/config.guess \ + scripts/.autostuff/scripts/config.sub \ + scripts/.autostuff/scripts/depcomp \ + scripts/.autostuff/scripts/install-sh \ + scripts/.autostuff/scripts/ltmain.sh \ + scripts/.autostuff/scripts/missing \ + scripts/.autostuff/scripts/ylwrap +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +am__CONFIG_DISTCLEAN_FILES = config.status config.cache config.log \ + configure.lineno config.status.lineno +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +SOURCES = +DIST_SOURCES = +RECURSIVE_TARGETS = all-recursive check-recursive dvi-recursive \ + html-recursive info-recursive install-data-recursive \ + install-dvi-recursive install-exec-recursive \ + install-html-recursive install-info-recursive \ + install-pdf-recursive install-ps-recursive install-recursive \ + installcheck-recursive installdirs-recursive pdf-recursive \ + ps-recursive uninstall-recursive +RECURSIVE_CLEAN_TARGETS = mostlyclean-recursive clean-recursive \ + distclean-recursive maintainer-clean-recursive +AM_RECURSIVE_TARGETS = $(RECURSIVE_TARGETS:-recursive=) \ + $(RECURSIVE_CLEAN_TARGETS:-recursive=) tags TAGS ctags CTAGS \ + distdir dist dist-all distcheck +ETAGS = etags +CTAGS = ctags +DIST_SUBDIRS = docs libs frontends scripts utils +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +distdir = $(PACKAGE)-$(VERSION) +top_distdir = $(distdir) +am__remove_distdir = \ + { test ! -d "$(distdir)" \ + || { find "$(distdir)" -type d ! -perm -200 -exec chmod u+w {} ';' \ + && rm -fr "$(distdir)"; }; } +am__relativize = \ + dir0=`pwd`; \ + sed_first='s,^\([^/]*\)/.*$$,\1,'; \ + sed_rest='s,^[^/]*/*,,'; \ + sed_last='s,^.*/\([^/]*\)$$,\1,'; \ + sed_butlast='s,/*[^/]*$$,,'; \ + while test -n "$$dir1"; do \ + first=`echo "$$dir1" | sed -e "$$sed_first"`; \ + if test "$$first" != "."; then \ + if test "$$first" = ".."; then \ + dir2=`echo "$$dir0" | sed -e "$$sed_last"`/"$$dir2"; \ + dir0=`echo "$$dir0" | sed -e "$$sed_butlast"`; \ + else \ + first2=`echo "$$dir2" | sed -e "$$sed_first"`; \ + if test "$$first2" = "$$first"; then \ + dir2=`echo "$$dir2" | sed -e "$$sed_rest"`; \ + else \ + dir2="../$$dir2"; \ + fi; \ + dir0="$$dir0"/"$$first"; \ + fi; \ + fi; \ + dir1=`echo "$$dir1" | sed -e "$$sed_rest"`; \ + done; \ + reldir="$$dir2" +DIST_ARCHIVES = $(distdir).tar.gz +GZIP_ENV = --best +distuninstallcheck_listfiles = find . -type f -print +distcleancheck_listfiles = find . -type f -print +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +ACLOCAL_AMFLAGS = -I scripts/.autostuff/m4 +MAKEFLAGS = $(SILENT_MAKEFLAGS) +@COND_utils_TRUE@MAYBE_utils = utils +SUBDIRS = docs libs frontends scripts $(MAYBE_utils) +EXTRA_DIST = bootstrap .version +all: all-recursive + +.SUFFIXES: +am--refresh: + @: +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + echo ' cd $(srcdir) && $(AUTOMAKE) --foreign'; \ + $(am__cd) $(srcdir) && $(AUTOMAKE) --foreign \ + && exit 0; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + echo ' $(SHELL) ./config.status'; \ + $(SHELL) ./config.status;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + $(SHELL) ./config.status --recheck + +$(top_srcdir)/configure: $(am__configure_deps) + $(am__cd) $(srcdir) && $(AUTOCONF) +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + $(am__cd) $(srcdir) && $(ACLOCAL) $(ACLOCAL_AMFLAGS) +$(am__aclocal_m4_deps): + +scripts/.autostuff/config.h: scripts/.autostuff/stamp-h1 + @if test ! -f $@; then \ + rm -f scripts/.autostuff/stamp-h1; \ + $(MAKE) $(AM_MAKEFLAGS) scripts/.autostuff/stamp-h1; \ + else :; fi + +scripts/.autostuff/stamp-h1: $(top_srcdir)/scripts/.autostuff/config.h.in $(top_builddir)/config.status + @rm -f scripts/.autostuff/stamp-h1 + cd $(top_builddir) && $(SHELL) ./config.status scripts/.autostuff/config.h +$(top_srcdir)/scripts/.autostuff/config.h.in: $(am__configure_deps) + ($(am__cd) $(top_srcdir) && $(AUTOHEADER)) + rm -f scripts/.autostuff/stamp-h1 + touch $@ + +distclean-hdr: + -rm -f scripts/.autostuff/config.h scripts/.autostuff/stamp-h1 + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs + +distclean-libtool: + -rm -f libtool config.lt + +# This directory's subdirectories are mostly independent; you can cd +# into them and run `make' without going through this Makefile. +# To change the values of `make' variables: instead of editing Makefiles, +# (1) if the variable is set in `config.status', edit `config.status' +# (which will cause the Makefiles to be regenerated when you run `make'); +# (2) otherwise, pass the desired values on the `make' command line. +$(RECURSIVE_TARGETS): + @fail= failcom='exit 1'; \ + for f in x $$MAKEFLAGS; do \ + case $$f in \ + *=* | --[!k]*);; \ + *k*) failcom='fail=yes';; \ + esac; \ + done; \ + dot_seen=no; \ + target=`echo $@ | sed s/-recursive//`; \ + list='$(SUBDIRS)'; for subdir in $$list; do \ + echo "Making $$target in $$subdir"; \ + if test "$$subdir" = "."; then \ + dot_seen=yes; \ + local_target="$$target-am"; \ + else \ + local_target="$$target"; \ + fi; \ + ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) $$local_target) \ + || eval $$failcom; \ + done; \ + if test "$$dot_seen" = "no"; then \ + $(MAKE) $(AM_MAKEFLAGS) "$$target-am" || exit 1; \ + fi; test -z "$$fail" + +$(RECURSIVE_CLEAN_TARGETS): + @fail= failcom='exit 1'; \ + for f in x $$MAKEFLAGS; do \ + case $$f in \ + *=* | --[!k]*);; \ + *k*) failcom='fail=yes';; \ + esac; \ + done; \ + dot_seen=no; \ + case "$@" in \ + distclean-* | maintainer-clean-*) list='$(DIST_SUBDIRS)' ;; \ + *) list='$(SUBDIRS)' ;; \ + esac; \ + rev=''; for subdir in $$list; do \ + if test "$$subdir" = "."; then :; else \ + rev="$$subdir $$rev"; \ + fi; \ + done; \ + rev="$$rev ."; \ + target=`echo $@ | sed s/-recursive//`; \ + for subdir in $$rev; do \ + echo "Making $$target in $$subdir"; \ + if test "$$subdir" = "."; then \ + local_target="$$target-am"; \ + else \ + local_target="$$target"; \ + fi; \ + ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) $$local_target) \ + || eval $$failcom; \ + done && test -z "$$fail" +tags-recursive: + list='$(SUBDIRS)'; for subdir in $$list; do \ + test "$$subdir" = . || ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) tags); \ + done +ctags-recursive: + list='$(SUBDIRS)'; for subdir in $$list; do \ + test "$$subdir" = . || ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) ctags); \ + done + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: tags-recursive $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + if ($(ETAGS) --etags-include --version) >/dev/null 2>&1; then \ + include_option=--etags-include; \ + empty_fix=.; \ + else \ + include_option=--include; \ + empty_fix=; \ + fi; \ + list='$(SUBDIRS)'; for subdir in $$list; do \ + if test "$$subdir" = .; then :; else \ + test ! -f $$subdir/TAGS || \ + set "$$@" "$$include_option=$$here/$$subdir/TAGS"; \ + fi; \ + done; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: ctags-recursive $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + $(am__remove_distdir) + test -d "$(distdir)" || mkdir "$(distdir)" + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done + @list='$(DIST_SUBDIRS)'; for subdir in $$list; do \ + if test "$$subdir" = .; then :; else \ + test -d "$(distdir)/$$subdir" \ + || $(MKDIR_P) "$(distdir)/$$subdir" \ + || exit 1; \ + fi; \ + done + @list='$(DIST_SUBDIRS)'; for subdir in $$list; do \ + if test "$$subdir" = .; then :; else \ + dir1=$$subdir; dir2="$(distdir)/$$subdir"; \ + $(am__relativize); \ + new_distdir=$$reldir; \ + dir1=$$subdir; dir2="$(top_distdir)"; \ + $(am__relativize); \ + new_top_distdir=$$reldir; \ + echo " (cd $$subdir && $(MAKE) $(AM_MAKEFLAGS) top_distdir="$$new_top_distdir" distdir="$$new_distdir" \\"; \ + echo " am__remove_distdir=: am__skip_length_check=: am__skip_mode_fix=: distdir)"; \ + ($(am__cd) $$subdir && \ + $(MAKE) $(AM_MAKEFLAGS) \ + top_distdir="$$new_top_distdir" \ + distdir="$$new_distdir" \ + am__remove_distdir=: \ + am__skip_length_check=: \ + am__skip_mode_fix=: \ + distdir) \ + || exit 1; \ + fi; \ + done + -test -n "$(am__skip_mode_fix)" \ + || find "$(distdir)" -type d ! -perm -755 \ + -exec chmod u+rwx,go+rx {} \; -o \ + ! -type d ! -perm -444 -links 1 -exec chmod a+r {} \; -o \ + ! -type d ! -perm -400 -exec chmod a+r {} \; -o \ + ! -type d ! -perm -444 -exec $(install_sh) -c -m a+r {} {} \; \ + || chmod -R a+r "$(distdir)" +dist-gzip: distdir + tardir=$(distdir) && $(am__tar) | GZIP=$(GZIP_ENV) gzip -c >$(distdir).tar.gz + $(am__remove_distdir) + +dist-bzip2: distdir + tardir=$(distdir) && $(am__tar) | bzip2 -9 -c >$(distdir).tar.bz2 + $(am__remove_distdir) + +dist-lzma: distdir + tardir=$(distdir) && $(am__tar) | lzma -9 -c >$(distdir).tar.lzma + $(am__remove_distdir) + +dist-xz: distdir + tardir=$(distdir) && $(am__tar) | xz -c >$(distdir).tar.xz + $(am__remove_distdir) + +dist-tarZ: distdir + tardir=$(distdir) && $(am__tar) | compress -c >$(distdir).tar.Z + $(am__remove_distdir) + +dist-shar: distdir + shar $(distdir) | GZIP=$(GZIP_ENV) gzip -c >$(distdir).shar.gz + $(am__remove_distdir) + +dist-zip: distdir + -rm -f $(distdir).zip + zip -rq $(distdir).zip $(distdir) + $(am__remove_distdir) + +dist dist-all: distdir + tardir=$(distdir) && $(am__tar) | GZIP=$(GZIP_ENV) gzip -c >$(distdir).tar.gz + $(am__remove_distdir) + +# This target untars the dist file and tries a VPATH configuration. Then +# it guarantees that the distribution is self-contained by making another +# tarfile. +distcheck: dist + case '$(DIST_ARCHIVES)' in \ + *.tar.gz*) \ + GZIP=$(GZIP_ENV) gzip -dc $(distdir).tar.gz | $(am__untar) ;;\ + *.tar.bz2*) \ + bzip2 -dc $(distdir).tar.bz2 | $(am__untar) ;;\ + *.tar.lzma*) \ + lzma -dc $(distdir).tar.lzma | $(am__untar) ;;\ + *.tar.xz*) \ + xz -dc $(distdir).tar.xz | $(am__untar) ;;\ + *.tar.Z*) \ + uncompress -c $(distdir).tar.Z | $(am__untar) ;;\ + *.shar.gz*) \ + GZIP=$(GZIP_ENV) gzip -dc $(distdir).shar.gz | unshar ;;\ + *.zip*) \ + unzip $(distdir).zip ;;\ + esac + chmod -R a-w $(distdir); chmod u+w $(distdir) + mkdir $(distdir)/_build + mkdir $(distdir)/_inst + chmod a-w $(distdir) + test -d $(distdir)/_build || exit 0; \ + dc_install_base=`$(am__cd) $(distdir)/_inst && pwd | sed -e 's,^[^:\\/]:[\\/],/,'` \ + && dc_destdir="$${TMPDIR-/tmp}/am-dc-$$$$/" \ + && am__cwd=`pwd` \ + && $(am__cd) $(distdir)/_build \ + && ../configure --srcdir=.. --prefix="$$dc_install_base" \ + $(DISTCHECK_CONFIGURE_FLAGS) \ + && $(MAKE) $(AM_MAKEFLAGS) \ + && $(MAKE) $(AM_MAKEFLAGS) dvi \ + && $(MAKE) $(AM_MAKEFLAGS) check \ + && $(MAKE) $(AM_MAKEFLAGS) install \ + && $(MAKE) $(AM_MAKEFLAGS) installcheck \ + && $(MAKE) $(AM_MAKEFLAGS) uninstall \ + && $(MAKE) $(AM_MAKEFLAGS) distuninstallcheck_dir="$$dc_install_base" \ + distuninstallcheck \ + && chmod -R a-w "$$dc_install_base" \ + && ({ \ + (cd ../.. && umask 077 && mkdir "$$dc_destdir") \ + && $(MAKE) $(AM_MAKEFLAGS) DESTDIR="$$dc_destdir" install \ + && $(MAKE) $(AM_MAKEFLAGS) DESTDIR="$$dc_destdir" uninstall \ + && $(MAKE) $(AM_MAKEFLAGS) DESTDIR="$$dc_destdir" \ + distuninstallcheck_dir="$$dc_destdir" distuninstallcheck; \ + } || { rm -rf "$$dc_destdir"; exit 1; }) \ + && rm -rf "$$dc_destdir" \ + && $(MAKE) $(AM_MAKEFLAGS) dist \ + && rm -rf $(DIST_ARCHIVES) \ + && $(MAKE) $(AM_MAKEFLAGS) distcleancheck \ + && cd "$$am__cwd" \ + || exit 1 + $(am__remove_distdir) + @(echo "$(distdir) archives ready for distribution: "; \ + list='$(DIST_ARCHIVES)'; for i in $$list; do echo $$i; done) | \ + sed -e 1h -e 1s/./=/g -e 1p -e 1x -e '$$p' -e '$$x' +distuninstallcheck: + @$(am__cd) '$(distuninstallcheck_dir)' \ + && test `$(distuninstallcheck_listfiles) | wc -l` -le 1 \ + || { echo "ERROR: files left after uninstall:" ; \ + if test -n "$(DESTDIR)"; then \ + echo " (check DESTDIR support)"; \ + fi ; \ + $(distuninstallcheck_listfiles) ; \ + exit 1; } >&2 +distcleancheck: distclean + @if test '$(srcdir)' = . ; then \ + echo "ERROR: distcleancheck can only run from a VPATH build" ; \ + exit 1 ; \ + fi + @test `$(distcleancheck_listfiles) | wc -l` -eq 0 \ + || { echo "ERROR: files left in build directory after distclean:" ; \ + $(distcleancheck_listfiles) ; \ + exit 1; } >&2 +check-am: all-am +check: check-recursive +all-am: Makefile +installdirs: installdirs-recursive +installdirs-am: +install: install-recursive +install-exec: install-exec-recursive +install-data: install-data-recursive +uninstall: uninstall-recursive + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-recursive +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-recursive + +clean-am: clean-generic clean-libtool mostlyclean-am + +distclean: distclean-recursive + -rm -f $(am__CONFIG_DISTCLEAN_FILES) + -rm -f Makefile +distclean-am: clean-am distclean-generic distclean-hdr \ + distclean-libtool distclean-tags + +dvi: dvi-recursive + +dvi-am: + +html: html-recursive + +html-am: + +info: info-recursive + +info-am: + +install-data-am: + +install-dvi: install-dvi-recursive + +install-dvi-am: + +install-exec-am: + +install-html: install-html-recursive + +install-html-am: + +install-info: install-info-recursive + +install-info-am: + +install-man: + +install-pdf: install-pdf-recursive + +install-pdf-am: + +install-ps: install-ps-recursive + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-recursive + -rm -f $(am__CONFIG_DISTCLEAN_FILES) + -rm -rf $(top_srcdir)/autom4te.cache + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-recursive + +mostlyclean-am: mostlyclean-generic mostlyclean-libtool + +pdf: pdf-recursive + +pdf-am: + +ps: ps-recursive + +ps-am: + +uninstall-am: + +.MAKE: $(RECURSIVE_CLEAN_TARGETS) $(RECURSIVE_TARGETS) ctags-recursive \ + install-am install-strip tags-recursive + +.PHONY: $(RECURSIVE_CLEAN_TARGETS) $(RECURSIVE_TARGETS) CTAGS GTAGS \ + all all-am am--refresh check check-am clean clean-generic \ + clean-libtool ctags ctags-recursive dist dist-all dist-bzip2 \ + dist-gzip dist-lzma dist-shar dist-tarZ dist-xz dist-zip \ + distcheck distclean distclean-generic distclean-hdr \ + distclean-libtool distclean-tags distcleancheck distdir \ + distuninstallcheck dvi dvi-am html html-am info info-am \ + install install-am install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + installdirs-am maintainer-clean maintainer-clean-generic \ + mostlyclean mostlyclean-generic mostlyclean-libtool pdf pdf-am \ + ps ps-am tags tags-recursive uninstall uninstall-am + + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/README b/misc/tools/kconfig-frontends/README new file mode 100644 index 0000000000..c4a72d5e8f --- /dev/null +++ b/misc/tools/kconfig-frontends/README @@ -0,0 +1,39 @@ +This package contains the kconfig frontends and parser. + +Kconfig is the configuration language used by the Linux kernel. This package +is a simple copy of the frontends and the parser found in the Linux kernel +source tree, with very minor changes to adapt them to being built out of +the kernel build infrastructure. + +This package does *not* take any change to the parser or frontends. Such +changes shall be directed directly to the appropriate mailing list, and they +will eventually find their way is this package at the next sync: + mailto:linux-kbuild@vger.kernel.org + +However, if there is a bug in the packaging infrastructure, patches are +most welcome, of course! Most notably, because this is my very first +autostuff-based package, I may have done mistakes here and there... + +As such, there are currently a few known limitations: + +- statically linking is much, much more complex than it should be. I have + been seemingly able to build part of the frontends with such incantations + of ./configure and make: + ./configure LDFLAGS=-static nconf_EXTRA_LIBS=-lgpm \ + --disable-shared --enable-static \ + --disable-gconf --disable-qconf + make LDFLAGS="-all-static -static-libtool-libs" + +- the nconf frontends requires (at least on my machine) to be linked against + GPM; this is not detected when staticaly linking (hence the nconf_EXTRA_LIBS + in the command above). + +- statically linking the graphical frontends (gconf and qconf) is *not* + supported: I am missing static libs for Qt3Support, so qconf does not link. + And there is a stupid bug in libtool that prevents properly linking against + installed static libraries (seemingly fixed in 2.4, but not quite yet, in + fact...), so gconf does not link. That's why they are disabled above. + +Note that, provided you have the required dependencies, all frontends are +properly built if you link dynamicaly. The following just works as expected: + ./configure && make diff --git a/misc/tools/kconfig-frontends/aclocal.m4 b/misc/tools/kconfig-frontends/aclocal.m4 new file mode 100644 index 0000000000..ec9f510b3f --- /dev/null +++ b/misc/tools/kconfig-frontends/aclocal.m4 @@ -0,0 +1,9137 @@ +# generated automatically by aclocal 1.11.1 -*- Autoconf -*- + +# Copyright (C) 1996, 1997, 1998, 1999, 2000, 2001, 2002, 2003, 2004, +# 2005, 2006, 2007, 2008, 2009 Free Software Foundation, Inc. +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +m4_ifndef([AC_AUTOCONF_VERSION], + [m4_copy([m4_PACKAGE_VERSION], [AC_AUTOCONF_VERSION])])dnl +m4_if(m4_defn([AC_AUTOCONF_VERSION]), [2.67],, +[m4_warning([this file was generated for autoconf 2.67. +You have another version of autoconf. It may work, but is not guaranteed to. +If you have problems, you may need to regenerate the build system entirely. +To do so, use the procedure documented by the package, typically `autoreconf'.])]) + +# libtool.m4 - Configure libtool for the host system. -*-Autoconf-*- +# +# Copyright (C) 1996, 1997, 1998, 1999, 2000, 2001, 2003, 2004, 2005, +# 2006, 2007, 2008 Free Software Foundation, Inc. +# Written by Gordon Matzigkeit, 1996 +# +# This file is free software; the Free Software Foundation gives +# unlimited permission to copy and/or distribute it, with or without +# modifications, as long as this notice is preserved. + +m4_define([_LT_COPYING], [dnl +# Copyright (C) 1996, 1997, 1998, 1999, 2000, 2001, 2003, 2004, 2005, +# 2006, 2007, 2008 Free Software Foundation, Inc. +# Written by Gordon Matzigkeit, 1996 +# +# This file is part of GNU Libtool. +# +# GNU Libtool is free software; you can redistribute it and/or +# modify it under the terms of the GNU General Public License as +# published by the Free Software Foundation; either version 2 of +# the License, or (at your option) any later version. +# +# As a special exception to the GNU General Public License, +# if you distribute this file as part of a program or library that +# is built using GNU Libtool, you may include this file under the +# same distribution terms that you use for the rest of that program. +# +# GNU Libtool is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with GNU Libtool; see the file COPYING. If not, a copy +# can be downloaded from http://www.gnu.org/licenses/gpl.html, or +# obtained by writing to the Free Software Foundation, Inc., +# 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. +]) + +# serial 56 LT_INIT + + +# LT_PREREQ(VERSION) +# ------------------ +# Complain and exit if this libtool version is less that VERSION. +m4_defun([LT_PREREQ], +[m4_if(m4_version_compare(m4_defn([LT_PACKAGE_VERSION]), [$1]), -1, + [m4_default([$3], + [m4_fatal([Libtool version $1 or higher is required], + 63)])], + [$2])]) + + +# _LT_CHECK_BUILDDIR +# ------------------ +# Complain if the absolute build directory name contains unusual characters +m4_defun([_LT_CHECK_BUILDDIR], +[case `pwd` in + *\ * | *\ *) + AC_MSG_WARN([Libtool does not cope well with whitespace in `pwd`]) ;; +esac +]) + + +# LT_INIT([OPTIONS]) +# ------------------ +AC_DEFUN([LT_INIT], +[AC_PREREQ([2.58])dnl We use AC_INCLUDES_DEFAULT +AC_BEFORE([$0], [LT_LANG])dnl +AC_BEFORE([$0], [LT_OUTPUT])dnl +AC_BEFORE([$0], [LTDL_INIT])dnl +m4_require([_LT_CHECK_BUILDDIR])dnl + +dnl Autoconf doesn't catch unexpanded LT_ macros by default: +m4_pattern_forbid([^_?LT_[A-Z_]+$])dnl +m4_pattern_allow([^(_LT_EOF|LT_DLGLOBAL|LT_DLLAZY_OR_NOW|LT_MULTI_MODULE)$])dnl +dnl aclocal doesn't pull ltoptions.m4, ltsugar.m4, or ltversion.m4 +dnl unless we require an AC_DEFUNed macro: +AC_REQUIRE([LTOPTIONS_VERSION])dnl +AC_REQUIRE([LTSUGAR_VERSION])dnl +AC_REQUIRE([LTVERSION_VERSION])dnl +AC_REQUIRE([LTOBSOLETE_VERSION])dnl +m4_require([_LT_PROG_LTMAIN])dnl + +dnl Parse OPTIONS +_LT_SET_OPTIONS([$0], [$1]) + +# This can be used to rebuild libtool when needed +LIBTOOL_DEPS="$ltmain" + +# Always use our own libtool. +LIBTOOL='$(SHELL) $(top_builddir)/libtool' +AC_SUBST(LIBTOOL)dnl + +_LT_SETUP + +# Only expand once: +m4_define([LT_INIT]) +])# LT_INIT + +# Old names: +AU_ALIAS([AC_PROG_LIBTOOL], [LT_INIT]) +AU_ALIAS([AM_PROG_LIBTOOL], [LT_INIT]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_PROG_LIBTOOL], []) +dnl AC_DEFUN([AM_PROG_LIBTOOL], []) + + +# _LT_CC_BASENAME(CC) +# ------------------- +# Calculate cc_basename. Skip known compiler wrappers and cross-prefix. +m4_defun([_LT_CC_BASENAME], +[for cc_temp in $1""; do + case $cc_temp in + compile | *[[\\/]]compile | ccache | *[[\\/]]ccache ) ;; + distcc | *[[\\/]]distcc | purify | *[[\\/]]purify ) ;; + \-*) ;; + *) break;; + esac +done +cc_basename=`$ECHO "X$cc_temp" | $Xsed -e 's%.*/%%' -e "s%^$host_alias-%%"` +]) + + +# _LT_FILEUTILS_DEFAULTS +# ---------------------- +# It is okay to use these file commands and assume they have been set +# sensibly after `m4_require([_LT_FILEUTILS_DEFAULTS])'. +m4_defun([_LT_FILEUTILS_DEFAULTS], +[: ${CP="cp -f"} +: ${MV="mv -f"} +: ${RM="rm -f"} +])# _LT_FILEUTILS_DEFAULTS + + +# _LT_SETUP +# --------- +m4_defun([_LT_SETUP], +[AC_REQUIRE([AC_CANONICAL_HOST])dnl +AC_REQUIRE([AC_CANONICAL_BUILD])dnl +_LT_DECL([], [host_alias], [0], [The host system])dnl +_LT_DECL([], [host], [0])dnl +_LT_DECL([], [host_os], [0])dnl +dnl +_LT_DECL([], [build_alias], [0], [The build system])dnl +_LT_DECL([], [build], [0])dnl +_LT_DECL([], [build_os], [0])dnl +dnl +AC_REQUIRE([AC_PROG_CC])dnl +AC_REQUIRE([LT_PATH_LD])dnl +AC_REQUIRE([LT_PATH_NM])dnl +dnl +AC_REQUIRE([AC_PROG_LN_S])dnl +test -z "$LN_S" && LN_S="ln -s" +_LT_DECL([], [LN_S], [1], [Whether we need soft or hard links])dnl +dnl +AC_REQUIRE([LT_CMD_MAX_LEN])dnl +_LT_DECL([objext], [ac_objext], [0], [Object file suffix (normally "o")])dnl +_LT_DECL([], [exeext], [0], [Executable file suffix (normally "")])dnl +dnl +m4_require([_LT_FILEUTILS_DEFAULTS])dnl +m4_require([_LT_CHECK_SHELL_FEATURES])dnl +m4_require([_LT_CMD_RELOAD])dnl +m4_require([_LT_CHECK_MAGIC_METHOD])dnl +m4_require([_LT_CMD_OLD_ARCHIVE])dnl +m4_require([_LT_CMD_GLOBAL_SYMBOLS])dnl + +_LT_CONFIG_LIBTOOL_INIT([ +# See if we are running on zsh, and set the options which allow our +# commands through without removal of \ escapes INIT. +if test -n "\${ZSH_VERSION+set}" ; then + setopt NO_GLOB_SUBST +fi +]) +if test -n "${ZSH_VERSION+set}" ; then + setopt NO_GLOB_SUBST +fi + +_LT_CHECK_OBJDIR + +m4_require([_LT_TAG_COMPILER])dnl +_LT_PROG_ECHO_BACKSLASH + +case $host_os in +aix3*) + # AIX sometimes has problems with the GCC collect2 program. For some + # reason, if we set the COLLECT_NAMES environment variable, the problems + # vanish in a puff of smoke. + if test "X${COLLECT_NAMES+set}" != Xset; then + COLLECT_NAMES= + export COLLECT_NAMES + fi + ;; +esac + +# Sed substitution that helps us do robust quoting. It backslashifies +# metacharacters that are still active within double-quoted strings. +sed_quote_subst='s/\([["`$\\]]\)/\\\1/g' + +# Same as above, but do not quote variable references. +double_quote_subst='s/\([["`\\]]\)/\\\1/g' + +# Sed substitution to delay expansion of an escaped shell variable in a +# double_quote_subst'ed string. +delay_variable_subst='s/\\\\\\\\\\\$/\\\\\\$/g' + +# Sed substitution to delay expansion of an escaped single quote. +delay_single_quote_subst='s/'\''/'\'\\\\\\\'\''/g' + +# Sed substitution to avoid accidental globbing in evaled expressions +no_glob_subst='s/\*/\\\*/g' + +# Global variables: +ofile=libtool +can_build_shared=yes + +# All known linkers require a `.a' archive for static linking (except MSVC, +# which needs '.lib'). +libext=a + +with_gnu_ld="$lt_cv_prog_gnu_ld" + +old_CC="$CC" +old_CFLAGS="$CFLAGS" + +# Set sane defaults for various variables +test -z "$CC" && CC=cc +test -z "$LTCC" && LTCC=$CC +test -z "$LTCFLAGS" && LTCFLAGS=$CFLAGS +test -z "$LD" && LD=ld +test -z "$ac_objext" && ac_objext=o + +_LT_CC_BASENAME([$compiler]) + +# Only perform the check for file, if the check method requires it +test -z "$MAGIC_CMD" && MAGIC_CMD=file +case $deplibs_check_method in +file_magic*) + if test "$file_magic_cmd" = '$MAGIC_CMD'; then + _LT_PATH_MAGIC + fi + ;; +esac + +# Use C for the default configuration in the libtool script +LT_SUPPORTED_TAG([CC]) +_LT_LANG_C_CONFIG +_LT_LANG_DEFAULT_CONFIG +_LT_CONFIG_COMMANDS +])# _LT_SETUP + + +# _LT_PROG_LTMAIN +# --------------- +# Note that this code is called both from `configure', and `config.status' +# now that we use AC_CONFIG_COMMANDS to generate libtool. Notably, +# `config.status' has no value for ac_aux_dir unless we are using Automake, +# so we pass a copy along to make sure it has a sensible value anyway. +m4_defun([_LT_PROG_LTMAIN], +[m4_ifdef([AC_REQUIRE_AUX_FILE], [AC_REQUIRE_AUX_FILE([ltmain.sh])])dnl +_LT_CONFIG_LIBTOOL_INIT([ac_aux_dir='$ac_aux_dir']) +ltmain="$ac_aux_dir/ltmain.sh" +])# _LT_PROG_LTMAIN + + + +# So that we can recreate a full libtool script including additional +# tags, we accumulate the chunks of code to send to AC_CONFIG_COMMANDS +# in macros and then make a single call at the end using the `libtool' +# label. + + +# _LT_CONFIG_LIBTOOL_INIT([INIT-COMMANDS]) +# ---------------------------------------- +# Register INIT-COMMANDS to be passed to AC_CONFIG_COMMANDS later. +m4_define([_LT_CONFIG_LIBTOOL_INIT], +[m4_ifval([$1], + [m4_append([_LT_OUTPUT_LIBTOOL_INIT], + [$1 +])])]) + +# Initialize. +m4_define([_LT_OUTPUT_LIBTOOL_INIT]) + + +# _LT_CONFIG_LIBTOOL([COMMANDS]) +# ------------------------------ +# Register COMMANDS to be passed to AC_CONFIG_COMMANDS later. +m4_define([_LT_CONFIG_LIBTOOL], +[m4_ifval([$1], + [m4_append([_LT_OUTPUT_LIBTOOL_COMMANDS], + [$1 +])])]) + +# Initialize. +m4_define([_LT_OUTPUT_LIBTOOL_COMMANDS]) + + +# _LT_CONFIG_SAVE_COMMANDS([COMMANDS], [INIT_COMMANDS]) +# ----------------------------------------------------- +m4_defun([_LT_CONFIG_SAVE_COMMANDS], +[_LT_CONFIG_LIBTOOL([$1]) +_LT_CONFIG_LIBTOOL_INIT([$2]) +]) + + +# _LT_FORMAT_COMMENT([COMMENT]) +# ----------------------------- +# Add leading comment marks to the start of each line, and a trailing +# full-stop to the whole comment if one is not present already. +m4_define([_LT_FORMAT_COMMENT], +[m4_ifval([$1], [ +m4_bpatsubst([m4_bpatsubst([$1], [^ *], [# ])], + [['`$\]], [\\\&])]m4_bmatch([$1], [[!?.]$], [], [.]) +)]) + + + + + +# _LT_DECL([CONFIGNAME], VARNAME, VALUE, [DESCRIPTION], [IS-TAGGED?]) +# ------------------------------------------------------------------- +# CONFIGNAME is the name given to the value in the libtool script. +# VARNAME is the (base) name used in the configure script. +# VALUE may be 0, 1 or 2 for a computed quote escaped value based on +# VARNAME. Any other value will be used directly. +m4_define([_LT_DECL], +[lt_if_append_uniq([lt_decl_varnames], [$2], [, ], + [lt_dict_add_subkey([lt_decl_dict], [$2], [libtool_name], + [m4_ifval([$1], [$1], [$2])]) + lt_dict_add_subkey([lt_decl_dict], [$2], [value], [$3]) + m4_ifval([$4], + [lt_dict_add_subkey([lt_decl_dict], [$2], [description], [$4])]) + lt_dict_add_subkey([lt_decl_dict], [$2], + [tagged?], [m4_ifval([$5], [yes], [no])])]) +]) + + +# _LT_TAGDECL([CONFIGNAME], VARNAME, VALUE, [DESCRIPTION]) +# -------------------------------------------------------- +m4_define([_LT_TAGDECL], [_LT_DECL([$1], [$2], [$3], [$4], [yes])]) + + +# lt_decl_tag_varnames([SEPARATOR], [VARNAME1...]) +# ------------------------------------------------ +m4_define([lt_decl_tag_varnames], +[_lt_decl_filter([tagged?], [yes], $@)]) + + +# _lt_decl_filter(SUBKEY, VALUE, [SEPARATOR], [VARNAME1..]) +# --------------------------------------------------------- +m4_define([_lt_decl_filter], +[m4_case([$#], + [0], [m4_fatal([$0: too few arguments: $#])], + [1], [m4_fatal([$0: too few arguments: $#: $1])], + [2], [lt_dict_filter([lt_decl_dict], [$1], [$2], [], lt_decl_varnames)], + [3], [lt_dict_filter([lt_decl_dict], [$1], [$2], [$3], lt_decl_varnames)], + [lt_dict_filter([lt_decl_dict], $@)])[]dnl +]) + + +# lt_decl_quote_varnames([SEPARATOR], [VARNAME1...]) +# -------------------------------------------------- +m4_define([lt_decl_quote_varnames], +[_lt_decl_filter([value], [1], $@)]) + + +# lt_decl_dquote_varnames([SEPARATOR], [VARNAME1...]) +# --------------------------------------------------- +m4_define([lt_decl_dquote_varnames], +[_lt_decl_filter([value], [2], $@)]) + + +# lt_decl_varnames_tagged([SEPARATOR], [VARNAME1...]) +# --------------------------------------------------- +m4_define([lt_decl_varnames_tagged], +[m4_assert([$# <= 2])dnl +_$0(m4_quote(m4_default([$1], [[, ]])), + m4_ifval([$2], [[$2]], [m4_dquote(lt_decl_tag_varnames)]), + m4_split(m4_normalize(m4_quote(_LT_TAGS)), [ ]))]) +m4_define([_lt_decl_varnames_tagged], +[m4_ifval([$3], [lt_combine([$1], [$2], [_], $3)])]) + + +# lt_decl_all_varnames([SEPARATOR], [VARNAME1...]) +# ------------------------------------------------ +m4_define([lt_decl_all_varnames], +[_$0(m4_quote(m4_default([$1], [[, ]])), + m4_if([$2], [], + m4_quote(lt_decl_varnames), + m4_quote(m4_shift($@))))[]dnl +]) +m4_define([_lt_decl_all_varnames], +[lt_join($@, lt_decl_varnames_tagged([$1], + lt_decl_tag_varnames([[, ]], m4_shift($@))))dnl +]) + + +# _LT_CONFIG_STATUS_DECLARE([VARNAME]) +# ------------------------------------ +# Quote a variable value, and forward it to `config.status' so that its +# declaration there will have the same value as in `configure'. VARNAME +# must have a single quote delimited value for this to work. +m4_define([_LT_CONFIG_STATUS_DECLARE], +[$1='`$ECHO "X$][$1" | $Xsed -e "$delay_single_quote_subst"`']) + + +# _LT_CONFIG_STATUS_DECLARATIONS +# ------------------------------ +# We delimit libtool config variables with single quotes, so when +# we write them to config.status, we have to be sure to quote all +# embedded single quotes properly. In configure, this macro expands +# each variable declared with _LT_DECL (and _LT_TAGDECL) into: +# +# ='`$ECHO "X$" | $Xsed -e "$delay_single_quote_subst"`' +m4_defun([_LT_CONFIG_STATUS_DECLARATIONS], +[m4_foreach([_lt_var], m4_quote(lt_decl_all_varnames), + [m4_n([_LT_CONFIG_STATUS_DECLARE(_lt_var)])])]) + + +# _LT_LIBTOOL_TAGS +# ---------------- +# Output comment and list of tags supported by the script +m4_defun([_LT_LIBTOOL_TAGS], +[_LT_FORMAT_COMMENT([The names of the tagged configurations supported by this script])dnl +available_tags="_LT_TAGS"dnl +]) + + +# _LT_LIBTOOL_DECLARE(VARNAME, [TAG]) +# ----------------------------------- +# Extract the dictionary values for VARNAME (optionally with TAG) and +# expand to a commented shell variable setting: +# +# # Some comment about what VAR is for. +# visible_name=$lt_internal_name +m4_define([_LT_LIBTOOL_DECLARE], +[_LT_FORMAT_COMMENT(m4_quote(lt_dict_fetch([lt_decl_dict], [$1], + [description])))[]dnl +m4_pushdef([_libtool_name], + m4_quote(lt_dict_fetch([lt_decl_dict], [$1], [libtool_name])))[]dnl +m4_case(m4_quote(lt_dict_fetch([lt_decl_dict], [$1], [value])), + [0], [_libtool_name=[$]$1], + [1], [_libtool_name=$lt_[]$1], + [2], [_libtool_name=$lt_[]$1], + [_libtool_name=lt_dict_fetch([lt_decl_dict], [$1], [value])])[]dnl +m4_ifval([$2], [_$2])[]m4_popdef([_libtool_name])[]dnl +]) + + +# _LT_LIBTOOL_CONFIG_VARS +# ----------------------- +# Produce commented declarations of non-tagged libtool config variables +# suitable for insertion in the LIBTOOL CONFIG section of the `libtool' +# script. Tagged libtool config variables (even for the LIBTOOL CONFIG +# section) are produced by _LT_LIBTOOL_TAG_VARS. +m4_defun([_LT_LIBTOOL_CONFIG_VARS], +[m4_foreach([_lt_var], + m4_quote(_lt_decl_filter([tagged?], [no], [], lt_decl_varnames)), + [m4_n([_LT_LIBTOOL_DECLARE(_lt_var)])])]) + + +# _LT_LIBTOOL_TAG_VARS(TAG) +# ------------------------- +m4_define([_LT_LIBTOOL_TAG_VARS], +[m4_foreach([_lt_var], m4_quote(lt_decl_tag_varnames), + [m4_n([_LT_LIBTOOL_DECLARE(_lt_var, [$1])])])]) + + +# _LT_TAGVAR(VARNAME, [TAGNAME]) +# ------------------------------ +m4_define([_LT_TAGVAR], [m4_ifval([$2], [$1_$2], [$1])]) + + +# _LT_CONFIG_COMMANDS +# ------------------- +# Send accumulated output to $CONFIG_STATUS. Thanks to the lists of +# variables for single and double quote escaping we saved from calls +# to _LT_DECL, we can put quote escaped variables declarations +# into `config.status', and then the shell code to quote escape them in +# for loops in `config.status'. Finally, any additional code accumulated +# from calls to _LT_CONFIG_LIBTOOL_INIT is expanded. +m4_defun([_LT_CONFIG_COMMANDS], +[AC_PROVIDE_IFELSE([LT_OUTPUT], + dnl If the libtool generation code has been placed in $CONFIG_LT, + dnl instead of duplicating it all over again into config.status, + dnl then we will have config.status run $CONFIG_LT later, so it + dnl needs to know what name is stored there: + [AC_CONFIG_COMMANDS([libtool], + [$SHELL $CONFIG_LT || AS_EXIT(1)], [CONFIG_LT='$CONFIG_LT'])], + dnl If the libtool generation code is destined for config.status, + dnl expand the accumulated commands and init code now: + [AC_CONFIG_COMMANDS([libtool], + [_LT_OUTPUT_LIBTOOL_COMMANDS], [_LT_OUTPUT_LIBTOOL_COMMANDS_INIT])]) +])#_LT_CONFIG_COMMANDS + + +# Initialize. +m4_define([_LT_OUTPUT_LIBTOOL_COMMANDS_INIT], +[ + +# The HP-UX ksh and POSIX shell print the target directory to stdout +# if CDPATH is set. +(unset CDPATH) >/dev/null 2>&1 && unset CDPATH + +sed_quote_subst='$sed_quote_subst' +double_quote_subst='$double_quote_subst' +delay_variable_subst='$delay_variable_subst' +_LT_CONFIG_STATUS_DECLARATIONS +LTCC='$LTCC' +LTCFLAGS='$LTCFLAGS' +compiler='$compiler_DEFAULT' + +# Quote evaled strings. +for var in lt_decl_all_varnames([[ \ +]], lt_decl_quote_varnames); do + case \`eval \\\\\$ECHO "X\\\\\$\$var"\` in + *[[\\\\\\\`\\"\\\$]]*) + eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"X\\\$\$var\\" | \\\$Xsed -e \\"\\\$sed_quote_subst\\"\\\`\\\\\\"" + ;; + *) + eval "lt_\$var=\\\\\\"\\\$\$var\\\\\\"" + ;; + esac +done + +# Double-quote double-evaled strings. +for var in lt_decl_all_varnames([[ \ +]], lt_decl_dquote_varnames); do + case \`eval \\\\\$ECHO "X\\\\\$\$var"\` in + *[[\\\\\\\`\\"\\\$]]*) + eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"X\\\$\$var\\" | \\\$Xsed -e \\"\\\$double_quote_subst\\" -e \\"\\\$sed_quote_subst\\" -e \\"\\\$delay_variable_subst\\"\\\`\\\\\\"" + ;; + *) + eval "lt_\$var=\\\\\\"\\\$\$var\\\\\\"" + ;; + esac +done + +# Fix-up fallback echo if it was mangled by the above quoting rules. +case \$lt_ECHO in +*'\\\[$]0 --fallback-echo"')dnl " + lt_ECHO=\`\$ECHO "X\$lt_ECHO" | \$Xsed -e 's/\\\\\\\\\\\\\\\[$]0 --fallback-echo"\[$]/\[$]0 --fallback-echo"/'\` + ;; +esac + +_LT_OUTPUT_LIBTOOL_INIT +]) + + +# LT_OUTPUT +# --------- +# This macro allows early generation of the libtool script (before +# AC_OUTPUT is called), incase it is used in configure for compilation +# tests. +AC_DEFUN([LT_OUTPUT], +[: ${CONFIG_LT=./config.lt} +AC_MSG_NOTICE([creating $CONFIG_LT]) +cat >"$CONFIG_LT" <<_LTEOF +#! $SHELL +# Generated by $as_me. +# Run this file to recreate a libtool stub with the current configuration. + +lt_cl_silent=false +SHELL=\${CONFIG_SHELL-$SHELL} +_LTEOF + +cat >>"$CONFIG_LT" <<\_LTEOF +AS_SHELL_SANITIZE +_AS_PREPARE + +exec AS_MESSAGE_FD>&1 +exec AS_MESSAGE_LOG_FD>>config.log +{ + echo + AS_BOX([Running $as_me.]) +} >&AS_MESSAGE_LOG_FD + +lt_cl_help="\ +\`$as_me' creates a local libtool stub from the current configuration, +for use in further configure time tests before the real libtool is +generated. + +Usage: $[0] [[OPTIONS]] + + -h, --help print this help, then exit + -V, --version print version number, then exit + -q, --quiet do not print progress messages + -d, --debug don't remove temporary files + +Report bugs to ." + +lt_cl_version="\ +m4_ifset([AC_PACKAGE_NAME], [AC_PACKAGE_NAME ])config.lt[]dnl +m4_ifset([AC_PACKAGE_VERSION], [ AC_PACKAGE_VERSION]) +configured by $[0], generated by m4_PACKAGE_STRING. + +Copyright (C) 2008 Free Software Foundation, Inc. +This config.lt script is free software; the Free Software Foundation +gives unlimited permision to copy, distribute and modify it." + +while test $[#] != 0 +do + case $[1] in + --version | --v* | -V ) + echo "$lt_cl_version"; exit 0 ;; + --help | --h* | -h ) + echo "$lt_cl_help"; exit 0 ;; + --debug | --d* | -d ) + debug=: ;; + --quiet | --q* | --silent | --s* | -q ) + lt_cl_silent=: ;; + + -*) AC_MSG_ERROR([unrecognized option: $[1] +Try \`$[0] --help' for more information.]) ;; + + *) AC_MSG_ERROR([unrecognized argument: $[1] +Try \`$[0] --help' for more information.]) ;; + esac + shift +done + +if $lt_cl_silent; then + exec AS_MESSAGE_FD>/dev/null +fi +_LTEOF + +cat >>"$CONFIG_LT" <<_LTEOF +_LT_OUTPUT_LIBTOOL_COMMANDS_INIT +_LTEOF + +cat >>"$CONFIG_LT" <<\_LTEOF +AC_MSG_NOTICE([creating $ofile]) +_LT_OUTPUT_LIBTOOL_COMMANDS +AS_EXIT(0) +_LTEOF +chmod +x "$CONFIG_LT" + +# configure is writing to config.log, but config.lt does its own redirection, +# appending to config.log, which fails on DOS, as config.log is still kept +# open by configure. Here we exec the FD to /dev/null, effectively closing +# config.log, so it can be properly (re)opened and appended to by config.lt. +if test "$no_create" != yes; then + lt_cl_success=: + test "$silent" = yes && + lt_config_lt_args="$lt_config_lt_args --quiet" + exec AS_MESSAGE_LOG_FD>/dev/null + $SHELL "$CONFIG_LT" $lt_config_lt_args || lt_cl_success=false + exec AS_MESSAGE_LOG_FD>>config.log + $lt_cl_success || AS_EXIT(1) +fi +])# LT_OUTPUT + + +# _LT_CONFIG(TAG) +# --------------- +# If TAG is the built-in tag, create an initial libtool script with a +# default configuration from the untagged config vars. Otherwise add code +# to config.status for appending the configuration named by TAG from the +# matching tagged config vars. +m4_defun([_LT_CONFIG], +[m4_require([_LT_FILEUTILS_DEFAULTS])dnl +_LT_CONFIG_SAVE_COMMANDS([ + m4_define([_LT_TAG], m4_if([$1], [], [C], [$1]))dnl + m4_if(_LT_TAG, [C], [ + # See if we are running on zsh, and set the options which allow our + # commands through without removal of \ escapes. + if test -n "${ZSH_VERSION+set}" ; then + setopt NO_GLOB_SUBST + fi + + cfgfile="${ofile}T" + trap "$RM \"$cfgfile\"; exit 1" 1 2 15 + $RM "$cfgfile" + + cat <<_LT_EOF >> "$cfgfile" +#! $SHELL + +# `$ECHO "$ofile" | sed 's%^.*/%%'` - Provide generalized library-building support services. +# Generated automatically by $as_me ($PACKAGE$TIMESTAMP) $VERSION +# Libtool was configured on host `(hostname || uname -n) 2>/dev/null | sed 1q`: +# NOTE: Changes made to this file will be lost: look at ltmain.sh. +# +_LT_COPYING +_LT_LIBTOOL_TAGS + +# ### BEGIN LIBTOOL CONFIG +_LT_LIBTOOL_CONFIG_VARS +_LT_LIBTOOL_TAG_VARS +# ### END LIBTOOL CONFIG + +_LT_EOF + + case $host_os in + aix3*) + cat <<\_LT_EOF >> "$cfgfile" +# AIX sometimes has problems with the GCC collect2 program. For some +# reason, if we set the COLLECT_NAMES environment variable, the problems +# vanish in a puff of smoke. +if test "X${COLLECT_NAMES+set}" != Xset; then + COLLECT_NAMES= + export COLLECT_NAMES +fi +_LT_EOF + ;; + esac + + _LT_PROG_LTMAIN + + # We use sed instead of cat because bash on DJGPP gets confused if + # if finds mixed CR/LF and LF-only lines. Since sed operates in + # text mode, it properly converts lines to CR/LF. This bash problem + # is reportedly fixed, but why not run on old versions too? + sed '/^# Generated shell functions inserted here/q' "$ltmain" >> "$cfgfile" \ + || (rm -f "$cfgfile"; exit 1) + + _LT_PROG_XSI_SHELLFNS + + sed -n '/^# Generated shell functions inserted here/,$p' "$ltmain" >> "$cfgfile" \ + || (rm -f "$cfgfile"; exit 1) + + mv -f "$cfgfile" "$ofile" || + (rm -f "$ofile" && cp "$cfgfile" "$ofile" && rm -f "$cfgfile") + chmod +x "$ofile" +], +[cat <<_LT_EOF >> "$ofile" + +dnl Unfortunately we have to use $1 here, since _LT_TAG is not expanded +dnl in a comment (ie after a #). +# ### BEGIN LIBTOOL TAG CONFIG: $1 +_LT_LIBTOOL_TAG_VARS(_LT_TAG) +# ### END LIBTOOL TAG CONFIG: $1 +_LT_EOF +])dnl /m4_if +], +[m4_if([$1], [], [ + PACKAGE='$PACKAGE' + VERSION='$VERSION' + TIMESTAMP='$TIMESTAMP' + RM='$RM' + ofile='$ofile'], []) +])dnl /_LT_CONFIG_SAVE_COMMANDS +])# _LT_CONFIG + + +# LT_SUPPORTED_TAG(TAG) +# --------------------- +# Trace this macro to discover what tags are supported by the libtool +# --tag option, using: +# autoconf --trace 'LT_SUPPORTED_TAG:$1' +AC_DEFUN([LT_SUPPORTED_TAG], []) + + +# C support is built-in for now +m4_define([_LT_LANG_C_enabled], []) +m4_define([_LT_TAGS], []) + + +# LT_LANG(LANG) +# ------------- +# Enable libtool support for the given language if not already enabled. +AC_DEFUN([LT_LANG], +[AC_BEFORE([$0], [LT_OUTPUT])dnl +m4_case([$1], + [C], [_LT_LANG(C)], + [C++], [_LT_LANG(CXX)], + [Java], [_LT_LANG(GCJ)], + [Fortran 77], [_LT_LANG(F77)], + [Fortran], [_LT_LANG(FC)], + [Windows Resource], [_LT_LANG(RC)], + [m4_ifdef([_LT_LANG_]$1[_CONFIG], + [_LT_LANG($1)], + [m4_fatal([$0: unsupported language: "$1"])])])dnl +])# LT_LANG + + +# _LT_LANG(LANGNAME) +# ------------------ +m4_defun([_LT_LANG], +[m4_ifdef([_LT_LANG_]$1[_enabled], [], + [LT_SUPPORTED_TAG([$1])dnl + m4_append([_LT_TAGS], [$1 ])dnl + m4_define([_LT_LANG_]$1[_enabled], [])dnl + _LT_LANG_$1_CONFIG($1)])dnl +])# _LT_LANG + + +# _LT_LANG_DEFAULT_CONFIG +# ----------------------- +m4_defun([_LT_LANG_DEFAULT_CONFIG], +[AC_PROVIDE_IFELSE([AC_PROG_CXX], + [LT_LANG(CXX)], + [m4_define([AC_PROG_CXX], defn([AC_PROG_CXX])[LT_LANG(CXX)])]) + +AC_PROVIDE_IFELSE([AC_PROG_F77], + [LT_LANG(F77)], + [m4_define([AC_PROG_F77], defn([AC_PROG_F77])[LT_LANG(F77)])]) + +AC_PROVIDE_IFELSE([AC_PROG_FC], + [LT_LANG(FC)], + [m4_define([AC_PROG_FC], defn([AC_PROG_FC])[LT_LANG(FC)])]) + +dnl The call to [A][M_PROG_GCJ] is quoted like that to stop aclocal +dnl pulling things in needlessly. +AC_PROVIDE_IFELSE([AC_PROG_GCJ], + [LT_LANG(GCJ)], + [AC_PROVIDE_IFELSE([A][M_PROG_GCJ], + [LT_LANG(GCJ)], + [AC_PROVIDE_IFELSE([LT_PROG_GCJ], + [LT_LANG(GCJ)], + [m4_ifdef([AC_PROG_GCJ], + [m4_define([AC_PROG_GCJ], defn([AC_PROG_GCJ])[LT_LANG(GCJ)])]) + m4_ifdef([A][M_PROG_GCJ], + [m4_define([A][M_PROG_GCJ], defn([A][M_PROG_GCJ])[LT_LANG(GCJ)])]) + m4_ifdef([LT_PROG_GCJ], + [m4_define([LT_PROG_GCJ], defn([LT_PROG_GCJ])[LT_LANG(GCJ)])])])])]) + +AC_PROVIDE_IFELSE([LT_PROG_RC], + [LT_LANG(RC)], + [m4_define([LT_PROG_RC], defn([LT_PROG_RC])[LT_LANG(RC)])]) +])# _LT_LANG_DEFAULT_CONFIG + +# Obsolete macros: +AU_DEFUN([AC_LIBTOOL_CXX], [LT_LANG(C++)]) +AU_DEFUN([AC_LIBTOOL_F77], [LT_LANG(Fortran 77)]) +AU_DEFUN([AC_LIBTOOL_FC], [LT_LANG(Fortran)]) +AU_DEFUN([AC_LIBTOOL_GCJ], [LT_LANG(Java)]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_LIBTOOL_CXX], []) +dnl AC_DEFUN([AC_LIBTOOL_F77], []) +dnl AC_DEFUN([AC_LIBTOOL_FC], []) +dnl AC_DEFUN([AC_LIBTOOL_GCJ], []) + + +# _LT_TAG_COMPILER +# ---------------- +m4_defun([_LT_TAG_COMPILER], +[AC_REQUIRE([AC_PROG_CC])dnl + +_LT_DECL([LTCC], [CC], [1], [A C compiler])dnl +_LT_DECL([LTCFLAGS], [CFLAGS], [1], [LTCC compiler flags])dnl +_LT_TAGDECL([CC], [compiler], [1], [A language specific compiler])dnl +_LT_TAGDECL([with_gcc], [GCC], [0], [Is the compiler the GNU compiler?])dnl + +# If no C compiler was specified, use CC. +LTCC=${LTCC-"$CC"} + +# If no C compiler flags were specified, use CFLAGS. +LTCFLAGS=${LTCFLAGS-"$CFLAGS"} + +# Allow CC to be a program name with arguments. +compiler=$CC +])# _LT_TAG_COMPILER + + +# _LT_COMPILER_BOILERPLATE +# ------------------------ +# Check for compiler boilerplate output or warnings with +# the simple compiler test code. +m4_defun([_LT_COMPILER_BOILERPLATE], +[m4_require([_LT_DECL_SED])dnl +ac_outfile=conftest.$ac_objext +echo "$lt_simple_compile_test_code" >conftest.$ac_ext +eval "$ac_compile" 2>&1 >/dev/null | $SED '/^$/d; /^ *+/d' >conftest.err +_lt_compiler_boilerplate=`cat conftest.err` +$RM conftest* +])# _LT_COMPILER_BOILERPLATE + + +# _LT_LINKER_BOILERPLATE +# ---------------------- +# Check for linker boilerplate output or warnings with +# the simple link test code. +m4_defun([_LT_LINKER_BOILERPLATE], +[m4_require([_LT_DECL_SED])dnl +ac_outfile=conftest.$ac_objext +echo "$lt_simple_link_test_code" >conftest.$ac_ext +eval "$ac_link" 2>&1 >/dev/null | $SED '/^$/d; /^ *+/d' >conftest.err +_lt_linker_boilerplate=`cat conftest.err` +$RM -r conftest* +])# _LT_LINKER_BOILERPLATE + +# _LT_REQUIRED_DARWIN_CHECKS +# ------------------------- +m4_defun_once([_LT_REQUIRED_DARWIN_CHECKS],[ + case $host_os in + rhapsody* | darwin*) + AC_CHECK_TOOL([DSYMUTIL], [dsymutil], [:]) + AC_CHECK_TOOL([NMEDIT], [nmedit], [:]) + AC_CHECK_TOOL([LIPO], [lipo], [:]) + AC_CHECK_TOOL([OTOOL], [otool], [:]) + AC_CHECK_TOOL([OTOOL64], [otool64], [:]) + _LT_DECL([], [DSYMUTIL], [1], + [Tool to manipulate archived DWARF debug symbol files on Mac OS X]) + _LT_DECL([], [NMEDIT], [1], + [Tool to change global to local symbols on Mac OS X]) + _LT_DECL([], [LIPO], [1], + [Tool to manipulate fat objects and archives on Mac OS X]) + _LT_DECL([], [OTOOL], [1], + [ldd/readelf like tool for Mach-O binaries on Mac OS X]) + _LT_DECL([], [OTOOL64], [1], + [ldd/readelf like tool for 64 bit Mach-O binaries on Mac OS X 10.4]) + + AC_CACHE_CHECK([for -single_module linker flag],[lt_cv_apple_cc_single_mod], + [lt_cv_apple_cc_single_mod=no + if test -z "${LT_MULTI_MODULE}"; then + # By default we will add the -single_module flag. You can override + # by either setting the environment variable LT_MULTI_MODULE + # non-empty at configure time, or by adding -multi_module to the + # link flags. + rm -rf libconftest.dylib* + echo "int foo(void){return 1;}" > conftest.c + echo "$LTCC $LTCFLAGS $LDFLAGS -o libconftest.dylib \ +-dynamiclib -Wl,-single_module conftest.c" >&AS_MESSAGE_LOG_FD + $LTCC $LTCFLAGS $LDFLAGS -o libconftest.dylib \ + -dynamiclib -Wl,-single_module conftest.c 2>conftest.err + _lt_result=$? + if test -f libconftest.dylib && test ! -s conftest.err && test $_lt_result = 0; then + lt_cv_apple_cc_single_mod=yes + else + cat conftest.err >&AS_MESSAGE_LOG_FD + fi + rm -rf libconftest.dylib* + rm -f conftest.* + fi]) + AC_CACHE_CHECK([for -exported_symbols_list linker flag], + [lt_cv_ld_exported_symbols_list], + [lt_cv_ld_exported_symbols_list=no + save_LDFLAGS=$LDFLAGS + echo "_main" > conftest.sym + LDFLAGS="$LDFLAGS -Wl,-exported_symbols_list,conftest.sym" + AC_LINK_IFELSE([AC_LANG_PROGRAM([],[])], + [lt_cv_ld_exported_symbols_list=yes], + [lt_cv_ld_exported_symbols_list=no]) + LDFLAGS="$save_LDFLAGS" + ]) + case $host_os in + rhapsody* | darwin1.[[012]]) + _lt_dar_allow_undefined='${wl}-undefined ${wl}suppress' ;; + darwin1.*) + _lt_dar_allow_undefined='${wl}-flat_namespace ${wl}-undefined ${wl}suppress' ;; + darwin*) # darwin 5.x on + # if running on 10.5 or later, the deployment target defaults + # to the OS version, if on x86, and 10.4, the deployment + # target defaults to 10.4. Don't you love it? + case ${MACOSX_DEPLOYMENT_TARGET-10.0},$host in + 10.0,*86*-darwin8*|10.0,*-darwin[[91]]*) + _lt_dar_allow_undefined='${wl}-undefined ${wl}dynamic_lookup' ;; + 10.[[012]]*) + _lt_dar_allow_undefined='${wl}-flat_namespace ${wl}-undefined ${wl}suppress' ;; + 10.*) + _lt_dar_allow_undefined='${wl}-undefined ${wl}dynamic_lookup' ;; + esac + ;; + esac + if test "$lt_cv_apple_cc_single_mod" = "yes"; then + _lt_dar_single_mod='$single_module' + fi + if test "$lt_cv_ld_exported_symbols_list" = "yes"; then + _lt_dar_export_syms=' ${wl}-exported_symbols_list,$output_objdir/${libname}-symbols.expsym' + else + _lt_dar_export_syms='~$NMEDIT -s $output_objdir/${libname}-symbols.expsym ${lib}' + fi + if test "$DSYMUTIL" != ":"; then + _lt_dsymutil='~$DSYMUTIL $lib || :' + else + _lt_dsymutil= + fi + ;; + esac +]) + + +# _LT_DARWIN_LINKER_FEATURES +# -------------------------- +# Checks for linker and compiler features on darwin +m4_defun([_LT_DARWIN_LINKER_FEATURES], +[ + m4_require([_LT_REQUIRED_DARWIN_CHECKS]) + _LT_TAGVAR(archive_cmds_need_lc, $1)=no + _LT_TAGVAR(hardcode_direct, $1)=no + _LT_TAGVAR(hardcode_automatic, $1)=yes + _LT_TAGVAR(hardcode_shlibpath_var, $1)=unsupported + _LT_TAGVAR(whole_archive_flag_spec, $1)='' + _LT_TAGVAR(link_all_deplibs, $1)=yes + _LT_TAGVAR(allow_undefined_flag, $1)="$_lt_dar_allow_undefined" + case $cc_basename in + ifort*) _lt_dar_can_shared=yes ;; + *) _lt_dar_can_shared=$GCC ;; + esac + if test "$_lt_dar_can_shared" = "yes"; then + output_verbose_link_cmd=echo + _LT_TAGVAR(archive_cmds, $1)="\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod${_lt_dsymutil}" + _LT_TAGVAR(module_cmds, $1)="\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dsymutil}" + _LT_TAGVAR(archive_expsym_cmds, $1)="sed 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring ${_lt_dar_single_mod}${_lt_dar_export_syms}${_lt_dsymutil}" + _LT_TAGVAR(module_expsym_cmds, $1)="sed -e 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dar_export_syms}${_lt_dsymutil}" + m4_if([$1], [CXX], +[ if test "$lt_cv_apple_cc_single_mod" != "yes"; then + _LT_TAGVAR(archive_cmds, $1)="\$CC -r -keep_private_externs -nostdlib -o \${lib}-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \${lib}-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring${_lt_dsymutil}" + _LT_TAGVAR(archive_expsym_cmds, $1)="sed 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC -r -keep_private_externs -nostdlib -o \${lib}-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \${lib}-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring${_lt_dar_export_syms}${_lt_dsymutil}" + fi +],[]) + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi +]) + +# _LT_SYS_MODULE_PATH_AIX +# ----------------------- +# Links a minimal program and checks the executable +# for the system default hardcoded library path. In most cases, +# this is /usr/lib:/lib, but when the MPI compilers are used +# the location of the communication and MPI libs are included too. +# If we don't find anything, use the default library path according +# to the aix ld manual. +m4_defun([_LT_SYS_MODULE_PATH_AIX], +[m4_require([_LT_DECL_SED])dnl +AC_LINK_IFELSE(AC_LANG_PROGRAM,[ +lt_aix_libpath_sed=' + /Import File Strings/,/^$/ { + /^0/ { + s/^0 *\(.*\)$/\1/ + p + } + }' +aix_libpath=`dump -H conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` +# Check for a 64-bit object if we didn't find anything. +if test -z "$aix_libpath"; then + aix_libpath=`dump -HX64 conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` +fi],[]) +if test -z "$aix_libpath"; then aix_libpath="/usr/lib:/lib"; fi +])# _LT_SYS_MODULE_PATH_AIX + + +# _LT_SHELL_INIT(ARG) +# ------------------- +m4_define([_LT_SHELL_INIT], +[ifdef([AC_DIVERSION_NOTICE], + [AC_DIVERT_PUSH(AC_DIVERSION_NOTICE)], + [AC_DIVERT_PUSH(NOTICE)]) +$1 +AC_DIVERT_POP +])# _LT_SHELL_INIT + + +# _LT_PROG_ECHO_BACKSLASH +# ----------------------- +# Add some code to the start of the generated configure script which +# will find an echo command which doesn't interpret backslashes. +m4_defun([_LT_PROG_ECHO_BACKSLASH], +[_LT_SHELL_INIT([ +# Check that we are running under the correct shell. +SHELL=${CONFIG_SHELL-/bin/sh} + +case X$lt_ECHO in +X*--fallback-echo) + # Remove one level of quotation (which was required for Make). + ECHO=`echo "$lt_ECHO" | sed 's,\\\\\[$]\\[$]0,'[$]0','` + ;; +esac + +ECHO=${lt_ECHO-echo} +if test "X[$]1" = X--no-reexec; then + # Discard the --no-reexec flag, and continue. + shift +elif test "X[$]1" = X--fallback-echo; then + # Avoid inline document here, it may be left over + : +elif test "X`{ $ECHO '\t'; } 2>/dev/null`" = 'X\t' ; then + # Yippee, $ECHO works! + : +else + # Restart under the correct shell. + exec $SHELL "[$]0" --no-reexec ${1+"[$]@"} +fi + +if test "X[$]1" = X--fallback-echo; then + # used as fallback echo + shift + cat <<_LT_EOF +[$]* +_LT_EOF + exit 0 +fi + +# The HP-UX ksh and POSIX shell print the target directory to stdout +# if CDPATH is set. +(unset CDPATH) >/dev/null 2>&1 && unset CDPATH + +if test -z "$lt_ECHO"; then + if test "X${echo_test_string+set}" != Xset; then + # find a string as large as possible, as long as the shell can cope with it + for cmd in 'sed 50q "[$]0"' 'sed 20q "[$]0"' 'sed 10q "[$]0"' 'sed 2q "[$]0"' 'echo test'; do + # expected sizes: less than 2Kb, 1Kb, 512 bytes, 16 bytes, ... + if { echo_test_string=`eval $cmd`; } 2>/dev/null && + { test "X$echo_test_string" = "X$echo_test_string"; } 2>/dev/null + then + break + fi + done + fi + + if test "X`{ $ECHO '\t'; } 2>/dev/null`" = 'X\t' && + echo_testing_string=`{ $ECHO "$echo_test_string"; } 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + : + else + # The Solaris, AIX, and Digital Unix default echo programs unquote + # backslashes. This makes it impossible to quote backslashes using + # echo "$something" | sed 's/\\/\\\\/g' + # + # So, first we look for a working echo in the user's PATH. + + lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + for dir in $PATH /usr/ucb; do + IFS="$lt_save_ifs" + if (test -f $dir/echo || test -f $dir/echo$ac_exeext) && + test "X`($dir/echo '\t') 2>/dev/null`" = 'X\t' && + echo_testing_string=`($dir/echo "$echo_test_string") 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + ECHO="$dir/echo" + break + fi + done + IFS="$lt_save_ifs" + + if test "X$ECHO" = Xecho; then + # We didn't find a better echo, so look for alternatives. + if test "X`{ print -r '\t'; } 2>/dev/null`" = 'X\t' && + echo_testing_string=`{ print -r "$echo_test_string"; } 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + # This shell has a builtin print -r that does the trick. + ECHO='print -r' + elif { test -f /bin/ksh || test -f /bin/ksh$ac_exeext; } && + test "X$CONFIG_SHELL" != X/bin/ksh; then + # If we have ksh, try running configure again with it. + ORIGINAL_CONFIG_SHELL=${CONFIG_SHELL-/bin/sh} + export ORIGINAL_CONFIG_SHELL + CONFIG_SHELL=/bin/ksh + export CONFIG_SHELL + exec $CONFIG_SHELL "[$]0" --no-reexec ${1+"[$]@"} + else + # Try using printf. + ECHO='printf %s\n' + if test "X`{ $ECHO '\t'; } 2>/dev/null`" = 'X\t' && + echo_testing_string=`{ $ECHO "$echo_test_string"; } 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + # Cool, printf works + : + elif echo_testing_string=`($ORIGINAL_CONFIG_SHELL "[$]0" --fallback-echo '\t') 2>/dev/null` && + test "X$echo_testing_string" = 'X\t' && + echo_testing_string=`($ORIGINAL_CONFIG_SHELL "[$]0" --fallback-echo "$echo_test_string") 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + CONFIG_SHELL=$ORIGINAL_CONFIG_SHELL + export CONFIG_SHELL + SHELL="$CONFIG_SHELL" + export SHELL + ECHO="$CONFIG_SHELL [$]0 --fallback-echo" + elif echo_testing_string=`($CONFIG_SHELL "[$]0" --fallback-echo '\t') 2>/dev/null` && + test "X$echo_testing_string" = 'X\t' && + echo_testing_string=`($CONFIG_SHELL "[$]0" --fallback-echo "$echo_test_string") 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + ECHO="$CONFIG_SHELL [$]0 --fallback-echo" + else + # maybe with a smaller string... + prev=: + + for cmd in 'echo test' 'sed 2q "[$]0"' 'sed 10q "[$]0"' 'sed 20q "[$]0"' 'sed 50q "[$]0"'; do + if { test "X$echo_test_string" = "X`eval $cmd`"; } 2>/dev/null + then + break + fi + prev="$cmd" + done + + if test "$prev" != 'sed 50q "[$]0"'; then + echo_test_string=`eval $prev` + export echo_test_string + exec ${ORIGINAL_CONFIG_SHELL-${CONFIG_SHELL-/bin/sh}} "[$]0" ${1+"[$]@"} + else + # Oops. We lost completely, so just stick with echo. + ECHO=echo + fi + fi + fi + fi + fi +fi + +# Copy echo and quote the copy suitably for passing to libtool from +# the Makefile, instead of quoting the original, which is used later. +lt_ECHO=$ECHO +if test "X$lt_ECHO" = "X$CONFIG_SHELL [$]0 --fallback-echo"; then + lt_ECHO="$CONFIG_SHELL \\\$\[$]0 --fallback-echo" +fi + +AC_SUBST(lt_ECHO) +]) +_LT_DECL([], [SHELL], [1], [Shell to use when invoking shell scripts]) +_LT_DECL([], [ECHO], [1], + [An echo program that does not interpret backslashes]) +])# _LT_PROG_ECHO_BACKSLASH + + +# _LT_ENABLE_LOCK +# --------------- +m4_defun([_LT_ENABLE_LOCK], +[AC_ARG_ENABLE([libtool-lock], + [AS_HELP_STRING([--disable-libtool-lock], + [avoid locking (might break parallel builds)])]) +test "x$enable_libtool_lock" != xno && enable_libtool_lock=yes + +# Some flags need to be propagated to the compiler or linker for good +# libtool support. +case $host in +ia64-*-hpux*) + # Find out which ABI we are using. + echo 'int i;' > conftest.$ac_ext + if AC_TRY_EVAL(ac_compile); then + case `/usr/bin/file conftest.$ac_objext` in + *ELF-32*) + HPUX_IA64_MODE="32" + ;; + *ELF-64*) + HPUX_IA64_MODE="64" + ;; + esac + fi + rm -rf conftest* + ;; +*-*-irix6*) + # Find out which ABI we are using. + echo '[#]line __oline__ "configure"' > conftest.$ac_ext + if AC_TRY_EVAL(ac_compile); then + if test "$lt_cv_prog_gnu_ld" = yes; then + case `/usr/bin/file conftest.$ac_objext` in + *32-bit*) + LD="${LD-ld} -melf32bsmip" + ;; + *N32*) + LD="${LD-ld} -melf32bmipn32" + ;; + *64-bit*) + LD="${LD-ld} -melf64bmip" + ;; + esac + else + case `/usr/bin/file conftest.$ac_objext` in + *32-bit*) + LD="${LD-ld} -32" + ;; + *N32*) + LD="${LD-ld} -n32" + ;; + *64-bit*) + LD="${LD-ld} -64" + ;; + esac + fi + fi + rm -rf conftest* + ;; + +x86_64-*kfreebsd*-gnu|x86_64-*linux*|ppc*-*linux*|powerpc*-*linux*| \ +s390*-*linux*|s390*-*tpf*|sparc*-*linux*) + # Find out which ABI we are using. + echo 'int i;' > conftest.$ac_ext + if AC_TRY_EVAL(ac_compile); then + case `/usr/bin/file conftest.o` in + *32-bit*) + case $host in + x86_64-*kfreebsd*-gnu) + LD="${LD-ld} -m elf_i386_fbsd" + ;; + x86_64-*linux*) + LD="${LD-ld} -m elf_i386" + ;; + ppc64-*linux*|powerpc64-*linux*) + LD="${LD-ld} -m elf32ppclinux" + ;; + s390x-*linux*) + LD="${LD-ld} -m elf_s390" + ;; + sparc64-*linux*) + LD="${LD-ld} -m elf32_sparc" + ;; + esac + ;; + *64-bit*) + case $host in + x86_64-*kfreebsd*-gnu) + LD="${LD-ld} -m elf_x86_64_fbsd" + ;; + x86_64-*linux*) + LD="${LD-ld} -m elf_x86_64" + ;; + ppc*-*linux*|powerpc*-*linux*) + LD="${LD-ld} -m elf64ppc" + ;; + s390*-*linux*|s390*-*tpf*) + LD="${LD-ld} -m elf64_s390" + ;; + sparc*-*linux*) + LD="${LD-ld} -m elf64_sparc" + ;; + esac + ;; + esac + fi + rm -rf conftest* + ;; + +*-*-sco3.2v5*) + # On SCO OpenServer 5, we need -belf to get full-featured binaries. + SAVE_CFLAGS="$CFLAGS" + CFLAGS="$CFLAGS -belf" + AC_CACHE_CHECK([whether the C compiler needs -belf], lt_cv_cc_needs_belf, + [AC_LANG_PUSH(C) + AC_LINK_IFELSE([AC_LANG_PROGRAM([[]],[[]])],[lt_cv_cc_needs_belf=yes],[lt_cv_cc_needs_belf=no]) + AC_LANG_POP]) + if test x"$lt_cv_cc_needs_belf" != x"yes"; then + # this is probably gcc 2.8.0, egcs 1.0 or newer; no need for -belf + CFLAGS="$SAVE_CFLAGS" + fi + ;; +sparc*-*solaris*) + # Find out which ABI we are using. + echo 'int i;' > conftest.$ac_ext + if AC_TRY_EVAL(ac_compile); then + case `/usr/bin/file conftest.o` in + *64-bit*) + case $lt_cv_prog_gnu_ld in + yes*) LD="${LD-ld} -m elf64_sparc" ;; + *) + if ${LD-ld} -64 -r -o conftest2.o conftest.o >/dev/null 2>&1; then + LD="${LD-ld} -64" + fi + ;; + esac + ;; + esac + fi + rm -rf conftest* + ;; +esac + +need_locks="$enable_libtool_lock" +])# _LT_ENABLE_LOCK + + +# _LT_CMD_OLD_ARCHIVE +# ------------------- +m4_defun([_LT_CMD_OLD_ARCHIVE], +[AC_CHECK_TOOL(AR, ar, false) +test -z "$AR" && AR=ar +test -z "$AR_FLAGS" && AR_FLAGS=cru +_LT_DECL([], [AR], [1], [The archiver]) +_LT_DECL([], [AR_FLAGS], [1]) + +AC_CHECK_TOOL(STRIP, strip, :) +test -z "$STRIP" && STRIP=: +_LT_DECL([], [STRIP], [1], [A symbol stripping program]) + +AC_CHECK_TOOL(RANLIB, ranlib, :) +test -z "$RANLIB" && RANLIB=: +_LT_DECL([], [RANLIB], [1], + [Commands used to install an old-style archive]) + +# Determine commands to create old-style static archives. +old_archive_cmds='$AR $AR_FLAGS $oldlib$oldobjs' +old_postinstall_cmds='chmod 644 $oldlib' +old_postuninstall_cmds= + +if test -n "$RANLIB"; then + case $host_os in + openbsd*) + old_postinstall_cmds="$old_postinstall_cmds~\$RANLIB -t \$oldlib" + ;; + *) + old_postinstall_cmds="$old_postinstall_cmds~\$RANLIB \$oldlib" + ;; + esac + old_archive_cmds="$old_archive_cmds~\$RANLIB \$oldlib" +fi +_LT_DECL([], [old_postinstall_cmds], [2]) +_LT_DECL([], [old_postuninstall_cmds], [2]) +_LT_TAGDECL([], [old_archive_cmds], [2], + [Commands used to build an old-style archive]) +])# _LT_CMD_OLD_ARCHIVE + + +# _LT_COMPILER_OPTION(MESSAGE, VARIABLE-NAME, FLAGS, +# [OUTPUT-FILE], [ACTION-SUCCESS], [ACTION-FAILURE]) +# ---------------------------------------------------------------- +# Check whether the given compiler option works +AC_DEFUN([_LT_COMPILER_OPTION], +[m4_require([_LT_FILEUTILS_DEFAULTS])dnl +m4_require([_LT_DECL_SED])dnl +AC_CACHE_CHECK([$1], [$2], + [$2=no + m4_if([$4], , [ac_outfile=conftest.$ac_objext], [ac_outfile=$4]) + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + lt_compiler_flag="$3" + # Insert the option either (1) after the last *FLAGS variable, or + # (2) before a word containing "conftest.", or (3) at the end. + # Note that $ac_compile itself does not contain backslashes and begins + # with a dollar sign (not a hyphen), so the echo should work correctly. + # The option is referenced via a variable to avoid confusing sed. + lt_compile=`echo "$ac_compile" | $SED \ + -e 's:.*FLAGS}\{0,1\} :&$lt_compiler_flag :; t' \ + -e 's: [[^ ]]*conftest\.: $lt_compiler_flag&:; t' \ + -e 's:$: $lt_compiler_flag:'` + (eval echo "\"\$as_me:__oline__: $lt_compile\"" >&AS_MESSAGE_LOG_FD) + (eval "$lt_compile" 2>conftest.err) + ac_status=$? + cat conftest.err >&AS_MESSAGE_LOG_FD + echo "$as_me:__oline__: \$? = $ac_status" >&AS_MESSAGE_LOG_FD + if (exit $ac_status) && test -s "$ac_outfile"; then + # The compiler can only warn and ignore the option if not recognized + # So say no if there are warnings other than the usual output. + $ECHO "X$_lt_compiler_boilerplate" | $Xsed -e '/^$/d' >conftest.exp + $SED '/^$/d; /^ *+/d' conftest.err >conftest.er2 + if test ! -s conftest.er2 || diff conftest.exp conftest.er2 >/dev/null; then + $2=yes + fi + fi + $RM conftest* +]) + +if test x"[$]$2" = xyes; then + m4_if([$5], , :, [$5]) +else + m4_if([$6], , :, [$6]) +fi +])# _LT_COMPILER_OPTION + +# Old name: +AU_ALIAS([AC_LIBTOOL_COMPILER_OPTION], [_LT_COMPILER_OPTION]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_LIBTOOL_COMPILER_OPTION], []) + + +# _LT_LINKER_OPTION(MESSAGE, VARIABLE-NAME, FLAGS, +# [ACTION-SUCCESS], [ACTION-FAILURE]) +# ---------------------------------------------------- +# Check whether the given linker option works +AC_DEFUN([_LT_LINKER_OPTION], +[m4_require([_LT_FILEUTILS_DEFAULTS])dnl +m4_require([_LT_DECL_SED])dnl +AC_CACHE_CHECK([$1], [$2], + [$2=no + save_LDFLAGS="$LDFLAGS" + LDFLAGS="$LDFLAGS $3" + echo "$lt_simple_link_test_code" > conftest.$ac_ext + if (eval $ac_link 2>conftest.err) && test -s conftest$ac_exeext; then + # The linker can only warn and ignore the option if not recognized + # So say no if there are warnings + if test -s conftest.err; then + # Append any errors to the config.log. + cat conftest.err 1>&AS_MESSAGE_LOG_FD + $ECHO "X$_lt_linker_boilerplate" | $Xsed -e '/^$/d' > conftest.exp + $SED '/^$/d; /^ *+/d' conftest.err >conftest.er2 + if diff conftest.exp conftest.er2 >/dev/null; then + $2=yes + fi + else + $2=yes + fi + fi + $RM -r conftest* + LDFLAGS="$save_LDFLAGS" +]) + +if test x"[$]$2" = xyes; then + m4_if([$4], , :, [$4]) +else + m4_if([$5], , :, [$5]) +fi +])# _LT_LINKER_OPTION + +# Old name: +AU_ALIAS([AC_LIBTOOL_LINKER_OPTION], [_LT_LINKER_OPTION]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_LIBTOOL_LINKER_OPTION], []) + + +# LT_CMD_MAX_LEN +#--------------- +AC_DEFUN([LT_CMD_MAX_LEN], +[AC_REQUIRE([AC_CANONICAL_HOST])dnl +# find the maximum length of command line arguments +AC_MSG_CHECKING([the maximum length of command line arguments]) +AC_CACHE_VAL([lt_cv_sys_max_cmd_len], [dnl + i=0 + teststring="ABCD" + + case $build_os in + msdosdjgpp*) + # On DJGPP, this test can blow up pretty badly due to problems in libc + # (any single argument exceeding 2000 bytes causes a buffer overrun + # during glob expansion). Even if it were fixed, the result of this + # check would be larger than it should be. + lt_cv_sys_max_cmd_len=12288; # 12K is about right + ;; + + gnu*) + # Under GNU Hurd, this test is not required because there is + # no limit to the length of command line arguments. + # Libtool will interpret -1 as no limit whatsoever + lt_cv_sys_max_cmd_len=-1; + ;; + + cygwin* | mingw* | cegcc*) + # On Win9x/ME, this test blows up -- it succeeds, but takes + # about 5 minutes as the teststring grows exponentially. + # Worse, since 9x/ME are not pre-emptively multitasking, + # you end up with a "frozen" computer, even though with patience + # the test eventually succeeds (with a max line length of 256k). + # Instead, let's just punt: use the minimum linelength reported by + # all of the supported platforms: 8192 (on NT/2K/XP). + lt_cv_sys_max_cmd_len=8192; + ;; + + amigaos*) + # On AmigaOS with pdksh, this test takes hours, literally. + # So we just punt and use a minimum line length of 8192. + lt_cv_sys_max_cmd_len=8192; + ;; + + netbsd* | freebsd* | openbsd* | darwin* | dragonfly*) + # This has been around since 386BSD, at least. Likely further. + if test -x /sbin/sysctl; then + lt_cv_sys_max_cmd_len=`/sbin/sysctl -n kern.argmax` + elif test -x /usr/sbin/sysctl; then + lt_cv_sys_max_cmd_len=`/usr/sbin/sysctl -n kern.argmax` + else + lt_cv_sys_max_cmd_len=65536 # usable default for all BSDs + fi + # And add a safety zone + lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \/ 4` + lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \* 3` + ;; + + interix*) + # We know the value 262144 and hardcode it with a safety zone (like BSD) + lt_cv_sys_max_cmd_len=196608 + ;; + + osf*) + # Dr. Hans Ekkehard Plesser reports seeing a kernel panic running configure + # due to this test when exec_disable_arg_limit is 1 on Tru64. It is not + # nice to cause kernel panics so lets avoid the loop below. + # First set a reasonable default. + lt_cv_sys_max_cmd_len=16384 + # + if test -x /sbin/sysconfig; then + case `/sbin/sysconfig -q proc exec_disable_arg_limit` in + *1*) lt_cv_sys_max_cmd_len=-1 ;; + esac + fi + ;; + sco3.2v5*) + lt_cv_sys_max_cmd_len=102400 + ;; + sysv5* | sco5v6* | sysv4.2uw2*) + kargmax=`grep ARG_MAX /etc/conf/cf.d/stune 2>/dev/null` + if test -n "$kargmax"; then + lt_cv_sys_max_cmd_len=`echo $kargmax | sed 's/.*[[ ]]//'` + else + lt_cv_sys_max_cmd_len=32768 + fi + ;; + *) + lt_cv_sys_max_cmd_len=`(getconf ARG_MAX) 2> /dev/null` + if test -n "$lt_cv_sys_max_cmd_len"; then + lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \/ 4` + lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \* 3` + else + # Make teststring a little bigger before we do anything with it. + # a 1K string should be a reasonable start. + for i in 1 2 3 4 5 6 7 8 ; do + teststring=$teststring$teststring + done + SHELL=${SHELL-${CONFIG_SHELL-/bin/sh}} + # If test is not a shell built-in, we'll probably end up computing a + # maximum length that is only half of the actual maximum length, but + # we can't tell. + while { test "X"`$SHELL [$]0 --fallback-echo "X$teststring$teststring" 2>/dev/null` \ + = "XX$teststring$teststring"; } >/dev/null 2>&1 && + test $i != 17 # 1/2 MB should be enough + do + i=`expr $i + 1` + teststring=$teststring$teststring + done + # Only check the string length outside the loop. + lt_cv_sys_max_cmd_len=`expr "X$teststring" : ".*" 2>&1` + teststring= + # Add a significant safety factor because C++ compilers can tack on + # massive amounts of additional arguments before passing them to the + # linker. It appears as though 1/2 is a usable value. + lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \/ 2` + fi + ;; + esac +]) +if test -n $lt_cv_sys_max_cmd_len ; then + AC_MSG_RESULT($lt_cv_sys_max_cmd_len) +else + AC_MSG_RESULT(none) +fi +max_cmd_len=$lt_cv_sys_max_cmd_len +_LT_DECL([], [max_cmd_len], [0], + [What is the maximum length of a command?]) +])# LT_CMD_MAX_LEN + +# Old name: +AU_ALIAS([AC_LIBTOOL_SYS_MAX_CMD_LEN], [LT_CMD_MAX_LEN]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_LIBTOOL_SYS_MAX_CMD_LEN], []) + + +# _LT_HEADER_DLFCN +# ---------------- +m4_defun([_LT_HEADER_DLFCN], +[AC_CHECK_HEADERS([dlfcn.h], [], [], [AC_INCLUDES_DEFAULT])dnl +])# _LT_HEADER_DLFCN + + +# _LT_TRY_DLOPEN_SELF (ACTION-IF-TRUE, ACTION-IF-TRUE-W-USCORE, +# ACTION-IF-FALSE, ACTION-IF-CROSS-COMPILING) +# ---------------------------------------------------------------- +m4_defun([_LT_TRY_DLOPEN_SELF], +[m4_require([_LT_HEADER_DLFCN])dnl +if test "$cross_compiling" = yes; then : + [$4] +else + lt_dlunknown=0; lt_dlno_uscore=1; lt_dlneed_uscore=2 + lt_status=$lt_dlunknown + cat > conftest.$ac_ext <<_LT_EOF +[#line __oline__ "configure" +#include "confdefs.h" + +#if HAVE_DLFCN_H +#include +#endif + +#include + +#ifdef RTLD_GLOBAL +# define LT_DLGLOBAL RTLD_GLOBAL +#else +# ifdef DL_GLOBAL +# define LT_DLGLOBAL DL_GLOBAL +# else +# define LT_DLGLOBAL 0 +# endif +#endif + +/* We may have to define LT_DLLAZY_OR_NOW in the command line if we + find out it does not work in some platform. */ +#ifndef LT_DLLAZY_OR_NOW +# ifdef RTLD_LAZY +# define LT_DLLAZY_OR_NOW RTLD_LAZY +# else +# ifdef DL_LAZY +# define LT_DLLAZY_OR_NOW DL_LAZY +# else +# ifdef RTLD_NOW +# define LT_DLLAZY_OR_NOW RTLD_NOW +# else +# ifdef DL_NOW +# define LT_DLLAZY_OR_NOW DL_NOW +# else +# define LT_DLLAZY_OR_NOW 0 +# endif +# endif +# endif +# endif +#endif + +void fnord() { int i=42;} +int main () +{ + void *self = dlopen (0, LT_DLGLOBAL|LT_DLLAZY_OR_NOW); + int status = $lt_dlunknown; + + if (self) + { + if (dlsym (self,"fnord")) status = $lt_dlno_uscore; + else if (dlsym( self,"_fnord")) status = $lt_dlneed_uscore; + /* dlclose (self); */ + } + else + puts (dlerror ()); + + return status; +}] +_LT_EOF + if AC_TRY_EVAL(ac_link) && test -s conftest${ac_exeext} 2>/dev/null; then + (./conftest; exit; ) >&AS_MESSAGE_LOG_FD 2>/dev/null + lt_status=$? + case x$lt_status in + x$lt_dlno_uscore) $1 ;; + x$lt_dlneed_uscore) $2 ;; + x$lt_dlunknown|x*) $3 ;; + esac + else : + # compilation failed + $3 + fi +fi +rm -fr conftest* +])# _LT_TRY_DLOPEN_SELF + + +# LT_SYS_DLOPEN_SELF +# ------------------ +AC_DEFUN([LT_SYS_DLOPEN_SELF], +[m4_require([_LT_HEADER_DLFCN])dnl +if test "x$enable_dlopen" != xyes; then + enable_dlopen=unknown + enable_dlopen_self=unknown + enable_dlopen_self_static=unknown +else + lt_cv_dlopen=no + lt_cv_dlopen_libs= + + case $host_os in + beos*) + lt_cv_dlopen="load_add_on" + lt_cv_dlopen_libs= + lt_cv_dlopen_self=yes + ;; + + mingw* | pw32* | cegcc*) + lt_cv_dlopen="LoadLibrary" + lt_cv_dlopen_libs= + ;; + + cygwin*) + lt_cv_dlopen="dlopen" + lt_cv_dlopen_libs= + ;; + + darwin*) + # if libdl is installed we need to link against it + AC_CHECK_LIB([dl], [dlopen], + [lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-ldl"],[ + lt_cv_dlopen="dyld" + lt_cv_dlopen_libs= + lt_cv_dlopen_self=yes + ]) + ;; + + *) + AC_CHECK_FUNC([shl_load], + [lt_cv_dlopen="shl_load"], + [AC_CHECK_LIB([dld], [shl_load], + [lt_cv_dlopen="shl_load" lt_cv_dlopen_libs="-ldld"], + [AC_CHECK_FUNC([dlopen], + [lt_cv_dlopen="dlopen"], + [AC_CHECK_LIB([dl], [dlopen], + [lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-ldl"], + [AC_CHECK_LIB([svld], [dlopen], + [lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-lsvld"], + [AC_CHECK_LIB([dld], [dld_link], + [lt_cv_dlopen="dld_link" lt_cv_dlopen_libs="-ldld"]) + ]) + ]) + ]) + ]) + ]) + ;; + esac + + if test "x$lt_cv_dlopen" != xno; then + enable_dlopen=yes + else + enable_dlopen=no + fi + + case $lt_cv_dlopen in + dlopen) + save_CPPFLAGS="$CPPFLAGS" + test "x$ac_cv_header_dlfcn_h" = xyes && CPPFLAGS="$CPPFLAGS -DHAVE_DLFCN_H" + + save_LDFLAGS="$LDFLAGS" + wl=$lt_prog_compiler_wl eval LDFLAGS=\"\$LDFLAGS $export_dynamic_flag_spec\" + + save_LIBS="$LIBS" + LIBS="$lt_cv_dlopen_libs $LIBS" + + AC_CACHE_CHECK([whether a program can dlopen itself], + lt_cv_dlopen_self, [dnl + _LT_TRY_DLOPEN_SELF( + lt_cv_dlopen_self=yes, lt_cv_dlopen_self=yes, + lt_cv_dlopen_self=no, lt_cv_dlopen_self=cross) + ]) + + if test "x$lt_cv_dlopen_self" = xyes; then + wl=$lt_prog_compiler_wl eval LDFLAGS=\"\$LDFLAGS $lt_prog_compiler_static\" + AC_CACHE_CHECK([whether a statically linked program can dlopen itself], + lt_cv_dlopen_self_static, [dnl + _LT_TRY_DLOPEN_SELF( + lt_cv_dlopen_self_static=yes, lt_cv_dlopen_self_static=yes, + lt_cv_dlopen_self_static=no, lt_cv_dlopen_self_static=cross) + ]) + fi + + CPPFLAGS="$save_CPPFLAGS" + LDFLAGS="$save_LDFLAGS" + LIBS="$save_LIBS" + ;; + esac + + case $lt_cv_dlopen_self in + yes|no) enable_dlopen_self=$lt_cv_dlopen_self ;; + *) enable_dlopen_self=unknown ;; + esac + + case $lt_cv_dlopen_self_static in + yes|no) enable_dlopen_self_static=$lt_cv_dlopen_self_static ;; + *) enable_dlopen_self_static=unknown ;; + esac +fi +_LT_DECL([dlopen_support], [enable_dlopen], [0], + [Whether dlopen is supported]) +_LT_DECL([dlopen_self], [enable_dlopen_self], [0], + [Whether dlopen of programs is supported]) +_LT_DECL([dlopen_self_static], [enable_dlopen_self_static], [0], + [Whether dlopen of statically linked programs is supported]) +])# LT_SYS_DLOPEN_SELF + +# Old name: +AU_ALIAS([AC_LIBTOOL_DLOPEN_SELF], [LT_SYS_DLOPEN_SELF]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_LIBTOOL_DLOPEN_SELF], []) + + +# _LT_COMPILER_C_O([TAGNAME]) +# --------------------------- +# Check to see if options -c and -o are simultaneously supported by compiler. +# This macro does not hard code the compiler like AC_PROG_CC_C_O. +m4_defun([_LT_COMPILER_C_O], +[m4_require([_LT_DECL_SED])dnl +m4_require([_LT_FILEUTILS_DEFAULTS])dnl +m4_require([_LT_TAG_COMPILER])dnl +AC_CACHE_CHECK([if $compiler supports -c -o file.$ac_objext], + [_LT_TAGVAR(lt_cv_prog_compiler_c_o, $1)], + [_LT_TAGVAR(lt_cv_prog_compiler_c_o, $1)=no + $RM -r conftest 2>/dev/null + mkdir conftest + cd conftest + mkdir out + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + + lt_compiler_flag="-o out/conftest2.$ac_objext" + # Insert the option either (1) after the last *FLAGS variable, or + # (2) before a word containing "conftest.", or (3) at the end. + # Note that $ac_compile itself does not contain backslashes and begins + # with a dollar sign (not a hyphen), so the echo should work correctly. + lt_compile=`echo "$ac_compile" | $SED \ + -e 's:.*FLAGS}\{0,1\} :&$lt_compiler_flag :; t' \ + -e 's: [[^ ]]*conftest\.: $lt_compiler_flag&:; t' \ + -e 's:$: $lt_compiler_flag:'` + (eval echo "\"\$as_me:__oline__: $lt_compile\"" >&AS_MESSAGE_LOG_FD) + (eval "$lt_compile" 2>out/conftest.err) + ac_status=$? + cat out/conftest.err >&AS_MESSAGE_LOG_FD + echo "$as_me:__oline__: \$? = $ac_status" >&AS_MESSAGE_LOG_FD + if (exit $ac_status) && test -s out/conftest2.$ac_objext + then + # The compiler can only warn and ignore the option if not recognized + # So say no if there are warnings + $ECHO "X$_lt_compiler_boilerplate" | $Xsed -e '/^$/d' > out/conftest.exp + $SED '/^$/d; /^ *+/d' out/conftest.err >out/conftest.er2 + if test ! -s out/conftest.er2 || diff out/conftest.exp out/conftest.er2 >/dev/null; then + _LT_TAGVAR(lt_cv_prog_compiler_c_o, $1)=yes + fi + fi + chmod u+w . 2>&AS_MESSAGE_LOG_FD + $RM conftest* + # SGI C++ compiler will create directory out/ii_files/ for + # template instantiation + test -d out/ii_files && $RM out/ii_files/* && rmdir out/ii_files + $RM out/* && rmdir out + cd .. + $RM -r conftest + $RM conftest* +]) +_LT_TAGDECL([compiler_c_o], [lt_cv_prog_compiler_c_o], [1], + [Does compiler simultaneously support -c and -o options?]) +])# _LT_COMPILER_C_O + + +# _LT_COMPILER_FILE_LOCKS([TAGNAME]) +# ---------------------------------- +# Check to see if we can do hard links to lock some files if needed +m4_defun([_LT_COMPILER_FILE_LOCKS], +[m4_require([_LT_ENABLE_LOCK])dnl +m4_require([_LT_FILEUTILS_DEFAULTS])dnl +_LT_COMPILER_C_O([$1]) + +hard_links="nottested" +if test "$_LT_TAGVAR(lt_cv_prog_compiler_c_o, $1)" = no && test "$need_locks" != no; then + # do not overwrite the value of need_locks provided by the user + AC_MSG_CHECKING([if we can lock with hard links]) + hard_links=yes + $RM conftest* + ln conftest.a conftest.b 2>/dev/null && hard_links=no + touch conftest.a + ln conftest.a conftest.b 2>&5 || hard_links=no + ln conftest.a conftest.b 2>/dev/null && hard_links=no + AC_MSG_RESULT([$hard_links]) + if test "$hard_links" = no; then + AC_MSG_WARN([`$CC' does not support `-c -o', so `make -j' may be unsafe]) + need_locks=warn + fi +else + need_locks=no +fi +_LT_DECL([], [need_locks], [1], [Must we lock files when doing compilation?]) +])# _LT_COMPILER_FILE_LOCKS + + +# _LT_CHECK_OBJDIR +# ---------------- +m4_defun([_LT_CHECK_OBJDIR], +[AC_CACHE_CHECK([for objdir], [lt_cv_objdir], +[rm -f .libs 2>/dev/null +mkdir .libs 2>/dev/null +if test -d .libs; then + lt_cv_objdir=.libs +else + # MS-DOS does not allow filenames that begin with a dot. + lt_cv_objdir=_libs +fi +rmdir .libs 2>/dev/null]) +objdir=$lt_cv_objdir +_LT_DECL([], [objdir], [0], + [The name of the directory that contains temporary libtool files])dnl +m4_pattern_allow([LT_OBJDIR])dnl +AC_DEFINE_UNQUOTED(LT_OBJDIR, "$lt_cv_objdir/", + [Define to the sub-directory in which libtool stores uninstalled libraries.]) +])# _LT_CHECK_OBJDIR + + +# _LT_LINKER_HARDCODE_LIBPATH([TAGNAME]) +# -------------------------------------- +# Check hardcoding attributes. +m4_defun([_LT_LINKER_HARDCODE_LIBPATH], +[AC_MSG_CHECKING([how to hardcode library paths into programs]) +_LT_TAGVAR(hardcode_action, $1)= +if test -n "$_LT_TAGVAR(hardcode_libdir_flag_spec, $1)" || + test -n "$_LT_TAGVAR(runpath_var, $1)" || + test "X$_LT_TAGVAR(hardcode_automatic, $1)" = "Xyes" ; then + + # We can hardcode non-existent directories. + if test "$_LT_TAGVAR(hardcode_direct, $1)" != no && + # If the only mechanism to avoid hardcoding is shlibpath_var, we + # have to relink, otherwise we might link with an installed library + # when we should be linking with a yet-to-be-installed one + ## test "$_LT_TAGVAR(hardcode_shlibpath_var, $1)" != no && + test "$_LT_TAGVAR(hardcode_minus_L, $1)" != no; then + # Linking always hardcodes the temporary library directory. + _LT_TAGVAR(hardcode_action, $1)=relink + else + # We can link without hardcoding, and we can hardcode nonexisting dirs. + _LT_TAGVAR(hardcode_action, $1)=immediate + fi +else + # We cannot hardcode anything, or else we can only hardcode existing + # directories. + _LT_TAGVAR(hardcode_action, $1)=unsupported +fi +AC_MSG_RESULT([$_LT_TAGVAR(hardcode_action, $1)]) + +if test "$_LT_TAGVAR(hardcode_action, $1)" = relink || + test "$_LT_TAGVAR(inherit_rpath, $1)" = yes; then + # Fast installation is not supported + enable_fast_install=no +elif test "$shlibpath_overrides_runpath" = yes || + test "$enable_shared" = no; then + # Fast installation is not necessary + enable_fast_install=needless +fi +_LT_TAGDECL([], [hardcode_action], [0], + [How to hardcode a shared library path into an executable]) +])# _LT_LINKER_HARDCODE_LIBPATH + + +# _LT_CMD_STRIPLIB +# ---------------- +m4_defun([_LT_CMD_STRIPLIB], +[m4_require([_LT_DECL_EGREP]) +striplib= +old_striplib= +AC_MSG_CHECKING([whether stripping libraries is possible]) +if test -n "$STRIP" && $STRIP -V 2>&1 | $GREP "GNU strip" >/dev/null; then + test -z "$old_striplib" && old_striplib="$STRIP --strip-debug" + test -z "$striplib" && striplib="$STRIP --strip-unneeded" + AC_MSG_RESULT([yes]) +else +# FIXME - insert some real tests, host_os isn't really good enough + case $host_os in + darwin*) + if test -n "$STRIP" ; then + striplib="$STRIP -x" + old_striplib="$STRIP -S" + AC_MSG_RESULT([yes]) + else + AC_MSG_RESULT([no]) + fi + ;; + *) + AC_MSG_RESULT([no]) + ;; + esac +fi +_LT_DECL([], [old_striplib], [1], [Commands to strip libraries]) +_LT_DECL([], [striplib], [1]) +])# _LT_CMD_STRIPLIB + + +# _LT_SYS_DYNAMIC_LINKER([TAG]) +# ----------------------------- +# PORTME Fill in your ld.so characteristics +m4_defun([_LT_SYS_DYNAMIC_LINKER], +[AC_REQUIRE([AC_CANONICAL_HOST])dnl +m4_require([_LT_DECL_EGREP])dnl +m4_require([_LT_FILEUTILS_DEFAULTS])dnl +m4_require([_LT_DECL_OBJDUMP])dnl +m4_require([_LT_DECL_SED])dnl +AC_MSG_CHECKING([dynamic linker characteristics]) +m4_if([$1], + [], [ +if test "$GCC" = yes; then + case $host_os in + darwin*) lt_awk_arg="/^libraries:/,/LR/" ;; + *) lt_awk_arg="/^libraries:/" ;; + esac + lt_search_path_spec=`$CC -print-search-dirs | awk $lt_awk_arg | $SED -e "s/^libraries://" -e "s,=/,/,g"` + if $ECHO "$lt_search_path_spec" | $GREP ';' >/dev/null ; then + # if the path contains ";" then we assume it to be the separator + # otherwise default to the standard path separator (i.e. ":") - it is + # assumed that no part of a normal pathname contains ";" but that should + # okay in the real world where ";" in dirpaths is itself problematic. + lt_search_path_spec=`$ECHO "$lt_search_path_spec" | $SED -e 's/;/ /g'` + else + lt_search_path_spec=`$ECHO "$lt_search_path_spec" | $SED -e "s/$PATH_SEPARATOR/ /g"` + fi + # Ok, now we have the path, separated by spaces, we can step through it + # and add multilib dir if necessary. + lt_tmp_lt_search_path_spec= + lt_multi_os_dir=`$CC $CPPFLAGS $CFLAGS $LDFLAGS -print-multi-os-directory 2>/dev/null` + for lt_sys_path in $lt_search_path_spec; do + if test -d "$lt_sys_path/$lt_multi_os_dir"; then + lt_tmp_lt_search_path_spec="$lt_tmp_lt_search_path_spec $lt_sys_path/$lt_multi_os_dir" + else + test -d "$lt_sys_path" && \ + lt_tmp_lt_search_path_spec="$lt_tmp_lt_search_path_spec $lt_sys_path" + fi + done + lt_search_path_spec=`$ECHO $lt_tmp_lt_search_path_spec | awk ' +BEGIN {RS=" "; FS="/|\n";} { + lt_foo=""; + lt_count=0; + for (lt_i = NF; lt_i > 0; lt_i--) { + if ($lt_i != "" && $lt_i != ".") { + if ($lt_i == "..") { + lt_count++; + } else { + if (lt_count == 0) { + lt_foo="/" $lt_i lt_foo; + } else { + lt_count--; + } + } + } + } + if (lt_foo != "") { lt_freq[[lt_foo]]++; } + if (lt_freq[[lt_foo]] == 1) { print lt_foo; } +}'` + sys_lib_search_path_spec=`$ECHO $lt_search_path_spec` +else + sys_lib_search_path_spec="/lib /usr/lib /usr/local/lib" +fi]) +library_names_spec= +libname_spec='lib$name' +soname_spec= +shrext_cmds=".so" +postinstall_cmds= +postuninstall_cmds= +finish_cmds= +finish_eval= +shlibpath_var= +shlibpath_overrides_runpath=unknown +version_type=none +dynamic_linker="$host_os ld.so" +sys_lib_dlsearch_path_spec="/lib /usr/lib" +need_lib_prefix=unknown +hardcode_into_libs=no + +# when you set need_version to no, make sure it does not cause -set_version +# flags to be left without arguments +need_version=unknown + +case $host_os in +aix3*) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix $libname.a' + shlibpath_var=LIBPATH + + # AIX 3 has no versioning support, so we append a major version to the name. + soname_spec='${libname}${release}${shared_ext}$major' + ;; + +aix[[4-9]]*) + version_type=linux + need_lib_prefix=no + need_version=no + hardcode_into_libs=yes + if test "$host_cpu" = ia64; then + # AIX 5 supports IA64 + library_names_spec='${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext}$versuffix $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + else + # With GCC up to 2.95.x, collect2 would create an import file + # for dependence libraries. The import file would start with + # the line `#! .'. This would cause the generated library to + # depend on `.', always an invalid library. This was fixed in + # development snapshots of GCC prior to 3.0. + case $host_os in + aix4 | aix4.[[01]] | aix4.[[01]].*) + if { echo '#if __GNUC__ > 2 || (__GNUC__ == 2 && __GNUC_MINOR__ >= 97)' + echo ' yes ' + echo '#endif'; } | ${CC} -E - | $GREP yes > /dev/null; then + : + else + can_build_shared=no + fi + ;; + esac + # AIX (on Power*) has no versioning support, so currently we can not hardcode correct + # soname into executable. Probably we can add versioning support to + # collect2, so additional links can be useful in future. + if test "$aix_use_runtimelinking" = yes; then + # If using run time linking (on AIX 4.2 or later) use lib.so + # instead of lib.a to let people know that these are not + # typical AIX shared libraries. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + else + # We preserve .a as extension for shared libraries through AIX4.2 + # and later when we are not doing run time linking. + library_names_spec='${libname}${release}.a $libname.a' + soname_spec='${libname}${release}${shared_ext}$major' + fi + shlibpath_var=LIBPATH + fi + ;; + +amigaos*) + case $host_cpu in + powerpc) + # Since July 2007 AmigaOS4 officially supports .so libraries. + # When compiling the executable, add -use-dynld -Lsobjs: to the compileline. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + ;; + m68k) + library_names_spec='$libname.ixlibrary $libname.a' + # Create ${libname}_ixlibrary.a entries in /sys/libs. + finish_eval='for lib in `ls $libdir/*.ixlibrary 2>/dev/null`; do libname=`$ECHO "X$lib" | $Xsed -e '\''s%^.*/\([[^/]]*\)\.ixlibrary$%\1%'\''`; test $RM /sys/libs/${libname}_ixlibrary.a; $show "cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a"; cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a || exit 1; done' + ;; + esac + ;; + +beos*) + library_names_spec='${libname}${shared_ext}' + dynamic_linker="$host_os ld.so" + shlibpath_var=LIBRARY_PATH + ;; + +bsdi[[45]]*) + version_type=linux + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + finish_cmds='PATH="\$PATH:/sbin" ldconfig $libdir' + shlibpath_var=LD_LIBRARY_PATH + sys_lib_search_path_spec="/shlib /usr/lib /usr/X11/lib /usr/contrib/lib /lib /usr/local/lib" + sys_lib_dlsearch_path_spec="/shlib /usr/lib /usr/local/lib" + # the default ld.so.conf also contains /usr/contrib/lib and + # /usr/X11R6/lib (/usr/X11 is a link to /usr/X11R6), but let us allow + # libtool to hard-code these into programs + ;; + +cygwin* | mingw* | pw32* | cegcc*) + version_type=windows + shrext_cmds=".dll" + need_version=no + need_lib_prefix=no + + case $GCC,$host_os in + yes,cygwin* | yes,mingw* | yes,pw32* | yes,cegcc*) + library_names_spec='$libname.dll.a' + # DLL is installed to $(libdir)/../bin by postinstall_cmds + postinstall_cmds='base_file=`basename \${file}`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\${base_file}'\''i; echo \$dlname'\''`~ + dldir=$destdir/`dirname \$dlpath`~ + test -d \$dldir || mkdir -p \$dldir~ + $install_prog $dir/$dlname \$dldir/$dlname~ + chmod a+x \$dldir/$dlname~ + if test -n '\''$stripme'\'' && test -n '\''$striplib'\''; then + eval '\''$striplib \$dldir/$dlname'\'' || exit \$?; + fi' + postuninstall_cmds='dldll=`$SHELL 2>&1 -c '\''. $file; echo \$dlname'\''`~ + dlpath=$dir/\$dldll~ + $RM \$dlpath' + shlibpath_overrides_runpath=yes + + case $host_os in + cygwin*) + # Cygwin DLLs use 'cyg' prefix rather than 'lib' + soname_spec='`echo ${libname} | sed -e 's/^lib/cyg/'``echo ${release} | $SED -e 's/[[.]]/-/g'`${versuffix}${shared_ext}' + sys_lib_search_path_spec="/usr/lib /lib/w32api /lib /usr/local/lib" + ;; + mingw* | cegcc*) + # MinGW DLLs use traditional 'lib' prefix + soname_spec='${libname}`echo ${release} | $SED -e 's/[[.]]/-/g'`${versuffix}${shared_ext}' + sys_lib_search_path_spec=`$CC -print-search-dirs | $GREP "^libraries:" | $SED -e "s/^libraries://" -e "s,=/,/,g"` + if $ECHO "$sys_lib_search_path_spec" | [$GREP ';[c-zC-Z]:/' >/dev/null]; then + # It is most probably a Windows format PATH printed by + # mingw gcc, but we are running on Cygwin. Gcc prints its search + # path with ; separators, and with drive letters. We can handle the + # drive letters (cygwin fileutils understands them), so leave them, + # especially as we might pass files found there to a mingw objdump, + # which wouldn't understand a cygwinified path. Ahh. + sys_lib_search_path_spec=`$ECHO "$sys_lib_search_path_spec" | $SED -e 's/;/ /g'` + else + sys_lib_search_path_spec=`$ECHO "$sys_lib_search_path_spec" | $SED -e "s/$PATH_SEPARATOR/ /g"` + fi + ;; + pw32*) + # pw32 DLLs use 'pw' prefix rather than 'lib' + library_names_spec='`echo ${libname} | sed -e 's/^lib/pw/'``echo ${release} | $SED -e 's/[[.]]/-/g'`${versuffix}${shared_ext}' + ;; + esac + ;; + + *) + library_names_spec='${libname}`echo ${release} | $SED -e 's/[[.]]/-/g'`${versuffix}${shared_ext} $libname.lib' + ;; + esac + dynamic_linker='Win32 ld.exe' + # FIXME: first we should search . and the directory the executable is in + shlibpath_var=PATH + ;; + +darwin* | rhapsody*) + dynamic_linker="$host_os dyld" + version_type=darwin + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${major}$shared_ext ${libname}$shared_ext' + soname_spec='${libname}${release}${major}$shared_ext' + shlibpath_overrides_runpath=yes + shlibpath_var=DYLD_LIBRARY_PATH + shrext_cmds='`test .$module = .yes && echo .so || echo .dylib`' +m4_if([$1], [],[ + sys_lib_search_path_spec="$sys_lib_search_path_spec /usr/local/lib"]) + sys_lib_dlsearch_path_spec='/usr/local/lib /lib /usr/lib' + ;; + +dgux*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname$shared_ext' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + ;; + +freebsd1*) + dynamic_linker=no + ;; + +freebsd* | dragonfly*) + # DragonFly does not have aout. When/if they implement a new + # versioning mechanism, adjust this. + if test -x /usr/bin/objformat; then + objformat=`/usr/bin/objformat` + else + case $host_os in + freebsd[[123]]*) objformat=aout ;; + *) objformat=elf ;; + esac + fi + version_type=freebsd-$objformat + case $version_type in + freebsd-elf*) + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' + need_version=no + need_lib_prefix=no + ;; + freebsd-*) + library_names_spec='${libname}${release}${shared_ext}$versuffix $libname${shared_ext}$versuffix' + need_version=yes + ;; + esac + shlibpath_var=LD_LIBRARY_PATH + case $host_os in + freebsd2*) + shlibpath_overrides_runpath=yes + ;; + freebsd3.[[01]]* | freebsdelf3.[[01]]*) + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + ;; + freebsd3.[[2-9]]* | freebsdelf3.[[2-9]]* | \ + freebsd4.[[0-5]] | freebsdelf4.[[0-5]] | freebsd4.1.1 | freebsdelf4.1.1) + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + ;; + *) # from 4.6 on, and DragonFly + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + ;; + esac + ;; + +gnu*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}${major} ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + hardcode_into_libs=yes + ;; + +hpux9* | hpux10* | hpux11*) + # Give a soname corresponding to the major version so that dld.sl refuses to + # link against other versions. + version_type=sunos + need_lib_prefix=no + need_version=no + case $host_cpu in + ia64*) + shrext_cmds='.so' + hardcode_into_libs=yes + dynamic_linker="$host_os dld.so" + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + if test "X$HPUX_IA64_MODE" = X32; then + sys_lib_search_path_spec="/usr/lib/hpux32 /usr/local/lib/hpux32 /usr/local/lib" + else + sys_lib_search_path_spec="/usr/lib/hpux64 /usr/local/lib/hpux64" + fi + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec + ;; + hppa*64*) + shrext_cmds='.sl' + hardcode_into_libs=yes + dynamic_linker="$host_os dld.sl" + shlibpath_var=LD_LIBRARY_PATH # How should we handle SHLIB_PATH + shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + sys_lib_search_path_spec="/usr/lib/pa20_64 /usr/ccs/lib/pa20_64" + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec + ;; + *) + shrext_cmds='.sl' + dynamic_linker="$host_os dld.sl" + shlibpath_var=SHLIB_PATH + shlibpath_overrides_runpath=no # +s is required to enable SHLIB_PATH + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + ;; + esac + # HP-UX runs *really* slowly unless shared libraries are mode 555. + postinstall_cmds='chmod 555 $lib' + ;; + +interix[[3-9]]*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + dynamic_linker='Interix 3.x ld.so.1 (PE, like ELF)' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + ;; + +irix5* | irix6* | nonstopux*) + case $host_os in + nonstopux*) version_type=nonstopux ;; + *) + if test "$lt_cv_prog_gnu_ld" = yes; then + version_type=linux + else + version_type=irix + fi ;; + esac + need_lib_prefix=no + need_version=no + soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext} $libname${shared_ext}' + case $host_os in + irix5* | nonstopux*) + libsuff= shlibsuff= + ;; + *) + case $LD in # libtool.m4 will add one of these switches to LD + *-32|*"-32 "|*-melf32bsmip|*"-melf32bsmip ") + libsuff= shlibsuff= libmagic=32-bit;; + *-n32|*"-n32 "|*-melf32bmipn32|*"-melf32bmipn32 ") + libsuff=32 shlibsuff=N32 libmagic=N32;; + *-64|*"-64 "|*-melf64bmip|*"-melf64bmip ") + libsuff=64 shlibsuff=64 libmagic=64-bit;; + *) libsuff= shlibsuff= libmagic=never-match;; + esac + ;; + esac + shlibpath_var=LD_LIBRARY${shlibsuff}_PATH + shlibpath_overrides_runpath=no + sys_lib_search_path_spec="/usr/lib${libsuff} /lib${libsuff} /usr/local/lib${libsuff}" + sys_lib_dlsearch_path_spec="/usr/lib${libsuff} /lib${libsuff}" + hardcode_into_libs=yes + ;; + +# No shared lib support for Linux oldld, aout, or coff. +linux*oldld* | linux*aout* | linux*coff*) + dynamic_linker=no + ;; + +# This must be Linux ELF. +linux* | k*bsd*-gnu | kopensolaris*-gnu) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + finish_cmds='PATH="\$PATH:/sbin" ldconfig -n $libdir' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + # Some binutils ld are patched to set DT_RUNPATH + save_LDFLAGS=$LDFLAGS + save_libdir=$libdir + eval "libdir=/foo; wl=\"$_LT_TAGVAR(lt_prog_compiler_wl, $1)\"; \ + LDFLAGS=\"\$LDFLAGS $_LT_TAGVAR(hardcode_libdir_flag_spec, $1)\"" + AC_LINK_IFELSE([AC_LANG_PROGRAM([],[])], + [AS_IF([ ($OBJDUMP -p conftest$ac_exeext) 2>/dev/null | grep "RUNPATH.*$libdir" >/dev/null], + [shlibpath_overrides_runpath=yes])]) + LDFLAGS=$save_LDFLAGS + libdir=$save_libdir + + # This implies no fast_install, which is unacceptable. + # Some rework will be needed to allow for fast_install + # before this can be enabled. + hardcode_into_libs=yes + + # Append ld.so.conf contents to the search path + if test -f /etc/ld.so.conf; then + lt_ld_extra=`awk '/^include / { system(sprintf("cd /etc; cat %s 2>/dev/null", \[$]2)); skip = 1; } { if (!skip) print \[$]0; skip = 0; }' < /etc/ld.so.conf | $SED -e 's/#.*//;/^[ ]*hwcap[ ]/d;s/[:, ]/ /g;s/=[^=]*$//;s/=[^= ]* / /g;/^$/d' | tr '\n' ' '` + sys_lib_dlsearch_path_spec="/lib /usr/lib $lt_ld_extra" + fi + + # We used to test for /lib/ld.so.1 and disable shared libraries on + # powerpc, because MkLinux only supported shared libraries with the + # GNU dynamic linker. Since this was broken with cross compilers, + # most powerpc-linux boxes support dynamic linking these days and + # people can always --disable-shared, the test was removed, and we + # assume the GNU/Linux dynamic linker is in use. + dynamic_linker='GNU/Linux ld.so' + ;; + +netbsdelf*-gnu) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + dynamic_linker='NetBSD ld.elf_so' + ;; + +netbsd*) + version_type=sunos + need_lib_prefix=no + need_version=no + if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' + dynamic_linker='NetBSD (a.out) ld.so' + else + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + dynamic_linker='NetBSD ld.elf_so' + fi + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + ;; + +newsos6) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + ;; + +*nto* | *qnx*) + version_type=qnx + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + dynamic_linker='ldqnx.so' + ;; + +openbsd*) + version_type=sunos + sys_lib_dlsearch_path_spec="/usr/lib" + need_lib_prefix=no + # Some older versions of OpenBSD (3.3 at least) *do* need versioned libs. + case $host_os in + openbsd3.3 | openbsd3.3.*) need_version=yes ;; + *) need_version=no ;; + esac + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' + shlibpath_var=LD_LIBRARY_PATH + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + case $host_os in + openbsd2.[[89]] | openbsd2.[[89]].*) + shlibpath_overrides_runpath=no + ;; + *) + shlibpath_overrides_runpath=yes + ;; + esac + else + shlibpath_overrides_runpath=yes + fi + ;; + +os2*) + libname_spec='$name' + shrext_cmds=".dll" + need_lib_prefix=no + library_names_spec='$libname${shared_ext} $libname.a' + dynamic_linker='OS/2 ld.exe' + shlibpath_var=LIBPATH + ;; + +osf3* | osf4* | osf5*) + version_type=osf + need_lib_prefix=no + need_version=no + soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + sys_lib_search_path_spec="/usr/shlib /usr/ccs/lib /usr/lib/cmplrs/cc /usr/lib /usr/local/lib /var/shlib" + sys_lib_dlsearch_path_spec="$sys_lib_search_path_spec" + ;; + +rdos*) + dynamic_linker=no + ;; + +solaris*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + # ldd complains unless libraries are executable + postinstall_cmds='chmod +x $lib' + ;; + +sunos4*) + version_type=sunos + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + finish_cmds='PATH="\$PATH:/usr/etc" ldconfig $libdir' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + if test "$with_gnu_ld" = yes; then + need_lib_prefix=no + fi + need_version=yes + ;; + +sysv4 | sysv4.3*) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + case $host_vendor in + sni) + shlibpath_overrides_runpath=no + need_lib_prefix=no + runpath_var=LD_RUN_PATH + ;; + siemens) + need_lib_prefix=no + ;; + motorola) + need_lib_prefix=no + need_version=no + shlibpath_overrides_runpath=no + sys_lib_search_path_spec='/lib /usr/lib /usr/ccs/lib' + ;; + esac + ;; + +sysv4*MP*) + if test -d /usr/nec ;then + version_type=linux + library_names_spec='$libname${shared_ext}.$versuffix $libname${shared_ext}.$major $libname${shared_ext}' + soname_spec='$libname${shared_ext}.$major' + shlibpath_var=LD_LIBRARY_PATH + fi + ;; + +sysv5* | sco3.2v5* | sco5v6* | unixware* | OpenUNIX* | sysv4*uw2*) + version_type=freebsd-elf + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + if test "$with_gnu_ld" = yes; then + sys_lib_search_path_spec='/usr/local/lib /usr/gnu/lib /usr/ccs/lib /usr/lib /lib' + else + sys_lib_search_path_spec='/usr/ccs/lib /usr/lib' + case $host_os in + sco3.2v5*) + sys_lib_search_path_spec="$sys_lib_search_path_spec /lib" + ;; + esac + fi + sys_lib_dlsearch_path_spec='/usr/lib' + ;; + +tpf*) + # TPF is a cross-target only. Preferred cross-host = GNU/Linux. + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + ;; + +uts4*) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + ;; + +*) + dynamic_linker=no + ;; +esac +AC_MSG_RESULT([$dynamic_linker]) +test "$dynamic_linker" = no && can_build_shared=no + +variables_saved_for_relink="PATH $shlibpath_var $runpath_var" +if test "$GCC" = yes; then + variables_saved_for_relink="$variables_saved_for_relink GCC_EXEC_PREFIX COMPILER_PATH LIBRARY_PATH" +fi + +if test "${lt_cv_sys_lib_search_path_spec+set}" = set; then + sys_lib_search_path_spec="$lt_cv_sys_lib_search_path_spec" +fi +if test "${lt_cv_sys_lib_dlsearch_path_spec+set}" = set; then + sys_lib_dlsearch_path_spec="$lt_cv_sys_lib_dlsearch_path_spec" +fi + +_LT_DECL([], [variables_saved_for_relink], [1], + [Variables whose values should be saved in libtool wrapper scripts and + restored at link time]) +_LT_DECL([], [need_lib_prefix], [0], + [Do we need the "lib" prefix for modules?]) +_LT_DECL([], [need_version], [0], [Do we need a version for libraries?]) +_LT_DECL([], [version_type], [0], [Library versioning type]) +_LT_DECL([], [runpath_var], [0], [Shared library runtime path variable]) +_LT_DECL([], [shlibpath_var], [0],[Shared library path variable]) +_LT_DECL([], [shlibpath_overrides_runpath], [0], + [Is shlibpath searched before the hard-coded library search path?]) +_LT_DECL([], [libname_spec], [1], [Format of library name prefix]) +_LT_DECL([], [library_names_spec], [1], + [[List of archive names. First name is the real one, the rest are links. + The last name is the one that the linker finds with -lNAME]]) +_LT_DECL([], [soname_spec], [1], + [[The coded name of the library, if different from the real name]]) +_LT_DECL([], [postinstall_cmds], [2], + [Command to use after installation of a shared archive]) +_LT_DECL([], [postuninstall_cmds], [2], + [Command to use after uninstallation of a shared archive]) +_LT_DECL([], [finish_cmds], [2], + [Commands used to finish a libtool library installation in a directory]) +_LT_DECL([], [finish_eval], [1], + [[As "finish_cmds", except a single script fragment to be evaled but + not shown]]) +_LT_DECL([], [hardcode_into_libs], [0], + [Whether we should hardcode library paths into libraries]) +_LT_DECL([], [sys_lib_search_path_spec], [2], + [Compile-time system search path for libraries]) +_LT_DECL([], [sys_lib_dlsearch_path_spec], [2], + [Run-time system search path for libraries]) +])# _LT_SYS_DYNAMIC_LINKER + + +# _LT_PATH_TOOL_PREFIX(TOOL) +# -------------------------- +# find a file program which can recognize shared library +AC_DEFUN([_LT_PATH_TOOL_PREFIX], +[m4_require([_LT_DECL_EGREP])dnl +AC_MSG_CHECKING([for $1]) +AC_CACHE_VAL(lt_cv_path_MAGIC_CMD, +[case $MAGIC_CMD in +[[\\/*] | ?:[\\/]*]) + lt_cv_path_MAGIC_CMD="$MAGIC_CMD" # Let the user override the test with a path. + ;; +*) + lt_save_MAGIC_CMD="$MAGIC_CMD" + lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR +dnl $ac_dummy forces splitting on constant user-supplied paths. +dnl POSIX.2 word splitting is done only on the output of word expansions, +dnl not every word. This closes a longstanding sh security hole. + ac_dummy="m4_if([$2], , $PATH, [$2])" + for ac_dir in $ac_dummy; do + IFS="$lt_save_ifs" + test -z "$ac_dir" && ac_dir=. + if test -f $ac_dir/$1; then + lt_cv_path_MAGIC_CMD="$ac_dir/$1" + if test -n "$file_magic_test_file"; then + case $deplibs_check_method in + "file_magic "*) + file_magic_regex=`expr "$deplibs_check_method" : "file_magic \(.*\)"` + MAGIC_CMD="$lt_cv_path_MAGIC_CMD" + if eval $file_magic_cmd \$file_magic_test_file 2> /dev/null | + $EGREP "$file_magic_regex" > /dev/null; then + : + else + cat <<_LT_EOF 1>&2 + +*** Warning: the command libtool uses to detect shared libraries, +*** $file_magic_cmd, produces output that libtool cannot recognize. +*** The result is that libtool may fail to recognize shared libraries +*** as such. This will affect the creation of libtool libraries that +*** depend on shared libraries, but programs linked with such libtool +*** libraries will work regardless of this problem. Nevertheless, you +*** may want to report the problem to your system manager and/or to +*** bug-libtool@gnu.org + +_LT_EOF + fi ;; + esac + fi + break + fi + done + IFS="$lt_save_ifs" + MAGIC_CMD="$lt_save_MAGIC_CMD" + ;; +esac]) +MAGIC_CMD="$lt_cv_path_MAGIC_CMD" +if test -n "$MAGIC_CMD"; then + AC_MSG_RESULT($MAGIC_CMD) +else + AC_MSG_RESULT(no) +fi +_LT_DECL([], [MAGIC_CMD], [0], + [Used to examine libraries when file_magic_cmd begins with "file"])dnl +])# _LT_PATH_TOOL_PREFIX + +# Old name: +AU_ALIAS([AC_PATH_TOOL_PREFIX], [_LT_PATH_TOOL_PREFIX]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_PATH_TOOL_PREFIX], []) + + +# _LT_PATH_MAGIC +# -------------- +# find a file program which can recognize a shared library +m4_defun([_LT_PATH_MAGIC], +[_LT_PATH_TOOL_PREFIX(${ac_tool_prefix}file, /usr/bin$PATH_SEPARATOR$PATH) +if test -z "$lt_cv_path_MAGIC_CMD"; then + if test -n "$ac_tool_prefix"; then + _LT_PATH_TOOL_PREFIX(file, /usr/bin$PATH_SEPARATOR$PATH) + else + MAGIC_CMD=: + fi +fi +])# _LT_PATH_MAGIC + + +# LT_PATH_LD +# ---------- +# find the pathname to the GNU or non-GNU linker +AC_DEFUN([LT_PATH_LD], +[AC_REQUIRE([AC_PROG_CC])dnl +AC_REQUIRE([AC_CANONICAL_HOST])dnl +AC_REQUIRE([AC_CANONICAL_BUILD])dnl +m4_require([_LT_DECL_SED])dnl +m4_require([_LT_DECL_EGREP])dnl + +AC_ARG_WITH([gnu-ld], + [AS_HELP_STRING([--with-gnu-ld], + [assume the C compiler uses GNU ld @<:@default=no@:>@])], + [test "$withval" = no || with_gnu_ld=yes], + [with_gnu_ld=no])dnl + +ac_prog=ld +if test "$GCC" = yes; then + # Check if gcc -print-prog-name=ld gives a path. + AC_MSG_CHECKING([for ld used by $CC]) + case $host in + *-*-mingw*) + # gcc leaves a trailing carriage return which upsets mingw + ac_prog=`($CC -print-prog-name=ld) 2>&5 | tr -d '\015'` ;; + *) + ac_prog=`($CC -print-prog-name=ld) 2>&5` ;; + esac + case $ac_prog in + # Accept absolute paths. + [[\\/]]* | ?:[[\\/]]*) + re_direlt='/[[^/]][[^/]]*/\.\./' + # Canonicalize the pathname of ld + ac_prog=`$ECHO "$ac_prog"| $SED 's%\\\\%/%g'` + while $ECHO "$ac_prog" | $GREP "$re_direlt" > /dev/null 2>&1; do + ac_prog=`$ECHO $ac_prog| $SED "s%$re_direlt%/%"` + done + test -z "$LD" && LD="$ac_prog" + ;; + "") + # If it fails, then pretend we aren't using GCC. + ac_prog=ld + ;; + *) + # If it is relative, then search for the first ld in PATH. + with_gnu_ld=unknown + ;; + esac +elif test "$with_gnu_ld" = yes; then + AC_MSG_CHECKING([for GNU ld]) +else + AC_MSG_CHECKING([for non-GNU ld]) +fi +AC_CACHE_VAL(lt_cv_path_LD, +[if test -z "$LD"; then + lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + for ac_dir in $PATH; do + IFS="$lt_save_ifs" + test -z "$ac_dir" && ac_dir=. + if test -f "$ac_dir/$ac_prog" || test -f "$ac_dir/$ac_prog$ac_exeext"; then + lt_cv_path_LD="$ac_dir/$ac_prog" + # Check to see if the program is GNU ld. I'd rather use --version, + # but apparently some variants of GNU ld only accept -v. + # Break only if it was the GNU/non-GNU ld that we prefer. + case `"$lt_cv_path_LD" -v 2>&1 &1 /dev/null 2>&1; then + lt_cv_deplibs_check_method='file_magic ^x86 archive import|^x86 DLL' + lt_cv_file_magic_cmd='func_win32_libid' + else + lt_cv_deplibs_check_method='file_magic file format pei*-i386(.*architecture: i386)?' + lt_cv_file_magic_cmd='$OBJDUMP -f' + fi + ;; + +cegcc) + # use the weaker test based on 'objdump'. See mingw*. + lt_cv_deplibs_check_method='file_magic file format pe-arm-.*little(.*architecture: arm)?' + lt_cv_file_magic_cmd='$OBJDUMP -f' + ;; + +darwin* | rhapsody*) + lt_cv_deplibs_check_method=pass_all + ;; + +freebsd* | dragonfly*) + if echo __ELF__ | $CC -E - | $GREP __ELF__ > /dev/null; then + case $host_cpu in + i*86 ) + # Not sure whether the presence of OpenBSD here was a mistake. + # Let's accept both of them until this is cleared up. + lt_cv_deplibs_check_method='file_magic (FreeBSD|OpenBSD|DragonFly)/i[[3-9]]86 (compact )?demand paged shared library' + lt_cv_file_magic_cmd=/usr/bin/file + lt_cv_file_magic_test_file=`echo /usr/lib/libc.so.*` + ;; + esac + else + lt_cv_deplibs_check_method=pass_all + fi + ;; + +gnu*) + lt_cv_deplibs_check_method=pass_all + ;; + +hpux10.20* | hpux11*) + lt_cv_file_magic_cmd=/usr/bin/file + case $host_cpu in + ia64*) + lt_cv_deplibs_check_method='file_magic (s[[0-9]][[0-9]][[0-9]]|ELF-[[0-9]][[0-9]]) shared object file - IA64' + lt_cv_file_magic_test_file=/usr/lib/hpux32/libc.so + ;; + hppa*64*) + [lt_cv_deplibs_check_method='file_magic (s[0-9][0-9][0-9]|ELF-[0-9][0-9]) shared object file - PA-RISC [0-9].[0-9]'] + lt_cv_file_magic_test_file=/usr/lib/pa20_64/libc.sl + ;; + *) + lt_cv_deplibs_check_method='file_magic (s[[0-9]][[0-9]][[0-9]]|PA-RISC[[0-9]].[[0-9]]) shared library' + lt_cv_file_magic_test_file=/usr/lib/libc.sl + ;; + esac + ;; + +interix[[3-9]]*) + # PIC code is broken on Interix 3.x, that's why |\.a not |_pic\.a here + lt_cv_deplibs_check_method='match_pattern /lib[[^/]]+(\.so|\.a)$' + ;; + +irix5* | irix6* | nonstopux*) + case $LD in + *-32|*"-32 ") libmagic=32-bit;; + *-n32|*"-n32 ") libmagic=N32;; + *-64|*"-64 ") libmagic=64-bit;; + *) libmagic=never-match;; + esac + lt_cv_deplibs_check_method=pass_all + ;; + +# This must be Linux ELF. +linux* | k*bsd*-gnu | kopensolaris*-gnu) + lt_cv_deplibs_check_method=pass_all + ;; + +netbsd* | netbsdelf*-gnu) + if echo __ELF__ | $CC -E - | $GREP __ELF__ > /dev/null; then + lt_cv_deplibs_check_method='match_pattern /lib[[^/]]+(\.so\.[[0-9]]+\.[[0-9]]+|_pic\.a)$' + else + lt_cv_deplibs_check_method='match_pattern /lib[[^/]]+(\.so|_pic\.a)$' + fi + ;; + +newos6*) + lt_cv_deplibs_check_method='file_magic ELF [[0-9]][[0-9]]*-bit [[ML]]SB (executable|dynamic lib)' + lt_cv_file_magic_cmd=/usr/bin/file + lt_cv_file_magic_test_file=/usr/lib/libnls.so + ;; + +*nto* | *qnx*) + lt_cv_deplibs_check_method=pass_all + ;; + +openbsd*) + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + lt_cv_deplibs_check_method='match_pattern /lib[[^/]]+(\.so\.[[0-9]]+\.[[0-9]]+|\.so|_pic\.a)$' + else + lt_cv_deplibs_check_method='match_pattern /lib[[^/]]+(\.so\.[[0-9]]+\.[[0-9]]+|_pic\.a)$' + fi + ;; + +osf3* | osf4* | osf5*) + lt_cv_deplibs_check_method=pass_all + ;; + +rdos*) + lt_cv_deplibs_check_method=pass_all + ;; + +solaris*) + lt_cv_deplibs_check_method=pass_all + ;; + +sysv5* | sco3.2v5* | sco5v6* | unixware* | OpenUNIX* | sysv4*uw2*) + lt_cv_deplibs_check_method=pass_all + ;; + +sysv4 | sysv4.3*) + case $host_vendor in + motorola) + lt_cv_deplibs_check_method='file_magic ELF [[0-9]][[0-9]]*-bit [[ML]]SB (shared object|dynamic lib) M[[0-9]][[0-9]]* Version [[0-9]]' + lt_cv_file_magic_test_file=`echo /usr/lib/libc.so*` + ;; + ncr) + lt_cv_deplibs_check_method=pass_all + ;; + sequent) + lt_cv_file_magic_cmd='/bin/file' + lt_cv_deplibs_check_method='file_magic ELF [[0-9]][[0-9]]*-bit [[LM]]SB (shared object|dynamic lib )' + ;; + sni) + lt_cv_file_magic_cmd='/bin/file' + lt_cv_deplibs_check_method="file_magic ELF [[0-9]][[0-9]]*-bit [[LM]]SB dynamic lib" + lt_cv_file_magic_test_file=/lib/libc.so + ;; + siemens) + lt_cv_deplibs_check_method=pass_all + ;; + pc) + lt_cv_deplibs_check_method=pass_all + ;; + esac + ;; + +tpf*) + lt_cv_deplibs_check_method=pass_all + ;; +esac +]) +file_magic_cmd=$lt_cv_file_magic_cmd +deplibs_check_method=$lt_cv_deplibs_check_method +test -z "$deplibs_check_method" && deplibs_check_method=unknown + +_LT_DECL([], [deplibs_check_method], [1], + [Method to check whether dependent libraries are shared objects]) +_LT_DECL([], [file_magic_cmd], [1], + [Command to use when deplibs_check_method == "file_magic"]) +])# _LT_CHECK_MAGIC_METHOD + + +# LT_PATH_NM +# ---------- +# find the pathname to a BSD- or MS-compatible name lister +AC_DEFUN([LT_PATH_NM], +[AC_REQUIRE([AC_PROG_CC])dnl +AC_CACHE_CHECK([for BSD- or MS-compatible name lister (nm)], lt_cv_path_NM, +[if test -n "$NM"; then + # Let the user override the test. + lt_cv_path_NM="$NM" +else + lt_nm_to_check="${ac_tool_prefix}nm" + if test -n "$ac_tool_prefix" && test "$build" = "$host"; then + lt_nm_to_check="$lt_nm_to_check nm" + fi + for lt_tmp_nm in $lt_nm_to_check; do + lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + for ac_dir in $PATH /usr/ccs/bin/elf /usr/ccs/bin /usr/ucb /bin; do + IFS="$lt_save_ifs" + test -z "$ac_dir" && ac_dir=. + tmp_nm="$ac_dir/$lt_tmp_nm" + if test -f "$tmp_nm" || test -f "$tmp_nm$ac_exeext" ; then + # Check to see if the nm accepts a BSD-compat flag. + # Adding the `sed 1q' prevents false positives on HP-UX, which says: + # nm: unknown option "B" ignored + # Tru64's nm complains that /dev/null is an invalid object file + case `"$tmp_nm" -B /dev/null 2>&1 | sed '1q'` in + */dev/null* | *'Invalid file or object type'*) + lt_cv_path_NM="$tmp_nm -B" + break + ;; + *) + case `"$tmp_nm" -p /dev/null 2>&1 | sed '1q'` in + */dev/null*) + lt_cv_path_NM="$tmp_nm -p" + break + ;; + *) + lt_cv_path_NM=${lt_cv_path_NM="$tmp_nm"} # keep the first match, but + continue # so that we can try to find one that supports BSD flags + ;; + esac + ;; + esac + fi + done + IFS="$lt_save_ifs" + done + : ${lt_cv_path_NM=no} +fi]) +if test "$lt_cv_path_NM" != "no"; then + NM="$lt_cv_path_NM" +else + # Didn't find any BSD compatible name lister, look for dumpbin. + AC_CHECK_TOOLS(DUMPBIN, ["dumpbin -symbols" "link -dump -symbols"], :) + AC_SUBST([DUMPBIN]) + if test "$DUMPBIN" != ":"; then + NM="$DUMPBIN" + fi +fi +test -z "$NM" && NM=nm +AC_SUBST([NM]) +_LT_DECL([], [NM], [1], [A BSD- or MS-compatible name lister])dnl + +AC_CACHE_CHECK([the name lister ($NM) interface], [lt_cv_nm_interface], + [lt_cv_nm_interface="BSD nm" + echo "int some_variable = 0;" > conftest.$ac_ext + (eval echo "\"\$as_me:__oline__: $ac_compile\"" >&AS_MESSAGE_LOG_FD) + (eval "$ac_compile" 2>conftest.err) + cat conftest.err >&AS_MESSAGE_LOG_FD + (eval echo "\"\$as_me:__oline__: $NM \\\"conftest.$ac_objext\\\"\"" >&AS_MESSAGE_LOG_FD) + (eval "$NM \"conftest.$ac_objext\"" 2>conftest.err > conftest.out) + cat conftest.err >&AS_MESSAGE_LOG_FD + (eval echo "\"\$as_me:__oline__: output\"" >&AS_MESSAGE_LOG_FD) + cat conftest.out >&AS_MESSAGE_LOG_FD + if $GREP 'External.*some_variable' conftest.out > /dev/null; then + lt_cv_nm_interface="MS dumpbin" + fi + rm -f conftest*]) +])# LT_PATH_NM + +# Old names: +AU_ALIAS([AM_PROG_NM], [LT_PATH_NM]) +AU_ALIAS([AC_PROG_NM], [LT_PATH_NM]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AM_PROG_NM], []) +dnl AC_DEFUN([AC_PROG_NM], []) + + +# LT_LIB_M +# -------- +# check for math library +AC_DEFUN([LT_LIB_M], +[AC_REQUIRE([AC_CANONICAL_HOST])dnl +LIBM= +case $host in +*-*-beos* | *-*-cygwin* | *-*-pw32* | *-*-darwin*) + # These system don't have libm, or don't need it + ;; +*-ncr-sysv4.3*) + AC_CHECK_LIB(mw, _mwvalidcheckl, LIBM="-lmw") + AC_CHECK_LIB(m, cos, LIBM="$LIBM -lm") + ;; +*) + AC_CHECK_LIB(m, cos, LIBM="-lm") + ;; +esac +AC_SUBST([LIBM]) +])# LT_LIB_M + +# Old name: +AU_ALIAS([AC_CHECK_LIBM], [LT_LIB_M]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_CHECK_LIBM], []) + + +# _LT_COMPILER_NO_RTTI([TAGNAME]) +# ------------------------------- +m4_defun([_LT_COMPILER_NO_RTTI], +[m4_require([_LT_TAG_COMPILER])dnl + +_LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)= + +if test "$GCC" = yes; then + _LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)=' -fno-builtin' + + _LT_COMPILER_OPTION([if $compiler supports -fno-rtti -fno-exceptions], + lt_cv_prog_compiler_rtti_exceptions, + [-fno-rtti -fno-exceptions], [], + [_LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)="$_LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1) -fno-rtti -fno-exceptions"]) +fi +_LT_TAGDECL([no_builtin_flag], [lt_prog_compiler_no_builtin_flag], [1], + [Compiler flag to turn off builtin functions]) +])# _LT_COMPILER_NO_RTTI + + +# _LT_CMD_GLOBAL_SYMBOLS +# ---------------------- +m4_defun([_LT_CMD_GLOBAL_SYMBOLS], +[AC_REQUIRE([AC_CANONICAL_HOST])dnl +AC_REQUIRE([AC_PROG_CC])dnl +AC_REQUIRE([LT_PATH_NM])dnl +AC_REQUIRE([LT_PATH_LD])dnl +m4_require([_LT_DECL_SED])dnl +m4_require([_LT_DECL_EGREP])dnl +m4_require([_LT_TAG_COMPILER])dnl + +# Check for command to grab the raw symbol name followed by C symbol from nm. +AC_MSG_CHECKING([command to parse $NM output from $compiler object]) +AC_CACHE_VAL([lt_cv_sys_global_symbol_pipe], +[ +# These are sane defaults that work on at least a few old systems. +# [They come from Ultrix. What could be older than Ultrix?!! ;)] + +# Character class describing NM global symbol codes. +symcode='[[BCDEGRST]]' + +# Regexp to match symbols that can be accessed directly from C. +sympat='\([[_A-Za-z]][[_A-Za-z0-9]]*\)' + +# Define system-specific variables. +case $host_os in +aix*) + symcode='[[BCDT]]' + ;; +cygwin* | mingw* | pw32* | cegcc*) + symcode='[[ABCDGISTW]]' + ;; +hpux*) + if test "$host_cpu" = ia64; then + symcode='[[ABCDEGRST]]' + fi + ;; +irix* | nonstopux*) + symcode='[[BCDEGRST]]' + ;; +osf*) + symcode='[[BCDEGQRST]]' + ;; +solaris*) + symcode='[[BDRT]]' + ;; +sco3.2v5*) + symcode='[[DT]]' + ;; +sysv4.2uw2*) + symcode='[[DT]]' + ;; +sysv5* | sco5v6* | unixware* | OpenUNIX*) + symcode='[[ABDT]]' + ;; +sysv4) + symcode='[[DFNSTU]]' + ;; +esac + +# If we're using GNU nm, then use its standard symbol codes. +case `$NM -V 2>&1` in +*GNU* | *'with BFD'*) + symcode='[[ABCDGIRSTW]]' ;; +esac + +# Transform an extracted symbol line into a proper C declaration. +# Some systems (esp. on ia64) link data and code symbols differently, +# so use this general approach. +lt_cv_sys_global_symbol_to_cdecl="sed -n -e 's/^T .* \(.*\)$/extern int \1();/p' -e 's/^$symcode* .* \(.*\)$/extern char \1;/p'" + +# Transform an extracted symbol line into symbol name and symbol address +lt_cv_sys_global_symbol_to_c_name_address="sed -n -e 's/^: \([[^ ]]*\) $/ {\\\"\1\\\", (void *) 0},/p' -e 's/^$symcode* \([[^ ]]*\) \([[^ ]]*\)$/ {\"\2\", (void *) \&\2},/p'" +lt_cv_sys_global_symbol_to_c_name_address_lib_prefix="sed -n -e 's/^: \([[^ ]]*\) $/ {\\\"\1\\\", (void *) 0},/p' -e 's/^$symcode* \([[^ ]]*\) \(lib[[^ ]]*\)$/ {\"\2\", (void *) \&\2},/p' -e 's/^$symcode* \([[^ ]]*\) \([[^ ]]*\)$/ {\"lib\2\", (void *) \&\2},/p'" + +# Handle CRLF in mingw tool chain +opt_cr= +case $build_os in +mingw*) + opt_cr=`$ECHO 'x\{0,1\}' | tr x '\015'` # option cr in regexp + ;; +esac + +# Try without a prefix underscore, then with it. +for ac_symprfx in "" "_"; do + + # Transform symcode, sympat, and symprfx into a raw symbol and a C symbol. + symxfrm="\\1 $ac_symprfx\\2 \\2" + + # Write the raw and C identifiers. + if test "$lt_cv_nm_interface" = "MS dumpbin"; then + # Fake it for dumpbin and say T for any non-static function + # and D for any global variable. + # Also find C++ and __fastcall symbols from MSVC++, + # which start with @ or ?. + lt_cv_sys_global_symbol_pipe="$AWK ['"\ +" {last_section=section; section=\$ 3};"\ +" /Section length .*#relocs.*(pick any)/{hide[last_section]=1};"\ +" \$ 0!~/External *\|/{next};"\ +" / 0+ UNDEF /{next}; / UNDEF \([^|]\)*()/{next};"\ +" {if(hide[section]) next};"\ +" {f=0}; \$ 0~/\(\).*\|/{f=1}; {printf f ? \"T \" : \"D \"};"\ +" {split(\$ 0, a, /\||\r/); split(a[2], s)};"\ +" s[1]~/^[@?]/{print s[1], s[1]; next};"\ +" s[1]~prfx {split(s[1],t,\"@\"); print t[1], substr(t[1],length(prfx))}"\ +" ' prfx=^$ac_symprfx]" + else + lt_cv_sys_global_symbol_pipe="sed -n -e 's/^.*[[ ]]\($symcode$symcode*\)[[ ]][[ ]]*$ac_symprfx$sympat$opt_cr$/$symxfrm/p'" + fi + + # Check to see that the pipe works correctly. + pipe_works=no + + rm -f conftest* + cat > conftest.$ac_ext <<_LT_EOF +#ifdef __cplusplus +extern "C" { +#endif +char nm_test_var; +void nm_test_func(void); +void nm_test_func(void){} +#ifdef __cplusplus +} +#endif +int main(){nm_test_var='a';nm_test_func();return(0);} +_LT_EOF + + if AC_TRY_EVAL(ac_compile); then + # Now try to grab the symbols. + nlist=conftest.nm + if AC_TRY_EVAL(NM conftest.$ac_objext \| $lt_cv_sys_global_symbol_pipe \> $nlist) && test -s "$nlist"; then + # Try sorting and uniquifying the output. + if sort "$nlist" | uniq > "$nlist"T; then + mv -f "$nlist"T "$nlist" + else + rm -f "$nlist"T + fi + + # Make sure that we snagged all the symbols we need. + if $GREP ' nm_test_var$' "$nlist" >/dev/null; then + if $GREP ' nm_test_func$' "$nlist" >/dev/null; then + cat <<_LT_EOF > conftest.$ac_ext +#ifdef __cplusplus +extern "C" { +#endif + +_LT_EOF + # Now generate the symbol file. + eval "$lt_cv_sys_global_symbol_to_cdecl"' < "$nlist" | $GREP -v main >> conftest.$ac_ext' + + cat <<_LT_EOF >> conftest.$ac_ext + +/* The mapping between symbol names and symbols. */ +const struct { + const char *name; + void *address; +} +lt__PROGRAM__LTX_preloaded_symbols[[]] = +{ + { "@PROGRAM@", (void *) 0 }, +_LT_EOF + $SED "s/^$symcode$symcode* \(.*\) \(.*\)$/ {\"\2\", (void *) \&\2},/" < "$nlist" | $GREP -v main >> conftest.$ac_ext + cat <<\_LT_EOF >> conftest.$ac_ext + {0, (void *) 0} +}; + +/* This works around a problem in FreeBSD linker */ +#ifdef FREEBSD_WORKAROUND +static const void *lt_preloaded_setup() { + return lt__PROGRAM__LTX_preloaded_symbols; +} +#endif + +#ifdef __cplusplus +} +#endif +_LT_EOF + # Now try linking the two files. + mv conftest.$ac_objext conftstm.$ac_objext + lt_save_LIBS="$LIBS" + lt_save_CFLAGS="$CFLAGS" + LIBS="conftstm.$ac_objext" + CFLAGS="$CFLAGS$_LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)" + if AC_TRY_EVAL(ac_link) && test -s conftest${ac_exeext}; then + pipe_works=yes + fi + LIBS="$lt_save_LIBS" + CFLAGS="$lt_save_CFLAGS" + else + echo "cannot find nm_test_func in $nlist" >&AS_MESSAGE_LOG_FD + fi + else + echo "cannot find nm_test_var in $nlist" >&AS_MESSAGE_LOG_FD + fi + else + echo "cannot run $lt_cv_sys_global_symbol_pipe" >&AS_MESSAGE_LOG_FD + fi + else + echo "$progname: failed program was:" >&AS_MESSAGE_LOG_FD + cat conftest.$ac_ext >&5 + fi + rm -rf conftest* conftst* + + # Do not use the global_symbol_pipe unless it works. + if test "$pipe_works" = yes; then + break + else + lt_cv_sys_global_symbol_pipe= + fi +done +]) +if test -z "$lt_cv_sys_global_symbol_pipe"; then + lt_cv_sys_global_symbol_to_cdecl= +fi +if test -z "$lt_cv_sys_global_symbol_pipe$lt_cv_sys_global_symbol_to_cdecl"; then + AC_MSG_RESULT(failed) +else + AC_MSG_RESULT(ok) +fi + +_LT_DECL([global_symbol_pipe], [lt_cv_sys_global_symbol_pipe], [1], + [Take the output of nm and produce a listing of raw symbols and C names]) +_LT_DECL([global_symbol_to_cdecl], [lt_cv_sys_global_symbol_to_cdecl], [1], + [Transform the output of nm in a proper C declaration]) +_LT_DECL([global_symbol_to_c_name_address], + [lt_cv_sys_global_symbol_to_c_name_address], [1], + [Transform the output of nm in a C name address pair]) +_LT_DECL([global_symbol_to_c_name_address_lib_prefix], + [lt_cv_sys_global_symbol_to_c_name_address_lib_prefix], [1], + [Transform the output of nm in a C name address pair when lib prefix is needed]) +]) # _LT_CMD_GLOBAL_SYMBOLS + + +# _LT_COMPILER_PIC([TAGNAME]) +# --------------------------- +m4_defun([_LT_COMPILER_PIC], +[m4_require([_LT_TAG_COMPILER])dnl +_LT_TAGVAR(lt_prog_compiler_wl, $1)= +_LT_TAGVAR(lt_prog_compiler_pic, $1)= +_LT_TAGVAR(lt_prog_compiler_static, $1)= + +AC_MSG_CHECKING([for $compiler option to produce PIC]) +m4_if([$1], [CXX], [ + # C++ specific cases for pic, static, wl, etc. + if test "$GXX" = yes; then + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-static' + + case $host_os in + aix*) + # All AIX code is PIC. + if test "$host_cpu" = ia64; then + # AIX 5 now supports IA64 processor + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + fi + ;; + + amigaos*) + case $host_cpu in + powerpc) + # see comment about AmigaOS4 .so support + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' + ;; + m68k) + # FIXME: we need at least 68020 code to build shared libraries, but + # adding the `-m68020' flag to GCC prevents building anything better, + # like `-m68040'. + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-m68020 -resident32 -malways-restore-a4' + ;; + esac + ;; + + beos* | irix5* | irix6* | nonstopux* | osf3* | osf4* | osf5*) + # PIC is the default for these OSes. + ;; + mingw* | cygwin* | os2* | pw32* | cegcc*) + # This hack is so that the source file can tell whether it is being + # built for inclusion in a dll (and should export symbols for example). + # Although the cygwin gcc ignores -fPIC, still need this for old-style + # (--disable-auto-import) libraries + m4_if([$1], [GCJ], [], + [_LT_TAGVAR(lt_prog_compiler_pic, $1)='-DDLL_EXPORT']) + ;; + darwin* | rhapsody*) + # PIC is the default on this platform + # Common symbols not allowed in MH_DYLIB files + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fno-common' + ;; + *djgpp*) + # DJGPP does not support shared libraries at all + _LT_TAGVAR(lt_prog_compiler_pic, $1)= + ;; + interix[[3-9]]*) + # Interix 3.x gcc -fpic/-fPIC options generate broken code. + # Instead, we relocate shared libraries at runtime. + ;; + sysv4*MP*) + if test -d /usr/nec; then + _LT_TAGVAR(lt_prog_compiler_pic, $1)=-Kconform_pic + fi + ;; + hpux*) + # PIC is the default for 64-bit PA HP-UX, but not for 32-bit + # PA HP-UX. On IA64 HP-UX, PIC is the default but the pic flag + # sets the default TLS model and affects inlining. + case $host_cpu in + hppa*64*) + ;; + *) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' + ;; + esac + ;; + *qnx* | *nto*) + # QNX uses GNU C++, but need to define -shared option too, otherwise + # it will coredump. + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC -shared' + ;; + *) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' + ;; + esac + else + case $host_os in + aix[[4-9]]*) + # All AIX code is PIC. + if test "$host_cpu" = ia64; then + # AIX 5 now supports IA64 processor + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + else + _LT_TAGVAR(lt_prog_compiler_static, $1)='-bnso -bI:/lib/syscalls.exp' + fi + ;; + chorus*) + case $cc_basename in + cxch68*) + # Green Hills C++ Compiler + # _LT_TAGVAR(lt_prog_compiler_static, $1)="--no_auto_instantiation -u __main -u __premain -u _abort -r $COOL_DIR/lib/libOrb.a $MVME_DIR/lib/CC/libC.a $MVME_DIR/lib/classix/libcx.s.a" + ;; + esac + ;; + dgux*) + case $cc_basename in + ec++*) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + ;; + ghcx*) + # Green Hills C++ Compiler + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-pic' + ;; + *) + ;; + esac + ;; + freebsd* | dragonfly*) + # FreeBSD uses GNU C++ + ;; + hpux9* | hpux10* | hpux11*) + case $cc_basename in + CC*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_static, $1)='${wl}-a ${wl}archive' + if test "$host_cpu" != ia64; then + _LT_TAGVAR(lt_prog_compiler_pic, $1)='+Z' + fi + ;; + aCC*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_static, $1)='${wl}-a ${wl}archive' + case $host_cpu in + hppa*64*|ia64*) + # +Z the default + ;; + *) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='+Z' + ;; + esac + ;; + *) + ;; + esac + ;; + interix*) + # This is c89, which is MS Visual C++ (no shared libs) + # Anyone wants to do a port? + ;; + irix5* | irix6* | nonstopux*) + case $cc_basename in + CC*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-non_shared' + # CC pic flag -KPIC is the default. + ;; + *) + ;; + esac + ;; + linux* | k*bsd*-gnu | kopensolaris*-gnu) + case $cc_basename in + KCC*) + # KAI C++ Compiler + _LT_TAGVAR(lt_prog_compiler_wl, $1)='--backend -Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' + ;; + ecpc* ) + # old Intel C++ for x86_64 which still supported -KPIC. + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-static' + ;; + icpc* ) + # Intel C++, used to be incompatible with GCC. + # ICC 10 doesn't accept -KPIC any more. + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-static' + ;; + pgCC* | pgcpp*) + # Portland Group C++ compiler + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fpic' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + ;; + cxx*) + # Compaq C++ + # Make sure the PIC flag is empty. It appears that all Alpha + # Linux and Compaq Tru64 Unix objects are PIC. + _LT_TAGVAR(lt_prog_compiler_pic, $1)= + _LT_TAGVAR(lt_prog_compiler_static, $1)='-non_shared' + ;; + xlc* | xlC*) + # IBM XL 8.0 on PPC + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-qpic' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-qstaticlink' + ;; + *) + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) + # Sun C++ 5.9 + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Qoption ld ' + ;; + esac + ;; + esac + ;; + lynxos*) + ;; + m88k*) + ;; + mvs*) + case $cc_basename in + cxx*) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-W c,exportall' + ;; + *) + ;; + esac + ;; + netbsd* | netbsdelf*-gnu) + ;; + *qnx* | *nto*) + # QNX uses GNU C++, but need to define -shared option too, otherwise + # it will coredump. + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC -shared' + ;; + osf3* | osf4* | osf5*) + case $cc_basename in + KCC*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='--backend -Wl,' + ;; + RCC*) + # Rational C++ 2.4.1 + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-pic' + ;; + cxx*) + # Digital/Compaq C++ + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + # Make sure the PIC flag is empty. It appears that all Alpha + # Linux and Compaq Tru64 Unix objects are PIC. + _LT_TAGVAR(lt_prog_compiler_pic, $1)= + _LT_TAGVAR(lt_prog_compiler_static, $1)='-non_shared' + ;; + *) + ;; + esac + ;; + psos*) + ;; + solaris*) + case $cc_basename in + CC*) + # Sun C++ 4.2, 5.x and Centerline C++ + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Qoption ld ' + ;; + gcx*) + # Green Hills C++ Compiler + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-PIC' + ;; + *) + ;; + esac + ;; + sunos4*) + case $cc_basename in + CC*) + # Sun C++ 4.x + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-pic' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + ;; + lcc*) + # Lucid + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-pic' + ;; + *) + ;; + esac + ;; + sysv5* | unixware* | sco3.2v5* | sco5v6* | OpenUNIX*) + case $cc_basename in + CC*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + ;; + esac + ;; + tandem*) + case $cc_basename in + NCC*) + # NonStop-UX NCC 3.20 + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + ;; + *) + ;; + esac + ;; + vxworks*) + ;; + *) + _LT_TAGVAR(lt_prog_compiler_can_build_shared, $1)=no + ;; + esac + fi +], +[ + if test "$GCC" = yes; then + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-static' + + case $host_os in + aix*) + # All AIX code is PIC. + if test "$host_cpu" = ia64; then + # AIX 5 now supports IA64 processor + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + fi + ;; + + amigaos*) + case $host_cpu in + powerpc) + # see comment about AmigaOS4 .so support + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' + ;; + m68k) + # FIXME: we need at least 68020 code to build shared libraries, but + # adding the `-m68020' flag to GCC prevents building anything better, + # like `-m68040'. + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-m68020 -resident32 -malways-restore-a4' + ;; + esac + ;; + + beos* | irix5* | irix6* | nonstopux* | osf3* | osf4* | osf5*) + # PIC is the default for these OSes. + ;; + + mingw* | cygwin* | pw32* | os2* | cegcc*) + # This hack is so that the source file can tell whether it is being + # built for inclusion in a dll (and should export symbols for example). + # Although the cygwin gcc ignores -fPIC, still need this for old-style + # (--disable-auto-import) libraries + m4_if([$1], [GCJ], [], + [_LT_TAGVAR(lt_prog_compiler_pic, $1)='-DDLL_EXPORT']) + ;; + + darwin* | rhapsody*) + # PIC is the default on this platform + # Common symbols not allowed in MH_DYLIB files + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fno-common' + ;; + + hpux*) + # PIC is the default for 64-bit PA HP-UX, but not for 32-bit + # PA HP-UX. On IA64 HP-UX, PIC is the default but the pic flag + # sets the default TLS model and affects inlining. + case $host_cpu in + hppa*64*) + # +Z the default + ;; + *) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' + ;; + esac + ;; + + interix[[3-9]]*) + # Interix 3.x gcc -fpic/-fPIC options generate broken code. + # Instead, we relocate shared libraries at runtime. + ;; + + msdosdjgpp*) + # Just because we use GCC doesn't mean we suddenly get shared libraries + # on systems that don't support them. + _LT_TAGVAR(lt_prog_compiler_can_build_shared, $1)=no + enable_shared=no + ;; + + *nto* | *qnx*) + # QNX uses GNU C++, but need to define -shared option too, otherwise + # it will coredump. + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC -shared' + ;; + + sysv4*MP*) + if test -d /usr/nec; then + _LT_TAGVAR(lt_prog_compiler_pic, $1)=-Kconform_pic + fi + ;; + + *) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' + ;; + esac + else + # PORTME Check for flag to pass linker flags through the system compiler. + case $host_os in + aix*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + if test "$host_cpu" = ia64; then + # AIX 5 now supports IA64 processor + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + else + _LT_TAGVAR(lt_prog_compiler_static, $1)='-bnso -bI:/lib/syscalls.exp' + fi + ;; + + mingw* | cygwin* | pw32* | os2* | cegcc*) + # This hack is so that the source file can tell whether it is being + # built for inclusion in a dll (and should export symbols for example). + m4_if([$1], [GCJ], [], + [_LT_TAGVAR(lt_prog_compiler_pic, $1)='-DDLL_EXPORT']) + ;; + + hpux9* | hpux10* | hpux11*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + # PIC is the default for IA64 HP-UX and 64-bit HP-UX, but + # not for PA HP-UX. + case $host_cpu in + hppa*64*|ia64*) + # +Z the default + ;; + *) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='+Z' + ;; + esac + # Is there a better lt_prog_compiler_static that works with the bundled CC? + _LT_TAGVAR(lt_prog_compiler_static, $1)='${wl}-a ${wl}archive' + ;; + + irix5* | irix6* | nonstopux*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + # PIC (with -KPIC) is the default. + _LT_TAGVAR(lt_prog_compiler_static, $1)='-non_shared' + ;; + + linux* | k*bsd*-gnu | kopensolaris*-gnu) + case $cc_basename in + # old Intel for x86_64 which still supported -KPIC. + ecc*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-static' + ;; + # icc used to be incompatible with GCC. + # ICC 10 doesn't accept -KPIC any more. + icc* | ifort*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-static' + ;; + # Lahey Fortran 8.1. + lf95*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='--shared' + _LT_TAGVAR(lt_prog_compiler_static, $1)='--static' + ;; + pgcc* | pgf77* | pgf90* | pgf95*) + # Portland Group compilers (*not* the Pentium gcc compiler, + # which looks to be a dead project) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fpic' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + ;; + ccc*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + # All Alpha code is PIC. + _LT_TAGVAR(lt_prog_compiler_static, $1)='-non_shared' + ;; + xl*) + # IBM XL C 8.0/Fortran 10.1 on PPC + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-qpic' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-qstaticlink' + ;; + *) + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) + # Sun C 5.9 + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + ;; + *Sun\ F*) + # Sun Fortran 8.3 passes all unrecognized flags to the linker + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + _LT_TAGVAR(lt_prog_compiler_wl, $1)='' + ;; + esac + ;; + esac + ;; + + newsos6) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + ;; + + *nto* | *qnx*) + # QNX uses GNU C++, but need to define -shared option too, otherwise + # it will coredump. + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC -shared' + ;; + + osf3* | osf4* | osf5*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + # All OSF/1 code is PIC. + _LT_TAGVAR(lt_prog_compiler_static, $1)='-non_shared' + ;; + + rdos*) + _LT_TAGVAR(lt_prog_compiler_static, $1)='-non_shared' + ;; + + solaris*) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + case $cc_basename in + f77* | f90* | f95*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Qoption ld ';; + *) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,';; + esac + ;; + + sunos4*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Qoption ld ' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-PIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + ;; + + sysv4 | sysv4.2uw2* | sysv4.3*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + ;; + + sysv4*MP*) + if test -d /usr/nec ;then + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-Kconform_pic' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + fi + ;; + + sysv5* | unixware* | sco3.2v5* | sco5v6* | OpenUNIX*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + ;; + + unicos*) + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_can_build_shared, $1)=no + ;; + + uts4*) + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-pic' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + ;; + + *) + _LT_TAGVAR(lt_prog_compiler_can_build_shared, $1)=no + ;; + esac + fi +]) +case $host_os in + # For platforms which do not support PIC, -DPIC is meaningless: + *djgpp*) + _LT_TAGVAR(lt_prog_compiler_pic, $1)= + ;; + *) + _LT_TAGVAR(lt_prog_compiler_pic, $1)="$_LT_TAGVAR(lt_prog_compiler_pic, $1)@&t@m4_if([$1],[],[ -DPIC],[m4_if([$1],[CXX],[ -DPIC],[])])" + ;; +esac +AC_MSG_RESULT([$_LT_TAGVAR(lt_prog_compiler_pic, $1)]) +_LT_TAGDECL([wl], [lt_prog_compiler_wl], [1], + [How to pass a linker flag through the compiler]) + +# +# Check to make sure the PIC flag actually works. +# +if test -n "$_LT_TAGVAR(lt_prog_compiler_pic, $1)"; then + _LT_COMPILER_OPTION([if $compiler PIC flag $_LT_TAGVAR(lt_prog_compiler_pic, $1) works], + [_LT_TAGVAR(lt_cv_prog_compiler_pic_works, $1)], + [$_LT_TAGVAR(lt_prog_compiler_pic, $1)@&t@m4_if([$1],[],[ -DPIC],[m4_if([$1],[CXX],[ -DPIC],[])])], [], + [case $_LT_TAGVAR(lt_prog_compiler_pic, $1) in + "" | " "*) ;; + *) _LT_TAGVAR(lt_prog_compiler_pic, $1)=" $_LT_TAGVAR(lt_prog_compiler_pic, $1)" ;; + esac], + [_LT_TAGVAR(lt_prog_compiler_pic, $1)= + _LT_TAGVAR(lt_prog_compiler_can_build_shared, $1)=no]) +fi +_LT_TAGDECL([pic_flag], [lt_prog_compiler_pic], [1], + [Additional compiler flags for building library objects]) + +# +# Check to make sure the static flag actually works. +# +wl=$_LT_TAGVAR(lt_prog_compiler_wl, $1) eval lt_tmp_static_flag=\"$_LT_TAGVAR(lt_prog_compiler_static, $1)\" +_LT_LINKER_OPTION([if $compiler static flag $lt_tmp_static_flag works], + _LT_TAGVAR(lt_cv_prog_compiler_static_works, $1), + $lt_tmp_static_flag, + [], + [_LT_TAGVAR(lt_prog_compiler_static, $1)=]) +_LT_TAGDECL([link_static_flag], [lt_prog_compiler_static], [1], + [Compiler flag to prevent dynamic linking]) +])# _LT_COMPILER_PIC + + +# _LT_LINKER_SHLIBS([TAGNAME]) +# ---------------------------- +# See if the linker supports building shared libraries. +m4_defun([_LT_LINKER_SHLIBS], +[AC_REQUIRE([LT_PATH_LD])dnl +AC_REQUIRE([LT_PATH_NM])dnl +m4_require([_LT_FILEUTILS_DEFAULTS])dnl +m4_require([_LT_DECL_EGREP])dnl +m4_require([_LT_DECL_SED])dnl +m4_require([_LT_CMD_GLOBAL_SYMBOLS])dnl +m4_require([_LT_TAG_COMPILER])dnl +AC_MSG_CHECKING([whether the $compiler linker ($LD) supports shared libraries]) +m4_if([$1], [CXX], [ + _LT_TAGVAR(export_symbols_cmds, $1)='$NM $libobjs $convenience | $global_symbol_pipe | $SED '\''s/.* //'\'' | sort | uniq > $export_symbols' + case $host_os in + aix[[4-9]]*) + # If we're using GNU nm, then we don't want the "-C" option. + # -C means demangle to AIX nm, but means don't demangle with GNU nm + if $NM -V 2>&1 | $GREP 'GNU' > /dev/null; then + _LT_TAGVAR(export_symbols_cmds, $1)='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && ([substr](\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + else + _LT_TAGVAR(export_symbols_cmds, $1)='$NM -BCpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && ([substr](\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + fi + ;; + pw32*) + _LT_TAGVAR(export_symbols_cmds, $1)="$ltdll_cmds" + ;; + cygwin* | mingw* | cegcc*) + _LT_TAGVAR(export_symbols_cmds, $1)='$NM $libobjs $convenience | $global_symbol_pipe | $SED -e '\''/^[[BCDGRS]][[ ]]/s/.*[[ ]]\([[^ ]]*\)/\1 DATA/;/^.*[[ ]]__nm__/s/^.*[[ ]]__nm__\([[^ ]]*\)[[ ]][[^ ]]*/\1 DATA/;/^I[[ ]]/d;/^[[AITW]][[ ]]/s/.* //'\'' | sort | uniq > $export_symbols' + ;; + linux* | k*bsd*-gnu) + _LT_TAGVAR(link_all_deplibs, $1)=no + ;; + *) + _LT_TAGVAR(export_symbols_cmds, $1)='$NM $libobjs $convenience | $global_symbol_pipe | $SED '\''s/.* //'\'' | sort | uniq > $export_symbols' + ;; + esac + _LT_TAGVAR(exclude_expsyms, $1)=['_GLOBAL_OFFSET_TABLE_|_GLOBAL__F[ID]_.*'] +], [ + runpath_var= + _LT_TAGVAR(allow_undefined_flag, $1)= + _LT_TAGVAR(always_export_symbols, $1)=no + _LT_TAGVAR(archive_cmds, $1)= + _LT_TAGVAR(archive_expsym_cmds, $1)= + _LT_TAGVAR(compiler_needs_object, $1)=no + _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=no + _LT_TAGVAR(export_dynamic_flag_spec, $1)= + _LT_TAGVAR(export_symbols_cmds, $1)='$NM $libobjs $convenience | $global_symbol_pipe | $SED '\''s/.* //'\'' | sort | uniq > $export_symbols' + _LT_TAGVAR(hardcode_automatic, $1)=no + _LT_TAGVAR(hardcode_direct, $1)=no + _LT_TAGVAR(hardcode_direct_absolute, $1)=no + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)= + _LT_TAGVAR(hardcode_libdir_flag_spec_ld, $1)= + _LT_TAGVAR(hardcode_libdir_separator, $1)= + _LT_TAGVAR(hardcode_minus_L, $1)=no + _LT_TAGVAR(hardcode_shlibpath_var, $1)=unsupported + _LT_TAGVAR(inherit_rpath, $1)=no + _LT_TAGVAR(link_all_deplibs, $1)=unknown + _LT_TAGVAR(module_cmds, $1)= + _LT_TAGVAR(module_expsym_cmds, $1)= + _LT_TAGVAR(old_archive_from_new_cmds, $1)= + _LT_TAGVAR(old_archive_from_expsyms_cmds, $1)= + _LT_TAGVAR(thread_safe_flag_spec, $1)= + _LT_TAGVAR(whole_archive_flag_spec, $1)= + # include_expsyms should be a list of space-separated symbols to be *always* + # included in the symbol list + _LT_TAGVAR(include_expsyms, $1)= + # exclude_expsyms can be an extended regexp of symbols to exclude + # it will be wrapped by ` (' and `)$', so one must not match beginning or + # end of line. Example: `a|bc|.*d.*' will exclude the symbols `a' and `bc', + # as well as any symbol that contains `d'. + _LT_TAGVAR(exclude_expsyms, $1)=['_GLOBAL_OFFSET_TABLE_|_GLOBAL__F[ID]_.*'] + # Although _GLOBAL_OFFSET_TABLE_ is a valid symbol C name, most a.out + # platforms (ab)use it in PIC code, but their linkers get confused if + # the symbol is explicitly referenced. Since portable code cannot + # rely on this symbol name, it's probably fine to never include it in + # preloaded symbol tables. + # Exclude shared library initialization/finalization symbols. +dnl Note also adjust exclude_expsyms for C++ above. + extract_expsyms_cmds= + + case $host_os in + cygwin* | mingw* | pw32* | cegcc*) + # FIXME: the MSVC++ port hasn't been tested in a loooong time + # When not using gcc, we currently assume that we are using + # Microsoft Visual C++. + if test "$GCC" != yes; then + with_gnu_ld=no + fi + ;; + interix*) + # we just hope/assume this is gcc and not c89 (= MSVC++) + with_gnu_ld=yes + ;; + openbsd*) + with_gnu_ld=no + ;; + linux* | k*bsd*-gnu) + _LT_TAGVAR(link_all_deplibs, $1)=no + ;; + esac + + _LT_TAGVAR(ld_shlibs, $1)=yes + if test "$with_gnu_ld" = yes; then + # If archive_cmds runs LD, not CC, wlarc should be empty + wlarc='${wl}' + + # Set some defaults for GNU ld with shared library support. These + # are reset later if shared libraries are not supported. Putting them + # here allows them to be overridden if necessary. + runpath_var=LD_RUN_PATH + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' + # ancient GNU ld didn't support --whole-archive et. al. + if $LD --help 2>&1 | $GREP 'no-whole-archive' > /dev/null; then + _LT_TAGVAR(whole_archive_flag_spec, $1)="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + else + _LT_TAGVAR(whole_archive_flag_spec, $1)= + fi + supports_anon_versioning=no + case `$LD -v 2>&1` in + *GNU\ gold*) supports_anon_versioning=yes ;; + *\ [[01]].* | *\ 2.[[0-9]].* | *\ 2.10.*) ;; # catch versions < 2.11 + *\ 2.11.93.0.2\ *) supports_anon_versioning=yes ;; # RH7.3 ... + *\ 2.11.92.0.12\ *) supports_anon_versioning=yes ;; # Mandrake 8.2 ... + *\ 2.11.*) ;; # other 2.11 versions + *) supports_anon_versioning=yes ;; + esac + + # See if GNU ld supports shared libraries. + case $host_os in + aix[[3-9]]*) + # On AIX/PPC, the GNU linker is very broken + if test "$host_cpu" != ia64; then + _LT_TAGVAR(ld_shlibs, $1)=no + cat <<_LT_EOF 1>&2 + +*** Warning: the GNU linker, at least up to release 2.9.1, is reported +*** to be unable to reliably create shared libraries on AIX. +*** Therefore, libtool is disabling shared libraries support. If you +*** really care for shared libraries, you may want to modify your PATH +*** so that a non-GNU linker is found, and then restart. + +_LT_EOF + fi + ;; + + amigaos*) + case $host_cpu in + powerpc) + # see comment about AmigaOS4 .so support + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='' + ;; + m68k) + _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/a2ixlibrary.data~$ECHO "#define NAME $libname" > $output_objdir/a2ixlibrary.data~$ECHO "#define LIBRARY_ID 1" >> $output_objdir/a2ixlibrary.data~$ECHO "#define VERSION $major" >> $output_objdir/a2ixlibrary.data~$ECHO "#define REVISION $revision" >> $output_objdir/a2ixlibrary.data~$AR $AR_FLAGS $lib $libobjs~$RANLIB $lib~(cd $output_objdir && a2ixlibrary -32)' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(hardcode_minus_L, $1)=yes + ;; + esac + ;; + + beos*) + if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then + _LT_TAGVAR(allow_undefined_flag, $1)=unsupported + # Joseph Beckenbach says some releases of gcc + # support --undefined. This deserves some investigation. FIXME + _LT_TAGVAR(archive_cmds, $1)='$CC -nostart $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + + cygwin* | mingw* | pw32* | cegcc*) + # _LT_TAGVAR(hardcode_libdir_flag_spec, $1) is actually meaningless, + # as there is no search path for DLLs. + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(allow_undefined_flag, $1)=unsupported + _LT_TAGVAR(always_export_symbols, $1)=no + _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=yes + _LT_TAGVAR(export_symbols_cmds, $1)='$NM $libobjs $convenience | $global_symbol_pipe | $SED -e '\''/^[[BCDGRS]][[ ]]/s/.*[[ ]]\([[^ ]]*\)/\1 DATA/'\'' | $SED -e '\''/^[[AITW]][[ ]]/s/.*[[ ]]//'\'' | sort | uniq > $export_symbols' + + if $LD --help 2>&1 | $GREP 'auto-import' > /dev/null; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + # If the export-symbols file already is a .def file (1st line + # is EXPORTS), use it as is; otherwise, prepend... + _LT_TAGVAR(archive_expsym_cmds, $1)='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then + cp $export_symbols $output_objdir/$soname.def; + else + echo EXPORTS > $output_objdir/$soname.def; + cat $export_symbols >> $output_objdir/$soname.def; + fi~ + $CC -shared $output_objdir/$soname.def $libobjs $deplibs $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + + interix[[3-9]]*) + _LT_TAGVAR(hardcode_direct, $1)=no + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + # Hack: On Interix 3.x, we cannot compile PIC because of a broken gcc. + # Instead, shared libraries are loaded at an image base (0x10000000 by + # default) and relocated if they conflict, which is a slow very memory + # consuming and fragmenting process. To avoid this, we pick a random, + # 256 KiB-aligned image base between 0x50000000 and 0x6FFC0000 at link + # time. Moving up from 0x10000000 also allows more sbrk(2) space. + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='sed "s,^,_," $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--retain-symbols-file,$output_objdir/$soname.expsym ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + ;; + + gnu* | linux* | tpf* | k*bsd*-gnu | kopensolaris*-gnu) + tmp_diet=no + if test "$host_os" = linux-dietlibc; then + case $cc_basename in + diet\ *) tmp_diet=yes;; # linux-dietlibc with static linking (!diet-dyn) + esac + fi + if $LD --help 2>&1 | $EGREP ': supported targets:.* elf' > /dev/null \ + && test "$tmp_diet" = no + then + tmp_addflag= + tmp_sharedflag='-shared' + case $cc_basename,$host_cpu in + pgcc*) # Portland Group C compiler + _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; $ECHO \"$new_convenience\"` ${wl}--no-whole-archive' + tmp_addflag=' $pic_flag' + ;; + pgf77* | pgf90* | pgf95*) # Portland Group f77 and f90 compilers + _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; $ECHO \"$new_convenience\"` ${wl}--no-whole-archive' + tmp_addflag=' $pic_flag -Mnomain' ;; + ecc*,ia64* | icc*,ia64*) # Intel C compiler on ia64 + tmp_addflag=' -i_dynamic' ;; + efc*,ia64* | ifort*,ia64*) # Intel Fortran compiler on ia64 + tmp_addflag=' -i_dynamic -nofor_main' ;; + ifc* | ifort*) # Intel Fortran compiler + tmp_addflag=' -nofor_main' ;; + lf95*) # Lahey Fortran 8.1 + _LT_TAGVAR(whole_archive_flag_spec, $1)= + tmp_sharedflag='--shared' ;; + xl[[cC]]*) # IBM XL C 8.0 on PPC (deal with xlf below) + tmp_sharedflag='-qmkshrobj' + tmp_addflag= ;; + esac + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) # Sun C 5.9 + _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; $ECHO \"$new_convenience\"` ${wl}--no-whole-archive' + _LT_TAGVAR(compiler_needs_object, $1)=yes + tmp_sharedflag='-G' ;; + *Sun\ F*) # Sun Fortran 8.3 + tmp_sharedflag='-G' ;; + esac + _LT_TAGVAR(archive_cmds, $1)='$CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + + if test "x$supports_anon_versioning" = xyes; then + _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $output_objdir/$libname.ver~ + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-version-script ${wl}$output_objdir/$libname.ver -o $lib' + fi + + case $cc_basename in + xlf*) + # IBM XL Fortran 10.1 on PPC cannot create shared libs itself + _LT_TAGVAR(whole_archive_flag_spec, $1)='--whole-archive$convenience --no-whole-archive' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)= + _LT_TAGVAR(hardcode_libdir_flag_spec_ld, $1)='-rpath $libdir' + _LT_TAGVAR(archive_cmds, $1)='$LD -shared $libobjs $deplibs $compiler_flags -soname $soname -o $lib' + if test "x$supports_anon_versioning" = xyes; then + _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $output_objdir/$libname.ver~ + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $LD -shared $libobjs $deplibs $compiler_flags -soname $soname -version-script $output_objdir/$libname.ver -o $lib' + fi + ;; + esac + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + + netbsd* | netbsdelf*-gnu) + if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then + _LT_TAGVAR(archive_cmds, $1)='$LD -Bshareable $libobjs $deplibs $linker_flags -o $lib' + wlarc= + else + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + fi + ;; + + solaris*) + if $LD -v 2>&1 | $GREP 'BFD 2\.8' > /dev/null; then + _LT_TAGVAR(ld_shlibs, $1)=no + cat <<_LT_EOF 1>&2 + +*** Warning: The releases 2.8.* of the GNU linker cannot reliably +*** create shared libraries on Solaris systems. Therefore, libtool +*** is disabling shared libraries support. We urge you to upgrade GNU +*** binutils to release 2.9.1 or newer. Another option is to modify +*** your PATH or compiler configuration so that the native linker is +*** used, and then restart. + +_LT_EOF + elif $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + + sysv5* | sco3.2v5* | sco5v6* | unixware* | OpenUNIX*) + case `$LD -v 2>&1` in + *\ [[01]].* | *\ 2.[[0-9]].* | *\ 2.1[[0-5]].*) + _LT_TAGVAR(ld_shlibs, $1)=no + cat <<_LT_EOF 1>&2 + +*** Warning: Releases of the GNU linker prior to 2.16.91.0.3 can not +*** reliably create shared libraries on SCO systems. Therefore, libtool +*** is disabling shared libraries support. We urge you to upgrade GNU +*** binutils to release 2.16.91.0.3 or newer. Another option is to modify +*** your PATH or compiler configuration so that the native linker is +*** used, and then restart. + +_LT_EOF + ;; + *) + # For security reasons, it is highly recommended that you always + # use absolute paths for naming shared libraries, and exclude the + # DT_RUNPATH tag from executables and libraries. But doing so + # requires that you compile everything twice, which is a pain. + if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + esac + ;; + + sunos4*) + _LT_TAGVAR(archive_cmds, $1)='$LD -assert pure-text -Bshareable -o $lib $libobjs $deplibs $linker_flags' + wlarc= + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + + *) + if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + esac + + if test "$_LT_TAGVAR(ld_shlibs, $1)" = no; then + runpath_var= + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)= + _LT_TAGVAR(export_dynamic_flag_spec, $1)= + _LT_TAGVAR(whole_archive_flag_spec, $1)= + fi + else + # PORTME fill in a description of your system's linker (not GNU ld) + case $host_os in + aix3*) + _LT_TAGVAR(allow_undefined_flag, $1)=unsupported + _LT_TAGVAR(always_export_symbols, $1)=yes + _LT_TAGVAR(archive_expsym_cmds, $1)='$LD -o $output_objdir/$soname $libobjs $deplibs $linker_flags -bE:$export_symbols -T512 -H512 -bM:SRE~$AR $AR_FLAGS $lib $output_objdir/$soname' + # Note: this linker hardcodes the directories in LIBPATH if there + # are no directories specified by -L. + _LT_TAGVAR(hardcode_minus_L, $1)=yes + if test "$GCC" = yes && test -z "$lt_prog_compiler_static"; then + # Neither direct hardcoding nor static linking is supported with a + # broken collect2. + _LT_TAGVAR(hardcode_direct, $1)=unsupported + fi + ;; + + aix[[4-9]]*) + if test "$host_cpu" = ia64; then + # On IA64, the linker does run time linking by default, so we don't + # have to do anything special. + aix_use_runtimelinking=no + exp_sym_flag='-Bexport' + no_entry_flag="" + else + # If we're using GNU nm, then we don't want the "-C" option. + # -C means demangle to AIX nm, but means don't demangle with GNU nm + if $NM -V 2>&1 | $GREP 'GNU' > /dev/null; then + _LT_TAGVAR(export_symbols_cmds, $1)='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && ([substr](\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + else + _LT_TAGVAR(export_symbols_cmds, $1)='$NM -BCpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && ([substr](\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + fi + aix_use_runtimelinking=no + + # Test if we are trying to use run time linking or normal + # AIX style linking. If -brtl is somewhere in LDFLAGS, we + # need to do runtime linking. + case $host_os in aix4.[[23]]|aix4.[[23]].*|aix[[5-9]]*) + for ld_flag in $LDFLAGS; do + if (test $ld_flag = "-brtl" || test $ld_flag = "-Wl,-brtl"); then + aix_use_runtimelinking=yes + break + fi + done + ;; + esac + + exp_sym_flag='-bexport' + no_entry_flag='-bnoentry' + fi + + # When large executables or shared objects are built, AIX ld can + # have problems creating the table of contents. If linking a library + # or program results in "error TOC overflow" add -mminimal-toc to + # CXXFLAGS/CFLAGS for g++/gcc. In the cases where that is not + # enough to fix the problem, add -Wl,-bbigtoc to LDFLAGS. + + _LT_TAGVAR(archive_cmds, $1)='' + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_direct_absolute, $1)=yes + _LT_TAGVAR(hardcode_libdir_separator, $1)=':' + _LT_TAGVAR(link_all_deplibs, $1)=yes + _LT_TAGVAR(file_list_spec, $1)='${wl}-f,' + + if test "$GCC" = yes; then + case $host_os in aix4.[[012]]|aix4.[[012]].*) + # We only want to do this on AIX 4.2 and lower, the check + # below for broken collect2 doesn't work under 4.3+ + collect2name=`${CC} -print-prog-name=collect2` + if test -f "$collect2name" && + strings "$collect2name" | $GREP resolve_lib_name >/dev/null + then + # We have reworked collect2 + : + else + # We have old collect2 + _LT_TAGVAR(hardcode_direct, $1)=unsupported + # It fails to find uninstalled libraries when the uninstalled + # path is not listed in the libpath. Setting hardcode_minus_L + # to unsupported forces relinking + _LT_TAGVAR(hardcode_minus_L, $1)=yes + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)= + fi + ;; + esac + shared_flag='-shared' + if test "$aix_use_runtimelinking" = yes; then + shared_flag="$shared_flag "'${wl}-G' + fi + _LT_TAGVAR(link_all_deplibs, $1)=no + else + # not using gcc + if test "$host_cpu" = ia64; then + # VisualAge C++, Version 5.5 for AIX 5L for IA-64, Beta 3 Release + # chokes on -Wl,-G. The following line is correct: + shared_flag='-G' + else + if test "$aix_use_runtimelinking" = yes; then + shared_flag='${wl}-G' + else + shared_flag='${wl}-bM:SRE' + fi + fi + fi + + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-bexpall' + # It seems that -bexpall does not export symbols beginning with + # underscore (_), so it is better to generate a list of symbols to export. + _LT_TAGVAR(always_export_symbols, $1)=yes + if test "$aix_use_runtimelinking" = yes; then + # Warning - without using the other runtime loading flags (-brtl), + # -berok will link without error, but may produce a broken library. + _LT_TAGVAR(allow_undefined_flag, $1)='-berok' + # Determine the default libpath from the value encoded in an + # empty executable. + _LT_SYS_MODULE_PATH_AIX + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-blibpath:$libdir:'"$aix_libpath" + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags `if test "x${allow_undefined_flag}" != "x"; then $ECHO "X${wl}${allow_undefined_flag}" | $Xsed; else :; fi` '"\${wl}$exp_sym_flag:\$export_symbols $shared_flag" + else + if test "$host_cpu" = ia64; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-R $libdir:/usr/lib:/lib' + _LT_TAGVAR(allow_undefined_flag, $1)="-z nodefs" + _LT_TAGVAR(archive_expsym_cmds, $1)="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags ${wl}${allow_undefined_flag} '"\${wl}$exp_sym_flag:\$export_symbols" + else + # Determine the default libpath from the value encoded in an + # empty executable. + _LT_SYS_MODULE_PATH_AIX + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-blibpath:$libdir:'"$aix_libpath" + # Warning - without using the other run time loading flags, + # -berok will link without error, but may produce a broken library. + _LT_TAGVAR(no_undefined_flag, $1)=' ${wl}-bernotok' + _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-berok' + # Exported symbols can be pulled into shared objects from archives + _LT_TAGVAR(whole_archive_flag_spec, $1)='$convenience' + _LT_TAGVAR(archive_cmds_need_lc, $1)=yes + # This is similar to how AIX traditionally builds its shared libraries. + _LT_TAGVAR(archive_expsym_cmds, $1)="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs ${wl}-bnoentry $compiler_flags ${wl}-bE:$export_symbols${allow_undefined_flag}~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$soname' + fi + fi + ;; + + amigaos*) + case $host_cpu in + powerpc) + # see comment about AmigaOS4 .so support + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='' + ;; + m68k) + _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/a2ixlibrary.data~$ECHO "#define NAME $libname" > $output_objdir/a2ixlibrary.data~$ECHO "#define LIBRARY_ID 1" >> $output_objdir/a2ixlibrary.data~$ECHO "#define VERSION $major" >> $output_objdir/a2ixlibrary.data~$ECHO "#define REVISION $revision" >> $output_objdir/a2ixlibrary.data~$AR $AR_FLAGS $lib $libobjs~$RANLIB $lib~(cd $output_objdir && a2ixlibrary -32)' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(hardcode_minus_L, $1)=yes + ;; + esac + ;; + + bsdi[[45]]*) + _LT_TAGVAR(export_dynamic_flag_spec, $1)=-rdynamic + ;; + + cygwin* | mingw* | pw32* | cegcc*) + # When not using gcc, we currently assume that we are using + # Microsoft Visual C++. + # hardcode_libdir_flag_spec is actually meaningless, as there is + # no search path for DLLs. + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)=' ' + _LT_TAGVAR(allow_undefined_flag, $1)=unsupported + # Tell ltmain to make .lib files, not .a files. + libext=lib + # Tell ltmain to make .dll files, not .so files. + shrext_cmds=".dll" + # FIXME: Setting linknames here is a bad hack. + _LT_TAGVAR(archive_cmds, $1)='$CC -o $lib $libobjs $compiler_flags `$ECHO "X$deplibs" | $Xsed -e '\''s/ -lc$//'\''` -link -dll~linknames=' + # The linker will automatically build a .lib file if we build a DLL. + _LT_TAGVAR(old_archive_from_new_cmds, $1)='true' + # FIXME: Should let the user specify the lib program. + _LT_TAGVAR(old_archive_cmds, $1)='lib -OUT:$oldlib$oldobjs$old_deplibs' + _LT_TAGVAR(fix_srcfile_path, $1)='`cygpath -w "$srcfile"`' + _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=yes + ;; + + darwin* | rhapsody*) + _LT_DARWIN_LINKER_FEATURES($1) + ;; + + dgux*) + _LT_TAGVAR(archive_cmds, $1)='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + + freebsd1*) + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + + # FreeBSD 2.2.[012] allows us to include c++rt0.o to get C++ constructor + # support. Future versions do this automatically, but an explicit c++rt0.o + # does not break anything, and helps significantly (at the cost of a little + # extra space). + freebsd2.2*) + _LT_TAGVAR(archive_cmds, $1)='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags /usr/lib/c++rt0.o' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + + # Unfortunately, older versions of FreeBSD 2 do not have this feature. + freebsd2*) + _LT_TAGVAR(archive_cmds, $1)='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_minus_L, $1)=yes + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + + # FreeBSD 3 and greater uses gcc -shared to do shared libraries. + freebsd* | dragonfly*) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + + hpux9*) + if test "$GCC" = yes; then + _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$CC -shared -fPIC ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $libobjs $deplibs $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + else + _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$LD -b +b $install_libdir -o $output_objdir/$soname $libobjs $deplibs $linker_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + fi + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}+b ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + _LT_TAGVAR(hardcode_direct, $1)=yes + + # hardcode_minus_L: Not really in the search PATH, + # but as the default location of the library. + _LT_TAGVAR(hardcode_minus_L, $1)=yes + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + ;; + + hpux10*) + if test "$GCC" = yes -a "$with_gnu_ld" = no; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -fPIC ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' + else + _LT_TAGVAR(archive_cmds, $1)='$LD -b +h $soname +b $install_libdir -o $lib $libobjs $deplibs $linker_flags' + fi + if test "$with_gnu_ld" = no; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}+b ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec_ld, $1)='+b $libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_direct_absolute, $1)=yes + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + # hardcode_minus_L: Not really in the search PATH, + # but as the default location of the library. + _LT_TAGVAR(hardcode_minus_L, $1)=yes + fi + ;; + + hpux11*) + if test "$GCC" = yes -a "$with_gnu_ld" = no; then + case $host_cpu in + hppa*64*) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}+h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + ia64*) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -fPIC ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' + ;; + *) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -fPIC ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' + ;; + esac + else + case $host_cpu in + hppa*64*) + _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + ia64*) + _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' + ;; + *) + _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' + ;; + esac + fi + if test "$with_gnu_ld" = no; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}+b ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + + case $host_cpu in + hppa*64*|ia64*) + _LT_TAGVAR(hardcode_direct, $1)=no + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + *) + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_direct_absolute, $1)=yes + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + + # hardcode_minus_L: Not really in the search PATH, + # but as the default location of the library. + _LT_TAGVAR(hardcode_minus_L, $1)=yes + ;; + esac + fi + ;; + + irix5* | irix6* | nonstopux*) + if test "$GCC" = yes; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + # Try to use the -exported_symbol ld option, if it does not + # work, assume that -exports_file does not work either and + # implicitly export all symbols. + save_LDFLAGS="$LDFLAGS" + LDFLAGS="$LDFLAGS -shared ${wl}-exported_symbol ${wl}foo ${wl}-update_registry ${wl}/dev/null" + AC_LINK_IFELSE(int foo(void) {}, + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations ${wl}-exports_file ${wl}$export_symbols -o $lib' + ) + LDFLAGS="$save_LDFLAGS" + else + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -exports_file $export_symbols -o $lib' + fi + _LT_TAGVAR(archive_cmds_need_lc, $1)='no' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + _LT_TAGVAR(inherit_rpath, $1)=yes + _LT_TAGVAR(link_all_deplibs, $1)=yes + ;; + + netbsd* | netbsdelf*-gnu) + if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then + _LT_TAGVAR(archive_cmds, $1)='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags' # a.out + else + _LT_TAGVAR(archive_cmds, $1)='$LD -shared -o $lib $libobjs $deplibs $linker_flags' # ELF + fi + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + + newsos6) + _LT_TAGVAR(archive_cmds, $1)='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + + *nto* | *qnx*) + ;; + + openbsd*) + if test -f /usr/libexec/ld.so; then + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + _LT_TAGVAR(hardcode_direct_absolute, $1)=yes + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags ${wl}-retain-symbols-file,$export_symbols' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + else + case $host_os in + openbsd[[01]].* | openbsd2.[[0-7]] | openbsd2.[[0-7]].*) + _LT_TAGVAR(archive_cmds, $1)='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' + ;; + *) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' + ;; + esac + fi + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + + os2*) + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(hardcode_minus_L, $1)=yes + _LT_TAGVAR(allow_undefined_flag, $1)=unsupported + _LT_TAGVAR(archive_cmds, $1)='$ECHO "LIBRARY $libname INITINSTANCE" > $output_objdir/$libname.def~$ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~$ECHO DATA >> $output_objdir/$libname.def~$ECHO " SINGLE NONSHARED" >> $output_objdir/$libname.def~$ECHO EXPORTS >> $output_objdir/$libname.def~emxexp $libobjs >> $output_objdir/$libname.def~$CC -Zdll -Zcrtdll -o $lib $libobjs $deplibs $compiler_flags $output_objdir/$libname.def' + _LT_TAGVAR(old_archive_from_new_cmds, $1)='emximp -o $output_objdir/$libname.a $output_objdir/$libname.def' + ;; + + osf3*) + if test "$GCC" = yes; then + _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-expect_unresolved ${wl}\*' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + else + _LT_TAGVAR(allow_undefined_flag, $1)=' -expect_unresolved \*' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + fi + _LT_TAGVAR(archive_cmds_need_lc, $1)='no' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + ;; + + osf4* | osf5*) # as osf3* with the addition of -msym flag + if test "$GCC" = yes; then + _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-expect_unresolved ${wl}\*' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags ${wl}-msym ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + else + _LT_TAGVAR(allow_undefined_flag, $1)=' -expect_unresolved \*' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags -msym -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='for i in `cat $export_symbols`; do printf "%s %s\\n" -exported_symbol "\$i" >> $lib.exp; done; printf "%s\\n" "-hidden">> $lib.exp~ + $CC -shared${allow_undefined_flag} ${wl}-input ${wl}$lib.exp $compiler_flags $libobjs $deplibs -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib~$RM $lib.exp' + + # Both c and cxx compiler support -rpath directly + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-rpath $libdir' + fi + _LT_TAGVAR(archive_cmds_need_lc, $1)='no' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + ;; + + solaris*) + _LT_TAGVAR(no_undefined_flag, $1)=' -z defs' + if test "$GCC" = yes; then + wlarc='${wl}' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}-z ${wl}text ${wl}-h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $CC -shared ${wl}-z ${wl}text ${wl}-M ${wl}$lib.exp ${wl}-h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' + else + case `$CC -V 2>&1` in + *"Compilers 5.0"*) + wlarc='' + _LT_TAGVAR(archive_cmds, $1)='$LD -G${allow_undefined_flag} -h $soname -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $LD -G${allow_undefined_flag} -M $lib.exp -h $soname -o $lib $libobjs $deplibs $linker_flags~$RM $lib.exp' + ;; + *) + wlarc='${wl}' + _LT_TAGVAR(archive_cmds, $1)='$CC -G${allow_undefined_flag} -h $soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $CC -G${allow_undefined_flag} -M $lib.exp -h $soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' + ;; + esac + fi + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + case $host_os in + solaris2.[[0-5]] | solaris2.[[0-5]].*) ;; + *) + # The compiler driver will combine and reorder linker options, + # but understands `-z linker_flag'. GCC discards it without `$wl', + # but is careful enough not to reorder. + # Supported since Solaris 2.6 (maybe 2.5.1?) + if test "$GCC" = yes; then + _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}-z ${wl}allextract$convenience ${wl}-z ${wl}defaultextract' + else + _LT_TAGVAR(whole_archive_flag_spec, $1)='-z allextract$convenience -z defaultextract' + fi + ;; + esac + _LT_TAGVAR(link_all_deplibs, $1)=yes + ;; + + sunos4*) + if test "x$host_vendor" = xsequent; then + # Use $CC to link under sequent, because it throws in some extra .o + # files that make .init and .fini sections work. + _LT_TAGVAR(archive_cmds, $1)='$CC -G ${wl}-h $soname -o $lib $libobjs $deplibs $compiler_flags' + else + _LT_TAGVAR(archive_cmds, $1)='$LD -assert pure-text -Bstatic -o $lib $libobjs $deplibs $linker_flags' + fi + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_minus_L, $1)=yes + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + + sysv4) + case $host_vendor in + sni) + _LT_TAGVAR(archive_cmds, $1)='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(hardcode_direct, $1)=yes # is this really true??? + ;; + siemens) + ## LD is ld it makes a PLAMLIB + ## CC just makes a GrossModule. + _LT_TAGVAR(archive_cmds, $1)='$LD -G -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(reload_cmds, $1)='$CC -r -o $output$reload_objs' + _LT_TAGVAR(hardcode_direct, $1)=no + ;; + motorola) + _LT_TAGVAR(archive_cmds, $1)='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(hardcode_direct, $1)=no #Motorola manual says yes, but my tests say they lie + ;; + esac + runpath_var='LD_RUN_PATH' + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + + sysv4.3*) + _LT_TAGVAR(archive_cmds, $1)='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + _LT_TAGVAR(export_dynamic_flag_spec, $1)='-Bexport' + ;; + + sysv4*MP*) + if test -d /usr/nec; then + _LT_TAGVAR(archive_cmds, $1)='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + runpath_var=LD_RUN_PATH + hardcode_runpath_var=yes + _LT_TAGVAR(ld_shlibs, $1)=yes + fi + ;; + + sysv4*uw2* | sysv5OpenUNIX* | sysv5UnixWare7.[[01]].[[10]]* | unixware7* | sco3.2v5.0.[[024]]*) + _LT_TAGVAR(no_undefined_flag, $1)='${wl}-z,text' + _LT_TAGVAR(archive_cmds_need_lc, $1)=no + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + runpath_var='LD_RUN_PATH' + + if test "$GCC" = yes; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + else + _LT_TAGVAR(archive_cmds, $1)='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + fi + ;; + + sysv5* | sco3.2v5* | sco5v6*) + # Note: We can NOT use -z defs as we might desire, because we do not + # link with -lc, and that would cause any symbols used from libc to + # always be unresolved, which means just about no library would + # ever link correctly. If we're not using GNU ld we use -z text + # though, which does catch some bad symbols but isn't as heavy-handed + # as -z defs. + _LT_TAGVAR(no_undefined_flag, $1)='${wl}-z,text' + _LT_TAGVAR(allow_undefined_flag, $1)='${wl}-z,nodefs' + _LT_TAGVAR(archive_cmds_need_lc, $1)=no + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-R,$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=':' + _LT_TAGVAR(link_all_deplibs, $1)=yes + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-Bexport' + runpath_var='LD_RUN_PATH' + + if test "$GCC" = yes; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + else + _LT_TAGVAR(archive_cmds, $1)='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + fi + ;; + + uts4*) + _LT_TAGVAR(archive_cmds, $1)='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + + *) + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + esac + + if test x$host_vendor = xsni; then + case $host in + sysv4 | sysv4.2uw2* | sysv4.3* | sysv5*) + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-Blargedynsym' + ;; + esac + fi + fi +]) +AC_MSG_RESULT([$_LT_TAGVAR(ld_shlibs, $1)]) +test "$_LT_TAGVAR(ld_shlibs, $1)" = no && can_build_shared=no + +_LT_TAGVAR(with_gnu_ld, $1)=$with_gnu_ld + +_LT_DECL([], [libext], [0], [Old archive suffix (normally "a")])dnl +_LT_DECL([], [shrext_cmds], [1], [Shared library suffix (normally ".so")])dnl +_LT_DECL([], [extract_expsyms_cmds], [2], + [The commands to extract the exported symbol list from a shared archive]) + +# +# Do we need to explicitly link libc? +# +case "x$_LT_TAGVAR(archive_cmds_need_lc, $1)" in +x|xyes) + # Assume -lc should be added + _LT_TAGVAR(archive_cmds_need_lc, $1)=yes + + if test "$enable_shared" = yes && test "$GCC" = yes; then + case $_LT_TAGVAR(archive_cmds, $1) in + *'~'*) + # FIXME: we may have to deal with multi-command sequences. + ;; + '$CC '*) + # Test whether the compiler implicitly links with -lc since on some + # systems, -lgcc has to come before -lc. If gcc already passes -lc + # to ld, don't add -lc before -lgcc. + AC_MSG_CHECKING([whether -lc should be explicitly linked in]) + $RM conftest* + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + + if AC_TRY_EVAL(ac_compile) 2>conftest.err; then + soname=conftest + lib=conftest + libobjs=conftest.$ac_objext + deplibs= + wl=$_LT_TAGVAR(lt_prog_compiler_wl, $1) + pic_flag=$_LT_TAGVAR(lt_prog_compiler_pic, $1) + compiler_flags=-v + linker_flags=-v + verstring= + output_objdir=. + libname=conftest + lt_save_allow_undefined_flag=$_LT_TAGVAR(allow_undefined_flag, $1) + _LT_TAGVAR(allow_undefined_flag, $1)= + if AC_TRY_EVAL(_LT_TAGVAR(archive_cmds, $1) 2\>\&1 \| $GREP \" -lc \" \>/dev/null 2\>\&1) + then + _LT_TAGVAR(archive_cmds_need_lc, $1)=no + else + _LT_TAGVAR(archive_cmds_need_lc, $1)=yes + fi + _LT_TAGVAR(allow_undefined_flag, $1)=$lt_save_allow_undefined_flag + else + cat conftest.err 1>&5 + fi + $RM conftest* + AC_MSG_RESULT([$_LT_TAGVAR(archive_cmds_need_lc, $1)]) + ;; + esac + fi + ;; +esac + +_LT_TAGDECL([build_libtool_need_lc], [archive_cmds_need_lc], [0], + [Whether or not to add -lc for building shared libraries]) +_LT_TAGDECL([allow_libtool_libs_with_static_runtimes], + [enable_shared_with_static_runtimes], [0], + [Whether or not to disallow shared libs when runtime libs are static]) +_LT_TAGDECL([], [export_dynamic_flag_spec], [1], + [Compiler flag to allow reflexive dlopens]) +_LT_TAGDECL([], [whole_archive_flag_spec], [1], + [Compiler flag to generate shared objects directly from archives]) +_LT_TAGDECL([], [compiler_needs_object], [1], + [Whether the compiler copes with passing no objects directly]) +_LT_TAGDECL([], [old_archive_from_new_cmds], [2], + [Create an old-style archive from a shared archive]) +_LT_TAGDECL([], [old_archive_from_expsyms_cmds], [2], + [Create a temporary old-style archive to link instead of a shared archive]) +_LT_TAGDECL([], [archive_cmds], [2], [Commands used to build a shared archive]) +_LT_TAGDECL([], [archive_expsym_cmds], [2]) +_LT_TAGDECL([], [module_cmds], [2], + [Commands used to build a loadable module if different from building + a shared archive.]) +_LT_TAGDECL([], [module_expsym_cmds], [2]) +_LT_TAGDECL([], [with_gnu_ld], [1], + [Whether we are building with GNU ld or not]) +_LT_TAGDECL([], [allow_undefined_flag], [1], + [Flag that allows shared libraries with undefined symbols to be built]) +_LT_TAGDECL([], [no_undefined_flag], [1], + [Flag that enforces no undefined symbols]) +_LT_TAGDECL([], [hardcode_libdir_flag_spec], [1], + [Flag to hardcode $libdir into a binary during linking. + This must work even if $libdir does not exist]) +_LT_TAGDECL([], [hardcode_libdir_flag_spec_ld], [1], + [[If ld is used when linking, flag to hardcode $libdir into a binary + during linking. This must work even if $libdir does not exist]]) +_LT_TAGDECL([], [hardcode_libdir_separator], [1], + [Whether we need a single "-rpath" flag with a separated argument]) +_LT_TAGDECL([], [hardcode_direct], [0], + [Set to "yes" if using DIR/libNAME${shared_ext} during linking hardcodes + DIR into the resulting binary]) +_LT_TAGDECL([], [hardcode_direct_absolute], [0], + [Set to "yes" if using DIR/libNAME${shared_ext} during linking hardcodes + DIR into the resulting binary and the resulting library dependency is + "absolute", i.e impossible to change by setting ${shlibpath_var} if the + library is relocated]) +_LT_TAGDECL([], [hardcode_minus_L], [0], + [Set to "yes" if using the -LDIR flag during linking hardcodes DIR + into the resulting binary]) +_LT_TAGDECL([], [hardcode_shlibpath_var], [0], + [Set to "yes" if using SHLIBPATH_VAR=DIR during linking hardcodes DIR + into the resulting binary]) +_LT_TAGDECL([], [hardcode_automatic], [0], + [Set to "yes" if building a shared library automatically hardcodes DIR + into the library and all subsequent libraries and executables linked + against it]) +_LT_TAGDECL([], [inherit_rpath], [0], + [Set to yes if linker adds runtime paths of dependent libraries + to runtime path list]) +_LT_TAGDECL([], [link_all_deplibs], [0], + [Whether libtool must link a program against all its dependency libraries]) +_LT_TAGDECL([], [fix_srcfile_path], [1], + [Fix the shell variable $srcfile for the compiler]) +_LT_TAGDECL([], [always_export_symbols], [0], + [Set to "yes" if exported symbols are required]) +_LT_TAGDECL([], [export_symbols_cmds], [2], + [The commands to list exported symbols]) +_LT_TAGDECL([], [exclude_expsyms], [1], + [Symbols that should not be listed in the preloaded symbols]) +_LT_TAGDECL([], [include_expsyms], [1], + [Symbols that must always be exported]) +_LT_TAGDECL([], [prelink_cmds], [2], + [Commands necessary for linking programs (against libraries) with templates]) +_LT_TAGDECL([], [file_list_spec], [1], + [Specify filename containing input files]) +dnl FIXME: Not yet implemented +dnl _LT_TAGDECL([], [thread_safe_flag_spec], [1], +dnl [Compiler flag to generate thread safe objects]) +])# _LT_LINKER_SHLIBS + + +# _LT_LANG_C_CONFIG([TAG]) +# ------------------------ +# Ensure that the configuration variables for a C compiler are suitably +# defined. These variables are subsequently used by _LT_CONFIG to write +# the compiler configuration to `libtool'. +m4_defun([_LT_LANG_C_CONFIG], +[m4_require([_LT_DECL_EGREP])dnl +lt_save_CC="$CC" +AC_LANG_PUSH(C) + +# Source file extension for C test sources. +ac_ext=c + +# Object file extension for compiled C test sources. +objext=o +_LT_TAGVAR(objext, $1)=$objext + +# Code to be used in simple compile tests +lt_simple_compile_test_code="int some_variable = 0;" + +# Code to be used in simple link tests +lt_simple_link_test_code='int main(){return(0);}' + +_LT_TAG_COMPILER +# Save the default compiler, since it gets overwritten when the other +# tags are being tested, and _LT_TAGVAR(compiler, []) is a NOP. +compiler_DEFAULT=$CC + +# save warnings/boilerplate of simple test code +_LT_COMPILER_BOILERPLATE +_LT_LINKER_BOILERPLATE + +if test -n "$compiler"; then + _LT_COMPILER_NO_RTTI($1) + _LT_COMPILER_PIC($1) + _LT_COMPILER_C_O($1) + _LT_COMPILER_FILE_LOCKS($1) + _LT_LINKER_SHLIBS($1) + _LT_SYS_DYNAMIC_LINKER($1) + _LT_LINKER_HARDCODE_LIBPATH($1) + LT_SYS_DLOPEN_SELF + _LT_CMD_STRIPLIB + + # Report which library types will actually be built + AC_MSG_CHECKING([if libtool supports shared libraries]) + AC_MSG_RESULT([$can_build_shared]) + + AC_MSG_CHECKING([whether to build shared libraries]) + test "$can_build_shared" = "no" && enable_shared=no + + # On AIX, shared libraries and static libraries use the same namespace, and + # are all built from PIC. + case $host_os in + aix3*) + test "$enable_shared" = yes && enable_static=no + if test -n "$RANLIB"; then + archive_cmds="$archive_cmds~\$RANLIB \$lib" + postinstall_cmds='$RANLIB $lib' + fi + ;; + + aix[[4-9]]*) + if test "$host_cpu" != ia64 && test "$aix_use_runtimelinking" = no ; then + test "$enable_shared" = yes && enable_static=no + fi + ;; + esac + AC_MSG_RESULT([$enable_shared]) + + AC_MSG_CHECKING([whether to build static libraries]) + # Make sure either enable_shared or enable_static is yes. + test "$enable_shared" = yes || enable_static=yes + AC_MSG_RESULT([$enable_static]) + + _LT_CONFIG($1) +fi +AC_LANG_POP +CC="$lt_save_CC" +])# _LT_LANG_C_CONFIG + + +# _LT_PROG_CXX +# ------------ +# Since AC_PROG_CXX is broken, in that it returns g++ if there is no c++ +# compiler, we have our own version here. +m4_defun([_LT_PROG_CXX], +[ +pushdef([AC_MSG_ERROR], [_lt_caught_CXX_error=yes]) +AC_PROG_CXX +if test -n "$CXX" && ( test "X$CXX" != "Xno" && + ( (test "X$CXX" = "Xg++" && `g++ -v >/dev/null 2>&1` ) || + (test "X$CXX" != "Xg++"))) ; then + AC_PROG_CXXCPP +else + _lt_caught_CXX_error=yes +fi +popdef([AC_MSG_ERROR]) +])# _LT_PROG_CXX + +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([_LT_PROG_CXX], []) + + +# _LT_LANG_CXX_CONFIG([TAG]) +# -------------------------- +# Ensure that the configuration variables for a C++ compiler are suitably +# defined. These variables are subsequently used by _LT_CONFIG to write +# the compiler configuration to `libtool'. +m4_defun([_LT_LANG_CXX_CONFIG], +[AC_REQUIRE([_LT_PROG_CXX])dnl +m4_require([_LT_FILEUTILS_DEFAULTS])dnl +m4_require([_LT_DECL_EGREP])dnl + +AC_LANG_PUSH(C++) +_LT_TAGVAR(archive_cmds_need_lc, $1)=no +_LT_TAGVAR(allow_undefined_flag, $1)= +_LT_TAGVAR(always_export_symbols, $1)=no +_LT_TAGVAR(archive_expsym_cmds, $1)= +_LT_TAGVAR(compiler_needs_object, $1)=no +_LT_TAGVAR(export_dynamic_flag_spec, $1)= +_LT_TAGVAR(hardcode_direct, $1)=no +_LT_TAGVAR(hardcode_direct_absolute, $1)=no +_LT_TAGVAR(hardcode_libdir_flag_spec, $1)= +_LT_TAGVAR(hardcode_libdir_flag_spec_ld, $1)= +_LT_TAGVAR(hardcode_libdir_separator, $1)= +_LT_TAGVAR(hardcode_minus_L, $1)=no +_LT_TAGVAR(hardcode_shlibpath_var, $1)=unsupported +_LT_TAGVAR(hardcode_automatic, $1)=no +_LT_TAGVAR(inherit_rpath, $1)=no +_LT_TAGVAR(module_cmds, $1)= +_LT_TAGVAR(module_expsym_cmds, $1)= +_LT_TAGVAR(link_all_deplibs, $1)=unknown +_LT_TAGVAR(old_archive_cmds, $1)=$old_archive_cmds +_LT_TAGVAR(no_undefined_flag, $1)= +_LT_TAGVAR(whole_archive_flag_spec, $1)= +_LT_TAGVAR(enable_shared_with_static_runtimes, $1)=no + +# Source file extension for C++ test sources. +ac_ext=cpp + +# Object file extension for compiled C++ test sources. +objext=o +_LT_TAGVAR(objext, $1)=$objext + +# No sense in running all these tests if we already determined that +# the CXX compiler isn't working. Some variables (like enable_shared) +# are currently assumed to apply to all compilers on this platform, +# and will be corrupted by setting them based on a non-working compiler. +if test "$_lt_caught_CXX_error" != yes; then + # Code to be used in simple compile tests + lt_simple_compile_test_code="int some_variable = 0;" + + # Code to be used in simple link tests + lt_simple_link_test_code='int main(int, char *[[]]) { return(0); }' + + # ltmain only uses $CC for tagged configurations so make sure $CC is set. + _LT_TAG_COMPILER + + # save warnings/boilerplate of simple test code + _LT_COMPILER_BOILERPLATE + _LT_LINKER_BOILERPLATE + + # Allow CC to be a program name with arguments. + lt_save_CC=$CC + lt_save_LD=$LD + lt_save_GCC=$GCC + GCC=$GXX + lt_save_with_gnu_ld=$with_gnu_ld + lt_save_path_LD=$lt_cv_path_LD + if test -n "${lt_cv_prog_gnu_ldcxx+set}"; then + lt_cv_prog_gnu_ld=$lt_cv_prog_gnu_ldcxx + else + $as_unset lt_cv_prog_gnu_ld + fi + if test -n "${lt_cv_path_LDCXX+set}"; then + lt_cv_path_LD=$lt_cv_path_LDCXX + else + $as_unset lt_cv_path_LD + fi + test -z "${LDCXX+set}" || LD=$LDCXX + CC=${CXX-"c++"} + compiler=$CC + _LT_TAGVAR(compiler, $1)=$CC + _LT_CC_BASENAME([$compiler]) + + if test -n "$compiler"; then + # We don't want -fno-exception when compiling C++ code, so set the + # no_builtin_flag separately + if test "$GXX" = yes; then + _LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)=' -fno-builtin' + else + _LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)= + fi + + if test "$GXX" = yes; then + # Set up default GNU C++ configuration + + LT_PATH_LD + + # Check if GNU C++ uses GNU ld as the underlying linker, since the + # archiving commands below assume that GNU ld is being used. + if test "$with_gnu_ld" = yes; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' + + # If archive_cmds runs LD, not CC, wlarc should be empty + # XXX I think wlarc can be eliminated in ltcf-cxx, but I need to + # investigate it a little bit more. (MM) + wlarc='${wl}' + + # ancient GNU ld didn't support --whole-archive et. al. + if eval "`$CC -print-prog-name=ld` --help 2>&1" | + $GREP 'no-whole-archive' > /dev/null; then + _LT_TAGVAR(whole_archive_flag_spec, $1)="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + else + _LT_TAGVAR(whole_archive_flag_spec, $1)= + fi + else + with_gnu_ld=no + wlarc= + + # A generic and very simple default shared library creation + # command for GNU C++ for the case where it uses the native + # linker, instead of GNU ld. If possible, this setting should + # overridden to take advantage of the native linker features on + # the platform it is being used on. + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $lib' + fi + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + output_verbose_link_cmd='$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "\-L"' + + else + GXX=no + with_gnu_ld=no + wlarc= + fi + + # PORTME: fill in a description of your system's C++ link characteristics + AC_MSG_CHECKING([whether the $compiler linker ($LD) supports shared libraries]) + _LT_TAGVAR(ld_shlibs, $1)=yes + case $host_os in + aix3*) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + aix[[4-9]]*) + if test "$host_cpu" = ia64; then + # On IA64, the linker does run time linking by default, so we don't + # have to do anything special. + aix_use_runtimelinking=no + exp_sym_flag='-Bexport' + no_entry_flag="" + else + aix_use_runtimelinking=no + + # Test if we are trying to use run time linking or normal + # AIX style linking. If -brtl is somewhere in LDFLAGS, we + # need to do runtime linking. + case $host_os in aix4.[[23]]|aix4.[[23]].*|aix[[5-9]]*) + for ld_flag in $LDFLAGS; do + case $ld_flag in + *-brtl*) + aix_use_runtimelinking=yes + break + ;; + esac + done + ;; + esac + + exp_sym_flag='-bexport' + no_entry_flag='-bnoentry' + fi + + # When large executables or shared objects are built, AIX ld can + # have problems creating the table of contents. If linking a library + # or program results in "error TOC overflow" add -mminimal-toc to + # CXXFLAGS/CFLAGS for g++/gcc. In the cases where that is not + # enough to fix the problem, add -Wl,-bbigtoc to LDFLAGS. + + _LT_TAGVAR(archive_cmds, $1)='' + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_direct_absolute, $1)=yes + _LT_TAGVAR(hardcode_libdir_separator, $1)=':' + _LT_TAGVAR(link_all_deplibs, $1)=yes + _LT_TAGVAR(file_list_spec, $1)='${wl}-f,' + + if test "$GXX" = yes; then + case $host_os in aix4.[[012]]|aix4.[[012]].*) + # We only want to do this on AIX 4.2 and lower, the check + # below for broken collect2 doesn't work under 4.3+ + collect2name=`${CC} -print-prog-name=collect2` + if test -f "$collect2name" && + strings "$collect2name" | $GREP resolve_lib_name >/dev/null + then + # We have reworked collect2 + : + else + # We have old collect2 + _LT_TAGVAR(hardcode_direct, $1)=unsupported + # It fails to find uninstalled libraries when the uninstalled + # path is not listed in the libpath. Setting hardcode_minus_L + # to unsupported forces relinking + _LT_TAGVAR(hardcode_minus_L, $1)=yes + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)= + fi + esac + shared_flag='-shared' + if test "$aix_use_runtimelinking" = yes; then + shared_flag="$shared_flag "'${wl}-G' + fi + else + # not using gcc + if test "$host_cpu" = ia64; then + # VisualAge C++, Version 5.5 for AIX 5L for IA-64, Beta 3 Release + # chokes on -Wl,-G. The following line is correct: + shared_flag='-G' + else + if test "$aix_use_runtimelinking" = yes; then + shared_flag='${wl}-G' + else + shared_flag='${wl}-bM:SRE' + fi + fi + fi + + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-bexpall' + # It seems that -bexpall does not export symbols beginning with + # underscore (_), so it is better to generate a list of symbols to + # export. + _LT_TAGVAR(always_export_symbols, $1)=yes + if test "$aix_use_runtimelinking" = yes; then + # Warning - without using the other runtime loading flags (-brtl), + # -berok will link without error, but may produce a broken library. + _LT_TAGVAR(allow_undefined_flag, $1)='-berok' + # Determine the default libpath from the value encoded in an empty + # executable. + _LT_SYS_MODULE_PATH_AIX + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-blibpath:$libdir:'"$aix_libpath" + + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags `if test "x${allow_undefined_flag}" != "x"; then $ECHO "X${wl}${allow_undefined_flag}" | $Xsed; else :; fi` '"\${wl}$exp_sym_flag:\$export_symbols $shared_flag" + else + if test "$host_cpu" = ia64; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-R $libdir:/usr/lib:/lib' + _LT_TAGVAR(allow_undefined_flag, $1)="-z nodefs" + _LT_TAGVAR(archive_expsym_cmds, $1)="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags ${wl}${allow_undefined_flag} '"\${wl}$exp_sym_flag:\$export_symbols" + else + # Determine the default libpath from the value encoded in an + # empty executable. + _LT_SYS_MODULE_PATH_AIX + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-blibpath:$libdir:'"$aix_libpath" + # Warning - without using the other run time loading flags, + # -berok will link without error, but may produce a broken library. + _LT_TAGVAR(no_undefined_flag, $1)=' ${wl}-bernotok' + _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-berok' + # Exported symbols can be pulled into shared objects from archives + _LT_TAGVAR(whole_archive_flag_spec, $1)='$convenience' + _LT_TAGVAR(archive_cmds_need_lc, $1)=yes + # This is similar to how AIX traditionally builds its shared + # libraries. + _LT_TAGVAR(archive_expsym_cmds, $1)="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs ${wl}-bnoentry $compiler_flags ${wl}-bE:$export_symbols${allow_undefined_flag}~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$soname' + fi + fi + ;; + + beos*) + if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then + _LT_TAGVAR(allow_undefined_flag, $1)=unsupported + # Joseph Beckenbach says some releases of gcc + # support --undefined. This deserves some investigation. FIXME + _LT_TAGVAR(archive_cmds, $1)='$CC -nostart $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + + chorus*) + case $cc_basename in + *) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + esac + ;; + + cygwin* | mingw* | pw32* | cegcc*) + # _LT_TAGVAR(hardcode_libdir_flag_spec, $1) is actually meaningless, + # as there is no search path for DLLs. + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(allow_undefined_flag, $1)=unsupported + _LT_TAGVAR(always_export_symbols, $1)=no + _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=yes + + if $LD --help 2>&1 | $GREP 'auto-import' > /dev/null; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + # If the export-symbols file already is a .def file (1st line + # is EXPORTS), use it as is; otherwise, prepend... + _LT_TAGVAR(archive_expsym_cmds, $1)='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then + cp $export_symbols $output_objdir/$soname.def; + else + echo EXPORTS > $output_objdir/$soname.def; + cat $export_symbols >> $output_objdir/$soname.def; + fi~ + $CC -shared -nostdlib $output_objdir/$soname.def $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + darwin* | rhapsody*) + _LT_DARWIN_LINKER_FEATURES($1) + ;; + + dgux*) + case $cc_basename in + ec++*) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + ghcx*) + # Green Hills C++ Compiler + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + *) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + esac + ;; + + freebsd[[12]]*) + # C++ shared libraries reported to be fairly broken before + # switch to ELF + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + + freebsd-elf*) + _LT_TAGVAR(archive_cmds_need_lc, $1)=no + ;; + + freebsd* | dragonfly*) + # FreeBSD 3 and later use GNU C++ and GNU ld with standard ELF + # conventions + _LT_TAGVAR(ld_shlibs, $1)=yes + ;; + + gnu*) + ;; + + hpux9*) + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}+b ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_minus_L, $1)=yes # Not in the search PATH, + # but as the default + # location of the library. + + case $cc_basename in + CC*) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + aCC*) + _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$CC -b ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + # + # There doesn't appear to be a way to prevent this compiler from + # explicitly linking system object files so we need to strip them + # from the output so that they don't get included in the library + # dependencies. + output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $EGREP "\-L"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; $ECHO "X$list" | $Xsed' + ;; + *) + if test "$GXX" = yes; then + _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$CC -shared -nostdlib -fPIC ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + else + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + esac + ;; + + hpux10*|hpux11*) + if test $with_gnu_ld = no; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}+b ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + + case $host_cpu in + hppa*64*|ia64*) + ;; + *) + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + ;; + esac + fi + case $host_cpu in + hppa*64*|ia64*) + _LT_TAGVAR(hardcode_direct, $1)=no + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + ;; + *) + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_direct_absolute, $1)=yes + _LT_TAGVAR(hardcode_minus_L, $1)=yes # Not in the search PATH, + # but as the default + # location of the library. + ;; + esac + + case $cc_basename in + CC*) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + aCC*) + case $host_cpu in + hppa*64*) + _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + ia64*) + _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + *) + _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + esac + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + # + # There doesn't appear to be a way to prevent this compiler from + # explicitly linking system object files so we need to strip them + # from the output so that they don't get included in the library + # dependencies. + output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $GREP "\-L"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; $ECHO "X$list" | $Xsed' + ;; + *) + if test "$GXX" = yes; then + if test $with_gnu_ld = no; then + case $host_cpu in + hppa*64*) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib -fPIC ${wl}+h ${wl}$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + ia64*) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib -fPIC ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + *) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib -fPIC ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + esac + fi + else + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + esac + ;; + + interix[[3-9]]*) + _LT_TAGVAR(hardcode_direct, $1)=no + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + # Hack: On Interix 3.x, we cannot compile PIC because of a broken gcc. + # Instead, shared libraries are loaded at an image base (0x10000000 by + # default) and relocated if they conflict, which is a slow very memory + # consuming and fragmenting process. To avoid this, we pick a random, + # 256 KiB-aligned image base between 0x50000000 and 0x6FFC0000 at link + # time. Moving up from 0x10000000 also allows more sbrk(2) space. + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='sed "s,^,_," $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--retain-symbols-file,$output_objdir/$soname.expsym ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + ;; + irix5* | irix6*) + case $cc_basename in + CC*) + # SGI C++ + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -all -multigot $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + + # Archives containing C++ object files must be created using + # "CC -ar", where "CC" is the IRIX C++ compiler. This is + # necessary to make sure instantiated templates are included + # in the archive. + _LT_TAGVAR(old_archive_cmds, $1)='$CC -ar -WR,-u -o $oldlib $oldobjs' + ;; + *) + if test "$GXX" = yes; then + if test "$with_gnu_ld" = no; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + else + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` -o $lib' + fi + fi + _LT_TAGVAR(link_all_deplibs, $1)=yes + ;; + esac + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + _LT_TAGVAR(inherit_rpath, $1)=yes + ;; + + linux* | k*bsd*-gnu | kopensolaris*-gnu) + case $cc_basename in + KCC*) + # Kuck and Associates, Inc. (KAI) C++ Compiler + + # KCC will only create a shared library if the output file + # ends with ".so" (or ".sl" for HP-UX), so rename the library + # to its proper name (with version) after linking. + _LT_TAGVAR(archive_cmds, $1)='tempext=`echo $shared_ext | $SED -e '\''s/\([[^()0-9A-Za-z{}]]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='tempext=`echo $shared_ext | $SED -e '\''s/\([[^()0-9A-Za-z{}]]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib ${wl}-retain-symbols-file,$export_symbols; mv \$templib $lib' + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + # + # There doesn't appear to be a way to prevent this compiler from + # explicitly linking system object files so we need to strip them + # from the output so that they don't get included in the library + # dependencies. + output_verbose_link_cmd='templist=`$CC $CFLAGS -v conftest.$objext -o libconftest$shared_ext 2>&1 | $GREP "ld"`; rm -f libconftest$shared_ext; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; $ECHO "X$list" | $Xsed' + + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' + + # Archives containing C++ object files must be created using + # "CC -Bstatic", where "CC" is the KAI C++ compiler. + _LT_TAGVAR(old_archive_cmds, $1)='$CC -Bstatic -o $oldlib $oldobjs' + ;; + icpc* | ecpc* ) + # Intel C++ + with_gnu_ld=yes + # version 8.0 and above of icpc choke on multiply defined symbols + # if we add $predep_objects and $postdep_objects, however 7.1 and + # earlier do not add the objects themselves. + case `$CC -V 2>&1` in + *"Version 7."*) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + ;; + *) # Version 8.0 or newer + tmp_idyn= + case $host_cpu in + ia64*) tmp_idyn=' -i_dynamic';; + esac + _LT_TAGVAR(archive_cmds, $1)='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + ;; + esac + _LT_TAGVAR(archive_cmds_need_lc, $1)=no + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' + _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive$convenience ${wl}--no-whole-archive' + ;; + pgCC* | pgcpp*) + # Portland Group C++ compiler + case `$CC -V` in + *pgCC\ [[1-5]]* | *pgcpp\ [[1-5]]*) + _LT_TAGVAR(prelink_cmds, $1)='tpldir=Template.dir~ + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $objs $libobjs $compile_deplibs~ + compile_command="$compile_command `find $tpldir -name \*.o | $NL2SP`"' + _LT_TAGVAR(old_archive_cmds, $1)='tpldir=Template.dir~ + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $oldobjs$old_deplibs~ + $AR $AR_FLAGS $oldlib$oldobjs$old_deplibs `find $tpldir -name \*.o | $NL2SP`~ + $RANLIB $oldlib' + _LT_TAGVAR(archive_cmds, $1)='tpldir=Template.dir~ + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ + $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | $NL2SP` $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='tpldir=Template.dir~ + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ + $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | $NL2SP` $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname ${wl}-retain-symbols-file ${wl}$export_symbols -o $lib' + ;; + *) # Version 6 will use weak symbols + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname ${wl}-retain-symbols-file ${wl}$export_symbols -o $lib' + ;; + esac + + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}--rpath ${wl}$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' + _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; $ECHO \"$new_convenience\"` ${wl}--no-whole-archive' + ;; + cxx*) + # Compaq C++ + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib ${wl}-retain-symbols-file $wl$export_symbols' + + runpath_var=LD_RUN_PATH + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-rpath $libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + # + # There doesn't appear to be a way to prevent this compiler from + # explicitly linking system object files so we need to strip them + # from the output so that they don't get included in the library + # dependencies. + output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld"`; templist=`$ECHO "X$templist" | $Xsed -e "s/\(^.*ld.*\)\( .*ld .*$\)/\1/"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; $ECHO "X$list" | $Xsed' + ;; + xl*) + # IBM XL 8.0 on PPC, with GNU ld + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' + _LT_TAGVAR(archive_cmds, $1)='$CC -qmkshrobj $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + if test "x$supports_anon_versioning" = xyes; then + _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $output_objdir/$libname.ver~ + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $CC -qmkshrobj $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-version-script ${wl}$output_objdir/$libname.ver -o $lib' + fi + ;; + *) + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) + # Sun C++ 5.9 + _LT_TAGVAR(no_undefined_flag, $1)=' -zdefs' + _LT_TAGVAR(archive_cmds, $1)='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-retain-symbols-file ${wl}$export_symbols' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' + _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; $ECHO \"$new_convenience\"` ${wl}--no-whole-archive' + _LT_TAGVAR(compiler_needs_object, $1)=yes + + # Not sure whether something based on + # $CC $CFLAGS -v conftest.$objext -o libconftest$shared_ext 2>&1 + # would be better. + output_verbose_link_cmd='echo' + + # Archives containing C++ object files must be created using + # "CC -xar", where "CC" is the Sun C++ compiler. This is + # necessary to make sure instantiated templates are included + # in the archive. + _LT_TAGVAR(old_archive_cmds, $1)='$CC -xar -o $oldlib $oldobjs' + ;; + esac + ;; + esac + ;; + + lynxos*) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + + m88k*) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + + mvs*) + case $cc_basename in + cxx*) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + *) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + esac + ;; + + netbsd*) + if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then + _LT_TAGVAR(archive_cmds, $1)='$LD -Bshareable -o $lib $predep_objects $libobjs $deplibs $postdep_objects $linker_flags' + wlarc= + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + fi + # Workaround some broken pre-1.5 toolchains + output_verbose_link_cmd='$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP conftest.$objext | $SED -e "s:-lgcc -lc -lgcc::"' + ;; + + *nto* | *qnx*) + _LT_TAGVAR(ld_shlibs, $1)=yes + ;; + + openbsd2*) + # C++ shared libraries are fairly broken + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + + openbsd*) + if test -f /usr/libexec/ld.so; then + _LT_TAGVAR(hardcode_direct, $1)=yes + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + _LT_TAGVAR(hardcode_direct_absolute, $1)=yes + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $lib' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' + if test -z "`echo __ELF__ | $CC -E - | grep __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-retain-symbols-file,$export_symbols -o $lib' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + _LT_TAGVAR(whole_archive_flag_spec, $1)="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + fi + output_verbose_link_cmd=echo + else + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + + osf3* | osf4* | osf5*) + case $cc_basename in + KCC*) + # Kuck and Associates, Inc. (KAI) C++ Compiler + + # KCC will only create a shared library if the output file + # ends with ".so" (or ".sl" for HP-UX), so rename the library + # to its proper name (with version) after linking. + _LT_TAGVAR(archive_cmds, $1)='tempext=`echo $shared_ext | $SED -e '\''s/\([[^()0-9A-Za-z{}]]\)/\\\\\1/g'\''`; templib=`echo "$lib" | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' + + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + + # Archives containing C++ object files must be created using + # the KAI C++ compiler. + case $host in + osf3*) _LT_TAGVAR(old_archive_cmds, $1)='$CC -Bstatic -o $oldlib $oldobjs' ;; + *) _LT_TAGVAR(old_archive_cmds, $1)='$CC -o $oldlib $oldobjs' ;; + esac + ;; + RCC*) + # Rational C++ 2.4.1 + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + cxx*) + case $host in + osf3*) + _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-expect_unresolved ${wl}\*' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $soname `test -n "$verstring" && $ECHO "X${wl}-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + ;; + *) + _LT_TAGVAR(allow_undefined_flag, $1)=' -expect_unresolved \*' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='for i in `cat $export_symbols`; do printf "%s %s\\n" -exported_symbol "\$i" >> $lib.exp; done~ + echo "-hidden">> $lib.exp~ + $CC -shared$allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname ${wl}-input ${wl}$lib.exp `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib~ + $RM $lib.exp' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-rpath $libdir' + ;; + esac + + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + # + # There doesn't appear to be a way to prevent this compiler from + # explicitly linking system object files so we need to strip them + # from the output so that they don't get included in the library + # dependencies. + output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld" | $GREP -v "ld:"`; templist=`$ECHO "X$templist" | $Xsed -e "s/\(^.*ld.*\)\( .*ld.*$\)/\1/"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; $ECHO "X$list" | $Xsed' + ;; + *) + if test "$GXX" = yes && test "$with_gnu_ld" = no; then + _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-expect_unresolved ${wl}\*' + case $host in + osf3*) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib ${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + ;; + *) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib ${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-msym ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + ;; + esac + + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=: + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + output_verbose_link_cmd='$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "\-L"' + + else + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + fi + ;; + esac + ;; + + psos*) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + + sunos4*) + case $cc_basename in + CC*) + # Sun C++ 4.x + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + lcc*) + # Lucid + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + *) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + esac + ;; + + solaris*) + case $cc_basename in + CC*) + # Sun C++ 4.2, 5.x and Centerline C++ + _LT_TAGVAR(archive_cmds_need_lc,$1)=yes + _LT_TAGVAR(no_undefined_flag, $1)=' -zdefs' + _LT_TAGVAR(archive_cmds, $1)='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $CC -G${allow_undefined_flag} ${wl}-M ${wl}$lib.exp -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + case $host_os in + solaris2.[[0-5]] | solaris2.[[0-5]].*) ;; + *) + # The compiler driver will combine and reorder linker options, + # but understands `-z linker_flag'. + # Supported since Solaris 2.6 (maybe 2.5.1?) + _LT_TAGVAR(whole_archive_flag_spec, $1)='-z allextract$convenience -z defaultextract' + ;; + esac + _LT_TAGVAR(link_all_deplibs, $1)=yes + + output_verbose_link_cmd='echo' + + # Archives containing C++ object files must be created using + # "CC -xar", where "CC" is the Sun C++ compiler. This is + # necessary to make sure instantiated templates are included + # in the archive. + _LT_TAGVAR(old_archive_cmds, $1)='$CC -xar -o $oldlib $oldobjs' + ;; + gcx*) + # Green Hills C++ Compiler + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + + # The C++ compiler must be used to create the archive. + _LT_TAGVAR(old_archive_cmds, $1)='$CC $LDFLAGS -archive -o $oldlib $oldobjs' + ;; + *) + # GNU C++ compiler with Solaris linker + if test "$GXX" = yes && test "$with_gnu_ld" = no; then + _LT_TAGVAR(no_undefined_flag, $1)=' ${wl}-z ${wl}defs' + if $CC --version | $GREP -v '^2\.7' > /dev/null; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $LDFLAGS $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $CC -shared -nostdlib ${wl}-M $wl$lib.exp -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + output_verbose_link_cmd='$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "\-L"' + else + # g++ 2.7 appears to require `-G' NOT `-shared' on this + # platform. + _LT_TAGVAR(archive_cmds, $1)='$CC -G -nostdlib $LDFLAGS $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $CC -G -nostdlib ${wl}-M $wl$lib.exp -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + output_verbose_link_cmd='$CC -G $CFLAGS -v conftest.$objext 2>&1 | $GREP "\-L"' + fi + + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-R $wl$libdir' + case $host_os in + solaris2.[[0-5]] | solaris2.[[0-5]].*) ;; + *) + _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}-z ${wl}allextract$convenience ${wl}-z ${wl}defaultextract' + ;; + esac + fi + ;; + esac + ;; + + sysv4*uw2* | sysv5OpenUNIX* | sysv5UnixWare7.[[01]].[[10]]* | unixware7* | sco3.2v5.0.[[024]]*) + _LT_TAGVAR(no_undefined_flag, $1)='${wl}-z,text' + _LT_TAGVAR(archive_cmds_need_lc, $1)=no + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + runpath_var='LD_RUN_PATH' + + case $cc_basename in + CC*) + _LT_TAGVAR(archive_cmds, $1)='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + *) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + esac + ;; + + sysv5* | sco3.2v5* | sco5v6*) + # Note: We can NOT use -z defs as we might desire, because we do not + # link with -lc, and that would cause any symbols used from libc to + # always be unresolved, which means just about no library would + # ever link correctly. If we're not using GNU ld we use -z text + # though, which does catch some bad symbols but isn't as heavy-handed + # as -z defs. + _LT_TAGVAR(no_undefined_flag, $1)='${wl}-z,text' + _LT_TAGVAR(allow_undefined_flag, $1)='${wl}-z,nodefs' + _LT_TAGVAR(archive_cmds_need_lc, $1)=no + _LT_TAGVAR(hardcode_shlibpath_var, $1)=no + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-R,$libdir' + _LT_TAGVAR(hardcode_libdir_separator, $1)=':' + _LT_TAGVAR(link_all_deplibs, $1)=yes + _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-Bexport' + runpath_var='LD_RUN_PATH' + + case $cc_basename in + CC*) + _LT_TAGVAR(archive_cmds, $1)='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + *) + _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + esac + ;; + + tandem*) + case $cc_basename in + NCC*) + # NonStop-UX NCC 3.20 + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + *) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + esac + ;; + + vxworks*) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + + *) + # FIXME: insert proper C++ library support + _LT_TAGVAR(ld_shlibs, $1)=no + ;; + esac + + AC_MSG_RESULT([$_LT_TAGVAR(ld_shlibs, $1)]) + test "$_LT_TAGVAR(ld_shlibs, $1)" = no && can_build_shared=no + + _LT_TAGVAR(GCC, $1)="$GXX" + _LT_TAGVAR(LD, $1)="$LD" + + ## CAVEAT EMPTOR: + ## There is no encapsulation within the following macros, do not change + ## the running order or otherwise move them around unless you know exactly + ## what you are doing... + _LT_SYS_HIDDEN_LIBDEPS($1) + _LT_COMPILER_PIC($1) + _LT_COMPILER_C_O($1) + _LT_COMPILER_FILE_LOCKS($1) + _LT_LINKER_SHLIBS($1) + _LT_SYS_DYNAMIC_LINKER($1) + _LT_LINKER_HARDCODE_LIBPATH($1) + + _LT_CONFIG($1) + fi # test -n "$compiler" + + CC=$lt_save_CC + LDCXX=$LD + LD=$lt_save_LD + GCC=$lt_save_GCC + with_gnu_ld=$lt_save_with_gnu_ld + lt_cv_path_LDCXX=$lt_cv_path_LD + lt_cv_path_LD=$lt_save_path_LD + lt_cv_prog_gnu_ldcxx=$lt_cv_prog_gnu_ld + lt_cv_prog_gnu_ld=$lt_save_with_gnu_ld +fi # test "$_lt_caught_CXX_error" != yes + +AC_LANG_POP +])# _LT_LANG_CXX_CONFIG + + +# _LT_SYS_HIDDEN_LIBDEPS([TAGNAME]) +# --------------------------------- +# Figure out "hidden" library dependencies from verbose +# compiler output when linking a shared library. +# Parse the compiler output and extract the necessary +# objects, libraries and library flags. +m4_defun([_LT_SYS_HIDDEN_LIBDEPS], +[m4_require([_LT_FILEUTILS_DEFAULTS])dnl +# Dependencies to place before and after the object being linked: +_LT_TAGVAR(predep_objects, $1)= +_LT_TAGVAR(postdep_objects, $1)= +_LT_TAGVAR(predeps, $1)= +_LT_TAGVAR(postdeps, $1)= +_LT_TAGVAR(compiler_lib_search_path, $1)= + +dnl we can't use the lt_simple_compile_test_code here, +dnl because it contains code intended for an executable, +dnl not a library. It's possible we should let each +dnl tag define a new lt_????_link_test_code variable, +dnl but it's only used here... +m4_if([$1], [], [cat > conftest.$ac_ext <<_LT_EOF +int a; +void foo (void) { a = 0; } +_LT_EOF +], [$1], [CXX], [cat > conftest.$ac_ext <<_LT_EOF +class Foo +{ +public: + Foo (void) { a = 0; } +private: + int a; +}; +_LT_EOF +], [$1], [F77], [cat > conftest.$ac_ext <<_LT_EOF + subroutine foo + implicit none + integer*4 a + a=0 + return + end +_LT_EOF +], [$1], [FC], [cat > conftest.$ac_ext <<_LT_EOF + subroutine foo + implicit none + integer a + a=0 + return + end +_LT_EOF +], [$1], [GCJ], [cat > conftest.$ac_ext <<_LT_EOF +public class foo { + private int a; + public void bar (void) { + a = 0; + } +}; +_LT_EOF +]) +dnl Parse the compiler output and extract the necessary +dnl objects, libraries and library flags. +if AC_TRY_EVAL(ac_compile); then + # Parse the compiler output and extract the necessary + # objects, libraries and library flags. + + # Sentinel used to keep track of whether or not we are before + # the conftest object file. + pre_test_object_deps_done=no + + for p in `eval "$output_verbose_link_cmd"`; do + case $p in + + -L* | -R* | -l*) + # Some compilers place space between "-{L,R}" and the path. + # Remove the space. + if test $p = "-L" || + test $p = "-R"; then + prev=$p + continue + else + prev= + fi + + if test "$pre_test_object_deps_done" = no; then + case $p in + -L* | -R*) + # Internal compiler library paths should come after those + # provided the user. The postdeps already come after the + # user supplied libs so there is no need to process them. + if test -z "$_LT_TAGVAR(compiler_lib_search_path, $1)"; then + _LT_TAGVAR(compiler_lib_search_path, $1)="${prev}${p}" + else + _LT_TAGVAR(compiler_lib_search_path, $1)="${_LT_TAGVAR(compiler_lib_search_path, $1)} ${prev}${p}" + fi + ;; + # The "-l" case would never come before the object being + # linked, so don't bother handling this case. + esac + else + if test -z "$_LT_TAGVAR(postdeps, $1)"; then + _LT_TAGVAR(postdeps, $1)="${prev}${p}" + else + _LT_TAGVAR(postdeps, $1)="${_LT_TAGVAR(postdeps, $1)} ${prev}${p}" + fi + fi + ;; + + *.$objext) + # This assumes that the test object file only shows up + # once in the compiler output. + if test "$p" = "conftest.$objext"; then + pre_test_object_deps_done=yes + continue + fi + + if test "$pre_test_object_deps_done" = no; then + if test -z "$_LT_TAGVAR(predep_objects, $1)"; then + _LT_TAGVAR(predep_objects, $1)="$p" + else + _LT_TAGVAR(predep_objects, $1)="$_LT_TAGVAR(predep_objects, $1) $p" + fi + else + if test -z "$_LT_TAGVAR(postdep_objects, $1)"; then + _LT_TAGVAR(postdep_objects, $1)="$p" + else + _LT_TAGVAR(postdep_objects, $1)="$_LT_TAGVAR(postdep_objects, $1) $p" + fi + fi + ;; + + *) ;; # Ignore the rest. + + esac + done + + # Clean up. + rm -f a.out a.exe +else + echo "libtool.m4: error: problem compiling $1 test program" +fi + +$RM -f confest.$objext + +# PORTME: override above test on systems where it is broken +m4_if([$1], [CXX], +[case $host_os in +interix[[3-9]]*) + # Interix 3.5 installs completely hosed .la files for C++, so rather than + # hack all around it, let's just trust "g++" to DTRT. + _LT_TAGVAR(predep_objects,$1)= + _LT_TAGVAR(postdep_objects,$1)= + _LT_TAGVAR(postdeps,$1)= + ;; + +linux*) + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) + # Sun C++ 5.9 + + # The more standards-conforming stlport4 library is + # incompatible with the Cstd library. Avoid specifying + # it if it's in CXXFLAGS. Ignore libCrun as + # -library=stlport4 depends on it. + case " $CXX $CXXFLAGS " in + *" -library=stlport4 "*) + solaris_use_stlport4=yes + ;; + esac + + if test "$solaris_use_stlport4" != yes; then + _LT_TAGVAR(postdeps,$1)='-library=Cstd -library=Crun' + fi + ;; + esac + ;; + +solaris*) + case $cc_basename in + CC*) + # The more standards-conforming stlport4 library is + # incompatible with the Cstd library. Avoid specifying + # it if it's in CXXFLAGS. Ignore libCrun as + # -library=stlport4 depends on it. + case " $CXX $CXXFLAGS " in + *" -library=stlport4 "*) + solaris_use_stlport4=yes + ;; + esac + + # Adding this requires a known-good setup of shared libraries for + # Sun compiler versions before 5.6, else PIC objects from an old + # archive will be linked into the output, leading to subtle bugs. + if test "$solaris_use_stlport4" != yes; then + _LT_TAGVAR(postdeps,$1)='-library=Cstd -library=Crun' + fi + ;; + esac + ;; +esac +]) + +case " $_LT_TAGVAR(postdeps, $1) " in +*" -lc "*) _LT_TAGVAR(archive_cmds_need_lc, $1)=no ;; +esac + _LT_TAGVAR(compiler_lib_search_dirs, $1)= +if test -n "${_LT_TAGVAR(compiler_lib_search_path, $1)}"; then + _LT_TAGVAR(compiler_lib_search_dirs, $1)=`echo " ${_LT_TAGVAR(compiler_lib_search_path, $1)}" | ${SED} -e 's! -L! !g' -e 's!^ !!'` +fi +_LT_TAGDECL([], [compiler_lib_search_dirs], [1], + [The directories searched by this compiler when creating a shared library]) +_LT_TAGDECL([], [predep_objects], [1], + [Dependencies to place before and after the objects being linked to + create a shared library]) +_LT_TAGDECL([], [postdep_objects], [1]) +_LT_TAGDECL([], [predeps], [1]) +_LT_TAGDECL([], [postdeps], [1]) +_LT_TAGDECL([], [compiler_lib_search_path], [1], + [The library search path used internally by the compiler when linking + a shared library]) +])# _LT_SYS_HIDDEN_LIBDEPS + + +# _LT_PROG_F77 +# ------------ +# Since AC_PROG_F77 is broken, in that it returns the empty string +# if there is no fortran compiler, we have our own version here. +m4_defun([_LT_PROG_F77], +[ +pushdef([AC_MSG_ERROR], [_lt_disable_F77=yes]) +AC_PROG_F77 +if test -z "$F77" || test "X$F77" = "Xno"; then + _lt_disable_F77=yes +fi +popdef([AC_MSG_ERROR]) +])# _LT_PROG_F77 + +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([_LT_PROG_F77], []) + + +# _LT_LANG_F77_CONFIG([TAG]) +# -------------------------- +# Ensure that the configuration variables for a Fortran 77 compiler are +# suitably defined. These variables are subsequently used by _LT_CONFIG +# to write the compiler configuration to `libtool'. +m4_defun([_LT_LANG_F77_CONFIG], +[AC_REQUIRE([_LT_PROG_F77])dnl +AC_LANG_PUSH(Fortran 77) + +_LT_TAGVAR(archive_cmds_need_lc, $1)=no +_LT_TAGVAR(allow_undefined_flag, $1)= +_LT_TAGVAR(always_export_symbols, $1)=no +_LT_TAGVAR(archive_expsym_cmds, $1)= +_LT_TAGVAR(export_dynamic_flag_spec, $1)= +_LT_TAGVAR(hardcode_direct, $1)=no +_LT_TAGVAR(hardcode_direct_absolute, $1)=no +_LT_TAGVAR(hardcode_libdir_flag_spec, $1)= +_LT_TAGVAR(hardcode_libdir_flag_spec_ld, $1)= +_LT_TAGVAR(hardcode_libdir_separator, $1)= +_LT_TAGVAR(hardcode_minus_L, $1)=no +_LT_TAGVAR(hardcode_automatic, $1)=no +_LT_TAGVAR(inherit_rpath, $1)=no +_LT_TAGVAR(module_cmds, $1)= +_LT_TAGVAR(module_expsym_cmds, $1)= +_LT_TAGVAR(link_all_deplibs, $1)=unknown +_LT_TAGVAR(old_archive_cmds, $1)=$old_archive_cmds +_LT_TAGVAR(no_undefined_flag, $1)= +_LT_TAGVAR(whole_archive_flag_spec, $1)= +_LT_TAGVAR(enable_shared_with_static_runtimes, $1)=no + +# Source file extension for f77 test sources. +ac_ext=f + +# Object file extension for compiled f77 test sources. +objext=o +_LT_TAGVAR(objext, $1)=$objext + +# No sense in running all these tests if we already determined that +# the F77 compiler isn't working. Some variables (like enable_shared) +# are currently assumed to apply to all compilers on this platform, +# and will be corrupted by setting them based on a non-working compiler. +if test "$_lt_disable_F77" != yes; then + # Code to be used in simple compile tests + lt_simple_compile_test_code="\ + subroutine t + return + end +" + + # Code to be used in simple link tests + lt_simple_link_test_code="\ + program t + end +" + + # ltmain only uses $CC for tagged configurations so make sure $CC is set. + _LT_TAG_COMPILER + + # save warnings/boilerplate of simple test code + _LT_COMPILER_BOILERPLATE + _LT_LINKER_BOILERPLATE + + # Allow CC to be a program name with arguments. + lt_save_CC="$CC" + lt_save_GCC=$GCC + CC=${F77-"f77"} + compiler=$CC + _LT_TAGVAR(compiler, $1)=$CC + _LT_CC_BASENAME([$compiler]) + GCC=$G77 + if test -n "$compiler"; then + AC_MSG_CHECKING([if libtool supports shared libraries]) + AC_MSG_RESULT([$can_build_shared]) + + AC_MSG_CHECKING([whether to build shared libraries]) + test "$can_build_shared" = "no" && enable_shared=no + + # On AIX, shared libraries and static libraries use the same namespace, and + # are all built from PIC. + case $host_os in + aix3*) + test "$enable_shared" = yes && enable_static=no + if test -n "$RANLIB"; then + archive_cmds="$archive_cmds~\$RANLIB \$lib" + postinstall_cmds='$RANLIB $lib' + fi + ;; + aix[[4-9]]*) + if test "$host_cpu" != ia64 && test "$aix_use_runtimelinking" = no ; then + test "$enable_shared" = yes && enable_static=no + fi + ;; + esac + AC_MSG_RESULT([$enable_shared]) + + AC_MSG_CHECKING([whether to build static libraries]) + # Make sure either enable_shared or enable_static is yes. + test "$enable_shared" = yes || enable_static=yes + AC_MSG_RESULT([$enable_static]) + + _LT_TAGVAR(GCC, $1)="$G77" + _LT_TAGVAR(LD, $1)="$LD" + + ## CAVEAT EMPTOR: + ## There is no encapsulation within the following macros, do not change + ## the running order or otherwise move them around unless you know exactly + ## what you are doing... + _LT_COMPILER_PIC($1) + _LT_COMPILER_C_O($1) + _LT_COMPILER_FILE_LOCKS($1) + _LT_LINKER_SHLIBS($1) + _LT_SYS_DYNAMIC_LINKER($1) + _LT_LINKER_HARDCODE_LIBPATH($1) + + _LT_CONFIG($1) + fi # test -n "$compiler" + + GCC=$lt_save_GCC + CC="$lt_save_CC" +fi # test "$_lt_disable_F77" != yes + +AC_LANG_POP +])# _LT_LANG_F77_CONFIG + + +# _LT_PROG_FC +# ----------- +# Since AC_PROG_FC is broken, in that it returns the empty string +# if there is no fortran compiler, we have our own version here. +m4_defun([_LT_PROG_FC], +[ +pushdef([AC_MSG_ERROR], [_lt_disable_FC=yes]) +AC_PROG_FC +if test -z "$FC" || test "X$FC" = "Xno"; then + _lt_disable_FC=yes +fi +popdef([AC_MSG_ERROR]) +])# _LT_PROG_FC + +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([_LT_PROG_FC], []) + + +# _LT_LANG_FC_CONFIG([TAG]) +# ------------------------- +# Ensure that the configuration variables for a Fortran compiler are +# suitably defined. These variables are subsequently used by _LT_CONFIG +# to write the compiler configuration to `libtool'. +m4_defun([_LT_LANG_FC_CONFIG], +[AC_REQUIRE([_LT_PROG_FC])dnl +AC_LANG_PUSH(Fortran) + +_LT_TAGVAR(archive_cmds_need_lc, $1)=no +_LT_TAGVAR(allow_undefined_flag, $1)= +_LT_TAGVAR(always_export_symbols, $1)=no +_LT_TAGVAR(archive_expsym_cmds, $1)= +_LT_TAGVAR(export_dynamic_flag_spec, $1)= +_LT_TAGVAR(hardcode_direct, $1)=no +_LT_TAGVAR(hardcode_direct_absolute, $1)=no +_LT_TAGVAR(hardcode_libdir_flag_spec, $1)= +_LT_TAGVAR(hardcode_libdir_flag_spec_ld, $1)= +_LT_TAGVAR(hardcode_libdir_separator, $1)= +_LT_TAGVAR(hardcode_minus_L, $1)=no +_LT_TAGVAR(hardcode_automatic, $1)=no +_LT_TAGVAR(inherit_rpath, $1)=no +_LT_TAGVAR(module_cmds, $1)= +_LT_TAGVAR(module_expsym_cmds, $1)= +_LT_TAGVAR(link_all_deplibs, $1)=unknown +_LT_TAGVAR(old_archive_cmds, $1)=$old_archive_cmds +_LT_TAGVAR(no_undefined_flag, $1)= +_LT_TAGVAR(whole_archive_flag_spec, $1)= +_LT_TAGVAR(enable_shared_with_static_runtimes, $1)=no + +# Source file extension for fc test sources. +ac_ext=${ac_fc_srcext-f} + +# Object file extension for compiled fc test sources. +objext=o +_LT_TAGVAR(objext, $1)=$objext + +# No sense in running all these tests if we already determined that +# the FC compiler isn't working. Some variables (like enable_shared) +# are currently assumed to apply to all compilers on this platform, +# and will be corrupted by setting them based on a non-working compiler. +if test "$_lt_disable_FC" != yes; then + # Code to be used in simple compile tests + lt_simple_compile_test_code="\ + subroutine t + return + end +" + + # Code to be used in simple link tests + lt_simple_link_test_code="\ + program t + end +" + + # ltmain only uses $CC for tagged configurations so make sure $CC is set. + _LT_TAG_COMPILER + + # save warnings/boilerplate of simple test code + _LT_COMPILER_BOILERPLATE + _LT_LINKER_BOILERPLATE + + # Allow CC to be a program name with arguments. + lt_save_CC="$CC" + lt_save_GCC=$GCC + CC=${FC-"f95"} + compiler=$CC + GCC=$ac_cv_fc_compiler_gnu + + _LT_TAGVAR(compiler, $1)=$CC + _LT_CC_BASENAME([$compiler]) + + if test -n "$compiler"; then + AC_MSG_CHECKING([if libtool supports shared libraries]) + AC_MSG_RESULT([$can_build_shared]) + + AC_MSG_CHECKING([whether to build shared libraries]) + test "$can_build_shared" = "no" && enable_shared=no + + # On AIX, shared libraries and static libraries use the same namespace, and + # are all built from PIC. + case $host_os in + aix3*) + test "$enable_shared" = yes && enable_static=no + if test -n "$RANLIB"; then + archive_cmds="$archive_cmds~\$RANLIB \$lib" + postinstall_cmds='$RANLIB $lib' + fi + ;; + aix[[4-9]]*) + if test "$host_cpu" != ia64 && test "$aix_use_runtimelinking" = no ; then + test "$enable_shared" = yes && enable_static=no + fi + ;; + esac + AC_MSG_RESULT([$enable_shared]) + + AC_MSG_CHECKING([whether to build static libraries]) + # Make sure either enable_shared or enable_static is yes. + test "$enable_shared" = yes || enable_static=yes + AC_MSG_RESULT([$enable_static]) + + _LT_TAGVAR(GCC, $1)="$ac_cv_fc_compiler_gnu" + _LT_TAGVAR(LD, $1)="$LD" + + ## CAVEAT EMPTOR: + ## There is no encapsulation within the following macros, do not change + ## the running order or otherwise move them around unless you know exactly + ## what you are doing... + _LT_SYS_HIDDEN_LIBDEPS($1) + _LT_COMPILER_PIC($1) + _LT_COMPILER_C_O($1) + _LT_COMPILER_FILE_LOCKS($1) + _LT_LINKER_SHLIBS($1) + _LT_SYS_DYNAMIC_LINKER($1) + _LT_LINKER_HARDCODE_LIBPATH($1) + + _LT_CONFIG($1) + fi # test -n "$compiler" + + GCC=$lt_save_GCC + CC="$lt_save_CC" +fi # test "$_lt_disable_FC" != yes + +AC_LANG_POP +])# _LT_LANG_FC_CONFIG + + +# _LT_LANG_GCJ_CONFIG([TAG]) +# -------------------------- +# Ensure that the configuration variables for the GNU Java Compiler compiler +# are suitably defined. These variables are subsequently used by _LT_CONFIG +# to write the compiler configuration to `libtool'. +m4_defun([_LT_LANG_GCJ_CONFIG], +[AC_REQUIRE([LT_PROG_GCJ])dnl +AC_LANG_SAVE + +# Source file extension for Java test sources. +ac_ext=java + +# Object file extension for compiled Java test sources. +objext=o +_LT_TAGVAR(objext, $1)=$objext + +# Code to be used in simple compile tests +lt_simple_compile_test_code="class foo {}" + +# Code to be used in simple link tests +lt_simple_link_test_code='public class conftest { public static void main(String[[]] argv) {}; }' + +# ltmain only uses $CC for tagged configurations so make sure $CC is set. +_LT_TAG_COMPILER + +# save warnings/boilerplate of simple test code +_LT_COMPILER_BOILERPLATE +_LT_LINKER_BOILERPLATE + +# Allow CC to be a program name with arguments. +lt_save_CC="$CC" +lt_save_GCC=$GCC +GCC=yes +CC=${GCJ-"gcj"} +compiler=$CC +_LT_TAGVAR(compiler, $1)=$CC +_LT_TAGVAR(LD, $1)="$LD" +_LT_CC_BASENAME([$compiler]) + +# GCJ did not exist at the time GCC didn't implicitly link libc in. +_LT_TAGVAR(archive_cmds_need_lc, $1)=no + +_LT_TAGVAR(old_archive_cmds, $1)=$old_archive_cmds + +if test -n "$compiler"; then + _LT_COMPILER_NO_RTTI($1) + _LT_COMPILER_PIC($1) + _LT_COMPILER_C_O($1) + _LT_COMPILER_FILE_LOCKS($1) + _LT_LINKER_SHLIBS($1) + _LT_LINKER_HARDCODE_LIBPATH($1) + + _LT_CONFIG($1) +fi + +AC_LANG_RESTORE + +GCC=$lt_save_GCC +CC="$lt_save_CC" +])# _LT_LANG_GCJ_CONFIG + + +# _LT_LANG_RC_CONFIG([TAG]) +# ------------------------- +# Ensure that the configuration variables for the Windows resource compiler +# are suitably defined. These variables are subsequently used by _LT_CONFIG +# to write the compiler configuration to `libtool'. +m4_defun([_LT_LANG_RC_CONFIG], +[AC_REQUIRE([LT_PROG_RC])dnl +AC_LANG_SAVE + +# Source file extension for RC test sources. +ac_ext=rc + +# Object file extension for compiled RC test sources. +objext=o +_LT_TAGVAR(objext, $1)=$objext + +# Code to be used in simple compile tests +lt_simple_compile_test_code='sample MENU { MENUITEM "&Soup", 100, CHECKED }' + +# Code to be used in simple link tests +lt_simple_link_test_code="$lt_simple_compile_test_code" + +# ltmain only uses $CC for tagged configurations so make sure $CC is set. +_LT_TAG_COMPILER + +# save warnings/boilerplate of simple test code +_LT_COMPILER_BOILERPLATE +_LT_LINKER_BOILERPLATE + +# Allow CC to be a program name with arguments. +lt_save_CC="$CC" +lt_save_GCC=$GCC +GCC= +CC=${RC-"windres"} +compiler=$CC +_LT_TAGVAR(compiler, $1)=$CC +_LT_CC_BASENAME([$compiler]) +_LT_TAGVAR(lt_cv_prog_compiler_c_o, $1)=yes + +if test -n "$compiler"; then + : + _LT_CONFIG($1) +fi + +GCC=$lt_save_GCC +AC_LANG_RESTORE +CC="$lt_save_CC" +])# _LT_LANG_RC_CONFIG + + +# LT_PROG_GCJ +# ----------- +AC_DEFUN([LT_PROG_GCJ], +[m4_ifdef([AC_PROG_GCJ], [AC_PROG_GCJ], + [m4_ifdef([A][M_PROG_GCJ], [A][M_PROG_GCJ], + [AC_CHECK_TOOL(GCJ, gcj,) + test "x${GCJFLAGS+set}" = xset || GCJFLAGS="-g -O2" + AC_SUBST(GCJFLAGS)])])[]dnl +]) + +# Old name: +AU_ALIAS([LT_AC_PROG_GCJ], [LT_PROG_GCJ]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([LT_AC_PROG_GCJ], []) + + +# LT_PROG_RC +# ---------- +AC_DEFUN([LT_PROG_RC], +[AC_CHECK_TOOL(RC, windres,) +]) + +# Old name: +AU_ALIAS([LT_AC_PROG_RC], [LT_PROG_RC]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([LT_AC_PROG_RC], []) + + +# _LT_DECL_EGREP +# -------------- +# If we don't have a new enough Autoconf to choose the best grep +# available, choose the one first in the user's PATH. +m4_defun([_LT_DECL_EGREP], +[AC_REQUIRE([AC_PROG_EGREP])dnl +AC_REQUIRE([AC_PROG_FGREP])dnl +test -z "$GREP" && GREP=grep +_LT_DECL([], [GREP], [1], [A grep program that handles long lines]) +_LT_DECL([], [EGREP], [1], [An ERE matcher]) +_LT_DECL([], [FGREP], [1], [A literal string matcher]) +dnl Non-bleeding-edge autoconf doesn't subst GREP, so do it here too +AC_SUBST([GREP]) +]) + + +# _LT_DECL_OBJDUMP +# -------------- +# If we don't have a new enough Autoconf to choose the best objdump +# available, choose the one first in the user's PATH. +m4_defun([_LT_DECL_OBJDUMP], +[AC_CHECK_TOOL(OBJDUMP, objdump, false) +test -z "$OBJDUMP" && OBJDUMP=objdump +_LT_DECL([], [OBJDUMP], [1], [An object symbol dumper]) +AC_SUBST([OBJDUMP]) +]) + + +# _LT_DECL_SED +# ------------ +# Check for a fully-functional sed program, that truncates +# as few characters as possible. Prefer GNU sed if found. +m4_defun([_LT_DECL_SED], +[AC_PROG_SED +test -z "$SED" && SED=sed +Xsed="$SED -e 1s/^X//" +_LT_DECL([], [SED], [1], [A sed program that does not truncate output]) +_LT_DECL([], [Xsed], ["\$SED -e 1s/^X//"], + [Sed that helps us avoid accidentally triggering echo(1) options like -n]) +])# _LT_DECL_SED + +m4_ifndef([AC_PROG_SED], [ +# NOTE: This macro has been submitted for inclusion into # +# GNU Autoconf as AC_PROG_SED. When it is available in # +# a released version of Autoconf we should remove this # +# macro and use it instead. # + +m4_defun([AC_PROG_SED], +[AC_MSG_CHECKING([for a sed that does not truncate output]) +AC_CACHE_VAL(lt_cv_path_SED, +[# Loop through the user's path and test for sed and gsed. +# Then use that list of sed's as ones to test for truncation. +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for lt_ac_prog in sed gsed; do + for ac_exec_ext in '' $ac_executable_extensions; do + if $as_executable_p "$as_dir/$lt_ac_prog$ac_exec_ext"; then + lt_ac_sed_list="$lt_ac_sed_list $as_dir/$lt_ac_prog$ac_exec_ext" + fi + done + done +done +IFS=$as_save_IFS +lt_ac_max=0 +lt_ac_count=0 +# Add /usr/xpg4/bin/sed as it is typically found on Solaris +# along with /bin/sed that truncates output. +for lt_ac_sed in $lt_ac_sed_list /usr/xpg4/bin/sed; do + test ! -f $lt_ac_sed && continue + cat /dev/null > conftest.in + lt_ac_count=0 + echo $ECHO_N "0123456789$ECHO_C" >conftest.in + # Check for GNU sed and select it if it is found. + if "$lt_ac_sed" --version 2>&1 < /dev/null | grep 'GNU' > /dev/null; then + lt_cv_path_SED=$lt_ac_sed + break + fi + while true; do + cat conftest.in conftest.in >conftest.tmp + mv conftest.tmp conftest.in + cp conftest.in conftest.nl + echo >>conftest.nl + $lt_ac_sed -e 's/a$//' < conftest.nl >conftest.out || break + cmp -s conftest.out conftest.nl || break + # 10000 chars as input seems more than enough + test $lt_ac_count -gt 10 && break + lt_ac_count=`expr $lt_ac_count + 1` + if test $lt_ac_count -gt $lt_ac_max; then + lt_ac_max=$lt_ac_count + lt_cv_path_SED=$lt_ac_sed + fi + done +done +]) +SED=$lt_cv_path_SED +AC_SUBST([SED]) +AC_MSG_RESULT([$SED]) +])#AC_PROG_SED +])#m4_ifndef + +# Old name: +AU_ALIAS([LT_AC_PROG_SED], [AC_PROG_SED]) +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([LT_AC_PROG_SED], []) + + +# _LT_CHECK_SHELL_FEATURES +# ------------------------ +# Find out whether the shell is Bourne or XSI compatible, +# or has some other useful features. +m4_defun([_LT_CHECK_SHELL_FEATURES], +[AC_MSG_CHECKING([whether the shell understands some XSI constructs]) +# Try some XSI features +xsi_shell=no +( _lt_dummy="a/b/c" + test "${_lt_dummy##*/},${_lt_dummy%/*},"${_lt_dummy%"$_lt_dummy"}, \ + = c,a/b,, \ + && eval 'test $(( 1 + 1 )) -eq 2 \ + && test "${#_lt_dummy}" -eq 5' ) >/dev/null 2>&1 \ + && xsi_shell=yes +AC_MSG_RESULT([$xsi_shell]) +_LT_CONFIG_LIBTOOL_INIT([xsi_shell='$xsi_shell']) + +AC_MSG_CHECKING([whether the shell understands "+="]) +lt_shell_append=no +( foo=bar; set foo baz; eval "$[1]+=\$[2]" && test "$foo" = barbaz ) \ + >/dev/null 2>&1 \ + && lt_shell_append=yes +AC_MSG_RESULT([$lt_shell_append]) +_LT_CONFIG_LIBTOOL_INIT([lt_shell_append='$lt_shell_append']) + +if ( (MAIL=60; unset MAIL) || exit) >/dev/null 2>&1; then + lt_unset=unset +else + lt_unset=false +fi +_LT_DECL([], [lt_unset], [0], [whether the shell understands "unset"])dnl + +# test EBCDIC or ASCII +case `echo X|tr X '\101'` in + A) # ASCII based system + # \n is not interpreted correctly by Solaris 8 /usr/ucb/tr + lt_SP2NL='tr \040 \012' + lt_NL2SP='tr \015\012 \040\040' + ;; + *) # EBCDIC based system + lt_SP2NL='tr \100 \n' + lt_NL2SP='tr \r\n \100\100' + ;; +esac +_LT_DECL([SP2NL], [lt_SP2NL], [1], [turn spaces into newlines])dnl +_LT_DECL([NL2SP], [lt_NL2SP], [1], [turn newlines into spaces])dnl +])# _LT_CHECK_SHELL_FEATURES + + +# _LT_PROG_XSI_SHELLFNS +# --------------------- +# Bourne and XSI compatible variants of some useful shell functions. +m4_defun([_LT_PROG_XSI_SHELLFNS], +[case $xsi_shell in + yes) + cat << \_LT_EOF >> "$cfgfile" + +# func_dirname file append nondir_replacement +# Compute the dirname of FILE. If nonempty, add APPEND to the result, +# otherwise set result to NONDIR_REPLACEMENT. +func_dirname () +{ + case ${1} in + */*) func_dirname_result="${1%/*}${2}" ;; + * ) func_dirname_result="${3}" ;; + esac +} + +# func_basename file +func_basename () +{ + func_basename_result="${1##*/}" +} + +# func_dirname_and_basename file append nondir_replacement +# perform func_basename and func_dirname in a single function +# call: +# dirname: Compute the dirname of FILE. If nonempty, +# add APPEND to the result, otherwise set result +# to NONDIR_REPLACEMENT. +# value returned in "$func_dirname_result" +# basename: Compute filename of FILE. +# value retuned in "$func_basename_result" +# Implementation must be kept synchronized with func_dirname +# and func_basename. For efficiency, we do not delegate to +# those functions but instead duplicate the functionality here. +func_dirname_and_basename () +{ + case ${1} in + */*) func_dirname_result="${1%/*}${2}" ;; + * ) func_dirname_result="${3}" ;; + esac + func_basename_result="${1##*/}" +} + +# func_stripname prefix suffix name +# strip PREFIX and SUFFIX off of NAME. +# PREFIX and SUFFIX must not contain globbing or regex special +# characters, hashes, percent signs, but SUFFIX may contain a leading +# dot (in which case that matches only a dot). +func_stripname () +{ + # pdksh 5.2.14 does not do ${X%$Y} correctly if both X and Y are + # positional parameters, so assign one to ordinary parameter first. + func_stripname_result=${3} + func_stripname_result=${func_stripname_result#"${1}"} + func_stripname_result=${func_stripname_result%"${2}"} +} + +# func_opt_split +func_opt_split () +{ + func_opt_split_opt=${1%%=*} + func_opt_split_arg=${1#*=} +} + +# func_lo2o object +func_lo2o () +{ + case ${1} in + *.lo) func_lo2o_result=${1%.lo}.${objext} ;; + *) func_lo2o_result=${1} ;; + esac +} + +# func_xform libobj-or-source +func_xform () +{ + func_xform_result=${1%.*}.lo +} + +# func_arith arithmetic-term... +func_arith () +{ + func_arith_result=$(( $[*] )) +} + +# func_len string +# STRING may not start with a hyphen. +func_len () +{ + func_len_result=${#1} +} + +_LT_EOF + ;; + *) # Bourne compatible functions. + cat << \_LT_EOF >> "$cfgfile" + +# func_dirname file append nondir_replacement +# Compute the dirname of FILE. If nonempty, add APPEND to the result, +# otherwise set result to NONDIR_REPLACEMENT. +func_dirname () +{ + # Extract subdirectory from the argument. + func_dirname_result=`$ECHO "X${1}" | $Xsed -e "$dirname"` + if test "X$func_dirname_result" = "X${1}"; then + func_dirname_result="${3}" + else + func_dirname_result="$func_dirname_result${2}" + fi +} + +# func_basename file +func_basename () +{ + func_basename_result=`$ECHO "X${1}" | $Xsed -e "$basename"` +} + +dnl func_dirname_and_basename +dnl A portable version of this function is already defined in general.m4sh +dnl so there is no need for it here. + +# func_stripname prefix suffix name +# strip PREFIX and SUFFIX off of NAME. +# PREFIX and SUFFIX must not contain globbing or regex special +# characters, hashes, percent signs, but SUFFIX may contain a leading +# dot (in which case that matches only a dot). +# func_strip_suffix prefix name +func_stripname () +{ + case ${2} in + .*) func_stripname_result=`$ECHO "X${3}" \ + | $Xsed -e "s%^${1}%%" -e "s%\\\\${2}\$%%"`;; + *) func_stripname_result=`$ECHO "X${3}" \ + | $Xsed -e "s%^${1}%%" -e "s%${2}\$%%"`;; + esac +} + +# sed scripts: +my_sed_long_opt='1s/^\(-[[^=]]*\)=.*/\1/;q' +my_sed_long_arg='1s/^-[[^=]]*=//' + +# func_opt_split +func_opt_split () +{ + func_opt_split_opt=`$ECHO "X${1}" | $Xsed -e "$my_sed_long_opt"` + func_opt_split_arg=`$ECHO "X${1}" | $Xsed -e "$my_sed_long_arg"` +} + +# func_lo2o object +func_lo2o () +{ + func_lo2o_result=`$ECHO "X${1}" | $Xsed -e "$lo2o"` +} + +# func_xform libobj-or-source +func_xform () +{ + func_xform_result=`$ECHO "X${1}" | $Xsed -e 's/\.[[^.]]*$/.lo/'` +} + +# func_arith arithmetic-term... +func_arith () +{ + func_arith_result=`expr "$[@]"` +} + +# func_len string +# STRING may not start with a hyphen. +func_len () +{ + func_len_result=`expr "$[1]" : ".*" 2>/dev/null || echo $max_cmd_len` +} + +_LT_EOF +esac + +case $lt_shell_append in + yes) + cat << \_LT_EOF >> "$cfgfile" + +# func_append var value +# Append VALUE to the end of shell variable VAR. +func_append () +{ + eval "$[1]+=\$[2]" +} +_LT_EOF + ;; + *) + cat << \_LT_EOF >> "$cfgfile" + +# func_append var value +# Append VALUE to the end of shell variable VAR. +func_append () +{ + eval "$[1]=\$$[1]\$[2]" +} + +_LT_EOF + ;; + esac +]) + +# Helper functions for option handling. -*- Autoconf -*- +# +# Copyright (C) 2004, 2005, 2007, 2008 Free Software Foundation, Inc. +# Written by Gary V. Vaughan, 2004 +# +# This file is free software; the Free Software Foundation gives +# unlimited permission to copy and/or distribute it, with or without +# modifications, as long as this notice is preserved. + +# serial 6 ltoptions.m4 + +# This is to help aclocal find these macros, as it can't see m4_define. +AC_DEFUN([LTOPTIONS_VERSION], [m4_if([1])]) + + +# _LT_MANGLE_OPTION(MACRO-NAME, OPTION-NAME) +# ------------------------------------------ +m4_define([_LT_MANGLE_OPTION], +[[_LT_OPTION_]m4_bpatsubst($1__$2, [[^a-zA-Z0-9_]], [_])]) + + +# _LT_SET_OPTION(MACRO-NAME, OPTION-NAME) +# --------------------------------------- +# Set option OPTION-NAME for macro MACRO-NAME, and if there is a +# matching handler defined, dispatch to it. Other OPTION-NAMEs are +# saved as a flag. +m4_define([_LT_SET_OPTION], +[m4_define(_LT_MANGLE_OPTION([$1], [$2]))dnl +m4_ifdef(_LT_MANGLE_DEFUN([$1], [$2]), + _LT_MANGLE_DEFUN([$1], [$2]), + [m4_warning([Unknown $1 option `$2'])])[]dnl +]) + + +# _LT_IF_OPTION(MACRO-NAME, OPTION-NAME, IF-SET, [IF-NOT-SET]) +# ------------------------------------------------------------ +# Execute IF-SET if OPTION is set, IF-NOT-SET otherwise. +m4_define([_LT_IF_OPTION], +[m4_ifdef(_LT_MANGLE_OPTION([$1], [$2]), [$3], [$4])]) + + +# _LT_UNLESS_OPTIONS(MACRO-NAME, OPTION-LIST, IF-NOT-SET) +# ------------------------------------------------------- +# Execute IF-NOT-SET unless all options in OPTION-LIST for MACRO-NAME +# are set. +m4_define([_LT_UNLESS_OPTIONS], +[m4_foreach([_LT_Option], m4_split(m4_normalize([$2])), + [m4_ifdef(_LT_MANGLE_OPTION([$1], _LT_Option), + [m4_define([$0_found])])])[]dnl +m4_ifdef([$0_found], [m4_undefine([$0_found])], [$3 +])[]dnl +]) + + +# _LT_SET_OPTIONS(MACRO-NAME, OPTION-LIST) +# ---------------------------------------- +# OPTION-LIST is a space-separated list of Libtool options associated +# with MACRO-NAME. If any OPTION has a matching handler declared with +# LT_OPTION_DEFINE, dispatch to that macro; otherwise complain about +# the unknown option and exit. +m4_defun([_LT_SET_OPTIONS], +[# Set options +m4_foreach([_LT_Option], m4_split(m4_normalize([$2])), + [_LT_SET_OPTION([$1], _LT_Option)]) + +m4_if([$1],[LT_INIT],[ + dnl + dnl Simply set some default values (i.e off) if boolean options were not + dnl specified: + _LT_UNLESS_OPTIONS([LT_INIT], [dlopen], [enable_dlopen=no + ]) + _LT_UNLESS_OPTIONS([LT_INIT], [win32-dll], [enable_win32_dll=no + ]) + dnl + dnl If no reference was made to various pairs of opposing options, then + dnl we run the default mode handler for the pair. For example, if neither + dnl `shared' nor `disable-shared' was passed, we enable building of shared + dnl archives by default: + _LT_UNLESS_OPTIONS([LT_INIT], [shared disable-shared], [_LT_ENABLE_SHARED]) + _LT_UNLESS_OPTIONS([LT_INIT], [static disable-static], [_LT_ENABLE_STATIC]) + _LT_UNLESS_OPTIONS([LT_INIT], [pic-only no-pic], [_LT_WITH_PIC]) + _LT_UNLESS_OPTIONS([LT_INIT], [fast-install disable-fast-install], + [_LT_ENABLE_FAST_INSTALL]) + ]) +])# _LT_SET_OPTIONS + + + +# _LT_MANGLE_DEFUN(MACRO-NAME, OPTION-NAME) +# ----------------------------------------- +m4_define([_LT_MANGLE_DEFUN], +[[_LT_OPTION_DEFUN_]m4_bpatsubst(m4_toupper([$1__$2]), [[^A-Z0-9_]], [_])]) + + +# LT_OPTION_DEFINE(MACRO-NAME, OPTION-NAME, CODE) +# ----------------------------------------------- +m4_define([LT_OPTION_DEFINE], +[m4_define(_LT_MANGLE_DEFUN([$1], [$2]), [$3])[]dnl +])# LT_OPTION_DEFINE + + +# dlopen +# ------ +LT_OPTION_DEFINE([LT_INIT], [dlopen], [enable_dlopen=yes +]) + +AU_DEFUN([AC_LIBTOOL_DLOPEN], +[_LT_SET_OPTION([LT_INIT], [dlopen]) +AC_DIAGNOSE([obsolete], +[$0: Remove this warning and the call to _LT_SET_OPTION when you +put the `dlopen' option into LT_INIT's first parameter.]) +]) + +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_LIBTOOL_DLOPEN], []) + + +# win32-dll +# --------- +# Declare package support for building win32 dll's. +LT_OPTION_DEFINE([LT_INIT], [win32-dll], +[enable_win32_dll=yes + +case $host in +*-*-cygwin* | *-*-mingw* | *-*-pw32* | *-cegcc*) + AC_CHECK_TOOL(AS, as, false) + AC_CHECK_TOOL(DLLTOOL, dlltool, false) + AC_CHECK_TOOL(OBJDUMP, objdump, false) + ;; +esac + +test -z "$AS" && AS=as +_LT_DECL([], [AS], [0], [Assembler program])dnl + +test -z "$DLLTOOL" && DLLTOOL=dlltool +_LT_DECL([], [DLLTOOL], [0], [DLL creation program])dnl + +test -z "$OBJDUMP" && OBJDUMP=objdump +_LT_DECL([], [OBJDUMP], [0], [Object dumper program])dnl +])# win32-dll + +AU_DEFUN([AC_LIBTOOL_WIN32_DLL], +[AC_REQUIRE([AC_CANONICAL_HOST])dnl +_LT_SET_OPTION([LT_INIT], [win32-dll]) +AC_DIAGNOSE([obsolete], +[$0: Remove this warning and the call to _LT_SET_OPTION when you +put the `win32-dll' option into LT_INIT's first parameter.]) +]) + +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_LIBTOOL_WIN32_DLL], []) + + +# _LT_ENABLE_SHARED([DEFAULT]) +# ---------------------------- +# implement the --enable-shared flag, and supports the `shared' and +# `disable-shared' LT_INIT options. +# DEFAULT is either `yes' or `no'. If omitted, it defaults to `yes'. +m4_define([_LT_ENABLE_SHARED], +[m4_define([_LT_ENABLE_SHARED_DEFAULT], [m4_if($1, no, no, yes)])dnl +AC_ARG_ENABLE([shared], + [AS_HELP_STRING([--enable-shared@<:@=PKGS@:>@], + [build shared libraries @<:@default=]_LT_ENABLE_SHARED_DEFAULT[@:>@])], + [p=${PACKAGE-default} + case $enableval in + yes) enable_shared=yes ;; + no) enable_shared=no ;; + *) + enable_shared=no + # Look at the argument we got. We use all the common list separators. + lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + for pkg in $enableval; do + IFS="$lt_save_ifs" + if test "X$pkg" = "X$p"; then + enable_shared=yes + fi + done + IFS="$lt_save_ifs" + ;; + esac], + [enable_shared=]_LT_ENABLE_SHARED_DEFAULT) + + _LT_DECL([build_libtool_libs], [enable_shared], [0], + [Whether or not to build shared libraries]) +])# _LT_ENABLE_SHARED + +LT_OPTION_DEFINE([LT_INIT], [shared], [_LT_ENABLE_SHARED([yes])]) +LT_OPTION_DEFINE([LT_INIT], [disable-shared], [_LT_ENABLE_SHARED([no])]) + +# Old names: +AC_DEFUN([AC_ENABLE_SHARED], +[_LT_SET_OPTION([LT_INIT], m4_if([$1], [no], [disable-])[shared]) +]) + +AC_DEFUN([AC_DISABLE_SHARED], +[_LT_SET_OPTION([LT_INIT], [disable-shared]) +]) + +AU_DEFUN([AM_ENABLE_SHARED], [AC_ENABLE_SHARED($@)]) +AU_DEFUN([AM_DISABLE_SHARED], [AC_DISABLE_SHARED($@)]) + +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AM_ENABLE_SHARED], []) +dnl AC_DEFUN([AM_DISABLE_SHARED], []) + + + +# _LT_ENABLE_STATIC([DEFAULT]) +# ---------------------------- +# implement the --enable-static flag, and support the `static' and +# `disable-static' LT_INIT options. +# DEFAULT is either `yes' or `no'. If omitted, it defaults to `yes'. +m4_define([_LT_ENABLE_STATIC], +[m4_define([_LT_ENABLE_STATIC_DEFAULT], [m4_if($1, no, no, yes)])dnl +AC_ARG_ENABLE([static], + [AS_HELP_STRING([--enable-static@<:@=PKGS@:>@], + [build static libraries @<:@default=]_LT_ENABLE_STATIC_DEFAULT[@:>@])], + [p=${PACKAGE-default} + case $enableval in + yes) enable_static=yes ;; + no) enable_static=no ;; + *) + enable_static=no + # Look at the argument we got. We use all the common list separators. + lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + for pkg in $enableval; do + IFS="$lt_save_ifs" + if test "X$pkg" = "X$p"; then + enable_static=yes + fi + done + IFS="$lt_save_ifs" + ;; + esac], + [enable_static=]_LT_ENABLE_STATIC_DEFAULT) + + _LT_DECL([build_old_libs], [enable_static], [0], + [Whether or not to build static libraries]) +])# _LT_ENABLE_STATIC + +LT_OPTION_DEFINE([LT_INIT], [static], [_LT_ENABLE_STATIC([yes])]) +LT_OPTION_DEFINE([LT_INIT], [disable-static], [_LT_ENABLE_STATIC([no])]) + +# Old names: +AC_DEFUN([AC_ENABLE_STATIC], +[_LT_SET_OPTION([LT_INIT], m4_if([$1], [no], [disable-])[static]) +]) + +AC_DEFUN([AC_DISABLE_STATIC], +[_LT_SET_OPTION([LT_INIT], [disable-static]) +]) + +AU_DEFUN([AM_ENABLE_STATIC], [AC_ENABLE_STATIC($@)]) +AU_DEFUN([AM_DISABLE_STATIC], [AC_DISABLE_STATIC($@)]) + +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AM_ENABLE_STATIC], []) +dnl AC_DEFUN([AM_DISABLE_STATIC], []) + + + +# _LT_ENABLE_FAST_INSTALL([DEFAULT]) +# ---------------------------------- +# implement the --enable-fast-install flag, and support the `fast-install' +# and `disable-fast-install' LT_INIT options. +# DEFAULT is either `yes' or `no'. If omitted, it defaults to `yes'. +m4_define([_LT_ENABLE_FAST_INSTALL], +[m4_define([_LT_ENABLE_FAST_INSTALL_DEFAULT], [m4_if($1, no, no, yes)])dnl +AC_ARG_ENABLE([fast-install], + [AS_HELP_STRING([--enable-fast-install@<:@=PKGS@:>@], + [optimize for fast installation @<:@default=]_LT_ENABLE_FAST_INSTALL_DEFAULT[@:>@])], + [p=${PACKAGE-default} + case $enableval in + yes) enable_fast_install=yes ;; + no) enable_fast_install=no ;; + *) + enable_fast_install=no + # Look at the argument we got. We use all the common list separators. + lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + for pkg in $enableval; do + IFS="$lt_save_ifs" + if test "X$pkg" = "X$p"; then + enable_fast_install=yes + fi + done + IFS="$lt_save_ifs" + ;; + esac], + [enable_fast_install=]_LT_ENABLE_FAST_INSTALL_DEFAULT) + +_LT_DECL([fast_install], [enable_fast_install], [0], + [Whether or not to optimize for fast installation])dnl +])# _LT_ENABLE_FAST_INSTALL + +LT_OPTION_DEFINE([LT_INIT], [fast-install], [_LT_ENABLE_FAST_INSTALL([yes])]) +LT_OPTION_DEFINE([LT_INIT], [disable-fast-install], [_LT_ENABLE_FAST_INSTALL([no])]) + +# Old names: +AU_DEFUN([AC_ENABLE_FAST_INSTALL], +[_LT_SET_OPTION([LT_INIT], m4_if([$1], [no], [disable-])[fast-install]) +AC_DIAGNOSE([obsolete], +[$0: Remove this warning and the call to _LT_SET_OPTION when you put +the `fast-install' option into LT_INIT's first parameter.]) +]) + +AU_DEFUN([AC_DISABLE_FAST_INSTALL], +[_LT_SET_OPTION([LT_INIT], [disable-fast-install]) +AC_DIAGNOSE([obsolete], +[$0: Remove this warning and the call to _LT_SET_OPTION when you put +the `disable-fast-install' option into LT_INIT's first parameter.]) +]) + +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_ENABLE_FAST_INSTALL], []) +dnl AC_DEFUN([AM_DISABLE_FAST_INSTALL], []) + + +# _LT_WITH_PIC([MODE]) +# -------------------- +# implement the --with-pic flag, and support the `pic-only' and `no-pic' +# LT_INIT options. +# MODE is either `yes' or `no'. If omitted, it defaults to `both'. +m4_define([_LT_WITH_PIC], +[AC_ARG_WITH([pic], + [AS_HELP_STRING([--with-pic], + [try to use only PIC/non-PIC objects @<:@default=use both@:>@])], + [pic_mode="$withval"], + [pic_mode=default]) + +test -z "$pic_mode" && pic_mode=m4_default([$1], [default]) + +_LT_DECL([], [pic_mode], [0], [What type of objects to build])dnl +])# _LT_WITH_PIC + +LT_OPTION_DEFINE([LT_INIT], [pic-only], [_LT_WITH_PIC([yes])]) +LT_OPTION_DEFINE([LT_INIT], [no-pic], [_LT_WITH_PIC([no])]) + +# Old name: +AU_DEFUN([AC_LIBTOOL_PICMODE], +[_LT_SET_OPTION([LT_INIT], [pic-only]) +AC_DIAGNOSE([obsolete], +[$0: Remove this warning and the call to _LT_SET_OPTION when you +put the `pic-only' option into LT_INIT's first parameter.]) +]) + +dnl aclocal-1.4 backwards compatibility: +dnl AC_DEFUN([AC_LIBTOOL_PICMODE], []) + + +m4_define([_LTDL_MODE], []) +LT_OPTION_DEFINE([LTDL_INIT], [nonrecursive], + [m4_define([_LTDL_MODE], [nonrecursive])]) +LT_OPTION_DEFINE([LTDL_INIT], [recursive], + [m4_define([_LTDL_MODE], [recursive])]) +LT_OPTION_DEFINE([LTDL_INIT], [subproject], + [m4_define([_LTDL_MODE], [subproject])]) + +m4_define([_LTDL_TYPE], []) +LT_OPTION_DEFINE([LTDL_INIT], [installable], + [m4_define([_LTDL_TYPE], [installable])]) +LT_OPTION_DEFINE([LTDL_INIT], [convenience], + [m4_define([_LTDL_TYPE], [convenience])]) + +# ltsugar.m4 -- libtool m4 base layer. -*-Autoconf-*- +# +# Copyright (C) 2004, 2005, 2007, 2008 Free Software Foundation, Inc. +# Written by Gary V. Vaughan, 2004 +# +# This file is free software; the Free Software Foundation gives +# unlimited permission to copy and/or distribute it, with or without +# modifications, as long as this notice is preserved. + +# serial 6 ltsugar.m4 + +# This is to help aclocal find these macros, as it can't see m4_define. +AC_DEFUN([LTSUGAR_VERSION], [m4_if([0.1])]) + + +# lt_join(SEP, ARG1, [ARG2...]) +# ----------------------------- +# Produce ARG1SEPARG2...SEPARGn, omitting [] arguments and their +# associated separator. +# Needed until we can rely on m4_join from Autoconf 2.62, since all earlier +# versions in m4sugar had bugs. +m4_define([lt_join], +[m4_if([$#], [1], [], + [$#], [2], [[$2]], + [m4_if([$2], [], [], [[$2]_])$0([$1], m4_shift(m4_shift($@)))])]) +m4_define([_lt_join], +[m4_if([$#$2], [2], [], + [m4_if([$2], [], [], [[$1$2]])$0([$1], m4_shift(m4_shift($@)))])]) + + +# lt_car(LIST) +# lt_cdr(LIST) +# ------------ +# Manipulate m4 lists. +# These macros are necessary as long as will still need to support +# Autoconf-2.59 which quotes differently. +m4_define([lt_car], [[$1]]) +m4_define([lt_cdr], +[m4_if([$#], 0, [m4_fatal([$0: cannot be called without arguments])], + [$#], 1, [], + [m4_dquote(m4_shift($@))])]) +m4_define([lt_unquote], $1) + + +# lt_append(MACRO-NAME, STRING, [SEPARATOR]) +# ------------------------------------------ +# Redefine MACRO-NAME to hold its former content plus `SEPARATOR'`STRING'. +# Note that neither SEPARATOR nor STRING are expanded; they are appended +# to MACRO-NAME as is (leaving the expansion for when MACRO-NAME is invoked). +# No SEPARATOR is output if MACRO-NAME was previously undefined (different +# than defined and empty). +# +# This macro is needed until we can rely on Autoconf 2.62, since earlier +# versions of m4sugar mistakenly expanded SEPARATOR but not STRING. +m4_define([lt_append], +[m4_define([$1], + m4_ifdef([$1], [m4_defn([$1])[$3]])[$2])]) + + + +# lt_combine(SEP, PREFIX-LIST, INFIX, SUFFIX1, [SUFFIX2...]) +# ---------------------------------------------------------- +# Produce a SEP delimited list of all paired combinations of elements of +# PREFIX-LIST with SUFFIX1 through SUFFIXn. Each element of the list +# has the form PREFIXmINFIXSUFFIXn. +# Needed until we can rely on m4_combine added in Autoconf 2.62. +m4_define([lt_combine], +[m4_if(m4_eval([$# > 3]), [1], + [m4_pushdef([_Lt_sep], [m4_define([_Lt_sep], m4_defn([lt_car]))])]]dnl +[[m4_foreach([_Lt_prefix], [$2], + [m4_foreach([_Lt_suffix], + ]m4_dquote(m4_dquote(m4_shift(m4_shift(m4_shift($@)))))[, + [_Lt_sep([$1])[]m4_defn([_Lt_prefix])[$3]m4_defn([_Lt_suffix])])])])]) + + +# lt_if_append_uniq(MACRO-NAME, VARNAME, [SEPARATOR], [UNIQ], [NOT-UNIQ]) +# ----------------------------------------------------------------------- +# Iff MACRO-NAME does not yet contain VARNAME, then append it (delimited +# by SEPARATOR if supplied) and expand UNIQ, else NOT-UNIQ. +m4_define([lt_if_append_uniq], +[m4_ifdef([$1], + [m4_if(m4_index([$3]m4_defn([$1])[$3], [$3$2$3]), [-1], + [lt_append([$1], [$2], [$3])$4], + [$5])], + [lt_append([$1], [$2], [$3])$4])]) + + +# lt_dict_add(DICT, KEY, VALUE) +# ----------------------------- +m4_define([lt_dict_add], +[m4_define([$1($2)], [$3])]) + + +# lt_dict_add_subkey(DICT, KEY, SUBKEY, VALUE) +# -------------------------------------------- +m4_define([lt_dict_add_subkey], +[m4_define([$1($2:$3)], [$4])]) + + +# lt_dict_fetch(DICT, KEY, [SUBKEY]) +# ---------------------------------- +m4_define([lt_dict_fetch], +[m4_ifval([$3], + m4_ifdef([$1($2:$3)], [m4_defn([$1($2:$3)])]), + m4_ifdef([$1($2)], [m4_defn([$1($2)])]))]) + + +# lt_if_dict_fetch(DICT, KEY, [SUBKEY], VALUE, IF-TRUE, [IF-FALSE]) +# ----------------------------------------------------------------- +m4_define([lt_if_dict_fetch], +[m4_if(lt_dict_fetch([$1], [$2], [$3]), [$4], + [$5], + [$6])]) + + +# lt_dict_filter(DICT, [SUBKEY], VALUE, [SEPARATOR], KEY, [...]) +# -------------------------------------------------------------- +m4_define([lt_dict_filter], +[m4_if([$5], [], [], + [lt_join(m4_quote(m4_default([$4], [[, ]])), + lt_unquote(m4_split(m4_normalize(m4_foreach(_Lt_key, lt_car([m4_shiftn(4, $@)]), + [lt_if_dict_fetch([$1], _Lt_key, [$2], [$3], [_Lt_key ])])))))])[]dnl +]) + +# ltversion.m4 -- version numbers -*- Autoconf -*- +# +# Copyright (C) 2004 Free Software Foundation, Inc. +# Written by Scott James Remnant, 2004 +# +# This file is free software; the Free Software Foundation gives +# unlimited permission to copy and/or distribute it, with or without +# modifications, as long as this notice is preserved. + +# Generated from ltversion.in. + +# serial 3017 ltversion.m4 +# This file is part of GNU Libtool + +m4_define([LT_PACKAGE_VERSION], [2.2.6b]) +m4_define([LT_PACKAGE_REVISION], [1.3017]) + +AC_DEFUN([LTVERSION_VERSION], +[macro_version='2.2.6b' +macro_revision='1.3017' +_LT_DECL(, macro_version, 0, [Which release of libtool.m4 was used?]) +_LT_DECL(, macro_revision, 0) +]) + +# lt~obsolete.m4 -- aclocal satisfying obsolete definitions. -*-Autoconf-*- +# +# Copyright (C) 2004, 2005, 2007 Free Software Foundation, Inc. +# Written by Scott James Remnant, 2004. +# +# This file is free software; the Free Software Foundation gives +# unlimited permission to copy and/or distribute it, with or without +# modifications, as long as this notice is preserved. + +# serial 4 lt~obsolete.m4 + +# These exist entirely to fool aclocal when bootstrapping libtool. +# +# In the past libtool.m4 has provided macros via AC_DEFUN (or AU_DEFUN) +# which have later been changed to m4_define as they aren't part of the +# exported API, or moved to Autoconf or Automake where they belong. +# +# The trouble is, aclocal is a bit thick. It'll see the old AC_DEFUN +# in /usr/share/aclocal/libtool.m4 and remember it, then when it sees us +# using a macro with the same name in our local m4/libtool.m4 it'll +# pull the old libtool.m4 in (it doesn't see our shiny new m4_define +# and doesn't know about Autoconf macros at all.) +# +# So we provide this file, which has a silly filename so it's always +# included after everything else. This provides aclocal with the +# AC_DEFUNs it wants, but when m4 processes it, it doesn't do anything +# because those macros already exist, or will be overwritten later. +# We use AC_DEFUN over AU_DEFUN for compatibility with aclocal-1.6. +# +# Anytime we withdraw an AC_DEFUN or AU_DEFUN, remember to add it here. +# Yes, that means every name once taken will need to remain here until +# we give up compatibility with versions before 1.7, at which point +# we need to keep only those names which we still refer to. + +# This is to help aclocal find these macros, as it can't see m4_define. +AC_DEFUN([LTOBSOLETE_VERSION], [m4_if([1])]) + +m4_ifndef([AC_LIBTOOL_LINKER_OPTION], [AC_DEFUN([AC_LIBTOOL_LINKER_OPTION])]) +m4_ifndef([AC_PROG_EGREP], [AC_DEFUN([AC_PROG_EGREP])]) +m4_ifndef([_LT_AC_PROG_ECHO_BACKSLASH], [AC_DEFUN([_LT_AC_PROG_ECHO_BACKSLASH])]) +m4_ifndef([_LT_AC_SHELL_INIT], [AC_DEFUN([_LT_AC_SHELL_INIT])]) +m4_ifndef([_LT_AC_SYS_LIBPATH_AIX], [AC_DEFUN([_LT_AC_SYS_LIBPATH_AIX])]) +m4_ifndef([_LT_PROG_LTMAIN], [AC_DEFUN([_LT_PROG_LTMAIN])]) +m4_ifndef([_LT_AC_TAGVAR], [AC_DEFUN([_LT_AC_TAGVAR])]) +m4_ifndef([AC_LTDL_ENABLE_INSTALL], [AC_DEFUN([AC_LTDL_ENABLE_INSTALL])]) +m4_ifndef([AC_LTDL_PREOPEN], [AC_DEFUN([AC_LTDL_PREOPEN])]) +m4_ifndef([_LT_AC_SYS_COMPILER], [AC_DEFUN([_LT_AC_SYS_COMPILER])]) +m4_ifndef([_LT_AC_LOCK], [AC_DEFUN([_LT_AC_LOCK])]) +m4_ifndef([AC_LIBTOOL_SYS_OLD_ARCHIVE], [AC_DEFUN([AC_LIBTOOL_SYS_OLD_ARCHIVE])]) +m4_ifndef([_LT_AC_TRY_DLOPEN_SELF], [AC_DEFUN([_LT_AC_TRY_DLOPEN_SELF])]) +m4_ifndef([AC_LIBTOOL_PROG_CC_C_O], [AC_DEFUN([AC_LIBTOOL_PROG_CC_C_O])]) +m4_ifndef([AC_LIBTOOL_SYS_HARD_LINK_LOCKS], [AC_DEFUN([AC_LIBTOOL_SYS_HARD_LINK_LOCKS])]) +m4_ifndef([AC_LIBTOOL_OBJDIR], [AC_DEFUN([AC_LIBTOOL_OBJDIR])]) +m4_ifndef([AC_LTDL_OBJDIR], [AC_DEFUN([AC_LTDL_OBJDIR])]) +m4_ifndef([AC_LIBTOOL_PROG_LD_HARDCODE_LIBPATH], [AC_DEFUN([AC_LIBTOOL_PROG_LD_HARDCODE_LIBPATH])]) +m4_ifndef([AC_LIBTOOL_SYS_LIB_STRIP], [AC_DEFUN([AC_LIBTOOL_SYS_LIB_STRIP])]) +m4_ifndef([AC_PATH_MAGIC], [AC_DEFUN([AC_PATH_MAGIC])]) +m4_ifndef([AC_PROG_LD_GNU], [AC_DEFUN([AC_PROG_LD_GNU])]) +m4_ifndef([AC_PROG_LD_RELOAD_FLAG], [AC_DEFUN([AC_PROG_LD_RELOAD_FLAG])]) +m4_ifndef([AC_DEPLIBS_CHECK_METHOD], [AC_DEFUN([AC_DEPLIBS_CHECK_METHOD])]) +m4_ifndef([AC_LIBTOOL_PROG_COMPILER_NO_RTTI], [AC_DEFUN([AC_LIBTOOL_PROG_COMPILER_NO_RTTI])]) +m4_ifndef([AC_LIBTOOL_SYS_GLOBAL_SYMBOL_PIPE], [AC_DEFUN([AC_LIBTOOL_SYS_GLOBAL_SYMBOL_PIPE])]) +m4_ifndef([AC_LIBTOOL_PROG_COMPILER_PIC], [AC_DEFUN([AC_LIBTOOL_PROG_COMPILER_PIC])]) +m4_ifndef([AC_LIBTOOL_PROG_LD_SHLIBS], [AC_DEFUN([AC_LIBTOOL_PROG_LD_SHLIBS])]) +m4_ifndef([AC_LIBTOOL_POSTDEP_PREDEP], [AC_DEFUN([AC_LIBTOOL_POSTDEP_PREDEP])]) +m4_ifndef([LT_AC_PROG_EGREP], [AC_DEFUN([LT_AC_PROG_EGREP])]) +m4_ifndef([LT_AC_PROG_SED], [AC_DEFUN([LT_AC_PROG_SED])]) +m4_ifndef([_LT_CC_BASENAME], [AC_DEFUN([_LT_CC_BASENAME])]) +m4_ifndef([_LT_COMPILER_BOILERPLATE], [AC_DEFUN([_LT_COMPILER_BOILERPLATE])]) +m4_ifndef([_LT_LINKER_BOILERPLATE], [AC_DEFUN([_LT_LINKER_BOILERPLATE])]) +m4_ifndef([_AC_PROG_LIBTOOL], [AC_DEFUN([_AC_PROG_LIBTOOL])]) +m4_ifndef([AC_LIBTOOL_SETUP], [AC_DEFUN([AC_LIBTOOL_SETUP])]) +m4_ifndef([_LT_AC_CHECK_DLFCN], [AC_DEFUN([_LT_AC_CHECK_DLFCN])]) +m4_ifndef([AC_LIBTOOL_SYS_DYNAMIC_LINKER], [AC_DEFUN([AC_LIBTOOL_SYS_DYNAMIC_LINKER])]) +m4_ifndef([_LT_AC_TAGCONFIG], [AC_DEFUN([_LT_AC_TAGCONFIG])]) +m4_ifndef([AC_DISABLE_FAST_INSTALL], [AC_DEFUN([AC_DISABLE_FAST_INSTALL])]) +m4_ifndef([_LT_AC_LANG_CXX], [AC_DEFUN([_LT_AC_LANG_CXX])]) +m4_ifndef([_LT_AC_LANG_F77], [AC_DEFUN([_LT_AC_LANG_F77])]) +m4_ifndef([_LT_AC_LANG_GCJ], [AC_DEFUN([_LT_AC_LANG_GCJ])]) +m4_ifndef([AC_LIBTOOL_RC], [AC_DEFUN([AC_LIBTOOL_RC])]) +m4_ifndef([AC_LIBTOOL_LANG_C_CONFIG], [AC_DEFUN([AC_LIBTOOL_LANG_C_CONFIG])]) +m4_ifndef([_LT_AC_LANG_C_CONFIG], [AC_DEFUN([_LT_AC_LANG_C_CONFIG])]) +m4_ifndef([AC_LIBTOOL_LANG_CXX_CONFIG], [AC_DEFUN([AC_LIBTOOL_LANG_CXX_CONFIG])]) +m4_ifndef([_LT_AC_LANG_CXX_CONFIG], [AC_DEFUN([_LT_AC_LANG_CXX_CONFIG])]) +m4_ifndef([AC_LIBTOOL_LANG_F77_CONFIG], [AC_DEFUN([AC_LIBTOOL_LANG_F77_CONFIG])]) +m4_ifndef([_LT_AC_LANG_F77_CONFIG], [AC_DEFUN([_LT_AC_LANG_F77_CONFIG])]) +m4_ifndef([AC_LIBTOOL_LANG_GCJ_CONFIG], [AC_DEFUN([AC_LIBTOOL_LANG_GCJ_CONFIG])]) +m4_ifndef([_LT_AC_LANG_GCJ_CONFIG], [AC_DEFUN([_LT_AC_LANG_GCJ_CONFIG])]) +m4_ifndef([AC_LIBTOOL_LANG_RC_CONFIG], [AC_DEFUN([AC_LIBTOOL_LANG_RC_CONFIG])]) +m4_ifndef([_LT_AC_LANG_RC_CONFIG], [AC_DEFUN([_LT_AC_LANG_RC_CONFIG])]) +m4_ifndef([AC_LIBTOOL_CONFIG], [AC_DEFUN([AC_LIBTOOL_CONFIG])]) +m4_ifndef([_LT_AC_FILE_LTDLL_C], [AC_DEFUN([_LT_AC_FILE_LTDLL_C])]) + +# pkg.m4 - Macros to locate and utilise pkg-config. -*- Autoconf -*- +# serial 1 (pkg-config-0.24) +# +# Copyright © 2004 Scott James Remnant . +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, but +# WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +# General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program; if not, write to the Free Software +# Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +# +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program that contains a +# configuration script generated by Autoconf, you may include it under +# the same distribution terms that you use for the rest of that program. + +# PKG_PROG_PKG_CONFIG([MIN-VERSION]) +# ---------------------------------- +AC_DEFUN([PKG_PROG_PKG_CONFIG], +[m4_pattern_forbid([^_?PKG_[A-Z_]+$]) +m4_pattern_allow([^PKG_CONFIG(_PATH)?$]) +AC_ARG_VAR([PKG_CONFIG], [path to pkg-config utility]) +AC_ARG_VAR([PKG_CONFIG_PATH], [directories to add to pkg-config's search path]) +AC_ARG_VAR([PKG_CONFIG_LIBDIR], [path overriding pkg-config's built-in search path]) + +if test "x$ac_cv_env_PKG_CONFIG_set" != "xset"; then + AC_PATH_TOOL([PKG_CONFIG], [pkg-config]) +fi +if test -n "$PKG_CONFIG"; then + _pkg_min_version=m4_default([$1], [0.9.0]) + AC_MSG_CHECKING([pkg-config is at least version $_pkg_min_version]) + if $PKG_CONFIG --atleast-pkgconfig-version $_pkg_min_version; then + AC_MSG_RESULT([yes]) + else + AC_MSG_RESULT([no]) + PKG_CONFIG="" + fi +fi[]dnl +])# PKG_PROG_PKG_CONFIG + +# PKG_CHECK_EXISTS(MODULES, [ACTION-IF-FOUND], [ACTION-IF-NOT-FOUND]) +# +# Check to see whether a particular set of modules exists. Similar +# to PKG_CHECK_MODULES(), but does not set variables or print errors. +# +# Please remember that m4 expands AC_REQUIRE([PKG_PROG_PKG_CONFIG]) +# only at the first occurence in configure.ac, so if the first place +# it's called might be skipped (such as if it is within an "if", you +# have to call PKG_CHECK_EXISTS manually +# -------------------------------------------------------------- +AC_DEFUN([PKG_CHECK_EXISTS], +[AC_REQUIRE([PKG_PROG_PKG_CONFIG])dnl +if test -n "$PKG_CONFIG" && \ + AC_RUN_LOG([$PKG_CONFIG --exists --print-errors "$1"]); then + m4_default([$2], [:]) +m4_ifvaln([$3], [else + $3])dnl +fi]) + +# _PKG_CONFIG([VARIABLE], [COMMAND], [MODULES]) +# --------------------------------------------- +m4_define([_PKG_CONFIG], +[if test -n "$$1"; then + pkg_cv_[]$1="$$1" + elif test -n "$PKG_CONFIG"; then + PKG_CHECK_EXISTS([$3], + [pkg_cv_[]$1=`$PKG_CONFIG --[]$2 "$3" 2>/dev/null`], + [pkg_failed=yes]) + else + pkg_failed=untried +fi[]dnl +])# _PKG_CONFIG + +# _PKG_SHORT_ERRORS_SUPPORTED +# ----------------------------- +AC_DEFUN([_PKG_SHORT_ERRORS_SUPPORTED], +[AC_REQUIRE([PKG_PROG_PKG_CONFIG]) +if $PKG_CONFIG --atleast-pkgconfig-version 0.20; then + _pkg_short_errors_supported=yes +else + _pkg_short_errors_supported=no +fi[]dnl +])# _PKG_SHORT_ERRORS_SUPPORTED + + +# PKG_CHECK_MODULES(VARIABLE-PREFIX, MODULES, [ACTION-IF-FOUND], +# [ACTION-IF-NOT-FOUND]) +# +# +# Note that if there is a possibility the first call to +# PKG_CHECK_MODULES might not happen, you should be sure to include an +# explicit call to PKG_PROG_PKG_CONFIG in your configure.ac +# +# +# -------------------------------------------------------------- +AC_DEFUN([PKG_CHECK_MODULES], +[AC_REQUIRE([PKG_PROG_PKG_CONFIG])dnl +AC_ARG_VAR([$1][_CFLAGS], [C compiler flags for $1, overriding pkg-config])dnl +AC_ARG_VAR([$1][_LIBS], [linker flags for $1, overriding pkg-config])dnl + +pkg_failed=no +AC_MSG_CHECKING([for $1]) + +_PKG_CONFIG([$1][_CFLAGS], [cflags], [$2]) +_PKG_CONFIG([$1][_LIBS], [libs], [$2]) + +m4_define([_PKG_TEXT], [Alternatively, you may set the environment variables $1[]_CFLAGS +and $1[]_LIBS to avoid the need to call pkg-config. +See the pkg-config man page for more details.]) + +if test $pkg_failed = yes; then + AC_MSG_RESULT([no]) + _PKG_SHORT_ERRORS_SUPPORTED + if test $_pkg_short_errors_supported = yes; then + $1[]_PKG_ERRORS=`$PKG_CONFIG --short-errors --print-errors "$2" 2>&1` + else + $1[]_PKG_ERRORS=`$PKG_CONFIG --print-errors "$2" 2>&1` + fi + # Put the nasty error message in config.log where it belongs + echo "$$1[]_PKG_ERRORS" >&AS_MESSAGE_LOG_FD + + m4_default([$4], [AC_MSG_ERROR( +[Package requirements ($2) were not met: + +$$1_PKG_ERRORS + +Consider adjusting the PKG_CONFIG_PATH environment variable if you +installed software in a non-standard prefix. + +_PKG_TEXT])[]dnl + ]) +elif test $pkg_failed = untried; then + AC_MSG_RESULT([no]) + m4_default([$4], [AC_MSG_FAILURE( +[The pkg-config script could not be found or is too old. Make sure it +is in your PATH or set the PKG_CONFIG environment variable to the full +path to pkg-config. + +_PKG_TEXT + +To get pkg-config, see .])[]dnl + ]) +else + $1[]_CFLAGS=$pkg_cv_[]$1[]_CFLAGS + $1[]_LIBS=$pkg_cv_[]$1[]_LIBS + AC_MSG_RESULT([yes]) + $3 +fi[]dnl +])# PKG_CHECK_MODULES + +# Copyright (C) 2002, 2003, 2005, 2006, 2007, 2008 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# AM_AUTOMAKE_VERSION(VERSION) +# ---------------------------- +# Automake X.Y traces this macro to ensure aclocal.m4 has been +# generated from the m4 files accompanying Automake X.Y. +# (This private macro should not be called outside this file.) +AC_DEFUN([AM_AUTOMAKE_VERSION], +[am__api_version='1.11' +dnl Some users find AM_AUTOMAKE_VERSION and mistake it for a way to +dnl require some minimum version. Point them to the right macro. +m4_if([$1], [1.11.1], [], + [AC_FATAL([Do not call $0, use AM_INIT_AUTOMAKE([$1]).])])dnl +]) + +# _AM_AUTOCONF_VERSION(VERSION) +# ----------------------------- +# aclocal traces this macro to find the Autoconf version. +# This is a private macro too. Using m4_define simplifies +# the logic in aclocal, which can simply ignore this definition. +m4_define([_AM_AUTOCONF_VERSION], []) + +# AM_SET_CURRENT_AUTOMAKE_VERSION +# ------------------------------- +# Call AM_AUTOMAKE_VERSION and AM_AUTOMAKE_VERSION so they can be traced. +# This function is AC_REQUIREd by AM_INIT_AUTOMAKE. +AC_DEFUN([AM_SET_CURRENT_AUTOMAKE_VERSION], +[AM_AUTOMAKE_VERSION([1.11.1])dnl +m4_ifndef([AC_AUTOCONF_VERSION], + [m4_copy([m4_PACKAGE_VERSION], [AC_AUTOCONF_VERSION])])dnl +_AM_AUTOCONF_VERSION(m4_defn([AC_AUTOCONF_VERSION]))]) + +# AM_AUX_DIR_EXPAND -*- Autoconf -*- + +# Copyright (C) 2001, 2003, 2005 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# For projects using AC_CONFIG_AUX_DIR([foo]), Autoconf sets +# $ac_aux_dir to `$srcdir/foo'. In other projects, it is set to +# `$srcdir', `$srcdir/..', or `$srcdir/../..'. +# +# Of course, Automake must honor this variable whenever it calls a +# tool from the auxiliary directory. The problem is that $srcdir (and +# therefore $ac_aux_dir as well) can be either absolute or relative, +# depending on how configure is run. This is pretty annoying, since +# it makes $ac_aux_dir quite unusable in subdirectories: in the top +# source directory, any form will work fine, but in subdirectories a +# relative path needs to be adjusted first. +# +# $ac_aux_dir/missing +# fails when called from a subdirectory if $ac_aux_dir is relative +# $top_srcdir/$ac_aux_dir/missing +# fails if $ac_aux_dir is absolute, +# fails when called from a subdirectory in a VPATH build with +# a relative $ac_aux_dir +# +# The reason of the latter failure is that $top_srcdir and $ac_aux_dir +# are both prefixed by $srcdir. In an in-source build this is usually +# harmless because $srcdir is `.', but things will broke when you +# start a VPATH build or use an absolute $srcdir. +# +# So we could use something similar to $top_srcdir/$ac_aux_dir/missing, +# iff we strip the leading $srcdir from $ac_aux_dir. That would be: +# am_aux_dir='\$(top_srcdir)/'`expr "$ac_aux_dir" : "$srcdir//*\(.*\)"` +# and then we would define $MISSING as +# MISSING="\${SHELL} $am_aux_dir/missing" +# This will work as long as MISSING is not called from configure, because +# unfortunately $(top_srcdir) has no meaning in configure. +# However there are other variables, like CC, which are often used in +# configure, and could therefore not use this "fixed" $ac_aux_dir. +# +# Another solution, used here, is to always expand $ac_aux_dir to an +# absolute PATH. The drawback is that using absolute paths prevent a +# configured tree to be moved without reconfiguration. + +AC_DEFUN([AM_AUX_DIR_EXPAND], +[dnl Rely on autoconf to set up CDPATH properly. +AC_PREREQ([2.50])dnl +# expand $ac_aux_dir to an absolute path +am_aux_dir=`cd $ac_aux_dir && pwd` +]) + +# AM_CONDITIONAL -*- Autoconf -*- + +# Copyright (C) 1997, 2000, 2001, 2003, 2004, 2005, 2006, 2008 +# Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 9 + +# AM_CONDITIONAL(NAME, SHELL-CONDITION) +# ------------------------------------- +# Define a conditional. +AC_DEFUN([AM_CONDITIONAL], +[AC_PREREQ(2.52)dnl + ifelse([$1], [TRUE], [AC_FATAL([$0: invalid condition: $1])], + [$1], [FALSE], [AC_FATAL([$0: invalid condition: $1])])dnl +AC_SUBST([$1_TRUE])dnl +AC_SUBST([$1_FALSE])dnl +_AM_SUBST_NOTMAKE([$1_TRUE])dnl +_AM_SUBST_NOTMAKE([$1_FALSE])dnl +m4_define([_AM_COND_VALUE_$1], [$2])dnl +if $2; then + $1_TRUE= + $1_FALSE='#' +else + $1_TRUE='#' + $1_FALSE= +fi +AC_CONFIG_COMMANDS_PRE( +[if test -z "${$1_TRUE}" && test -z "${$1_FALSE}"; then + AC_MSG_ERROR([[conditional "$1" was never defined. +Usually this means the macro was only invoked conditionally.]]) +fi])]) + +# Copyright (C) 1999, 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2009 +# Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 10 + +# There are a few dirty hacks below to avoid letting `AC_PROG_CC' be +# written in clear, in which case automake, when reading aclocal.m4, +# will think it sees a *use*, and therefore will trigger all it's +# C support machinery. Also note that it means that autoscan, seeing +# CC etc. in the Makefile, will ask for an AC_PROG_CC use... + + +# _AM_DEPENDENCIES(NAME) +# ---------------------- +# See how the compiler implements dependency checking. +# NAME is "CC", "CXX", "GCJ", or "OBJC". +# We try a few techniques and use that to set a single cache variable. +# +# We don't AC_REQUIRE the corresponding AC_PROG_CC since the latter was +# modified to invoke _AM_DEPENDENCIES(CC); we would have a circular +# dependency, and given that the user is not expected to run this macro, +# just rely on AC_PROG_CC. +AC_DEFUN([_AM_DEPENDENCIES], +[AC_REQUIRE([AM_SET_DEPDIR])dnl +AC_REQUIRE([AM_OUTPUT_DEPENDENCY_COMMANDS])dnl +AC_REQUIRE([AM_MAKE_INCLUDE])dnl +AC_REQUIRE([AM_DEP_TRACK])dnl + +ifelse([$1], CC, [depcc="$CC" am_compiler_list=], + [$1], CXX, [depcc="$CXX" am_compiler_list=], + [$1], OBJC, [depcc="$OBJC" am_compiler_list='gcc3 gcc'], + [$1], UPC, [depcc="$UPC" am_compiler_list=], + [$1], GCJ, [depcc="$GCJ" am_compiler_list='gcc3 gcc'], + [depcc="$$1" am_compiler_list=]) + +AC_CACHE_CHECK([dependency style of $depcc], + [am_cv_$1_dependencies_compiler_type], +[if test -z "$AMDEP_TRUE" && test -f "$am_depcomp"; then + # We make a subdir and do the tests there. Otherwise we can end up + # making bogus files that we don't know about and never remove. For + # instance it was reported that on HP-UX the gcc test will end up + # making a dummy file named `D' -- because `-MD' means `put the output + # in D'. + mkdir conftest.dir + # Copy depcomp to subdir because otherwise we won't find it if we're + # using a relative directory. + cp "$am_depcomp" conftest.dir + cd conftest.dir + # We will build objects and dependencies in a subdirectory because + # it helps to detect inapplicable dependency modes. For instance + # both Tru64's cc and ICC support -MD to output dependencies as a + # side effect of compilation, but ICC will put the dependencies in + # the current directory while Tru64 will put them in the object + # directory. + mkdir sub + + am_cv_$1_dependencies_compiler_type=none + if test "$am_compiler_list" = ""; then + am_compiler_list=`sed -n ['s/^#*\([a-zA-Z0-9]*\))$/\1/p'] < ./depcomp` + fi + am__universal=false + m4_case([$1], [CC], + [case " $depcc " in #( + *\ -arch\ *\ -arch\ *) am__universal=true ;; + esac], + [CXX], + [case " $depcc " in #( + *\ -arch\ *\ -arch\ *) am__universal=true ;; + esac]) + + for depmode in $am_compiler_list; do + # Setup a source with many dependencies, because some compilers + # like to wrap large dependency lists on column 80 (with \), and + # we should not choose a depcomp mode which is confused by this. + # + # We need to recreate these files for each test, as the compiler may + # overwrite some of them when testing with obscure command lines. + # This happens at least with the AIX C compiler. + : > sub/conftest.c + for i in 1 2 3 4 5 6; do + echo '#include "conftst'$i'.h"' >> sub/conftest.c + # Using `: > sub/conftst$i.h' creates only sub/conftst1.h with + # Solaris 8's {/usr,}/bin/sh. + touch sub/conftst$i.h + done + echo "${am__include} ${am__quote}sub/conftest.Po${am__quote}" > confmf + + # We check with `-c' and `-o' for the sake of the "dashmstdout" + # mode. It turns out that the SunPro C++ compiler does not properly + # handle `-M -o', and we need to detect this. Also, some Intel + # versions had trouble with output in subdirs + am__obj=sub/conftest.${OBJEXT-o} + am__minus_obj="-o $am__obj" + case $depmode in + gcc) + # This depmode causes a compiler race in universal mode. + test "$am__universal" = false || continue + ;; + nosideeffect) + # after this tag, mechanisms are not by side-effect, so they'll + # only be used when explicitly requested + if test "x$enable_dependency_tracking" = xyes; then + continue + else + break + fi + ;; + msvisualcpp | msvcmsys) + # This compiler won't grok `-c -o', but also, the minuso test has + # not run yet. These depmodes are late enough in the game, and + # so weak that their functioning should not be impacted. + am__obj=conftest.${OBJEXT-o} + am__minus_obj= + ;; + none) break ;; + esac + if depmode=$depmode \ + source=sub/conftest.c object=$am__obj \ + depfile=sub/conftest.Po tmpdepfile=sub/conftest.TPo \ + $SHELL ./depcomp $depcc -c $am__minus_obj sub/conftest.c \ + >/dev/null 2>conftest.err && + grep sub/conftst1.h sub/conftest.Po > /dev/null 2>&1 && + grep sub/conftst6.h sub/conftest.Po > /dev/null 2>&1 && + grep $am__obj sub/conftest.Po > /dev/null 2>&1 && + ${MAKE-make} -s -f confmf > /dev/null 2>&1; then + # icc doesn't choke on unknown options, it will just issue warnings + # or remarks (even with -Werror). So we grep stderr for any message + # that says an option was ignored or not supported. + # When given -MP, icc 7.0 and 7.1 complain thusly: + # icc: Command line warning: ignoring option '-M'; no argument required + # The diagnosis changed in icc 8.0: + # icc: Command line remark: option '-MP' not supported + if (grep 'ignoring option' conftest.err || + grep 'not supported' conftest.err) >/dev/null 2>&1; then :; else + am_cv_$1_dependencies_compiler_type=$depmode + break + fi + fi + done + + cd .. + rm -rf conftest.dir +else + am_cv_$1_dependencies_compiler_type=none +fi +]) +AC_SUBST([$1DEPMODE], [depmode=$am_cv_$1_dependencies_compiler_type]) +AM_CONDITIONAL([am__fastdep$1], [ + test "x$enable_dependency_tracking" != xno \ + && test "$am_cv_$1_dependencies_compiler_type" = gcc3]) +]) + + +# AM_SET_DEPDIR +# ------------- +# Choose a directory name for dependency files. +# This macro is AC_REQUIREd in _AM_DEPENDENCIES +AC_DEFUN([AM_SET_DEPDIR], +[AC_REQUIRE([AM_SET_LEADING_DOT])dnl +AC_SUBST([DEPDIR], ["${am__leading_dot}deps"])dnl +]) + + +# AM_DEP_TRACK +# ------------ +AC_DEFUN([AM_DEP_TRACK], +[AC_ARG_ENABLE(dependency-tracking, +[ --disable-dependency-tracking speeds up one-time build + --enable-dependency-tracking do not reject slow dependency extractors]) +if test "x$enable_dependency_tracking" != xno; then + am_depcomp="$ac_aux_dir/depcomp" + AMDEPBACKSLASH='\' +fi +AM_CONDITIONAL([AMDEP], [test "x$enable_dependency_tracking" != xno]) +AC_SUBST([AMDEPBACKSLASH])dnl +_AM_SUBST_NOTMAKE([AMDEPBACKSLASH])dnl +]) + +# Generate code to set up dependency tracking. -*- Autoconf -*- + +# Copyright (C) 1999, 2000, 2001, 2002, 2003, 2004, 2005, 2008 +# Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +#serial 5 + +# _AM_OUTPUT_DEPENDENCY_COMMANDS +# ------------------------------ +AC_DEFUN([_AM_OUTPUT_DEPENDENCY_COMMANDS], +[{ + # Autoconf 2.62 quotes --file arguments for eval, but not when files + # are listed without --file. Let's play safe and only enable the eval + # if we detect the quoting. + case $CONFIG_FILES in + *\'*) eval set x "$CONFIG_FILES" ;; + *) set x $CONFIG_FILES ;; + esac + shift + for mf + do + # Strip MF so we end up with the name of the file. + mf=`echo "$mf" | sed -e 's/:.*$//'` + # Check whether this is an Automake generated Makefile or not. + # We used to match only the files named `Makefile.in', but + # some people rename them; so instead we look at the file content. + # Grep'ing the first line is not enough: some people post-process + # each Makefile.in and add a new line on top of each file to say so. + # Grep'ing the whole file is not good either: AIX grep has a line + # limit of 2048, but all sed's we know have understand at least 4000. + if sed -n 's,^#.*generated by automake.*,X,p' "$mf" | grep X >/dev/null 2>&1; then + dirpart=`AS_DIRNAME("$mf")` + else + continue + fi + # Extract the definition of DEPDIR, am__include, and am__quote + # from the Makefile without running `make'. + DEPDIR=`sed -n 's/^DEPDIR = //p' < "$mf"` + test -z "$DEPDIR" && continue + am__include=`sed -n 's/^am__include = //p' < "$mf"` + test -z "am__include" && continue + am__quote=`sed -n 's/^am__quote = //p' < "$mf"` + # When using ansi2knr, U may be empty or an underscore; expand it + U=`sed -n 's/^U = //p' < "$mf"` + # Find all dependency output files, they are included files with + # $(DEPDIR) in their names. We invoke sed twice because it is the + # simplest approach to changing $(DEPDIR) to its actual value in the + # expansion. + for file in `sed -n " + s/^$am__include $am__quote\(.*(DEPDIR).*\)$am__quote"'$/\1/p' <"$mf" | \ + sed -e 's/\$(DEPDIR)/'"$DEPDIR"'/g' -e 's/\$U/'"$U"'/g'`; do + # Make sure the directory exists. + test -f "$dirpart/$file" && continue + fdir=`AS_DIRNAME(["$file"])` + AS_MKDIR_P([$dirpart/$fdir]) + # echo "creating $dirpart/$file" + echo '# dummy' > "$dirpart/$file" + done + done +} +])# _AM_OUTPUT_DEPENDENCY_COMMANDS + + +# AM_OUTPUT_DEPENDENCY_COMMANDS +# ----------------------------- +# This macro should only be invoked once -- use via AC_REQUIRE. +# +# This code is only required when automatic dependency tracking +# is enabled. FIXME. This creates each `.P' file that we will +# need in order to bootstrap the dependency handling code. +AC_DEFUN([AM_OUTPUT_DEPENDENCY_COMMANDS], +[AC_CONFIG_COMMANDS([depfiles], + [test x"$AMDEP_TRUE" != x"" || _AM_OUTPUT_DEPENDENCY_COMMANDS], + [AMDEP_TRUE="$AMDEP_TRUE" ac_aux_dir="$ac_aux_dir"]) +]) + +# Do all the work for Automake. -*- Autoconf -*- + +# Copyright (C) 1996, 1997, 1998, 1999, 2000, 2001, 2002, 2003, 2004, +# 2005, 2006, 2008, 2009 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 16 + +# This macro actually does too much. Some checks are only needed if +# your package does certain things. But this isn't really a big deal. + +# AM_INIT_AUTOMAKE(PACKAGE, VERSION, [NO-DEFINE]) +# AM_INIT_AUTOMAKE([OPTIONS]) +# ----------------------------------------------- +# The call with PACKAGE and VERSION arguments is the old style +# call (pre autoconf-2.50), which is being phased out. PACKAGE +# and VERSION should now be passed to AC_INIT and removed from +# the call to AM_INIT_AUTOMAKE. +# We support both call styles for the transition. After +# the next Automake release, Autoconf can make the AC_INIT +# arguments mandatory, and then we can depend on a new Autoconf +# release and drop the old call support. +AC_DEFUN([AM_INIT_AUTOMAKE], +[AC_PREREQ([2.62])dnl +dnl Autoconf wants to disallow AM_ names. We explicitly allow +dnl the ones we care about. +m4_pattern_allow([^AM_[A-Z]+FLAGS$])dnl +AC_REQUIRE([AM_SET_CURRENT_AUTOMAKE_VERSION])dnl +AC_REQUIRE([AC_PROG_INSTALL])dnl +if test "`cd $srcdir && pwd`" != "`pwd`"; then + # Use -I$(srcdir) only when $(srcdir) != ., so that make's output + # is not polluted with repeated "-I." + AC_SUBST([am__isrc], [' -I$(srcdir)'])_AM_SUBST_NOTMAKE([am__isrc])dnl + # test to see if srcdir already configured + if test -f $srcdir/config.status; then + AC_MSG_ERROR([source directory already configured; run "make distclean" there first]) + fi +fi + +# test whether we have cygpath +if test -z "$CYGPATH_W"; then + if (cygpath --version) >/dev/null 2>/dev/null; then + CYGPATH_W='cygpath -w' + else + CYGPATH_W=echo + fi +fi +AC_SUBST([CYGPATH_W]) + +# Define the identity of the package. +dnl Distinguish between old-style and new-style calls. +m4_ifval([$2], +[m4_ifval([$3], [_AM_SET_OPTION([no-define])])dnl + AC_SUBST([PACKAGE], [$1])dnl + AC_SUBST([VERSION], [$2])], +[_AM_SET_OPTIONS([$1])dnl +dnl Diagnose old-style AC_INIT with new-style AM_AUTOMAKE_INIT. +m4_if(m4_ifdef([AC_PACKAGE_NAME], 1)m4_ifdef([AC_PACKAGE_VERSION], 1), 11,, + [m4_fatal([AC_INIT should be called with package and version arguments])])dnl + AC_SUBST([PACKAGE], ['AC_PACKAGE_TARNAME'])dnl + AC_SUBST([VERSION], ['AC_PACKAGE_VERSION'])])dnl + +_AM_IF_OPTION([no-define],, +[AC_DEFINE_UNQUOTED(PACKAGE, "$PACKAGE", [Name of package]) + AC_DEFINE_UNQUOTED(VERSION, "$VERSION", [Version number of package])])dnl + +# Some tools Automake needs. +AC_REQUIRE([AM_SANITY_CHECK])dnl +AC_REQUIRE([AC_ARG_PROGRAM])dnl +AM_MISSING_PROG(ACLOCAL, aclocal-${am__api_version}) +AM_MISSING_PROG(AUTOCONF, autoconf) +AM_MISSING_PROG(AUTOMAKE, automake-${am__api_version}) +AM_MISSING_PROG(AUTOHEADER, autoheader) +AM_MISSING_PROG(MAKEINFO, makeinfo) +AC_REQUIRE([AM_PROG_INSTALL_SH])dnl +AC_REQUIRE([AM_PROG_INSTALL_STRIP])dnl +AC_REQUIRE([AM_PROG_MKDIR_P])dnl +# We need awk for the "check" target. The system "awk" is bad on +# some platforms. +AC_REQUIRE([AC_PROG_AWK])dnl +AC_REQUIRE([AC_PROG_MAKE_SET])dnl +AC_REQUIRE([AM_SET_LEADING_DOT])dnl +_AM_IF_OPTION([tar-ustar], [_AM_PROG_TAR([ustar])], + [_AM_IF_OPTION([tar-pax], [_AM_PROG_TAR([pax])], + [_AM_PROG_TAR([v7])])]) +_AM_IF_OPTION([no-dependencies],, +[AC_PROVIDE_IFELSE([AC_PROG_CC], + [_AM_DEPENDENCIES(CC)], + [define([AC_PROG_CC], + defn([AC_PROG_CC])[_AM_DEPENDENCIES(CC)])])dnl +AC_PROVIDE_IFELSE([AC_PROG_CXX], + [_AM_DEPENDENCIES(CXX)], + [define([AC_PROG_CXX], + defn([AC_PROG_CXX])[_AM_DEPENDENCIES(CXX)])])dnl +AC_PROVIDE_IFELSE([AC_PROG_OBJC], + [_AM_DEPENDENCIES(OBJC)], + [define([AC_PROG_OBJC], + defn([AC_PROG_OBJC])[_AM_DEPENDENCIES(OBJC)])])dnl +]) +_AM_IF_OPTION([silent-rules], [AC_REQUIRE([AM_SILENT_RULES])])dnl +dnl The `parallel-tests' driver may need to know about EXEEXT, so add the +dnl `am__EXEEXT' conditional if _AM_COMPILER_EXEEXT was seen. This macro +dnl is hooked onto _AC_COMPILER_EXEEXT early, see below. +AC_CONFIG_COMMANDS_PRE(dnl +[m4_provide_if([_AM_COMPILER_EXEEXT], + [AM_CONDITIONAL([am__EXEEXT], [test -n "$EXEEXT"])])])dnl +]) + +dnl Hook into `_AC_COMPILER_EXEEXT' early to learn its expansion. Do not +dnl add the conditional right here, as _AC_COMPILER_EXEEXT may be further +dnl mangled by Autoconf and run in a shell conditional statement. +m4_define([_AC_COMPILER_EXEEXT], +m4_defn([_AC_COMPILER_EXEEXT])[m4_provide([_AM_COMPILER_EXEEXT])]) + + +# When config.status generates a header, we must update the stamp-h file. +# This file resides in the same directory as the config header +# that is generated. The stamp files are numbered to have different names. + +# Autoconf calls _AC_AM_CONFIG_HEADER_HOOK (when defined) in the +# loop where config.status creates the headers, so we can generate +# our stamp files there. +AC_DEFUN([_AC_AM_CONFIG_HEADER_HOOK], +[# Compute $1's index in $config_headers. +_am_arg=$1 +_am_stamp_count=1 +for _am_header in $config_headers :; do + case $_am_header in + $_am_arg | $_am_arg:* ) + break ;; + * ) + _am_stamp_count=`expr $_am_stamp_count + 1` ;; + esac +done +echo "timestamp for $_am_arg" >`AS_DIRNAME(["$_am_arg"])`/stamp-h[]$_am_stamp_count]) + +# Copyright (C) 2001, 2003, 2005, 2008 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# AM_PROG_INSTALL_SH +# ------------------ +# Define $install_sh. +AC_DEFUN([AM_PROG_INSTALL_SH], +[AC_REQUIRE([AM_AUX_DIR_EXPAND])dnl +if test x"${install_sh}" != xset; then + case $am_aux_dir in + *\ * | *\ *) + install_sh="\${SHELL} '$am_aux_dir/install-sh'" ;; + *) + install_sh="\${SHELL} $am_aux_dir/install-sh" + esac +fi +AC_SUBST(install_sh)]) + +# Copyright (C) 2003, 2005 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 2 + +# Check whether the underlying file-system supports filenames +# with a leading dot. For instance MS-DOS doesn't. +AC_DEFUN([AM_SET_LEADING_DOT], +[rm -rf .tst 2>/dev/null +mkdir .tst 2>/dev/null +if test -d .tst; then + am__leading_dot=. +else + am__leading_dot=_ +fi +rmdir .tst 2>/dev/null +AC_SUBST([am__leading_dot])]) + +# Check to see how 'make' treats includes. -*- Autoconf -*- + +# Copyright (C) 2001, 2002, 2003, 2005, 2009 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 4 + +# AM_MAKE_INCLUDE() +# ----------------- +# Check to see how make treats includes. +AC_DEFUN([AM_MAKE_INCLUDE], +[am_make=${MAKE-make} +cat > confinc << 'END' +am__doit: + @echo this is the am__doit target +.PHONY: am__doit +END +# If we don't find an include directive, just comment out the code. +AC_MSG_CHECKING([for style of include used by $am_make]) +am__include="#" +am__quote= +_am_result=none +# First try GNU make style include. +echo "include confinc" > confmf +# Ignore all kinds of additional output from `make'. +case `$am_make -s -f confmf 2> /dev/null` in #( +*the\ am__doit\ target*) + am__include=include + am__quote= + _am_result=GNU + ;; +esac +# Now try BSD make style include. +if test "$am__include" = "#"; then + echo '.include "confinc"' > confmf + case `$am_make -s -f confmf 2> /dev/null` in #( + *the\ am__doit\ target*) + am__include=.include + am__quote="\"" + _am_result=BSD + ;; + esac +fi +AC_SUBST([am__include]) +AC_SUBST([am__quote]) +AC_MSG_RESULT([$_am_result]) +rm -f confinc confmf +]) + +# Copyright (C) 1999, 2000, 2001, 2003, 2004, 2005, 2008 +# Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 6 + +# AM_PROG_CC_C_O +# -------------- +# Like AC_PROG_CC_C_O, but changed for automake. +AC_DEFUN([AM_PROG_CC_C_O], +[AC_REQUIRE([AC_PROG_CC_C_O])dnl +AC_REQUIRE([AM_AUX_DIR_EXPAND])dnl +AC_REQUIRE_AUX_FILE([compile])dnl +# FIXME: we rely on the cache variable name because +# there is no other way. +set dummy $CC +am_cc=`echo $[2] | sed ['s/[^a-zA-Z0-9_]/_/g;s/^[0-9]/_/']` +eval am_t=\$ac_cv_prog_cc_${am_cc}_c_o +if test "$am_t" != yes; then + # Losing compiler, so override with the script. + # FIXME: It is wrong to rewrite CC. + # But if we don't then we get into trouble of one sort or another. + # A longer-term fix would be to have automake use am__CC in this case, + # and then we could set am__CC="\$(top_srcdir)/compile \$(CC)" + CC="$am_aux_dir/compile $CC" +fi +dnl Make sure AC_PROG_CC is never called again, or it will override our +dnl setting of CC. +m4_define([AC_PROG_CC], + [m4_fatal([AC_PROG_CC cannot be called after AM_PROG_CC_C_O])]) +]) + +# Fake the existence of programs that GNU maintainers use. -*- Autoconf -*- + +# Copyright (C) 1997, 1999, 2000, 2001, 2003, 2004, 2005, 2008 +# Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 6 + +# AM_MISSING_PROG(NAME, PROGRAM) +# ------------------------------ +AC_DEFUN([AM_MISSING_PROG], +[AC_REQUIRE([AM_MISSING_HAS_RUN]) +$1=${$1-"${am_missing_run}$2"} +AC_SUBST($1)]) + + +# AM_MISSING_HAS_RUN +# ------------------ +# Define MISSING if not defined so far and test if it supports --run. +# If it does, set am_missing_run to use it, otherwise, to nothing. +AC_DEFUN([AM_MISSING_HAS_RUN], +[AC_REQUIRE([AM_AUX_DIR_EXPAND])dnl +AC_REQUIRE_AUX_FILE([missing])dnl +if test x"${MISSING+set}" != xset; then + case $am_aux_dir in + *\ * | *\ *) + MISSING="\${SHELL} \"$am_aux_dir/missing\"" ;; + *) + MISSING="\${SHELL} $am_aux_dir/missing" ;; + esac +fi +# Use eval to expand $SHELL +if eval "$MISSING --run true"; then + am_missing_run="$MISSING --run " +else + am_missing_run= + AC_MSG_WARN([`missing' script is too old or missing]) +fi +]) + +# Copyright (C) 2003, 2004, 2005, 2006 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# AM_PROG_MKDIR_P +# --------------- +# Check for `mkdir -p'. +AC_DEFUN([AM_PROG_MKDIR_P], +[AC_PREREQ([2.60])dnl +AC_REQUIRE([AC_PROG_MKDIR_P])dnl +dnl Automake 1.8 to 1.9.6 used to define mkdir_p. We now use MKDIR_P, +dnl while keeping a definition of mkdir_p for backward compatibility. +dnl @MKDIR_P@ is magic: AC_OUTPUT adjusts its value for each Makefile. +dnl However we cannot define mkdir_p as $(MKDIR_P) for the sake of +dnl Makefile.ins that do not define MKDIR_P, so we do our own +dnl adjustment using top_builddir (which is defined more often than +dnl MKDIR_P). +AC_SUBST([mkdir_p], ["$MKDIR_P"])dnl +case $mkdir_p in + [[\\/$]]* | ?:[[\\/]]*) ;; + */*) mkdir_p="\$(top_builddir)/$mkdir_p" ;; +esac +]) + +# Helper functions for option handling. -*- Autoconf -*- + +# Copyright (C) 2001, 2002, 2003, 2005, 2008 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 4 + +# _AM_MANGLE_OPTION(NAME) +# ----------------------- +AC_DEFUN([_AM_MANGLE_OPTION], +[[_AM_OPTION_]m4_bpatsubst($1, [[^a-zA-Z0-9_]], [_])]) + +# _AM_SET_OPTION(NAME) +# ------------------------------ +# Set option NAME. Presently that only means defining a flag for this option. +AC_DEFUN([_AM_SET_OPTION], +[m4_define(_AM_MANGLE_OPTION([$1]), 1)]) + +# _AM_SET_OPTIONS(OPTIONS) +# ---------------------------------- +# OPTIONS is a space-separated list of Automake options. +AC_DEFUN([_AM_SET_OPTIONS], +[m4_foreach_w([_AM_Option], [$1], [_AM_SET_OPTION(_AM_Option)])]) + +# _AM_IF_OPTION(OPTION, IF-SET, [IF-NOT-SET]) +# ------------------------------------------- +# Execute IF-SET if OPTION is set, IF-NOT-SET otherwise. +AC_DEFUN([_AM_IF_OPTION], +[m4_ifset(_AM_MANGLE_OPTION([$1]), [$2], [$3])]) + +# Check to make sure that the build environment is sane. -*- Autoconf -*- + +# Copyright (C) 1996, 1997, 2000, 2001, 2003, 2005, 2008 +# Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 5 + +# AM_SANITY_CHECK +# --------------- +AC_DEFUN([AM_SANITY_CHECK], +[AC_MSG_CHECKING([whether build environment is sane]) +# Just in case +sleep 1 +echo timestamp > conftest.file +# Reject unsafe characters in $srcdir or the absolute working directory +# name. Accept space and tab only in the latter. +am_lf=' +' +case `pwd` in + *[[\\\"\#\$\&\'\`$am_lf]]*) + AC_MSG_ERROR([unsafe absolute working directory name]);; +esac +case $srcdir in + *[[\\\"\#\$\&\'\`$am_lf\ \ ]]*) + AC_MSG_ERROR([unsafe srcdir value: `$srcdir']);; +esac + +# Do `set' in a subshell so we don't clobber the current shell's +# arguments. Must try -L first in case configure is actually a +# symlink; some systems play weird games with the mod time of symlinks +# (eg FreeBSD returns the mod time of the symlink's containing +# directory). +if ( + set X `ls -Lt "$srcdir/configure" conftest.file 2> /dev/null` + if test "$[*]" = "X"; then + # -L didn't work. + set X `ls -t "$srcdir/configure" conftest.file` + fi + rm -f conftest.file + if test "$[*]" != "X $srcdir/configure conftest.file" \ + && test "$[*]" != "X conftest.file $srcdir/configure"; then + + # If neither matched, then we have a broken ls. This can happen + # if, for instance, CONFIG_SHELL is bash and it inherits a + # broken ls alias from the environment. This has actually + # happened. Such a system could not be considered "sane". + AC_MSG_ERROR([ls -t appears to fail. Make sure there is not a broken +alias in your environment]) + fi + + test "$[2]" = conftest.file + ) +then + # Ok. + : +else + AC_MSG_ERROR([newly created file is older than distributed files! +Check your system clock]) +fi +AC_MSG_RESULT(yes)]) + +# Copyright (C) 2009 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 1 + +# AM_SILENT_RULES([DEFAULT]) +# -------------------------- +# Enable less verbose build rules; with the default set to DEFAULT +# (`yes' being less verbose, `no' or empty being verbose). +AC_DEFUN([AM_SILENT_RULES], +[AC_ARG_ENABLE([silent-rules], +[ --enable-silent-rules less verbose build output (undo: `make V=1') + --disable-silent-rules verbose build output (undo: `make V=0')]) +case $enable_silent_rules in +yes) AM_DEFAULT_VERBOSITY=0;; +no) AM_DEFAULT_VERBOSITY=1;; +*) AM_DEFAULT_VERBOSITY=m4_if([$1], [yes], [0], [1]);; +esac +AC_SUBST([AM_DEFAULT_VERBOSITY])dnl +AM_BACKSLASH='\' +AC_SUBST([AM_BACKSLASH])dnl +_AM_SUBST_NOTMAKE([AM_BACKSLASH])dnl +]) + +# Copyright (C) 2001, 2003, 2005 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# AM_PROG_INSTALL_STRIP +# --------------------- +# One issue with vendor `install' (even GNU) is that you can't +# specify the program used to strip binaries. This is especially +# annoying in cross-compiling environments, where the build's strip +# is unlikely to handle the host's binaries. +# Fortunately install-sh will honor a STRIPPROG variable, so we +# always use install-sh in `make install-strip', and initialize +# STRIPPROG with the value of the STRIP variable (set by the user). +AC_DEFUN([AM_PROG_INSTALL_STRIP], +[AC_REQUIRE([AM_PROG_INSTALL_SH])dnl +# Installed binaries are usually stripped using `strip' when the user +# run `make install-strip'. However `strip' might not be the right +# tool to use in cross-compilation environments, therefore Automake +# will honor the `STRIP' environment variable to overrule this program. +dnl Don't test for $cross_compiling = yes, because it might be `maybe'. +if test "$cross_compiling" != no; then + AC_CHECK_TOOL([STRIP], [strip], :) +fi +INSTALL_STRIP_PROGRAM="\$(install_sh) -c -s" +AC_SUBST([INSTALL_STRIP_PROGRAM])]) + +# Copyright (C) 2006, 2008 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 2 + +# _AM_SUBST_NOTMAKE(VARIABLE) +# --------------------------- +# Prevent Automake from outputting VARIABLE = @VARIABLE@ in Makefile.in. +# This macro is traced by Automake. +AC_DEFUN([_AM_SUBST_NOTMAKE]) + +# AM_SUBST_NOTMAKE(VARIABLE) +# --------------------------- +# Public sister of _AM_SUBST_NOTMAKE. +AC_DEFUN([AM_SUBST_NOTMAKE], [_AM_SUBST_NOTMAKE($@)]) + +# Check how to create a tarball. -*- Autoconf -*- + +# Copyright (C) 2004, 2005 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# serial 2 + +# _AM_PROG_TAR(FORMAT) +# -------------------- +# Check how to create a tarball in format FORMAT. +# FORMAT should be one of `v7', `ustar', or `pax'. +# +# Substitute a variable $(am__tar) that is a command +# writing to stdout a FORMAT-tarball containing the directory +# $tardir. +# tardir=directory && $(am__tar) > result.tar +# +# Substitute a variable $(am__untar) that extract such +# a tarball read from stdin. +# $(am__untar) < result.tar +AC_DEFUN([_AM_PROG_TAR], +[# Always define AMTAR for backward compatibility. +AM_MISSING_PROG([AMTAR], [tar]) +m4_if([$1], [v7], + [am__tar='${AMTAR} chof - "$$tardir"'; am__untar='${AMTAR} xf -'], + [m4_case([$1], [ustar],, [pax],, + [m4_fatal([Unknown tar format])]) +AC_MSG_CHECKING([how to create a $1 tar archive]) +# Loop over all known methods to create a tar archive until one works. +_am_tools='gnutar m4_if([$1], [ustar], [plaintar]) pax cpio none' +_am_tools=${am_cv_prog_tar_$1-$_am_tools} +# Do not fold the above two line into one, because Tru64 sh and +# Solaris sh will not grok spaces in the rhs of `-'. +for _am_tool in $_am_tools +do + case $_am_tool in + gnutar) + for _am_tar in tar gnutar gtar; + do + AM_RUN_LOG([$_am_tar --version]) && break + done + am__tar="$_am_tar --format=m4_if([$1], [pax], [posix], [$1]) -chf - "'"$$tardir"' + am__tar_="$_am_tar --format=m4_if([$1], [pax], [posix], [$1]) -chf - "'"$tardir"' + am__untar="$_am_tar -xf -" + ;; + plaintar) + # Must skip GNU tar: if it does not support --format= it doesn't create + # ustar tarball either. + (tar --version) >/dev/null 2>&1 && continue + am__tar='tar chf - "$$tardir"' + am__tar_='tar chf - "$tardir"' + am__untar='tar xf -' + ;; + pax) + am__tar='pax -L -x $1 -w "$$tardir"' + am__tar_='pax -L -x $1 -w "$tardir"' + am__untar='pax -r' + ;; + cpio) + am__tar='find "$$tardir" -print | cpio -o -H $1 -L' + am__tar_='find "$tardir" -print | cpio -o -H $1 -L' + am__untar='cpio -i -H $1 -d' + ;; + none) + am__tar=false + am__tar_=false + am__untar=false + ;; + esac + + # If the value was cached, stop now. We just wanted to have am__tar + # and am__untar set. + test -n "${am_cv_prog_tar_$1}" && break + + # tar/untar a dummy directory, and stop if the command works + rm -rf conftest.dir + mkdir conftest.dir + echo GrepMe > conftest.dir/file + AM_RUN_LOG([tardir=conftest.dir && eval $am__tar_ >conftest.tar]) + rm -rf conftest.dir + if test -s conftest.tar; then + AM_RUN_LOG([$am__untar /dev/null 2>&1 && break + fi +done +rm -rf conftest.dir + +AC_CACHE_VAL([am_cv_prog_tar_$1], [am_cv_prog_tar_$1=$_am_tool]) +AC_MSG_RESULT([$am_cv_prog_tar_$1])]) +AC_SUBST([am__tar]) +AC_SUBST([am__untar]) +]) # _AM_PROG_TAR + diff --git a/misc/tools/kconfig-frontends/bootstrap b/misc/tools/kconfig-frontends/bootstrap new file mode 100755 index 0000000000..b9dcbaf622 --- /dev/null +++ b/misc/tools/kconfig-frontends/bootstrap @@ -0,0 +1,22 @@ +#!/bin/sh +set -e + +printf "Running libtoolize...\n" +libtoolize --copy --force + +printf "Running aclocal...\n" +aclocal -Wall --force + +printf "Running autoconf...\n" +autoconf -Wall --force + +printf "Running autoheader...\n" +autoheader -Wall --force + +printf "Running automake...\n" +automake --foreign --add-missing --copy -Wall --force + +# Cleanup the mess... :-( +rm -rf autom4te.cache + +printf "Done. You may now run:\n ./configure\n" diff --git a/misc/tools/kconfig-frontends/configure b/misc/tools/kconfig-frontends/configure new file mode 100755 index 0000000000..ad26f3f9d7 --- /dev/null +++ b/misc/tools/kconfig-frontends/configure @@ -0,0 +1,20052 @@ +#! /bin/sh +# Guess values for system-dependent variables and create Makefiles. +# Generated by GNU Autoconf 2.67 for kconfig-frontends 3.6.0-0. +# +# Report bugs to . +# +# +# Copyright (C) 1992, 1993, 1994, 1995, 1996, 1998, 1999, 2000, 2001, +# 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010 Free Software +# Foundation, Inc. +# +# +# This configure script is free software; the Free Software Foundation +# gives unlimited permission to copy, distribute and modify it. +## -------------------- ## +## M4sh Initialization. ## +## -------------------- ## + +# Be more Bourne compatible +DUALCASE=1; export DUALCASE # for MKS sh +if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then : + emulate sh + NULLCMD=: + # Pre-4.2 versions of Zsh do word splitting on ${1+"$@"}, which + # is contrary to our usage. Disable this feature. + alias -g '${1+"$@"}'='"$@"' + setopt NO_GLOB_SUBST +else + case `(set -o) 2>/dev/null` in #( + *posix*) : + set -o posix ;; #( + *) : + ;; +esac +fi + + +as_nl=' +' +export as_nl +# Printing a long string crashes Solaris 7 /usr/bin/printf. +as_echo='\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\' +as_echo=$as_echo$as_echo$as_echo$as_echo$as_echo +as_echo=$as_echo$as_echo$as_echo$as_echo$as_echo$as_echo +# Prefer a ksh shell builtin over an external printf program on Solaris, +# but without wasting forks for bash or zsh. +if test -z "$BASH_VERSION$ZSH_VERSION" \ + && (test "X`print -r -- $as_echo`" = "X$as_echo") 2>/dev/null; then + as_echo='print -r --' + as_echo_n='print -rn --' +elif (test "X`printf %s $as_echo`" = "X$as_echo") 2>/dev/null; then + as_echo='printf %s\n' + as_echo_n='printf %s' +else + if test "X`(/usr/ucb/echo -n -n $as_echo) 2>/dev/null`" = "X-n $as_echo"; then + as_echo_body='eval /usr/ucb/echo -n "$1$as_nl"' + as_echo_n='/usr/ucb/echo -n' + else + as_echo_body='eval expr "X$1" : "X\\(.*\\)"' + as_echo_n_body='eval + arg=$1; + case $arg in #( + *"$as_nl"*) + expr "X$arg" : "X\\(.*\\)$as_nl"; + arg=`expr "X$arg" : ".*$as_nl\\(.*\\)"`;; + esac; + expr "X$arg" : "X\\(.*\\)" | tr -d "$as_nl" + ' + export as_echo_n_body + as_echo_n='sh -c $as_echo_n_body as_echo' + fi + export as_echo_body + as_echo='sh -c $as_echo_body as_echo' +fi + +# The user is always right. +if test "${PATH_SEPARATOR+set}" != set; then + PATH_SEPARATOR=: + (PATH='/bin;/bin'; FPATH=$PATH; sh -c :) >/dev/null 2>&1 && { + (PATH='/bin:/bin'; FPATH=$PATH; sh -c :) >/dev/null 2>&1 || + PATH_SEPARATOR=';' + } +fi + + +# IFS +# We need space, tab and new line, in precisely that order. Quoting is +# there to prevent editors from complaining about space-tab. +# (If _AS_PATH_WALK were called with IFS unset, it would disable word +# splitting by setting IFS to empty value.) +IFS=" "" $as_nl" + +# Find who we are. Look in the path if we contain no directory separator. +case $0 in #(( + *[\\/]* ) as_myself=$0 ;; + *) as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + test -r "$as_dir/$0" && as_myself=$as_dir/$0 && break + done +IFS=$as_save_IFS + + ;; +esac +# We did not find ourselves, most probably we were run as `sh COMMAND' +# in which case we are not to be found in the path. +if test "x$as_myself" = x; then + as_myself=$0 +fi +if test ! -f "$as_myself"; then + $as_echo "$as_myself: error: cannot find myself; rerun with an absolute file name" >&2 + exit 1 +fi + +# Unset variables that we do not need and which cause bugs (e.g. in +# pre-3.0 UWIN ksh). But do not cause bugs in bash 2.01; the "|| exit 1" +# suppresses any "Segmentation fault" message there. '((' could +# trigger a bug in pdksh 5.2.14. +for as_var in BASH_ENV ENV MAIL MAILPATH +do eval test x\${$as_var+set} = xset \ + && ( (unset $as_var) || exit 1) >/dev/null 2>&1 && unset $as_var || : +done +PS1='$ ' +PS2='> ' +PS4='+ ' + +# NLS nuisances. +LC_ALL=C +export LC_ALL +LANGUAGE=C +export LANGUAGE + +# CDPATH. +(unset CDPATH) >/dev/null 2>&1 && unset CDPATH + +if test "x$CONFIG_SHELL" = x; then + as_bourne_compatible="if test -n \"\${ZSH_VERSION+set}\" && (emulate sh) >/dev/null 2>&1; then : + emulate sh + NULLCMD=: + # Pre-4.2 versions of Zsh do word splitting on \${1+\"\$@\"}, which + # is contrary to our usage. Disable this feature. + alias -g '\${1+\"\$@\"}'='\"\$@\"' + setopt NO_GLOB_SUBST +else + case \`(set -o) 2>/dev/null\` in #( + *posix*) : + set -o posix ;; #( + *) : + ;; +esac +fi +" + as_required="as_fn_return () { (exit \$1); } +as_fn_success () { as_fn_return 0; } +as_fn_failure () { as_fn_return 1; } +as_fn_ret_success () { return 0; } +as_fn_ret_failure () { return 1; } + +exitcode=0 +as_fn_success || { exitcode=1; echo as_fn_success failed.; } +as_fn_failure && { exitcode=1; echo as_fn_failure succeeded.; } +as_fn_ret_success || { exitcode=1; echo as_fn_ret_success failed.; } +as_fn_ret_failure && { exitcode=1; echo as_fn_ret_failure succeeded.; } +if ( set x; as_fn_ret_success y && test x = \"\$1\" ); then : + +else + exitcode=1; echo positional parameters were not saved. +fi +test x\$exitcode = x0 || exit 1" + as_suggested=" as_lineno_1=";as_suggested=$as_suggested$LINENO;as_suggested=$as_suggested" as_lineno_1a=\$LINENO + as_lineno_2=";as_suggested=$as_suggested$LINENO;as_suggested=$as_suggested" as_lineno_2a=\$LINENO + eval 'test \"x\$as_lineno_1'\$as_run'\" != \"x\$as_lineno_2'\$as_run'\" && + test \"x\`expr \$as_lineno_1'\$as_run' + 1\`\" = \"x\$as_lineno_2'\$as_run'\"' || exit 1 +test \$(( 1 + 1 )) = 2 || exit 1" + if (eval "$as_required") 2>/dev/null; then : + as_have_required=yes +else + as_have_required=no +fi + if test x$as_have_required = xyes && (eval "$as_suggested") 2>/dev/null; then : + +else + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +as_found=false +for as_dir in /bin$PATH_SEPARATOR/usr/bin$PATH_SEPARATOR$PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + as_found=: + case $as_dir in #( + /*) + for as_base in sh bash ksh sh5; do + # Try only shells that exist, to save several forks. + as_shell=$as_dir/$as_base + if { test -f "$as_shell" || test -f "$as_shell.exe"; } && + { $as_echo "$as_bourne_compatible""$as_required" | as_run=a "$as_shell"; } 2>/dev/null; then : + CONFIG_SHELL=$as_shell as_have_required=yes + if { $as_echo "$as_bourne_compatible""$as_suggested" | as_run=a "$as_shell"; } 2>/dev/null; then : + break 2 +fi +fi + done;; + esac + as_found=false +done +$as_found || { if { test -f "$SHELL" || test -f "$SHELL.exe"; } && + { $as_echo "$as_bourne_compatible""$as_required" | as_run=a "$SHELL"; } 2>/dev/null; then : + CONFIG_SHELL=$SHELL as_have_required=yes +fi; } +IFS=$as_save_IFS + + + if test "x$CONFIG_SHELL" != x; then : + # We cannot yet assume a decent shell, so we have to provide a + # neutralization value for shells without unset; and this also + # works around shells that cannot unset nonexistent variables. + BASH_ENV=/dev/null + ENV=/dev/null + (unset BASH_ENV) >/dev/null 2>&1 && unset BASH_ENV ENV + export CONFIG_SHELL + exec "$CONFIG_SHELL" "$as_myself" ${1+"$@"} +fi + + if test x$as_have_required = xno; then : + $as_echo "$0: This script requires a shell more modern than all" + $as_echo "$0: the shells that I found on your system." + if test x${ZSH_VERSION+set} = xset ; then + $as_echo "$0: In particular, zsh $ZSH_VERSION has bugs and should" + $as_echo "$0: be upgraded to zsh 4.3.4 or later." + else + $as_echo "$0: Please tell bug-autoconf@gnu.org and +$0: yann.morin.1998@free.fr about your system, including +$0: any error possibly output before this message. Then +$0: install a modern shell, or manually run the script +$0: under such a shell if you do have one." + fi + exit 1 +fi +fi +fi +SHELL=${CONFIG_SHELL-/bin/sh} +export SHELL +# Unset more variables known to interfere with behavior of common tools. +CLICOLOR_FORCE= GREP_OPTIONS= +unset CLICOLOR_FORCE GREP_OPTIONS + +## --------------------- ## +## M4sh Shell Functions. ## +## --------------------- ## +# as_fn_unset VAR +# --------------- +# Portably unset VAR. +as_fn_unset () +{ + { eval $1=; unset $1;} +} +as_unset=as_fn_unset + +# as_fn_set_status STATUS +# ----------------------- +# Set $? to STATUS, without forking. +as_fn_set_status () +{ + return $1 +} # as_fn_set_status + +# as_fn_exit STATUS +# ----------------- +# Exit the shell with STATUS, even in a "trap 0" or "set -e" context. +as_fn_exit () +{ + set +e + as_fn_set_status $1 + exit $1 +} # as_fn_exit + +# as_fn_mkdir_p +# ------------- +# Create "$as_dir" as a directory, including parents if necessary. +as_fn_mkdir_p () +{ + + case $as_dir in #( + -*) as_dir=./$as_dir;; + esac + test -d "$as_dir" || eval $as_mkdir_p || { + as_dirs= + while :; do + case $as_dir in #( + *\'*) as_qdir=`$as_echo "$as_dir" | sed "s/'/'\\\\\\\\''/g"`;; #'( + *) as_qdir=$as_dir;; + esac + as_dirs="'$as_qdir' $as_dirs" + as_dir=`$as_dirname -- "$as_dir" || +$as_expr X"$as_dir" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \ + X"$as_dir" : 'X\(//\)[^/]' \| \ + X"$as_dir" : 'X\(//\)$' \| \ + X"$as_dir" : 'X\(/\)' \| . 2>/dev/null || +$as_echo X"$as_dir" | + sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ + s//\1/ + q + } + /^X\(\/\/\)[^/].*/{ + s//\1/ + q + } + /^X\(\/\/\)$/{ + s//\1/ + q + } + /^X\(\/\).*/{ + s//\1/ + q + } + s/.*/./; q'` + test -d "$as_dir" && break + done + test -z "$as_dirs" || eval "mkdir $as_dirs" + } || test -d "$as_dir" || as_fn_error $? "cannot create directory $as_dir" + + +} # as_fn_mkdir_p +# as_fn_append VAR VALUE +# ---------------------- +# Append the text in VALUE to the end of the definition contained in VAR. Take +# advantage of any shell optimizations that allow amortized linear growth over +# repeated appends, instead of the typical quadratic growth present in naive +# implementations. +if (eval "as_var=1; as_var+=2; test x\$as_var = x12") 2>/dev/null; then : + eval 'as_fn_append () + { + eval $1+=\$2 + }' +else + as_fn_append () + { + eval $1=\$$1\$2 + } +fi # as_fn_append + +# as_fn_arith ARG... +# ------------------ +# Perform arithmetic evaluation on the ARGs, and store the result in the +# global $as_val. Take advantage of shells that can avoid forks. The arguments +# must be portable across $(()) and expr. +if (eval "test \$(( 1 + 1 )) = 2") 2>/dev/null; then : + eval 'as_fn_arith () + { + as_val=$(( $* )) + }' +else + as_fn_arith () + { + as_val=`expr "$@" || test $? -eq 1` + } +fi # as_fn_arith + + +# as_fn_error STATUS ERROR [LINENO LOG_FD] +# ---------------------------------------- +# Output "`basename $0`: error: ERROR" to stderr. If LINENO and LOG_FD are +# provided, also output the error to LOG_FD, referencing LINENO. Then exit the +# script with STATUS, using 1 if that was 0. +as_fn_error () +{ + as_status=$1; test $as_status -eq 0 && as_status=1 + if test "$4"; then + as_lineno=${as_lineno-"$3"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + $as_echo "$as_me:${as_lineno-$LINENO}: error: $2" >&$4 + fi + $as_echo "$as_me: error: $2" >&2 + as_fn_exit $as_status +} # as_fn_error + +if expr a : '\(a\)' >/dev/null 2>&1 && + test "X`expr 00001 : '.*\(...\)'`" = X001; then + as_expr=expr +else + as_expr=false +fi + +if (basename -- /) >/dev/null 2>&1 && test "X`basename -- / 2>&1`" = "X/"; then + as_basename=basename +else + as_basename=false +fi + +if (as_dir=`dirname -- /` && test "X$as_dir" = X/) >/dev/null 2>&1; then + as_dirname=dirname +else + as_dirname=false +fi + +as_me=`$as_basename -- "$0" || +$as_expr X/"$0" : '.*/\([^/][^/]*\)/*$' \| \ + X"$0" : 'X\(//\)$' \| \ + X"$0" : 'X\(/\)' \| . 2>/dev/null || +$as_echo X/"$0" | + sed '/^.*\/\([^/][^/]*\)\/*$/{ + s//\1/ + q + } + /^X\/\(\/\/\)$/{ + s//\1/ + q + } + /^X\/\(\/\).*/{ + s//\1/ + q + } + s/.*/./; q'` + +# Avoid depending upon Character Ranges. +as_cr_letters='abcdefghijklmnopqrstuvwxyz' +as_cr_LETTERS='ABCDEFGHIJKLMNOPQRSTUVWXYZ' +as_cr_Letters=$as_cr_letters$as_cr_LETTERS +as_cr_digits='0123456789' +as_cr_alnum=$as_cr_Letters$as_cr_digits + + + as_lineno_1=$LINENO as_lineno_1a=$LINENO + as_lineno_2=$LINENO as_lineno_2a=$LINENO + eval 'test "x$as_lineno_1'$as_run'" != "x$as_lineno_2'$as_run'" && + test "x`expr $as_lineno_1'$as_run' + 1`" = "x$as_lineno_2'$as_run'"' || { + # Blame Lee E. McMahon (1931-1989) for sed's syntax. :-) + sed -n ' + p + /[$]LINENO/= + ' <$as_myself | + sed ' + s/[$]LINENO.*/&-/ + t lineno + b + :lineno + N + :loop + s/[$]LINENO\([^'$as_cr_alnum'_].*\n\)\(.*\)/\2\1\2/ + t loop + s/-\n.*// + ' >$as_me.lineno && + chmod +x "$as_me.lineno" || + { $as_echo "$as_me: error: cannot create $as_me.lineno; rerun with a POSIX shell" >&2; as_fn_exit 1; } + + # Don't try to exec as it changes $[0], causing all sort of problems + # (the dirname of $[0] is not the place where we might find the + # original and so on. Autoconf is especially sensitive to this). + . "./$as_me.lineno" + # Exit status is that of the last command. + exit +} + +ECHO_C= ECHO_N= ECHO_T= +case `echo -n x` in #((((( +-n*) + case `echo 'xy\c'` in + *c*) ECHO_T=' ';; # ECHO_T is single tab character. + xy) ECHO_C='\c';; + *) echo `echo ksh88 bug on AIX 6.1` > /dev/null + ECHO_T=' ';; + esac;; +*) + ECHO_N='-n';; +esac + +rm -f conf$$ conf$$.exe conf$$.file +if test -d conf$$.dir; then + rm -f conf$$.dir/conf$$.file +else + rm -f conf$$.dir + mkdir conf$$.dir 2>/dev/null +fi +if (echo >conf$$.file) 2>/dev/null; then + if ln -s conf$$.file conf$$ 2>/dev/null; then + as_ln_s='ln -s' + # ... but there are two gotchas: + # 1) On MSYS, both `ln -s file dir' and `ln file dir' fail. + # 2) DJGPP < 2.04 has no symlinks; `ln -s' creates a wrapper executable. + # In both cases, we have to default to `cp -p'. + ln -s conf$$.file conf$$.dir 2>/dev/null && test ! -f conf$$.exe || + as_ln_s='cp -p' + elif ln conf$$.file conf$$ 2>/dev/null; then + as_ln_s=ln + else + as_ln_s='cp -p' + fi +else + as_ln_s='cp -p' +fi +rm -f conf$$ conf$$.exe conf$$.dir/conf$$.file conf$$.file +rmdir conf$$.dir 2>/dev/null + +if mkdir -p . 2>/dev/null; then + as_mkdir_p='mkdir -p "$as_dir"' +else + test -d ./-p && rmdir ./-p + as_mkdir_p=false +fi + +if test -x / >/dev/null 2>&1; then + as_test_x='test -x' +else + if ls -dL / >/dev/null 2>&1; then + as_ls_L_option=L + else + as_ls_L_option= + fi + as_test_x=' + eval sh -c '\'' + if test -d "$1"; then + test -d "$1/."; + else + case $1 in #( + -*)set "./$1";; + esac; + case `ls -ld'$as_ls_L_option' "$1" 2>/dev/null` in #(( + ???[sx]*):;;*)false;;esac;fi + '\'' sh + ' +fi +as_executable_p=$as_test_x + +# Sed expression to map a string onto a valid CPP name. +as_tr_cpp="eval sed 'y%*$as_cr_letters%P$as_cr_LETTERS%;s%[^_$as_cr_alnum]%_%g'" + +# Sed expression to map a string onto a valid variable name. +as_tr_sh="eval sed 'y%*+%pp%;s%[^_$as_cr_alnum]%_%g'" + + + +# Check that we are running under the correct shell. +SHELL=${CONFIG_SHELL-/bin/sh} + +case X$lt_ECHO in +X*--fallback-echo) + # Remove one level of quotation (which was required for Make). + ECHO=`echo "$lt_ECHO" | sed 's,\\\\\$\\$0,'$0','` + ;; +esac + +ECHO=${lt_ECHO-echo} +if test "X$1" = X--no-reexec; then + # Discard the --no-reexec flag, and continue. + shift +elif test "X$1" = X--fallback-echo; then + # Avoid inline document here, it may be left over + : +elif test "X`{ $ECHO '\t'; } 2>/dev/null`" = 'X\t' ; then + # Yippee, $ECHO works! + : +else + # Restart under the correct shell. + exec $SHELL "$0" --no-reexec ${1+"$@"} +fi + +if test "X$1" = X--fallback-echo; then + # used as fallback echo + shift + cat <<_LT_EOF +$* +_LT_EOF + exit 0 +fi + +# The HP-UX ksh and POSIX shell print the target directory to stdout +# if CDPATH is set. +(unset CDPATH) >/dev/null 2>&1 && unset CDPATH + +if test -z "$lt_ECHO"; then + if test "X${echo_test_string+set}" != Xset; then + # find a string as large as possible, as long as the shell can cope with it + for cmd in 'sed 50q "$0"' 'sed 20q "$0"' 'sed 10q "$0"' 'sed 2q "$0"' 'echo test'; do + # expected sizes: less than 2Kb, 1Kb, 512 bytes, 16 bytes, ... + if { echo_test_string=`eval $cmd`; } 2>/dev/null && + { test "X$echo_test_string" = "X$echo_test_string"; } 2>/dev/null + then + break + fi + done + fi + + if test "X`{ $ECHO '\t'; } 2>/dev/null`" = 'X\t' && + echo_testing_string=`{ $ECHO "$echo_test_string"; } 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + : + else + # The Solaris, AIX, and Digital Unix default echo programs unquote + # backslashes. This makes it impossible to quote backslashes using + # echo "$something" | sed 's/\\/\\\\/g' + # + # So, first we look for a working echo in the user's PATH. + + lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + for dir in $PATH /usr/ucb; do + IFS="$lt_save_ifs" + if (test -f $dir/echo || test -f $dir/echo$ac_exeext) && + test "X`($dir/echo '\t') 2>/dev/null`" = 'X\t' && + echo_testing_string=`($dir/echo "$echo_test_string") 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + ECHO="$dir/echo" + break + fi + done + IFS="$lt_save_ifs" + + if test "X$ECHO" = Xecho; then + # We didn't find a better echo, so look for alternatives. + if test "X`{ print -r '\t'; } 2>/dev/null`" = 'X\t' && + echo_testing_string=`{ print -r "$echo_test_string"; } 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + # This shell has a builtin print -r that does the trick. + ECHO='print -r' + elif { test -f /bin/ksh || test -f /bin/ksh$ac_exeext; } && + test "X$CONFIG_SHELL" != X/bin/ksh; then + # If we have ksh, try running configure again with it. + ORIGINAL_CONFIG_SHELL=${CONFIG_SHELL-/bin/sh} + export ORIGINAL_CONFIG_SHELL + CONFIG_SHELL=/bin/ksh + export CONFIG_SHELL + exec $CONFIG_SHELL "$0" --no-reexec ${1+"$@"} + else + # Try using printf. + ECHO='printf %s\n' + if test "X`{ $ECHO '\t'; } 2>/dev/null`" = 'X\t' && + echo_testing_string=`{ $ECHO "$echo_test_string"; } 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + # Cool, printf works + : + elif echo_testing_string=`($ORIGINAL_CONFIG_SHELL "$0" --fallback-echo '\t') 2>/dev/null` && + test "X$echo_testing_string" = 'X\t' && + echo_testing_string=`($ORIGINAL_CONFIG_SHELL "$0" --fallback-echo "$echo_test_string") 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + CONFIG_SHELL=$ORIGINAL_CONFIG_SHELL + export CONFIG_SHELL + SHELL="$CONFIG_SHELL" + export SHELL + ECHO="$CONFIG_SHELL $0 --fallback-echo" + elif echo_testing_string=`($CONFIG_SHELL "$0" --fallback-echo '\t') 2>/dev/null` && + test "X$echo_testing_string" = 'X\t' && + echo_testing_string=`($CONFIG_SHELL "$0" --fallback-echo "$echo_test_string") 2>/dev/null` && + test "X$echo_testing_string" = "X$echo_test_string"; then + ECHO="$CONFIG_SHELL $0 --fallback-echo" + else + # maybe with a smaller string... + prev=: + + for cmd in 'echo test' 'sed 2q "$0"' 'sed 10q "$0"' 'sed 20q "$0"' 'sed 50q "$0"'; do + if { test "X$echo_test_string" = "X`eval $cmd`"; } 2>/dev/null + then + break + fi + prev="$cmd" + done + + if test "$prev" != 'sed 50q "$0"'; then + echo_test_string=`eval $prev` + export echo_test_string + exec ${ORIGINAL_CONFIG_SHELL-${CONFIG_SHELL-/bin/sh}} "$0" ${1+"$@"} + else + # Oops. We lost completely, so just stick with echo. + ECHO=echo + fi + fi + fi + fi + fi +fi + +# Copy echo and quote the copy suitably for passing to libtool from +# the Makefile, instead of quoting the original, which is used later. +lt_ECHO=$ECHO +if test "X$lt_ECHO" = "X$CONFIG_SHELL $0 --fallback-echo"; then + lt_ECHO="$CONFIG_SHELL \\\$\$0 --fallback-echo" +fi + + + + +test -n "$DJDIR" || exec 7<&0 &1 + +# Name of the host. +# hostname on some systems (SVR3.2, old GNU/Linux) returns a bogus exit status, +# so uname gets run too. +ac_hostname=`(hostname || uname -n) 2>/dev/null | sed 1q` + +# +# Initializations. +# +ac_default_prefix=/usr/local +ac_clean_files= +ac_config_libobj_dir=. +LIBOBJS= +cross_compiling=no +subdirs= +MFLAGS= +MAKEFLAGS= + +# Identity of this package. +PACKAGE_NAME='kconfig-frontends' +PACKAGE_TARNAME='kconfig-frontends' +PACKAGE_VERSION='3.6.0-0' +PACKAGE_STRING='kconfig-frontends 3.6.0-0' +PACKAGE_BUGREPORT='yann.morin.1998@free.fr' +PACKAGE_URL='' + +ac_unique_file="frontends/conf/conf.c" +# Factoring default headers for most tests. +ac_includes_default="\ +#include +#ifdef HAVE_SYS_TYPES_H +# include +#endif +#ifdef HAVE_SYS_STAT_H +# include +#endif +#ifdef STDC_HEADERS +# include +# include +#else +# ifdef HAVE_STDLIB_H +# include +# endif +#endif +#ifdef HAVE_STRING_H +# if !defined STDC_HEADERS && defined HAVE_MEMORY_H +# include +# endif +# include +#endif +#ifdef HAVE_STRINGS_H +# include +#endif +#ifdef HAVE_INTTYPES_H +# include +#endif +#ifdef HAVE_STDINT_H +# include +#endif +#ifdef HAVE_UNISTD_H +# include +#endif" + +ac_subst_vars='am__EXEEXT_FALSE +am__EXEEXT_TRUE +LTLIBOBJS +KCONFIGPARSER_LIB_VERSION +COND_utils_gettext_FALSE +COND_utils_gettext_TRUE +COND_utils_FALSE +COND_utils_TRUE +COND_images_FALSE +COND_images_TRUE +COND_lxdialog_FALSE +COND_lxdialog_TRUE +COND_qconf_FALSE +COND_qconf_TRUE +COND_gconf_FALSE +COND_gconf_TRUE +COND_nconf_FALSE +COND_nconf_TRUE +COND_mconf_FALSE +COND_mconf_TRUE +COND_conf_FALSE +COND_conf_TRUE +qconf_EXTRA_LIBS +nconf_EXTRA_LIBS +mconf_EXTRA_LIBS +gconf_EXTRA_LIBS +conf_EXTRA_LIBS +MOC +qt4_LIBS +qt4_CFLAGS +gtk_LIBS +gtk_CFLAGS +ncurses_extra_CPPFLAGS +ncurses_extra_LIBS +ncurses_LIBS +CURSES_LOC +intl_LIBS +intl_CPPFLAGS +ALLOCA +LIBOBJS +AM_YFLAGS +YFLAGS +YACC +AM_LFLAGS +LEXLIB +LEX_OUTPUT_ROOT +LEX +PKG_CONFIG_LIBDIR +PKG_CONFIG_PATH +PKG_CONFIG +GPERF +CXXCPP +am__fastdepCXX_FALSE +am__fastdepCXX_TRUE +CXXDEPMODE +ac_ct_CXX +CXXFLAGS +CXX +kf_CFLAGS +enable_frontends +enable_qconf +enable_gconf +enable_nconf +enable_mconf +enable_conf +enable_L10n +enable_utils +config_prefix +root_menu +werror_CFLAGS +wall_CFLAGS +CPP +OTOOL64 +OTOOL +LIPO +NMEDIT +DSYMUTIL +lt_ECHO +RANLIB +AR +OBJDUMP +LN_S +NM +ac_ct_DUMPBIN +DUMPBIN +LD +FGREP +EGREP +GREP +SED +am__fastdepCC_FALSE +am__fastdepCC_TRUE +CCDEPMODE +AMDEPBACKSLASH +AMDEP_FALSE +AMDEP_TRUE +am__quote +am__include +DEPDIR +OBJEXT +EXEEXT +ac_ct_CC +CPPFLAGS +LDFLAGS +CFLAGS +CC +host_os +host_vendor +host_cpu +host +build_os +build_vendor +build_cpu +build +LIBTOOL +SILENT_MAKEFLAGS +AM_BACKSLASH +AM_DEFAULT_VERBOSITY +am__untar +am__tar +AMTAR +am__leading_dot +SET_MAKE +AWK +mkdir_p +MKDIR_P +INSTALL_STRIP_PROGRAM +STRIP +install_sh +MAKEINFO +AUTOHEADER +AUTOMAKE +AUTOCONF +ACLOCAL +VERSION +PACKAGE +CYGPATH_W +am__isrc +INSTALL_DATA +INSTALL_SCRIPT +INSTALL_PROGRAM +target_alias +host_alias +build_alias +LIBS +ECHO_T +ECHO_N +ECHO_C +DEFS +mandir +localedir +libdir +psdir +pdfdir +dvidir +htmldir +infodir +docdir +oldincludedir +includedir +localstatedir +sharedstatedir +sysconfdir +datadir +datarootdir +libexecdir +sbindir +bindir +program_transform_name +prefix +exec_prefix +PACKAGE_URL +PACKAGE_BUGREPORT +PACKAGE_STRING +PACKAGE_VERSION +PACKAGE_TARNAME +PACKAGE_NAME +PATH_SEPARATOR +SHELL' +ac_subst_files='' +ac_user_opts=' +enable_option_checking +enable_silent_rules +enable_static +enable_shared +with_pic +enable_fast_install +enable_dependency_tracking +with_gnu_ld +enable_libtool_lock +enable_wall +enable_werror +enable_root_menu_prompt +enable_config_prefix +enable_utils +enable_L10n +enable_conf +enable_mconf +enable_nconf +enable_gconf +enable_qconf +enable_frontends +' + ac_precious_vars='build_alias +host_alias +target_alias +CC +CFLAGS +LDFLAGS +LIBS +CPPFLAGS +CPP +CXX +CXXFLAGS +CCC +CXXCPP +PKG_CONFIG +PKG_CONFIG_PATH +PKG_CONFIG_LIBDIR +YACC +YFLAGS +gtk_CFLAGS +gtk_LIBS +qt4_CFLAGS +qt4_LIBS +MOC +conf_EXTRA_LIBS +gconf_EXTRA_LIBS +mconf_EXTRA_LIBS +nconf_EXTRA_LIBS +qconf_EXTRA_LIBS' + + +# Initialize some variables set by options. +ac_init_help= +ac_init_version=false +ac_unrecognized_opts= +ac_unrecognized_sep= +# The variables have the same names as the options, with +# dashes changed to underlines. +cache_file=/dev/null +exec_prefix=NONE +no_create= +no_recursion= +prefix=NONE +program_prefix=NONE +program_suffix=NONE +program_transform_name=s,x,x, +silent= +site= +srcdir= +verbose= +x_includes=NONE +x_libraries=NONE + +# Installation directory options. +# These are left unexpanded so users can "make install exec_prefix=/foo" +# and all the variables that are supposed to be based on exec_prefix +# by default will actually change. +# Use braces instead of parens because sh, perl, etc. also accept them. +# (The list follows the same order as the GNU Coding Standards.) +bindir='${exec_prefix}/bin' +sbindir='${exec_prefix}/sbin' +libexecdir='${exec_prefix}/libexec' +datarootdir='${prefix}/share' +datadir='${datarootdir}' +sysconfdir='${prefix}/etc' +sharedstatedir='${prefix}/com' +localstatedir='${prefix}/var' +includedir='${prefix}/include' +oldincludedir='/usr/include' +docdir='${datarootdir}/doc/${PACKAGE_TARNAME}' +infodir='${datarootdir}/info' +htmldir='${docdir}' +dvidir='${docdir}' +pdfdir='${docdir}' +psdir='${docdir}' +libdir='${exec_prefix}/lib' +localedir='${datarootdir}/locale' +mandir='${datarootdir}/man' + +ac_prev= +ac_dashdash= +for ac_option +do + # If the previous option needs an argument, assign it. + if test -n "$ac_prev"; then + eval $ac_prev=\$ac_option + ac_prev= + continue + fi + + case $ac_option in + *=?*) ac_optarg=`expr "X$ac_option" : '[^=]*=\(.*\)'` ;; + *=) ac_optarg= ;; + *) ac_optarg=yes ;; + esac + + # Accept the important Cygnus configure options, so we can diagnose typos. + + case $ac_dashdash$ac_option in + --) + ac_dashdash=yes ;; + + -bindir | --bindir | --bindi | --bind | --bin | --bi) + ac_prev=bindir ;; + -bindir=* | --bindir=* | --bindi=* | --bind=* | --bin=* | --bi=*) + bindir=$ac_optarg ;; + + -build | --build | --buil | --bui | --bu) + ac_prev=build_alias ;; + -build=* | --build=* | --buil=* | --bui=* | --bu=*) + build_alias=$ac_optarg ;; + + -cache-file | --cache-file | --cache-fil | --cache-fi \ + | --cache-f | --cache- | --cache | --cach | --cac | --ca | --c) + ac_prev=cache_file ;; + -cache-file=* | --cache-file=* | --cache-fil=* | --cache-fi=* \ + | --cache-f=* | --cache-=* | --cache=* | --cach=* | --cac=* | --ca=* | --c=*) + cache_file=$ac_optarg ;; + + --config-cache | -C) + cache_file=config.cache ;; + + -datadir | --datadir | --datadi | --datad) + ac_prev=datadir ;; + -datadir=* | --datadir=* | --datadi=* | --datad=*) + datadir=$ac_optarg ;; + + -datarootdir | --datarootdir | --datarootdi | --datarootd | --dataroot \ + | --dataroo | --dataro | --datar) + ac_prev=datarootdir ;; + -datarootdir=* | --datarootdir=* | --datarootdi=* | --datarootd=* \ + | --dataroot=* | --dataroo=* | --dataro=* | --datar=*) + datarootdir=$ac_optarg ;; + + -disable-* | --disable-*) + ac_useropt=`expr "x$ac_option" : 'x-*disable-\(.*\)'` + # Reject names that are not valid shell variable names. + expr "x$ac_useropt" : ".*[^-+._$as_cr_alnum]" >/dev/null && + as_fn_error $? "invalid feature name: $ac_useropt" + ac_useropt_orig=$ac_useropt + ac_useropt=`$as_echo "$ac_useropt" | sed 's/[-+.]/_/g'` + case $ac_user_opts in + *" +"enable_$ac_useropt" +"*) ;; + *) ac_unrecognized_opts="$ac_unrecognized_opts$ac_unrecognized_sep--disable-$ac_useropt_orig" + ac_unrecognized_sep=', ';; + esac + eval enable_$ac_useropt=no ;; + + -docdir | --docdir | --docdi | --doc | --do) + ac_prev=docdir ;; + -docdir=* | --docdir=* | --docdi=* | --doc=* | --do=*) + docdir=$ac_optarg ;; + + -dvidir | --dvidir | --dvidi | --dvid | --dvi | --dv) + ac_prev=dvidir ;; + -dvidir=* | --dvidir=* | --dvidi=* | --dvid=* | --dvi=* | --dv=*) + dvidir=$ac_optarg ;; + + -enable-* | --enable-*) + ac_useropt=`expr "x$ac_option" : 'x-*enable-\([^=]*\)'` + # Reject names that are not valid shell variable names. + expr "x$ac_useropt" : ".*[^-+._$as_cr_alnum]" >/dev/null && + as_fn_error $? "invalid feature name: $ac_useropt" + ac_useropt_orig=$ac_useropt + ac_useropt=`$as_echo "$ac_useropt" | sed 's/[-+.]/_/g'` + case $ac_user_opts in + *" +"enable_$ac_useropt" +"*) ;; + *) ac_unrecognized_opts="$ac_unrecognized_opts$ac_unrecognized_sep--enable-$ac_useropt_orig" + ac_unrecognized_sep=', ';; + esac + eval enable_$ac_useropt=\$ac_optarg ;; + + -exec-prefix | --exec_prefix | --exec-prefix | --exec-prefi \ + | --exec-pref | --exec-pre | --exec-pr | --exec-p | --exec- \ + | --exec | --exe | --ex) + ac_prev=exec_prefix ;; + -exec-prefix=* | --exec_prefix=* | --exec-prefix=* | --exec-prefi=* \ + | --exec-pref=* | --exec-pre=* | --exec-pr=* | --exec-p=* | --exec-=* \ + | --exec=* | --exe=* | --ex=*) + exec_prefix=$ac_optarg ;; + + -gas | --gas | --ga | --g) + # Obsolete; use --with-gas. + with_gas=yes ;; + + -help | --help | --hel | --he | -h) + ac_init_help=long ;; + -help=r* | --help=r* | --hel=r* | --he=r* | -hr*) + ac_init_help=recursive ;; + -help=s* | --help=s* | --hel=s* | --he=s* | -hs*) + ac_init_help=short ;; + + -host | --host | --hos | --ho) + ac_prev=host_alias ;; + -host=* | --host=* | --hos=* | --ho=*) + host_alias=$ac_optarg ;; + + -htmldir | --htmldir | --htmldi | --htmld | --html | --htm | --ht) + ac_prev=htmldir ;; + -htmldir=* | --htmldir=* | --htmldi=* | --htmld=* | --html=* | --htm=* \ + | --ht=*) + htmldir=$ac_optarg ;; + + -includedir | --includedir | --includedi | --included | --include \ + | --includ | --inclu | --incl | --inc) + ac_prev=includedir ;; + -includedir=* | --includedir=* | --includedi=* | --included=* | --include=* \ + | --includ=* | --inclu=* | --incl=* | --inc=*) + includedir=$ac_optarg ;; + + -infodir | --infodir | --infodi | --infod | --info | --inf) + ac_prev=infodir ;; + -infodir=* | --infodir=* | --infodi=* | --infod=* | --info=* | --inf=*) + infodir=$ac_optarg ;; + + -libdir | --libdir | --libdi | --libd) + ac_prev=libdir ;; + -libdir=* | --libdir=* | --libdi=* | --libd=*) + libdir=$ac_optarg ;; + + -libexecdir | --libexecdir | --libexecdi | --libexecd | --libexec \ + | --libexe | --libex | --libe) + ac_prev=libexecdir ;; + -libexecdir=* | --libexecdir=* | --libexecdi=* | --libexecd=* | --libexec=* \ + | --libexe=* | --libex=* | --libe=*) + libexecdir=$ac_optarg ;; + + -localedir | --localedir | --localedi | --localed | --locale) + ac_prev=localedir ;; + -localedir=* | --localedir=* | --localedi=* | --localed=* | --locale=*) + localedir=$ac_optarg ;; + + -localstatedir | --localstatedir | --localstatedi | --localstated \ + | --localstate | --localstat | --localsta | --localst | --locals) + ac_prev=localstatedir ;; + -localstatedir=* | --localstatedir=* | --localstatedi=* | --localstated=* \ + | --localstate=* | --localstat=* | --localsta=* | --localst=* | --locals=*) + localstatedir=$ac_optarg ;; + + -mandir | --mandir | --mandi | --mand | --man | --ma | --m) + ac_prev=mandir ;; + -mandir=* | --mandir=* | --mandi=* | --mand=* | --man=* | --ma=* | --m=*) + mandir=$ac_optarg ;; + + -nfp | --nfp | --nf) + # Obsolete; use --without-fp. + with_fp=no ;; + + -no-create | --no-create | --no-creat | --no-crea | --no-cre \ + | --no-cr | --no-c | -n) + no_create=yes ;; + + -no-recursion | --no-recursion | --no-recursio | --no-recursi \ + | --no-recurs | --no-recur | --no-recu | --no-rec | --no-re | --no-r) + no_recursion=yes ;; + + -oldincludedir | --oldincludedir | --oldincludedi | --oldincluded \ + | --oldinclude | --oldinclud | --oldinclu | --oldincl | --oldinc \ + | --oldin | --oldi | --old | --ol | --o) + ac_prev=oldincludedir ;; + -oldincludedir=* | --oldincludedir=* | --oldincludedi=* | --oldincluded=* \ + | --oldinclude=* | --oldinclud=* | --oldinclu=* | --oldincl=* | --oldinc=* \ + | --oldin=* | --oldi=* | --old=* | --ol=* | --o=*) + oldincludedir=$ac_optarg ;; + + -prefix | --prefix | --prefi | --pref | --pre | --pr | --p) + ac_prev=prefix ;; + -prefix=* | --prefix=* | --prefi=* | --pref=* | --pre=* | --pr=* | --p=*) + prefix=$ac_optarg ;; + + -program-prefix | --program-prefix | --program-prefi | --program-pref \ + | --program-pre | --program-pr | --program-p) + ac_prev=program_prefix ;; + -program-prefix=* | --program-prefix=* | --program-prefi=* \ + | --program-pref=* | --program-pre=* | --program-pr=* | --program-p=*) + program_prefix=$ac_optarg ;; + + -program-suffix | --program-suffix | --program-suffi | --program-suff \ + | --program-suf | --program-su | --program-s) + ac_prev=program_suffix ;; + -program-suffix=* | --program-suffix=* | --program-suffi=* \ + | --program-suff=* | --program-suf=* | --program-su=* | --program-s=*) + program_suffix=$ac_optarg ;; + + -program-transform-name | --program-transform-name \ + | --program-transform-nam | --program-transform-na \ + | --program-transform-n | --program-transform- \ + | --program-transform | --program-transfor \ + | --program-transfo | --program-transf \ + | --program-trans | --program-tran \ + | --progr-tra | --program-tr | --program-t) + ac_prev=program_transform_name ;; + -program-transform-name=* | --program-transform-name=* \ + | --program-transform-nam=* | --program-transform-na=* \ + | --program-transform-n=* | --program-transform-=* \ + | --program-transform=* | --program-transfor=* \ + | --program-transfo=* | --program-transf=* \ + | --program-trans=* | --program-tran=* \ + | --progr-tra=* | --program-tr=* | --program-t=*) + program_transform_name=$ac_optarg ;; + + -pdfdir | --pdfdir | --pdfdi | --pdfd | --pdf | --pd) + ac_prev=pdfdir ;; + -pdfdir=* | --pdfdir=* | --pdfdi=* | --pdfd=* | --pdf=* | --pd=*) + pdfdir=$ac_optarg ;; + + -psdir | --psdir | --psdi | --psd | --ps) + ac_prev=psdir ;; + -psdir=* | --psdir=* | --psdi=* | --psd=* | --ps=*) + psdir=$ac_optarg ;; + + -q | -quiet | --quiet | --quie | --qui | --qu | --q \ + | -silent | --silent | --silen | --sile | --sil) + silent=yes ;; + + -sbindir | --sbindir | --sbindi | --sbind | --sbin | --sbi | --sb) + ac_prev=sbindir ;; + -sbindir=* | --sbindir=* | --sbindi=* | --sbind=* | --sbin=* \ + | --sbi=* | --sb=*) + sbindir=$ac_optarg ;; + + -sharedstatedir | --sharedstatedir | --sharedstatedi \ + | --sharedstated | --sharedstate | --sharedstat | --sharedsta \ + | --sharedst | --shareds | --shared | --share | --shar \ + | --sha | --sh) + ac_prev=sharedstatedir ;; + -sharedstatedir=* | --sharedstatedir=* | --sharedstatedi=* \ + | --sharedstated=* | --sharedstate=* | --sharedstat=* | --sharedsta=* \ + | --sharedst=* | --shareds=* | --shared=* | --share=* | --shar=* \ + | --sha=* | --sh=*) + sharedstatedir=$ac_optarg ;; + + -site | --site | --sit) + ac_prev=site ;; + -site=* | --site=* | --sit=*) + site=$ac_optarg ;; + + -srcdir | --srcdir | --srcdi | --srcd | --src | --sr) + ac_prev=srcdir ;; + -srcdir=* | --srcdir=* | --srcdi=* | --srcd=* | --src=* | --sr=*) + srcdir=$ac_optarg ;; + + -sysconfdir | --sysconfdir | --sysconfdi | --sysconfd | --sysconf \ + | --syscon | --sysco | --sysc | --sys | --sy) + ac_prev=sysconfdir ;; + -sysconfdir=* | --sysconfdir=* | --sysconfdi=* | --sysconfd=* | --sysconf=* \ + | --syscon=* | --sysco=* | --sysc=* | --sys=* | --sy=*) + sysconfdir=$ac_optarg ;; + + -target | --target | --targe | --targ | --tar | --ta | --t) + ac_prev=target_alias ;; + -target=* | --target=* | --targe=* | --targ=* | --tar=* | --ta=* | --t=*) + target_alias=$ac_optarg ;; + + -v | -verbose | --verbose | --verbos | --verbo | --verb) + verbose=yes ;; + + -version | --version | --versio | --versi | --vers | -V) + ac_init_version=: ;; + + -with-* | --with-*) + ac_useropt=`expr "x$ac_option" : 'x-*with-\([^=]*\)'` + # Reject names that are not valid shell variable names. + expr "x$ac_useropt" : ".*[^-+._$as_cr_alnum]" >/dev/null && + as_fn_error $? "invalid package name: $ac_useropt" + ac_useropt_orig=$ac_useropt + ac_useropt=`$as_echo "$ac_useropt" | sed 's/[-+.]/_/g'` + case $ac_user_opts in + *" +"with_$ac_useropt" +"*) ;; + *) ac_unrecognized_opts="$ac_unrecognized_opts$ac_unrecognized_sep--with-$ac_useropt_orig" + ac_unrecognized_sep=', ';; + esac + eval with_$ac_useropt=\$ac_optarg ;; + + -without-* | --without-*) + ac_useropt=`expr "x$ac_option" : 'x-*without-\(.*\)'` + # Reject names that are not valid shell variable names. + expr "x$ac_useropt" : ".*[^-+._$as_cr_alnum]" >/dev/null && + as_fn_error $? "invalid package name: $ac_useropt" + ac_useropt_orig=$ac_useropt + ac_useropt=`$as_echo "$ac_useropt" | sed 's/[-+.]/_/g'` + case $ac_user_opts in + *" +"with_$ac_useropt" +"*) ;; + *) ac_unrecognized_opts="$ac_unrecognized_opts$ac_unrecognized_sep--without-$ac_useropt_orig" + ac_unrecognized_sep=', ';; + esac + eval with_$ac_useropt=no ;; + + --x) + # Obsolete; use --with-x. + with_x=yes ;; + + -x-includes | --x-includes | --x-include | --x-includ | --x-inclu \ + | --x-incl | --x-inc | --x-in | --x-i) + ac_prev=x_includes ;; + -x-includes=* | --x-includes=* | --x-include=* | --x-includ=* | --x-inclu=* \ + | --x-incl=* | --x-inc=* | --x-in=* | --x-i=*) + x_includes=$ac_optarg ;; + + -x-libraries | --x-libraries | --x-librarie | --x-librari \ + | --x-librar | --x-libra | --x-libr | --x-lib | --x-li | --x-l) + ac_prev=x_libraries ;; + -x-libraries=* | --x-libraries=* | --x-librarie=* | --x-librari=* \ + | --x-librar=* | --x-libra=* | --x-libr=* | --x-lib=* | --x-li=* | --x-l=*) + x_libraries=$ac_optarg ;; + + -*) as_fn_error $? "unrecognized option: \`$ac_option' +Try \`$0 --help' for more information" + ;; + + *=*) + ac_envvar=`expr "x$ac_option" : 'x\([^=]*\)='` + # Reject names that are not valid shell variable names. + case $ac_envvar in #( + '' | [0-9]* | *[!_$as_cr_alnum]* ) + as_fn_error $? "invalid variable name: \`$ac_envvar'" ;; + esac + eval $ac_envvar=\$ac_optarg + export $ac_envvar ;; + + *) + # FIXME: should be removed in autoconf 3.0. + $as_echo "$as_me: WARNING: you should use --build, --host, --target" >&2 + expr "x$ac_option" : ".*[^-._$as_cr_alnum]" >/dev/null && + $as_echo "$as_me: WARNING: invalid host type: $ac_option" >&2 + : ${build_alias=$ac_option} ${host_alias=$ac_option} ${target_alias=$ac_option} + ;; + + esac +done + +if test -n "$ac_prev"; then + ac_option=--`echo $ac_prev | sed 's/_/-/g'` + as_fn_error $? "missing argument to $ac_option" +fi + +if test -n "$ac_unrecognized_opts"; then + case $enable_option_checking in + no) ;; + fatal) as_fn_error $? "unrecognized options: $ac_unrecognized_opts" ;; + *) $as_echo "$as_me: WARNING: unrecognized options: $ac_unrecognized_opts" >&2 ;; + esac +fi + +# Check all directory arguments for consistency. +for ac_var in exec_prefix prefix bindir sbindir libexecdir datarootdir \ + datadir sysconfdir sharedstatedir localstatedir includedir \ + oldincludedir docdir infodir htmldir dvidir pdfdir psdir \ + libdir localedir mandir +do + eval ac_val=\$$ac_var + # Remove trailing slashes. + case $ac_val in + */ ) + ac_val=`expr "X$ac_val" : 'X\(.*[^/]\)' \| "X$ac_val" : 'X\(.*\)'` + eval $ac_var=\$ac_val;; + esac + # Be sure to have absolute directory names. + case $ac_val in + [\\/$]* | ?:[\\/]* ) continue;; + NONE | '' ) case $ac_var in *prefix ) continue;; esac;; + esac + as_fn_error $? "expected an absolute directory name for --$ac_var: $ac_val" +done + +# There might be people who depend on the old broken behavior: `$host' +# used to hold the argument of --host etc. +# FIXME: To remove some day. +build=$build_alias +host=$host_alias +target=$target_alias + +# FIXME: To remove some day. +if test "x$host_alias" != x; then + if test "x$build_alias" = x; then + cross_compiling=maybe + $as_echo "$as_me: WARNING: if you wanted to set the --build type, don't use --host. + If a cross compiler is detected then cross compile mode will be used" >&2 + elif test "x$build_alias" != "x$host_alias"; then + cross_compiling=yes + fi +fi + +ac_tool_prefix= +test -n "$host_alias" && ac_tool_prefix=$host_alias- + +test "$silent" = yes && exec 6>/dev/null + + +ac_pwd=`pwd` && test -n "$ac_pwd" && +ac_ls_di=`ls -di .` && +ac_pwd_ls_di=`cd "$ac_pwd" && ls -di .` || + as_fn_error $? "working directory cannot be determined" +test "X$ac_ls_di" = "X$ac_pwd_ls_di" || + as_fn_error $? "pwd does not report name of working directory" + + +# Find the source files, if location was not specified. +if test -z "$srcdir"; then + ac_srcdir_defaulted=yes + # Try the directory containing this script, then the parent directory. + ac_confdir=`$as_dirname -- "$as_myself" || +$as_expr X"$as_myself" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \ + X"$as_myself" : 'X\(//\)[^/]' \| \ + X"$as_myself" : 'X\(//\)$' \| \ + X"$as_myself" : 'X\(/\)' \| . 2>/dev/null || +$as_echo X"$as_myself" | + sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ + s//\1/ + q + } + /^X\(\/\/\)[^/].*/{ + s//\1/ + q + } + /^X\(\/\/\)$/{ + s//\1/ + q + } + /^X\(\/\).*/{ + s//\1/ + q + } + s/.*/./; q'` + srcdir=$ac_confdir + if test ! -r "$srcdir/$ac_unique_file"; then + srcdir=.. + fi +else + ac_srcdir_defaulted=no +fi +if test ! -r "$srcdir/$ac_unique_file"; then + test "$ac_srcdir_defaulted" = yes && srcdir="$ac_confdir or .." + as_fn_error $? "cannot find sources ($ac_unique_file) in $srcdir" +fi +ac_msg="sources are in $srcdir, but \`cd $srcdir' does not work" +ac_abs_confdir=`( + cd "$srcdir" && test -r "./$ac_unique_file" || as_fn_error $? "$ac_msg" + pwd)` +# When building in place, set srcdir=. +if test "$ac_abs_confdir" = "$ac_pwd"; then + srcdir=. +fi +# Remove unnecessary trailing slashes from srcdir. +# Double slashes in file names in object file debugging info +# mess up M-x gdb in Emacs. +case $srcdir in +*/) srcdir=`expr "X$srcdir" : 'X\(.*[^/]\)' \| "X$srcdir" : 'X\(.*\)'`;; +esac +for ac_var in $ac_precious_vars; do + eval ac_env_${ac_var}_set=\${${ac_var}+set} + eval ac_env_${ac_var}_value=\$${ac_var} + eval ac_cv_env_${ac_var}_set=\${${ac_var}+set} + eval ac_cv_env_${ac_var}_value=\$${ac_var} +done + +# +# Report the --help message. +# +if test "$ac_init_help" = "long"; then + # Omit some internal or obsolete options to make the list less imposing. + # This message is too long to be a string in the A/UX 3.1 sh. + cat <<_ACEOF +\`configure' configures kconfig-frontends 3.6.0-0 to adapt to many kinds of systems. + +Usage: $0 [OPTION]... [VAR=VALUE]... + +To assign environment variables (e.g., CC, CFLAGS...), specify them as +VAR=VALUE. See below for descriptions of some of the useful variables. + +Defaults for the options are specified in brackets. + +Configuration: + -h, --help display this help and exit + --help=short display options specific to this package + --help=recursive display the short help of all the included packages + -V, --version display version information and exit + -q, --quiet, --silent do not print \`checking ...' messages + --cache-file=FILE cache test results in FILE [disabled] + -C, --config-cache alias for \`--cache-file=config.cache' + -n, --no-create do not create output files + --srcdir=DIR find the sources in DIR [configure dir or \`..'] + +Installation directories: + --prefix=PREFIX install architecture-independent files in PREFIX + [$ac_default_prefix] + --exec-prefix=EPREFIX install architecture-dependent files in EPREFIX + [PREFIX] + +By default, \`make install' will install all the files in +\`$ac_default_prefix/bin', \`$ac_default_prefix/lib' etc. You can specify +an installation prefix other than \`$ac_default_prefix' using \`--prefix', +for instance \`--prefix=\$HOME'. + +For better control, use the options below. + +Fine tuning of the installation directories: + --bindir=DIR user executables [EPREFIX/bin] + --sbindir=DIR system admin executables [EPREFIX/sbin] + --libexecdir=DIR program executables [EPREFIX/libexec] + --sysconfdir=DIR read-only single-machine data [PREFIX/etc] + --sharedstatedir=DIR modifiable architecture-independent data [PREFIX/com] + --localstatedir=DIR modifiable single-machine data [PREFIX/var] + --libdir=DIR object code libraries [EPREFIX/lib] + --includedir=DIR C header files [PREFIX/include] + --oldincludedir=DIR C header files for non-gcc [/usr/include] + --datarootdir=DIR read-only arch.-independent data root [PREFIX/share] + --datadir=DIR read-only architecture-independent data [DATAROOTDIR] + --infodir=DIR info documentation [DATAROOTDIR/info] + --localedir=DIR locale-dependent data [DATAROOTDIR/locale] + --mandir=DIR man documentation [DATAROOTDIR/man] + --docdir=DIR documentation root + [DATAROOTDIR/doc/kconfig-frontends] + --htmldir=DIR html documentation [DOCDIR] + --dvidir=DIR dvi documentation [DOCDIR] + --pdfdir=DIR pdf documentation [DOCDIR] + --psdir=DIR ps documentation [DOCDIR] +_ACEOF + + cat <<\_ACEOF + +Program names: + --program-prefix=PREFIX prepend PREFIX to installed program names + --program-suffix=SUFFIX append SUFFIX to installed program names + --program-transform-name=PROGRAM run sed PROGRAM on installed program names + +System types: + --build=BUILD configure for building on BUILD [guessed] + --host=HOST cross-compile to build programs to run on HOST [BUILD] +_ACEOF +fi + +if test -n "$ac_init_help"; then + case $ac_init_help in + short | recursive ) echo "Configuration of kconfig-frontends 3.6.0-0:";; + esac + cat <<\_ACEOF + +Optional Features: + --disable-option-checking ignore unrecognized --enable/--with options + --disable-FEATURE do not include FEATURE (same as --enable-FEATURE=no) + --enable-FEATURE[=ARG] include FEATURE [ARG=yes] + --enable-silent-rules less verbose build output (undo: `make V=1') + --disable-silent-rules verbose build output (undo: `make V=0') + --enable-static[=PKGS] build static libraries [default=no] + --enable-shared[=PKGS] build shared libraries [default=yes] + --enable-fast-install[=PKGS] + optimize for fast installation [default=yes] + --disable-dependency-tracking speeds up one-time build + --enable-dependency-tracking do not reject slow dependency extractors + --disable-libtool-lock avoid locking (might break parallel builds) + --enable-wall build with -Wall (default=no) + --enable-werror build with -Werror (default=no) + --enable-root-menu-prompt=PROMPT + set the root-menu prompt (default=Configuration) + --enable-config-prefix=PREFIX + the prefix to the config option (default=CONFIG_) + --disable-utils install utilities to manage .config files + (default=no) + --disable-L10n enable localisation (L10n) (default=auto) + --disable-conf conf, the stdin-based frontend (default=auto) + --disable-mconf mconf, the traditional ncurses-based frontend + (default=auto) + --disable-nconf nconf, the modern ncurses-based frontend + (default=auto) + --disable-gconf gconf, the GTK-based frontend (default=auto) + --disable-qconf qconf, the QT-based frontend (default=auto) + --enable-frontends=list enables only the set of frontends in comma-separated + 'list' (default: auto selection), takes precedence + over all --enable-*conf, above + +Optional Packages: + --with-PACKAGE[=ARG] use PACKAGE [ARG=yes] + --without-PACKAGE do not use PACKAGE (same as --with-PACKAGE=no) + --with-pic try to use only PIC/non-PIC objects [default=use + both] + --with-gnu-ld assume the C compiler uses GNU ld [default=no] + +Some influential environment variables: + CC C compiler command + CFLAGS C compiler flags + LDFLAGS linker flags, e.g. -L if you have libraries in a + nonstandard directory + LIBS libraries to pass to the linker, e.g. -l + CPPFLAGS (Objective) C/C++ preprocessor flags, e.g. -I if + you have headers in a nonstandard directory + CPP C preprocessor + CXX C++ compiler command + CXXFLAGS C++ compiler flags + CXXCPP C++ preprocessor + PKG_CONFIG path to pkg-config utility + PKG_CONFIG_PATH + directories to add to pkg-config's search path + PKG_CONFIG_LIBDIR + path overriding pkg-config's built-in search path + YACC The `Yet Another C Compiler' implementation to use. Defaults to + the first program found out of: `bison -y', `byacc', `yacc'. + YFLAGS The list of arguments that will be passed by default to $YACC. + This script will default YFLAGS to the empty string to avoid a + default value of `-d' given by some make applications. + gtk_CFLAGS C compiler flags for gtk, overriding pkg-config + gtk_LIBS linker flags for gtk, overriding pkg-config + qt4_CFLAGS C compiler flags for qt4, overriding pkg-config + qt4_LIBS linker flags for qt4, overriding pkg-config + MOC Qt meta object compiler (moc) command + conf_EXTRA_LIBS + Extra libraries to build the conf frontend + gconf_EXTRA_LIBS + Extra libraries to build the gconf frontend + mconf_EXTRA_LIBS + Extra libraries to build the mconf frontend + nconf_EXTRA_LIBS + Extra libraries to build the nconf frontend + qconf_EXTRA_LIBS + Extra libraries to build the qconf frontend + +Use these variables to override the choices made by `configure' or to help +it to find libraries and programs with nonstandard names/locations. + +Report bugs to . +_ACEOF +ac_status=$? +fi + +if test "$ac_init_help" = "recursive"; then + # If there are subdirs, report their specific --help. + for ac_dir in : $ac_subdirs_all; do test "x$ac_dir" = x: && continue + test -d "$ac_dir" || + { cd "$srcdir" && ac_pwd=`pwd` && srcdir=. && test -d "$ac_dir"; } || + continue + ac_builddir=. + +case "$ac_dir" in +.) ac_dir_suffix= ac_top_builddir_sub=. ac_top_build_prefix= ;; +*) + ac_dir_suffix=/`$as_echo "$ac_dir" | sed 's|^\.[\\/]||'` + # A ".." for each directory in $ac_dir_suffix. + ac_top_builddir_sub=`$as_echo "$ac_dir_suffix" | sed 's|/[^\\/]*|/..|g;s|/||'` + case $ac_top_builddir_sub in + "") ac_top_builddir_sub=. ac_top_build_prefix= ;; + *) ac_top_build_prefix=$ac_top_builddir_sub/ ;; + esac ;; +esac +ac_abs_top_builddir=$ac_pwd +ac_abs_builddir=$ac_pwd$ac_dir_suffix +# for backward compatibility: +ac_top_builddir=$ac_top_build_prefix + +case $srcdir in + .) # We are building in place. + ac_srcdir=. + ac_top_srcdir=$ac_top_builddir_sub + ac_abs_top_srcdir=$ac_pwd ;; + [\\/]* | ?:[\\/]* ) # Absolute name. + ac_srcdir=$srcdir$ac_dir_suffix; + ac_top_srcdir=$srcdir + ac_abs_top_srcdir=$srcdir ;; + *) # Relative name. + ac_srcdir=$ac_top_build_prefix$srcdir$ac_dir_suffix + ac_top_srcdir=$ac_top_build_prefix$srcdir + ac_abs_top_srcdir=$ac_pwd/$srcdir ;; +esac +ac_abs_srcdir=$ac_abs_top_srcdir$ac_dir_suffix + + cd "$ac_dir" || { ac_status=$?; continue; } + # Check for guested configure. + if test -f "$ac_srcdir/configure.gnu"; then + echo && + $SHELL "$ac_srcdir/configure.gnu" --help=recursive + elif test -f "$ac_srcdir/configure"; then + echo && + $SHELL "$ac_srcdir/configure" --help=recursive + else + $as_echo "$as_me: WARNING: no configuration information is in $ac_dir" >&2 + fi || ac_status=$? + cd "$ac_pwd" || { ac_status=$?; break; } + done +fi + +test -n "$ac_init_help" && exit $ac_status +if $ac_init_version; then + cat <<\_ACEOF +kconfig-frontends configure 3.6.0-0 +generated by GNU Autoconf 2.67 + +Copyright (C) 2010 Free Software Foundation, Inc. +This configure script is free software; the Free Software Foundation +gives unlimited permission to copy, distribute and modify it. +_ACEOF + exit +fi + +## ------------------------ ## +## Autoconf initialization. ## +## ------------------------ ## + +# ac_fn_c_try_compile LINENO +# -------------------------- +# Try to compile conftest.$ac_ext, and return whether this succeeded. +ac_fn_c_try_compile () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + rm -f conftest.$ac_objext + if { { ac_try="$ac_compile" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_compile") 2>conftest.err + ac_status=$? + if test -s conftest.err; then + grep -v '^ *+' conftest.err >conftest.er1 + cat conftest.er1 >&5 + mv -f conftest.er1 conftest.err + fi + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && { + test -z "$ac_c_werror_flag" || + test ! -s conftest.err + } && test -s conftest.$ac_objext; then : + ac_retval=0 +else + $as_echo "$as_me: failed program was:" >&5 +sed 's/^/| /' conftest.$ac_ext >&5 + + ac_retval=1 +fi + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + as_fn_set_status $ac_retval + +} # ac_fn_c_try_compile + +# ac_fn_c_try_link LINENO +# ----------------------- +# Try to link conftest.$ac_ext, and return whether this succeeded. +ac_fn_c_try_link () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + rm -f conftest.$ac_objext conftest$ac_exeext + if { { ac_try="$ac_link" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_link") 2>conftest.err + ac_status=$? + if test -s conftest.err; then + grep -v '^ *+' conftest.err >conftest.er1 + cat conftest.er1 >&5 + mv -f conftest.er1 conftest.err + fi + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && { + test -z "$ac_c_werror_flag" || + test ! -s conftest.err + } && test -s conftest$ac_exeext && { + test "$cross_compiling" = yes || + $as_test_x conftest$ac_exeext + }; then : + ac_retval=0 +else + $as_echo "$as_me: failed program was:" >&5 +sed 's/^/| /' conftest.$ac_ext >&5 + + ac_retval=1 +fi + # Delete the IPA/IPO (Inter Procedural Analysis/Optimization) information + # created by the PGI compiler (conftest_ipa8_conftest.oo), as it would + # interfere with the next link command; also delete a directory that is + # left behind by Apple's compiler. We do this before executing the actions. + rm -rf conftest.dSYM conftest_ipa8_conftest.oo + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + as_fn_set_status $ac_retval + +} # ac_fn_c_try_link + +# ac_fn_c_check_header_compile LINENO HEADER VAR INCLUDES +# ------------------------------------------------------- +# Tests whether HEADER exists and can be compiled using the include files in +# INCLUDES, setting the cache variable VAR accordingly. +ac_fn_c_check_header_compile () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for $2" >&5 +$as_echo_n "checking for $2... " >&6; } +if eval "test \"\${$3+set}\"" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +$4 +#include <$2> +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + eval "$3=yes" +else + eval "$3=no" +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +eval ac_res=\$$3 + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_res" >&5 +$as_echo "$ac_res" >&6; } + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + +} # ac_fn_c_check_header_compile + +# ac_fn_c_try_cpp LINENO +# ---------------------- +# Try to preprocess conftest.$ac_ext, and return whether this succeeded. +ac_fn_c_try_cpp () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + if { { ac_try="$ac_cpp conftest.$ac_ext" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_cpp conftest.$ac_ext") 2>conftest.err + ac_status=$? + if test -s conftest.err; then + grep -v '^ *+' conftest.err >conftest.er1 + cat conftest.er1 >&5 + mv -f conftest.er1 conftest.err + fi + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } > conftest.i && { + test -z "$ac_c_preproc_warn_flag$ac_c_werror_flag" || + test ! -s conftest.err + }; then : + ac_retval=0 +else + $as_echo "$as_me: failed program was:" >&5 +sed 's/^/| /' conftest.$ac_ext >&5 + + ac_retval=1 +fi + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + as_fn_set_status $ac_retval + +} # ac_fn_c_try_cpp + +# ac_fn_c_try_run LINENO +# ---------------------- +# Try to link conftest.$ac_ext, and return whether this succeeded. Assumes +# that executables *can* be run. +ac_fn_c_try_run () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + if { { ac_try="$ac_link" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_link") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && { ac_try='./conftest$ac_exeext' + { { case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_try") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; }; then : + ac_retval=0 +else + $as_echo "$as_me: program exited with status $ac_status" >&5 + $as_echo "$as_me: failed program was:" >&5 +sed 's/^/| /' conftest.$ac_ext >&5 + + ac_retval=$ac_status +fi + rm -rf conftest.dSYM conftest_ipa8_conftest.oo + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + as_fn_set_status $ac_retval + +} # ac_fn_c_try_run + +# ac_fn_c_check_func LINENO FUNC VAR +# ---------------------------------- +# Tests whether FUNC exists, setting the cache variable VAR accordingly +ac_fn_c_check_func () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for $2" >&5 +$as_echo_n "checking for $2... " >&6; } +if eval "test \"\${$3+set}\"" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +/* Define $2 to an innocuous variant, in case declares $2. + For example, HP-UX 11i declares gettimeofday. */ +#define $2 innocuous_$2 + +/* System header to define __stub macros and hopefully few prototypes, + which can conflict with char $2 (); below. + Prefer to if __STDC__ is defined, since + exists even on freestanding compilers. */ + +#ifdef __STDC__ +# include +#else +# include +#endif + +#undef $2 + +/* Override any GCC internal prototype to avoid an error. + Use char because int might match the return type of a GCC + builtin and then its argument prototype would still apply. */ +#ifdef __cplusplus +extern "C" +#endif +char $2 (); +/* The GNU C library defines this for functions which it implements + to always fail with ENOSYS. Some functions are actually named + something starting with __ and the normal name is an alias. */ +#if defined __stub_$2 || defined __stub___$2 +choke me +#endif + +int +main () +{ +return $2 (); + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + eval "$3=yes" +else + eval "$3=no" +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +fi +eval ac_res=\$$3 + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_res" >&5 +$as_echo "$ac_res" >&6; } + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + +} # ac_fn_c_check_func + +# ac_fn_cxx_try_compile LINENO +# ---------------------------- +# Try to compile conftest.$ac_ext, and return whether this succeeded. +ac_fn_cxx_try_compile () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + rm -f conftest.$ac_objext + if { { ac_try="$ac_compile" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_compile") 2>conftest.err + ac_status=$? + if test -s conftest.err; then + grep -v '^ *+' conftest.err >conftest.er1 + cat conftest.er1 >&5 + mv -f conftest.er1 conftest.err + fi + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && { + test -z "$ac_cxx_werror_flag" || + test ! -s conftest.err + } && test -s conftest.$ac_objext; then : + ac_retval=0 +else + $as_echo "$as_me: failed program was:" >&5 +sed 's/^/| /' conftest.$ac_ext >&5 + + ac_retval=1 +fi + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + as_fn_set_status $ac_retval + +} # ac_fn_cxx_try_compile + +# ac_fn_cxx_try_cpp LINENO +# ------------------------ +# Try to preprocess conftest.$ac_ext, and return whether this succeeded. +ac_fn_cxx_try_cpp () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + if { { ac_try="$ac_cpp conftest.$ac_ext" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_cpp conftest.$ac_ext") 2>conftest.err + ac_status=$? + if test -s conftest.err; then + grep -v '^ *+' conftest.err >conftest.er1 + cat conftest.er1 >&5 + mv -f conftest.er1 conftest.err + fi + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } > conftest.i && { + test -z "$ac_cxx_preproc_warn_flag$ac_cxx_werror_flag" || + test ! -s conftest.err + }; then : + ac_retval=0 +else + $as_echo "$as_me: failed program was:" >&5 +sed 's/^/| /' conftest.$ac_ext >&5 + + ac_retval=1 +fi + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + as_fn_set_status $ac_retval + +} # ac_fn_cxx_try_cpp + +# ac_fn_cxx_try_link LINENO +# ------------------------- +# Try to link conftest.$ac_ext, and return whether this succeeded. +ac_fn_cxx_try_link () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + rm -f conftest.$ac_objext conftest$ac_exeext + if { { ac_try="$ac_link" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_link") 2>conftest.err + ac_status=$? + if test -s conftest.err; then + grep -v '^ *+' conftest.err >conftest.er1 + cat conftest.er1 >&5 + mv -f conftest.er1 conftest.err + fi + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && { + test -z "$ac_cxx_werror_flag" || + test ! -s conftest.err + } && test -s conftest$ac_exeext && { + test "$cross_compiling" = yes || + $as_test_x conftest$ac_exeext + }; then : + ac_retval=0 +else + $as_echo "$as_me: failed program was:" >&5 +sed 's/^/| /' conftest.$ac_ext >&5 + + ac_retval=1 +fi + # Delete the IPA/IPO (Inter Procedural Analysis/Optimization) information + # created by the PGI compiler (conftest_ipa8_conftest.oo), as it would + # interfere with the next link command; also delete a directory that is + # left behind by Apple's compiler. We do this before executing the actions. + rm -rf conftest.dSYM conftest_ipa8_conftest.oo + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + as_fn_set_status $ac_retval + +} # ac_fn_cxx_try_link + +# ac_fn_c_check_type LINENO TYPE VAR INCLUDES +# ------------------------------------------- +# Tests whether TYPE exists after having included INCLUDES, setting cache +# variable VAR accordingly. +ac_fn_c_check_type () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for $2" >&5 +$as_echo_n "checking for $2... " >&6; } +if eval "test \"\${$3+set}\"" = set; then : + $as_echo_n "(cached) " >&6 +else + eval "$3=no" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +$4 +int +main () +{ +if (sizeof ($2)) + return 0; + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +$4 +int +main () +{ +if (sizeof (($2))) + return 0; + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + +else + eval "$3=yes" +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +eval ac_res=\$$3 + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_res" >&5 +$as_echo "$ac_res" >&6; } + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + +} # ac_fn_c_check_type + +# ac_fn_c_check_header_mongrel LINENO HEADER VAR INCLUDES +# ------------------------------------------------------- +# Tests whether HEADER exists, giving a warning if it cannot be compiled using +# the include files in INCLUDES and setting the cache variable VAR +# accordingly. +ac_fn_c_check_header_mongrel () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + if eval "test \"\${$3+set}\"" = set; then : + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for $2" >&5 +$as_echo_n "checking for $2... " >&6; } +if eval "test \"\${$3+set}\"" = set; then : + $as_echo_n "(cached) " >&6 +fi +eval ac_res=\$$3 + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_res" >&5 +$as_echo "$ac_res" >&6; } +else + # Is the header compilable? +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking $2 usability" >&5 +$as_echo_n "checking $2 usability... " >&6; } +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +$4 +#include <$2> +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_header_compiler=yes +else + ac_header_compiler=no +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_header_compiler" >&5 +$as_echo "$ac_header_compiler" >&6; } + +# Is the header present? +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking $2 presence" >&5 +$as_echo_n "checking $2 presence... " >&6; } +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include <$2> +_ACEOF +if ac_fn_c_try_cpp "$LINENO"; then : + ac_header_preproc=yes +else + ac_header_preproc=no +fi +rm -f conftest.err conftest.i conftest.$ac_ext +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_header_preproc" >&5 +$as_echo "$ac_header_preproc" >&6; } + +# So? What about this header? +case $ac_header_compiler:$ac_header_preproc:$ac_c_preproc_warn_flag in #(( + yes:no: ) + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: accepted by the compiler, rejected by the preprocessor!" >&5 +$as_echo "$as_me: WARNING: $2: accepted by the compiler, rejected by the preprocessor!" >&2;} + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: proceeding with the compiler's result" >&5 +$as_echo "$as_me: WARNING: $2: proceeding with the compiler's result" >&2;} + ;; + no:yes:* ) + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: present but cannot be compiled" >&5 +$as_echo "$as_me: WARNING: $2: present but cannot be compiled" >&2;} + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: check for missing prerequisite headers?" >&5 +$as_echo "$as_me: WARNING: $2: check for missing prerequisite headers?" >&2;} + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: see the Autoconf documentation" >&5 +$as_echo "$as_me: WARNING: $2: see the Autoconf documentation" >&2;} + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: section \"Present But Cannot Be Compiled\"" >&5 +$as_echo "$as_me: WARNING: $2: section \"Present But Cannot Be Compiled\"" >&2;} + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: proceeding with the compiler's result" >&5 +$as_echo "$as_me: WARNING: $2: proceeding with the compiler's result" >&2;} +( $as_echo "## -------------------------------------- ## +## Report this to yann.morin.1998@free.fr ## +## -------------------------------------- ##" + ) | sed "s/^/$as_me: WARNING: /" >&2 + ;; +esac + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for $2" >&5 +$as_echo_n "checking for $2... " >&6; } +if eval "test \"\${$3+set}\"" = set; then : + $as_echo_n "(cached) " >&6 +else + eval "$3=\$ac_header_compiler" +fi +eval ac_res=\$$3 + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_res" >&5 +$as_echo "$ac_res" >&6; } +fi + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + +} # ac_fn_c_check_header_mongrel + +# ac_fn_c_check_decl LINENO SYMBOL VAR INCLUDES +# --------------------------------------------- +# Tests whether SYMBOL is declared in INCLUDES, setting cache variable VAR +# accordingly. +ac_fn_c_check_decl () +{ + as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + as_decl_name=`echo $2|sed 's/ *(.*//'` + as_decl_use=`echo $2|sed -e 's/(/((/' -e 's/)/) 0&/' -e 's/,/) 0& (/g'` + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether $as_decl_name is declared" >&5 +$as_echo_n "checking whether $as_decl_name is declared... " >&6; } +if eval "test \"\${$3+set}\"" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +$4 +int +main () +{ +#ifndef $as_decl_name +#ifdef __cplusplus + (void) $as_decl_use; +#else + (void) $as_decl_name; +#endif +#endif + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + eval "$3=yes" +else + eval "$3=no" +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +eval ac_res=\$$3 + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_res" >&5 +$as_echo "$ac_res" >&6; } + eval $as_lineno_stack; test "x$as_lineno_stack" = x && { as_lineno=; unset as_lineno;} + +} # ac_fn_c_check_decl +cat >config.log <<_ACEOF +This file contains any messages produced by compilers while +running configure, to aid debugging if configure makes a mistake. + +It was created by kconfig-frontends $as_me 3.6.0-0, which was +generated by GNU Autoconf 2.67. Invocation command line was + + $ $0 $@ + +_ACEOF +exec 5>>config.log +{ +cat <<_ASUNAME +## --------- ## +## Platform. ## +## --------- ## + +hostname = `(hostname || uname -n) 2>/dev/null | sed 1q` +uname -m = `(uname -m) 2>/dev/null || echo unknown` +uname -r = `(uname -r) 2>/dev/null || echo unknown` +uname -s = `(uname -s) 2>/dev/null || echo unknown` +uname -v = `(uname -v) 2>/dev/null || echo unknown` + +/usr/bin/uname -p = `(/usr/bin/uname -p) 2>/dev/null || echo unknown` +/bin/uname -X = `(/bin/uname -X) 2>/dev/null || echo unknown` + +/bin/arch = `(/bin/arch) 2>/dev/null || echo unknown` +/usr/bin/arch -k = `(/usr/bin/arch -k) 2>/dev/null || echo unknown` +/usr/convex/getsysinfo = `(/usr/convex/getsysinfo) 2>/dev/null || echo unknown` +/usr/bin/hostinfo = `(/usr/bin/hostinfo) 2>/dev/null || echo unknown` +/bin/machine = `(/bin/machine) 2>/dev/null || echo unknown` +/usr/bin/oslevel = `(/usr/bin/oslevel) 2>/dev/null || echo unknown` +/bin/universe = `(/bin/universe) 2>/dev/null || echo unknown` + +_ASUNAME + +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + $as_echo "PATH: $as_dir" + done +IFS=$as_save_IFS + +} >&5 + +cat >&5 <<_ACEOF + + +## ----------- ## +## Core tests. ## +## ----------- ## + +_ACEOF + + +# Keep a trace of the command line. +# Strip out --no-create and --no-recursion so they do not pile up. +# Strip out --silent because we don't want to record it for future runs. +# Also quote any args containing shell meta-characters. +# Make two passes to allow for proper duplicate-argument suppression. +ac_configure_args= +ac_configure_args0= +ac_configure_args1= +ac_must_keep_next=false +for ac_pass in 1 2 +do + for ac_arg + do + case $ac_arg in + -no-create | --no-c* | -n | -no-recursion | --no-r*) continue ;; + -q | -quiet | --quiet | --quie | --qui | --qu | --q \ + | -silent | --silent | --silen | --sile | --sil) + continue ;; + *\'*) + ac_arg=`$as_echo "$ac_arg" | sed "s/'/'\\\\\\\\''/g"` ;; + esac + case $ac_pass in + 1) as_fn_append ac_configure_args0 " '$ac_arg'" ;; + 2) + as_fn_append ac_configure_args1 " '$ac_arg'" + if test $ac_must_keep_next = true; then + ac_must_keep_next=false # Got value, back to normal. + else + case $ac_arg in + *=* | --config-cache | -C | -disable-* | --disable-* \ + | -enable-* | --enable-* | -gas | --g* | -nfp | --nf* \ + | -q | -quiet | --q* | -silent | --sil* | -v | -verb* \ + | -with-* | --with-* | -without-* | --without-* | --x) + case "$ac_configure_args0 " in + "$ac_configure_args1"*" '$ac_arg' "* ) continue ;; + esac + ;; + -* ) ac_must_keep_next=true ;; + esac + fi + as_fn_append ac_configure_args " '$ac_arg'" + ;; + esac + done +done +{ ac_configure_args0=; unset ac_configure_args0;} +{ ac_configure_args1=; unset ac_configure_args1;} + +# When interrupted or exit'd, cleanup temporary files, and complete +# config.log. We remove comments because anyway the quotes in there +# would cause problems or look ugly. +# WARNING: Use '\'' to represent an apostrophe within the trap. +# WARNING: Do not start the trap code with a newline, due to a FreeBSD 4.0 bug. +trap 'exit_status=$? + # Save into config.log some information that might help in debugging. + { + echo + + $as_echo "## ---------------- ## +## Cache variables. ## +## ---------------- ##" + echo + # The following way of writing the cache mishandles newlines in values, +( + for ac_var in `(set) 2>&1 | sed -n '\''s/^\([a-zA-Z_][a-zA-Z0-9_]*\)=.*/\1/p'\''`; do + eval ac_val=\$$ac_var + case $ac_val in #( + *${as_nl}*) + case $ac_var in #( + *_cv_*) { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: cache variable $ac_var contains a newline" >&5 +$as_echo "$as_me: WARNING: cache variable $ac_var contains a newline" >&2;} ;; + esac + case $ac_var in #( + _ | IFS | as_nl) ;; #( + BASH_ARGV | BASH_SOURCE) eval $ac_var= ;; #( + *) { eval $ac_var=; unset $ac_var;} ;; + esac ;; + esac + done + (set) 2>&1 | + case $as_nl`(ac_space='\'' '\''; set) 2>&1` in #( + *${as_nl}ac_space=\ *) + sed -n \ + "s/'\''/'\''\\\\'\'''\''/g; + s/^\\([_$as_cr_alnum]*_cv_[_$as_cr_alnum]*\\)=\\(.*\\)/\\1='\''\\2'\''/p" + ;; #( + *) + sed -n "/^[_$as_cr_alnum]*_cv_[_$as_cr_alnum]*=/p" + ;; + esac | + sort +) + echo + + $as_echo "## ----------------- ## +## Output variables. ## +## ----------------- ##" + echo + for ac_var in $ac_subst_vars + do + eval ac_val=\$$ac_var + case $ac_val in + *\'\''*) ac_val=`$as_echo "$ac_val" | sed "s/'\''/'\''\\\\\\\\'\'''\''/g"`;; + esac + $as_echo "$ac_var='\''$ac_val'\''" + done | sort + echo + + if test -n "$ac_subst_files"; then + $as_echo "## ------------------- ## +## File substitutions. ## +## ------------------- ##" + echo + for ac_var in $ac_subst_files + do + eval ac_val=\$$ac_var + case $ac_val in + *\'\''*) ac_val=`$as_echo "$ac_val" | sed "s/'\''/'\''\\\\\\\\'\'''\''/g"`;; + esac + $as_echo "$ac_var='\''$ac_val'\''" + done | sort + echo + fi + + if test -s confdefs.h; then + $as_echo "## ----------- ## +## confdefs.h. ## +## ----------- ##" + echo + cat confdefs.h + echo + fi + test "$ac_signal" != 0 && + $as_echo "$as_me: caught signal $ac_signal" + $as_echo "$as_me: exit $exit_status" + } >&5 + rm -f core *.core core.conftest.* && + rm -f -r conftest* confdefs* conf$$* $ac_clean_files && + exit $exit_status +' 0 +for ac_signal in 1 2 13 15; do + trap 'ac_signal='$ac_signal'; as_fn_exit 1' $ac_signal +done +ac_signal=0 + +# confdefs.h avoids OS command line length limits that DEFS can exceed. +rm -f -r conftest* confdefs.h + +$as_echo "/* confdefs.h */" > confdefs.h + +# Predefined preprocessor variables. + +cat >>confdefs.h <<_ACEOF +#define PACKAGE_NAME "$PACKAGE_NAME" +_ACEOF + +cat >>confdefs.h <<_ACEOF +#define PACKAGE_TARNAME "$PACKAGE_TARNAME" +_ACEOF + +cat >>confdefs.h <<_ACEOF +#define PACKAGE_VERSION "$PACKAGE_VERSION" +_ACEOF + +cat >>confdefs.h <<_ACEOF +#define PACKAGE_STRING "$PACKAGE_STRING" +_ACEOF + +cat >>confdefs.h <<_ACEOF +#define PACKAGE_BUGREPORT "$PACKAGE_BUGREPORT" +_ACEOF + +cat >>confdefs.h <<_ACEOF +#define PACKAGE_URL "$PACKAGE_URL" +_ACEOF + + +# Let the site file select an alternate cache file if it wants to. +# Prefer an explicitly selected file to automatically selected ones. +ac_site_file1=NONE +ac_site_file2=NONE +if test -n "$CONFIG_SITE"; then + # We do not want a PATH search for config.site. + case $CONFIG_SITE in #(( + -*) ac_site_file1=./$CONFIG_SITE;; + */*) ac_site_file1=$CONFIG_SITE;; + *) ac_site_file1=./$CONFIG_SITE;; + esac +elif test "x$prefix" != xNONE; then + ac_site_file1=$prefix/share/config.site + ac_site_file2=$prefix/etc/config.site +else + ac_site_file1=$ac_default_prefix/share/config.site + ac_site_file2=$ac_default_prefix/etc/config.site +fi +for ac_site_file in "$ac_site_file1" "$ac_site_file2" +do + test "x$ac_site_file" = xNONE && continue + if test /dev/null != "$ac_site_file" && test -r "$ac_site_file"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: loading site script $ac_site_file" >&5 +$as_echo "$as_me: loading site script $ac_site_file" >&6;} + sed 's/^/| /' "$ac_site_file" >&5 + . "$ac_site_file" \ + || { { $as_echo "$as_me:${as_lineno-$LINENO}: error: in \`$ac_pwd':" >&5 +$as_echo "$as_me: error: in \`$ac_pwd':" >&2;} +as_fn_error $? "failed to load site script $ac_site_file +See \`config.log' for more details" "$LINENO" 5 ; } + fi +done + +if test -r "$cache_file"; then + # Some versions of bash will fail to source /dev/null (special files + # actually), so we avoid doing that. DJGPP emulates it as a regular file. + if test /dev/null != "$cache_file" && test -f "$cache_file"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: loading cache $cache_file" >&5 +$as_echo "$as_me: loading cache $cache_file" >&6;} + case $cache_file in + [\\/]* | ?:[\\/]* ) . "$cache_file";; + *) . "./$cache_file";; + esac + fi +else + { $as_echo "$as_me:${as_lineno-$LINENO}: creating cache $cache_file" >&5 +$as_echo "$as_me: creating cache $cache_file" >&6;} + >$cache_file +fi + +# Check that the precious variables saved in the cache have kept the same +# value. +ac_cache_corrupted=false +for ac_var in $ac_precious_vars; do + eval ac_old_set=\$ac_cv_env_${ac_var}_set + eval ac_new_set=\$ac_env_${ac_var}_set + eval ac_old_val=\$ac_cv_env_${ac_var}_value + eval ac_new_val=\$ac_env_${ac_var}_value + case $ac_old_set,$ac_new_set in + set,) + { $as_echo "$as_me:${as_lineno-$LINENO}: error: \`$ac_var' was set to \`$ac_old_val' in the previous run" >&5 +$as_echo "$as_me: error: \`$ac_var' was set to \`$ac_old_val' in the previous run" >&2;} + ac_cache_corrupted=: ;; + ,set) + { $as_echo "$as_me:${as_lineno-$LINENO}: error: \`$ac_var' was not set in the previous run" >&5 +$as_echo "$as_me: error: \`$ac_var' was not set in the previous run" >&2;} + ac_cache_corrupted=: ;; + ,);; + *) + if test "x$ac_old_val" != "x$ac_new_val"; then + # differences in whitespace do not lead to failure. + ac_old_val_w=`echo x $ac_old_val` + ac_new_val_w=`echo x $ac_new_val` + if test "$ac_old_val_w" != "$ac_new_val_w"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: error: \`$ac_var' has changed since the previous run:" >&5 +$as_echo "$as_me: error: \`$ac_var' has changed since the previous run:" >&2;} + ac_cache_corrupted=: + else + { $as_echo "$as_me:${as_lineno-$LINENO}: warning: ignoring whitespace changes in \`$ac_var' since the previous run:" >&5 +$as_echo "$as_me: warning: ignoring whitespace changes in \`$ac_var' since the previous run:" >&2;} + eval $ac_var=\$ac_old_val + fi + { $as_echo "$as_me:${as_lineno-$LINENO}: former value: \`$ac_old_val'" >&5 +$as_echo "$as_me: former value: \`$ac_old_val'" >&2;} + { $as_echo "$as_me:${as_lineno-$LINENO}: current value: \`$ac_new_val'" >&5 +$as_echo "$as_me: current value: \`$ac_new_val'" >&2;} + fi;; + esac + # Pass precious variables to config.status. + if test "$ac_new_set" = set; then + case $ac_new_val in + *\'*) ac_arg=$ac_var=`$as_echo "$ac_new_val" | sed "s/'/'\\\\\\\\''/g"` ;; + *) ac_arg=$ac_var=$ac_new_val ;; + esac + case " $ac_configure_args " in + *" '$ac_arg' "*) ;; # Avoid dups. Use of quotes ensures accuracy. + *) as_fn_append ac_configure_args " '$ac_arg'" ;; + esac + fi +done +if $ac_cache_corrupted; then + { $as_echo "$as_me:${as_lineno-$LINENO}: error: in \`$ac_pwd':" >&5 +$as_echo "$as_me: error: in \`$ac_pwd':" >&2;} + { $as_echo "$as_me:${as_lineno-$LINENO}: error: changes in the environment can compromise the build" >&5 +$as_echo "$as_me: error: changes in the environment can compromise the build" >&2;} + as_fn_error $? "run \`make distclean' and/or \`rm $cache_file' and start over" "$LINENO" 5 +fi +## -------------------- ## +## Main body of script. ## +## -------------------- ## + +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + + + +# Use a config.h to avoid brazilions -DHAVE_FOO on compile lines +ac_config_headers="$ac_config_headers scripts/.autostuff/config.h" + +ac_aux_dir= +for ac_dir in scripts/.autostuff/scripts "$srcdir"/scripts/.autostuff/scripts; do + if test -f "$ac_dir/install-sh"; then + ac_aux_dir=$ac_dir + ac_install_sh="$ac_aux_dir/install-sh -c" + break + elif test -f "$ac_dir/install.sh"; then + ac_aux_dir=$ac_dir + ac_install_sh="$ac_aux_dir/install.sh -c" + break + elif test -f "$ac_dir/shtool"; then + ac_aux_dir=$ac_dir + ac_install_sh="$ac_aux_dir/shtool install -c" + break + fi +done +if test -z "$ac_aux_dir"; then + as_fn_error $? "cannot find install-sh, install.sh, or shtool in scripts/.autostuff/scripts \"$srcdir\"/scripts/.autostuff/scripts" "$LINENO" 5 +fi + +# These three variables are undocumented and unsupported, +# and are intended to be withdrawn in a future Autoconf release. +# They can cause serious problems if a builder's source tree is in a directory +# whose full name contains unusual characters. +ac_config_guess="$SHELL $ac_aux_dir/config.guess" # Please don't use this var. +ac_config_sub="$SHELL $ac_aux_dir/config.sub" # Please don't use this var. +ac_configure="$SHELL $ac_aux_dir/configure" # Please don't use this var. + + + + +#---------------------------------------- +# Prepare automake + +# We want to allow the user to override our default program-prefix, +# so we must set-it now, before automake has a chance to interpret +# it, but after the options are parsed, so as not to overwrite the +# value (if any) set by the user +if test "$program_prefix" = NONE; then : + program_prefix=kconfig- +fi + +am__api_version='1.11' + +# Find a good install program. We prefer a C program (faster), +# so one script is as good as another. But avoid the broken or +# incompatible versions: +# SysV /etc/install, /usr/sbin/install +# SunOS /usr/etc/install +# IRIX /sbin/install +# AIX /bin/install +# AmigaOS /C/install, which installs bootblocks on floppy discs +# AIX 4 /usr/bin/installbsd, which doesn't work without a -g flag +# AFS /usr/afsws/bin/install, which mishandles nonexistent args +# SVR4 /usr/ucb/install, which tries to use the nonexistent group "staff" +# OS/2's system install, which has a completely different semantic +# ./install, which can be erroneously created by make from ./install.sh. +# Reject install programs that cannot install multiple files. +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for a BSD-compatible install" >&5 +$as_echo_n "checking for a BSD-compatible install... " >&6; } +if test -z "$INSTALL"; then +if test "${ac_cv_path_install+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + # Account for people who put trailing slashes in PATH elements. +case $as_dir/ in #(( + ./ | .// | /[cC]/* | \ + /etc/* | /usr/sbin/* | /usr/etc/* | /sbin/* | /usr/afsws/bin/* | \ + ?:[\\/]os2[\\/]install[\\/]* | ?:[\\/]OS2[\\/]INSTALL[\\/]* | \ + /usr/ucb/* ) ;; + *) + # OSF1 and SCO ODT 3.0 have their own names for install. + # Don't use installbsd from OSF since it installs stuff as root + # by default. + for ac_prog in ginstall scoinst install; do + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_prog$ac_exec_ext" && $as_test_x "$as_dir/$ac_prog$ac_exec_ext"; }; then + if test $ac_prog = install && + grep dspmsg "$as_dir/$ac_prog$ac_exec_ext" >/dev/null 2>&1; then + # AIX install. It has an incompatible calling convention. + : + elif test $ac_prog = install && + grep pwplus "$as_dir/$ac_prog$ac_exec_ext" >/dev/null 2>&1; then + # program-specific install script used by HP pwplus--don't use. + : + else + rm -rf conftest.one conftest.two conftest.dir + echo one > conftest.one + echo two > conftest.two + mkdir conftest.dir + if "$as_dir/$ac_prog$ac_exec_ext" -c conftest.one conftest.two "`pwd`/conftest.dir" && + test -s conftest.one && test -s conftest.two && + test -s conftest.dir/conftest.one && + test -s conftest.dir/conftest.two + then + ac_cv_path_install="$as_dir/$ac_prog$ac_exec_ext -c" + break 3 + fi + fi + fi + done + done + ;; +esac + + done +IFS=$as_save_IFS + +rm -rf conftest.one conftest.two conftest.dir + +fi + if test "${ac_cv_path_install+set}" = set; then + INSTALL=$ac_cv_path_install + else + # As a last resort, use the slow shell script. Don't cache a + # value for INSTALL within a source directory, because that will + # break other packages using the cache if that directory is + # removed, or if the value is a relative name. + INSTALL=$ac_install_sh + fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $INSTALL" >&5 +$as_echo "$INSTALL" >&6; } + +# Use test -z because SunOS4 sh mishandles braces in ${var-val}. +# It thinks the first close brace ends the variable substitution. +test -z "$INSTALL_PROGRAM" && INSTALL_PROGRAM='${INSTALL}' + +test -z "$INSTALL_SCRIPT" && INSTALL_SCRIPT='${INSTALL}' + +test -z "$INSTALL_DATA" && INSTALL_DATA='${INSTALL} -m 644' + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether build environment is sane" >&5 +$as_echo_n "checking whether build environment is sane... " >&6; } +# Just in case +sleep 1 +echo timestamp > conftest.file +# Reject unsafe characters in $srcdir or the absolute working directory +# name. Accept space and tab only in the latter. +am_lf=' +' +case `pwd` in + *[\\\"\#\$\&\'\`$am_lf]*) + as_fn_error $? "unsafe absolute working directory name" "$LINENO" 5 ;; +esac +case $srcdir in + *[\\\"\#\$\&\'\`$am_lf\ \ ]*) + as_fn_error $? "unsafe srcdir value: \`$srcdir'" "$LINENO" 5 ;; +esac + +# Do `set' in a subshell so we don't clobber the current shell's +# arguments. Must try -L first in case configure is actually a +# symlink; some systems play weird games with the mod time of symlinks +# (eg FreeBSD returns the mod time of the symlink's containing +# directory). +if ( + set X `ls -Lt "$srcdir/configure" conftest.file 2> /dev/null` + if test "$*" = "X"; then + # -L didn't work. + set X `ls -t "$srcdir/configure" conftest.file` + fi + rm -f conftest.file + if test "$*" != "X $srcdir/configure conftest.file" \ + && test "$*" != "X conftest.file $srcdir/configure"; then + + # If neither matched, then we have a broken ls. This can happen + # if, for instance, CONFIG_SHELL is bash and it inherits a + # broken ls alias from the environment. This has actually + # happened. Such a system could not be considered "sane". + as_fn_error $? "ls -t appears to fail. Make sure there is not a broken +alias in your environment" "$LINENO" 5 + fi + + test "$2" = conftest.file + ) +then + # Ok. + : +else + as_fn_error $? "newly created file is older than distributed files! +Check your system clock" "$LINENO" 5 +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } +test "$program_prefix" != NONE && + program_transform_name="s&^&$program_prefix&;$program_transform_name" +# Use a double $ so make ignores it. +test "$program_suffix" != NONE && + program_transform_name="s&\$&$program_suffix&;$program_transform_name" +# Double any \ or $. +# By default was `s,x,x', remove it if useless. +ac_script='s/[\\$]/&&/g;s/;s,x,x,$//' +program_transform_name=`$as_echo "$program_transform_name" | sed "$ac_script"` + +# expand $ac_aux_dir to an absolute path +am_aux_dir=`cd $ac_aux_dir && pwd` + +if test x"${MISSING+set}" != xset; then + case $am_aux_dir in + *\ * | *\ *) + MISSING="\${SHELL} \"$am_aux_dir/missing\"" ;; + *) + MISSING="\${SHELL} $am_aux_dir/missing" ;; + esac +fi +# Use eval to expand $SHELL +if eval "$MISSING --run true"; then + am_missing_run="$MISSING --run " +else + am_missing_run= + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: \`missing' script is too old or missing" >&5 +$as_echo "$as_me: WARNING: \`missing' script is too old or missing" >&2;} +fi + +if test x"${install_sh}" != xset; then + case $am_aux_dir in + *\ * | *\ *) + install_sh="\${SHELL} '$am_aux_dir/install-sh'" ;; + *) + install_sh="\${SHELL} $am_aux_dir/install-sh" + esac +fi + +# Installed binaries are usually stripped using `strip' when the user +# run `make install-strip'. However `strip' might not be the right +# tool to use in cross-compilation environments, therefore Automake +# will honor the `STRIP' environment variable to overrule this program. +if test "$cross_compiling" != no; then + if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}strip", so it can be a program name with args. +set dummy ${ac_tool_prefix}strip; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_STRIP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$STRIP"; then + ac_cv_prog_STRIP="$STRIP" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_STRIP="${ac_tool_prefix}strip" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +STRIP=$ac_cv_prog_STRIP +if test -n "$STRIP"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $STRIP" >&5 +$as_echo "$STRIP" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_STRIP"; then + ac_ct_STRIP=$STRIP + # Extract the first word of "strip", so it can be a program name with args. +set dummy strip; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_STRIP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_STRIP"; then + ac_cv_prog_ac_ct_STRIP="$ac_ct_STRIP" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_STRIP="strip" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_STRIP=$ac_cv_prog_ac_ct_STRIP +if test -n "$ac_ct_STRIP"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_STRIP" >&5 +$as_echo "$ac_ct_STRIP" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_STRIP" = x; then + STRIP=":" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + STRIP=$ac_ct_STRIP + fi +else + STRIP="$ac_cv_prog_STRIP" +fi + +fi +INSTALL_STRIP_PROGRAM="\$(install_sh) -c -s" + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for a thread-safe mkdir -p" >&5 +$as_echo_n "checking for a thread-safe mkdir -p... " >&6; } +if test -z "$MKDIR_P"; then + if test "${ac_cv_path_mkdir+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH$PATH_SEPARATOR/opt/sfw/bin +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_prog in mkdir gmkdir; do + for ac_exec_ext in '' $ac_executable_extensions; do + { test -f "$as_dir/$ac_prog$ac_exec_ext" && $as_test_x "$as_dir/$ac_prog$ac_exec_ext"; } || continue + case `"$as_dir/$ac_prog$ac_exec_ext" --version 2>&1` in #( + 'mkdir (GNU coreutils) '* | \ + 'mkdir (coreutils) '* | \ + 'mkdir (fileutils) '4.1*) + ac_cv_path_mkdir=$as_dir/$ac_prog$ac_exec_ext + break 3;; + esac + done + done + done +IFS=$as_save_IFS + +fi + + test -d ./--version && rmdir ./--version + if test "${ac_cv_path_mkdir+set}" = set; then + MKDIR_P="$ac_cv_path_mkdir -p" + else + # As a last resort, use the slow shell script. Don't cache a + # value for MKDIR_P within a source directory, because that will + # break other packages using the cache if that directory is + # removed, or if the value is a relative name. + MKDIR_P="$ac_install_sh -d" + fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $MKDIR_P" >&5 +$as_echo "$MKDIR_P" >&6; } + +mkdir_p="$MKDIR_P" +case $mkdir_p in + [\\/$]* | ?:[\\/]*) ;; + */*) mkdir_p="\$(top_builddir)/$mkdir_p" ;; +esac + +for ac_prog in gawk mawk nawk awk +do + # Extract the first word of "$ac_prog", so it can be a program name with args. +set dummy $ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_AWK+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$AWK"; then + ac_cv_prog_AWK="$AWK" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_AWK="$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +AWK=$ac_cv_prog_AWK +if test -n "$AWK"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $AWK" >&5 +$as_echo "$AWK" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$AWK" && break +done + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether ${MAKE-make} sets \$(MAKE)" >&5 +$as_echo_n "checking whether ${MAKE-make} sets \$(MAKE)... " >&6; } +set x ${MAKE-make} +ac_make=`$as_echo "$2" | sed 's/+/p/g; s/[^a-zA-Z0-9_]/_/g'` +if eval "test \"\${ac_cv_prog_make_${ac_make}_set+set}\"" = set; then : + $as_echo_n "(cached) " >&6 +else + cat >conftest.make <<\_ACEOF +SHELL = /bin/sh +all: + @echo '@@@%%%=$(MAKE)=@@@%%%' +_ACEOF +# GNU make sometimes prints "make[1]: Entering ...", which would confuse us. +case `${MAKE-make} -f conftest.make 2>/dev/null` in + *@@@%%%=?*=@@@%%%*) + eval ac_cv_prog_make_${ac_make}_set=yes;; + *) + eval ac_cv_prog_make_${ac_make}_set=no;; +esac +rm -f conftest.make +fi +if eval test \$ac_cv_prog_make_${ac_make}_set = yes; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } + SET_MAKE= +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + SET_MAKE="MAKE=${MAKE-make}" +fi + +rm -rf .tst 2>/dev/null +mkdir .tst 2>/dev/null +if test -d .tst; then + am__leading_dot=. +else + am__leading_dot=_ +fi +rmdir .tst 2>/dev/null + +if test "`cd $srcdir && pwd`" != "`pwd`"; then + # Use -I$(srcdir) only when $(srcdir) != ., so that make's output + # is not polluted with repeated "-I." + am__isrc=' -I$(srcdir)' + # test to see if srcdir already configured + if test -f $srcdir/config.status; then + as_fn_error $? "source directory already configured; run \"make distclean\" there first" "$LINENO" 5 + fi +fi + +# test whether we have cygpath +if test -z "$CYGPATH_W"; then + if (cygpath --version) >/dev/null 2>/dev/null; then + CYGPATH_W='cygpath -w' + else + CYGPATH_W=echo + fi +fi + + +# Define the identity of the package. + PACKAGE='kconfig-frontends' + VERSION='3.6.0-0' + + +cat >>confdefs.h <<_ACEOF +#define PACKAGE "$PACKAGE" +_ACEOF + + +cat >>confdefs.h <<_ACEOF +#define VERSION "$VERSION" +_ACEOF + +# Some tools Automake needs. + +ACLOCAL=${ACLOCAL-"${am_missing_run}aclocal-${am__api_version}"} + + +AUTOCONF=${AUTOCONF-"${am_missing_run}autoconf"} + + +AUTOMAKE=${AUTOMAKE-"${am_missing_run}automake-${am__api_version}"} + + +AUTOHEADER=${AUTOHEADER-"${am_missing_run}autoheader"} + + +MAKEINFO=${MAKEINFO-"${am_missing_run}makeinfo"} + +# We need awk for the "check" target. The system "awk" is bad on +# some platforms. +# Always define AMTAR for backward compatibility. + +AMTAR=${AMTAR-"${am_missing_run}tar"} + +am__tar='${AMTAR} chof - "$$tardir"'; am__untar='${AMTAR} xf -' + + + + + + +if test "$(${srcdir}/scripts/version.sh --internal)" = "hg"; then : + # Check whether --enable-silent-rules was given. +if test "${enable_silent_rules+set}" = set; then : + enableval=$enable_silent_rules; +fi + +case $enable_silent_rules in +yes) AM_DEFAULT_VERBOSITY=0;; +no) AM_DEFAULT_VERBOSITY=1;; +*) AM_DEFAULT_VERBOSITY=1;; +esac +AM_BACKSLASH='\' + +else + # Check whether --enable-silent-rules was given. +if test "${enable_silent_rules+set}" = set; then : + enableval=$enable_silent_rules; +fi + +case $enable_silent_rules in +yes) AM_DEFAULT_VERBOSITY=0;; +no) AM_DEFAULT_VERBOSITY=1;; +*) AM_DEFAULT_VERBOSITY=0;; +esac +AM_BACKSLASH='\' + +fi + +if test $AM_DEFAULT_VERBOSITY -eq 0; then : + SILENT_MAKEFLAGS="--no-print-directory -s" +else + SILENT_MAKEFLAGS="" +fi + + +#---------------------------------------- +# Prepare libtool + +case `pwd` in + *\ * | *\ *) + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: Libtool does not cope well with whitespace in \`pwd\`" >&5 +$as_echo "$as_me: WARNING: Libtool does not cope well with whitespace in \`pwd\`" >&2;} ;; +esac + + + +macro_version='2.2.6b' +macro_revision='1.3017' + + + + + + + + + + + + + +ltmain="$ac_aux_dir/ltmain.sh" + +# Make sure we can run config.sub. +$SHELL "$ac_aux_dir/config.sub" sun4 >/dev/null 2>&1 || + as_fn_error $? "cannot run $SHELL $ac_aux_dir/config.sub" "$LINENO" 5 + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking build system type" >&5 +$as_echo_n "checking build system type... " >&6; } +if test "${ac_cv_build+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_build_alias=$build_alias +test "x$ac_build_alias" = x && + ac_build_alias=`$SHELL "$ac_aux_dir/config.guess"` +test "x$ac_build_alias" = x && + as_fn_error $? "cannot guess build type; you must specify one" "$LINENO" 5 +ac_cv_build=`$SHELL "$ac_aux_dir/config.sub" $ac_build_alias` || + as_fn_error $? "$SHELL $ac_aux_dir/config.sub $ac_build_alias failed" "$LINENO" 5 + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_build" >&5 +$as_echo "$ac_cv_build" >&6; } +case $ac_cv_build in +*-*-*) ;; +*) as_fn_error $? "invalid value of canonical build" "$LINENO" 5 ;; +esac +build=$ac_cv_build +ac_save_IFS=$IFS; IFS='-' +set x $ac_cv_build +shift +build_cpu=$1 +build_vendor=$2 +shift; shift +# Remember, the first character of IFS is used to create $*, +# except with old shells: +build_os=$* +IFS=$ac_save_IFS +case $build_os in *\ *) build_os=`echo "$build_os" | sed 's/ /-/g'`;; esac + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking host system type" >&5 +$as_echo_n "checking host system type... " >&6; } +if test "${ac_cv_host+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test "x$host_alias" = x; then + ac_cv_host=$ac_cv_build +else + ac_cv_host=`$SHELL "$ac_aux_dir/config.sub" $host_alias` || + as_fn_error $? "$SHELL $ac_aux_dir/config.sub $host_alias failed" "$LINENO" 5 +fi + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_host" >&5 +$as_echo "$ac_cv_host" >&6; } +case $ac_cv_host in +*-*-*) ;; +*) as_fn_error $? "invalid value of canonical host" "$LINENO" 5 ;; +esac +host=$ac_cv_host +ac_save_IFS=$IFS; IFS='-' +set x $ac_cv_host +shift +host_cpu=$1 +host_vendor=$2 +shift; shift +# Remember, the first character of IFS is used to create $*, +# except with old shells: +host_os=$* +IFS=$ac_save_IFS +case $host_os in *\ *) host_os=`echo "$host_os" | sed 's/ /-/g'`;; esac + + +DEPDIR="${am__leading_dot}deps" + +ac_config_commands="$ac_config_commands depfiles" + + +am_make=${MAKE-make} +cat > confinc << 'END' +am__doit: + @echo this is the am__doit target +.PHONY: am__doit +END +# If we don't find an include directive, just comment out the code. +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for style of include used by $am_make" >&5 +$as_echo_n "checking for style of include used by $am_make... " >&6; } +am__include="#" +am__quote= +_am_result=none +# First try GNU make style include. +echo "include confinc" > confmf +# Ignore all kinds of additional output from `make'. +case `$am_make -s -f confmf 2> /dev/null` in #( +*the\ am__doit\ target*) + am__include=include + am__quote= + _am_result=GNU + ;; +esac +# Now try BSD make style include. +if test "$am__include" = "#"; then + echo '.include "confinc"' > confmf + case `$am_make -s -f confmf 2> /dev/null` in #( + *the\ am__doit\ target*) + am__include=.include + am__quote="\"" + _am_result=BSD + ;; + esac +fi + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $_am_result" >&5 +$as_echo "$_am_result" >&6; } +rm -f confinc confmf + +# Check whether --enable-dependency-tracking was given. +if test "${enable_dependency_tracking+set}" = set; then : + enableval=$enable_dependency_tracking; +fi + +if test "x$enable_dependency_tracking" != xno; then + am_depcomp="$ac_aux_dir/depcomp" + AMDEPBACKSLASH='\' +fi + if test "x$enable_dependency_tracking" != xno; then + AMDEP_TRUE= + AMDEP_FALSE='#' +else + AMDEP_TRUE='#' + AMDEP_FALSE= +fi + + +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu +if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}gcc", so it can be a program name with args. +set dummy ${ac_tool_prefix}gcc; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$CC"; then + ac_cv_prog_CC="$CC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_CC="${ac_tool_prefix}gcc" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +CC=$ac_cv_prog_CC +if test -n "$CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $CC" >&5 +$as_echo "$CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_CC"; then + ac_ct_CC=$CC + # Extract the first word of "gcc", so it can be a program name with args. +set dummy gcc; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_CC"; then + ac_cv_prog_ac_ct_CC="$ac_ct_CC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_CC="gcc" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_CC=$ac_cv_prog_ac_ct_CC +if test -n "$ac_ct_CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_CC" >&5 +$as_echo "$ac_ct_CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_CC" = x; then + CC="" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + CC=$ac_ct_CC + fi +else + CC="$ac_cv_prog_CC" +fi + +if test -z "$CC"; then + if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}cc", so it can be a program name with args. +set dummy ${ac_tool_prefix}cc; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$CC"; then + ac_cv_prog_CC="$CC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_CC="${ac_tool_prefix}cc" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +CC=$ac_cv_prog_CC +if test -n "$CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $CC" >&5 +$as_echo "$CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + fi +fi +if test -z "$CC"; then + # Extract the first word of "cc", so it can be a program name with args. +set dummy cc; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$CC"; then + ac_cv_prog_CC="$CC" # Let the user override the test. +else + ac_prog_rejected=no +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + if test "$as_dir/$ac_word$ac_exec_ext" = "/usr/ucb/cc"; then + ac_prog_rejected=yes + continue + fi + ac_cv_prog_CC="cc" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +if test $ac_prog_rejected = yes; then + # We found a bogon in the path, so make sure we never use it. + set dummy $ac_cv_prog_CC + shift + if test $# != 0; then + # We chose a different compiler from the bogus one. + # However, it has the same basename, so the bogon will be chosen + # first if we set CC to just the basename; use the full file name. + shift + ac_cv_prog_CC="$as_dir/$ac_word${1+' '}$@" + fi +fi +fi +fi +CC=$ac_cv_prog_CC +if test -n "$CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $CC" >&5 +$as_echo "$CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$CC"; then + if test -n "$ac_tool_prefix"; then + for ac_prog in cl.exe + do + # Extract the first word of "$ac_tool_prefix$ac_prog", so it can be a program name with args. +set dummy $ac_tool_prefix$ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$CC"; then + ac_cv_prog_CC="$CC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_CC="$ac_tool_prefix$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +CC=$ac_cv_prog_CC +if test -n "$CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $CC" >&5 +$as_echo "$CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$CC" && break + done +fi +if test -z "$CC"; then + ac_ct_CC=$CC + for ac_prog in cl.exe +do + # Extract the first word of "$ac_prog", so it can be a program name with args. +set dummy $ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_CC"; then + ac_cv_prog_ac_ct_CC="$ac_ct_CC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_CC="$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_CC=$ac_cv_prog_ac_ct_CC +if test -n "$ac_ct_CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_CC" >&5 +$as_echo "$ac_ct_CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$ac_ct_CC" && break +done + + if test "x$ac_ct_CC" = x; then + CC="" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + CC=$ac_ct_CC + fi +fi + +fi + + +test -z "$CC" && { { $as_echo "$as_me:${as_lineno-$LINENO}: error: in \`$ac_pwd':" >&5 +$as_echo "$as_me: error: in \`$ac_pwd':" >&2;} +as_fn_error $? "no acceptable C compiler found in \$PATH +See \`config.log' for more details" "$LINENO" 5 ; } + +# Provide some information about the compiler. +$as_echo "$as_me:${as_lineno-$LINENO}: checking for C compiler version" >&5 +set X $ac_compile +ac_compiler=$2 +for ac_option in --version -v -V -qversion; do + { { ac_try="$ac_compiler $ac_option >&5" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_compiler $ac_option >&5") 2>conftest.err + ac_status=$? + if test -s conftest.err; then + sed '10a\ +... rest of stderr output deleted ... + 10q' conftest.err >conftest.er1 + cat conftest.er1 >&5 + fi + rm -f conftest.er1 conftest.err + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } +done + +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +ac_clean_files_save=$ac_clean_files +ac_clean_files="$ac_clean_files a.out a.out.dSYM a.exe b.out" +# Try to create an executable without -o first, disregard a.out. +# It will help us diagnose broken compilers, and finding out an intuition +# of exeext. +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether the C compiler works" >&5 +$as_echo_n "checking whether the C compiler works... " >&6; } +ac_link_default=`$as_echo "$ac_link" | sed 's/ -o *conftest[^ ]*//'` + +# The possible output files: +ac_files="a.out conftest.exe conftest a.exe a_out.exe b.out conftest.*" + +ac_rmfiles= +for ac_file in $ac_files +do + case $ac_file in + *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg | *.map | *.inf | *.dSYM | *.o | *.obj ) ;; + * ) ac_rmfiles="$ac_rmfiles $ac_file";; + esac +done +rm -f $ac_rmfiles + +if { { ac_try="$ac_link_default" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_link_default") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then : + # Autoconf-2.13 could set the ac_cv_exeext variable to `no'. +# So ignore a value of `no', otherwise this would lead to `EXEEXT = no' +# in a Makefile. We should not override ac_cv_exeext if it was cached, +# so that the user can short-circuit this test for compilers unknown to +# Autoconf. +for ac_file in $ac_files '' +do + test -f "$ac_file" || continue + case $ac_file in + *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg | *.map | *.inf | *.dSYM | *.o | *.obj ) + ;; + [ab].out ) + # We found the default executable, but exeext='' is most + # certainly right. + break;; + *.* ) + if test "${ac_cv_exeext+set}" = set && test "$ac_cv_exeext" != no; + then :; else + ac_cv_exeext=`expr "$ac_file" : '[^.]*\(\..*\)'` + fi + # We set ac_cv_exeext here because the later test for it is not + # safe: cross compilers may not add the suffix if given an `-o' + # argument, so we may need to know it at that point already. + # Even if this section looks crufty: it has the advantage of + # actually working. + break;; + * ) + break;; + esac +done +test "$ac_cv_exeext" = no && ac_cv_exeext= + +else + ac_file='' +fi +if test -z "$ac_file"; then : + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +$as_echo "$as_me: failed program was:" >&5 +sed 's/^/| /' conftest.$ac_ext >&5 + +{ { $as_echo "$as_me:${as_lineno-$LINENO}: error: in \`$ac_pwd':" >&5 +$as_echo "$as_me: error: in \`$ac_pwd':" >&2;} +as_fn_error 77 "C compiler cannot create executables +See \`config.log' for more details" "$LINENO" 5 ; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for C compiler default output file name" >&5 +$as_echo_n "checking for C compiler default output file name... " >&6; } +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_file" >&5 +$as_echo "$ac_file" >&6; } +ac_exeext=$ac_cv_exeext + +rm -f -r a.out a.out.dSYM a.exe conftest$ac_cv_exeext b.out +ac_clean_files=$ac_clean_files_save +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for suffix of executables" >&5 +$as_echo_n "checking for suffix of executables... " >&6; } +if { { ac_try="$ac_link" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_link") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then : + # If both `conftest.exe' and `conftest' are `present' (well, observable) +# catch `conftest.exe'. For instance with Cygwin, `ls conftest' will +# work properly (i.e., refer to `conftest.exe'), while it won't with +# `rm'. +for ac_file in conftest.exe conftest conftest.*; do + test -f "$ac_file" || continue + case $ac_file in + *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg | *.map | *.inf | *.dSYM | *.o | *.obj ) ;; + *.* ) ac_cv_exeext=`expr "$ac_file" : '[^.]*\(\..*\)'` + break;; + * ) break;; + esac +done +else + { { $as_echo "$as_me:${as_lineno-$LINENO}: error: in \`$ac_pwd':" >&5 +$as_echo "$as_me: error: in \`$ac_pwd':" >&2;} +as_fn_error $? "cannot compute suffix of executables: cannot compile and link +See \`config.log' for more details" "$LINENO" 5 ; } +fi +rm -f conftest conftest$ac_cv_exeext +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_exeext" >&5 +$as_echo "$ac_cv_exeext" >&6; } + +rm -f conftest.$ac_ext +EXEEXT=$ac_cv_exeext +ac_exeext=$EXEEXT +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +int +main () +{ +FILE *f = fopen ("conftest.out", "w"); + return ferror (f) || fclose (f) != 0; + + ; + return 0; +} +_ACEOF +ac_clean_files="$ac_clean_files conftest.out" +# Check that the compiler produces executables we can run. If not, either +# the compiler is broken, or we cross compile. +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether we are cross compiling" >&5 +$as_echo_n "checking whether we are cross compiling... " >&6; } +if test "$cross_compiling" != yes; then + { { ac_try="$ac_link" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_link") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } + if { ac_try='./conftest$ac_cv_exeext' + { { case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_try") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; }; then + cross_compiling=no + else + if test "$cross_compiling" = maybe; then + cross_compiling=yes + else + { { $as_echo "$as_me:${as_lineno-$LINENO}: error: in \`$ac_pwd':" >&5 +$as_echo "$as_me: error: in \`$ac_pwd':" >&2;} +as_fn_error $? "cannot run C compiled programs. +If you meant to cross compile, use \`--host'. +See \`config.log' for more details" "$LINENO" 5 ; } + fi + fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $cross_compiling" >&5 +$as_echo "$cross_compiling" >&6; } + +rm -f conftest.$ac_ext conftest$ac_cv_exeext conftest.out +ac_clean_files=$ac_clean_files_save +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for suffix of object files" >&5 +$as_echo_n "checking for suffix of object files... " >&6; } +if test "${ac_cv_objext+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +rm -f conftest.o conftest.obj +if { { ac_try="$ac_compile" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_compile") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then : + for ac_file in conftest.o conftest.obj conftest.*; do + test -f "$ac_file" || continue; + case $ac_file in + *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg | *.map | *.inf | *.dSYM ) ;; + *) ac_cv_objext=`expr "$ac_file" : '.*\.\(.*\)'` + break;; + esac +done +else + $as_echo "$as_me: failed program was:" >&5 +sed 's/^/| /' conftest.$ac_ext >&5 + +{ { $as_echo "$as_me:${as_lineno-$LINENO}: error: in \`$ac_pwd':" >&5 +$as_echo "$as_me: error: in \`$ac_pwd':" >&2;} +as_fn_error $? "cannot compute suffix of object files: cannot compile +See \`config.log' for more details" "$LINENO" 5 ; } +fi +rm -f conftest.$ac_cv_objext conftest.$ac_ext +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_objext" >&5 +$as_echo "$ac_cv_objext" >&6; } +OBJEXT=$ac_cv_objext +ac_objext=$OBJEXT +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether we are using the GNU C compiler" >&5 +$as_echo_n "checking whether we are using the GNU C compiler... " >&6; } +if test "${ac_cv_c_compiler_gnu+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ +#ifndef __GNUC__ + choke me +#endif + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_compiler_gnu=yes +else + ac_compiler_gnu=no +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +ac_cv_c_compiler_gnu=$ac_compiler_gnu + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_c_compiler_gnu" >&5 +$as_echo "$ac_cv_c_compiler_gnu" >&6; } +if test $ac_compiler_gnu = yes; then + GCC=yes +else + GCC= +fi +ac_test_CFLAGS=${CFLAGS+set} +ac_save_CFLAGS=$CFLAGS +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether $CC accepts -g" >&5 +$as_echo_n "checking whether $CC accepts -g... " >&6; } +if test "${ac_cv_prog_cc_g+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_save_c_werror_flag=$ac_c_werror_flag + ac_c_werror_flag=yes + ac_cv_prog_cc_g=no + CFLAGS="-g" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_cv_prog_cc_g=yes +else + CFLAGS="" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + +else + ac_c_werror_flag=$ac_save_c_werror_flag + CFLAGS="-g" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_cv_prog_cc_g=yes +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext + ac_c_werror_flag=$ac_save_c_werror_flag +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_prog_cc_g" >&5 +$as_echo "$ac_cv_prog_cc_g" >&6; } +if test "$ac_test_CFLAGS" = set; then + CFLAGS=$ac_save_CFLAGS +elif test $ac_cv_prog_cc_g = yes; then + if test "$GCC" = yes; then + CFLAGS="-g -O2" + else + CFLAGS="-g" + fi +else + if test "$GCC" = yes; then + CFLAGS="-O2" + else + CFLAGS= + fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $CC option to accept ISO C89" >&5 +$as_echo_n "checking for $CC option to accept ISO C89... " >&6; } +if test "${ac_cv_prog_cc_c89+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_cv_prog_cc_c89=no +ac_save_CC=$CC +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +#include +#include +#include +/* Most of the following tests are stolen from RCS 5.7's src/conf.sh. */ +struct buf { int x; }; +FILE * (*rcsopen) (struct buf *, struct stat *, int); +static char *e (p, i) + char **p; + int i; +{ + return p[i]; +} +static char *f (char * (*g) (char **, int), char **p, ...) +{ + char *s; + va_list v; + va_start (v,p); + s = g (p, va_arg (v,int)); + va_end (v); + return s; +} + +/* OSF 4.0 Compaq cc is some sort of almost-ANSI by default. It has + function prototypes and stuff, but not '\xHH' hex character constants. + These don't provoke an error unfortunately, instead are silently treated + as 'x'. The following induces an error, until -std is added to get + proper ANSI mode. Curiously '\x00'!='x' always comes out true, for an + array size at least. It's necessary to write '\x00'==0 to get something + that's true only with -std. */ +int osf4_cc_array ['\x00' == 0 ? 1 : -1]; + +/* IBM C 6 for AIX is almost-ANSI by default, but it replaces macro parameters + inside strings and character constants. */ +#define FOO(x) 'x' +int xlc6_cc_array[FOO(a) == 'x' ? 1 : -1]; + +int test (int i, double x); +struct s1 {int (*f) (int a);}; +struct s2 {int (*f) (double a);}; +int pairnames (int, char **, FILE *(*)(struct buf *, struct stat *, int), int, int); +int argc; +char **argv; +int +main () +{ +return f (e, argv, 0) != argv[0] || f (e, argv, 1) != argv[1]; + ; + return 0; +} +_ACEOF +for ac_arg in '' -qlanglvl=extc89 -qlanglvl=ansi -std \ + -Ae "-Aa -D_HPUX_SOURCE" "-Xc -D__EXTENSIONS__" +do + CC="$ac_save_CC $ac_arg" + if ac_fn_c_try_compile "$LINENO"; then : + ac_cv_prog_cc_c89=$ac_arg +fi +rm -f core conftest.err conftest.$ac_objext + test "x$ac_cv_prog_cc_c89" != "xno" && break +done +rm -f conftest.$ac_ext +CC=$ac_save_CC + +fi +# AC_CACHE_VAL +case "x$ac_cv_prog_cc_c89" in + x) + { $as_echo "$as_me:${as_lineno-$LINENO}: result: none needed" >&5 +$as_echo "none needed" >&6; } ;; + xno) + { $as_echo "$as_me:${as_lineno-$LINENO}: result: unsupported" >&5 +$as_echo "unsupported" >&6; } ;; + *) + CC="$CC $ac_cv_prog_cc_c89" + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_prog_cc_c89" >&5 +$as_echo "$ac_cv_prog_cc_c89" >&6; } ;; +esac +if test "x$ac_cv_prog_cc_c89" != xno; then : + +fi + +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + +depcc="$CC" am_compiler_list= + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking dependency style of $depcc" >&5 +$as_echo_n "checking dependency style of $depcc... " >&6; } +if test "${am_cv_CC_dependencies_compiler_type+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -z "$AMDEP_TRUE" && test -f "$am_depcomp"; then + # We make a subdir and do the tests there. Otherwise we can end up + # making bogus files that we don't know about and never remove. For + # instance it was reported that on HP-UX the gcc test will end up + # making a dummy file named `D' -- because `-MD' means `put the output + # in D'. + mkdir conftest.dir + # Copy depcomp to subdir because otherwise we won't find it if we're + # using a relative directory. + cp "$am_depcomp" conftest.dir + cd conftest.dir + # We will build objects and dependencies in a subdirectory because + # it helps to detect inapplicable dependency modes. For instance + # both Tru64's cc and ICC support -MD to output dependencies as a + # side effect of compilation, but ICC will put the dependencies in + # the current directory while Tru64 will put them in the object + # directory. + mkdir sub + + am_cv_CC_dependencies_compiler_type=none + if test "$am_compiler_list" = ""; then + am_compiler_list=`sed -n 's/^#*\([a-zA-Z0-9]*\))$/\1/p' < ./depcomp` + fi + am__universal=false + case " $depcc " in #( + *\ -arch\ *\ -arch\ *) am__universal=true ;; + esac + + for depmode in $am_compiler_list; do + # Setup a source with many dependencies, because some compilers + # like to wrap large dependency lists on column 80 (with \), and + # we should not choose a depcomp mode which is confused by this. + # + # We need to recreate these files for each test, as the compiler may + # overwrite some of them when testing with obscure command lines. + # This happens at least with the AIX C compiler. + : > sub/conftest.c + for i in 1 2 3 4 5 6; do + echo '#include "conftst'$i'.h"' >> sub/conftest.c + # Using `: > sub/conftst$i.h' creates only sub/conftst1.h with + # Solaris 8's {/usr,}/bin/sh. + touch sub/conftst$i.h + done + echo "${am__include} ${am__quote}sub/conftest.Po${am__quote}" > confmf + + # We check with `-c' and `-o' for the sake of the "dashmstdout" + # mode. It turns out that the SunPro C++ compiler does not properly + # handle `-M -o', and we need to detect this. Also, some Intel + # versions had trouble with output in subdirs + am__obj=sub/conftest.${OBJEXT-o} + am__minus_obj="-o $am__obj" + case $depmode in + gcc) + # This depmode causes a compiler race in universal mode. + test "$am__universal" = false || continue + ;; + nosideeffect) + # after this tag, mechanisms are not by side-effect, so they'll + # only be used when explicitly requested + if test "x$enable_dependency_tracking" = xyes; then + continue + else + break + fi + ;; + msvisualcpp | msvcmsys) + # This compiler won't grok `-c -o', but also, the minuso test has + # not run yet. These depmodes are late enough in the game, and + # so weak that their functioning should not be impacted. + am__obj=conftest.${OBJEXT-o} + am__minus_obj= + ;; + none) break ;; + esac + if depmode=$depmode \ + source=sub/conftest.c object=$am__obj \ + depfile=sub/conftest.Po tmpdepfile=sub/conftest.TPo \ + $SHELL ./depcomp $depcc -c $am__minus_obj sub/conftest.c \ + >/dev/null 2>conftest.err && + grep sub/conftst1.h sub/conftest.Po > /dev/null 2>&1 && + grep sub/conftst6.h sub/conftest.Po > /dev/null 2>&1 && + grep $am__obj sub/conftest.Po > /dev/null 2>&1 && + ${MAKE-make} -s -f confmf > /dev/null 2>&1; then + # icc doesn't choke on unknown options, it will just issue warnings + # or remarks (even with -Werror). So we grep stderr for any message + # that says an option was ignored or not supported. + # When given -MP, icc 7.0 and 7.1 complain thusly: + # icc: Command line warning: ignoring option '-M'; no argument required + # The diagnosis changed in icc 8.0: + # icc: Command line remark: option '-MP' not supported + if (grep 'ignoring option' conftest.err || + grep 'not supported' conftest.err) >/dev/null 2>&1; then :; else + am_cv_CC_dependencies_compiler_type=$depmode + break + fi + fi + done + + cd .. + rm -rf conftest.dir +else + am_cv_CC_dependencies_compiler_type=none +fi + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $am_cv_CC_dependencies_compiler_type" >&5 +$as_echo "$am_cv_CC_dependencies_compiler_type" >&6; } +CCDEPMODE=depmode=$am_cv_CC_dependencies_compiler_type + + if + test "x$enable_dependency_tracking" != xno \ + && test "$am_cv_CC_dependencies_compiler_type" = gcc3; then + am__fastdepCC_TRUE= + am__fastdepCC_FALSE='#' +else + am__fastdepCC_TRUE='#' + am__fastdepCC_FALSE= +fi + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for a sed that does not truncate output" >&5 +$as_echo_n "checking for a sed that does not truncate output... " >&6; } +if test "${ac_cv_path_SED+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_script=s/aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa/bbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbb/ + for ac_i in 1 2 3 4 5 6 7; do + ac_script="$ac_script$as_nl$ac_script" + done + echo "$ac_script" 2>/dev/null | sed 99q >conftest.sed + { ac_script=; unset ac_script;} + if test -z "$SED"; then + ac_path_SED_found=false + # Loop through the user's path and test for each of PROGNAME-LIST + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_prog in sed gsed; do + for ac_exec_ext in '' $ac_executable_extensions; do + ac_path_SED="$as_dir/$ac_prog$ac_exec_ext" + { test -f "$ac_path_SED" && $as_test_x "$ac_path_SED"; } || continue +# Check for GNU ac_path_SED and select it if it is found. + # Check for GNU $ac_path_SED +case `"$ac_path_SED" --version 2>&1` in +*GNU*) + ac_cv_path_SED="$ac_path_SED" ac_path_SED_found=:;; +*) + ac_count=0 + $as_echo_n 0123456789 >"conftest.in" + while : + do + cat "conftest.in" "conftest.in" >"conftest.tmp" + mv "conftest.tmp" "conftest.in" + cp "conftest.in" "conftest.nl" + $as_echo '' >> "conftest.nl" + "$ac_path_SED" -f conftest.sed < "conftest.nl" >"conftest.out" 2>/dev/null || break + diff "conftest.out" "conftest.nl" >/dev/null 2>&1 || break + as_fn_arith $ac_count + 1 && ac_count=$as_val + if test $ac_count -gt ${ac_path_SED_max-0}; then + # Best one so far, save it but keep looking for a better one + ac_cv_path_SED="$ac_path_SED" + ac_path_SED_max=$ac_count + fi + # 10*(2^10) chars as input seems more than enough + test $ac_count -gt 10 && break + done + rm -f conftest.in conftest.tmp conftest.nl conftest.out;; +esac + + $ac_path_SED_found && break 3 + done + done + done +IFS=$as_save_IFS + if test -z "$ac_cv_path_SED"; then + as_fn_error $? "no acceptable sed could be found in \$PATH" "$LINENO" 5 + fi +else + ac_cv_path_SED=$SED +fi + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_path_SED" >&5 +$as_echo "$ac_cv_path_SED" >&6; } + SED="$ac_cv_path_SED" + rm -f conftest.sed + +test -z "$SED" && SED=sed +Xsed="$SED -e 1s/^X//" + + + + + + + + + + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for grep that handles long lines and -e" >&5 +$as_echo_n "checking for grep that handles long lines and -e... " >&6; } +if test "${ac_cv_path_GREP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -z "$GREP"; then + ac_path_GREP_found=false + # Loop through the user's path and test for each of PROGNAME-LIST + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH$PATH_SEPARATOR/usr/xpg4/bin +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_prog in grep ggrep; do + for ac_exec_ext in '' $ac_executable_extensions; do + ac_path_GREP="$as_dir/$ac_prog$ac_exec_ext" + { test -f "$ac_path_GREP" && $as_test_x "$ac_path_GREP"; } || continue +# Check for GNU ac_path_GREP and select it if it is found. + # Check for GNU $ac_path_GREP +case `"$ac_path_GREP" --version 2>&1` in +*GNU*) + ac_cv_path_GREP="$ac_path_GREP" ac_path_GREP_found=:;; +*) + ac_count=0 + $as_echo_n 0123456789 >"conftest.in" + while : + do + cat "conftest.in" "conftest.in" >"conftest.tmp" + mv "conftest.tmp" "conftest.in" + cp "conftest.in" "conftest.nl" + $as_echo 'GREP' >> "conftest.nl" + "$ac_path_GREP" -e 'GREP$' -e '-(cannot match)-' < "conftest.nl" >"conftest.out" 2>/dev/null || break + diff "conftest.out" "conftest.nl" >/dev/null 2>&1 || break + as_fn_arith $ac_count + 1 && ac_count=$as_val + if test $ac_count -gt ${ac_path_GREP_max-0}; then + # Best one so far, save it but keep looking for a better one + ac_cv_path_GREP="$ac_path_GREP" + ac_path_GREP_max=$ac_count + fi + # 10*(2^10) chars as input seems more than enough + test $ac_count -gt 10 && break + done + rm -f conftest.in conftest.tmp conftest.nl conftest.out;; +esac + + $ac_path_GREP_found && break 3 + done + done + done +IFS=$as_save_IFS + if test -z "$ac_cv_path_GREP"; then + as_fn_error $? "no acceptable grep could be found in $PATH$PATH_SEPARATOR/usr/xpg4/bin" "$LINENO" 5 + fi +else + ac_cv_path_GREP=$GREP +fi + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_path_GREP" >&5 +$as_echo "$ac_cv_path_GREP" >&6; } + GREP="$ac_cv_path_GREP" + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for egrep" >&5 +$as_echo_n "checking for egrep... " >&6; } +if test "${ac_cv_path_EGREP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if echo a | $GREP -E '(a|b)' >/dev/null 2>&1 + then ac_cv_path_EGREP="$GREP -E" + else + if test -z "$EGREP"; then + ac_path_EGREP_found=false + # Loop through the user's path and test for each of PROGNAME-LIST + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH$PATH_SEPARATOR/usr/xpg4/bin +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_prog in egrep; do + for ac_exec_ext in '' $ac_executable_extensions; do + ac_path_EGREP="$as_dir/$ac_prog$ac_exec_ext" + { test -f "$ac_path_EGREP" && $as_test_x "$ac_path_EGREP"; } || continue +# Check for GNU ac_path_EGREP and select it if it is found. + # Check for GNU $ac_path_EGREP +case `"$ac_path_EGREP" --version 2>&1` in +*GNU*) + ac_cv_path_EGREP="$ac_path_EGREP" ac_path_EGREP_found=:;; +*) + ac_count=0 + $as_echo_n 0123456789 >"conftest.in" + while : + do + cat "conftest.in" "conftest.in" >"conftest.tmp" + mv "conftest.tmp" "conftest.in" + cp "conftest.in" "conftest.nl" + $as_echo 'EGREP' >> "conftest.nl" + "$ac_path_EGREP" 'EGREP$' < "conftest.nl" >"conftest.out" 2>/dev/null || break + diff "conftest.out" "conftest.nl" >/dev/null 2>&1 || break + as_fn_arith $ac_count + 1 && ac_count=$as_val + if test $ac_count -gt ${ac_path_EGREP_max-0}; then + # Best one so far, save it but keep looking for a better one + ac_cv_path_EGREP="$ac_path_EGREP" + ac_path_EGREP_max=$ac_count + fi + # 10*(2^10) chars as input seems more than enough + test $ac_count -gt 10 && break + done + rm -f conftest.in conftest.tmp conftest.nl conftest.out;; +esac + + $ac_path_EGREP_found && break 3 + done + done + done +IFS=$as_save_IFS + if test -z "$ac_cv_path_EGREP"; then + as_fn_error $? "no acceptable egrep could be found in $PATH$PATH_SEPARATOR/usr/xpg4/bin" "$LINENO" 5 + fi +else + ac_cv_path_EGREP=$EGREP +fi + + fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_path_EGREP" >&5 +$as_echo "$ac_cv_path_EGREP" >&6; } + EGREP="$ac_cv_path_EGREP" + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for fgrep" >&5 +$as_echo_n "checking for fgrep... " >&6; } +if test "${ac_cv_path_FGREP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if echo 'ab*c' | $GREP -F 'ab*c' >/dev/null 2>&1 + then ac_cv_path_FGREP="$GREP -F" + else + if test -z "$FGREP"; then + ac_path_FGREP_found=false + # Loop through the user's path and test for each of PROGNAME-LIST + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH$PATH_SEPARATOR/usr/xpg4/bin +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_prog in fgrep; do + for ac_exec_ext in '' $ac_executable_extensions; do + ac_path_FGREP="$as_dir/$ac_prog$ac_exec_ext" + { test -f "$ac_path_FGREP" && $as_test_x "$ac_path_FGREP"; } || continue +# Check for GNU ac_path_FGREP and select it if it is found. + # Check for GNU $ac_path_FGREP +case `"$ac_path_FGREP" --version 2>&1` in +*GNU*) + ac_cv_path_FGREP="$ac_path_FGREP" ac_path_FGREP_found=:;; +*) + ac_count=0 + $as_echo_n 0123456789 >"conftest.in" + while : + do + cat "conftest.in" "conftest.in" >"conftest.tmp" + mv "conftest.tmp" "conftest.in" + cp "conftest.in" "conftest.nl" + $as_echo 'FGREP' >> "conftest.nl" + "$ac_path_FGREP" FGREP < "conftest.nl" >"conftest.out" 2>/dev/null || break + diff "conftest.out" "conftest.nl" >/dev/null 2>&1 || break + as_fn_arith $ac_count + 1 && ac_count=$as_val + if test $ac_count -gt ${ac_path_FGREP_max-0}; then + # Best one so far, save it but keep looking for a better one + ac_cv_path_FGREP="$ac_path_FGREP" + ac_path_FGREP_max=$ac_count + fi + # 10*(2^10) chars as input seems more than enough + test $ac_count -gt 10 && break + done + rm -f conftest.in conftest.tmp conftest.nl conftest.out;; +esac + + $ac_path_FGREP_found && break 3 + done + done + done +IFS=$as_save_IFS + if test -z "$ac_cv_path_FGREP"; then + as_fn_error $? "no acceptable fgrep could be found in $PATH$PATH_SEPARATOR/usr/xpg4/bin" "$LINENO" 5 + fi +else + ac_cv_path_FGREP=$FGREP +fi + + fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_path_FGREP" >&5 +$as_echo "$ac_cv_path_FGREP" >&6; } + FGREP="$ac_cv_path_FGREP" + + +test -z "$GREP" && GREP=grep + + + + + + + + + + + + + + + + + + + +# Check whether --with-gnu-ld was given. +if test "${with_gnu_ld+set}" = set; then : + withval=$with_gnu_ld; test "$withval" = no || with_gnu_ld=yes +else + with_gnu_ld=no +fi + +ac_prog=ld +if test "$GCC" = yes; then + # Check if gcc -print-prog-name=ld gives a path. + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for ld used by $CC" >&5 +$as_echo_n "checking for ld used by $CC... " >&6; } + case $host in + *-*-mingw*) + # gcc leaves a trailing carriage return which upsets mingw + ac_prog=`($CC -print-prog-name=ld) 2>&5 | tr -d '\015'` ;; + *) + ac_prog=`($CC -print-prog-name=ld) 2>&5` ;; + esac + case $ac_prog in + # Accept absolute paths. + [\\/]* | ?:[\\/]*) + re_direlt='/[^/][^/]*/\.\./' + # Canonicalize the pathname of ld + ac_prog=`$ECHO "$ac_prog"| $SED 's%\\\\%/%g'` + while $ECHO "$ac_prog" | $GREP "$re_direlt" > /dev/null 2>&1; do + ac_prog=`$ECHO $ac_prog| $SED "s%$re_direlt%/%"` + done + test -z "$LD" && LD="$ac_prog" + ;; + "") + # If it fails, then pretend we aren't using GCC. + ac_prog=ld + ;; + *) + # If it is relative, then search for the first ld in PATH. + with_gnu_ld=unknown + ;; + esac +elif test "$with_gnu_ld" = yes; then + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for GNU ld" >&5 +$as_echo_n "checking for GNU ld... " >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for non-GNU ld" >&5 +$as_echo_n "checking for non-GNU ld... " >&6; } +fi +if test "${lt_cv_path_LD+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -z "$LD"; then + lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + for ac_dir in $PATH; do + IFS="$lt_save_ifs" + test -z "$ac_dir" && ac_dir=. + if test -f "$ac_dir/$ac_prog" || test -f "$ac_dir/$ac_prog$ac_exeext"; then + lt_cv_path_LD="$ac_dir/$ac_prog" + # Check to see if the program is GNU ld. I'd rather use --version, + # but apparently some variants of GNU ld only accept -v. + # Break only if it was the GNU/non-GNU ld that we prefer. + case `"$lt_cv_path_LD" -v 2>&1 &5 +$as_echo "$LD" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi +test -z "$LD" && as_fn_error $? "no acceptable ld found in \$PATH" "$LINENO" 5 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking if the linker ($LD) is GNU ld" >&5 +$as_echo_n "checking if the linker ($LD) is GNU ld... " >&6; } +if test "${lt_cv_prog_gnu_ld+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + # I'd rather use --version here, but apparently some GNU lds only accept -v. +case `$LD -v 2>&1 &5 +$as_echo "$lt_cv_prog_gnu_ld" >&6; } +with_gnu_ld=$lt_cv_prog_gnu_ld + + + + + + + + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for BSD- or MS-compatible name lister (nm)" >&5 +$as_echo_n "checking for BSD- or MS-compatible name lister (nm)... " >&6; } +if test "${lt_cv_path_NM+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$NM"; then + # Let the user override the test. + lt_cv_path_NM="$NM" +else + lt_nm_to_check="${ac_tool_prefix}nm" + if test -n "$ac_tool_prefix" && test "$build" = "$host"; then + lt_nm_to_check="$lt_nm_to_check nm" + fi + for lt_tmp_nm in $lt_nm_to_check; do + lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + for ac_dir in $PATH /usr/ccs/bin/elf /usr/ccs/bin /usr/ucb /bin; do + IFS="$lt_save_ifs" + test -z "$ac_dir" && ac_dir=. + tmp_nm="$ac_dir/$lt_tmp_nm" + if test -f "$tmp_nm" || test -f "$tmp_nm$ac_exeext" ; then + # Check to see if the nm accepts a BSD-compat flag. + # Adding the `sed 1q' prevents false positives on HP-UX, which says: + # nm: unknown option "B" ignored + # Tru64's nm complains that /dev/null is an invalid object file + case `"$tmp_nm" -B /dev/null 2>&1 | sed '1q'` in + */dev/null* | *'Invalid file or object type'*) + lt_cv_path_NM="$tmp_nm -B" + break + ;; + *) + case `"$tmp_nm" -p /dev/null 2>&1 | sed '1q'` in + */dev/null*) + lt_cv_path_NM="$tmp_nm -p" + break + ;; + *) + lt_cv_path_NM=${lt_cv_path_NM="$tmp_nm"} # keep the first match, but + continue # so that we can try to find one that supports BSD flags + ;; + esac + ;; + esac + fi + done + IFS="$lt_save_ifs" + done + : ${lt_cv_path_NM=no} +fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_path_NM" >&5 +$as_echo "$lt_cv_path_NM" >&6; } +if test "$lt_cv_path_NM" != "no"; then + NM="$lt_cv_path_NM" +else + # Didn't find any BSD compatible name lister, look for dumpbin. + if test -n "$ac_tool_prefix"; then + for ac_prog in "dumpbin -symbols" "link -dump -symbols" + do + # Extract the first word of "$ac_tool_prefix$ac_prog", so it can be a program name with args. +set dummy $ac_tool_prefix$ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_DUMPBIN+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$DUMPBIN"; then + ac_cv_prog_DUMPBIN="$DUMPBIN" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_DUMPBIN="$ac_tool_prefix$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +DUMPBIN=$ac_cv_prog_DUMPBIN +if test -n "$DUMPBIN"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $DUMPBIN" >&5 +$as_echo "$DUMPBIN" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$DUMPBIN" && break + done +fi +if test -z "$DUMPBIN"; then + ac_ct_DUMPBIN=$DUMPBIN + for ac_prog in "dumpbin -symbols" "link -dump -symbols" +do + # Extract the first word of "$ac_prog", so it can be a program name with args. +set dummy $ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_DUMPBIN+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_DUMPBIN"; then + ac_cv_prog_ac_ct_DUMPBIN="$ac_ct_DUMPBIN" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_DUMPBIN="$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_DUMPBIN=$ac_cv_prog_ac_ct_DUMPBIN +if test -n "$ac_ct_DUMPBIN"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_DUMPBIN" >&5 +$as_echo "$ac_ct_DUMPBIN" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$ac_ct_DUMPBIN" && break +done + + if test "x$ac_ct_DUMPBIN" = x; then + DUMPBIN=":" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + DUMPBIN=$ac_ct_DUMPBIN + fi +fi + + + if test "$DUMPBIN" != ":"; then + NM="$DUMPBIN" + fi +fi +test -z "$NM" && NM=nm + + + + + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking the name lister ($NM) interface" >&5 +$as_echo_n "checking the name lister ($NM) interface... " >&6; } +if test "${lt_cv_nm_interface+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_nm_interface="BSD nm" + echo "int some_variable = 0;" > conftest.$ac_ext + (eval echo "\"\$as_me:4898: $ac_compile\"" >&5) + (eval "$ac_compile" 2>conftest.err) + cat conftest.err >&5 + (eval echo "\"\$as_me:4901: $NM \\\"conftest.$ac_objext\\\"\"" >&5) + (eval "$NM \"conftest.$ac_objext\"" 2>conftest.err > conftest.out) + cat conftest.err >&5 + (eval echo "\"\$as_me:4904: output\"" >&5) + cat conftest.out >&5 + if $GREP 'External.*some_variable' conftest.out > /dev/null; then + lt_cv_nm_interface="MS dumpbin" + fi + rm -f conftest* +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_nm_interface" >&5 +$as_echo "$lt_cv_nm_interface" >&6; } + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether ln -s works" >&5 +$as_echo_n "checking whether ln -s works... " >&6; } +LN_S=$as_ln_s +if test "$LN_S" = "ln -s"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no, using $LN_S" >&5 +$as_echo "no, using $LN_S" >&6; } +fi + +# find the maximum length of command line arguments +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking the maximum length of command line arguments" >&5 +$as_echo_n "checking the maximum length of command line arguments... " >&6; } +if test "${lt_cv_sys_max_cmd_len+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + i=0 + teststring="ABCD" + + case $build_os in + msdosdjgpp*) + # On DJGPP, this test can blow up pretty badly due to problems in libc + # (any single argument exceeding 2000 bytes causes a buffer overrun + # during glob expansion). Even if it were fixed, the result of this + # check would be larger than it should be. + lt_cv_sys_max_cmd_len=12288; # 12K is about right + ;; + + gnu*) + # Under GNU Hurd, this test is not required because there is + # no limit to the length of command line arguments. + # Libtool will interpret -1 as no limit whatsoever + lt_cv_sys_max_cmd_len=-1; + ;; + + cygwin* | mingw* | cegcc*) + # On Win9x/ME, this test blows up -- it succeeds, but takes + # about 5 minutes as the teststring grows exponentially. + # Worse, since 9x/ME are not pre-emptively multitasking, + # you end up with a "frozen" computer, even though with patience + # the test eventually succeeds (with a max line length of 256k). + # Instead, let's just punt: use the minimum linelength reported by + # all of the supported platforms: 8192 (on NT/2K/XP). + lt_cv_sys_max_cmd_len=8192; + ;; + + amigaos*) + # On AmigaOS with pdksh, this test takes hours, literally. + # So we just punt and use a minimum line length of 8192. + lt_cv_sys_max_cmd_len=8192; + ;; + + netbsd* | freebsd* | openbsd* | darwin* | dragonfly*) + # This has been around since 386BSD, at least. Likely further. + if test -x /sbin/sysctl; then + lt_cv_sys_max_cmd_len=`/sbin/sysctl -n kern.argmax` + elif test -x /usr/sbin/sysctl; then + lt_cv_sys_max_cmd_len=`/usr/sbin/sysctl -n kern.argmax` + else + lt_cv_sys_max_cmd_len=65536 # usable default for all BSDs + fi + # And add a safety zone + lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \/ 4` + lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \* 3` + ;; + + interix*) + # We know the value 262144 and hardcode it with a safety zone (like BSD) + lt_cv_sys_max_cmd_len=196608 + ;; + + osf*) + # Dr. Hans Ekkehard Plesser reports seeing a kernel panic running configure + # due to this test when exec_disable_arg_limit is 1 on Tru64. It is not + # nice to cause kernel panics so lets avoid the loop below. + # First set a reasonable default. + lt_cv_sys_max_cmd_len=16384 + # + if test -x /sbin/sysconfig; then + case `/sbin/sysconfig -q proc exec_disable_arg_limit` in + *1*) lt_cv_sys_max_cmd_len=-1 ;; + esac + fi + ;; + sco3.2v5*) + lt_cv_sys_max_cmd_len=102400 + ;; + sysv5* | sco5v6* | sysv4.2uw2*) + kargmax=`grep ARG_MAX /etc/conf/cf.d/stune 2>/dev/null` + if test -n "$kargmax"; then + lt_cv_sys_max_cmd_len=`echo $kargmax | sed 's/.*[ ]//'` + else + lt_cv_sys_max_cmd_len=32768 + fi + ;; + *) + lt_cv_sys_max_cmd_len=`(getconf ARG_MAX) 2> /dev/null` + if test -n "$lt_cv_sys_max_cmd_len"; then + lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \/ 4` + lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \* 3` + else + # Make teststring a little bigger before we do anything with it. + # a 1K string should be a reasonable start. + for i in 1 2 3 4 5 6 7 8 ; do + teststring=$teststring$teststring + done + SHELL=${SHELL-${CONFIG_SHELL-/bin/sh}} + # If test is not a shell built-in, we'll probably end up computing a + # maximum length that is only half of the actual maximum length, but + # we can't tell. + while { test "X"`$SHELL $0 --fallback-echo "X$teststring$teststring" 2>/dev/null` \ + = "XX$teststring$teststring"; } >/dev/null 2>&1 && + test $i != 17 # 1/2 MB should be enough + do + i=`expr $i + 1` + teststring=$teststring$teststring + done + # Only check the string length outside the loop. + lt_cv_sys_max_cmd_len=`expr "X$teststring" : ".*" 2>&1` + teststring= + # Add a significant safety factor because C++ compilers can tack on + # massive amounts of additional arguments before passing them to the + # linker. It appears as though 1/2 is a usable value. + lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \/ 2` + fi + ;; + esac + +fi + +if test -n $lt_cv_sys_max_cmd_len ; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_sys_max_cmd_len" >&5 +$as_echo "$lt_cv_sys_max_cmd_len" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: none" >&5 +$as_echo "none" >&6; } +fi +max_cmd_len=$lt_cv_sys_max_cmd_len + + + + + + +: ${CP="cp -f"} +: ${MV="mv -f"} +: ${RM="rm -f"} + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether the shell understands some XSI constructs" >&5 +$as_echo_n "checking whether the shell understands some XSI constructs... " >&6; } +# Try some XSI features +xsi_shell=no +( _lt_dummy="a/b/c" + test "${_lt_dummy##*/},${_lt_dummy%/*},"${_lt_dummy%"$_lt_dummy"}, \ + = c,a/b,, \ + && eval 'test $(( 1 + 1 )) -eq 2 \ + && test "${#_lt_dummy}" -eq 5' ) >/dev/null 2>&1 \ + && xsi_shell=yes +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $xsi_shell" >&5 +$as_echo "$xsi_shell" >&6; } + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether the shell understands \"+=\"" >&5 +$as_echo_n "checking whether the shell understands \"+=\"... " >&6; } +lt_shell_append=no +( foo=bar; set foo baz; eval "$1+=\$2" && test "$foo" = barbaz ) \ + >/dev/null 2>&1 \ + && lt_shell_append=yes +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_shell_append" >&5 +$as_echo "$lt_shell_append" >&6; } + + +if ( (MAIL=60; unset MAIL) || exit) >/dev/null 2>&1; then + lt_unset=unset +else + lt_unset=false +fi + + + + + +# test EBCDIC or ASCII +case `echo X|tr X '\101'` in + A) # ASCII based system + # \n is not interpreted correctly by Solaris 8 /usr/ucb/tr + lt_SP2NL='tr \040 \012' + lt_NL2SP='tr \015\012 \040\040' + ;; + *) # EBCDIC based system + lt_SP2NL='tr \100 \n' + lt_NL2SP='tr \r\n \100\100' + ;; +esac + + + + + + + + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $LD option to reload object files" >&5 +$as_echo_n "checking for $LD option to reload object files... " >&6; } +if test "${lt_cv_ld_reload_flag+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_ld_reload_flag='-r' +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_ld_reload_flag" >&5 +$as_echo "$lt_cv_ld_reload_flag" >&6; } +reload_flag=$lt_cv_ld_reload_flag +case $reload_flag in +"" | " "*) ;; +*) reload_flag=" $reload_flag" ;; +esac +reload_cmds='$LD$reload_flag -o $output$reload_objs' +case $host_os in + darwin*) + if test "$GCC" = yes; then + reload_cmds='$LTCC $LTCFLAGS -nostdlib ${wl}-r -o $output$reload_objs' + else + reload_cmds='$LD$reload_flag -o $output$reload_objs' + fi + ;; +esac + + + + + + + + + +if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}objdump", so it can be a program name with args. +set dummy ${ac_tool_prefix}objdump; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_OBJDUMP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$OBJDUMP"; then + ac_cv_prog_OBJDUMP="$OBJDUMP" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_OBJDUMP="${ac_tool_prefix}objdump" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +OBJDUMP=$ac_cv_prog_OBJDUMP +if test -n "$OBJDUMP"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $OBJDUMP" >&5 +$as_echo "$OBJDUMP" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_OBJDUMP"; then + ac_ct_OBJDUMP=$OBJDUMP + # Extract the first word of "objdump", so it can be a program name with args. +set dummy objdump; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_OBJDUMP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_OBJDUMP"; then + ac_cv_prog_ac_ct_OBJDUMP="$ac_ct_OBJDUMP" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_OBJDUMP="objdump" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_OBJDUMP=$ac_cv_prog_ac_ct_OBJDUMP +if test -n "$ac_ct_OBJDUMP"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_OBJDUMP" >&5 +$as_echo "$ac_ct_OBJDUMP" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_OBJDUMP" = x; then + OBJDUMP="false" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + OBJDUMP=$ac_ct_OBJDUMP + fi +else + OBJDUMP="$ac_cv_prog_OBJDUMP" +fi + +test -z "$OBJDUMP" && OBJDUMP=objdump + + + + + + + + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking how to recognize dependent libraries" >&5 +$as_echo_n "checking how to recognize dependent libraries... " >&6; } +if test "${lt_cv_deplibs_check_method+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_file_magic_cmd='$MAGIC_CMD' +lt_cv_file_magic_test_file= +lt_cv_deplibs_check_method='unknown' +# Need to set the preceding variable on all platforms that support +# interlibrary dependencies. +# 'none' -- dependencies not supported. +# `unknown' -- same as none, but documents that we really don't know. +# 'pass_all' -- all dependencies passed with no checks. +# 'test_compile' -- check by making test program. +# 'file_magic [[regex]]' -- check by looking for files in library path +# which responds to the $file_magic_cmd with a given extended regex. +# If you have `file' or equivalent on your system and you're not sure +# whether `pass_all' will *always* work, you probably want this one. + +case $host_os in +aix[4-9]*) + lt_cv_deplibs_check_method=pass_all + ;; + +beos*) + lt_cv_deplibs_check_method=pass_all + ;; + +bsdi[45]*) + lt_cv_deplibs_check_method='file_magic ELF [0-9][0-9]*-bit [ML]SB (shared object|dynamic lib)' + lt_cv_file_magic_cmd='/usr/bin/file -L' + lt_cv_file_magic_test_file=/shlib/libc.so + ;; + +cygwin*) + # func_win32_libid is a shell function defined in ltmain.sh + lt_cv_deplibs_check_method='file_magic ^x86 archive import|^x86 DLL' + lt_cv_file_magic_cmd='func_win32_libid' + ;; + +mingw* | pw32*) + # Base MSYS/MinGW do not provide the 'file' command needed by + # func_win32_libid shell function, so use a weaker test based on 'objdump', + # unless we find 'file', for example because we are cross-compiling. + if ( file / ) >/dev/null 2>&1; then + lt_cv_deplibs_check_method='file_magic ^x86 archive import|^x86 DLL' + lt_cv_file_magic_cmd='func_win32_libid' + else + lt_cv_deplibs_check_method='file_magic file format pei*-i386(.*architecture: i386)?' + lt_cv_file_magic_cmd='$OBJDUMP -f' + fi + ;; + +cegcc) + # use the weaker test based on 'objdump'. See mingw*. + lt_cv_deplibs_check_method='file_magic file format pe-arm-.*little(.*architecture: arm)?' + lt_cv_file_magic_cmd='$OBJDUMP -f' + ;; + +darwin* | rhapsody*) + lt_cv_deplibs_check_method=pass_all + ;; + +freebsd* | dragonfly*) + if echo __ELF__ | $CC -E - | $GREP __ELF__ > /dev/null; then + case $host_cpu in + i*86 ) + # Not sure whether the presence of OpenBSD here was a mistake. + # Let's accept both of them until this is cleared up. + lt_cv_deplibs_check_method='file_magic (FreeBSD|OpenBSD|DragonFly)/i[3-9]86 (compact )?demand paged shared library' + lt_cv_file_magic_cmd=/usr/bin/file + lt_cv_file_magic_test_file=`echo /usr/lib/libc.so.*` + ;; + esac + else + lt_cv_deplibs_check_method=pass_all + fi + ;; + +gnu*) + lt_cv_deplibs_check_method=pass_all + ;; + +hpux10.20* | hpux11*) + lt_cv_file_magic_cmd=/usr/bin/file + case $host_cpu in + ia64*) + lt_cv_deplibs_check_method='file_magic (s[0-9][0-9][0-9]|ELF-[0-9][0-9]) shared object file - IA64' + lt_cv_file_magic_test_file=/usr/lib/hpux32/libc.so + ;; + hppa*64*) + lt_cv_deplibs_check_method='file_magic (s[0-9][0-9][0-9]|ELF-[0-9][0-9]) shared object file - PA-RISC [0-9].[0-9]' + lt_cv_file_magic_test_file=/usr/lib/pa20_64/libc.sl + ;; + *) + lt_cv_deplibs_check_method='file_magic (s[0-9][0-9][0-9]|PA-RISC[0-9].[0-9]) shared library' + lt_cv_file_magic_test_file=/usr/lib/libc.sl + ;; + esac + ;; + +interix[3-9]*) + # PIC code is broken on Interix 3.x, that's why |\.a not |_pic\.a here + lt_cv_deplibs_check_method='match_pattern /lib[^/]+(\.so|\.a)$' + ;; + +irix5* | irix6* | nonstopux*) + case $LD in + *-32|*"-32 ") libmagic=32-bit;; + *-n32|*"-n32 ") libmagic=N32;; + *-64|*"-64 ") libmagic=64-bit;; + *) libmagic=never-match;; + esac + lt_cv_deplibs_check_method=pass_all + ;; + +# This must be Linux ELF. +linux* | k*bsd*-gnu | kopensolaris*-gnu) + lt_cv_deplibs_check_method=pass_all + ;; + +netbsd* | netbsdelf*-gnu) + if echo __ELF__ | $CC -E - | $GREP __ELF__ > /dev/null; then + lt_cv_deplibs_check_method='match_pattern /lib[^/]+(\.so\.[0-9]+\.[0-9]+|_pic\.a)$' + else + lt_cv_deplibs_check_method='match_pattern /lib[^/]+(\.so|_pic\.a)$' + fi + ;; + +newos6*) + lt_cv_deplibs_check_method='file_magic ELF [0-9][0-9]*-bit [ML]SB (executable|dynamic lib)' + lt_cv_file_magic_cmd=/usr/bin/file + lt_cv_file_magic_test_file=/usr/lib/libnls.so + ;; + +*nto* | *qnx*) + lt_cv_deplibs_check_method=pass_all + ;; + +openbsd*) + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + lt_cv_deplibs_check_method='match_pattern /lib[^/]+(\.so\.[0-9]+\.[0-9]+|\.so|_pic\.a)$' + else + lt_cv_deplibs_check_method='match_pattern /lib[^/]+(\.so\.[0-9]+\.[0-9]+|_pic\.a)$' + fi + ;; + +osf3* | osf4* | osf5*) + lt_cv_deplibs_check_method=pass_all + ;; + +rdos*) + lt_cv_deplibs_check_method=pass_all + ;; + +solaris*) + lt_cv_deplibs_check_method=pass_all + ;; + +sysv5* | sco3.2v5* | sco5v6* | unixware* | OpenUNIX* | sysv4*uw2*) + lt_cv_deplibs_check_method=pass_all + ;; + +sysv4 | sysv4.3*) + case $host_vendor in + motorola) + lt_cv_deplibs_check_method='file_magic ELF [0-9][0-9]*-bit [ML]SB (shared object|dynamic lib) M[0-9][0-9]* Version [0-9]' + lt_cv_file_magic_test_file=`echo /usr/lib/libc.so*` + ;; + ncr) + lt_cv_deplibs_check_method=pass_all + ;; + sequent) + lt_cv_file_magic_cmd='/bin/file' + lt_cv_deplibs_check_method='file_magic ELF [0-9][0-9]*-bit [LM]SB (shared object|dynamic lib )' + ;; + sni) + lt_cv_file_magic_cmd='/bin/file' + lt_cv_deplibs_check_method="file_magic ELF [0-9][0-9]*-bit [LM]SB dynamic lib" + lt_cv_file_magic_test_file=/lib/libc.so + ;; + siemens) + lt_cv_deplibs_check_method=pass_all + ;; + pc) + lt_cv_deplibs_check_method=pass_all + ;; + esac + ;; + +tpf*) + lt_cv_deplibs_check_method=pass_all + ;; +esac + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_deplibs_check_method" >&5 +$as_echo "$lt_cv_deplibs_check_method" >&6; } +file_magic_cmd=$lt_cv_file_magic_cmd +deplibs_check_method=$lt_cv_deplibs_check_method +test -z "$deplibs_check_method" && deplibs_check_method=unknown + + + + + + + + + + + + +if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}ar", so it can be a program name with args. +set dummy ${ac_tool_prefix}ar; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_AR+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$AR"; then + ac_cv_prog_AR="$AR" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_AR="${ac_tool_prefix}ar" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +AR=$ac_cv_prog_AR +if test -n "$AR"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $AR" >&5 +$as_echo "$AR" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_AR"; then + ac_ct_AR=$AR + # Extract the first word of "ar", so it can be a program name with args. +set dummy ar; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_AR+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_AR"; then + ac_cv_prog_ac_ct_AR="$ac_ct_AR" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_AR="ar" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_AR=$ac_cv_prog_ac_ct_AR +if test -n "$ac_ct_AR"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_AR" >&5 +$as_echo "$ac_ct_AR" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_AR" = x; then + AR="false" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + AR=$ac_ct_AR + fi +else + AR="$ac_cv_prog_AR" +fi + +test -z "$AR" && AR=ar +test -z "$AR_FLAGS" && AR_FLAGS=cru + + + + + + + + + + + +if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}strip", so it can be a program name with args. +set dummy ${ac_tool_prefix}strip; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_STRIP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$STRIP"; then + ac_cv_prog_STRIP="$STRIP" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_STRIP="${ac_tool_prefix}strip" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +STRIP=$ac_cv_prog_STRIP +if test -n "$STRIP"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $STRIP" >&5 +$as_echo "$STRIP" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_STRIP"; then + ac_ct_STRIP=$STRIP + # Extract the first word of "strip", so it can be a program name with args. +set dummy strip; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_STRIP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_STRIP"; then + ac_cv_prog_ac_ct_STRIP="$ac_ct_STRIP" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_STRIP="strip" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_STRIP=$ac_cv_prog_ac_ct_STRIP +if test -n "$ac_ct_STRIP"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_STRIP" >&5 +$as_echo "$ac_ct_STRIP" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_STRIP" = x; then + STRIP=":" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + STRIP=$ac_ct_STRIP + fi +else + STRIP="$ac_cv_prog_STRIP" +fi + +test -z "$STRIP" && STRIP=: + + + + + + +if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}ranlib", so it can be a program name with args. +set dummy ${ac_tool_prefix}ranlib; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_RANLIB+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$RANLIB"; then + ac_cv_prog_RANLIB="$RANLIB" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_RANLIB="${ac_tool_prefix}ranlib" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +RANLIB=$ac_cv_prog_RANLIB +if test -n "$RANLIB"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $RANLIB" >&5 +$as_echo "$RANLIB" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_RANLIB"; then + ac_ct_RANLIB=$RANLIB + # Extract the first word of "ranlib", so it can be a program name with args. +set dummy ranlib; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_RANLIB+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_RANLIB"; then + ac_cv_prog_ac_ct_RANLIB="$ac_ct_RANLIB" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_RANLIB="ranlib" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_RANLIB=$ac_cv_prog_ac_ct_RANLIB +if test -n "$ac_ct_RANLIB"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_RANLIB" >&5 +$as_echo "$ac_ct_RANLIB" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_RANLIB" = x; then + RANLIB=":" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + RANLIB=$ac_ct_RANLIB + fi +else + RANLIB="$ac_cv_prog_RANLIB" +fi + +test -z "$RANLIB" && RANLIB=: + + + + + + +# Determine commands to create old-style static archives. +old_archive_cmds='$AR $AR_FLAGS $oldlib$oldobjs' +old_postinstall_cmds='chmod 644 $oldlib' +old_postuninstall_cmds= + +if test -n "$RANLIB"; then + case $host_os in + openbsd*) + old_postinstall_cmds="$old_postinstall_cmds~\$RANLIB -t \$oldlib" + ;; + *) + old_postinstall_cmds="$old_postinstall_cmds~\$RANLIB \$oldlib" + ;; + esac + old_archive_cmds="$old_archive_cmds~\$RANLIB \$oldlib" +fi + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +# If no C compiler was specified, use CC. +LTCC=${LTCC-"$CC"} + +# If no C compiler flags were specified, use CFLAGS. +LTCFLAGS=${LTCFLAGS-"$CFLAGS"} + +# Allow CC to be a program name with arguments. +compiler=$CC + + +# Check for command to grab the raw symbol name followed by C symbol from nm. +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking command to parse $NM output from $compiler object" >&5 +$as_echo_n "checking command to parse $NM output from $compiler object... " >&6; } +if test "${lt_cv_sys_global_symbol_pipe+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + +# These are sane defaults that work on at least a few old systems. +# [They come from Ultrix. What could be older than Ultrix?!! ;)] + +# Character class describing NM global symbol codes. +symcode='[BCDEGRST]' + +# Regexp to match symbols that can be accessed directly from C. +sympat='\([_A-Za-z][_A-Za-z0-9]*\)' + +# Define system-specific variables. +case $host_os in +aix*) + symcode='[BCDT]' + ;; +cygwin* | mingw* | pw32* | cegcc*) + symcode='[ABCDGISTW]' + ;; +hpux*) + if test "$host_cpu" = ia64; then + symcode='[ABCDEGRST]' + fi + ;; +irix* | nonstopux*) + symcode='[BCDEGRST]' + ;; +osf*) + symcode='[BCDEGQRST]' + ;; +solaris*) + symcode='[BDRT]' + ;; +sco3.2v5*) + symcode='[DT]' + ;; +sysv4.2uw2*) + symcode='[DT]' + ;; +sysv5* | sco5v6* | unixware* | OpenUNIX*) + symcode='[ABDT]' + ;; +sysv4) + symcode='[DFNSTU]' + ;; +esac + +# If we're using GNU nm, then use its standard symbol codes. +case `$NM -V 2>&1` in +*GNU* | *'with BFD'*) + symcode='[ABCDGIRSTW]' ;; +esac + +# Transform an extracted symbol line into a proper C declaration. +# Some systems (esp. on ia64) link data and code symbols differently, +# so use this general approach. +lt_cv_sys_global_symbol_to_cdecl="sed -n -e 's/^T .* \(.*\)$/extern int \1();/p' -e 's/^$symcode* .* \(.*\)$/extern char \1;/p'" + +# Transform an extracted symbol line into symbol name and symbol address +lt_cv_sys_global_symbol_to_c_name_address="sed -n -e 's/^: \([^ ]*\) $/ {\\\"\1\\\", (void *) 0},/p' -e 's/^$symcode* \([^ ]*\) \([^ ]*\)$/ {\"\2\", (void *) \&\2},/p'" +lt_cv_sys_global_symbol_to_c_name_address_lib_prefix="sed -n -e 's/^: \([^ ]*\) $/ {\\\"\1\\\", (void *) 0},/p' -e 's/^$symcode* \([^ ]*\) \(lib[^ ]*\)$/ {\"\2\", (void *) \&\2},/p' -e 's/^$symcode* \([^ ]*\) \([^ ]*\)$/ {\"lib\2\", (void *) \&\2},/p'" + +# Handle CRLF in mingw tool chain +opt_cr= +case $build_os in +mingw*) + opt_cr=`$ECHO 'x\{0,1\}' | tr x '\015'` # option cr in regexp + ;; +esac + +# Try without a prefix underscore, then with it. +for ac_symprfx in "" "_"; do + + # Transform symcode, sympat, and symprfx into a raw symbol and a C symbol. + symxfrm="\\1 $ac_symprfx\\2 \\2" + + # Write the raw and C identifiers. + if test "$lt_cv_nm_interface" = "MS dumpbin"; then + # Fake it for dumpbin and say T for any non-static function + # and D for any global variable. + # Also find C++ and __fastcall symbols from MSVC++, + # which start with @ or ?. + lt_cv_sys_global_symbol_pipe="$AWK '"\ +" {last_section=section; section=\$ 3};"\ +" /Section length .*#relocs.*(pick any)/{hide[last_section]=1};"\ +" \$ 0!~/External *\|/{next};"\ +" / 0+ UNDEF /{next}; / UNDEF \([^|]\)*()/{next};"\ +" {if(hide[section]) next};"\ +" {f=0}; \$ 0~/\(\).*\|/{f=1}; {printf f ? \"T \" : \"D \"};"\ +" {split(\$ 0, a, /\||\r/); split(a[2], s)};"\ +" s[1]~/^[@?]/{print s[1], s[1]; next};"\ +" s[1]~prfx {split(s[1],t,\"@\"); print t[1], substr(t[1],length(prfx))}"\ +" ' prfx=^$ac_symprfx" + else + lt_cv_sys_global_symbol_pipe="sed -n -e 's/^.*[ ]\($symcode$symcode*\)[ ][ ]*$ac_symprfx$sympat$opt_cr$/$symxfrm/p'" + fi + + # Check to see that the pipe works correctly. + pipe_works=no + + rm -f conftest* + cat > conftest.$ac_ext <<_LT_EOF +#ifdef __cplusplus +extern "C" { +#endif +char nm_test_var; +void nm_test_func(void); +void nm_test_func(void){} +#ifdef __cplusplus +} +#endif +int main(){nm_test_var='a';nm_test_func();return(0);} +_LT_EOF + + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 + (eval $ac_compile) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + # Now try to grab the symbols. + nlist=conftest.nm + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$NM conftest.$ac_objext \| $lt_cv_sys_global_symbol_pipe \> $nlist\""; } >&5 + (eval $NM conftest.$ac_objext \| $lt_cv_sys_global_symbol_pipe \> $nlist) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && test -s "$nlist"; then + # Try sorting and uniquifying the output. + if sort "$nlist" | uniq > "$nlist"T; then + mv -f "$nlist"T "$nlist" + else + rm -f "$nlist"T + fi + + # Make sure that we snagged all the symbols we need. + if $GREP ' nm_test_var$' "$nlist" >/dev/null; then + if $GREP ' nm_test_func$' "$nlist" >/dev/null; then + cat <<_LT_EOF > conftest.$ac_ext +#ifdef __cplusplus +extern "C" { +#endif + +_LT_EOF + # Now generate the symbol file. + eval "$lt_cv_sys_global_symbol_to_cdecl"' < "$nlist" | $GREP -v main >> conftest.$ac_ext' + + cat <<_LT_EOF >> conftest.$ac_ext + +/* The mapping between symbol names and symbols. */ +const struct { + const char *name; + void *address; +} +lt__PROGRAM__LTX_preloaded_symbols[] = +{ + { "@PROGRAM@", (void *) 0 }, +_LT_EOF + $SED "s/^$symcode$symcode* \(.*\) \(.*\)$/ {\"\2\", (void *) \&\2},/" < "$nlist" | $GREP -v main >> conftest.$ac_ext + cat <<\_LT_EOF >> conftest.$ac_ext + {0, (void *) 0} +}; + +/* This works around a problem in FreeBSD linker */ +#ifdef FREEBSD_WORKAROUND +static const void *lt_preloaded_setup() { + return lt__PROGRAM__LTX_preloaded_symbols; +} +#endif + +#ifdef __cplusplus +} +#endif +_LT_EOF + # Now try linking the two files. + mv conftest.$ac_objext conftstm.$ac_objext + lt_save_LIBS="$LIBS" + lt_save_CFLAGS="$CFLAGS" + LIBS="conftstm.$ac_objext" + CFLAGS="$CFLAGS$lt_prog_compiler_no_builtin_flag" + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_link\""; } >&5 + (eval $ac_link) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && test -s conftest${ac_exeext}; then + pipe_works=yes + fi + LIBS="$lt_save_LIBS" + CFLAGS="$lt_save_CFLAGS" + else + echo "cannot find nm_test_func in $nlist" >&5 + fi + else + echo "cannot find nm_test_var in $nlist" >&5 + fi + else + echo "cannot run $lt_cv_sys_global_symbol_pipe" >&5 + fi + else + echo "$progname: failed program was:" >&5 + cat conftest.$ac_ext >&5 + fi + rm -rf conftest* conftst* + + # Do not use the global_symbol_pipe unless it works. + if test "$pipe_works" = yes; then + break + else + lt_cv_sys_global_symbol_pipe= + fi +done + +fi + +if test -z "$lt_cv_sys_global_symbol_pipe"; then + lt_cv_sys_global_symbol_to_cdecl= +fi +if test -z "$lt_cv_sys_global_symbol_pipe$lt_cv_sys_global_symbol_to_cdecl"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: failed" >&5 +$as_echo "failed" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: ok" >&5 +$as_echo "ok" >&6; } +fi + + + + + + + + + + + + + + + + + + + + + + + +# Check whether --enable-libtool-lock was given. +if test "${enable_libtool_lock+set}" = set; then : + enableval=$enable_libtool_lock; +fi + +test "x$enable_libtool_lock" != xno && enable_libtool_lock=yes + +# Some flags need to be propagated to the compiler or linker for good +# libtool support. +case $host in +ia64-*-hpux*) + # Find out which ABI we are using. + echo 'int i;' > conftest.$ac_ext + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 + (eval $ac_compile) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + case `/usr/bin/file conftest.$ac_objext` in + *ELF-32*) + HPUX_IA64_MODE="32" + ;; + *ELF-64*) + HPUX_IA64_MODE="64" + ;; + esac + fi + rm -rf conftest* + ;; +*-*-irix6*) + # Find out which ABI we are using. + echo '#line 6110 "configure"' > conftest.$ac_ext + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 + (eval $ac_compile) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + if test "$lt_cv_prog_gnu_ld" = yes; then + case `/usr/bin/file conftest.$ac_objext` in + *32-bit*) + LD="${LD-ld} -melf32bsmip" + ;; + *N32*) + LD="${LD-ld} -melf32bmipn32" + ;; + *64-bit*) + LD="${LD-ld} -melf64bmip" + ;; + esac + else + case `/usr/bin/file conftest.$ac_objext` in + *32-bit*) + LD="${LD-ld} -32" + ;; + *N32*) + LD="${LD-ld} -n32" + ;; + *64-bit*) + LD="${LD-ld} -64" + ;; + esac + fi + fi + rm -rf conftest* + ;; + +x86_64-*kfreebsd*-gnu|x86_64-*linux*|ppc*-*linux*|powerpc*-*linux*| \ +s390*-*linux*|s390*-*tpf*|sparc*-*linux*) + # Find out which ABI we are using. + echo 'int i;' > conftest.$ac_ext + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 + (eval $ac_compile) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + case `/usr/bin/file conftest.o` in + *32-bit*) + case $host in + x86_64-*kfreebsd*-gnu) + LD="${LD-ld} -m elf_i386_fbsd" + ;; + x86_64-*linux*) + LD="${LD-ld} -m elf_i386" + ;; + ppc64-*linux*|powerpc64-*linux*) + LD="${LD-ld} -m elf32ppclinux" + ;; + s390x-*linux*) + LD="${LD-ld} -m elf_s390" + ;; + sparc64-*linux*) + LD="${LD-ld} -m elf32_sparc" + ;; + esac + ;; + *64-bit*) + case $host in + x86_64-*kfreebsd*-gnu) + LD="${LD-ld} -m elf_x86_64_fbsd" + ;; + x86_64-*linux*) + LD="${LD-ld} -m elf_x86_64" + ;; + ppc*-*linux*|powerpc*-*linux*) + LD="${LD-ld} -m elf64ppc" + ;; + s390*-*linux*|s390*-*tpf*) + LD="${LD-ld} -m elf64_s390" + ;; + sparc*-*linux*) + LD="${LD-ld} -m elf64_sparc" + ;; + esac + ;; + esac + fi + rm -rf conftest* + ;; + +*-*-sco3.2v5*) + # On SCO OpenServer 5, we need -belf to get full-featured binaries. + SAVE_CFLAGS="$CFLAGS" + CFLAGS="$CFLAGS -belf" + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether the C compiler needs -belf" >&5 +$as_echo_n "checking whether the C compiler needs -belf... " >&6; } +if test "${lt_cv_cc_needs_belf+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + lt_cv_cc_needs_belf=yes +else + lt_cv_cc_needs_belf=no +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext + ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_cc_needs_belf" >&5 +$as_echo "$lt_cv_cc_needs_belf" >&6; } + if test x"$lt_cv_cc_needs_belf" != x"yes"; then + # this is probably gcc 2.8.0, egcs 1.0 or newer; no need for -belf + CFLAGS="$SAVE_CFLAGS" + fi + ;; +sparc*-*solaris*) + # Find out which ABI we are using. + echo 'int i;' > conftest.$ac_ext + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 + (eval $ac_compile) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + case `/usr/bin/file conftest.o` in + *64-bit*) + case $lt_cv_prog_gnu_ld in + yes*) LD="${LD-ld} -m elf64_sparc" ;; + *) + if ${LD-ld} -64 -r -o conftest2.o conftest.o >/dev/null 2>&1; then + LD="${LD-ld} -64" + fi + ;; + esac + ;; + esac + fi + rm -rf conftest* + ;; +esac + +need_locks="$enable_libtool_lock" + + + case $host_os in + rhapsody* | darwin*) + if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}dsymutil", so it can be a program name with args. +set dummy ${ac_tool_prefix}dsymutil; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_DSYMUTIL+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$DSYMUTIL"; then + ac_cv_prog_DSYMUTIL="$DSYMUTIL" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_DSYMUTIL="${ac_tool_prefix}dsymutil" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +DSYMUTIL=$ac_cv_prog_DSYMUTIL +if test -n "$DSYMUTIL"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $DSYMUTIL" >&5 +$as_echo "$DSYMUTIL" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_DSYMUTIL"; then + ac_ct_DSYMUTIL=$DSYMUTIL + # Extract the first word of "dsymutil", so it can be a program name with args. +set dummy dsymutil; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_DSYMUTIL+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_DSYMUTIL"; then + ac_cv_prog_ac_ct_DSYMUTIL="$ac_ct_DSYMUTIL" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_DSYMUTIL="dsymutil" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_DSYMUTIL=$ac_cv_prog_ac_ct_DSYMUTIL +if test -n "$ac_ct_DSYMUTIL"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_DSYMUTIL" >&5 +$as_echo "$ac_ct_DSYMUTIL" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_DSYMUTIL" = x; then + DSYMUTIL=":" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + DSYMUTIL=$ac_ct_DSYMUTIL + fi +else + DSYMUTIL="$ac_cv_prog_DSYMUTIL" +fi + + if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}nmedit", so it can be a program name with args. +set dummy ${ac_tool_prefix}nmedit; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_NMEDIT+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$NMEDIT"; then + ac_cv_prog_NMEDIT="$NMEDIT" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_NMEDIT="${ac_tool_prefix}nmedit" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +NMEDIT=$ac_cv_prog_NMEDIT +if test -n "$NMEDIT"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $NMEDIT" >&5 +$as_echo "$NMEDIT" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_NMEDIT"; then + ac_ct_NMEDIT=$NMEDIT + # Extract the first word of "nmedit", so it can be a program name with args. +set dummy nmedit; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_NMEDIT+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_NMEDIT"; then + ac_cv_prog_ac_ct_NMEDIT="$ac_ct_NMEDIT" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_NMEDIT="nmedit" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_NMEDIT=$ac_cv_prog_ac_ct_NMEDIT +if test -n "$ac_ct_NMEDIT"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_NMEDIT" >&5 +$as_echo "$ac_ct_NMEDIT" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_NMEDIT" = x; then + NMEDIT=":" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + NMEDIT=$ac_ct_NMEDIT + fi +else + NMEDIT="$ac_cv_prog_NMEDIT" +fi + + if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}lipo", so it can be a program name with args. +set dummy ${ac_tool_prefix}lipo; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_LIPO+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$LIPO"; then + ac_cv_prog_LIPO="$LIPO" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_LIPO="${ac_tool_prefix}lipo" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +LIPO=$ac_cv_prog_LIPO +if test -n "$LIPO"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $LIPO" >&5 +$as_echo "$LIPO" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_LIPO"; then + ac_ct_LIPO=$LIPO + # Extract the first word of "lipo", so it can be a program name with args. +set dummy lipo; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_LIPO+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_LIPO"; then + ac_cv_prog_ac_ct_LIPO="$ac_ct_LIPO" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_LIPO="lipo" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_LIPO=$ac_cv_prog_ac_ct_LIPO +if test -n "$ac_ct_LIPO"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_LIPO" >&5 +$as_echo "$ac_ct_LIPO" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_LIPO" = x; then + LIPO=":" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + LIPO=$ac_ct_LIPO + fi +else + LIPO="$ac_cv_prog_LIPO" +fi + + if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}otool", so it can be a program name with args. +set dummy ${ac_tool_prefix}otool; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_OTOOL+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$OTOOL"; then + ac_cv_prog_OTOOL="$OTOOL" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_OTOOL="${ac_tool_prefix}otool" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +OTOOL=$ac_cv_prog_OTOOL +if test -n "$OTOOL"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $OTOOL" >&5 +$as_echo "$OTOOL" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_OTOOL"; then + ac_ct_OTOOL=$OTOOL + # Extract the first word of "otool", so it can be a program name with args. +set dummy otool; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_OTOOL+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_OTOOL"; then + ac_cv_prog_ac_ct_OTOOL="$ac_ct_OTOOL" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_OTOOL="otool" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_OTOOL=$ac_cv_prog_ac_ct_OTOOL +if test -n "$ac_ct_OTOOL"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_OTOOL" >&5 +$as_echo "$ac_ct_OTOOL" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_OTOOL" = x; then + OTOOL=":" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + OTOOL=$ac_ct_OTOOL + fi +else + OTOOL="$ac_cv_prog_OTOOL" +fi + + if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}otool64", so it can be a program name with args. +set dummy ${ac_tool_prefix}otool64; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_OTOOL64+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$OTOOL64"; then + ac_cv_prog_OTOOL64="$OTOOL64" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_OTOOL64="${ac_tool_prefix}otool64" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +OTOOL64=$ac_cv_prog_OTOOL64 +if test -n "$OTOOL64"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $OTOOL64" >&5 +$as_echo "$OTOOL64" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_OTOOL64"; then + ac_ct_OTOOL64=$OTOOL64 + # Extract the first word of "otool64", so it can be a program name with args. +set dummy otool64; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_OTOOL64+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_OTOOL64"; then + ac_cv_prog_ac_ct_OTOOL64="$ac_ct_OTOOL64" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_OTOOL64="otool64" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_OTOOL64=$ac_cv_prog_ac_ct_OTOOL64 +if test -n "$ac_ct_OTOOL64"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_OTOOL64" >&5 +$as_echo "$ac_ct_OTOOL64" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_OTOOL64" = x; then + OTOOL64=":" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + OTOOL64=$ac_ct_OTOOL64 + fi +else + OTOOL64="$ac_cv_prog_OTOOL64" +fi + + + + + + + + + + + + + + + + + + + + + + + + + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for -single_module linker flag" >&5 +$as_echo_n "checking for -single_module linker flag... " >&6; } +if test "${lt_cv_apple_cc_single_mod+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_apple_cc_single_mod=no + if test -z "${LT_MULTI_MODULE}"; then + # By default we will add the -single_module flag. You can override + # by either setting the environment variable LT_MULTI_MODULE + # non-empty at configure time, or by adding -multi_module to the + # link flags. + rm -rf libconftest.dylib* + echo "int foo(void){return 1;}" > conftest.c + echo "$LTCC $LTCFLAGS $LDFLAGS -o libconftest.dylib \ +-dynamiclib -Wl,-single_module conftest.c" >&5 + $LTCC $LTCFLAGS $LDFLAGS -o libconftest.dylib \ + -dynamiclib -Wl,-single_module conftest.c 2>conftest.err + _lt_result=$? + if test -f libconftest.dylib && test ! -s conftest.err && test $_lt_result = 0; then + lt_cv_apple_cc_single_mod=yes + else + cat conftest.err >&5 + fi + rm -rf libconftest.dylib* + rm -f conftest.* + fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_apple_cc_single_mod" >&5 +$as_echo "$lt_cv_apple_cc_single_mod" >&6; } + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for -exported_symbols_list linker flag" >&5 +$as_echo_n "checking for -exported_symbols_list linker flag... " >&6; } +if test "${lt_cv_ld_exported_symbols_list+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_ld_exported_symbols_list=no + save_LDFLAGS=$LDFLAGS + echo "_main" > conftest.sym + LDFLAGS="$LDFLAGS -Wl,-exported_symbols_list,conftest.sym" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + lt_cv_ld_exported_symbols_list=yes +else + lt_cv_ld_exported_symbols_list=no +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext + LDFLAGS="$save_LDFLAGS" + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_ld_exported_symbols_list" >&5 +$as_echo "$lt_cv_ld_exported_symbols_list" >&6; } + case $host_os in + rhapsody* | darwin1.[012]) + _lt_dar_allow_undefined='${wl}-undefined ${wl}suppress' ;; + darwin1.*) + _lt_dar_allow_undefined='${wl}-flat_namespace ${wl}-undefined ${wl}suppress' ;; + darwin*) # darwin 5.x on + # if running on 10.5 or later, the deployment target defaults + # to the OS version, if on x86, and 10.4, the deployment + # target defaults to 10.4. Don't you love it? + case ${MACOSX_DEPLOYMENT_TARGET-10.0},$host in + 10.0,*86*-darwin8*|10.0,*-darwin[91]*) + _lt_dar_allow_undefined='${wl}-undefined ${wl}dynamic_lookup' ;; + 10.[012]*) + _lt_dar_allow_undefined='${wl}-flat_namespace ${wl}-undefined ${wl}suppress' ;; + 10.*) + _lt_dar_allow_undefined='${wl}-undefined ${wl}dynamic_lookup' ;; + esac + ;; + esac + if test "$lt_cv_apple_cc_single_mod" = "yes"; then + _lt_dar_single_mod='$single_module' + fi + if test "$lt_cv_ld_exported_symbols_list" = "yes"; then + _lt_dar_export_syms=' ${wl}-exported_symbols_list,$output_objdir/${libname}-symbols.expsym' + else + _lt_dar_export_syms='~$NMEDIT -s $output_objdir/${libname}-symbols.expsym ${lib}' + fi + if test "$DSYMUTIL" != ":"; then + _lt_dsymutil='~$DSYMUTIL $lib || :' + else + _lt_dsymutil= + fi + ;; + esac + +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking how to run the C preprocessor" >&5 +$as_echo_n "checking how to run the C preprocessor... " >&6; } +# On Suns, sometimes $CPP names a directory. +if test -n "$CPP" && test -d "$CPP"; then + CPP= +fi +if test -z "$CPP"; then + if test "${ac_cv_prog_CPP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + # Double quotes because CPP needs to be expanded + for CPP in "$CC -E" "$CC -E -traditional-cpp" "/lib/cpp" + do + ac_preproc_ok=false +for ac_c_preproc_warn_flag in '' yes +do + # Use a header file that comes with gcc, so configuring glibc + # with a fresh cross-compiler works. + # Prefer to if __STDC__ is defined, since + # exists even on freestanding compilers. + # On the NeXT, cc -E runs the code through the compiler's parser, + # not just through cpp. "Syntax error" is here to catch this case. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#ifdef __STDC__ +# include +#else +# include +#endif + Syntax error +_ACEOF +if ac_fn_c_try_cpp "$LINENO"; then : + +else + # Broken: fails on valid input. +continue +fi +rm -f conftest.err conftest.i conftest.$ac_ext + + # OK, works on sane cases. Now check whether nonexistent headers + # can be detected and how. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +_ACEOF +if ac_fn_c_try_cpp "$LINENO"; then : + # Broken: success on invalid input. +continue +else + # Passes both tests. +ac_preproc_ok=: +break +fi +rm -f conftest.err conftest.i conftest.$ac_ext + +done +# Because of `break', _AC_PREPROC_IFELSE's cleaning code was skipped. +rm -f conftest.i conftest.err conftest.$ac_ext +if $ac_preproc_ok; then : + break +fi + + done + ac_cv_prog_CPP=$CPP + +fi + CPP=$ac_cv_prog_CPP +else + ac_cv_prog_CPP=$CPP +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $CPP" >&5 +$as_echo "$CPP" >&6; } +ac_preproc_ok=false +for ac_c_preproc_warn_flag in '' yes +do + # Use a header file that comes with gcc, so configuring glibc + # with a fresh cross-compiler works. + # Prefer to if __STDC__ is defined, since + # exists even on freestanding compilers. + # On the NeXT, cc -E runs the code through the compiler's parser, + # not just through cpp. "Syntax error" is here to catch this case. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#ifdef __STDC__ +# include +#else +# include +#endif + Syntax error +_ACEOF +if ac_fn_c_try_cpp "$LINENO"; then : + +else + # Broken: fails on valid input. +continue +fi +rm -f conftest.err conftest.i conftest.$ac_ext + + # OK, works on sane cases. Now check whether nonexistent headers + # can be detected and how. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +_ACEOF +if ac_fn_c_try_cpp "$LINENO"; then : + # Broken: success on invalid input. +continue +else + # Passes both tests. +ac_preproc_ok=: +break +fi +rm -f conftest.err conftest.i conftest.$ac_ext + +done +# Because of `break', _AC_PREPROC_IFELSE's cleaning code was skipped. +rm -f conftest.i conftest.err conftest.$ac_ext +if $ac_preproc_ok; then : + +else + { { $as_echo "$as_me:${as_lineno-$LINENO}: error: in \`$ac_pwd':" >&5 +$as_echo "$as_me: error: in \`$ac_pwd':" >&2;} +as_fn_error $? "C preprocessor \"$CPP\" fails sanity check +See \`config.log' for more details" "$LINENO" 5 ; } +fi + +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for ANSI C header files" >&5 +$as_echo_n "checking for ANSI C header files... " >&6; } +if test "${ac_cv_header_stdc+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +#include +#include +#include + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_cv_header_stdc=yes +else + ac_cv_header_stdc=no +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext + +if test $ac_cv_header_stdc = yes; then + # SunOS 4.x string.h does not declare mem*, contrary to ANSI. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include + +_ACEOF +if (eval "$ac_cpp conftest.$ac_ext") 2>&5 | + $EGREP "memchr" >/dev/null 2>&1; then : + +else + ac_cv_header_stdc=no +fi +rm -f conftest* + +fi + +if test $ac_cv_header_stdc = yes; then + # ISC 2.0.2 stdlib.h does not declare free, contrary to ANSI. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include + +_ACEOF +if (eval "$ac_cpp conftest.$ac_ext") 2>&5 | + $EGREP "free" >/dev/null 2>&1; then : + +else + ac_cv_header_stdc=no +fi +rm -f conftest* + +fi + +if test $ac_cv_header_stdc = yes; then + # /bin/cc in Irix-4.0.5 gets non-ANSI ctype macros unless using -ansi. + if test "$cross_compiling" = yes; then : + : +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +#include +#if ((' ' & 0x0FF) == 0x020) +# define ISLOWER(c) ('a' <= (c) && (c) <= 'z') +# define TOUPPER(c) (ISLOWER(c) ? 'A' + ((c) - 'a') : (c)) +#else +# define ISLOWER(c) \ + (('a' <= (c) && (c) <= 'i') \ + || ('j' <= (c) && (c) <= 'r') \ + || ('s' <= (c) && (c) <= 'z')) +# define TOUPPER(c) (ISLOWER(c) ? ((c) | 0x40) : (c)) +#endif + +#define XOR(e, f) (((e) && !(f)) || (!(e) && (f))) +int +main () +{ + int i; + for (i = 0; i < 256; i++) + if (XOR (islower (i), ISLOWER (i)) + || toupper (i) != TOUPPER (i)) + return 2; + return 0; +} +_ACEOF +if ac_fn_c_try_run "$LINENO"; then : + +else + ac_cv_header_stdc=no +fi +rm -f core *.core core.conftest.* gmon.out bb.out conftest$ac_exeext \ + conftest.$ac_objext conftest.beam conftest.$ac_ext +fi + +fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_header_stdc" >&5 +$as_echo "$ac_cv_header_stdc" >&6; } +if test $ac_cv_header_stdc = yes; then + +$as_echo "#define STDC_HEADERS 1" >>confdefs.h + +fi + +# On IRIX 5.3, sys/types and inttypes.h are conflicting. +for ac_header in sys/types.h sys/stat.h stdlib.h string.h memory.h strings.h \ + inttypes.h stdint.h unistd.h +do : + as_ac_Header=`$as_echo "ac_cv_header_$ac_header" | $as_tr_sh` +ac_fn_c_check_header_compile "$LINENO" "$ac_header" "$as_ac_Header" "$ac_includes_default +" +if eval test \"x\$"$as_ac_Header"\" = x"yes"; then : + cat >>confdefs.h <<_ACEOF +#define `$as_echo "HAVE_$ac_header" | $as_tr_cpp` 1 +_ACEOF + +fi + +done + + +for ac_header in dlfcn.h +do : + ac_fn_c_check_header_compile "$LINENO" "dlfcn.h" "ac_cv_header_dlfcn_h" "$ac_includes_default +" +if test "x$ac_cv_header_dlfcn_h" = x""yes; then : + cat >>confdefs.h <<_ACEOF +#define HAVE_DLFCN_H 1 +_ACEOF + +fi + +done + + + +# Set options +# Check whether --enable-static was given. +if test "${enable_static+set}" = set; then : + enableval=$enable_static; p=${PACKAGE-default} + case $enableval in + yes) enable_static=yes ;; + no) enable_static=no ;; + *) + enable_static=no + # Look at the argument we got. We use all the common list separators. + lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + for pkg in $enableval; do + IFS="$lt_save_ifs" + if test "X$pkg" = "X$p"; then + enable_static=yes + fi + done + IFS="$lt_save_ifs" + ;; + esac +else + enable_static=no +fi + + + + + + + + + + + enable_dlopen=no + + + enable_win32_dll=no + + + # Check whether --enable-shared was given. +if test "${enable_shared+set}" = set; then : + enableval=$enable_shared; p=${PACKAGE-default} + case $enableval in + yes) enable_shared=yes ;; + no) enable_shared=no ;; + *) + enable_shared=no + # Look at the argument we got. We use all the common list separators. + lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + for pkg in $enableval; do + IFS="$lt_save_ifs" + if test "X$pkg" = "X$p"; then + enable_shared=yes + fi + done + IFS="$lt_save_ifs" + ;; + esac +else + enable_shared=yes +fi + + + + + + + + + + + +# Check whether --with-pic was given. +if test "${with_pic+set}" = set; then : + withval=$with_pic; pic_mode="$withval" +else + pic_mode=default +fi + + +test -z "$pic_mode" && pic_mode=default + + + + + + + + # Check whether --enable-fast-install was given. +if test "${enable_fast_install+set}" = set; then : + enableval=$enable_fast_install; p=${PACKAGE-default} + case $enableval in + yes) enable_fast_install=yes ;; + no) enable_fast_install=no ;; + *) + enable_fast_install=no + # Look at the argument we got. We use all the common list separators. + lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + for pkg in $enableval; do + IFS="$lt_save_ifs" + if test "X$pkg" = "X$p"; then + enable_fast_install=yes + fi + done + IFS="$lt_save_ifs" + ;; + esac +else + enable_fast_install=yes +fi + + + + + + + + + + + +# This can be used to rebuild libtool when needed +LIBTOOL_DEPS="$ltmain" + +# Always use our own libtool. +LIBTOOL='$(SHELL) $(top_builddir)/libtool' + + + + + + + + + + + + + + + + + + + + + + + + + +test -z "$LN_S" && LN_S="ln -s" + + + + + + + + + + + + + + +if test -n "${ZSH_VERSION+set}" ; then + setopt NO_GLOB_SUBST +fi + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for objdir" >&5 +$as_echo_n "checking for objdir... " >&6; } +if test "${lt_cv_objdir+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + rm -f .libs 2>/dev/null +mkdir .libs 2>/dev/null +if test -d .libs; then + lt_cv_objdir=.libs +else + # MS-DOS does not allow filenames that begin with a dot. + lt_cv_objdir=_libs +fi +rmdir .libs 2>/dev/null +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_objdir" >&5 +$as_echo "$lt_cv_objdir" >&6; } +objdir=$lt_cv_objdir + + + + + +cat >>confdefs.h <<_ACEOF +#define LT_OBJDIR "$lt_cv_objdir/" +_ACEOF + + + + + + + + + + + + + + + + + +case $host_os in +aix3*) + # AIX sometimes has problems with the GCC collect2 program. For some + # reason, if we set the COLLECT_NAMES environment variable, the problems + # vanish in a puff of smoke. + if test "X${COLLECT_NAMES+set}" != Xset; then + COLLECT_NAMES= + export COLLECT_NAMES + fi + ;; +esac + +# Sed substitution that helps us do robust quoting. It backslashifies +# metacharacters that are still active within double-quoted strings. +sed_quote_subst='s/\(["`$\\]\)/\\\1/g' + +# Same as above, but do not quote variable references. +double_quote_subst='s/\(["`\\]\)/\\\1/g' + +# Sed substitution to delay expansion of an escaped shell variable in a +# double_quote_subst'ed string. +delay_variable_subst='s/\\\\\\\\\\\$/\\\\\\$/g' + +# Sed substitution to delay expansion of an escaped single quote. +delay_single_quote_subst='s/'\''/'\'\\\\\\\'\''/g' + +# Sed substitution to avoid accidental globbing in evaled expressions +no_glob_subst='s/\*/\\\*/g' + +# Global variables: +ofile=libtool +can_build_shared=yes + +# All known linkers require a `.a' archive for static linking (except MSVC, +# which needs '.lib'). +libext=a + +with_gnu_ld="$lt_cv_prog_gnu_ld" + +old_CC="$CC" +old_CFLAGS="$CFLAGS" + +# Set sane defaults for various variables +test -z "$CC" && CC=cc +test -z "$LTCC" && LTCC=$CC +test -z "$LTCFLAGS" && LTCFLAGS=$CFLAGS +test -z "$LD" && LD=ld +test -z "$ac_objext" && ac_objext=o + +for cc_temp in $compiler""; do + case $cc_temp in + compile | *[\\/]compile | ccache | *[\\/]ccache ) ;; + distcc | *[\\/]distcc | purify | *[\\/]purify ) ;; + \-*) ;; + *) break;; + esac +done +cc_basename=`$ECHO "X$cc_temp" | $Xsed -e 's%.*/%%' -e "s%^$host_alias-%%"` + + +# Only perform the check for file, if the check method requires it +test -z "$MAGIC_CMD" && MAGIC_CMD=file +case $deplibs_check_method in +file_magic*) + if test "$file_magic_cmd" = '$MAGIC_CMD'; then + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for ${ac_tool_prefix}file" >&5 +$as_echo_n "checking for ${ac_tool_prefix}file... " >&6; } +if test "${lt_cv_path_MAGIC_CMD+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + case $MAGIC_CMD in +[\\/*] | ?:[\\/]*) + lt_cv_path_MAGIC_CMD="$MAGIC_CMD" # Let the user override the test with a path. + ;; +*) + lt_save_MAGIC_CMD="$MAGIC_CMD" + lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + ac_dummy="/usr/bin$PATH_SEPARATOR$PATH" + for ac_dir in $ac_dummy; do + IFS="$lt_save_ifs" + test -z "$ac_dir" && ac_dir=. + if test -f $ac_dir/${ac_tool_prefix}file; then + lt_cv_path_MAGIC_CMD="$ac_dir/${ac_tool_prefix}file" + if test -n "$file_magic_test_file"; then + case $deplibs_check_method in + "file_magic "*) + file_magic_regex=`expr "$deplibs_check_method" : "file_magic \(.*\)"` + MAGIC_CMD="$lt_cv_path_MAGIC_CMD" + if eval $file_magic_cmd \$file_magic_test_file 2> /dev/null | + $EGREP "$file_magic_regex" > /dev/null; then + : + else + cat <<_LT_EOF 1>&2 + +*** Warning: the command libtool uses to detect shared libraries, +*** $file_magic_cmd, produces output that libtool cannot recognize. +*** The result is that libtool may fail to recognize shared libraries +*** as such. This will affect the creation of libtool libraries that +*** depend on shared libraries, but programs linked with such libtool +*** libraries will work regardless of this problem. Nevertheless, you +*** may want to report the problem to your system manager and/or to +*** bug-libtool@gnu.org + +_LT_EOF + fi ;; + esac + fi + break + fi + done + IFS="$lt_save_ifs" + MAGIC_CMD="$lt_save_MAGIC_CMD" + ;; +esac +fi + +MAGIC_CMD="$lt_cv_path_MAGIC_CMD" +if test -n "$MAGIC_CMD"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $MAGIC_CMD" >&5 +$as_echo "$MAGIC_CMD" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + + + +if test -z "$lt_cv_path_MAGIC_CMD"; then + if test -n "$ac_tool_prefix"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for file" >&5 +$as_echo_n "checking for file... " >&6; } +if test "${lt_cv_path_MAGIC_CMD+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + case $MAGIC_CMD in +[\\/*] | ?:[\\/]*) + lt_cv_path_MAGIC_CMD="$MAGIC_CMD" # Let the user override the test with a path. + ;; +*) + lt_save_MAGIC_CMD="$MAGIC_CMD" + lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + ac_dummy="/usr/bin$PATH_SEPARATOR$PATH" + for ac_dir in $ac_dummy; do + IFS="$lt_save_ifs" + test -z "$ac_dir" && ac_dir=. + if test -f $ac_dir/file; then + lt_cv_path_MAGIC_CMD="$ac_dir/file" + if test -n "$file_magic_test_file"; then + case $deplibs_check_method in + "file_magic "*) + file_magic_regex=`expr "$deplibs_check_method" : "file_magic \(.*\)"` + MAGIC_CMD="$lt_cv_path_MAGIC_CMD" + if eval $file_magic_cmd \$file_magic_test_file 2> /dev/null | + $EGREP "$file_magic_regex" > /dev/null; then + : + else + cat <<_LT_EOF 1>&2 + +*** Warning: the command libtool uses to detect shared libraries, +*** $file_magic_cmd, produces output that libtool cannot recognize. +*** The result is that libtool may fail to recognize shared libraries +*** as such. This will affect the creation of libtool libraries that +*** depend on shared libraries, but programs linked with such libtool +*** libraries will work regardless of this problem. Nevertheless, you +*** may want to report the problem to your system manager and/or to +*** bug-libtool@gnu.org + +_LT_EOF + fi ;; + esac + fi + break + fi + done + IFS="$lt_save_ifs" + MAGIC_CMD="$lt_save_MAGIC_CMD" + ;; +esac +fi + +MAGIC_CMD="$lt_cv_path_MAGIC_CMD" +if test -n "$MAGIC_CMD"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $MAGIC_CMD" >&5 +$as_echo "$MAGIC_CMD" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + else + MAGIC_CMD=: + fi +fi + + fi + ;; +esac + +# Use C for the default configuration in the libtool script + +lt_save_CC="$CC" +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + + +# Source file extension for C test sources. +ac_ext=c + +# Object file extension for compiled C test sources. +objext=o +objext=$objext + +# Code to be used in simple compile tests +lt_simple_compile_test_code="int some_variable = 0;" + +# Code to be used in simple link tests +lt_simple_link_test_code='int main(){return(0);}' + + + + + + + +# If no C compiler was specified, use CC. +LTCC=${LTCC-"$CC"} + +# If no C compiler flags were specified, use CFLAGS. +LTCFLAGS=${LTCFLAGS-"$CFLAGS"} + +# Allow CC to be a program name with arguments. +compiler=$CC + +# Save the default compiler, since it gets overwritten when the other +# tags are being tested, and _LT_TAGVAR(compiler, []) is a NOP. +compiler_DEFAULT=$CC + +# save warnings/boilerplate of simple test code +ac_outfile=conftest.$ac_objext +echo "$lt_simple_compile_test_code" >conftest.$ac_ext +eval "$ac_compile" 2>&1 >/dev/null | $SED '/^$/d; /^ *+/d' >conftest.err +_lt_compiler_boilerplate=`cat conftest.err` +$RM conftest* + +ac_outfile=conftest.$ac_objext +echo "$lt_simple_link_test_code" >conftest.$ac_ext +eval "$ac_link" 2>&1 >/dev/null | $SED '/^$/d; /^ *+/d' >conftest.err +_lt_linker_boilerplate=`cat conftest.err` +$RM -r conftest* + + +if test -n "$compiler"; then + +lt_prog_compiler_no_builtin_flag= + +if test "$GCC" = yes; then + lt_prog_compiler_no_builtin_flag=' -fno-builtin' + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking if $compiler supports -fno-rtti -fno-exceptions" >&5 +$as_echo_n "checking if $compiler supports -fno-rtti -fno-exceptions... " >&6; } +if test "${lt_cv_prog_compiler_rtti_exceptions+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_prog_compiler_rtti_exceptions=no + ac_outfile=conftest.$ac_objext + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + lt_compiler_flag="-fno-rtti -fno-exceptions" + # Insert the option either (1) after the last *FLAGS variable, or + # (2) before a word containing "conftest.", or (3) at the end. + # Note that $ac_compile itself does not contain backslashes and begins + # with a dollar sign (not a hyphen), so the echo should work correctly. + # The option is referenced via a variable to avoid confusing sed. + lt_compile=`echo "$ac_compile" | $SED \ + -e 's:.*FLAGS}\{0,1\} :&$lt_compiler_flag :; t' \ + -e 's: [^ ]*conftest\.: $lt_compiler_flag&:; t' \ + -e 's:$: $lt_compiler_flag:'` + (eval echo "\"\$as_me:7634: $lt_compile\"" >&5) + (eval "$lt_compile" 2>conftest.err) + ac_status=$? + cat conftest.err >&5 + echo "$as_me:7638: \$? = $ac_status" >&5 + if (exit $ac_status) && test -s "$ac_outfile"; then + # The compiler can only warn and ignore the option if not recognized + # So say no if there are warnings other than the usual output. + $ECHO "X$_lt_compiler_boilerplate" | $Xsed -e '/^$/d' >conftest.exp + $SED '/^$/d; /^ *+/d' conftest.err >conftest.er2 + if test ! -s conftest.er2 || diff conftest.exp conftest.er2 >/dev/null; then + lt_cv_prog_compiler_rtti_exceptions=yes + fi + fi + $RM conftest* + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_rtti_exceptions" >&5 +$as_echo "$lt_cv_prog_compiler_rtti_exceptions" >&6; } + +if test x"$lt_cv_prog_compiler_rtti_exceptions" = xyes; then + lt_prog_compiler_no_builtin_flag="$lt_prog_compiler_no_builtin_flag -fno-rtti -fno-exceptions" +else + : +fi + +fi + + + + + + + lt_prog_compiler_wl= +lt_prog_compiler_pic= +lt_prog_compiler_static= + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $compiler option to produce PIC" >&5 +$as_echo_n "checking for $compiler option to produce PIC... " >&6; } + + if test "$GCC" = yes; then + lt_prog_compiler_wl='-Wl,' + lt_prog_compiler_static='-static' + + case $host_os in + aix*) + # All AIX code is PIC. + if test "$host_cpu" = ia64; then + # AIX 5 now supports IA64 processor + lt_prog_compiler_static='-Bstatic' + fi + ;; + + amigaos*) + case $host_cpu in + powerpc) + # see comment about AmigaOS4 .so support + lt_prog_compiler_pic='-fPIC' + ;; + m68k) + # FIXME: we need at least 68020 code to build shared libraries, but + # adding the `-m68020' flag to GCC prevents building anything better, + # like `-m68040'. + lt_prog_compiler_pic='-m68020 -resident32 -malways-restore-a4' + ;; + esac + ;; + + beos* | irix5* | irix6* | nonstopux* | osf3* | osf4* | osf5*) + # PIC is the default for these OSes. + ;; + + mingw* | cygwin* | pw32* | os2* | cegcc*) + # This hack is so that the source file can tell whether it is being + # built for inclusion in a dll (and should export symbols for example). + # Although the cygwin gcc ignores -fPIC, still need this for old-style + # (--disable-auto-import) libraries + lt_prog_compiler_pic='-DDLL_EXPORT' + ;; + + darwin* | rhapsody*) + # PIC is the default on this platform + # Common symbols not allowed in MH_DYLIB files + lt_prog_compiler_pic='-fno-common' + ;; + + hpux*) + # PIC is the default for 64-bit PA HP-UX, but not for 32-bit + # PA HP-UX. On IA64 HP-UX, PIC is the default but the pic flag + # sets the default TLS model and affects inlining. + case $host_cpu in + hppa*64*) + # +Z the default + ;; + *) + lt_prog_compiler_pic='-fPIC' + ;; + esac + ;; + + interix[3-9]*) + # Interix 3.x gcc -fpic/-fPIC options generate broken code. + # Instead, we relocate shared libraries at runtime. + ;; + + msdosdjgpp*) + # Just because we use GCC doesn't mean we suddenly get shared libraries + # on systems that don't support them. + lt_prog_compiler_can_build_shared=no + enable_shared=no + ;; + + *nto* | *qnx*) + # QNX uses GNU C++, but need to define -shared option too, otherwise + # it will coredump. + lt_prog_compiler_pic='-fPIC -shared' + ;; + + sysv4*MP*) + if test -d /usr/nec; then + lt_prog_compiler_pic=-Kconform_pic + fi + ;; + + *) + lt_prog_compiler_pic='-fPIC' + ;; + esac + else + # PORTME Check for flag to pass linker flags through the system compiler. + case $host_os in + aix*) + lt_prog_compiler_wl='-Wl,' + if test "$host_cpu" = ia64; then + # AIX 5 now supports IA64 processor + lt_prog_compiler_static='-Bstatic' + else + lt_prog_compiler_static='-bnso -bI:/lib/syscalls.exp' + fi + ;; + + mingw* | cygwin* | pw32* | os2* | cegcc*) + # This hack is so that the source file can tell whether it is being + # built for inclusion in a dll (and should export symbols for example). + lt_prog_compiler_pic='-DDLL_EXPORT' + ;; + + hpux9* | hpux10* | hpux11*) + lt_prog_compiler_wl='-Wl,' + # PIC is the default for IA64 HP-UX and 64-bit HP-UX, but + # not for PA HP-UX. + case $host_cpu in + hppa*64*|ia64*) + # +Z the default + ;; + *) + lt_prog_compiler_pic='+Z' + ;; + esac + # Is there a better lt_prog_compiler_static that works with the bundled CC? + lt_prog_compiler_static='${wl}-a ${wl}archive' + ;; + + irix5* | irix6* | nonstopux*) + lt_prog_compiler_wl='-Wl,' + # PIC (with -KPIC) is the default. + lt_prog_compiler_static='-non_shared' + ;; + + linux* | k*bsd*-gnu | kopensolaris*-gnu) + case $cc_basename in + # old Intel for x86_64 which still supported -KPIC. + ecc*) + lt_prog_compiler_wl='-Wl,' + lt_prog_compiler_pic='-KPIC' + lt_prog_compiler_static='-static' + ;; + # icc used to be incompatible with GCC. + # ICC 10 doesn't accept -KPIC any more. + icc* | ifort*) + lt_prog_compiler_wl='-Wl,' + lt_prog_compiler_pic='-fPIC' + lt_prog_compiler_static='-static' + ;; + # Lahey Fortran 8.1. + lf95*) + lt_prog_compiler_wl='-Wl,' + lt_prog_compiler_pic='--shared' + lt_prog_compiler_static='--static' + ;; + pgcc* | pgf77* | pgf90* | pgf95*) + # Portland Group compilers (*not* the Pentium gcc compiler, + # which looks to be a dead project) + lt_prog_compiler_wl='-Wl,' + lt_prog_compiler_pic='-fpic' + lt_prog_compiler_static='-Bstatic' + ;; + ccc*) + lt_prog_compiler_wl='-Wl,' + # All Alpha code is PIC. + lt_prog_compiler_static='-non_shared' + ;; + xl*) + # IBM XL C 8.0/Fortran 10.1 on PPC + lt_prog_compiler_wl='-Wl,' + lt_prog_compiler_pic='-qpic' + lt_prog_compiler_static='-qstaticlink' + ;; + *) + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) + # Sun C 5.9 + lt_prog_compiler_pic='-KPIC' + lt_prog_compiler_static='-Bstatic' + lt_prog_compiler_wl='-Wl,' + ;; + *Sun\ F*) + # Sun Fortran 8.3 passes all unrecognized flags to the linker + lt_prog_compiler_pic='-KPIC' + lt_prog_compiler_static='-Bstatic' + lt_prog_compiler_wl='' + ;; + esac + ;; + esac + ;; + + newsos6) + lt_prog_compiler_pic='-KPIC' + lt_prog_compiler_static='-Bstatic' + ;; + + *nto* | *qnx*) + # QNX uses GNU C++, but need to define -shared option too, otherwise + # it will coredump. + lt_prog_compiler_pic='-fPIC -shared' + ;; + + osf3* | osf4* | osf5*) + lt_prog_compiler_wl='-Wl,' + # All OSF/1 code is PIC. + lt_prog_compiler_static='-non_shared' + ;; + + rdos*) + lt_prog_compiler_static='-non_shared' + ;; + + solaris*) + lt_prog_compiler_pic='-KPIC' + lt_prog_compiler_static='-Bstatic' + case $cc_basename in + f77* | f90* | f95*) + lt_prog_compiler_wl='-Qoption ld ';; + *) + lt_prog_compiler_wl='-Wl,';; + esac + ;; + + sunos4*) + lt_prog_compiler_wl='-Qoption ld ' + lt_prog_compiler_pic='-PIC' + lt_prog_compiler_static='-Bstatic' + ;; + + sysv4 | sysv4.2uw2* | sysv4.3*) + lt_prog_compiler_wl='-Wl,' + lt_prog_compiler_pic='-KPIC' + lt_prog_compiler_static='-Bstatic' + ;; + + sysv4*MP*) + if test -d /usr/nec ;then + lt_prog_compiler_pic='-Kconform_pic' + lt_prog_compiler_static='-Bstatic' + fi + ;; + + sysv5* | unixware* | sco3.2v5* | sco5v6* | OpenUNIX*) + lt_prog_compiler_wl='-Wl,' + lt_prog_compiler_pic='-KPIC' + lt_prog_compiler_static='-Bstatic' + ;; + + unicos*) + lt_prog_compiler_wl='-Wl,' + lt_prog_compiler_can_build_shared=no + ;; + + uts4*) + lt_prog_compiler_pic='-pic' + lt_prog_compiler_static='-Bstatic' + ;; + + *) + lt_prog_compiler_can_build_shared=no + ;; + esac + fi + +case $host_os in + # For platforms which do not support PIC, -DPIC is meaningless: + *djgpp*) + lt_prog_compiler_pic= + ;; + *) + lt_prog_compiler_pic="$lt_prog_compiler_pic -DPIC" + ;; +esac +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_prog_compiler_pic" >&5 +$as_echo "$lt_prog_compiler_pic" >&6; } + + + + + + +# +# Check to make sure the PIC flag actually works. +# +if test -n "$lt_prog_compiler_pic"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: checking if $compiler PIC flag $lt_prog_compiler_pic works" >&5 +$as_echo_n "checking if $compiler PIC flag $lt_prog_compiler_pic works... " >&6; } +if test "${lt_cv_prog_compiler_pic_works+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_prog_compiler_pic_works=no + ac_outfile=conftest.$ac_objext + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + lt_compiler_flag="$lt_prog_compiler_pic -DPIC" + # Insert the option either (1) after the last *FLAGS variable, or + # (2) before a word containing "conftest.", or (3) at the end. + # Note that $ac_compile itself does not contain backslashes and begins + # with a dollar sign (not a hyphen), so the echo should work correctly. + # The option is referenced via a variable to avoid confusing sed. + lt_compile=`echo "$ac_compile" | $SED \ + -e 's:.*FLAGS}\{0,1\} :&$lt_compiler_flag :; t' \ + -e 's: [^ ]*conftest\.: $lt_compiler_flag&:; t' \ + -e 's:$: $lt_compiler_flag:'` + (eval echo "\"\$as_me:7973: $lt_compile\"" >&5) + (eval "$lt_compile" 2>conftest.err) + ac_status=$? + cat conftest.err >&5 + echo "$as_me:7977: \$? = $ac_status" >&5 + if (exit $ac_status) && test -s "$ac_outfile"; then + # The compiler can only warn and ignore the option if not recognized + # So say no if there are warnings other than the usual output. + $ECHO "X$_lt_compiler_boilerplate" | $Xsed -e '/^$/d' >conftest.exp + $SED '/^$/d; /^ *+/d' conftest.err >conftest.er2 + if test ! -s conftest.er2 || diff conftest.exp conftest.er2 >/dev/null; then + lt_cv_prog_compiler_pic_works=yes + fi + fi + $RM conftest* + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_pic_works" >&5 +$as_echo "$lt_cv_prog_compiler_pic_works" >&6; } + +if test x"$lt_cv_prog_compiler_pic_works" = xyes; then + case $lt_prog_compiler_pic in + "" | " "*) ;; + *) lt_prog_compiler_pic=" $lt_prog_compiler_pic" ;; + esac +else + lt_prog_compiler_pic= + lt_prog_compiler_can_build_shared=no +fi + +fi + + + + + + +# +# Check to make sure the static flag actually works. +# +wl=$lt_prog_compiler_wl eval lt_tmp_static_flag=\"$lt_prog_compiler_static\" +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking if $compiler static flag $lt_tmp_static_flag works" >&5 +$as_echo_n "checking if $compiler static flag $lt_tmp_static_flag works... " >&6; } +if test "${lt_cv_prog_compiler_static_works+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_prog_compiler_static_works=no + save_LDFLAGS="$LDFLAGS" + LDFLAGS="$LDFLAGS $lt_tmp_static_flag" + echo "$lt_simple_link_test_code" > conftest.$ac_ext + if (eval $ac_link 2>conftest.err) && test -s conftest$ac_exeext; then + # The linker can only warn and ignore the option if not recognized + # So say no if there are warnings + if test -s conftest.err; then + # Append any errors to the config.log. + cat conftest.err 1>&5 + $ECHO "X$_lt_linker_boilerplate" | $Xsed -e '/^$/d' > conftest.exp + $SED '/^$/d; /^ *+/d' conftest.err >conftest.er2 + if diff conftest.exp conftest.er2 >/dev/null; then + lt_cv_prog_compiler_static_works=yes + fi + else + lt_cv_prog_compiler_static_works=yes + fi + fi + $RM -r conftest* + LDFLAGS="$save_LDFLAGS" + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_static_works" >&5 +$as_echo "$lt_cv_prog_compiler_static_works" >&6; } + +if test x"$lt_cv_prog_compiler_static_works" = xyes; then + : +else + lt_prog_compiler_static= +fi + + + + + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking if $compiler supports -c -o file.$ac_objext" >&5 +$as_echo_n "checking if $compiler supports -c -o file.$ac_objext... " >&6; } +if test "${lt_cv_prog_compiler_c_o+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_prog_compiler_c_o=no + $RM -r conftest 2>/dev/null + mkdir conftest + cd conftest + mkdir out + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + + lt_compiler_flag="-o out/conftest2.$ac_objext" + # Insert the option either (1) after the last *FLAGS variable, or + # (2) before a word containing "conftest.", or (3) at the end. + # Note that $ac_compile itself does not contain backslashes and begins + # with a dollar sign (not a hyphen), so the echo should work correctly. + lt_compile=`echo "$ac_compile" | $SED \ + -e 's:.*FLAGS}\{0,1\} :&$lt_compiler_flag :; t' \ + -e 's: [^ ]*conftest\.: $lt_compiler_flag&:; t' \ + -e 's:$: $lt_compiler_flag:'` + (eval echo "\"\$as_me:8078: $lt_compile\"" >&5) + (eval "$lt_compile" 2>out/conftest.err) + ac_status=$? + cat out/conftest.err >&5 + echo "$as_me:8082: \$? = $ac_status" >&5 + if (exit $ac_status) && test -s out/conftest2.$ac_objext + then + # The compiler can only warn and ignore the option if not recognized + # So say no if there are warnings + $ECHO "X$_lt_compiler_boilerplate" | $Xsed -e '/^$/d' > out/conftest.exp + $SED '/^$/d; /^ *+/d' out/conftest.err >out/conftest.er2 + if test ! -s out/conftest.er2 || diff out/conftest.exp out/conftest.er2 >/dev/null; then + lt_cv_prog_compiler_c_o=yes + fi + fi + chmod u+w . 2>&5 + $RM conftest* + # SGI C++ compiler will create directory out/ii_files/ for + # template instantiation + test -d out/ii_files && $RM out/ii_files/* && rmdir out/ii_files + $RM out/* && rmdir out + cd .. + $RM -r conftest + $RM conftest* + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_c_o" >&5 +$as_echo "$lt_cv_prog_compiler_c_o" >&6; } + + + + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking if $compiler supports -c -o file.$ac_objext" >&5 +$as_echo_n "checking if $compiler supports -c -o file.$ac_objext... " >&6; } +if test "${lt_cv_prog_compiler_c_o+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_prog_compiler_c_o=no + $RM -r conftest 2>/dev/null + mkdir conftest + cd conftest + mkdir out + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + + lt_compiler_flag="-o out/conftest2.$ac_objext" + # Insert the option either (1) after the last *FLAGS variable, or + # (2) before a word containing "conftest.", or (3) at the end. + # Note that $ac_compile itself does not contain backslashes and begins + # with a dollar sign (not a hyphen), so the echo should work correctly. + lt_compile=`echo "$ac_compile" | $SED \ + -e 's:.*FLAGS}\{0,1\} :&$lt_compiler_flag :; t' \ + -e 's: [^ ]*conftest\.: $lt_compiler_flag&:; t' \ + -e 's:$: $lt_compiler_flag:'` + (eval echo "\"\$as_me:8133: $lt_compile\"" >&5) + (eval "$lt_compile" 2>out/conftest.err) + ac_status=$? + cat out/conftest.err >&5 + echo "$as_me:8137: \$? = $ac_status" >&5 + if (exit $ac_status) && test -s out/conftest2.$ac_objext + then + # The compiler can only warn and ignore the option if not recognized + # So say no if there are warnings + $ECHO "X$_lt_compiler_boilerplate" | $Xsed -e '/^$/d' > out/conftest.exp + $SED '/^$/d; /^ *+/d' out/conftest.err >out/conftest.er2 + if test ! -s out/conftest.er2 || diff out/conftest.exp out/conftest.er2 >/dev/null; then + lt_cv_prog_compiler_c_o=yes + fi + fi + chmod u+w . 2>&5 + $RM conftest* + # SGI C++ compiler will create directory out/ii_files/ for + # template instantiation + test -d out/ii_files && $RM out/ii_files/* && rmdir out/ii_files + $RM out/* && rmdir out + cd .. + $RM -r conftest + $RM conftest* + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_c_o" >&5 +$as_echo "$lt_cv_prog_compiler_c_o" >&6; } + + + + +hard_links="nottested" +if test "$lt_cv_prog_compiler_c_o" = no && test "$need_locks" != no; then + # do not overwrite the value of need_locks provided by the user + { $as_echo "$as_me:${as_lineno-$LINENO}: checking if we can lock with hard links" >&5 +$as_echo_n "checking if we can lock with hard links... " >&6; } + hard_links=yes + $RM conftest* + ln conftest.a conftest.b 2>/dev/null && hard_links=no + touch conftest.a + ln conftest.a conftest.b 2>&5 || hard_links=no + ln conftest.a conftest.b 2>/dev/null && hard_links=no + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $hard_links" >&5 +$as_echo "$hard_links" >&6; } + if test "$hard_links" = no; then + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: \`$CC' does not support \`-c -o', so \`make -j' may be unsafe" >&5 +$as_echo "$as_me: WARNING: \`$CC' does not support \`-c -o', so \`make -j' may be unsafe" >&2;} + need_locks=warn + fi +else + need_locks=no +fi + + + + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether the $compiler linker ($LD) supports shared libraries" >&5 +$as_echo_n "checking whether the $compiler linker ($LD) supports shared libraries... " >&6; } + + runpath_var= + allow_undefined_flag= + always_export_symbols=no + archive_cmds= + archive_expsym_cmds= + compiler_needs_object=no + enable_shared_with_static_runtimes=no + export_dynamic_flag_spec= + export_symbols_cmds='$NM $libobjs $convenience | $global_symbol_pipe | $SED '\''s/.* //'\'' | sort | uniq > $export_symbols' + hardcode_automatic=no + hardcode_direct=no + hardcode_direct_absolute=no + hardcode_libdir_flag_spec= + hardcode_libdir_flag_spec_ld= + hardcode_libdir_separator= + hardcode_minus_L=no + hardcode_shlibpath_var=unsupported + inherit_rpath=no + link_all_deplibs=unknown + module_cmds= + module_expsym_cmds= + old_archive_from_new_cmds= + old_archive_from_expsyms_cmds= + thread_safe_flag_spec= + whole_archive_flag_spec= + # include_expsyms should be a list of space-separated symbols to be *always* + # included in the symbol list + include_expsyms= + # exclude_expsyms can be an extended regexp of symbols to exclude + # it will be wrapped by ` (' and `)$', so one must not match beginning or + # end of line. Example: `a|bc|.*d.*' will exclude the symbols `a' and `bc', + # as well as any symbol that contains `d'. + exclude_expsyms='_GLOBAL_OFFSET_TABLE_|_GLOBAL__F[ID]_.*' + # Although _GLOBAL_OFFSET_TABLE_ is a valid symbol C name, most a.out + # platforms (ab)use it in PIC code, but their linkers get confused if + # the symbol is explicitly referenced. Since portable code cannot + # rely on this symbol name, it's probably fine to never include it in + # preloaded symbol tables. + # Exclude shared library initialization/finalization symbols. + extract_expsyms_cmds= + + case $host_os in + cygwin* | mingw* | pw32* | cegcc*) + # FIXME: the MSVC++ port hasn't been tested in a loooong time + # When not using gcc, we currently assume that we are using + # Microsoft Visual C++. + if test "$GCC" != yes; then + with_gnu_ld=no + fi + ;; + interix*) + # we just hope/assume this is gcc and not c89 (= MSVC++) + with_gnu_ld=yes + ;; + openbsd*) + with_gnu_ld=no + ;; + linux* | k*bsd*-gnu) + link_all_deplibs=no + ;; + esac + + ld_shlibs=yes + if test "$with_gnu_ld" = yes; then + # If archive_cmds runs LD, not CC, wlarc should be empty + wlarc='${wl}' + + # Set some defaults for GNU ld with shared library support. These + # are reset later if shared libraries are not supported. Putting them + # here allows them to be overridden if necessary. + runpath_var=LD_RUN_PATH + hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + export_dynamic_flag_spec='${wl}--export-dynamic' + # ancient GNU ld didn't support --whole-archive et. al. + if $LD --help 2>&1 | $GREP 'no-whole-archive' > /dev/null; then + whole_archive_flag_spec="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + else + whole_archive_flag_spec= + fi + supports_anon_versioning=no + case `$LD -v 2>&1` in + *GNU\ gold*) supports_anon_versioning=yes ;; + *\ [01].* | *\ 2.[0-9].* | *\ 2.10.*) ;; # catch versions < 2.11 + *\ 2.11.93.0.2\ *) supports_anon_versioning=yes ;; # RH7.3 ... + *\ 2.11.92.0.12\ *) supports_anon_versioning=yes ;; # Mandrake 8.2 ... + *\ 2.11.*) ;; # other 2.11 versions + *) supports_anon_versioning=yes ;; + esac + + # See if GNU ld supports shared libraries. + case $host_os in + aix[3-9]*) + # On AIX/PPC, the GNU linker is very broken + if test "$host_cpu" != ia64; then + ld_shlibs=no + cat <<_LT_EOF 1>&2 + +*** Warning: the GNU linker, at least up to release 2.9.1, is reported +*** to be unable to reliably create shared libraries on AIX. +*** Therefore, libtool is disabling shared libraries support. If you +*** really care for shared libraries, you may want to modify your PATH +*** so that a non-GNU linker is found, and then restart. + +_LT_EOF + fi + ;; + + amigaos*) + case $host_cpu in + powerpc) + # see comment about AmigaOS4 .so support + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_expsym_cmds='' + ;; + m68k) + archive_cmds='$RM $output_objdir/a2ixlibrary.data~$ECHO "#define NAME $libname" > $output_objdir/a2ixlibrary.data~$ECHO "#define LIBRARY_ID 1" >> $output_objdir/a2ixlibrary.data~$ECHO "#define VERSION $major" >> $output_objdir/a2ixlibrary.data~$ECHO "#define REVISION $revision" >> $output_objdir/a2ixlibrary.data~$AR $AR_FLAGS $lib $libobjs~$RANLIB $lib~(cd $output_objdir && a2ixlibrary -32)' + hardcode_libdir_flag_spec='-L$libdir' + hardcode_minus_L=yes + ;; + esac + ;; + + beos*) + if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then + allow_undefined_flag=unsupported + # Joseph Beckenbach says some releases of gcc + # support --undefined. This deserves some investigation. FIXME + archive_cmds='$CC -nostart $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + else + ld_shlibs=no + fi + ;; + + cygwin* | mingw* | pw32* | cegcc*) + # _LT_TAGVAR(hardcode_libdir_flag_spec, ) is actually meaningless, + # as there is no search path for DLLs. + hardcode_libdir_flag_spec='-L$libdir' + allow_undefined_flag=unsupported + always_export_symbols=no + enable_shared_with_static_runtimes=yes + export_symbols_cmds='$NM $libobjs $convenience | $global_symbol_pipe | $SED -e '\''/^[BCDGRS][ ]/s/.*[ ]\([^ ]*\)/\1 DATA/'\'' | $SED -e '\''/^[AITW][ ]/s/.*[ ]//'\'' | sort | uniq > $export_symbols' + + if $LD --help 2>&1 | $GREP 'auto-import' > /dev/null; then + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + # If the export-symbols file already is a .def file (1st line + # is EXPORTS), use it as is; otherwise, prepend... + archive_expsym_cmds='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then + cp $export_symbols $output_objdir/$soname.def; + else + echo EXPORTS > $output_objdir/$soname.def; + cat $export_symbols >> $output_objdir/$soname.def; + fi~ + $CC -shared $output_objdir/$soname.def $libobjs $deplibs $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + else + ld_shlibs=no + fi + ;; + + interix[3-9]*) + hardcode_direct=no + hardcode_shlibpath_var=no + hardcode_libdir_flag_spec='${wl}-rpath,$libdir' + export_dynamic_flag_spec='${wl}-E' + # Hack: On Interix 3.x, we cannot compile PIC because of a broken gcc. + # Instead, shared libraries are loaded at an image base (0x10000000 by + # default) and relocated if they conflict, which is a slow very memory + # consuming and fragmenting process. To avoid this, we pick a random, + # 256 KiB-aligned image base between 0x50000000 and 0x6FFC0000 at link + # time. Moving up from 0x10000000 also allows more sbrk(2) space. + archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + archive_expsym_cmds='sed "s,^,_," $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--retain-symbols-file,$output_objdir/$soname.expsym ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + ;; + + gnu* | linux* | tpf* | k*bsd*-gnu | kopensolaris*-gnu) + tmp_diet=no + if test "$host_os" = linux-dietlibc; then + case $cc_basename in + diet\ *) tmp_diet=yes;; # linux-dietlibc with static linking (!diet-dyn) + esac + fi + if $LD --help 2>&1 | $EGREP ': supported targets:.* elf' > /dev/null \ + && test "$tmp_diet" = no + then + tmp_addflag= + tmp_sharedflag='-shared' + case $cc_basename,$host_cpu in + pgcc*) # Portland Group C compiler + whole_archive_flag_spec='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; $ECHO \"$new_convenience\"` ${wl}--no-whole-archive' + tmp_addflag=' $pic_flag' + ;; + pgf77* | pgf90* | pgf95*) # Portland Group f77 and f90 compilers + whole_archive_flag_spec='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; $ECHO \"$new_convenience\"` ${wl}--no-whole-archive' + tmp_addflag=' $pic_flag -Mnomain' ;; + ecc*,ia64* | icc*,ia64*) # Intel C compiler on ia64 + tmp_addflag=' -i_dynamic' ;; + efc*,ia64* | ifort*,ia64*) # Intel Fortran compiler on ia64 + tmp_addflag=' -i_dynamic -nofor_main' ;; + ifc* | ifort*) # Intel Fortran compiler + tmp_addflag=' -nofor_main' ;; + lf95*) # Lahey Fortran 8.1 + whole_archive_flag_spec= + tmp_sharedflag='--shared' ;; + xl[cC]*) # IBM XL C 8.0 on PPC (deal with xlf below) + tmp_sharedflag='-qmkshrobj' + tmp_addflag= ;; + esac + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) # Sun C 5.9 + whole_archive_flag_spec='${wl}--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; $ECHO \"$new_convenience\"` ${wl}--no-whole-archive' + compiler_needs_object=yes + tmp_sharedflag='-G' ;; + *Sun\ F*) # Sun Fortran 8.3 + tmp_sharedflag='-G' ;; + esac + archive_cmds='$CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + + if test "x$supports_anon_versioning" = xyes; then + archive_expsym_cmds='echo "{ global:" > $output_objdir/$libname.ver~ + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-version-script ${wl}$output_objdir/$libname.ver -o $lib' + fi + + case $cc_basename in + xlf*) + # IBM XL Fortran 10.1 on PPC cannot create shared libs itself + whole_archive_flag_spec='--whole-archive$convenience --no-whole-archive' + hardcode_libdir_flag_spec= + hardcode_libdir_flag_spec_ld='-rpath $libdir' + archive_cmds='$LD -shared $libobjs $deplibs $compiler_flags -soname $soname -o $lib' + if test "x$supports_anon_versioning" = xyes; then + archive_expsym_cmds='echo "{ global:" > $output_objdir/$libname.ver~ + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $LD -shared $libobjs $deplibs $compiler_flags -soname $soname -version-script $output_objdir/$libname.ver -o $lib' + fi + ;; + esac + else + ld_shlibs=no + fi + ;; + + netbsd* | netbsdelf*-gnu) + if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then + archive_cmds='$LD -Bshareable $libobjs $deplibs $linker_flags -o $lib' + wlarc= + else + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_expsym_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + fi + ;; + + solaris*) + if $LD -v 2>&1 | $GREP 'BFD 2\.8' > /dev/null; then + ld_shlibs=no + cat <<_LT_EOF 1>&2 + +*** Warning: The releases 2.8.* of the GNU linker cannot reliably +*** create shared libraries on Solaris systems. Therefore, libtool +*** is disabling shared libraries support. We urge you to upgrade GNU +*** binutils to release 2.9.1 or newer. Another option is to modify +*** your PATH or compiler configuration so that the native linker is +*** used, and then restart. + +_LT_EOF + elif $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_expsym_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + else + ld_shlibs=no + fi + ;; + + sysv5* | sco3.2v5* | sco5v6* | unixware* | OpenUNIX*) + case `$LD -v 2>&1` in + *\ [01].* | *\ 2.[0-9].* | *\ 2.1[0-5].*) + ld_shlibs=no + cat <<_LT_EOF 1>&2 + +*** Warning: Releases of the GNU linker prior to 2.16.91.0.3 can not +*** reliably create shared libraries on SCO systems. Therefore, libtool +*** is disabling shared libraries support. We urge you to upgrade GNU +*** binutils to release 2.16.91.0.3 or newer. Another option is to modify +*** your PATH or compiler configuration so that the native linker is +*** used, and then restart. + +_LT_EOF + ;; + *) + # For security reasons, it is highly recommended that you always + # use absolute paths for naming shared libraries, and exclude the + # DT_RUNPATH tag from executables and libraries. But doing so + # requires that you compile everything twice, which is a pain. + if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then + hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_expsym_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + else + ld_shlibs=no + fi + ;; + esac + ;; + + sunos4*) + archive_cmds='$LD -assert pure-text -Bshareable -o $lib $libobjs $deplibs $linker_flags' + wlarc= + hardcode_direct=yes + hardcode_shlibpath_var=no + ;; + + *) + if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_expsym_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + else + ld_shlibs=no + fi + ;; + esac + + if test "$ld_shlibs" = no; then + runpath_var= + hardcode_libdir_flag_spec= + export_dynamic_flag_spec= + whole_archive_flag_spec= + fi + else + # PORTME fill in a description of your system's linker (not GNU ld) + case $host_os in + aix3*) + allow_undefined_flag=unsupported + always_export_symbols=yes + archive_expsym_cmds='$LD -o $output_objdir/$soname $libobjs $deplibs $linker_flags -bE:$export_symbols -T512 -H512 -bM:SRE~$AR $AR_FLAGS $lib $output_objdir/$soname' + # Note: this linker hardcodes the directories in LIBPATH if there + # are no directories specified by -L. + hardcode_minus_L=yes + if test "$GCC" = yes && test -z "$lt_prog_compiler_static"; then + # Neither direct hardcoding nor static linking is supported with a + # broken collect2. + hardcode_direct=unsupported + fi + ;; + + aix[4-9]*) + if test "$host_cpu" = ia64; then + # On IA64, the linker does run time linking by default, so we don't + # have to do anything special. + aix_use_runtimelinking=no + exp_sym_flag='-Bexport' + no_entry_flag="" + else + # If we're using GNU nm, then we don't want the "-C" option. + # -C means demangle to AIX nm, but means don't demangle with GNU nm + if $NM -V 2>&1 | $GREP 'GNU' > /dev/null; then + export_symbols_cmds='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && (substr(\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + else + export_symbols_cmds='$NM -BCpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && (substr(\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + fi + aix_use_runtimelinking=no + + # Test if we are trying to use run time linking or normal + # AIX style linking. If -brtl is somewhere in LDFLAGS, we + # need to do runtime linking. + case $host_os in aix4.[23]|aix4.[23].*|aix[5-9]*) + for ld_flag in $LDFLAGS; do + if (test $ld_flag = "-brtl" || test $ld_flag = "-Wl,-brtl"); then + aix_use_runtimelinking=yes + break + fi + done + ;; + esac + + exp_sym_flag='-bexport' + no_entry_flag='-bnoentry' + fi + + # When large executables or shared objects are built, AIX ld can + # have problems creating the table of contents. If linking a library + # or program results in "error TOC overflow" add -mminimal-toc to + # CXXFLAGS/CFLAGS for g++/gcc. In the cases where that is not + # enough to fix the problem, add -Wl,-bbigtoc to LDFLAGS. + + archive_cmds='' + hardcode_direct=yes + hardcode_direct_absolute=yes + hardcode_libdir_separator=':' + link_all_deplibs=yes + file_list_spec='${wl}-f,' + + if test "$GCC" = yes; then + case $host_os in aix4.[012]|aix4.[012].*) + # We only want to do this on AIX 4.2 and lower, the check + # below for broken collect2 doesn't work under 4.3+ + collect2name=`${CC} -print-prog-name=collect2` + if test -f "$collect2name" && + strings "$collect2name" | $GREP resolve_lib_name >/dev/null + then + # We have reworked collect2 + : + else + # We have old collect2 + hardcode_direct=unsupported + # It fails to find uninstalled libraries when the uninstalled + # path is not listed in the libpath. Setting hardcode_minus_L + # to unsupported forces relinking + hardcode_minus_L=yes + hardcode_libdir_flag_spec='-L$libdir' + hardcode_libdir_separator= + fi + ;; + esac + shared_flag='-shared' + if test "$aix_use_runtimelinking" = yes; then + shared_flag="$shared_flag "'${wl}-G' + fi + link_all_deplibs=no + else + # not using gcc + if test "$host_cpu" = ia64; then + # VisualAge C++, Version 5.5 for AIX 5L for IA-64, Beta 3 Release + # chokes on -Wl,-G. The following line is correct: + shared_flag='-G' + else + if test "$aix_use_runtimelinking" = yes; then + shared_flag='${wl}-G' + else + shared_flag='${wl}-bM:SRE' + fi + fi + fi + + export_dynamic_flag_spec='${wl}-bexpall' + # It seems that -bexpall does not export symbols beginning with + # underscore (_), so it is better to generate a list of symbols to export. + always_export_symbols=yes + if test "$aix_use_runtimelinking" = yes; then + # Warning - without using the other runtime loading flags (-brtl), + # -berok will link without error, but may produce a broken library. + allow_undefined_flag='-berok' + # Determine the default libpath from the value encoded in an + # empty executable. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + +lt_aix_libpath_sed=' + /Import File Strings/,/^$/ { + /^0/ { + s/^0 *\(.*\)$/\1/ + p + } + }' +aix_libpath=`dump -H conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` +# Check for a 64-bit object if we didn't find anything. +if test -z "$aix_libpath"; then + aix_libpath=`dump -HX64 conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` +fi +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +if test -z "$aix_libpath"; then aix_libpath="/usr/lib:/lib"; fi + + hardcode_libdir_flag_spec='${wl}-blibpath:$libdir:'"$aix_libpath" + archive_expsym_cmds='$CC -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags `if test "x${allow_undefined_flag}" != "x"; then $ECHO "X${wl}${allow_undefined_flag}" | $Xsed; else :; fi` '"\${wl}$exp_sym_flag:\$export_symbols $shared_flag" + else + if test "$host_cpu" = ia64; then + hardcode_libdir_flag_spec='${wl}-R $libdir:/usr/lib:/lib' + allow_undefined_flag="-z nodefs" + archive_expsym_cmds="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags ${wl}${allow_undefined_flag} '"\${wl}$exp_sym_flag:\$export_symbols" + else + # Determine the default libpath from the value encoded in an + # empty executable. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + +lt_aix_libpath_sed=' + /Import File Strings/,/^$/ { + /^0/ { + s/^0 *\(.*\)$/\1/ + p + } + }' +aix_libpath=`dump -H conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` +# Check for a 64-bit object if we didn't find anything. +if test -z "$aix_libpath"; then + aix_libpath=`dump -HX64 conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` +fi +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +if test -z "$aix_libpath"; then aix_libpath="/usr/lib:/lib"; fi + + hardcode_libdir_flag_spec='${wl}-blibpath:$libdir:'"$aix_libpath" + # Warning - without using the other run time loading flags, + # -berok will link without error, but may produce a broken library. + no_undefined_flag=' ${wl}-bernotok' + allow_undefined_flag=' ${wl}-berok' + # Exported symbols can be pulled into shared objects from archives + whole_archive_flag_spec='$convenience' + archive_cmds_need_lc=yes + # This is similar to how AIX traditionally builds its shared libraries. + archive_expsym_cmds="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs ${wl}-bnoentry $compiler_flags ${wl}-bE:$export_symbols${allow_undefined_flag}~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$soname' + fi + fi + ;; + + amigaos*) + case $host_cpu in + powerpc) + # see comment about AmigaOS4 .so support + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_expsym_cmds='' + ;; + m68k) + archive_cmds='$RM $output_objdir/a2ixlibrary.data~$ECHO "#define NAME $libname" > $output_objdir/a2ixlibrary.data~$ECHO "#define LIBRARY_ID 1" >> $output_objdir/a2ixlibrary.data~$ECHO "#define VERSION $major" >> $output_objdir/a2ixlibrary.data~$ECHO "#define REVISION $revision" >> $output_objdir/a2ixlibrary.data~$AR $AR_FLAGS $lib $libobjs~$RANLIB $lib~(cd $output_objdir && a2ixlibrary -32)' + hardcode_libdir_flag_spec='-L$libdir' + hardcode_minus_L=yes + ;; + esac + ;; + + bsdi[45]*) + export_dynamic_flag_spec=-rdynamic + ;; + + cygwin* | mingw* | pw32* | cegcc*) + # When not using gcc, we currently assume that we are using + # Microsoft Visual C++. + # hardcode_libdir_flag_spec is actually meaningless, as there is + # no search path for DLLs. + hardcode_libdir_flag_spec=' ' + allow_undefined_flag=unsupported + # Tell ltmain to make .lib files, not .a files. + libext=lib + # Tell ltmain to make .dll files, not .so files. + shrext_cmds=".dll" + # FIXME: Setting linknames here is a bad hack. + archive_cmds='$CC -o $lib $libobjs $compiler_flags `$ECHO "X$deplibs" | $Xsed -e '\''s/ -lc$//'\''` -link -dll~linknames=' + # The linker will automatically build a .lib file if we build a DLL. + old_archive_from_new_cmds='true' + # FIXME: Should let the user specify the lib program. + old_archive_cmds='lib -OUT:$oldlib$oldobjs$old_deplibs' + fix_srcfile_path='`cygpath -w "$srcfile"`' + enable_shared_with_static_runtimes=yes + ;; + + darwin* | rhapsody*) + + + archive_cmds_need_lc=no + hardcode_direct=no + hardcode_automatic=yes + hardcode_shlibpath_var=unsupported + whole_archive_flag_spec='' + link_all_deplibs=yes + allow_undefined_flag="$_lt_dar_allow_undefined" + case $cc_basename in + ifort*) _lt_dar_can_shared=yes ;; + *) _lt_dar_can_shared=$GCC ;; + esac + if test "$_lt_dar_can_shared" = "yes"; then + output_verbose_link_cmd=echo + archive_cmds="\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod${_lt_dsymutil}" + module_cmds="\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dsymutil}" + archive_expsym_cmds="sed 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring ${_lt_dar_single_mod}${_lt_dar_export_syms}${_lt_dsymutil}" + module_expsym_cmds="sed -e 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dar_export_syms}${_lt_dsymutil}" + + else + ld_shlibs=no + fi + + ;; + + dgux*) + archive_cmds='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + hardcode_libdir_flag_spec='-L$libdir' + hardcode_shlibpath_var=no + ;; + + freebsd1*) + ld_shlibs=no + ;; + + # FreeBSD 2.2.[012] allows us to include c++rt0.o to get C++ constructor + # support. Future versions do this automatically, but an explicit c++rt0.o + # does not break anything, and helps significantly (at the cost of a little + # extra space). + freebsd2.2*) + archive_cmds='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags /usr/lib/c++rt0.o' + hardcode_libdir_flag_spec='-R$libdir' + hardcode_direct=yes + hardcode_shlibpath_var=no + ;; + + # Unfortunately, older versions of FreeBSD 2 do not have this feature. + freebsd2*) + archive_cmds='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags' + hardcode_direct=yes + hardcode_minus_L=yes + hardcode_shlibpath_var=no + ;; + + # FreeBSD 3 and greater uses gcc -shared to do shared libraries. + freebsd* | dragonfly*) + archive_cmds='$CC -shared -o $lib $libobjs $deplibs $compiler_flags' + hardcode_libdir_flag_spec='-R$libdir' + hardcode_direct=yes + hardcode_shlibpath_var=no + ;; + + hpux9*) + if test "$GCC" = yes; then + archive_cmds='$RM $output_objdir/$soname~$CC -shared -fPIC ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $libobjs $deplibs $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + else + archive_cmds='$RM $output_objdir/$soname~$LD -b +b $install_libdir -o $output_objdir/$soname $libobjs $deplibs $linker_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + fi + hardcode_libdir_flag_spec='${wl}+b ${wl}$libdir' + hardcode_libdir_separator=: + hardcode_direct=yes + + # hardcode_minus_L: Not really in the search PATH, + # but as the default location of the library. + hardcode_minus_L=yes + export_dynamic_flag_spec='${wl}-E' + ;; + + hpux10*) + if test "$GCC" = yes -a "$with_gnu_ld" = no; then + archive_cmds='$CC -shared -fPIC ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' + else + archive_cmds='$LD -b +h $soname +b $install_libdir -o $lib $libobjs $deplibs $linker_flags' + fi + if test "$with_gnu_ld" = no; then + hardcode_libdir_flag_spec='${wl}+b ${wl}$libdir' + hardcode_libdir_flag_spec_ld='+b $libdir' + hardcode_libdir_separator=: + hardcode_direct=yes + hardcode_direct_absolute=yes + export_dynamic_flag_spec='${wl}-E' + # hardcode_minus_L: Not really in the search PATH, + # but as the default location of the library. + hardcode_minus_L=yes + fi + ;; + + hpux11*) + if test "$GCC" = yes -a "$with_gnu_ld" = no; then + case $host_cpu in + hppa*64*) + archive_cmds='$CC -shared ${wl}+h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + ia64*) + archive_cmds='$CC -shared -fPIC ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' + ;; + *) + archive_cmds='$CC -shared -fPIC ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' + ;; + esac + else + case $host_cpu in + hppa*64*) + archive_cmds='$CC -b ${wl}+h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + ia64*) + archive_cmds='$CC -b ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' + ;; + *) + archive_cmds='$CC -b ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' + ;; + esac + fi + if test "$with_gnu_ld" = no; then + hardcode_libdir_flag_spec='${wl}+b ${wl}$libdir' + hardcode_libdir_separator=: + + case $host_cpu in + hppa*64*|ia64*) + hardcode_direct=no + hardcode_shlibpath_var=no + ;; + *) + hardcode_direct=yes + hardcode_direct_absolute=yes + export_dynamic_flag_spec='${wl}-E' + + # hardcode_minus_L: Not really in the search PATH, + # but as the default location of the library. + hardcode_minus_L=yes + ;; + esac + fi + ;; + + irix5* | irix6* | nonstopux*) + if test "$GCC" = yes; then + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + # Try to use the -exported_symbol ld option, if it does not + # work, assume that -exports_file does not work either and + # implicitly export all symbols. + save_LDFLAGS="$LDFLAGS" + LDFLAGS="$LDFLAGS -shared ${wl}-exported_symbol ${wl}foo ${wl}-update_registry ${wl}/dev/null" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +int foo(void) {} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + archive_expsym_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations ${wl}-exports_file ${wl}$export_symbols -o $lib' + +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext + LDFLAGS="$save_LDFLAGS" + else + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + archive_expsym_cmds='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -exports_file $export_symbols -o $lib' + fi + archive_cmds_need_lc='no' + hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + hardcode_libdir_separator=: + inherit_rpath=yes + link_all_deplibs=yes + ;; + + netbsd* | netbsdelf*-gnu) + if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then + archive_cmds='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags' # a.out + else + archive_cmds='$LD -shared -o $lib $libobjs $deplibs $linker_flags' # ELF + fi + hardcode_libdir_flag_spec='-R$libdir' + hardcode_direct=yes + hardcode_shlibpath_var=no + ;; + + newsos6) + archive_cmds='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + hardcode_direct=yes + hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + hardcode_libdir_separator=: + hardcode_shlibpath_var=no + ;; + + *nto* | *qnx*) + ;; + + openbsd*) + if test -f /usr/libexec/ld.so; then + hardcode_direct=yes + hardcode_shlibpath_var=no + hardcode_direct_absolute=yes + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + archive_cmds='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags ${wl}-retain-symbols-file,$export_symbols' + hardcode_libdir_flag_spec='${wl}-rpath,$libdir' + export_dynamic_flag_spec='${wl}-E' + else + case $host_os in + openbsd[01].* | openbsd2.[0-7] | openbsd2.[0-7].*) + archive_cmds='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags' + hardcode_libdir_flag_spec='-R$libdir' + ;; + *) + archive_cmds='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' + hardcode_libdir_flag_spec='${wl}-rpath,$libdir' + ;; + esac + fi + else + ld_shlibs=no + fi + ;; + + os2*) + hardcode_libdir_flag_spec='-L$libdir' + hardcode_minus_L=yes + allow_undefined_flag=unsupported + archive_cmds='$ECHO "LIBRARY $libname INITINSTANCE" > $output_objdir/$libname.def~$ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~$ECHO DATA >> $output_objdir/$libname.def~$ECHO " SINGLE NONSHARED" >> $output_objdir/$libname.def~$ECHO EXPORTS >> $output_objdir/$libname.def~emxexp $libobjs >> $output_objdir/$libname.def~$CC -Zdll -Zcrtdll -o $lib $libobjs $deplibs $compiler_flags $output_objdir/$libname.def' + old_archive_from_new_cmds='emximp -o $output_objdir/$libname.a $output_objdir/$libname.def' + ;; + + osf3*) + if test "$GCC" = yes; then + allow_undefined_flag=' ${wl}-expect_unresolved ${wl}\*' + archive_cmds='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + else + allow_undefined_flag=' -expect_unresolved \*' + archive_cmds='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + fi + archive_cmds_need_lc='no' + hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + hardcode_libdir_separator=: + ;; + + osf4* | osf5*) # as osf3* with the addition of -msym flag + if test "$GCC" = yes; then + allow_undefined_flag=' ${wl}-expect_unresolved ${wl}\*' + archive_cmds='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags ${wl}-msym ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + else + allow_undefined_flag=' -expect_unresolved \*' + archive_cmds='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags -msym -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + archive_expsym_cmds='for i in `cat $export_symbols`; do printf "%s %s\\n" -exported_symbol "\$i" >> $lib.exp; done; printf "%s\\n" "-hidden">> $lib.exp~ + $CC -shared${allow_undefined_flag} ${wl}-input ${wl}$lib.exp $compiler_flags $libobjs $deplibs -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib~$RM $lib.exp' + + # Both c and cxx compiler support -rpath directly + hardcode_libdir_flag_spec='-rpath $libdir' + fi + archive_cmds_need_lc='no' + hardcode_libdir_separator=: + ;; + + solaris*) + no_undefined_flag=' -z defs' + if test "$GCC" = yes; then + wlarc='${wl}' + archive_cmds='$CC -shared ${wl}-z ${wl}text ${wl}-h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $CC -shared ${wl}-z ${wl}text ${wl}-M ${wl}$lib.exp ${wl}-h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' + else + case `$CC -V 2>&1` in + *"Compilers 5.0"*) + wlarc='' + archive_cmds='$LD -G${allow_undefined_flag} -h $soname -o $lib $libobjs $deplibs $linker_flags' + archive_expsym_cmds='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $LD -G${allow_undefined_flag} -M $lib.exp -h $soname -o $lib $libobjs $deplibs $linker_flags~$RM $lib.exp' + ;; + *) + wlarc='${wl}' + archive_cmds='$CC -G${allow_undefined_flag} -h $soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $CC -G${allow_undefined_flag} -M $lib.exp -h $soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' + ;; + esac + fi + hardcode_libdir_flag_spec='-R$libdir' + hardcode_shlibpath_var=no + case $host_os in + solaris2.[0-5] | solaris2.[0-5].*) ;; + *) + # The compiler driver will combine and reorder linker options, + # but understands `-z linker_flag'. GCC discards it without `$wl', + # but is careful enough not to reorder. + # Supported since Solaris 2.6 (maybe 2.5.1?) + if test "$GCC" = yes; then + whole_archive_flag_spec='${wl}-z ${wl}allextract$convenience ${wl}-z ${wl}defaultextract' + else + whole_archive_flag_spec='-z allextract$convenience -z defaultextract' + fi + ;; + esac + link_all_deplibs=yes + ;; + + sunos4*) + if test "x$host_vendor" = xsequent; then + # Use $CC to link under sequent, because it throws in some extra .o + # files that make .init and .fini sections work. + archive_cmds='$CC -G ${wl}-h $soname -o $lib $libobjs $deplibs $compiler_flags' + else + archive_cmds='$LD -assert pure-text -Bstatic -o $lib $libobjs $deplibs $linker_flags' + fi + hardcode_libdir_flag_spec='-L$libdir' + hardcode_direct=yes + hardcode_minus_L=yes + hardcode_shlibpath_var=no + ;; + + sysv4) + case $host_vendor in + sni) + archive_cmds='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + hardcode_direct=yes # is this really true??? + ;; + siemens) + ## LD is ld it makes a PLAMLIB + ## CC just makes a GrossModule. + archive_cmds='$LD -G -o $lib $libobjs $deplibs $linker_flags' + reload_cmds='$CC -r -o $output$reload_objs' + hardcode_direct=no + ;; + motorola) + archive_cmds='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + hardcode_direct=no #Motorola manual says yes, but my tests say they lie + ;; + esac + runpath_var='LD_RUN_PATH' + hardcode_shlibpath_var=no + ;; + + sysv4.3*) + archive_cmds='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + hardcode_shlibpath_var=no + export_dynamic_flag_spec='-Bexport' + ;; + + sysv4*MP*) + if test -d /usr/nec; then + archive_cmds='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + hardcode_shlibpath_var=no + runpath_var=LD_RUN_PATH + hardcode_runpath_var=yes + ld_shlibs=yes + fi + ;; + + sysv4*uw2* | sysv5OpenUNIX* | sysv5UnixWare7.[01].[10]* | unixware7* | sco3.2v5.0.[024]*) + no_undefined_flag='${wl}-z,text' + archive_cmds_need_lc=no + hardcode_shlibpath_var=no + runpath_var='LD_RUN_PATH' + + if test "$GCC" = yes; then + archive_cmds='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + else + archive_cmds='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + fi + ;; + + sysv5* | sco3.2v5* | sco5v6*) + # Note: We can NOT use -z defs as we might desire, because we do not + # link with -lc, and that would cause any symbols used from libc to + # always be unresolved, which means just about no library would + # ever link correctly. If we're not using GNU ld we use -z text + # though, which does catch some bad symbols but isn't as heavy-handed + # as -z defs. + no_undefined_flag='${wl}-z,text' + allow_undefined_flag='${wl}-z,nodefs' + archive_cmds_need_lc=no + hardcode_shlibpath_var=no + hardcode_libdir_flag_spec='${wl}-R,$libdir' + hardcode_libdir_separator=':' + link_all_deplibs=yes + export_dynamic_flag_spec='${wl}-Bexport' + runpath_var='LD_RUN_PATH' + + if test "$GCC" = yes; then + archive_cmds='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + else + archive_cmds='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + fi + ;; + + uts4*) + archive_cmds='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' + hardcode_libdir_flag_spec='-L$libdir' + hardcode_shlibpath_var=no + ;; + + *) + ld_shlibs=no + ;; + esac + + if test x$host_vendor = xsni; then + case $host in + sysv4 | sysv4.2uw2* | sysv4.3* | sysv5*) + export_dynamic_flag_spec='${wl}-Blargedynsym' + ;; + esac + fi + fi + +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ld_shlibs" >&5 +$as_echo "$ld_shlibs" >&6; } +test "$ld_shlibs" = no && can_build_shared=no + +with_gnu_ld=$with_gnu_ld + + + + + + + + + + + + + + + +# +# Do we need to explicitly link libc? +# +case "x$archive_cmds_need_lc" in +x|xyes) + # Assume -lc should be added + archive_cmds_need_lc=yes + + if test "$enable_shared" = yes && test "$GCC" = yes; then + case $archive_cmds in + *'~'*) + # FIXME: we may have to deal with multi-command sequences. + ;; + '$CC '*) + # Test whether the compiler implicitly links with -lc since on some + # systems, -lgcc has to come before -lc. If gcc already passes -lc + # to ld, don't add -lc before -lgcc. + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether -lc should be explicitly linked in" >&5 +$as_echo_n "checking whether -lc should be explicitly linked in... " >&6; } + $RM conftest* + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 + (eval $ac_compile) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } 2>conftest.err; then + soname=conftest + lib=conftest + libobjs=conftest.$ac_objext + deplibs= + wl=$lt_prog_compiler_wl + pic_flag=$lt_prog_compiler_pic + compiler_flags=-v + linker_flags=-v + verstring= + output_objdir=. + libname=conftest + lt_save_allow_undefined_flag=$allow_undefined_flag + allow_undefined_flag= + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$archive_cmds 2\>\&1 \| $GREP \" -lc \" \>/dev/null 2\>\&1\""; } >&5 + (eval $archive_cmds 2\>\&1 \| $GREP \" -lc \" \>/dev/null 2\>\&1) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } + then + archive_cmds_need_lc=no + else + archive_cmds_need_lc=yes + fi + allow_undefined_flag=$lt_save_allow_undefined_flag + else + cat conftest.err 1>&5 + fi + $RM conftest* + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $archive_cmds_need_lc" >&5 +$as_echo "$archive_cmds_need_lc" >&6; } + ;; + esac + fi + ;; +esac + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking dynamic linker characteristics" >&5 +$as_echo_n "checking dynamic linker characteristics... " >&6; } + +if test "$GCC" = yes; then + case $host_os in + darwin*) lt_awk_arg="/^libraries:/,/LR/" ;; + *) lt_awk_arg="/^libraries:/" ;; + esac + lt_search_path_spec=`$CC -print-search-dirs | awk $lt_awk_arg | $SED -e "s/^libraries://" -e "s,=/,/,g"` + if $ECHO "$lt_search_path_spec" | $GREP ';' >/dev/null ; then + # if the path contains ";" then we assume it to be the separator + # otherwise default to the standard path separator (i.e. ":") - it is + # assumed that no part of a normal pathname contains ";" but that should + # okay in the real world where ";" in dirpaths is itself problematic. + lt_search_path_spec=`$ECHO "$lt_search_path_spec" | $SED -e 's/;/ /g'` + else + lt_search_path_spec=`$ECHO "$lt_search_path_spec" | $SED -e "s/$PATH_SEPARATOR/ /g"` + fi + # Ok, now we have the path, separated by spaces, we can step through it + # and add multilib dir if necessary. + lt_tmp_lt_search_path_spec= + lt_multi_os_dir=`$CC $CPPFLAGS $CFLAGS $LDFLAGS -print-multi-os-directory 2>/dev/null` + for lt_sys_path in $lt_search_path_spec; do + if test -d "$lt_sys_path/$lt_multi_os_dir"; then + lt_tmp_lt_search_path_spec="$lt_tmp_lt_search_path_spec $lt_sys_path/$lt_multi_os_dir" + else + test -d "$lt_sys_path" && \ + lt_tmp_lt_search_path_spec="$lt_tmp_lt_search_path_spec $lt_sys_path" + fi + done + lt_search_path_spec=`$ECHO $lt_tmp_lt_search_path_spec | awk ' +BEGIN {RS=" "; FS="/|\n";} { + lt_foo=""; + lt_count=0; + for (lt_i = NF; lt_i > 0; lt_i--) { + if ($lt_i != "" && $lt_i != ".") { + if ($lt_i == "..") { + lt_count++; + } else { + if (lt_count == 0) { + lt_foo="/" $lt_i lt_foo; + } else { + lt_count--; + } + } + } + } + if (lt_foo != "") { lt_freq[lt_foo]++; } + if (lt_freq[lt_foo] == 1) { print lt_foo; } +}'` + sys_lib_search_path_spec=`$ECHO $lt_search_path_spec` +else + sys_lib_search_path_spec="/lib /usr/lib /usr/local/lib" +fi +library_names_spec= +libname_spec='lib$name' +soname_spec= +shrext_cmds=".so" +postinstall_cmds= +postuninstall_cmds= +finish_cmds= +finish_eval= +shlibpath_var= +shlibpath_overrides_runpath=unknown +version_type=none +dynamic_linker="$host_os ld.so" +sys_lib_dlsearch_path_spec="/lib /usr/lib" +need_lib_prefix=unknown +hardcode_into_libs=no + +# when you set need_version to no, make sure it does not cause -set_version +# flags to be left without arguments +need_version=unknown + +case $host_os in +aix3*) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix $libname.a' + shlibpath_var=LIBPATH + + # AIX 3 has no versioning support, so we append a major version to the name. + soname_spec='${libname}${release}${shared_ext}$major' + ;; + +aix[4-9]*) + version_type=linux + need_lib_prefix=no + need_version=no + hardcode_into_libs=yes + if test "$host_cpu" = ia64; then + # AIX 5 supports IA64 + library_names_spec='${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext}$versuffix $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + else + # With GCC up to 2.95.x, collect2 would create an import file + # for dependence libraries. The import file would start with + # the line `#! .'. This would cause the generated library to + # depend on `.', always an invalid library. This was fixed in + # development snapshots of GCC prior to 3.0. + case $host_os in + aix4 | aix4.[01] | aix4.[01].*) + if { echo '#if __GNUC__ > 2 || (__GNUC__ == 2 && __GNUC_MINOR__ >= 97)' + echo ' yes ' + echo '#endif'; } | ${CC} -E - | $GREP yes > /dev/null; then + : + else + can_build_shared=no + fi + ;; + esac + # AIX (on Power*) has no versioning support, so currently we can not hardcode correct + # soname into executable. Probably we can add versioning support to + # collect2, so additional links can be useful in future. + if test "$aix_use_runtimelinking" = yes; then + # If using run time linking (on AIX 4.2 or later) use lib.so + # instead of lib.a to let people know that these are not + # typical AIX shared libraries. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + else + # We preserve .a as extension for shared libraries through AIX4.2 + # and later when we are not doing run time linking. + library_names_spec='${libname}${release}.a $libname.a' + soname_spec='${libname}${release}${shared_ext}$major' + fi + shlibpath_var=LIBPATH + fi + ;; + +amigaos*) + case $host_cpu in + powerpc) + # Since July 2007 AmigaOS4 officially supports .so libraries. + # When compiling the executable, add -use-dynld -Lsobjs: to the compileline. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + ;; + m68k) + library_names_spec='$libname.ixlibrary $libname.a' + # Create ${libname}_ixlibrary.a entries in /sys/libs. + finish_eval='for lib in `ls $libdir/*.ixlibrary 2>/dev/null`; do libname=`$ECHO "X$lib" | $Xsed -e '\''s%^.*/\([^/]*\)\.ixlibrary$%\1%'\''`; test $RM /sys/libs/${libname}_ixlibrary.a; $show "cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a"; cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a || exit 1; done' + ;; + esac + ;; + +beos*) + library_names_spec='${libname}${shared_ext}' + dynamic_linker="$host_os ld.so" + shlibpath_var=LIBRARY_PATH + ;; + +bsdi[45]*) + version_type=linux + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + finish_cmds='PATH="\$PATH:/sbin" ldconfig $libdir' + shlibpath_var=LD_LIBRARY_PATH + sys_lib_search_path_spec="/shlib /usr/lib /usr/X11/lib /usr/contrib/lib /lib /usr/local/lib" + sys_lib_dlsearch_path_spec="/shlib /usr/lib /usr/local/lib" + # the default ld.so.conf also contains /usr/contrib/lib and + # /usr/X11R6/lib (/usr/X11 is a link to /usr/X11R6), but let us allow + # libtool to hard-code these into programs + ;; + +cygwin* | mingw* | pw32* | cegcc*) + version_type=windows + shrext_cmds=".dll" + need_version=no + need_lib_prefix=no + + case $GCC,$host_os in + yes,cygwin* | yes,mingw* | yes,pw32* | yes,cegcc*) + library_names_spec='$libname.dll.a' + # DLL is installed to $(libdir)/../bin by postinstall_cmds + postinstall_cmds='base_file=`basename \${file}`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\${base_file}'\''i; echo \$dlname'\''`~ + dldir=$destdir/`dirname \$dlpath`~ + test -d \$dldir || mkdir -p \$dldir~ + $install_prog $dir/$dlname \$dldir/$dlname~ + chmod a+x \$dldir/$dlname~ + if test -n '\''$stripme'\'' && test -n '\''$striplib'\''; then + eval '\''$striplib \$dldir/$dlname'\'' || exit \$?; + fi' + postuninstall_cmds='dldll=`$SHELL 2>&1 -c '\''. $file; echo \$dlname'\''`~ + dlpath=$dir/\$dldll~ + $RM \$dlpath' + shlibpath_overrides_runpath=yes + + case $host_os in + cygwin*) + # Cygwin DLLs use 'cyg' prefix rather than 'lib' + soname_spec='`echo ${libname} | sed -e 's/^lib/cyg/'``echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + sys_lib_search_path_spec="/usr/lib /lib/w32api /lib /usr/local/lib" + ;; + mingw* | cegcc*) + # MinGW DLLs use traditional 'lib' prefix + soname_spec='${libname}`echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + sys_lib_search_path_spec=`$CC -print-search-dirs | $GREP "^libraries:" | $SED -e "s/^libraries://" -e "s,=/,/,g"` + if $ECHO "$sys_lib_search_path_spec" | $GREP ';[c-zC-Z]:/' >/dev/null; then + # It is most probably a Windows format PATH printed by + # mingw gcc, but we are running on Cygwin. Gcc prints its search + # path with ; separators, and with drive letters. We can handle the + # drive letters (cygwin fileutils understands them), so leave them, + # especially as we might pass files found there to a mingw objdump, + # which wouldn't understand a cygwinified path. Ahh. + sys_lib_search_path_spec=`$ECHO "$sys_lib_search_path_spec" | $SED -e 's/;/ /g'` + else + sys_lib_search_path_spec=`$ECHO "$sys_lib_search_path_spec" | $SED -e "s/$PATH_SEPARATOR/ /g"` + fi + ;; + pw32*) + # pw32 DLLs use 'pw' prefix rather than 'lib' + library_names_spec='`echo ${libname} | sed -e 's/^lib/pw/'``echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + ;; + esac + ;; + + *) + library_names_spec='${libname}`echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext} $libname.lib' + ;; + esac + dynamic_linker='Win32 ld.exe' + # FIXME: first we should search . and the directory the executable is in + shlibpath_var=PATH + ;; + +darwin* | rhapsody*) + dynamic_linker="$host_os dyld" + version_type=darwin + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${major}$shared_ext ${libname}$shared_ext' + soname_spec='${libname}${release}${major}$shared_ext' + shlibpath_overrides_runpath=yes + shlibpath_var=DYLD_LIBRARY_PATH + shrext_cmds='`test .$module = .yes && echo .so || echo .dylib`' + + sys_lib_search_path_spec="$sys_lib_search_path_spec /usr/local/lib" + sys_lib_dlsearch_path_spec='/usr/local/lib /lib /usr/lib' + ;; + +dgux*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname$shared_ext' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + ;; + +freebsd1*) + dynamic_linker=no + ;; + +freebsd* | dragonfly*) + # DragonFly does not have aout. When/if they implement a new + # versioning mechanism, adjust this. + if test -x /usr/bin/objformat; then + objformat=`/usr/bin/objformat` + else + case $host_os in + freebsd[123]*) objformat=aout ;; + *) objformat=elf ;; + esac + fi + version_type=freebsd-$objformat + case $version_type in + freebsd-elf*) + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' + need_version=no + need_lib_prefix=no + ;; + freebsd-*) + library_names_spec='${libname}${release}${shared_ext}$versuffix $libname${shared_ext}$versuffix' + need_version=yes + ;; + esac + shlibpath_var=LD_LIBRARY_PATH + case $host_os in + freebsd2*) + shlibpath_overrides_runpath=yes + ;; + freebsd3.[01]* | freebsdelf3.[01]*) + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + ;; + freebsd3.[2-9]* | freebsdelf3.[2-9]* | \ + freebsd4.[0-5] | freebsdelf4.[0-5] | freebsd4.1.1 | freebsdelf4.1.1) + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + ;; + *) # from 4.6 on, and DragonFly + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + ;; + esac + ;; + +gnu*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}${major} ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + hardcode_into_libs=yes + ;; + +hpux9* | hpux10* | hpux11*) + # Give a soname corresponding to the major version so that dld.sl refuses to + # link against other versions. + version_type=sunos + need_lib_prefix=no + need_version=no + case $host_cpu in + ia64*) + shrext_cmds='.so' + hardcode_into_libs=yes + dynamic_linker="$host_os dld.so" + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + if test "X$HPUX_IA64_MODE" = X32; then + sys_lib_search_path_spec="/usr/lib/hpux32 /usr/local/lib/hpux32 /usr/local/lib" + else + sys_lib_search_path_spec="/usr/lib/hpux64 /usr/local/lib/hpux64" + fi + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec + ;; + hppa*64*) + shrext_cmds='.sl' + hardcode_into_libs=yes + dynamic_linker="$host_os dld.sl" + shlibpath_var=LD_LIBRARY_PATH # How should we handle SHLIB_PATH + shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + sys_lib_search_path_spec="/usr/lib/pa20_64 /usr/ccs/lib/pa20_64" + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec + ;; + *) + shrext_cmds='.sl' + dynamic_linker="$host_os dld.sl" + shlibpath_var=SHLIB_PATH + shlibpath_overrides_runpath=no # +s is required to enable SHLIB_PATH + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + ;; + esac + # HP-UX runs *really* slowly unless shared libraries are mode 555. + postinstall_cmds='chmod 555 $lib' + ;; + +interix[3-9]*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + dynamic_linker='Interix 3.x ld.so.1 (PE, like ELF)' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + ;; + +irix5* | irix6* | nonstopux*) + case $host_os in + nonstopux*) version_type=nonstopux ;; + *) + if test "$lt_cv_prog_gnu_ld" = yes; then + version_type=linux + else + version_type=irix + fi ;; + esac + need_lib_prefix=no + need_version=no + soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext} $libname${shared_ext}' + case $host_os in + irix5* | nonstopux*) + libsuff= shlibsuff= + ;; + *) + case $LD in # libtool.m4 will add one of these switches to LD + *-32|*"-32 "|*-melf32bsmip|*"-melf32bsmip ") + libsuff= shlibsuff= libmagic=32-bit;; + *-n32|*"-n32 "|*-melf32bmipn32|*"-melf32bmipn32 ") + libsuff=32 shlibsuff=N32 libmagic=N32;; + *-64|*"-64 "|*-melf64bmip|*"-melf64bmip ") + libsuff=64 shlibsuff=64 libmagic=64-bit;; + *) libsuff= shlibsuff= libmagic=never-match;; + esac + ;; + esac + shlibpath_var=LD_LIBRARY${shlibsuff}_PATH + shlibpath_overrides_runpath=no + sys_lib_search_path_spec="/usr/lib${libsuff} /lib${libsuff} /usr/local/lib${libsuff}" + sys_lib_dlsearch_path_spec="/usr/lib${libsuff} /lib${libsuff}" + hardcode_into_libs=yes + ;; + +# No shared lib support for Linux oldld, aout, or coff. +linux*oldld* | linux*aout* | linux*coff*) + dynamic_linker=no + ;; + +# This must be Linux ELF. +linux* | k*bsd*-gnu | kopensolaris*-gnu) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + finish_cmds='PATH="\$PATH:/sbin" ldconfig -n $libdir' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + # Some binutils ld are patched to set DT_RUNPATH + save_LDFLAGS=$LDFLAGS + save_libdir=$libdir + eval "libdir=/foo; wl=\"$lt_prog_compiler_wl\"; \ + LDFLAGS=\"\$LDFLAGS $hardcode_libdir_flag_spec\"" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + if ($OBJDUMP -p conftest$ac_exeext) 2>/dev/null | grep "RUNPATH.*$libdir" >/dev/null; then : + shlibpath_overrides_runpath=yes +fi +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext + LDFLAGS=$save_LDFLAGS + libdir=$save_libdir + + # This implies no fast_install, which is unacceptable. + # Some rework will be needed to allow for fast_install + # before this can be enabled. + hardcode_into_libs=yes + + # Append ld.so.conf contents to the search path + if test -f /etc/ld.so.conf; then + lt_ld_extra=`awk '/^include / { system(sprintf("cd /etc; cat %s 2>/dev/null", \$2)); skip = 1; } { if (!skip) print \$0; skip = 0; }' < /etc/ld.so.conf | $SED -e 's/#.*//;/^[ ]*hwcap[ ]/d;s/[:, ]/ /g;s/=[^=]*$//;s/=[^= ]* / /g;/^$/d' | tr '\n' ' '` + sys_lib_dlsearch_path_spec="/lib /usr/lib $lt_ld_extra" + fi + + # We used to test for /lib/ld.so.1 and disable shared libraries on + # powerpc, because MkLinux only supported shared libraries with the + # GNU dynamic linker. Since this was broken with cross compilers, + # most powerpc-linux boxes support dynamic linking these days and + # people can always --disable-shared, the test was removed, and we + # assume the GNU/Linux dynamic linker is in use. + dynamic_linker='GNU/Linux ld.so' + ;; + +netbsdelf*-gnu) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + dynamic_linker='NetBSD ld.elf_so' + ;; + +netbsd*) + version_type=sunos + need_lib_prefix=no + need_version=no + if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' + dynamic_linker='NetBSD (a.out) ld.so' + else + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + dynamic_linker='NetBSD ld.elf_so' + fi + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + ;; + +newsos6) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + ;; + +*nto* | *qnx*) + version_type=qnx + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + dynamic_linker='ldqnx.so' + ;; + +openbsd*) + version_type=sunos + sys_lib_dlsearch_path_spec="/usr/lib" + need_lib_prefix=no + # Some older versions of OpenBSD (3.3 at least) *do* need versioned libs. + case $host_os in + openbsd3.3 | openbsd3.3.*) need_version=yes ;; + *) need_version=no ;; + esac + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' + shlibpath_var=LD_LIBRARY_PATH + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + case $host_os in + openbsd2.[89] | openbsd2.[89].*) + shlibpath_overrides_runpath=no + ;; + *) + shlibpath_overrides_runpath=yes + ;; + esac + else + shlibpath_overrides_runpath=yes + fi + ;; + +os2*) + libname_spec='$name' + shrext_cmds=".dll" + need_lib_prefix=no + library_names_spec='$libname${shared_ext} $libname.a' + dynamic_linker='OS/2 ld.exe' + shlibpath_var=LIBPATH + ;; + +osf3* | osf4* | osf5*) + version_type=osf + need_lib_prefix=no + need_version=no + soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + sys_lib_search_path_spec="/usr/shlib /usr/ccs/lib /usr/lib/cmplrs/cc /usr/lib /usr/local/lib /var/shlib" + sys_lib_dlsearch_path_spec="$sys_lib_search_path_spec" + ;; + +rdos*) + dynamic_linker=no + ;; + +solaris*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + # ldd complains unless libraries are executable + postinstall_cmds='chmod +x $lib' + ;; + +sunos4*) + version_type=sunos + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + finish_cmds='PATH="\$PATH:/usr/etc" ldconfig $libdir' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + if test "$with_gnu_ld" = yes; then + need_lib_prefix=no + fi + need_version=yes + ;; + +sysv4 | sysv4.3*) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + case $host_vendor in + sni) + shlibpath_overrides_runpath=no + need_lib_prefix=no + runpath_var=LD_RUN_PATH + ;; + siemens) + need_lib_prefix=no + ;; + motorola) + need_lib_prefix=no + need_version=no + shlibpath_overrides_runpath=no + sys_lib_search_path_spec='/lib /usr/lib /usr/ccs/lib' + ;; + esac + ;; + +sysv4*MP*) + if test -d /usr/nec ;then + version_type=linux + library_names_spec='$libname${shared_ext}.$versuffix $libname${shared_ext}.$major $libname${shared_ext}' + soname_spec='$libname${shared_ext}.$major' + shlibpath_var=LD_LIBRARY_PATH + fi + ;; + +sysv5* | sco3.2v5* | sco5v6* | unixware* | OpenUNIX* | sysv4*uw2*) + version_type=freebsd-elf + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + if test "$with_gnu_ld" = yes; then + sys_lib_search_path_spec='/usr/local/lib /usr/gnu/lib /usr/ccs/lib /usr/lib /lib' + else + sys_lib_search_path_spec='/usr/ccs/lib /usr/lib' + case $host_os in + sco3.2v5*) + sys_lib_search_path_spec="$sys_lib_search_path_spec /lib" + ;; + esac + fi + sys_lib_dlsearch_path_spec='/usr/lib' + ;; + +tpf*) + # TPF is a cross-target only. Preferred cross-host = GNU/Linux. + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + ;; + +uts4*) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + ;; + +*) + dynamic_linker=no + ;; +esac +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $dynamic_linker" >&5 +$as_echo "$dynamic_linker" >&6; } +test "$dynamic_linker" = no && can_build_shared=no + +variables_saved_for_relink="PATH $shlibpath_var $runpath_var" +if test "$GCC" = yes; then + variables_saved_for_relink="$variables_saved_for_relink GCC_EXEC_PREFIX COMPILER_PATH LIBRARY_PATH" +fi + +if test "${lt_cv_sys_lib_search_path_spec+set}" = set; then + sys_lib_search_path_spec="$lt_cv_sys_lib_search_path_spec" +fi +if test "${lt_cv_sys_lib_dlsearch_path_spec+set}" = set; then + sys_lib_dlsearch_path_spec="$lt_cv_sys_lib_dlsearch_path_spec" +fi + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking how to hardcode library paths into programs" >&5 +$as_echo_n "checking how to hardcode library paths into programs... " >&6; } +hardcode_action= +if test -n "$hardcode_libdir_flag_spec" || + test -n "$runpath_var" || + test "X$hardcode_automatic" = "Xyes" ; then + + # We can hardcode non-existent directories. + if test "$hardcode_direct" != no && + # If the only mechanism to avoid hardcoding is shlibpath_var, we + # have to relink, otherwise we might link with an installed library + # when we should be linking with a yet-to-be-installed one + ## test "$_LT_TAGVAR(hardcode_shlibpath_var, )" != no && + test "$hardcode_minus_L" != no; then + # Linking always hardcodes the temporary library directory. + hardcode_action=relink + else + # We can link without hardcoding, and we can hardcode nonexisting dirs. + hardcode_action=immediate + fi +else + # We cannot hardcode anything, or else we can only hardcode existing + # directories. + hardcode_action=unsupported +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $hardcode_action" >&5 +$as_echo "$hardcode_action" >&6; } + +if test "$hardcode_action" = relink || + test "$inherit_rpath" = yes; then + # Fast installation is not supported + enable_fast_install=no +elif test "$shlibpath_overrides_runpath" = yes || + test "$enable_shared" = no; then + # Fast installation is not necessary + enable_fast_install=needless +fi + + + + + + + if test "x$enable_dlopen" != xyes; then + enable_dlopen=unknown + enable_dlopen_self=unknown + enable_dlopen_self_static=unknown +else + lt_cv_dlopen=no + lt_cv_dlopen_libs= + + case $host_os in + beos*) + lt_cv_dlopen="load_add_on" + lt_cv_dlopen_libs= + lt_cv_dlopen_self=yes + ;; + + mingw* | pw32* | cegcc*) + lt_cv_dlopen="LoadLibrary" + lt_cv_dlopen_libs= + ;; + + cygwin*) + lt_cv_dlopen="dlopen" + lt_cv_dlopen_libs= + ;; + + darwin*) + # if libdl is installed we need to link against it + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for dlopen in -ldl" >&5 +$as_echo_n "checking for dlopen in -ldl... " >&6; } +if test "${ac_cv_lib_dl_dlopen+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_check_lib_save_LIBS=$LIBS +LIBS="-ldl $LIBS" +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +/* Override any GCC internal prototype to avoid an error. + Use char because int might match the return type of a GCC + builtin and then its argument prototype would still apply. */ +#ifdef __cplusplus +extern "C" +#endif +char dlopen (); +int +main () +{ +return dlopen (); + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + ac_cv_lib_dl_dlopen=yes +else + ac_cv_lib_dl_dlopen=no +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +LIBS=$ac_check_lib_save_LIBS +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_dl_dlopen" >&5 +$as_echo "$ac_cv_lib_dl_dlopen" >&6; } +if test "x$ac_cv_lib_dl_dlopen" = x""yes; then : + lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-ldl" +else + + lt_cv_dlopen="dyld" + lt_cv_dlopen_libs= + lt_cv_dlopen_self=yes + +fi + + ;; + + *) + ac_fn_c_check_func "$LINENO" "shl_load" "ac_cv_func_shl_load" +if test "x$ac_cv_func_shl_load" = x""yes; then : + lt_cv_dlopen="shl_load" +else + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for shl_load in -ldld" >&5 +$as_echo_n "checking for shl_load in -ldld... " >&6; } +if test "${ac_cv_lib_dld_shl_load+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_check_lib_save_LIBS=$LIBS +LIBS="-ldld $LIBS" +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +/* Override any GCC internal prototype to avoid an error. + Use char because int might match the return type of a GCC + builtin and then its argument prototype would still apply. */ +#ifdef __cplusplus +extern "C" +#endif +char shl_load (); +int +main () +{ +return shl_load (); + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + ac_cv_lib_dld_shl_load=yes +else + ac_cv_lib_dld_shl_load=no +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +LIBS=$ac_check_lib_save_LIBS +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_dld_shl_load" >&5 +$as_echo "$ac_cv_lib_dld_shl_load" >&6; } +if test "x$ac_cv_lib_dld_shl_load" = x""yes; then : + lt_cv_dlopen="shl_load" lt_cv_dlopen_libs="-ldld" +else + ac_fn_c_check_func "$LINENO" "dlopen" "ac_cv_func_dlopen" +if test "x$ac_cv_func_dlopen" = x""yes; then : + lt_cv_dlopen="dlopen" +else + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for dlopen in -ldl" >&5 +$as_echo_n "checking for dlopen in -ldl... " >&6; } +if test "${ac_cv_lib_dl_dlopen+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_check_lib_save_LIBS=$LIBS +LIBS="-ldl $LIBS" +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +/* Override any GCC internal prototype to avoid an error. + Use char because int might match the return type of a GCC + builtin and then its argument prototype would still apply. */ +#ifdef __cplusplus +extern "C" +#endif +char dlopen (); +int +main () +{ +return dlopen (); + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + ac_cv_lib_dl_dlopen=yes +else + ac_cv_lib_dl_dlopen=no +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +LIBS=$ac_check_lib_save_LIBS +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_dl_dlopen" >&5 +$as_echo "$ac_cv_lib_dl_dlopen" >&6; } +if test "x$ac_cv_lib_dl_dlopen" = x""yes; then : + lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-ldl" +else + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for dlopen in -lsvld" >&5 +$as_echo_n "checking for dlopen in -lsvld... " >&6; } +if test "${ac_cv_lib_svld_dlopen+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_check_lib_save_LIBS=$LIBS +LIBS="-lsvld $LIBS" +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +/* Override any GCC internal prototype to avoid an error. + Use char because int might match the return type of a GCC + builtin and then its argument prototype would still apply. */ +#ifdef __cplusplus +extern "C" +#endif +char dlopen (); +int +main () +{ +return dlopen (); + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + ac_cv_lib_svld_dlopen=yes +else + ac_cv_lib_svld_dlopen=no +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +LIBS=$ac_check_lib_save_LIBS +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_svld_dlopen" >&5 +$as_echo "$ac_cv_lib_svld_dlopen" >&6; } +if test "x$ac_cv_lib_svld_dlopen" = x""yes; then : + lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-lsvld" +else + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for dld_link in -ldld" >&5 +$as_echo_n "checking for dld_link in -ldld... " >&6; } +if test "${ac_cv_lib_dld_dld_link+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_check_lib_save_LIBS=$LIBS +LIBS="-ldld $LIBS" +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +/* Override any GCC internal prototype to avoid an error. + Use char because int might match the return type of a GCC + builtin and then its argument prototype would still apply. */ +#ifdef __cplusplus +extern "C" +#endif +char dld_link (); +int +main () +{ +return dld_link (); + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + ac_cv_lib_dld_dld_link=yes +else + ac_cv_lib_dld_dld_link=no +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +LIBS=$ac_check_lib_save_LIBS +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_dld_dld_link" >&5 +$as_echo "$ac_cv_lib_dld_dld_link" >&6; } +if test "x$ac_cv_lib_dld_dld_link" = x""yes; then : + lt_cv_dlopen="dld_link" lt_cv_dlopen_libs="-ldld" +fi + + +fi + + +fi + + +fi + + +fi + + +fi + + ;; + esac + + if test "x$lt_cv_dlopen" != xno; then + enable_dlopen=yes + else + enable_dlopen=no + fi + + case $lt_cv_dlopen in + dlopen) + save_CPPFLAGS="$CPPFLAGS" + test "x$ac_cv_header_dlfcn_h" = xyes && CPPFLAGS="$CPPFLAGS -DHAVE_DLFCN_H" + + save_LDFLAGS="$LDFLAGS" + wl=$lt_prog_compiler_wl eval LDFLAGS=\"\$LDFLAGS $export_dynamic_flag_spec\" + + save_LIBS="$LIBS" + LIBS="$lt_cv_dlopen_libs $LIBS" + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether a program can dlopen itself" >&5 +$as_echo_n "checking whether a program can dlopen itself... " >&6; } +if test "${lt_cv_dlopen_self+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test "$cross_compiling" = yes; then : + lt_cv_dlopen_self=cross +else + lt_dlunknown=0; lt_dlno_uscore=1; lt_dlneed_uscore=2 + lt_status=$lt_dlunknown + cat > conftest.$ac_ext <<_LT_EOF +#line 10517 "configure" +#include "confdefs.h" + +#if HAVE_DLFCN_H +#include +#endif + +#include + +#ifdef RTLD_GLOBAL +# define LT_DLGLOBAL RTLD_GLOBAL +#else +# ifdef DL_GLOBAL +# define LT_DLGLOBAL DL_GLOBAL +# else +# define LT_DLGLOBAL 0 +# endif +#endif + +/* We may have to define LT_DLLAZY_OR_NOW in the command line if we + find out it does not work in some platform. */ +#ifndef LT_DLLAZY_OR_NOW +# ifdef RTLD_LAZY +# define LT_DLLAZY_OR_NOW RTLD_LAZY +# else +# ifdef DL_LAZY +# define LT_DLLAZY_OR_NOW DL_LAZY +# else +# ifdef RTLD_NOW +# define LT_DLLAZY_OR_NOW RTLD_NOW +# else +# ifdef DL_NOW +# define LT_DLLAZY_OR_NOW DL_NOW +# else +# define LT_DLLAZY_OR_NOW 0 +# endif +# endif +# endif +# endif +#endif + +void fnord() { int i=42;} +int main () +{ + void *self = dlopen (0, LT_DLGLOBAL|LT_DLLAZY_OR_NOW); + int status = $lt_dlunknown; + + if (self) + { + if (dlsym (self,"fnord")) status = $lt_dlno_uscore; + else if (dlsym( self,"_fnord")) status = $lt_dlneed_uscore; + /* dlclose (self); */ + } + else + puts (dlerror ()); + + return status; +} +_LT_EOF + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_link\""; } >&5 + (eval $ac_link) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && test -s conftest${ac_exeext} 2>/dev/null; then + (./conftest; exit; ) >&5 2>/dev/null + lt_status=$? + case x$lt_status in + x$lt_dlno_uscore) lt_cv_dlopen_self=yes ;; + x$lt_dlneed_uscore) lt_cv_dlopen_self=yes ;; + x$lt_dlunknown|x*) lt_cv_dlopen_self=no ;; + esac + else : + # compilation failed + lt_cv_dlopen_self=no + fi +fi +rm -fr conftest* + + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_dlopen_self" >&5 +$as_echo "$lt_cv_dlopen_self" >&6; } + + if test "x$lt_cv_dlopen_self" = xyes; then + wl=$lt_prog_compiler_wl eval LDFLAGS=\"\$LDFLAGS $lt_prog_compiler_static\" + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether a statically linked program can dlopen itself" >&5 +$as_echo_n "checking whether a statically linked program can dlopen itself... " >&6; } +if test "${lt_cv_dlopen_self_static+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test "$cross_compiling" = yes; then : + lt_cv_dlopen_self_static=cross +else + lt_dlunknown=0; lt_dlno_uscore=1; lt_dlneed_uscore=2 + lt_status=$lt_dlunknown + cat > conftest.$ac_ext <<_LT_EOF +#line 10613 "configure" +#include "confdefs.h" + +#if HAVE_DLFCN_H +#include +#endif + +#include + +#ifdef RTLD_GLOBAL +# define LT_DLGLOBAL RTLD_GLOBAL +#else +# ifdef DL_GLOBAL +# define LT_DLGLOBAL DL_GLOBAL +# else +# define LT_DLGLOBAL 0 +# endif +#endif + +/* We may have to define LT_DLLAZY_OR_NOW in the command line if we + find out it does not work in some platform. */ +#ifndef LT_DLLAZY_OR_NOW +# ifdef RTLD_LAZY +# define LT_DLLAZY_OR_NOW RTLD_LAZY +# else +# ifdef DL_LAZY +# define LT_DLLAZY_OR_NOW DL_LAZY +# else +# ifdef RTLD_NOW +# define LT_DLLAZY_OR_NOW RTLD_NOW +# else +# ifdef DL_NOW +# define LT_DLLAZY_OR_NOW DL_NOW +# else +# define LT_DLLAZY_OR_NOW 0 +# endif +# endif +# endif +# endif +#endif + +void fnord() { int i=42;} +int main () +{ + void *self = dlopen (0, LT_DLGLOBAL|LT_DLLAZY_OR_NOW); + int status = $lt_dlunknown; + + if (self) + { + if (dlsym (self,"fnord")) status = $lt_dlno_uscore; + else if (dlsym( self,"_fnord")) status = $lt_dlneed_uscore; + /* dlclose (self); */ + } + else + puts (dlerror ()); + + return status; +} +_LT_EOF + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_link\""; } >&5 + (eval $ac_link) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && test -s conftest${ac_exeext} 2>/dev/null; then + (./conftest; exit; ) >&5 2>/dev/null + lt_status=$? + case x$lt_status in + x$lt_dlno_uscore) lt_cv_dlopen_self_static=yes ;; + x$lt_dlneed_uscore) lt_cv_dlopen_self_static=yes ;; + x$lt_dlunknown|x*) lt_cv_dlopen_self_static=no ;; + esac + else : + # compilation failed + lt_cv_dlopen_self_static=no + fi +fi +rm -fr conftest* + + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_dlopen_self_static" >&5 +$as_echo "$lt_cv_dlopen_self_static" >&6; } + fi + + CPPFLAGS="$save_CPPFLAGS" + LDFLAGS="$save_LDFLAGS" + LIBS="$save_LIBS" + ;; + esac + + case $lt_cv_dlopen_self in + yes|no) enable_dlopen_self=$lt_cv_dlopen_self ;; + *) enable_dlopen_self=unknown ;; + esac + + case $lt_cv_dlopen_self_static in + yes|no) enable_dlopen_self_static=$lt_cv_dlopen_self_static ;; + *) enable_dlopen_self_static=unknown ;; + esac +fi + + + + + + + + + + + + + + + + + +striplib= +old_striplib= +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether stripping libraries is possible" >&5 +$as_echo_n "checking whether stripping libraries is possible... " >&6; } +if test -n "$STRIP" && $STRIP -V 2>&1 | $GREP "GNU strip" >/dev/null; then + test -z "$old_striplib" && old_striplib="$STRIP --strip-debug" + test -z "$striplib" && striplib="$STRIP --strip-unneeded" + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } +else +# FIXME - insert some real tests, host_os isn't really good enough + case $host_os in + darwin*) + if test -n "$STRIP" ; then + striplib="$STRIP -x" + old_striplib="$STRIP -S" + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } + else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + fi + ;; + *) + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + ;; + esac +fi + + + + + + + + + + + + + # Report which library types will actually be built + { $as_echo "$as_me:${as_lineno-$LINENO}: checking if libtool supports shared libraries" >&5 +$as_echo_n "checking if libtool supports shared libraries... " >&6; } + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $can_build_shared" >&5 +$as_echo "$can_build_shared" >&6; } + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether to build shared libraries" >&5 +$as_echo_n "checking whether to build shared libraries... " >&6; } + test "$can_build_shared" = "no" && enable_shared=no + + # On AIX, shared libraries and static libraries use the same namespace, and + # are all built from PIC. + case $host_os in + aix3*) + test "$enable_shared" = yes && enable_static=no + if test -n "$RANLIB"; then + archive_cmds="$archive_cmds~\$RANLIB \$lib" + postinstall_cmds='$RANLIB $lib' + fi + ;; + + aix[4-9]*) + if test "$host_cpu" != ia64 && test "$aix_use_runtimelinking" = no ; then + test "$enable_shared" = yes && enable_static=no + fi + ;; + esac + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $enable_shared" >&5 +$as_echo "$enable_shared" >&6; } + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether to build static libraries" >&5 +$as_echo_n "checking whether to build static libraries... " >&6; } + # Make sure either enable_shared or enable_static is yes. + test "$enable_shared" = yes || enable_static=yes + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $enable_static" >&5 +$as_echo "$enable_static" >&6; } + + + + +fi +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + +CC="$lt_save_CC" + + + + + + + + + + + + + + ac_config_commands="$ac_config_commands libtool" + + + + +# Only expand once: + + + +#--------------------------------------------------------------------------- +# Set misc options + +# By default, do not build with -Wall, unless the user asks for it +# Check whether --enable-wall was given. +if test "${enable_wall+set}" = set; then : + enableval=$enable_wall; case "$enableval" in #( + yes) : + wall_CFLAGS=-Wall ;; #( + *) : + wall_CFLAGS="" ;; #( + *) : + ;; +esac +fi + +wall_CFLAGS=${wall_CFLAGS} + + +# By default, do not build with -Werror, unless the user asks for it +# Check whether --enable-werror was given. +if test "${enable_werror+set}" = set; then : + enableval=$enable_werror; case "$enableval" in #( + yes) : + werror_CFLAGS=-Werror ;; #( + *) : + werror_CFLAGS="" ;; #( + *) : + ;; +esac +fi + +werror_CFLAGS=${werror_CFLAGS} + + +# Although there is a default (="linux") in the code, we do provide +# a default here, to get a consistent autostuff behavior +# Check whether --enable-root-menu-prompt was given. +if test "${enable_root_menu_prompt+set}" = set; then : + enableval=$enable_root_menu_prompt; case "$enableval" in #( + yes) : + root_menu=Configuration ;; #( + no) : + root_menu= ;; #( + *) : + # Escape the $ signs, otherwise they would get munged by make + # Also, append a space at the end, to separate the package + # name from the literal 'Configuration' + root_menu="$( echo "$enableval" |sed -r -e 's/\$/\\$$/g;' )" ;; +esac +fi + +root_menu=${root_menu=Configuration} + + +# Check whether --enable-config-prefix was given. +if test "${enable_config_prefix+set}" = set; then : + enableval=$enable_config_prefix; case "$enableval" in #( + *" "*) : + as_fn_error $? "config prefix can not contain spaces: '$enableval'" "$LINENO" 5 ;; #( + yes) : + config_prefix=CONFIG_ ;; #( + no) : + config_prefix= ;; #( + *) : + config_prefix=$enableval ;; +esac +fi + +config_prefix=${config_prefix-CONFIG_} + + +# Check whether --enable-utils was given. +if test "${enable_utils+set}" = set; then : + enableval=$enable_utils; +fi + +enable_utils=${enable_utils:-yes} + + +# Check whether --enable-L10n was given. +if test "${enable_L10n+set}" = set; then : + enableval=$enable_L10n; +fi + +enable_L10n=${enable_L10n:-yes} + + +#---------------------------------------- +# Options to selectively enable/disable frontends +# All are selected by default +# Check whether --enable-conf was given. +if test "${enable_conf+set}" = set; then : + enableval=$enable_conf; +fi + +enable_conf=${enable_conf:-auto} + +# Check whether --enable-mconf was given. +if test "${enable_mconf+set}" = set; then : + enableval=$enable_mconf; +fi + +enable_mconf=${enable_mconf:-auto} + +# Check whether --enable-nconf was given. +if test "${enable_nconf+set}" = set; then : + enableval=$enable_nconf; +fi + +enable_nconf=${enable_nconf:-auto} + +# Check whether --enable-gconf was given. +if test "${enable_gconf+set}" = set; then : + enableval=$enable_gconf; +fi + +enable_gconf=${enable_gconf:-auto} + +# Check whether --enable-qconf was given. +if test "${enable_qconf+set}" = set; then : + enableval=$enable_qconf; +fi + +enable_qconf=${enable_qconf:-auto} + + +# Check whether --enable-frontends was given. +if test "${enable_frontends+set}" = set; then : + enableval=$enable_frontends; for f in conf mconf nconf gconf qconf; do + case "$enableval" in #( + yes) : + eval enable_$f=yes ;; #( + "$f") : + eval enable_$f=yes ;; #( + "$f",*) : + eval enable_$f=yes ;; #( + *,"$f") : + eval enable_$f=yes ;; #( + *,"$f",*) : + eval enable_$f=yes ;; #( + *) : + eval enable_$f=no ;; +esac + done +fi + + + +#---------------------------------------- +# What extra CFLAGS we will be using +kf_CFLAGS="$wall_CFLAGS $werror_CFLAGS" + + +#---------------------------------------- +# Dependencies that will be needed, depending on the frontends +case "$enable_mconf":"$enable_nconf" in #( + *yes*) : + need_curses=yes ;; #( + *auto*) : + need_curses=auto ;; #( + *) : + need_curses=no ;; +esac +need_panel_menu="$enable_nconf" +case "$enable_gconf":"$enable_qconf" in #( + *yes*) : + need_pkgconfig=yes ;; #( + *auto*) : + need_pkgconfig=yes ;; #( + *) : + need_pkgconfig=no ;; +esac +need_gtk="$enable_gconf" +need_qt="$enable_qconf" + +#--------------------------------------------------------------------------- +# Now check we have the required stuff + +#---------------------------------------- +# Some program checks +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu +if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}gcc", so it can be a program name with args. +set dummy ${ac_tool_prefix}gcc; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$CC"; then + ac_cv_prog_CC="$CC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_CC="${ac_tool_prefix}gcc" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +CC=$ac_cv_prog_CC +if test -n "$CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $CC" >&5 +$as_echo "$CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_prog_CC"; then + ac_ct_CC=$CC + # Extract the first word of "gcc", so it can be a program name with args. +set dummy gcc; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_CC"; then + ac_cv_prog_ac_ct_CC="$ac_ct_CC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_CC="gcc" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_CC=$ac_cv_prog_ac_ct_CC +if test -n "$ac_ct_CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_CC" >&5 +$as_echo "$ac_ct_CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_ct_CC" = x; then + CC="" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + CC=$ac_ct_CC + fi +else + CC="$ac_cv_prog_CC" +fi + +if test -z "$CC"; then + if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}cc", so it can be a program name with args. +set dummy ${ac_tool_prefix}cc; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$CC"; then + ac_cv_prog_CC="$CC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_CC="${ac_tool_prefix}cc" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +CC=$ac_cv_prog_CC +if test -n "$CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $CC" >&5 +$as_echo "$CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + fi +fi +if test -z "$CC"; then + # Extract the first word of "cc", so it can be a program name with args. +set dummy cc; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$CC"; then + ac_cv_prog_CC="$CC" # Let the user override the test. +else + ac_prog_rejected=no +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + if test "$as_dir/$ac_word$ac_exec_ext" = "/usr/ucb/cc"; then + ac_prog_rejected=yes + continue + fi + ac_cv_prog_CC="cc" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +if test $ac_prog_rejected = yes; then + # We found a bogon in the path, so make sure we never use it. + set dummy $ac_cv_prog_CC + shift + if test $# != 0; then + # We chose a different compiler from the bogus one. + # However, it has the same basename, so the bogon will be chosen + # first if we set CC to just the basename; use the full file name. + shift + ac_cv_prog_CC="$as_dir/$ac_word${1+' '}$@" + fi +fi +fi +fi +CC=$ac_cv_prog_CC +if test -n "$CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $CC" >&5 +$as_echo "$CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$CC"; then + if test -n "$ac_tool_prefix"; then + for ac_prog in cl.exe + do + # Extract the first word of "$ac_tool_prefix$ac_prog", so it can be a program name with args. +set dummy $ac_tool_prefix$ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$CC"; then + ac_cv_prog_CC="$CC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_CC="$ac_tool_prefix$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +CC=$ac_cv_prog_CC +if test -n "$CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $CC" >&5 +$as_echo "$CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$CC" && break + done +fi +if test -z "$CC"; then + ac_ct_CC=$CC + for ac_prog in cl.exe +do + # Extract the first word of "$ac_prog", so it can be a program name with args. +set dummy $ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_CC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_CC"; then + ac_cv_prog_ac_ct_CC="$ac_ct_CC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_CC="$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_CC=$ac_cv_prog_ac_ct_CC +if test -n "$ac_ct_CC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_CC" >&5 +$as_echo "$ac_ct_CC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$ac_ct_CC" && break +done + + if test "x$ac_ct_CC" = x; then + CC="" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + CC=$ac_ct_CC + fi +fi + +fi + + +test -z "$CC" && { { $as_echo "$as_me:${as_lineno-$LINENO}: error: in \`$ac_pwd':" >&5 +$as_echo "$as_me: error: in \`$ac_pwd':" >&2;} +as_fn_error $? "no acceptable C compiler found in \$PATH +See \`config.log' for more details" "$LINENO" 5 ; } + +# Provide some information about the compiler. +$as_echo "$as_me:${as_lineno-$LINENO}: checking for C compiler version" >&5 +set X $ac_compile +ac_compiler=$2 +for ac_option in --version -v -V -qversion; do + { { ac_try="$ac_compiler $ac_option >&5" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_compiler $ac_option >&5") 2>conftest.err + ac_status=$? + if test -s conftest.err; then + sed '10a\ +... rest of stderr output deleted ... + 10q' conftest.err >conftest.er1 + cat conftest.er1 >&5 + fi + rm -f conftest.er1 conftest.err + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } +done + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether we are using the GNU C compiler" >&5 +$as_echo_n "checking whether we are using the GNU C compiler... " >&6; } +if test "${ac_cv_c_compiler_gnu+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ +#ifndef __GNUC__ + choke me +#endif + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_compiler_gnu=yes +else + ac_compiler_gnu=no +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +ac_cv_c_compiler_gnu=$ac_compiler_gnu + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_c_compiler_gnu" >&5 +$as_echo "$ac_cv_c_compiler_gnu" >&6; } +if test $ac_compiler_gnu = yes; then + GCC=yes +else + GCC= +fi +ac_test_CFLAGS=${CFLAGS+set} +ac_save_CFLAGS=$CFLAGS +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether $CC accepts -g" >&5 +$as_echo_n "checking whether $CC accepts -g... " >&6; } +if test "${ac_cv_prog_cc_g+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_save_c_werror_flag=$ac_c_werror_flag + ac_c_werror_flag=yes + ac_cv_prog_cc_g=no + CFLAGS="-g" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_cv_prog_cc_g=yes +else + CFLAGS="" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + +else + ac_c_werror_flag=$ac_save_c_werror_flag + CFLAGS="-g" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_cv_prog_cc_g=yes +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext + ac_c_werror_flag=$ac_save_c_werror_flag +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_prog_cc_g" >&5 +$as_echo "$ac_cv_prog_cc_g" >&6; } +if test "$ac_test_CFLAGS" = set; then + CFLAGS=$ac_save_CFLAGS +elif test $ac_cv_prog_cc_g = yes; then + if test "$GCC" = yes; then + CFLAGS="-g -O2" + else + CFLAGS="-g" + fi +else + if test "$GCC" = yes; then + CFLAGS="-O2" + else + CFLAGS= + fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $CC option to accept ISO C89" >&5 +$as_echo_n "checking for $CC option to accept ISO C89... " >&6; } +if test "${ac_cv_prog_cc_c89+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_cv_prog_cc_c89=no +ac_save_CC=$CC +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +#include +#include +#include +/* Most of the following tests are stolen from RCS 5.7's src/conf.sh. */ +struct buf { int x; }; +FILE * (*rcsopen) (struct buf *, struct stat *, int); +static char *e (p, i) + char **p; + int i; +{ + return p[i]; +} +static char *f (char * (*g) (char **, int), char **p, ...) +{ + char *s; + va_list v; + va_start (v,p); + s = g (p, va_arg (v,int)); + va_end (v); + return s; +} + +/* OSF 4.0 Compaq cc is some sort of almost-ANSI by default. It has + function prototypes and stuff, but not '\xHH' hex character constants. + These don't provoke an error unfortunately, instead are silently treated + as 'x'. The following induces an error, until -std is added to get + proper ANSI mode. Curiously '\x00'!='x' always comes out true, for an + array size at least. It's necessary to write '\x00'==0 to get something + that's true only with -std. */ +int osf4_cc_array ['\x00' == 0 ? 1 : -1]; + +/* IBM C 6 for AIX is almost-ANSI by default, but it replaces macro parameters + inside strings and character constants. */ +#define FOO(x) 'x' +int xlc6_cc_array[FOO(a) == 'x' ? 1 : -1]; + +int test (int i, double x); +struct s1 {int (*f) (int a);}; +struct s2 {int (*f) (double a);}; +int pairnames (int, char **, FILE *(*)(struct buf *, struct stat *, int), int, int); +int argc; +char **argv; +int +main () +{ +return f (e, argv, 0) != argv[0] || f (e, argv, 1) != argv[1]; + ; + return 0; +} +_ACEOF +for ac_arg in '' -qlanglvl=extc89 -qlanglvl=ansi -std \ + -Ae "-Aa -D_HPUX_SOURCE" "-Xc -D__EXTENSIONS__" +do + CC="$ac_save_CC $ac_arg" + if ac_fn_c_try_compile "$LINENO"; then : + ac_cv_prog_cc_c89=$ac_arg +fi +rm -f core conftest.err conftest.$ac_objext + test "x$ac_cv_prog_cc_c89" != "xno" && break +done +rm -f conftest.$ac_ext +CC=$ac_save_CC + +fi +# AC_CACHE_VAL +case "x$ac_cv_prog_cc_c89" in + x) + { $as_echo "$as_me:${as_lineno-$LINENO}: result: none needed" >&5 +$as_echo "none needed" >&6; } ;; + xno) + { $as_echo "$as_me:${as_lineno-$LINENO}: result: unsupported" >&5 +$as_echo "unsupported" >&6; } ;; + *) + CC="$CC $ac_cv_prog_cc_c89" + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_prog_cc_c89" >&5 +$as_echo "$ac_cv_prog_cc_c89" >&6; } ;; +esac +if test "x$ac_cv_prog_cc_c89" != xno; then : + +fi + +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + +depcc="$CC" am_compiler_list= + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking dependency style of $depcc" >&5 +$as_echo_n "checking dependency style of $depcc... " >&6; } +if test "${am_cv_CC_dependencies_compiler_type+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -z "$AMDEP_TRUE" && test -f "$am_depcomp"; then + # We make a subdir and do the tests there. Otherwise we can end up + # making bogus files that we don't know about and never remove. For + # instance it was reported that on HP-UX the gcc test will end up + # making a dummy file named `D' -- because `-MD' means `put the output + # in D'. + mkdir conftest.dir + # Copy depcomp to subdir because otherwise we won't find it if we're + # using a relative directory. + cp "$am_depcomp" conftest.dir + cd conftest.dir + # We will build objects and dependencies in a subdirectory because + # it helps to detect inapplicable dependency modes. For instance + # both Tru64's cc and ICC support -MD to output dependencies as a + # side effect of compilation, but ICC will put the dependencies in + # the current directory while Tru64 will put them in the object + # directory. + mkdir sub + + am_cv_CC_dependencies_compiler_type=none + if test "$am_compiler_list" = ""; then + am_compiler_list=`sed -n 's/^#*\([a-zA-Z0-9]*\))$/\1/p' < ./depcomp` + fi + am__universal=false + case " $depcc " in #( + *\ -arch\ *\ -arch\ *) am__universal=true ;; + esac + + for depmode in $am_compiler_list; do + # Setup a source with many dependencies, because some compilers + # like to wrap large dependency lists on column 80 (with \), and + # we should not choose a depcomp mode which is confused by this. + # + # We need to recreate these files for each test, as the compiler may + # overwrite some of them when testing with obscure command lines. + # This happens at least with the AIX C compiler. + : > sub/conftest.c + for i in 1 2 3 4 5 6; do + echo '#include "conftst'$i'.h"' >> sub/conftest.c + # Using `: > sub/conftst$i.h' creates only sub/conftst1.h with + # Solaris 8's {/usr,}/bin/sh. + touch sub/conftst$i.h + done + echo "${am__include} ${am__quote}sub/conftest.Po${am__quote}" > confmf + + # We check with `-c' and `-o' for the sake of the "dashmstdout" + # mode. It turns out that the SunPro C++ compiler does not properly + # handle `-M -o', and we need to detect this. Also, some Intel + # versions had trouble with output in subdirs + am__obj=sub/conftest.${OBJEXT-o} + am__minus_obj="-o $am__obj" + case $depmode in + gcc) + # This depmode causes a compiler race in universal mode. + test "$am__universal" = false || continue + ;; + nosideeffect) + # after this tag, mechanisms are not by side-effect, so they'll + # only be used when explicitly requested + if test "x$enable_dependency_tracking" = xyes; then + continue + else + break + fi + ;; + msvisualcpp | msvcmsys) + # This compiler won't grok `-c -o', but also, the minuso test has + # not run yet. These depmodes are late enough in the game, and + # so weak that their functioning should not be impacted. + am__obj=conftest.${OBJEXT-o} + am__minus_obj= + ;; + none) break ;; + esac + if depmode=$depmode \ + source=sub/conftest.c object=$am__obj \ + depfile=sub/conftest.Po tmpdepfile=sub/conftest.TPo \ + $SHELL ./depcomp $depcc -c $am__minus_obj sub/conftest.c \ + >/dev/null 2>conftest.err && + grep sub/conftst1.h sub/conftest.Po > /dev/null 2>&1 && + grep sub/conftst6.h sub/conftest.Po > /dev/null 2>&1 && + grep $am__obj sub/conftest.Po > /dev/null 2>&1 && + ${MAKE-make} -s -f confmf > /dev/null 2>&1; then + # icc doesn't choke on unknown options, it will just issue warnings + # or remarks (even with -Werror). So we grep stderr for any message + # that says an option was ignored or not supported. + # When given -MP, icc 7.0 and 7.1 complain thusly: + # icc: Command line warning: ignoring option '-M'; no argument required + # The diagnosis changed in icc 8.0: + # icc: Command line remark: option '-MP' not supported + if (grep 'ignoring option' conftest.err || + grep 'not supported' conftest.err) >/dev/null 2>&1; then :; else + am_cv_CC_dependencies_compiler_type=$depmode + break + fi + fi + done + + cd .. + rm -rf conftest.dir +else + am_cv_CC_dependencies_compiler_type=none +fi + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $am_cv_CC_dependencies_compiler_type" >&5 +$as_echo "$am_cv_CC_dependencies_compiler_type" >&6; } +CCDEPMODE=depmode=$am_cv_CC_dependencies_compiler_type + + if + test "x$enable_dependency_tracking" != xno \ + && test "$am_cv_CC_dependencies_compiler_type" = gcc3; then + am__fastdepCC_TRUE= + am__fastdepCC_FALSE='#' +else + am__fastdepCC_TRUE='#' + am__fastdepCC_FALSE= +fi + + +if test "x$CC" != xcc; then + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether $CC and cc understand -c and -o together" >&5 +$as_echo_n "checking whether $CC and cc understand -c and -o together... " >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether cc understands -c and -o together" >&5 +$as_echo_n "checking whether cc understands -c and -o together... " >&6; } +fi +set dummy $CC; ac_cc=`$as_echo "$2" | + sed 's/[^a-zA-Z0-9_]/_/g;s/^[0-9]/_/'` +if eval "test \"\${ac_cv_prog_cc_${ac_cc}_c_o+set}\"" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +# Make sure it works both with $CC and with simple cc. +# We do the test twice because some compilers refuse to overwrite an +# existing .o file with -o, though they will create one. +ac_try='$CC -c conftest.$ac_ext -o conftest2.$ac_objext >&5' +rm -f conftest2.* +if { { case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_try") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && + test -f conftest2.$ac_objext && { { case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_try") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; +then + eval ac_cv_prog_cc_${ac_cc}_c_o=yes + if test "x$CC" != xcc; then + # Test first that cc exists at all. + if { ac_try='cc -c conftest.$ac_ext >&5' + { { case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_try") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; }; then + ac_try='cc -c conftest.$ac_ext -o conftest2.$ac_objext >&5' + rm -f conftest2.* + if { { case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_try") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && + test -f conftest2.$ac_objext && { { case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_try") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; + then + # cc works too. + : + else + # cc exists but doesn't like -o. + eval ac_cv_prog_cc_${ac_cc}_c_o=no + fi + fi + fi +else + eval ac_cv_prog_cc_${ac_cc}_c_o=no +fi +rm -f core conftest* + +fi +if eval test \$ac_cv_prog_cc_${ac_cc}_c_o = yes; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + +$as_echo "#define NO_MINUS_C_MINUS_O 1" >>confdefs.h + +fi + +# FIXME: we rely on the cache variable name because +# there is no other way. +set dummy $CC +am_cc=`echo $2 | sed 's/[^a-zA-Z0-9_]/_/g;s/^[0-9]/_/'` +eval am_t=\$ac_cv_prog_cc_${am_cc}_c_o +if test "$am_t" != yes; then + # Losing compiler, so override with the script. + # FIXME: It is wrong to rewrite CC. + # But if we don't then we get into trouble of one sort or another. + # A longer-term fix would be to have automake use am__CC in this case, + # and then we could set am__CC="\$(top_srcdir)/compile \$(CC)" + CC="$am_aux_dir/compile $CC" +fi + + +ac_ext=cpp +ac_cpp='$CXXCPP $CPPFLAGS' +ac_compile='$CXX -c $CXXFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CXX -o conftest$ac_exeext $CXXFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_cxx_compiler_gnu +if test -z "$CXX"; then + if test -n "$CCC"; then + CXX=$CCC + else + if test -n "$ac_tool_prefix"; then + for ac_prog in g++ c++ gpp aCC CC cxx cc++ cl.exe FCC KCC RCC xlC_r xlC + do + # Extract the first word of "$ac_tool_prefix$ac_prog", so it can be a program name with args. +set dummy $ac_tool_prefix$ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_CXX+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$CXX"; then + ac_cv_prog_CXX="$CXX" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_CXX="$ac_tool_prefix$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +CXX=$ac_cv_prog_CXX +if test -n "$CXX"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $CXX" >&5 +$as_echo "$CXX" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$CXX" && break + done +fi +if test -z "$CXX"; then + ac_ct_CXX=$CXX + for ac_prog in g++ c++ gpp aCC CC cxx cc++ cl.exe FCC KCC RCC xlC_r xlC +do + # Extract the first word of "$ac_prog", so it can be a program name with args. +set dummy $ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_CXX+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_CXX"; then + ac_cv_prog_ac_ct_CXX="$ac_ct_CXX" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_CXX="$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_CXX=$ac_cv_prog_ac_ct_CXX +if test -n "$ac_ct_CXX"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_CXX" >&5 +$as_echo "$ac_ct_CXX" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$ac_ct_CXX" && break +done + + if test "x$ac_ct_CXX" = x; then + CXX="g++" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + CXX=$ac_ct_CXX + fi +fi + + fi +fi +# Provide some information about the compiler. +$as_echo "$as_me:${as_lineno-$LINENO}: checking for C++ compiler version" >&5 +set X $ac_compile +ac_compiler=$2 +for ac_option in --version -v -V -qversion; do + { { ac_try="$ac_compiler $ac_option >&5" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_compiler $ac_option >&5") 2>conftest.err + ac_status=$? + if test -s conftest.err; then + sed '10a\ +... rest of stderr output deleted ... + 10q' conftest.err >conftest.er1 + cat conftest.er1 >&5 + fi + rm -f conftest.er1 conftest.err + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } +done + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether we are using the GNU C++ compiler" >&5 +$as_echo_n "checking whether we are using the GNU C++ compiler... " >&6; } +if test "${ac_cv_cxx_compiler_gnu+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ +#ifndef __GNUC__ + choke me +#endif + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_compile "$LINENO"; then : + ac_compiler_gnu=yes +else + ac_compiler_gnu=no +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +ac_cv_cxx_compiler_gnu=$ac_compiler_gnu + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_cxx_compiler_gnu" >&5 +$as_echo "$ac_cv_cxx_compiler_gnu" >&6; } +if test $ac_compiler_gnu = yes; then + GXX=yes +else + GXX= +fi +ac_test_CXXFLAGS=${CXXFLAGS+set} +ac_save_CXXFLAGS=$CXXFLAGS +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether $CXX accepts -g" >&5 +$as_echo_n "checking whether $CXX accepts -g... " >&6; } +if test "${ac_cv_prog_cxx_g+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_save_cxx_werror_flag=$ac_cxx_werror_flag + ac_cxx_werror_flag=yes + ac_cv_prog_cxx_g=no + CXXFLAGS="-g" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_compile "$LINENO"; then : + ac_cv_prog_cxx_g=yes +else + CXXFLAGS="" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_compile "$LINENO"; then : + +else + ac_cxx_werror_flag=$ac_save_cxx_werror_flag + CXXFLAGS="-g" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_compile "$LINENO"; then : + ac_cv_prog_cxx_g=yes +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext + ac_cxx_werror_flag=$ac_save_cxx_werror_flag +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_prog_cxx_g" >&5 +$as_echo "$ac_cv_prog_cxx_g" >&6; } +if test "$ac_test_CXXFLAGS" = set; then + CXXFLAGS=$ac_save_CXXFLAGS +elif test $ac_cv_prog_cxx_g = yes; then + if test "$GXX" = yes; then + CXXFLAGS="-g -O2" + else + CXXFLAGS="-g" + fi +else + if test "$GXX" = yes; then + CXXFLAGS="-O2" + else + CXXFLAGS= + fi +fi +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + +depcc="$CXX" am_compiler_list= + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking dependency style of $depcc" >&5 +$as_echo_n "checking dependency style of $depcc... " >&6; } +if test "${am_cv_CXX_dependencies_compiler_type+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -z "$AMDEP_TRUE" && test -f "$am_depcomp"; then + # We make a subdir and do the tests there. Otherwise we can end up + # making bogus files that we don't know about and never remove. For + # instance it was reported that on HP-UX the gcc test will end up + # making a dummy file named `D' -- because `-MD' means `put the output + # in D'. + mkdir conftest.dir + # Copy depcomp to subdir because otherwise we won't find it if we're + # using a relative directory. + cp "$am_depcomp" conftest.dir + cd conftest.dir + # We will build objects and dependencies in a subdirectory because + # it helps to detect inapplicable dependency modes. For instance + # both Tru64's cc and ICC support -MD to output dependencies as a + # side effect of compilation, but ICC will put the dependencies in + # the current directory while Tru64 will put them in the object + # directory. + mkdir sub + + am_cv_CXX_dependencies_compiler_type=none + if test "$am_compiler_list" = ""; then + am_compiler_list=`sed -n 's/^#*\([a-zA-Z0-9]*\))$/\1/p' < ./depcomp` + fi + am__universal=false + case " $depcc " in #( + *\ -arch\ *\ -arch\ *) am__universal=true ;; + esac + + for depmode in $am_compiler_list; do + # Setup a source with many dependencies, because some compilers + # like to wrap large dependency lists on column 80 (with \), and + # we should not choose a depcomp mode which is confused by this. + # + # We need to recreate these files for each test, as the compiler may + # overwrite some of them when testing with obscure command lines. + # This happens at least with the AIX C compiler. + : > sub/conftest.c + for i in 1 2 3 4 5 6; do + echo '#include "conftst'$i'.h"' >> sub/conftest.c + # Using `: > sub/conftst$i.h' creates only sub/conftst1.h with + # Solaris 8's {/usr,}/bin/sh. + touch sub/conftst$i.h + done + echo "${am__include} ${am__quote}sub/conftest.Po${am__quote}" > confmf + + # We check with `-c' and `-o' for the sake of the "dashmstdout" + # mode. It turns out that the SunPro C++ compiler does not properly + # handle `-M -o', and we need to detect this. Also, some Intel + # versions had trouble with output in subdirs + am__obj=sub/conftest.${OBJEXT-o} + am__minus_obj="-o $am__obj" + case $depmode in + gcc) + # This depmode causes a compiler race in universal mode. + test "$am__universal" = false || continue + ;; + nosideeffect) + # after this tag, mechanisms are not by side-effect, so they'll + # only be used when explicitly requested + if test "x$enable_dependency_tracking" = xyes; then + continue + else + break + fi + ;; + msvisualcpp | msvcmsys) + # This compiler won't grok `-c -o', but also, the minuso test has + # not run yet. These depmodes are late enough in the game, and + # so weak that their functioning should not be impacted. + am__obj=conftest.${OBJEXT-o} + am__minus_obj= + ;; + none) break ;; + esac + if depmode=$depmode \ + source=sub/conftest.c object=$am__obj \ + depfile=sub/conftest.Po tmpdepfile=sub/conftest.TPo \ + $SHELL ./depcomp $depcc -c $am__minus_obj sub/conftest.c \ + >/dev/null 2>conftest.err && + grep sub/conftst1.h sub/conftest.Po > /dev/null 2>&1 && + grep sub/conftst6.h sub/conftest.Po > /dev/null 2>&1 && + grep $am__obj sub/conftest.Po > /dev/null 2>&1 && + ${MAKE-make} -s -f confmf > /dev/null 2>&1; then + # icc doesn't choke on unknown options, it will just issue warnings + # or remarks (even with -Werror). So we grep stderr for any message + # that says an option was ignored or not supported. + # When given -MP, icc 7.0 and 7.1 complain thusly: + # icc: Command line warning: ignoring option '-M'; no argument required + # The diagnosis changed in icc 8.0: + # icc: Command line remark: option '-MP' not supported + if (grep 'ignoring option' conftest.err || + grep 'not supported' conftest.err) >/dev/null 2>&1; then :; else + am_cv_CXX_dependencies_compiler_type=$depmode + break + fi + fi + done + + cd .. + rm -rf conftest.dir +else + am_cv_CXX_dependencies_compiler_type=none +fi + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $am_cv_CXX_dependencies_compiler_type" >&5 +$as_echo "$am_cv_CXX_dependencies_compiler_type" >&6; } +CXXDEPMODE=depmode=$am_cv_CXX_dependencies_compiler_type + + if + test "x$enable_dependency_tracking" != xno \ + && test "$am_cv_CXX_dependencies_compiler_type" = gcc3; then + am__fastdepCXX_TRUE= + am__fastdepCXX_FALSE='#' +else + am__fastdepCXX_TRUE='#' + am__fastdepCXX_FALSE= +fi + + + +ac_ext=cpp +ac_cpp='$CXXCPP $CPPFLAGS' +ac_compile='$CXX -c $CXXFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CXX -o conftest$ac_exeext $CXXFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_cxx_compiler_gnu +if test -z "$CXX"; then + if test -n "$CCC"; then + CXX=$CCC + else + if test -n "$ac_tool_prefix"; then + for ac_prog in g++ c++ gpp aCC CC cxx cc++ cl.exe FCC KCC RCC xlC_r xlC + do + # Extract the first word of "$ac_tool_prefix$ac_prog", so it can be a program name with args. +set dummy $ac_tool_prefix$ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_CXX+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$CXX"; then + ac_cv_prog_CXX="$CXX" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_CXX="$ac_tool_prefix$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +CXX=$ac_cv_prog_CXX +if test -n "$CXX"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $CXX" >&5 +$as_echo "$CXX" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$CXX" && break + done +fi +if test -z "$CXX"; then + ac_ct_CXX=$CXX + for ac_prog in g++ c++ gpp aCC CC cxx cc++ cl.exe FCC KCC RCC xlC_r xlC +do + # Extract the first word of "$ac_prog", so it can be a program name with args. +set dummy $ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_ac_ct_CXX+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$ac_ct_CXX"; then + ac_cv_prog_ac_ct_CXX="$ac_ct_CXX" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_ac_ct_CXX="$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +ac_ct_CXX=$ac_cv_prog_ac_ct_CXX +if test -n "$ac_ct_CXX"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_ct_CXX" >&5 +$as_echo "$ac_ct_CXX" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$ac_ct_CXX" && break +done + + if test "x$ac_ct_CXX" = x; then + CXX="g++" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + CXX=$ac_ct_CXX + fi +fi + + fi +fi +# Provide some information about the compiler. +$as_echo "$as_me:${as_lineno-$LINENO}: checking for C++ compiler version" >&5 +set X $ac_compile +ac_compiler=$2 +for ac_option in --version -v -V -qversion; do + { { ac_try="$ac_compiler $ac_option >&5" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_compiler $ac_option >&5") 2>conftest.err + ac_status=$? + if test -s conftest.err; then + sed '10a\ +... rest of stderr output deleted ... + 10q' conftest.err >conftest.er1 + cat conftest.er1 >&5 + fi + rm -f conftest.er1 conftest.err + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } +done + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether we are using the GNU C++ compiler" >&5 +$as_echo_n "checking whether we are using the GNU C++ compiler... " >&6; } +if test "${ac_cv_cxx_compiler_gnu+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ +#ifndef __GNUC__ + choke me +#endif + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_compile "$LINENO"; then : + ac_compiler_gnu=yes +else + ac_compiler_gnu=no +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +ac_cv_cxx_compiler_gnu=$ac_compiler_gnu + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_cxx_compiler_gnu" >&5 +$as_echo "$ac_cv_cxx_compiler_gnu" >&6; } +if test $ac_compiler_gnu = yes; then + GXX=yes +else + GXX= +fi +ac_test_CXXFLAGS=${CXXFLAGS+set} +ac_save_CXXFLAGS=$CXXFLAGS +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether $CXX accepts -g" >&5 +$as_echo_n "checking whether $CXX accepts -g... " >&6; } +if test "${ac_cv_prog_cxx_g+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_save_cxx_werror_flag=$ac_cxx_werror_flag + ac_cxx_werror_flag=yes + ac_cv_prog_cxx_g=no + CXXFLAGS="-g" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_compile "$LINENO"; then : + ac_cv_prog_cxx_g=yes +else + CXXFLAGS="" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_compile "$LINENO"; then : + +else + ac_cxx_werror_flag=$ac_save_cxx_werror_flag + CXXFLAGS="-g" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_compile "$LINENO"; then : + ac_cv_prog_cxx_g=yes +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext + ac_cxx_werror_flag=$ac_save_cxx_werror_flag +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_prog_cxx_g" >&5 +$as_echo "$ac_cv_prog_cxx_g" >&6; } +if test "$ac_test_CXXFLAGS" = set; then + CXXFLAGS=$ac_save_CXXFLAGS +elif test $ac_cv_prog_cxx_g = yes; then + if test "$GXX" = yes; then + CXXFLAGS="-g -O2" + else + CXXFLAGS="-g" + fi +else + if test "$GXX" = yes; then + CXXFLAGS="-O2" + else + CXXFLAGS= + fi +fi +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + +depcc="$CXX" am_compiler_list= + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking dependency style of $depcc" >&5 +$as_echo_n "checking dependency style of $depcc... " >&6; } +if test "${am_cv_CXX_dependencies_compiler_type+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -z "$AMDEP_TRUE" && test -f "$am_depcomp"; then + # We make a subdir and do the tests there. Otherwise we can end up + # making bogus files that we don't know about and never remove. For + # instance it was reported that on HP-UX the gcc test will end up + # making a dummy file named `D' -- because `-MD' means `put the output + # in D'. + mkdir conftest.dir + # Copy depcomp to subdir because otherwise we won't find it if we're + # using a relative directory. + cp "$am_depcomp" conftest.dir + cd conftest.dir + # We will build objects and dependencies in a subdirectory because + # it helps to detect inapplicable dependency modes. For instance + # both Tru64's cc and ICC support -MD to output dependencies as a + # side effect of compilation, but ICC will put the dependencies in + # the current directory while Tru64 will put them in the object + # directory. + mkdir sub + + am_cv_CXX_dependencies_compiler_type=none + if test "$am_compiler_list" = ""; then + am_compiler_list=`sed -n 's/^#*\([a-zA-Z0-9]*\))$/\1/p' < ./depcomp` + fi + am__universal=false + case " $depcc " in #( + *\ -arch\ *\ -arch\ *) am__universal=true ;; + esac + + for depmode in $am_compiler_list; do + # Setup a source with many dependencies, because some compilers + # like to wrap large dependency lists on column 80 (with \), and + # we should not choose a depcomp mode which is confused by this. + # + # We need to recreate these files for each test, as the compiler may + # overwrite some of them when testing with obscure command lines. + # This happens at least with the AIX C compiler. + : > sub/conftest.c + for i in 1 2 3 4 5 6; do + echo '#include "conftst'$i'.h"' >> sub/conftest.c + # Using `: > sub/conftst$i.h' creates only sub/conftst1.h with + # Solaris 8's {/usr,}/bin/sh. + touch sub/conftst$i.h + done + echo "${am__include} ${am__quote}sub/conftest.Po${am__quote}" > confmf + + # We check with `-c' and `-o' for the sake of the "dashmstdout" + # mode. It turns out that the SunPro C++ compiler does not properly + # handle `-M -o', and we need to detect this. Also, some Intel + # versions had trouble with output in subdirs + am__obj=sub/conftest.${OBJEXT-o} + am__minus_obj="-o $am__obj" + case $depmode in + gcc) + # This depmode causes a compiler race in universal mode. + test "$am__universal" = false || continue + ;; + nosideeffect) + # after this tag, mechanisms are not by side-effect, so they'll + # only be used when explicitly requested + if test "x$enable_dependency_tracking" = xyes; then + continue + else + break + fi + ;; + msvisualcpp | msvcmsys) + # This compiler won't grok `-c -o', but also, the minuso test has + # not run yet. These depmodes are late enough in the game, and + # so weak that their functioning should not be impacted. + am__obj=conftest.${OBJEXT-o} + am__minus_obj= + ;; + none) break ;; + esac + if depmode=$depmode \ + source=sub/conftest.c object=$am__obj \ + depfile=sub/conftest.Po tmpdepfile=sub/conftest.TPo \ + $SHELL ./depcomp $depcc -c $am__minus_obj sub/conftest.c \ + >/dev/null 2>conftest.err && + grep sub/conftst1.h sub/conftest.Po > /dev/null 2>&1 && + grep sub/conftst6.h sub/conftest.Po > /dev/null 2>&1 && + grep $am__obj sub/conftest.Po > /dev/null 2>&1 && + ${MAKE-make} -s -f confmf > /dev/null 2>&1; then + # icc doesn't choke on unknown options, it will just issue warnings + # or remarks (even with -Werror). So we grep stderr for any message + # that says an option was ignored or not supported. + # When given -MP, icc 7.0 and 7.1 complain thusly: + # icc: Command line warning: ignoring option '-M'; no argument required + # The diagnosis changed in icc 8.0: + # icc: Command line remark: option '-MP' not supported + if (grep 'ignoring option' conftest.err || + grep 'not supported' conftest.err) >/dev/null 2>&1; then :; else + am_cv_CXX_dependencies_compiler_type=$depmode + break + fi + fi + done + + cd .. + rm -rf conftest.dir +else + am_cv_CXX_dependencies_compiler_type=none +fi + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $am_cv_CXX_dependencies_compiler_type" >&5 +$as_echo "$am_cv_CXX_dependencies_compiler_type" >&6; } +CXXDEPMODE=depmode=$am_cv_CXX_dependencies_compiler_type + + if + test "x$enable_dependency_tracking" != xno \ + && test "$am_cv_CXX_dependencies_compiler_type" = gcc3; then + am__fastdepCXX_TRUE= + am__fastdepCXX_FALSE='#' +else + am__fastdepCXX_TRUE='#' + am__fastdepCXX_FALSE= +fi + + +if test -n "$CXX" && ( test "X$CXX" != "Xno" && + ( (test "X$CXX" = "Xg++" && `g++ -v >/dev/null 2>&1` ) || + (test "X$CXX" != "Xg++"))) ; then + ac_ext=cpp +ac_cpp='$CXXCPP $CPPFLAGS' +ac_compile='$CXX -c $CXXFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CXX -o conftest$ac_exeext $CXXFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_cxx_compiler_gnu +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking how to run the C++ preprocessor" >&5 +$as_echo_n "checking how to run the C++ preprocessor... " >&6; } +if test -z "$CXXCPP"; then + if test "${ac_cv_prog_CXXCPP+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + # Double quotes because CXXCPP needs to be expanded + for CXXCPP in "$CXX -E" "/lib/cpp" + do + ac_preproc_ok=false +for ac_cxx_preproc_warn_flag in '' yes +do + # Use a header file that comes with gcc, so configuring glibc + # with a fresh cross-compiler works. + # Prefer to if __STDC__ is defined, since + # exists even on freestanding compilers. + # On the NeXT, cc -E runs the code through the compiler's parser, + # not just through cpp. "Syntax error" is here to catch this case. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#ifdef __STDC__ +# include +#else +# include +#endif + Syntax error +_ACEOF +if ac_fn_cxx_try_cpp "$LINENO"; then : + +else + # Broken: fails on valid input. +continue +fi +rm -f conftest.err conftest.i conftest.$ac_ext + + # OK, works on sane cases. Now check whether nonexistent headers + # can be detected and how. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +_ACEOF +if ac_fn_cxx_try_cpp "$LINENO"; then : + # Broken: success on invalid input. +continue +else + # Passes both tests. +ac_preproc_ok=: +break +fi +rm -f conftest.err conftest.i conftest.$ac_ext + +done +# Because of `break', _AC_PREPROC_IFELSE's cleaning code was skipped. +rm -f conftest.i conftest.err conftest.$ac_ext +if $ac_preproc_ok; then : + break +fi + + done + ac_cv_prog_CXXCPP=$CXXCPP + +fi + CXXCPP=$ac_cv_prog_CXXCPP +else + ac_cv_prog_CXXCPP=$CXXCPP +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $CXXCPP" >&5 +$as_echo "$CXXCPP" >&6; } +ac_preproc_ok=false +for ac_cxx_preproc_warn_flag in '' yes +do + # Use a header file that comes with gcc, so configuring glibc + # with a fresh cross-compiler works. + # Prefer to if __STDC__ is defined, since + # exists even on freestanding compilers. + # On the NeXT, cc -E runs the code through the compiler's parser, + # not just through cpp. "Syntax error" is here to catch this case. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#ifdef __STDC__ +# include +#else +# include +#endif + Syntax error +_ACEOF +if ac_fn_cxx_try_cpp "$LINENO"; then : + +else + # Broken: fails on valid input. +continue +fi +rm -f conftest.err conftest.i conftest.$ac_ext + + # OK, works on sane cases. Now check whether nonexistent headers + # can be detected and how. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +_ACEOF +if ac_fn_cxx_try_cpp "$LINENO"; then : + # Broken: success on invalid input. +continue +else + # Passes both tests. +ac_preproc_ok=: +break +fi +rm -f conftest.err conftest.i conftest.$ac_ext + +done +# Because of `break', _AC_PREPROC_IFELSE's cleaning code was skipped. +rm -f conftest.i conftest.err conftest.$ac_ext +if $ac_preproc_ok; then : + +else + { { $as_echo "$as_me:${as_lineno-$LINENO}: error: in \`$ac_pwd':" >&5 +$as_echo "$as_me: error: in \`$ac_pwd':" >&2;} +_lt_caught_CXX_error=yes; } +fi + +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + +else + _lt_caught_CXX_error=yes +fi + + + + +ac_ext=cpp +ac_cpp='$CXXCPP $CPPFLAGS' +ac_compile='$CXX -c $CXXFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CXX -o conftest$ac_exeext $CXXFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_cxx_compiler_gnu + +archive_cmds_need_lc_CXX=no +allow_undefined_flag_CXX= +always_export_symbols_CXX=no +archive_expsym_cmds_CXX= +compiler_needs_object_CXX=no +export_dynamic_flag_spec_CXX= +hardcode_direct_CXX=no +hardcode_direct_absolute_CXX=no +hardcode_libdir_flag_spec_CXX= +hardcode_libdir_flag_spec_ld_CXX= +hardcode_libdir_separator_CXX= +hardcode_minus_L_CXX=no +hardcode_shlibpath_var_CXX=unsupported +hardcode_automatic_CXX=no +inherit_rpath_CXX=no +module_cmds_CXX= +module_expsym_cmds_CXX= +link_all_deplibs_CXX=unknown +old_archive_cmds_CXX=$old_archive_cmds +no_undefined_flag_CXX= +whole_archive_flag_spec_CXX= +enable_shared_with_static_runtimes_CXX=no + +# Source file extension for C++ test sources. +ac_ext=cpp + +# Object file extension for compiled C++ test sources. +objext=o +objext_CXX=$objext + +# No sense in running all these tests if we already determined that +# the CXX compiler isn't working. Some variables (like enable_shared) +# are currently assumed to apply to all compilers on this platform, +# and will be corrupted by setting them based on a non-working compiler. +if test "$_lt_caught_CXX_error" != yes; then + # Code to be used in simple compile tests + lt_simple_compile_test_code="int some_variable = 0;" + + # Code to be used in simple link tests + lt_simple_link_test_code='int main(int, char *[]) { return(0); }' + + # ltmain only uses $CC for tagged configurations so make sure $CC is set. + + + + + + +# If no C compiler was specified, use CC. +LTCC=${LTCC-"$CC"} + +# If no C compiler flags were specified, use CFLAGS. +LTCFLAGS=${LTCFLAGS-"$CFLAGS"} + +# Allow CC to be a program name with arguments. +compiler=$CC + + + # save warnings/boilerplate of simple test code + ac_outfile=conftest.$ac_objext +echo "$lt_simple_compile_test_code" >conftest.$ac_ext +eval "$ac_compile" 2>&1 >/dev/null | $SED '/^$/d; /^ *+/d' >conftest.err +_lt_compiler_boilerplate=`cat conftest.err` +$RM conftest* + + ac_outfile=conftest.$ac_objext +echo "$lt_simple_link_test_code" >conftest.$ac_ext +eval "$ac_link" 2>&1 >/dev/null | $SED '/^$/d; /^ *+/d' >conftest.err +_lt_linker_boilerplate=`cat conftest.err` +$RM -r conftest* + + + # Allow CC to be a program name with arguments. + lt_save_CC=$CC + lt_save_LD=$LD + lt_save_GCC=$GCC + GCC=$GXX + lt_save_with_gnu_ld=$with_gnu_ld + lt_save_path_LD=$lt_cv_path_LD + if test -n "${lt_cv_prog_gnu_ldcxx+set}"; then + lt_cv_prog_gnu_ld=$lt_cv_prog_gnu_ldcxx + else + $as_unset lt_cv_prog_gnu_ld + fi + if test -n "${lt_cv_path_LDCXX+set}"; then + lt_cv_path_LD=$lt_cv_path_LDCXX + else + $as_unset lt_cv_path_LD + fi + test -z "${LDCXX+set}" || LD=$LDCXX + CC=${CXX-"c++"} + compiler=$CC + compiler_CXX=$CC + for cc_temp in $compiler""; do + case $cc_temp in + compile | *[\\/]compile | ccache | *[\\/]ccache ) ;; + distcc | *[\\/]distcc | purify | *[\\/]purify ) ;; + \-*) ;; + *) break;; + esac +done +cc_basename=`$ECHO "X$cc_temp" | $Xsed -e 's%.*/%%' -e "s%^$host_alias-%%"` + + + if test -n "$compiler"; then + # We don't want -fno-exception when compiling C++ code, so set the + # no_builtin_flag separately + if test "$GXX" = yes; then + lt_prog_compiler_no_builtin_flag_CXX=' -fno-builtin' + else + lt_prog_compiler_no_builtin_flag_CXX= + fi + + if test "$GXX" = yes; then + # Set up default GNU C++ configuration + + + +# Check whether --with-gnu-ld was given. +if test "${with_gnu_ld+set}" = set; then : + withval=$with_gnu_ld; test "$withval" = no || with_gnu_ld=yes +else + with_gnu_ld=no +fi + +ac_prog=ld +if test "$GCC" = yes; then + # Check if gcc -print-prog-name=ld gives a path. + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for ld used by $CC" >&5 +$as_echo_n "checking for ld used by $CC... " >&6; } + case $host in + *-*-mingw*) + # gcc leaves a trailing carriage return which upsets mingw + ac_prog=`($CC -print-prog-name=ld) 2>&5 | tr -d '\015'` ;; + *) + ac_prog=`($CC -print-prog-name=ld) 2>&5` ;; + esac + case $ac_prog in + # Accept absolute paths. + [\\/]* | ?:[\\/]*) + re_direlt='/[^/][^/]*/\.\./' + # Canonicalize the pathname of ld + ac_prog=`$ECHO "$ac_prog"| $SED 's%\\\\%/%g'` + while $ECHO "$ac_prog" | $GREP "$re_direlt" > /dev/null 2>&1; do + ac_prog=`$ECHO $ac_prog| $SED "s%$re_direlt%/%"` + done + test -z "$LD" && LD="$ac_prog" + ;; + "") + # If it fails, then pretend we aren't using GCC. + ac_prog=ld + ;; + *) + # If it is relative, then search for the first ld in PATH. + with_gnu_ld=unknown + ;; + esac +elif test "$with_gnu_ld" = yes; then + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for GNU ld" >&5 +$as_echo_n "checking for GNU ld... " >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for non-GNU ld" >&5 +$as_echo_n "checking for non-GNU ld... " >&6; } +fi +if test "${lt_cv_path_LD+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -z "$LD"; then + lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + for ac_dir in $PATH; do + IFS="$lt_save_ifs" + test -z "$ac_dir" && ac_dir=. + if test -f "$ac_dir/$ac_prog" || test -f "$ac_dir/$ac_prog$ac_exeext"; then + lt_cv_path_LD="$ac_dir/$ac_prog" + # Check to see if the program is GNU ld. I'd rather use --version, + # but apparently some variants of GNU ld only accept -v. + # Break only if it was the GNU/non-GNU ld that we prefer. + case `"$lt_cv_path_LD" -v 2>&1 &5 +$as_echo "$LD" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi +test -z "$LD" && as_fn_error $? "no acceptable ld found in \$PATH" "$LINENO" 5 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking if the linker ($LD) is GNU ld" >&5 +$as_echo_n "checking if the linker ($LD) is GNU ld... " >&6; } +if test "${lt_cv_prog_gnu_ld+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + # I'd rather use --version here, but apparently some GNU lds only accept -v. +case `$LD -v 2>&1 &5 +$as_echo "$lt_cv_prog_gnu_ld" >&6; } +with_gnu_ld=$lt_cv_prog_gnu_ld + + + + + + + + # Check if GNU C++ uses GNU ld as the underlying linker, since the + # archiving commands below assume that GNU ld is being used. + if test "$with_gnu_ld" = yes; then + archive_cmds_CXX='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_expsym_cmds_CXX='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + + hardcode_libdir_flag_spec_CXX='${wl}-rpath ${wl}$libdir' + export_dynamic_flag_spec_CXX='${wl}--export-dynamic' + + # If archive_cmds runs LD, not CC, wlarc should be empty + # XXX I think wlarc can be eliminated in ltcf-cxx, but I need to + # investigate it a little bit more. (MM) + wlarc='${wl}' + + # ancient GNU ld didn't support --whole-archive et. al. + if eval "`$CC -print-prog-name=ld` --help 2>&1" | + $GREP 'no-whole-archive' > /dev/null; then + whole_archive_flag_spec_CXX="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + else + whole_archive_flag_spec_CXX= + fi + else + with_gnu_ld=no + wlarc= + + # A generic and very simple default shared library creation + # command for GNU C++ for the case where it uses the native + # linker, instead of GNU ld. If possible, this setting should + # overridden to take advantage of the native linker features on + # the platform it is being used on. + archive_cmds_CXX='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $lib' + fi + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + output_verbose_link_cmd='$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "\-L"' + + else + GXX=no + with_gnu_ld=no + wlarc= + fi + + # PORTME: fill in a description of your system's C++ link characteristics + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether the $compiler linker ($LD) supports shared libraries" >&5 +$as_echo_n "checking whether the $compiler linker ($LD) supports shared libraries... " >&6; } + ld_shlibs_CXX=yes + case $host_os in + aix3*) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + aix[4-9]*) + if test "$host_cpu" = ia64; then + # On IA64, the linker does run time linking by default, so we don't + # have to do anything special. + aix_use_runtimelinking=no + exp_sym_flag='-Bexport' + no_entry_flag="" + else + aix_use_runtimelinking=no + + # Test if we are trying to use run time linking or normal + # AIX style linking. If -brtl is somewhere in LDFLAGS, we + # need to do runtime linking. + case $host_os in aix4.[23]|aix4.[23].*|aix[5-9]*) + for ld_flag in $LDFLAGS; do + case $ld_flag in + *-brtl*) + aix_use_runtimelinking=yes + break + ;; + esac + done + ;; + esac + + exp_sym_flag='-bexport' + no_entry_flag='-bnoentry' + fi + + # When large executables or shared objects are built, AIX ld can + # have problems creating the table of contents. If linking a library + # or program results in "error TOC overflow" add -mminimal-toc to + # CXXFLAGS/CFLAGS for g++/gcc. In the cases where that is not + # enough to fix the problem, add -Wl,-bbigtoc to LDFLAGS. + + archive_cmds_CXX='' + hardcode_direct_CXX=yes + hardcode_direct_absolute_CXX=yes + hardcode_libdir_separator_CXX=':' + link_all_deplibs_CXX=yes + file_list_spec_CXX='${wl}-f,' + + if test "$GXX" = yes; then + case $host_os in aix4.[012]|aix4.[012].*) + # We only want to do this on AIX 4.2 and lower, the check + # below for broken collect2 doesn't work under 4.3+ + collect2name=`${CC} -print-prog-name=collect2` + if test -f "$collect2name" && + strings "$collect2name" | $GREP resolve_lib_name >/dev/null + then + # We have reworked collect2 + : + else + # We have old collect2 + hardcode_direct_CXX=unsupported + # It fails to find uninstalled libraries when the uninstalled + # path is not listed in the libpath. Setting hardcode_minus_L + # to unsupported forces relinking + hardcode_minus_L_CXX=yes + hardcode_libdir_flag_spec_CXX='-L$libdir' + hardcode_libdir_separator_CXX= + fi + esac + shared_flag='-shared' + if test "$aix_use_runtimelinking" = yes; then + shared_flag="$shared_flag "'${wl}-G' + fi + else + # not using gcc + if test "$host_cpu" = ia64; then + # VisualAge C++, Version 5.5 for AIX 5L for IA-64, Beta 3 Release + # chokes on -Wl,-G. The following line is correct: + shared_flag='-G' + else + if test "$aix_use_runtimelinking" = yes; then + shared_flag='${wl}-G' + else + shared_flag='${wl}-bM:SRE' + fi + fi + fi + + export_dynamic_flag_spec_CXX='${wl}-bexpall' + # It seems that -bexpall does not export symbols beginning with + # underscore (_), so it is better to generate a list of symbols to + # export. + always_export_symbols_CXX=yes + if test "$aix_use_runtimelinking" = yes; then + # Warning - without using the other runtime loading flags (-brtl), + # -berok will link without error, but may produce a broken library. + allow_undefined_flag_CXX='-berok' + # Determine the default libpath from the value encoded in an empty + # executable. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_link "$LINENO"; then : + +lt_aix_libpath_sed=' + /Import File Strings/,/^$/ { + /^0/ { + s/^0 *\(.*\)$/\1/ + p + } + }' +aix_libpath=`dump -H conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` +# Check for a 64-bit object if we didn't find anything. +if test -z "$aix_libpath"; then + aix_libpath=`dump -HX64 conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` +fi +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +if test -z "$aix_libpath"; then aix_libpath="/usr/lib:/lib"; fi + + hardcode_libdir_flag_spec_CXX='${wl}-blibpath:$libdir:'"$aix_libpath" + + archive_expsym_cmds_CXX='$CC -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags `if test "x${allow_undefined_flag}" != "x"; then $ECHO "X${wl}${allow_undefined_flag}" | $Xsed; else :; fi` '"\${wl}$exp_sym_flag:\$export_symbols $shared_flag" + else + if test "$host_cpu" = ia64; then + hardcode_libdir_flag_spec_CXX='${wl}-R $libdir:/usr/lib:/lib' + allow_undefined_flag_CXX="-z nodefs" + archive_expsym_cmds_CXX="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags ${wl}${allow_undefined_flag} '"\${wl}$exp_sym_flag:\$export_symbols" + else + # Determine the default libpath from the value encoded in an + # empty executable. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_link "$LINENO"; then : + +lt_aix_libpath_sed=' + /Import File Strings/,/^$/ { + /^0/ { + s/^0 *\(.*\)$/\1/ + p + } + }' +aix_libpath=`dump -H conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` +# Check for a 64-bit object if we didn't find anything. +if test -z "$aix_libpath"; then + aix_libpath=`dump -HX64 conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` +fi +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +if test -z "$aix_libpath"; then aix_libpath="/usr/lib:/lib"; fi + + hardcode_libdir_flag_spec_CXX='${wl}-blibpath:$libdir:'"$aix_libpath" + # Warning - without using the other run time loading flags, + # -berok will link without error, but may produce a broken library. + no_undefined_flag_CXX=' ${wl}-bernotok' + allow_undefined_flag_CXX=' ${wl}-berok' + # Exported symbols can be pulled into shared objects from archives + whole_archive_flag_spec_CXX='$convenience' + archive_cmds_need_lc_CXX=yes + # This is similar to how AIX traditionally builds its shared + # libraries. + archive_expsym_cmds_CXX="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs ${wl}-bnoentry $compiler_flags ${wl}-bE:$export_symbols${allow_undefined_flag}~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$soname' + fi + fi + ;; + + beos*) + if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then + allow_undefined_flag_CXX=unsupported + # Joseph Beckenbach says some releases of gcc + # support --undefined. This deserves some investigation. FIXME + archive_cmds_CXX='$CC -nostart $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + else + ld_shlibs_CXX=no + fi + ;; + + chorus*) + case $cc_basename in + *) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + esac + ;; + + cygwin* | mingw* | pw32* | cegcc*) + # _LT_TAGVAR(hardcode_libdir_flag_spec, CXX) is actually meaningless, + # as there is no search path for DLLs. + hardcode_libdir_flag_spec_CXX='-L$libdir' + allow_undefined_flag_CXX=unsupported + always_export_symbols_CXX=no + enable_shared_with_static_runtimes_CXX=yes + + if $LD --help 2>&1 | $GREP 'auto-import' > /dev/null; then + archive_cmds_CXX='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + # If the export-symbols file already is a .def file (1st line + # is EXPORTS), use it as is; otherwise, prepend... + archive_expsym_cmds_CXX='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then + cp $export_symbols $output_objdir/$soname.def; + else + echo EXPORTS > $output_objdir/$soname.def; + cat $export_symbols >> $output_objdir/$soname.def; + fi~ + $CC -shared -nostdlib $output_objdir/$soname.def $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + else + ld_shlibs_CXX=no + fi + ;; + darwin* | rhapsody*) + + + archive_cmds_need_lc_CXX=no + hardcode_direct_CXX=no + hardcode_automatic_CXX=yes + hardcode_shlibpath_var_CXX=unsupported + whole_archive_flag_spec_CXX='' + link_all_deplibs_CXX=yes + allow_undefined_flag_CXX="$_lt_dar_allow_undefined" + case $cc_basename in + ifort*) _lt_dar_can_shared=yes ;; + *) _lt_dar_can_shared=$GCC ;; + esac + if test "$_lt_dar_can_shared" = "yes"; then + output_verbose_link_cmd=echo + archive_cmds_CXX="\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod${_lt_dsymutil}" + module_cmds_CXX="\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dsymutil}" + archive_expsym_cmds_CXX="sed 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring ${_lt_dar_single_mod}${_lt_dar_export_syms}${_lt_dsymutil}" + module_expsym_cmds_CXX="sed -e 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dar_export_syms}${_lt_dsymutil}" + if test "$lt_cv_apple_cc_single_mod" != "yes"; then + archive_cmds_CXX="\$CC -r -keep_private_externs -nostdlib -o \${lib}-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \${lib}-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring${_lt_dsymutil}" + archive_expsym_cmds_CXX="sed 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC -r -keep_private_externs -nostdlib -o \${lib}-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \${lib}-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring${_lt_dar_export_syms}${_lt_dsymutil}" + fi + + else + ld_shlibs_CXX=no + fi + + ;; + + dgux*) + case $cc_basename in + ec++*) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + ghcx*) + # Green Hills C++ Compiler + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + *) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + esac + ;; + + freebsd[12]*) + # C++ shared libraries reported to be fairly broken before + # switch to ELF + ld_shlibs_CXX=no + ;; + + freebsd-elf*) + archive_cmds_need_lc_CXX=no + ;; + + freebsd* | dragonfly*) + # FreeBSD 3 and later use GNU C++ and GNU ld with standard ELF + # conventions + ld_shlibs_CXX=yes + ;; + + gnu*) + ;; + + hpux9*) + hardcode_libdir_flag_spec_CXX='${wl}+b ${wl}$libdir' + hardcode_libdir_separator_CXX=: + export_dynamic_flag_spec_CXX='${wl}-E' + hardcode_direct_CXX=yes + hardcode_minus_L_CXX=yes # Not in the search PATH, + # but as the default + # location of the library. + + case $cc_basename in + CC*) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + aCC*) + archive_cmds_CXX='$RM $output_objdir/$soname~$CC -b ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + # + # There doesn't appear to be a way to prevent this compiler from + # explicitly linking system object files so we need to strip them + # from the output so that they don't get included in the library + # dependencies. + output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $EGREP "\-L"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; $ECHO "X$list" | $Xsed' + ;; + *) + if test "$GXX" = yes; then + archive_cmds_CXX='$RM $output_objdir/$soname~$CC -shared -nostdlib -fPIC ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + else + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + fi + ;; + esac + ;; + + hpux10*|hpux11*) + if test $with_gnu_ld = no; then + hardcode_libdir_flag_spec_CXX='${wl}+b ${wl}$libdir' + hardcode_libdir_separator_CXX=: + + case $host_cpu in + hppa*64*|ia64*) + ;; + *) + export_dynamic_flag_spec_CXX='${wl}-E' + ;; + esac + fi + case $host_cpu in + hppa*64*|ia64*) + hardcode_direct_CXX=no + hardcode_shlibpath_var_CXX=no + ;; + *) + hardcode_direct_CXX=yes + hardcode_direct_absolute_CXX=yes + hardcode_minus_L_CXX=yes # Not in the search PATH, + # but as the default + # location of the library. + ;; + esac + + case $cc_basename in + CC*) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + aCC*) + case $host_cpu in + hppa*64*) + archive_cmds_CXX='$CC -b ${wl}+h ${wl}$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + ia64*) + archive_cmds_CXX='$CC -b ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + *) + archive_cmds_CXX='$CC -b ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + esac + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + # + # There doesn't appear to be a way to prevent this compiler from + # explicitly linking system object files so we need to strip them + # from the output so that they don't get included in the library + # dependencies. + output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $GREP "\-L"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; $ECHO "X$list" | $Xsed' + ;; + *) + if test "$GXX" = yes; then + if test $with_gnu_ld = no; then + case $host_cpu in + hppa*64*) + archive_cmds_CXX='$CC -shared -nostdlib -fPIC ${wl}+h ${wl}$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + ia64*) + archive_cmds_CXX='$CC -shared -nostdlib -fPIC ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + *) + archive_cmds_CXX='$CC -shared -nostdlib -fPIC ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + ;; + esac + fi + else + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + fi + ;; + esac + ;; + + interix[3-9]*) + hardcode_direct_CXX=no + hardcode_shlibpath_var_CXX=no + hardcode_libdir_flag_spec_CXX='${wl}-rpath,$libdir' + export_dynamic_flag_spec_CXX='${wl}-E' + # Hack: On Interix 3.x, we cannot compile PIC because of a broken gcc. + # Instead, shared libraries are loaded at an image base (0x10000000 by + # default) and relocated if they conflict, which is a slow very memory + # consuming and fragmenting process. To avoid this, we pick a random, + # 256 KiB-aligned image base between 0x50000000 and 0x6FFC0000 at link + # time. Moving up from 0x10000000 also allows more sbrk(2) space. + archive_cmds_CXX='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + archive_expsym_cmds_CXX='sed "s,^,_," $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--retain-symbols-file,$output_objdir/$soname.expsym ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + ;; + irix5* | irix6*) + case $cc_basename in + CC*) + # SGI C++ + archive_cmds_CXX='$CC -shared -all -multigot $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + + # Archives containing C++ object files must be created using + # "CC -ar", where "CC" is the IRIX C++ compiler. This is + # necessary to make sure instantiated templates are included + # in the archive. + old_archive_cmds_CXX='$CC -ar -WR,-u -o $oldlib $oldobjs' + ;; + *) + if test "$GXX" = yes; then + if test "$with_gnu_ld" = no; then + archive_cmds_CXX='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + else + archive_cmds_CXX='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` -o $lib' + fi + fi + link_all_deplibs_CXX=yes + ;; + esac + hardcode_libdir_flag_spec_CXX='${wl}-rpath ${wl}$libdir' + hardcode_libdir_separator_CXX=: + inherit_rpath_CXX=yes + ;; + + linux* | k*bsd*-gnu | kopensolaris*-gnu) + case $cc_basename in + KCC*) + # Kuck and Associates, Inc. (KAI) C++ Compiler + + # KCC will only create a shared library if the output file + # ends with ".so" (or ".sl" for HP-UX), so rename the library + # to its proper name (with version) after linking. + archive_cmds_CXX='tempext=`echo $shared_ext | $SED -e '\''s/\([^()0-9A-Za-z{}]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' + archive_expsym_cmds_CXX='tempext=`echo $shared_ext | $SED -e '\''s/\([^()0-9A-Za-z{}]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib ${wl}-retain-symbols-file,$export_symbols; mv \$templib $lib' + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + # + # There doesn't appear to be a way to prevent this compiler from + # explicitly linking system object files so we need to strip them + # from the output so that they don't get included in the library + # dependencies. + output_verbose_link_cmd='templist=`$CC $CFLAGS -v conftest.$objext -o libconftest$shared_ext 2>&1 | $GREP "ld"`; rm -f libconftest$shared_ext; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; $ECHO "X$list" | $Xsed' + + hardcode_libdir_flag_spec_CXX='${wl}-rpath,$libdir' + export_dynamic_flag_spec_CXX='${wl}--export-dynamic' + + # Archives containing C++ object files must be created using + # "CC -Bstatic", where "CC" is the KAI C++ compiler. + old_archive_cmds_CXX='$CC -Bstatic -o $oldlib $oldobjs' + ;; + icpc* | ecpc* ) + # Intel C++ + with_gnu_ld=yes + # version 8.0 and above of icpc choke on multiply defined symbols + # if we add $predep_objects and $postdep_objects, however 7.1 and + # earlier do not add the objects themselves. + case `$CC -V 2>&1` in + *"Version 7."*) + archive_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_expsym_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + ;; + *) # Version 8.0 or newer + tmp_idyn= + case $host_cpu in + ia64*) tmp_idyn=' -i_dynamic';; + esac + archive_cmds_CXX='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_expsym_cmds_CXX='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + ;; + esac + archive_cmds_need_lc_CXX=no + hardcode_libdir_flag_spec_CXX='${wl}-rpath,$libdir' + export_dynamic_flag_spec_CXX='${wl}--export-dynamic' + whole_archive_flag_spec_CXX='${wl}--whole-archive$convenience ${wl}--no-whole-archive' + ;; + pgCC* | pgcpp*) + # Portland Group C++ compiler + case `$CC -V` in + *pgCC\ [1-5]* | *pgcpp\ [1-5]*) + prelink_cmds_CXX='tpldir=Template.dir~ + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $objs $libobjs $compile_deplibs~ + compile_command="$compile_command `find $tpldir -name \*.o | $NL2SP`"' + old_archive_cmds_CXX='tpldir=Template.dir~ + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $oldobjs$old_deplibs~ + $AR $AR_FLAGS $oldlib$oldobjs$old_deplibs `find $tpldir -name \*.o | $NL2SP`~ + $RANLIB $oldlib' + archive_cmds_CXX='tpldir=Template.dir~ + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ + $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | $NL2SP` $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname -o $lib' + archive_expsym_cmds_CXX='tpldir=Template.dir~ + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ + $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | $NL2SP` $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname ${wl}-retain-symbols-file ${wl}$export_symbols -o $lib' + ;; + *) # Version 6 will use weak symbols + archive_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname -o $lib' + archive_expsym_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname ${wl}-retain-symbols-file ${wl}$export_symbols -o $lib' + ;; + esac + + hardcode_libdir_flag_spec_CXX='${wl}--rpath ${wl}$libdir' + export_dynamic_flag_spec_CXX='${wl}--export-dynamic' + whole_archive_flag_spec_CXX='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; $ECHO \"$new_convenience\"` ${wl}--no-whole-archive' + ;; + cxx*) + # Compaq C++ + archive_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_expsym_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib ${wl}-retain-symbols-file $wl$export_symbols' + + runpath_var=LD_RUN_PATH + hardcode_libdir_flag_spec_CXX='-rpath $libdir' + hardcode_libdir_separator_CXX=: + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + # + # There doesn't appear to be a way to prevent this compiler from + # explicitly linking system object files so we need to strip them + # from the output so that they don't get included in the library + # dependencies. + output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld"`; templist=`$ECHO "X$templist" | $Xsed -e "s/\(^.*ld.*\)\( .*ld .*$\)/\1/"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; $ECHO "X$list" | $Xsed' + ;; + xl*) + # IBM XL 8.0 on PPC, with GNU ld + hardcode_libdir_flag_spec_CXX='${wl}-rpath ${wl}$libdir' + export_dynamic_flag_spec_CXX='${wl}--export-dynamic' + archive_cmds_CXX='$CC -qmkshrobj $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + if test "x$supports_anon_versioning" = xyes; then + archive_expsym_cmds_CXX='echo "{ global:" > $output_objdir/$libname.ver~ + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $CC -qmkshrobj $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-version-script ${wl}$output_objdir/$libname.ver -o $lib' + fi + ;; + *) + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) + # Sun C++ 5.9 + no_undefined_flag_CXX=' -zdefs' + archive_cmds_CXX='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + archive_expsym_cmds_CXX='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-retain-symbols-file ${wl}$export_symbols' + hardcode_libdir_flag_spec_CXX='-R$libdir' + whole_archive_flag_spec_CXX='${wl}--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; $ECHO \"$new_convenience\"` ${wl}--no-whole-archive' + compiler_needs_object_CXX=yes + + # Not sure whether something based on + # $CC $CFLAGS -v conftest.$objext -o libconftest$shared_ext 2>&1 + # would be better. + output_verbose_link_cmd='echo' + + # Archives containing C++ object files must be created using + # "CC -xar", where "CC" is the Sun C++ compiler. This is + # necessary to make sure instantiated templates are included + # in the archive. + old_archive_cmds_CXX='$CC -xar -o $oldlib $oldobjs' + ;; + esac + ;; + esac + ;; + + lynxos*) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + + m88k*) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + + mvs*) + case $cc_basename in + cxx*) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + *) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + esac + ;; + + netbsd*) + if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then + archive_cmds_CXX='$LD -Bshareable -o $lib $predep_objects $libobjs $deplibs $postdep_objects $linker_flags' + wlarc= + hardcode_libdir_flag_spec_CXX='-R$libdir' + hardcode_direct_CXX=yes + hardcode_shlibpath_var_CXX=no + fi + # Workaround some broken pre-1.5 toolchains + output_verbose_link_cmd='$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP conftest.$objext | $SED -e "s:-lgcc -lc -lgcc::"' + ;; + + *nto* | *qnx*) + ld_shlibs_CXX=yes + ;; + + openbsd2*) + # C++ shared libraries are fairly broken + ld_shlibs_CXX=no + ;; + + openbsd*) + if test -f /usr/libexec/ld.so; then + hardcode_direct_CXX=yes + hardcode_shlibpath_var_CXX=no + hardcode_direct_absolute_CXX=yes + archive_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $lib' + hardcode_libdir_flag_spec_CXX='${wl}-rpath,$libdir' + if test -z "`echo __ELF__ | $CC -E - | grep __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + archive_expsym_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-retain-symbols-file,$export_symbols -o $lib' + export_dynamic_flag_spec_CXX='${wl}-E' + whole_archive_flag_spec_CXX="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + fi + output_verbose_link_cmd=echo + else + ld_shlibs_CXX=no + fi + ;; + + osf3* | osf4* | osf5*) + case $cc_basename in + KCC*) + # Kuck and Associates, Inc. (KAI) C++ Compiler + + # KCC will only create a shared library if the output file + # ends with ".so" (or ".sl" for HP-UX), so rename the library + # to its proper name (with version) after linking. + archive_cmds_CXX='tempext=`echo $shared_ext | $SED -e '\''s/\([^()0-9A-Za-z{}]\)/\\\\\1/g'\''`; templib=`echo "$lib" | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' + + hardcode_libdir_flag_spec_CXX='${wl}-rpath,$libdir' + hardcode_libdir_separator_CXX=: + + # Archives containing C++ object files must be created using + # the KAI C++ compiler. + case $host in + osf3*) old_archive_cmds_CXX='$CC -Bstatic -o $oldlib $oldobjs' ;; + *) old_archive_cmds_CXX='$CC -o $oldlib $oldobjs' ;; + esac + ;; + RCC*) + # Rational C++ 2.4.1 + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + cxx*) + case $host in + osf3*) + allow_undefined_flag_CXX=' ${wl}-expect_unresolved ${wl}\*' + archive_cmds_CXX='$CC -shared${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $soname `test -n "$verstring" && $ECHO "X${wl}-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + hardcode_libdir_flag_spec_CXX='${wl}-rpath ${wl}$libdir' + ;; + *) + allow_undefined_flag_CXX=' -expect_unresolved \*' + archive_cmds_CXX='$CC -shared${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib' + archive_expsym_cmds_CXX='for i in `cat $export_symbols`; do printf "%s %s\\n" -exported_symbol "\$i" >> $lib.exp; done~ + echo "-hidden">> $lib.exp~ + $CC -shared$allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname ${wl}-input ${wl}$lib.exp `test -n "$verstring" && $ECHO "X-set_version $verstring" | $Xsed` -update_registry ${output_objdir}/so_locations -o $lib~ + $RM $lib.exp' + hardcode_libdir_flag_spec_CXX='-rpath $libdir' + ;; + esac + + hardcode_libdir_separator_CXX=: + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + # + # There doesn't appear to be a way to prevent this compiler from + # explicitly linking system object files so we need to strip them + # from the output so that they don't get included in the library + # dependencies. + output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld" | $GREP -v "ld:"`; templist=`$ECHO "X$templist" | $Xsed -e "s/\(^.*ld.*\)\( .*ld.*$\)/\1/"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; $ECHO "X$list" | $Xsed' + ;; + *) + if test "$GXX" = yes && test "$with_gnu_ld" = no; then + allow_undefined_flag_CXX=' ${wl}-expect_unresolved ${wl}\*' + case $host in + osf3*) + archive_cmds_CXX='$CC -shared -nostdlib ${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "X${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + ;; + *) + archive_cmds_CXX='$CC -shared -nostdlib ${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-msym ${wl}-soname ${wl}$soname `test -n "$verstring" && $ECHO "${wl}-set_version ${wl}$verstring" | $Xsed` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + ;; + esac + + hardcode_libdir_flag_spec_CXX='${wl}-rpath ${wl}$libdir' + hardcode_libdir_separator_CXX=: + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + output_verbose_link_cmd='$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "\-L"' + + else + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + fi + ;; + esac + ;; + + psos*) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + + sunos4*) + case $cc_basename in + CC*) + # Sun C++ 4.x + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + lcc*) + # Lucid + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + *) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + esac + ;; + + solaris*) + case $cc_basename in + CC*) + # Sun C++ 4.2, 5.x and Centerline C++ + archive_cmds_need_lc_CXX=yes + no_undefined_flag_CXX=' -zdefs' + archive_cmds_CXX='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + archive_expsym_cmds_CXX='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $CC -G${allow_undefined_flag} ${wl}-M ${wl}$lib.exp -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + + hardcode_libdir_flag_spec_CXX='-R$libdir' + hardcode_shlibpath_var_CXX=no + case $host_os in + solaris2.[0-5] | solaris2.[0-5].*) ;; + *) + # The compiler driver will combine and reorder linker options, + # but understands `-z linker_flag'. + # Supported since Solaris 2.6 (maybe 2.5.1?) + whole_archive_flag_spec_CXX='-z allextract$convenience -z defaultextract' + ;; + esac + link_all_deplibs_CXX=yes + + output_verbose_link_cmd='echo' + + # Archives containing C++ object files must be created using + # "CC -xar", where "CC" is the Sun C++ compiler. This is + # necessary to make sure instantiated templates are included + # in the archive. + old_archive_cmds_CXX='$CC -xar -o $oldlib $oldobjs' + ;; + gcx*) + # Green Hills C++ Compiler + archive_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + + # The C++ compiler must be used to create the archive. + old_archive_cmds_CXX='$CC $LDFLAGS -archive -o $oldlib $oldobjs' + ;; + *) + # GNU C++ compiler with Solaris linker + if test "$GXX" = yes && test "$with_gnu_ld" = no; then + no_undefined_flag_CXX=' ${wl}-z ${wl}defs' + if $CC --version | $GREP -v '^2\.7' > /dev/null; then + archive_cmds_CXX='$CC -shared -nostdlib $LDFLAGS $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + archive_expsym_cmds_CXX='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $CC -shared -nostdlib ${wl}-M $wl$lib.exp -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + output_verbose_link_cmd='$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "\-L"' + else + # g++ 2.7 appears to require `-G' NOT `-shared' on this + # platform. + archive_cmds_CXX='$CC -G -nostdlib $LDFLAGS $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + archive_expsym_cmds_CXX='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ + $CC -G -nostdlib ${wl}-M $wl$lib.exp -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + + # Commands to make compiler produce verbose output that lists + # what "hidden" libraries, object files and flags are used when + # linking a shared library. + output_verbose_link_cmd='$CC -G $CFLAGS -v conftest.$objext 2>&1 | $GREP "\-L"' + fi + + hardcode_libdir_flag_spec_CXX='${wl}-R $wl$libdir' + case $host_os in + solaris2.[0-5] | solaris2.[0-5].*) ;; + *) + whole_archive_flag_spec_CXX='${wl}-z ${wl}allextract$convenience ${wl}-z ${wl}defaultextract' + ;; + esac + fi + ;; + esac + ;; + + sysv4*uw2* | sysv5OpenUNIX* | sysv5UnixWare7.[01].[10]* | unixware7* | sco3.2v5.0.[024]*) + no_undefined_flag_CXX='${wl}-z,text' + archive_cmds_need_lc_CXX=no + hardcode_shlibpath_var_CXX=no + runpath_var='LD_RUN_PATH' + + case $cc_basename in + CC*) + archive_cmds_CXX='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds_CXX='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + *) + archive_cmds_CXX='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds_CXX='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + esac + ;; + + sysv5* | sco3.2v5* | sco5v6*) + # Note: We can NOT use -z defs as we might desire, because we do not + # link with -lc, and that would cause any symbols used from libc to + # always be unresolved, which means just about no library would + # ever link correctly. If we're not using GNU ld we use -z text + # though, which does catch some bad symbols but isn't as heavy-handed + # as -z defs. + no_undefined_flag_CXX='${wl}-z,text' + allow_undefined_flag_CXX='${wl}-z,nodefs' + archive_cmds_need_lc_CXX=no + hardcode_shlibpath_var_CXX=no + hardcode_libdir_flag_spec_CXX='${wl}-R,$libdir' + hardcode_libdir_separator_CXX=':' + link_all_deplibs_CXX=yes + export_dynamic_flag_spec_CXX='${wl}-Bexport' + runpath_var='LD_RUN_PATH' + + case $cc_basename in + CC*) + archive_cmds_CXX='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds_CXX='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + *) + archive_cmds_CXX='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds_CXX='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + ;; + esac + ;; + + tandem*) + case $cc_basename in + NCC*) + # NonStop-UX NCC 3.20 + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + *) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + esac + ;; + + vxworks*) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + + *) + # FIXME: insert proper C++ library support + ld_shlibs_CXX=no + ;; + esac + + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ld_shlibs_CXX" >&5 +$as_echo "$ld_shlibs_CXX" >&6; } + test "$ld_shlibs_CXX" = no && can_build_shared=no + + GCC_CXX="$GXX" + LD_CXX="$LD" + + ## CAVEAT EMPTOR: + ## There is no encapsulation within the following macros, do not change + ## the running order or otherwise move them around unless you know exactly + ## what you are doing... + # Dependencies to place before and after the object being linked: +predep_objects_CXX= +postdep_objects_CXX= +predeps_CXX= +postdeps_CXX= +compiler_lib_search_path_CXX= + +cat > conftest.$ac_ext <<_LT_EOF +class Foo +{ +public: + Foo (void) { a = 0; } +private: + int a; +}; +_LT_EOF + +if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 + (eval $ac_compile) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + # Parse the compiler output and extract the necessary + # objects, libraries and library flags. + + # Sentinel used to keep track of whether or not we are before + # the conftest object file. + pre_test_object_deps_done=no + + for p in `eval "$output_verbose_link_cmd"`; do + case $p in + + -L* | -R* | -l*) + # Some compilers place space between "-{L,R}" and the path. + # Remove the space. + if test $p = "-L" || + test $p = "-R"; then + prev=$p + continue + else + prev= + fi + + if test "$pre_test_object_deps_done" = no; then + case $p in + -L* | -R*) + # Internal compiler library paths should come after those + # provided the user. The postdeps already come after the + # user supplied libs so there is no need to process them. + if test -z "$compiler_lib_search_path_CXX"; then + compiler_lib_search_path_CXX="${prev}${p}" + else + compiler_lib_search_path_CXX="${compiler_lib_search_path_CXX} ${prev}${p}" + fi + ;; + # The "-l" case would never come before the object being + # linked, so don't bother handling this case. + esac + else + if test -z "$postdeps_CXX"; then + postdeps_CXX="${prev}${p}" + else + postdeps_CXX="${postdeps_CXX} ${prev}${p}" + fi + fi + ;; + + *.$objext) + # This assumes that the test object file only shows up + # once in the compiler output. + if test "$p" = "conftest.$objext"; then + pre_test_object_deps_done=yes + continue + fi + + if test "$pre_test_object_deps_done" = no; then + if test -z "$predep_objects_CXX"; then + predep_objects_CXX="$p" + else + predep_objects_CXX="$predep_objects_CXX $p" + fi + else + if test -z "$postdep_objects_CXX"; then + postdep_objects_CXX="$p" + else + postdep_objects_CXX="$postdep_objects_CXX $p" + fi + fi + ;; + + *) ;; # Ignore the rest. + + esac + done + + # Clean up. + rm -f a.out a.exe +else + echo "libtool.m4: error: problem compiling CXX test program" +fi + +$RM -f confest.$objext + +# PORTME: override above test on systems where it is broken +case $host_os in +interix[3-9]*) + # Interix 3.5 installs completely hosed .la files for C++, so rather than + # hack all around it, let's just trust "g++" to DTRT. + predep_objects_CXX= + postdep_objects_CXX= + postdeps_CXX= + ;; + +linux*) + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) + # Sun C++ 5.9 + + # The more standards-conforming stlport4 library is + # incompatible with the Cstd library. Avoid specifying + # it if it's in CXXFLAGS. Ignore libCrun as + # -library=stlport4 depends on it. + case " $CXX $CXXFLAGS " in + *" -library=stlport4 "*) + solaris_use_stlport4=yes + ;; + esac + + if test "$solaris_use_stlport4" != yes; then + postdeps_CXX='-library=Cstd -library=Crun' + fi + ;; + esac + ;; + +solaris*) + case $cc_basename in + CC*) + # The more standards-conforming stlport4 library is + # incompatible with the Cstd library. Avoid specifying + # it if it's in CXXFLAGS. Ignore libCrun as + # -library=stlport4 depends on it. + case " $CXX $CXXFLAGS " in + *" -library=stlport4 "*) + solaris_use_stlport4=yes + ;; + esac + + # Adding this requires a known-good setup of shared libraries for + # Sun compiler versions before 5.6, else PIC objects from an old + # archive will be linked into the output, leading to subtle bugs. + if test "$solaris_use_stlport4" != yes; then + postdeps_CXX='-library=Cstd -library=Crun' + fi + ;; + esac + ;; +esac + + +case " $postdeps_CXX " in +*" -lc "*) archive_cmds_need_lc_CXX=no ;; +esac + compiler_lib_search_dirs_CXX= +if test -n "${compiler_lib_search_path_CXX}"; then + compiler_lib_search_dirs_CXX=`echo " ${compiler_lib_search_path_CXX}" | ${SED} -e 's! -L! !g' -e 's!^ !!'` +fi + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + lt_prog_compiler_wl_CXX= +lt_prog_compiler_pic_CXX= +lt_prog_compiler_static_CXX= + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $compiler option to produce PIC" >&5 +$as_echo_n "checking for $compiler option to produce PIC... " >&6; } + + # C++ specific cases for pic, static, wl, etc. + if test "$GXX" = yes; then + lt_prog_compiler_wl_CXX='-Wl,' + lt_prog_compiler_static_CXX='-static' + + case $host_os in + aix*) + # All AIX code is PIC. + if test "$host_cpu" = ia64; then + # AIX 5 now supports IA64 processor + lt_prog_compiler_static_CXX='-Bstatic' + fi + ;; + + amigaos*) + case $host_cpu in + powerpc) + # see comment about AmigaOS4 .so support + lt_prog_compiler_pic_CXX='-fPIC' + ;; + m68k) + # FIXME: we need at least 68020 code to build shared libraries, but + # adding the `-m68020' flag to GCC prevents building anything better, + # like `-m68040'. + lt_prog_compiler_pic_CXX='-m68020 -resident32 -malways-restore-a4' + ;; + esac + ;; + + beos* | irix5* | irix6* | nonstopux* | osf3* | osf4* | osf5*) + # PIC is the default for these OSes. + ;; + mingw* | cygwin* | os2* | pw32* | cegcc*) + # This hack is so that the source file can tell whether it is being + # built for inclusion in a dll (and should export symbols for example). + # Although the cygwin gcc ignores -fPIC, still need this for old-style + # (--disable-auto-import) libraries + lt_prog_compiler_pic_CXX='-DDLL_EXPORT' + ;; + darwin* | rhapsody*) + # PIC is the default on this platform + # Common symbols not allowed in MH_DYLIB files + lt_prog_compiler_pic_CXX='-fno-common' + ;; + *djgpp*) + # DJGPP does not support shared libraries at all + lt_prog_compiler_pic_CXX= + ;; + interix[3-9]*) + # Interix 3.x gcc -fpic/-fPIC options generate broken code. + # Instead, we relocate shared libraries at runtime. + ;; + sysv4*MP*) + if test -d /usr/nec; then + lt_prog_compiler_pic_CXX=-Kconform_pic + fi + ;; + hpux*) + # PIC is the default for 64-bit PA HP-UX, but not for 32-bit + # PA HP-UX. On IA64 HP-UX, PIC is the default but the pic flag + # sets the default TLS model and affects inlining. + case $host_cpu in + hppa*64*) + ;; + *) + lt_prog_compiler_pic_CXX='-fPIC' + ;; + esac + ;; + *qnx* | *nto*) + # QNX uses GNU C++, but need to define -shared option too, otherwise + # it will coredump. + lt_prog_compiler_pic_CXX='-fPIC -shared' + ;; + *) + lt_prog_compiler_pic_CXX='-fPIC' + ;; + esac + else + case $host_os in + aix[4-9]*) + # All AIX code is PIC. + if test "$host_cpu" = ia64; then + # AIX 5 now supports IA64 processor + lt_prog_compiler_static_CXX='-Bstatic' + else + lt_prog_compiler_static_CXX='-bnso -bI:/lib/syscalls.exp' + fi + ;; + chorus*) + case $cc_basename in + cxch68*) + # Green Hills C++ Compiler + # _LT_TAGVAR(lt_prog_compiler_static, CXX)="--no_auto_instantiation -u __main -u __premain -u _abort -r $COOL_DIR/lib/libOrb.a $MVME_DIR/lib/CC/libC.a $MVME_DIR/lib/classix/libcx.s.a" + ;; + esac + ;; + dgux*) + case $cc_basename in + ec++*) + lt_prog_compiler_pic_CXX='-KPIC' + ;; + ghcx*) + # Green Hills C++ Compiler + lt_prog_compiler_pic_CXX='-pic' + ;; + *) + ;; + esac + ;; + freebsd* | dragonfly*) + # FreeBSD uses GNU C++ + ;; + hpux9* | hpux10* | hpux11*) + case $cc_basename in + CC*) + lt_prog_compiler_wl_CXX='-Wl,' + lt_prog_compiler_static_CXX='${wl}-a ${wl}archive' + if test "$host_cpu" != ia64; then + lt_prog_compiler_pic_CXX='+Z' + fi + ;; + aCC*) + lt_prog_compiler_wl_CXX='-Wl,' + lt_prog_compiler_static_CXX='${wl}-a ${wl}archive' + case $host_cpu in + hppa*64*|ia64*) + # +Z the default + ;; + *) + lt_prog_compiler_pic_CXX='+Z' + ;; + esac + ;; + *) + ;; + esac + ;; + interix*) + # This is c89, which is MS Visual C++ (no shared libs) + # Anyone wants to do a port? + ;; + irix5* | irix6* | nonstopux*) + case $cc_basename in + CC*) + lt_prog_compiler_wl_CXX='-Wl,' + lt_prog_compiler_static_CXX='-non_shared' + # CC pic flag -KPIC is the default. + ;; + *) + ;; + esac + ;; + linux* | k*bsd*-gnu | kopensolaris*-gnu) + case $cc_basename in + KCC*) + # KAI C++ Compiler + lt_prog_compiler_wl_CXX='--backend -Wl,' + lt_prog_compiler_pic_CXX='-fPIC' + ;; + ecpc* ) + # old Intel C++ for x86_64 which still supported -KPIC. + lt_prog_compiler_wl_CXX='-Wl,' + lt_prog_compiler_pic_CXX='-KPIC' + lt_prog_compiler_static_CXX='-static' + ;; + icpc* ) + # Intel C++, used to be incompatible with GCC. + # ICC 10 doesn't accept -KPIC any more. + lt_prog_compiler_wl_CXX='-Wl,' + lt_prog_compiler_pic_CXX='-fPIC' + lt_prog_compiler_static_CXX='-static' + ;; + pgCC* | pgcpp*) + # Portland Group C++ compiler + lt_prog_compiler_wl_CXX='-Wl,' + lt_prog_compiler_pic_CXX='-fpic' + lt_prog_compiler_static_CXX='-Bstatic' + ;; + cxx*) + # Compaq C++ + # Make sure the PIC flag is empty. It appears that all Alpha + # Linux and Compaq Tru64 Unix objects are PIC. + lt_prog_compiler_pic_CXX= + lt_prog_compiler_static_CXX='-non_shared' + ;; + xlc* | xlC*) + # IBM XL 8.0 on PPC + lt_prog_compiler_wl_CXX='-Wl,' + lt_prog_compiler_pic_CXX='-qpic' + lt_prog_compiler_static_CXX='-qstaticlink' + ;; + *) + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) + # Sun C++ 5.9 + lt_prog_compiler_pic_CXX='-KPIC' + lt_prog_compiler_static_CXX='-Bstatic' + lt_prog_compiler_wl_CXX='-Qoption ld ' + ;; + esac + ;; + esac + ;; + lynxos*) + ;; + m88k*) + ;; + mvs*) + case $cc_basename in + cxx*) + lt_prog_compiler_pic_CXX='-W c,exportall' + ;; + *) + ;; + esac + ;; + netbsd* | netbsdelf*-gnu) + ;; + *qnx* | *nto*) + # QNX uses GNU C++, but need to define -shared option too, otherwise + # it will coredump. + lt_prog_compiler_pic_CXX='-fPIC -shared' + ;; + osf3* | osf4* | osf5*) + case $cc_basename in + KCC*) + lt_prog_compiler_wl_CXX='--backend -Wl,' + ;; + RCC*) + # Rational C++ 2.4.1 + lt_prog_compiler_pic_CXX='-pic' + ;; + cxx*) + # Digital/Compaq C++ + lt_prog_compiler_wl_CXX='-Wl,' + # Make sure the PIC flag is empty. It appears that all Alpha + # Linux and Compaq Tru64 Unix objects are PIC. + lt_prog_compiler_pic_CXX= + lt_prog_compiler_static_CXX='-non_shared' + ;; + *) + ;; + esac + ;; + psos*) + ;; + solaris*) + case $cc_basename in + CC*) + # Sun C++ 4.2, 5.x and Centerline C++ + lt_prog_compiler_pic_CXX='-KPIC' + lt_prog_compiler_static_CXX='-Bstatic' + lt_prog_compiler_wl_CXX='-Qoption ld ' + ;; + gcx*) + # Green Hills C++ Compiler + lt_prog_compiler_pic_CXX='-PIC' + ;; + *) + ;; + esac + ;; + sunos4*) + case $cc_basename in + CC*) + # Sun C++ 4.x + lt_prog_compiler_pic_CXX='-pic' + lt_prog_compiler_static_CXX='-Bstatic' + ;; + lcc*) + # Lucid + lt_prog_compiler_pic_CXX='-pic' + ;; + *) + ;; + esac + ;; + sysv5* | unixware* | sco3.2v5* | sco5v6* | OpenUNIX*) + case $cc_basename in + CC*) + lt_prog_compiler_wl_CXX='-Wl,' + lt_prog_compiler_pic_CXX='-KPIC' + lt_prog_compiler_static_CXX='-Bstatic' + ;; + esac + ;; + tandem*) + case $cc_basename in + NCC*) + # NonStop-UX NCC 3.20 + lt_prog_compiler_pic_CXX='-KPIC' + ;; + *) + ;; + esac + ;; + vxworks*) + ;; + *) + lt_prog_compiler_can_build_shared_CXX=no + ;; + esac + fi + +case $host_os in + # For platforms which do not support PIC, -DPIC is meaningless: + *djgpp*) + lt_prog_compiler_pic_CXX= + ;; + *) + lt_prog_compiler_pic_CXX="$lt_prog_compiler_pic_CXX -DPIC" + ;; +esac +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_prog_compiler_pic_CXX" >&5 +$as_echo "$lt_prog_compiler_pic_CXX" >&6; } + + + +# +# Check to make sure the PIC flag actually works. +# +if test -n "$lt_prog_compiler_pic_CXX"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: checking if $compiler PIC flag $lt_prog_compiler_pic_CXX works" >&5 +$as_echo_n "checking if $compiler PIC flag $lt_prog_compiler_pic_CXX works... " >&6; } +if test "${lt_cv_prog_compiler_pic_works_CXX+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_prog_compiler_pic_works_CXX=no + ac_outfile=conftest.$ac_objext + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + lt_compiler_flag="$lt_prog_compiler_pic_CXX -DPIC" + # Insert the option either (1) after the last *FLAGS variable, or + # (2) before a word containing "conftest.", or (3) at the end. + # Note that $ac_compile itself does not contain backslashes and begins + # with a dollar sign (not a hyphen), so the echo should work correctly. + # The option is referenced via a variable to avoid confusing sed. + lt_compile=`echo "$ac_compile" | $SED \ + -e 's:.*FLAGS}\{0,1\} :&$lt_compiler_flag :; t' \ + -e 's: [^ ]*conftest\.: $lt_compiler_flag&:; t' \ + -e 's:$: $lt_compiler_flag:'` + (eval echo "\"\$as_me:14474: $lt_compile\"" >&5) + (eval "$lt_compile" 2>conftest.err) + ac_status=$? + cat conftest.err >&5 + echo "$as_me:14478: \$? = $ac_status" >&5 + if (exit $ac_status) && test -s "$ac_outfile"; then + # The compiler can only warn and ignore the option if not recognized + # So say no if there are warnings other than the usual output. + $ECHO "X$_lt_compiler_boilerplate" | $Xsed -e '/^$/d' >conftest.exp + $SED '/^$/d; /^ *+/d' conftest.err >conftest.er2 + if test ! -s conftest.er2 || diff conftest.exp conftest.er2 >/dev/null; then + lt_cv_prog_compiler_pic_works_CXX=yes + fi + fi + $RM conftest* + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_pic_works_CXX" >&5 +$as_echo "$lt_cv_prog_compiler_pic_works_CXX" >&6; } + +if test x"$lt_cv_prog_compiler_pic_works_CXX" = xyes; then + case $lt_prog_compiler_pic_CXX in + "" | " "*) ;; + *) lt_prog_compiler_pic_CXX=" $lt_prog_compiler_pic_CXX" ;; + esac +else + lt_prog_compiler_pic_CXX= + lt_prog_compiler_can_build_shared_CXX=no +fi + +fi + + + +# +# Check to make sure the static flag actually works. +# +wl=$lt_prog_compiler_wl_CXX eval lt_tmp_static_flag=\"$lt_prog_compiler_static_CXX\" +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking if $compiler static flag $lt_tmp_static_flag works" >&5 +$as_echo_n "checking if $compiler static flag $lt_tmp_static_flag works... " >&6; } +if test "${lt_cv_prog_compiler_static_works_CXX+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_prog_compiler_static_works_CXX=no + save_LDFLAGS="$LDFLAGS" + LDFLAGS="$LDFLAGS $lt_tmp_static_flag" + echo "$lt_simple_link_test_code" > conftest.$ac_ext + if (eval $ac_link 2>conftest.err) && test -s conftest$ac_exeext; then + # The linker can only warn and ignore the option if not recognized + # So say no if there are warnings + if test -s conftest.err; then + # Append any errors to the config.log. + cat conftest.err 1>&5 + $ECHO "X$_lt_linker_boilerplate" | $Xsed -e '/^$/d' > conftest.exp + $SED '/^$/d; /^ *+/d' conftest.err >conftest.er2 + if diff conftest.exp conftest.er2 >/dev/null; then + lt_cv_prog_compiler_static_works_CXX=yes + fi + else + lt_cv_prog_compiler_static_works_CXX=yes + fi + fi + $RM -r conftest* + LDFLAGS="$save_LDFLAGS" + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_static_works_CXX" >&5 +$as_echo "$lt_cv_prog_compiler_static_works_CXX" >&6; } + +if test x"$lt_cv_prog_compiler_static_works_CXX" = xyes; then + : +else + lt_prog_compiler_static_CXX= +fi + + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking if $compiler supports -c -o file.$ac_objext" >&5 +$as_echo_n "checking if $compiler supports -c -o file.$ac_objext... " >&6; } +if test "${lt_cv_prog_compiler_c_o_CXX+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_prog_compiler_c_o_CXX=no + $RM -r conftest 2>/dev/null + mkdir conftest + cd conftest + mkdir out + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + + lt_compiler_flag="-o out/conftest2.$ac_objext" + # Insert the option either (1) after the last *FLAGS variable, or + # (2) before a word containing "conftest.", or (3) at the end. + # Note that $ac_compile itself does not contain backslashes and begins + # with a dollar sign (not a hyphen), so the echo should work correctly. + lt_compile=`echo "$ac_compile" | $SED \ + -e 's:.*FLAGS}\{0,1\} :&$lt_compiler_flag :; t' \ + -e 's: [^ ]*conftest\.: $lt_compiler_flag&:; t' \ + -e 's:$: $lt_compiler_flag:'` + (eval echo "\"\$as_me:14573: $lt_compile\"" >&5) + (eval "$lt_compile" 2>out/conftest.err) + ac_status=$? + cat out/conftest.err >&5 + echo "$as_me:14577: \$? = $ac_status" >&5 + if (exit $ac_status) && test -s out/conftest2.$ac_objext + then + # The compiler can only warn and ignore the option if not recognized + # So say no if there are warnings + $ECHO "X$_lt_compiler_boilerplate" | $Xsed -e '/^$/d' > out/conftest.exp + $SED '/^$/d; /^ *+/d' out/conftest.err >out/conftest.er2 + if test ! -s out/conftest.er2 || diff out/conftest.exp out/conftest.er2 >/dev/null; then + lt_cv_prog_compiler_c_o_CXX=yes + fi + fi + chmod u+w . 2>&5 + $RM conftest* + # SGI C++ compiler will create directory out/ii_files/ for + # template instantiation + test -d out/ii_files && $RM out/ii_files/* && rmdir out/ii_files + $RM out/* && rmdir out + cd .. + $RM -r conftest + $RM conftest* + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_c_o_CXX" >&5 +$as_echo "$lt_cv_prog_compiler_c_o_CXX" >&6; } + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking if $compiler supports -c -o file.$ac_objext" >&5 +$as_echo_n "checking if $compiler supports -c -o file.$ac_objext... " >&6; } +if test "${lt_cv_prog_compiler_c_o_CXX+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_prog_compiler_c_o_CXX=no + $RM -r conftest 2>/dev/null + mkdir conftest + cd conftest + mkdir out + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + + lt_compiler_flag="-o out/conftest2.$ac_objext" + # Insert the option either (1) after the last *FLAGS variable, or + # (2) before a word containing "conftest.", or (3) at the end. + # Note that $ac_compile itself does not contain backslashes and begins + # with a dollar sign (not a hyphen), so the echo should work correctly. + lt_compile=`echo "$ac_compile" | $SED \ + -e 's:.*FLAGS}\{0,1\} :&$lt_compiler_flag :; t' \ + -e 's: [^ ]*conftest\.: $lt_compiler_flag&:; t' \ + -e 's:$: $lt_compiler_flag:'` + (eval echo "\"\$as_me:14625: $lt_compile\"" >&5) + (eval "$lt_compile" 2>out/conftest.err) + ac_status=$? + cat out/conftest.err >&5 + echo "$as_me:14629: \$? = $ac_status" >&5 + if (exit $ac_status) && test -s out/conftest2.$ac_objext + then + # The compiler can only warn and ignore the option if not recognized + # So say no if there are warnings + $ECHO "X$_lt_compiler_boilerplate" | $Xsed -e '/^$/d' > out/conftest.exp + $SED '/^$/d; /^ *+/d' out/conftest.err >out/conftest.er2 + if test ! -s out/conftest.er2 || diff out/conftest.exp out/conftest.er2 >/dev/null; then + lt_cv_prog_compiler_c_o_CXX=yes + fi + fi + chmod u+w . 2>&5 + $RM conftest* + # SGI C++ compiler will create directory out/ii_files/ for + # template instantiation + test -d out/ii_files && $RM out/ii_files/* && rmdir out/ii_files + $RM out/* && rmdir out + cd .. + $RM -r conftest + $RM conftest* + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_c_o_CXX" >&5 +$as_echo "$lt_cv_prog_compiler_c_o_CXX" >&6; } + + + + +hard_links="nottested" +if test "$lt_cv_prog_compiler_c_o_CXX" = no && test "$need_locks" != no; then + # do not overwrite the value of need_locks provided by the user + { $as_echo "$as_me:${as_lineno-$LINENO}: checking if we can lock with hard links" >&5 +$as_echo_n "checking if we can lock with hard links... " >&6; } + hard_links=yes + $RM conftest* + ln conftest.a conftest.b 2>/dev/null && hard_links=no + touch conftest.a + ln conftest.a conftest.b 2>&5 || hard_links=no + ln conftest.a conftest.b 2>/dev/null && hard_links=no + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $hard_links" >&5 +$as_echo "$hard_links" >&6; } + if test "$hard_links" = no; then + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: \`$CC' does not support \`-c -o', so \`make -j' may be unsafe" >&5 +$as_echo "$as_me: WARNING: \`$CC' does not support \`-c -o', so \`make -j' may be unsafe" >&2;} + need_locks=warn + fi +else + need_locks=no +fi + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether the $compiler linker ($LD) supports shared libraries" >&5 +$as_echo_n "checking whether the $compiler linker ($LD) supports shared libraries... " >&6; } + + export_symbols_cmds_CXX='$NM $libobjs $convenience | $global_symbol_pipe | $SED '\''s/.* //'\'' | sort | uniq > $export_symbols' + case $host_os in + aix[4-9]*) + # If we're using GNU nm, then we don't want the "-C" option. + # -C means demangle to AIX nm, but means don't demangle with GNU nm + if $NM -V 2>&1 | $GREP 'GNU' > /dev/null; then + export_symbols_cmds_CXX='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && (substr(\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + else + export_symbols_cmds_CXX='$NM -BCpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && (substr(\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + fi + ;; + pw32*) + export_symbols_cmds_CXX="$ltdll_cmds" + ;; + cygwin* | mingw* | cegcc*) + export_symbols_cmds_CXX='$NM $libobjs $convenience | $global_symbol_pipe | $SED -e '\''/^[BCDGRS][ ]/s/.*[ ]\([^ ]*\)/\1 DATA/;/^.*[ ]__nm__/s/^.*[ ]__nm__\([^ ]*\)[ ][^ ]*/\1 DATA/;/^I[ ]/d;/^[AITW][ ]/s/.* //'\'' | sort | uniq > $export_symbols' + ;; + linux* | k*bsd*-gnu) + link_all_deplibs_CXX=no + ;; + *) + export_symbols_cmds_CXX='$NM $libobjs $convenience | $global_symbol_pipe | $SED '\''s/.* //'\'' | sort | uniq > $export_symbols' + ;; + esac + exclude_expsyms_CXX='_GLOBAL_OFFSET_TABLE_|_GLOBAL__F[ID]_.*' + +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ld_shlibs_CXX" >&5 +$as_echo "$ld_shlibs_CXX" >&6; } +test "$ld_shlibs_CXX" = no && can_build_shared=no + +with_gnu_ld_CXX=$with_gnu_ld + + + + + + +# +# Do we need to explicitly link libc? +# +case "x$archive_cmds_need_lc_CXX" in +x|xyes) + # Assume -lc should be added + archive_cmds_need_lc_CXX=yes + + if test "$enable_shared" = yes && test "$GCC" = yes; then + case $archive_cmds_CXX in + *'~'*) + # FIXME: we may have to deal with multi-command sequences. + ;; + '$CC '*) + # Test whether the compiler implicitly links with -lc since on some + # systems, -lgcc has to come before -lc. If gcc already passes -lc + # to ld, don't add -lc before -lgcc. + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether -lc should be explicitly linked in" >&5 +$as_echo_n "checking whether -lc should be explicitly linked in... " >&6; } + $RM conftest* + echo "$lt_simple_compile_test_code" > conftest.$ac_ext + + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 + (eval $ac_compile) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } 2>conftest.err; then + soname=conftest + lib=conftest + libobjs=conftest.$ac_objext + deplibs= + wl=$lt_prog_compiler_wl_CXX + pic_flag=$lt_prog_compiler_pic_CXX + compiler_flags=-v + linker_flags=-v + verstring= + output_objdir=. + libname=conftest + lt_save_allow_undefined_flag=$allow_undefined_flag_CXX + allow_undefined_flag_CXX= + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$archive_cmds_CXX 2\>\&1 \| $GREP \" -lc \" \>/dev/null 2\>\&1\""; } >&5 + (eval $archive_cmds_CXX 2\>\&1 \| $GREP \" -lc \" \>/dev/null 2\>\&1) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } + then + archive_cmds_need_lc_CXX=no + else + archive_cmds_need_lc_CXX=yes + fi + allow_undefined_flag_CXX=$lt_save_allow_undefined_flag + else + cat conftest.err 1>&5 + fi + $RM conftest* + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $archive_cmds_need_lc_CXX" >&5 +$as_echo "$archive_cmds_need_lc_CXX" >&6; } + ;; + esac + fi + ;; +esac + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking dynamic linker characteristics" >&5 +$as_echo_n "checking dynamic linker characteristics... " >&6; } + +library_names_spec= +libname_spec='lib$name' +soname_spec= +shrext_cmds=".so" +postinstall_cmds= +postuninstall_cmds= +finish_cmds= +finish_eval= +shlibpath_var= +shlibpath_overrides_runpath=unknown +version_type=none +dynamic_linker="$host_os ld.so" +sys_lib_dlsearch_path_spec="/lib /usr/lib" +need_lib_prefix=unknown +hardcode_into_libs=no + +# when you set need_version to no, make sure it does not cause -set_version +# flags to be left without arguments +need_version=unknown + +case $host_os in +aix3*) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix $libname.a' + shlibpath_var=LIBPATH + + # AIX 3 has no versioning support, so we append a major version to the name. + soname_spec='${libname}${release}${shared_ext}$major' + ;; + +aix[4-9]*) + version_type=linux + need_lib_prefix=no + need_version=no + hardcode_into_libs=yes + if test "$host_cpu" = ia64; then + # AIX 5 supports IA64 + library_names_spec='${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext}$versuffix $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + else + # With GCC up to 2.95.x, collect2 would create an import file + # for dependence libraries. The import file would start with + # the line `#! .'. This would cause the generated library to + # depend on `.', always an invalid library. This was fixed in + # development snapshots of GCC prior to 3.0. + case $host_os in + aix4 | aix4.[01] | aix4.[01].*) + if { echo '#if __GNUC__ > 2 || (__GNUC__ == 2 && __GNUC_MINOR__ >= 97)' + echo ' yes ' + echo '#endif'; } | ${CC} -E - | $GREP yes > /dev/null; then + : + else + can_build_shared=no + fi + ;; + esac + # AIX (on Power*) has no versioning support, so currently we can not hardcode correct + # soname into executable. Probably we can add versioning support to + # collect2, so additional links can be useful in future. + if test "$aix_use_runtimelinking" = yes; then + # If using run time linking (on AIX 4.2 or later) use lib.so + # instead of lib.a to let people know that these are not + # typical AIX shared libraries. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + else + # We preserve .a as extension for shared libraries through AIX4.2 + # and later when we are not doing run time linking. + library_names_spec='${libname}${release}.a $libname.a' + soname_spec='${libname}${release}${shared_ext}$major' + fi + shlibpath_var=LIBPATH + fi + ;; + +amigaos*) + case $host_cpu in + powerpc) + # Since July 2007 AmigaOS4 officially supports .so libraries. + # When compiling the executable, add -use-dynld -Lsobjs: to the compileline. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + ;; + m68k) + library_names_spec='$libname.ixlibrary $libname.a' + # Create ${libname}_ixlibrary.a entries in /sys/libs. + finish_eval='for lib in `ls $libdir/*.ixlibrary 2>/dev/null`; do libname=`$ECHO "X$lib" | $Xsed -e '\''s%^.*/\([^/]*\)\.ixlibrary$%\1%'\''`; test $RM /sys/libs/${libname}_ixlibrary.a; $show "cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a"; cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a || exit 1; done' + ;; + esac + ;; + +beos*) + library_names_spec='${libname}${shared_ext}' + dynamic_linker="$host_os ld.so" + shlibpath_var=LIBRARY_PATH + ;; + +bsdi[45]*) + version_type=linux + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + finish_cmds='PATH="\$PATH:/sbin" ldconfig $libdir' + shlibpath_var=LD_LIBRARY_PATH + sys_lib_search_path_spec="/shlib /usr/lib /usr/X11/lib /usr/contrib/lib /lib /usr/local/lib" + sys_lib_dlsearch_path_spec="/shlib /usr/lib /usr/local/lib" + # the default ld.so.conf also contains /usr/contrib/lib and + # /usr/X11R6/lib (/usr/X11 is a link to /usr/X11R6), but let us allow + # libtool to hard-code these into programs + ;; + +cygwin* | mingw* | pw32* | cegcc*) + version_type=windows + shrext_cmds=".dll" + need_version=no + need_lib_prefix=no + + case $GCC,$host_os in + yes,cygwin* | yes,mingw* | yes,pw32* | yes,cegcc*) + library_names_spec='$libname.dll.a' + # DLL is installed to $(libdir)/../bin by postinstall_cmds + postinstall_cmds='base_file=`basename \${file}`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\${base_file}'\''i; echo \$dlname'\''`~ + dldir=$destdir/`dirname \$dlpath`~ + test -d \$dldir || mkdir -p \$dldir~ + $install_prog $dir/$dlname \$dldir/$dlname~ + chmod a+x \$dldir/$dlname~ + if test -n '\''$stripme'\'' && test -n '\''$striplib'\''; then + eval '\''$striplib \$dldir/$dlname'\'' || exit \$?; + fi' + postuninstall_cmds='dldll=`$SHELL 2>&1 -c '\''. $file; echo \$dlname'\''`~ + dlpath=$dir/\$dldll~ + $RM \$dlpath' + shlibpath_overrides_runpath=yes + + case $host_os in + cygwin*) + # Cygwin DLLs use 'cyg' prefix rather than 'lib' + soname_spec='`echo ${libname} | sed -e 's/^lib/cyg/'``echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + sys_lib_search_path_spec="/usr/lib /lib/w32api /lib /usr/local/lib" + ;; + mingw* | cegcc*) + # MinGW DLLs use traditional 'lib' prefix + soname_spec='${libname}`echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + sys_lib_search_path_spec=`$CC -print-search-dirs | $GREP "^libraries:" | $SED -e "s/^libraries://" -e "s,=/,/,g"` + if $ECHO "$sys_lib_search_path_spec" | $GREP ';[c-zC-Z]:/' >/dev/null; then + # It is most probably a Windows format PATH printed by + # mingw gcc, but we are running on Cygwin. Gcc prints its search + # path with ; separators, and with drive letters. We can handle the + # drive letters (cygwin fileutils understands them), so leave them, + # especially as we might pass files found there to a mingw objdump, + # which wouldn't understand a cygwinified path. Ahh. + sys_lib_search_path_spec=`$ECHO "$sys_lib_search_path_spec" | $SED -e 's/;/ /g'` + else + sys_lib_search_path_spec=`$ECHO "$sys_lib_search_path_spec" | $SED -e "s/$PATH_SEPARATOR/ /g"` + fi + ;; + pw32*) + # pw32 DLLs use 'pw' prefix rather than 'lib' + library_names_spec='`echo ${libname} | sed -e 's/^lib/pw/'``echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + ;; + esac + ;; + + *) + library_names_spec='${libname}`echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext} $libname.lib' + ;; + esac + dynamic_linker='Win32 ld.exe' + # FIXME: first we should search . and the directory the executable is in + shlibpath_var=PATH + ;; + +darwin* | rhapsody*) + dynamic_linker="$host_os dyld" + version_type=darwin + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${major}$shared_ext ${libname}$shared_ext' + soname_spec='${libname}${release}${major}$shared_ext' + shlibpath_overrides_runpath=yes + shlibpath_var=DYLD_LIBRARY_PATH + shrext_cmds='`test .$module = .yes && echo .so || echo .dylib`' + + sys_lib_dlsearch_path_spec='/usr/local/lib /lib /usr/lib' + ;; + +dgux*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname$shared_ext' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + ;; + +freebsd1*) + dynamic_linker=no + ;; + +freebsd* | dragonfly*) + # DragonFly does not have aout. When/if they implement a new + # versioning mechanism, adjust this. + if test -x /usr/bin/objformat; then + objformat=`/usr/bin/objformat` + else + case $host_os in + freebsd[123]*) objformat=aout ;; + *) objformat=elf ;; + esac + fi + version_type=freebsd-$objformat + case $version_type in + freebsd-elf*) + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' + need_version=no + need_lib_prefix=no + ;; + freebsd-*) + library_names_spec='${libname}${release}${shared_ext}$versuffix $libname${shared_ext}$versuffix' + need_version=yes + ;; + esac + shlibpath_var=LD_LIBRARY_PATH + case $host_os in + freebsd2*) + shlibpath_overrides_runpath=yes + ;; + freebsd3.[01]* | freebsdelf3.[01]*) + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + ;; + freebsd3.[2-9]* | freebsdelf3.[2-9]* | \ + freebsd4.[0-5] | freebsdelf4.[0-5] | freebsd4.1.1 | freebsdelf4.1.1) + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + ;; + *) # from 4.6 on, and DragonFly + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + ;; + esac + ;; + +gnu*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}${major} ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + hardcode_into_libs=yes + ;; + +hpux9* | hpux10* | hpux11*) + # Give a soname corresponding to the major version so that dld.sl refuses to + # link against other versions. + version_type=sunos + need_lib_prefix=no + need_version=no + case $host_cpu in + ia64*) + shrext_cmds='.so' + hardcode_into_libs=yes + dynamic_linker="$host_os dld.so" + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + if test "X$HPUX_IA64_MODE" = X32; then + sys_lib_search_path_spec="/usr/lib/hpux32 /usr/local/lib/hpux32 /usr/local/lib" + else + sys_lib_search_path_spec="/usr/lib/hpux64 /usr/local/lib/hpux64" + fi + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec + ;; + hppa*64*) + shrext_cmds='.sl' + hardcode_into_libs=yes + dynamic_linker="$host_os dld.sl" + shlibpath_var=LD_LIBRARY_PATH # How should we handle SHLIB_PATH + shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + sys_lib_search_path_spec="/usr/lib/pa20_64 /usr/ccs/lib/pa20_64" + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec + ;; + *) + shrext_cmds='.sl' + dynamic_linker="$host_os dld.sl" + shlibpath_var=SHLIB_PATH + shlibpath_overrides_runpath=no # +s is required to enable SHLIB_PATH + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + ;; + esac + # HP-UX runs *really* slowly unless shared libraries are mode 555. + postinstall_cmds='chmod 555 $lib' + ;; + +interix[3-9]*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + dynamic_linker='Interix 3.x ld.so.1 (PE, like ELF)' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + ;; + +irix5* | irix6* | nonstopux*) + case $host_os in + nonstopux*) version_type=nonstopux ;; + *) + if test "$lt_cv_prog_gnu_ld" = yes; then + version_type=linux + else + version_type=irix + fi ;; + esac + need_lib_prefix=no + need_version=no + soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext} $libname${shared_ext}' + case $host_os in + irix5* | nonstopux*) + libsuff= shlibsuff= + ;; + *) + case $LD in # libtool.m4 will add one of these switches to LD + *-32|*"-32 "|*-melf32bsmip|*"-melf32bsmip ") + libsuff= shlibsuff= libmagic=32-bit;; + *-n32|*"-n32 "|*-melf32bmipn32|*"-melf32bmipn32 ") + libsuff=32 shlibsuff=N32 libmagic=N32;; + *-64|*"-64 "|*-melf64bmip|*"-melf64bmip ") + libsuff=64 shlibsuff=64 libmagic=64-bit;; + *) libsuff= shlibsuff= libmagic=never-match;; + esac + ;; + esac + shlibpath_var=LD_LIBRARY${shlibsuff}_PATH + shlibpath_overrides_runpath=no + sys_lib_search_path_spec="/usr/lib${libsuff} /lib${libsuff} /usr/local/lib${libsuff}" + sys_lib_dlsearch_path_spec="/usr/lib${libsuff} /lib${libsuff}" + hardcode_into_libs=yes + ;; + +# No shared lib support for Linux oldld, aout, or coff. +linux*oldld* | linux*aout* | linux*coff*) + dynamic_linker=no + ;; + +# This must be Linux ELF. +linux* | k*bsd*-gnu | kopensolaris*-gnu) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + finish_cmds='PATH="\$PATH:/sbin" ldconfig -n $libdir' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + # Some binutils ld are patched to set DT_RUNPATH + save_LDFLAGS=$LDFLAGS + save_libdir=$libdir + eval "libdir=/foo; wl=\"$lt_prog_compiler_wl_CXX\"; \ + LDFLAGS=\"\$LDFLAGS $hardcode_libdir_flag_spec_CXX\"" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_link "$LINENO"; then : + if ($OBJDUMP -p conftest$ac_exeext) 2>/dev/null | grep "RUNPATH.*$libdir" >/dev/null; then : + shlibpath_overrides_runpath=yes +fi +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext + LDFLAGS=$save_LDFLAGS + libdir=$save_libdir + + # This implies no fast_install, which is unacceptable. + # Some rework will be needed to allow for fast_install + # before this can be enabled. + hardcode_into_libs=yes + + # Append ld.so.conf contents to the search path + if test -f /etc/ld.so.conf; then + lt_ld_extra=`awk '/^include / { system(sprintf("cd /etc; cat %s 2>/dev/null", \$2)); skip = 1; } { if (!skip) print \$0; skip = 0; }' < /etc/ld.so.conf | $SED -e 's/#.*//;/^[ ]*hwcap[ ]/d;s/[:, ]/ /g;s/=[^=]*$//;s/=[^= ]* / /g;/^$/d' | tr '\n' ' '` + sys_lib_dlsearch_path_spec="/lib /usr/lib $lt_ld_extra" + fi + + # We used to test for /lib/ld.so.1 and disable shared libraries on + # powerpc, because MkLinux only supported shared libraries with the + # GNU dynamic linker. Since this was broken with cross compilers, + # most powerpc-linux boxes support dynamic linking these days and + # people can always --disable-shared, the test was removed, and we + # assume the GNU/Linux dynamic linker is in use. + dynamic_linker='GNU/Linux ld.so' + ;; + +netbsdelf*-gnu) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + dynamic_linker='NetBSD ld.elf_so' + ;; + +netbsd*) + version_type=sunos + need_lib_prefix=no + need_version=no + if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' + dynamic_linker='NetBSD (a.out) ld.so' + else + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + dynamic_linker='NetBSD ld.elf_so' + fi + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + ;; + +newsos6) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + ;; + +*nto* | *qnx*) + version_type=qnx + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + dynamic_linker='ldqnx.so' + ;; + +openbsd*) + version_type=sunos + sys_lib_dlsearch_path_spec="/usr/lib" + need_lib_prefix=no + # Some older versions of OpenBSD (3.3 at least) *do* need versioned libs. + case $host_os in + openbsd3.3 | openbsd3.3.*) need_version=yes ;; + *) need_version=no ;; + esac + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' + shlibpath_var=LD_LIBRARY_PATH + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + case $host_os in + openbsd2.[89] | openbsd2.[89].*) + shlibpath_overrides_runpath=no + ;; + *) + shlibpath_overrides_runpath=yes + ;; + esac + else + shlibpath_overrides_runpath=yes + fi + ;; + +os2*) + libname_spec='$name' + shrext_cmds=".dll" + need_lib_prefix=no + library_names_spec='$libname${shared_ext} $libname.a' + dynamic_linker='OS/2 ld.exe' + shlibpath_var=LIBPATH + ;; + +osf3* | osf4* | osf5*) + version_type=osf + need_lib_prefix=no + need_version=no + soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + sys_lib_search_path_spec="/usr/shlib /usr/ccs/lib /usr/lib/cmplrs/cc /usr/lib /usr/local/lib /var/shlib" + sys_lib_dlsearch_path_spec="$sys_lib_search_path_spec" + ;; + +rdos*) + dynamic_linker=no + ;; + +solaris*) + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + # ldd complains unless libraries are executable + postinstall_cmds='chmod +x $lib' + ;; + +sunos4*) + version_type=sunos + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + finish_cmds='PATH="\$PATH:/usr/etc" ldconfig $libdir' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + if test "$with_gnu_ld" = yes; then + need_lib_prefix=no + fi + need_version=yes + ;; + +sysv4 | sysv4.3*) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + case $host_vendor in + sni) + shlibpath_overrides_runpath=no + need_lib_prefix=no + runpath_var=LD_RUN_PATH + ;; + siemens) + need_lib_prefix=no + ;; + motorola) + need_lib_prefix=no + need_version=no + shlibpath_overrides_runpath=no + sys_lib_search_path_spec='/lib /usr/lib /usr/ccs/lib' + ;; + esac + ;; + +sysv4*MP*) + if test -d /usr/nec ;then + version_type=linux + library_names_spec='$libname${shared_ext}.$versuffix $libname${shared_ext}.$major $libname${shared_ext}' + soname_spec='$libname${shared_ext}.$major' + shlibpath_var=LD_LIBRARY_PATH + fi + ;; + +sysv5* | sco3.2v5* | sco5v6* | unixware* | OpenUNIX* | sysv4*uw2*) + version_type=freebsd-elf + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + hardcode_into_libs=yes + if test "$with_gnu_ld" = yes; then + sys_lib_search_path_spec='/usr/local/lib /usr/gnu/lib /usr/ccs/lib /usr/lib /lib' + else + sys_lib_search_path_spec='/usr/ccs/lib /usr/lib' + case $host_os in + sco3.2v5*) + sys_lib_search_path_spec="$sys_lib_search_path_spec /lib" + ;; + esac + fi + sys_lib_dlsearch_path_spec='/usr/lib' + ;; + +tpf*) + # TPF is a cross-target only. Preferred cross-host = GNU/Linux. + version_type=linux + need_lib_prefix=no + need_version=no + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=no + hardcode_into_libs=yes + ;; + +uts4*) + version_type=linux + library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='${libname}${release}${shared_ext}$major' + shlibpath_var=LD_LIBRARY_PATH + ;; + +*) + dynamic_linker=no + ;; +esac +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $dynamic_linker" >&5 +$as_echo "$dynamic_linker" >&6; } +test "$dynamic_linker" = no && can_build_shared=no + +variables_saved_for_relink="PATH $shlibpath_var $runpath_var" +if test "$GCC" = yes; then + variables_saved_for_relink="$variables_saved_for_relink GCC_EXEC_PREFIX COMPILER_PATH LIBRARY_PATH" +fi + +if test "${lt_cv_sys_lib_search_path_spec+set}" = set; then + sys_lib_search_path_spec="$lt_cv_sys_lib_search_path_spec" +fi +if test "${lt_cv_sys_lib_dlsearch_path_spec+set}" = set; then + sys_lib_dlsearch_path_spec="$lt_cv_sys_lib_dlsearch_path_spec" +fi + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + { $as_echo "$as_me:${as_lineno-$LINENO}: checking how to hardcode library paths into programs" >&5 +$as_echo_n "checking how to hardcode library paths into programs... " >&6; } +hardcode_action_CXX= +if test -n "$hardcode_libdir_flag_spec_CXX" || + test -n "$runpath_var_CXX" || + test "X$hardcode_automatic_CXX" = "Xyes" ; then + + # We can hardcode non-existent directories. + if test "$hardcode_direct_CXX" != no && + # If the only mechanism to avoid hardcoding is shlibpath_var, we + # have to relink, otherwise we might link with an installed library + # when we should be linking with a yet-to-be-installed one + ## test "$_LT_TAGVAR(hardcode_shlibpath_var, CXX)" != no && + test "$hardcode_minus_L_CXX" != no; then + # Linking always hardcodes the temporary library directory. + hardcode_action_CXX=relink + else + # We can link without hardcoding, and we can hardcode nonexisting dirs. + hardcode_action_CXX=immediate + fi +else + # We cannot hardcode anything, or else we can only hardcode existing + # directories. + hardcode_action_CXX=unsupported +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $hardcode_action_CXX" >&5 +$as_echo "$hardcode_action_CXX" >&6; } + +if test "$hardcode_action_CXX" = relink || + test "$inherit_rpath_CXX" = yes; then + # Fast installation is not supported + enable_fast_install=no +elif test "$shlibpath_overrides_runpath" = yes || + test "$enable_shared" = no; then + # Fast installation is not necessary + enable_fast_install=needless +fi + + + + + + + + fi # test -n "$compiler" + + CC=$lt_save_CC + LDCXX=$LD + LD=$lt_save_LD + GCC=$lt_save_GCC + with_gnu_ld=$lt_save_with_gnu_ld + lt_cv_path_LDCXX=$lt_cv_path_LD + lt_cv_path_LD=$lt_save_path_LD + lt_cv_prog_gnu_ldcxx=$lt_cv_prog_gnu_ld + lt_cv_prog_gnu_ld=$lt_save_with_gnu_ld +fi # test "$_lt_caught_CXX_error" != yes + +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for inline" >&5 +$as_echo_n "checking for inline... " >&6; } +if test "${ac_cv_c_inline+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_cv_c_inline=no +for ac_kw in inline __inline__ __inline; do + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#ifndef __cplusplus +typedef int foo_t; +static $ac_kw foo_t static_foo () {return 0; } +$ac_kw foo_t foo () {return 0; } +#endif + +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_cv_c_inline=$ac_kw +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext + test "$ac_cv_c_inline" != no && break +done + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_c_inline" >&5 +$as_echo "$ac_cv_c_inline" >&6; } + +case $ac_cv_c_inline in + inline | yes) ;; + *) + case $ac_cv_c_inline in + no) ac_val=;; + *) ac_val=$ac_cv_c_inline;; + esac + cat >>confdefs.h <<_ACEOF +#ifndef __cplusplus +#define inline $ac_val +#endif +_ACEOF + ;; +esac + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether ${MAKE-make} sets \$(MAKE)" >&5 +$as_echo_n "checking whether ${MAKE-make} sets \$(MAKE)... " >&6; } +set x ${MAKE-make} +ac_make=`$as_echo "$2" | sed 's/+/p/g; s/[^a-zA-Z0-9_]/_/g'` +if eval "test \"\${ac_cv_prog_make_${ac_make}_set+set}\"" = set; then : + $as_echo_n "(cached) " >&6 +else + cat >conftest.make <<\_ACEOF +SHELL = /bin/sh +all: + @echo '@@@%%%=$(MAKE)=@@@%%%' +_ACEOF +# GNU make sometimes prints "make[1]: Entering ...", which would confuse us. +case `${MAKE-make} -f conftest.make 2>/dev/null` in + *@@@%%%=?*=@@@%%%*) + eval ac_cv_prog_make_${ac_make}_set=yes;; + *) + eval ac_cv_prog_make_${ac_make}_set=no;; +esac +rm -f conftest.make +fi +if eval test \$ac_cv_prog_make_${ac_make}_set = yes; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } + SET_MAKE= +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + SET_MAKE="MAKE=${MAKE-make}" +fi + +for ac_prog in gperf +do + # Extract the first word of "$ac_prog", so it can be a program name with args. +set dummy $ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_GPERF+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$GPERF"; then + ac_cv_prog_GPERF="$GPERF" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_GPERF="$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +GPERF=$ac_cv_prog_GPERF +if test -n "$GPERF"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $GPERF" >&5 +$as_echo "$GPERF" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$GPERF" && break +done + +if test -z "$GPERF"; then : + as_fn_error $? "can not find gperf" "$LINENO" 5 +fi +if test "$need_pkgconfig" = "yes"; then : + + + + + + +if test "x$ac_cv_env_PKG_CONFIG_set" != "xset"; then + if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}pkg-config", so it can be a program name with args. +set dummy ${ac_tool_prefix}pkg-config; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_path_PKG_CONFIG+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + case $PKG_CONFIG in + [\\/]* | ?:[\\/]*) + ac_cv_path_PKG_CONFIG="$PKG_CONFIG" # Let the user override the test with a path. + ;; + *) + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_path_PKG_CONFIG="$as_dir/$ac_word$ac_exec_ext" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + + ;; +esac +fi +PKG_CONFIG=$ac_cv_path_PKG_CONFIG +if test -n "$PKG_CONFIG"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $PKG_CONFIG" >&5 +$as_echo "$PKG_CONFIG" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_path_PKG_CONFIG"; then + ac_pt_PKG_CONFIG=$PKG_CONFIG + # Extract the first word of "pkg-config", so it can be a program name with args. +set dummy pkg-config; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_path_ac_pt_PKG_CONFIG+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + case $ac_pt_PKG_CONFIG in + [\\/]* | ?:[\\/]*) + ac_cv_path_ac_pt_PKG_CONFIG="$ac_pt_PKG_CONFIG" # Let the user override the test with a path. + ;; + *) + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_path_ac_pt_PKG_CONFIG="$as_dir/$ac_word$ac_exec_ext" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + + ;; +esac +fi +ac_pt_PKG_CONFIG=$ac_cv_path_ac_pt_PKG_CONFIG +if test -n "$ac_pt_PKG_CONFIG"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_pt_PKG_CONFIG" >&5 +$as_echo "$ac_pt_PKG_CONFIG" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_pt_PKG_CONFIG" = x; then + PKG_CONFIG="" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + PKG_CONFIG=$ac_pt_PKG_CONFIG + fi +else + PKG_CONFIG="$ac_cv_path_PKG_CONFIG" +fi + +fi +if test -n "$PKG_CONFIG"; then + _pkg_min_version=0.9.0 + { $as_echo "$as_me:${as_lineno-$LINENO}: checking pkg-config is at least version $_pkg_min_version" >&5 +$as_echo_n "checking pkg-config is at least version $_pkg_min_version... " >&6; } + if $PKG_CONFIG --atleast-pkgconfig-version $_pkg_min_version; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } + else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + PKG_CONFIG="" + fi +fi +fi +for ac_prog in flex lex +do + # Extract the first word of "$ac_prog", so it can be a program name with args. +set dummy $ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_LEX+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$LEX"; then + ac_cv_prog_LEX="$LEX" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_LEX="$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +LEX=$ac_cv_prog_LEX +if test -n "$LEX"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $LEX" >&5 +$as_echo "$LEX" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$LEX" && break +done +test -n "$LEX" || LEX=":" + +if test "x$LEX" != "x:"; then + cat >conftest.l <<_ACEOF +%% +a { ECHO; } +b { REJECT; } +c { yymore (); } +d { yyless (1); } +e { yyless (input () != 0); } +f { unput (yytext[0]); } +. { BEGIN INITIAL; } +%% +#ifdef YYTEXT_POINTER +extern char *yytext; +#endif +int +main (void) +{ + return ! yylex () + ! yywrap (); +} +_ACEOF +{ { ac_try="$LEX conftest.l" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$LEX conftest.l") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking lex output file root" >&5 +$as_echo_n "checking lex output file root... " >&6; } +if test "${ac_cv_prog_lex_root+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + +if test -f lex.yy.c; then + ac_cv_prog_lex_root=lex.yy +elif test -f lexyy.c; then + ac_cv_prog_lex_root=lexyy +else + as_fn_error $? "cannot find output from $LEX; giving up" "$LINENO" 5 +fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_prog_lex_root" >&5 +$as_echo "$ac_cv_prog_lex_root" >&6; } +LEX_OUTPUT_ROOT=$ac_cv_prog_lex_root + +if test -z "${LEXLIB+set}"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: checking lex library" >&5 +$as_echo_n "checking lex library... " >&6; } +if test "${ac_cv_lib_lex+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + + ac_save_LIBS=$LIBS + ac_cv_lib_lex='none needed' + for ac_lib in '' -lfl -ll; do + LIBS="$ac_lib $ac_save_LIBS" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +`cat $LEX_OUTPUT_ROOT.c` +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + ac_cv_lib_lex=$ac_lib +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext + test "$ac_cv_lib_lex" != 'none needed' && break + done + LIBS=$ac_save_LIBS + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_lex" >&5 +$as_echo "$ac_cv_lib_lex" >&6; } + test "$ac_cv_lib_lex" != 'none needed' && LEXLIB=$ac_cv_lib_lex +fi + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether yytext is a pointer" >&5 +$as_echo_n "checking whether yytext is a pointer... " >&6; } +if test "${ac_cv_prog_lex_yytext_pointer+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + # POSIX says lex can declare yytext either as a pointer or an array; the +# default is implementation-dependent. Figure out which it is, since +# not all implementations provide the %pointer and %array declarations. +ac_cv_prog_lex_yytext_pointer=no +ac_save_LIBS=$LIBS +LIBS="$LEXLIB $ac_save_LIBS" +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#define YYTEXT_POINTER 1 +`cat $LEX_OUTPUT_ROOT.c` +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + ac_cv_prog_lex_yytext_pointer=yes +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +LIBS=$ac_save_LIBS + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_prog_lex_yytext_pointer" >&5 +$as_echo "$ac_cv_prog_lex_yytext_pointer" >&6; } +if test $ac_cv_prog_lex_yytext_pointer = yes; then + +$as_echo "#define YYTEXT_POINTER 1" >>confdefs.h + +fi +rm -f conftest.l $LEX_OUTPUT_ROOT.c + +fi +AM_LFLAGS="-L -P zconf" + +for ac_prog in 'bison -y' byacc +do + # Extract the first word of "$ac_prog", so it can be a program name with args. +set dummy $ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_prog_YACC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test -n "$YACC"; then + ac_cv_prog_YACC="$YACC" # Let the user override the test. +else +as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_prog_YACC="$ac_prog" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + +fi +fi +YACC=$ac_cv_prog_YACC +if test -n "$YACC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $YACC" >&5 +$as_echo "$YACC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$YACC" && break +done +test -n "$YACC" || YACC="yacc" + +AM_YFLAGS="-t -l -p zconf" + + +#---------------------------------------- +# Check for standard headers +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for ANSI C header files" >&5 +$as_echo_n "checking for ANSI C header files... " >&6; } +if test "${ac_cv_header_stdc+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +#include +#include +#include + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_cv_header_stdc=yes +else + ac_cv_header_stdc=no +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext + +if test $ac_cv_header_stdc = yes; then + # SunOS 4.x string.h does not declare mem*, contrary to ANSI. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include + +_ACEOF +if (eval "$ac_cpp conftest.$ac_ext") 2>&5 | + $EGREP "memchr" >/dev/null 2>&1; then : + +else + ac_cv_header_stdc=no +fi +rm -f conftest* + +fi + +if test $ac_cv_header_stdc = yes; then + # ISC 2.0.2 stdlib.h does not declare free, contrary to ANSI. + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include + +_ACEOF +if (eval "$ac_cpp conftest.$ac_ext") 2>&5 | + $EGREP "free" >/dev/null 2>&1; then : + +else + ac_cv_header_stdc=no +fi +rm -f conftest* + +fi + +if test $ac_cv_header_stdc = yes; then + # /bin/cc in Irix-4.0.5 gets non-ANSI ctype macros unless using -ansi. + if test "$cross_compiling" = yes; then : + : +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +#include +#if ((' ' & 0x0FF) == 0x020) +# define ISLOWER(c) ('a' <= (c) && (c) <= 'z') +# define TOUPPER(c) (ISLOWER(c) ? 'A' + ((c) - 'a') : (c)) +#else +# define ISLOWER(c) \ + (('a' <= (c) && (c) <= 'i') \ + || ('j' <= (c) && (c) <= 'r') \ + || ('s' <= (c) && (c) <= 'z')) +# define TOUPPER(c) (ISLOWER(c) ? ((c) | 0x40) : (c)) +#endif + +#define XOR(e, f) (((e) && !(f)) || (!(e) && (f))) +int +main () +{ + int i; + for (i = 0; i < 256; i++) + if (XOR (islower (i), ISLOWER (i)) + || toupper (i) != TOUPPER (i)) + return 2; + return 0; +} +_ACEOF +if ac_fn_c_try_run "$LINENO"; then : + +else + ac_cv_header_stdc=no +fi +rm -f core *.core core.conftest.* gmon.out bb.out conftest$ac_exeext \ + conftest.$ac_objext conftest.beam conftest.$ac_ext +fi + +fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_header_stdc" >&5 +$as_echo "$ac_cv_header_stdc" >&6; } +if test $ac_cv_header_stdc = yes; then + +$as_echo "#define STDC_HEADERS 1" >>confdefs.h + +fi + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for stdbool.h that conforms to C99" >&5 +$as_echo_n "checking for stdbool.h that conforms to C99... " >&6; } +if test "${ac_cv_header_stdbool_h+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +#include +#ifndef bool + "error: bool is not defined" +#endif +#ifndef false + "error: false is not defined" +#endif +#if false + "error: false is not 0" +#endif +#ifndef true + "error: true is not defined" +#endif +#if true != 1 + "error: true is not 1" +#endif +#ifndef __bool_true_false_are_defined + "error: __bool_true_false_are_defined is not defined" +#endif + + struct s { _Bool s: 1; _Bool t; } s; + + char a[true == 1 ? 1 : -1]; + char b[false == 0 ? 1 : -1]; + char c[__bool_true_false_are_defined == 1 ? 1 : -1]; + char d[(bool) 0.5 == true ? 1 : -1]; + bool e = &s; + char f[(_Bool) 0.0 == false ? 1 : -1]; + char g[true]; + char h[sizeof (_Bool)]; + char i[sizeof s.t]; + enum { j = false, k = true, l = false * true, m = true * 256 }; + /* The following fails for + HP aC++/ANSI C B3910B A.05.55 [Dec 04 2003]. */ + _Bool n[m]; + char o[sizeof n == m * sizeof n[0] ? 1 : -1]; + char p[-1 - (_Bool) 0 < 0 && -1 - (bool) 0 < 0 ? 1 : -1]; +# if defined __xlc__ || defined __GNUC__ + /* Catch a bug in IBM AIX xlc compiler version 6.0.0.0 + reported by James Lemley on 2005-10-05; see + http://lists.gnu.org/archive/html/bug-coreutils/2005-10/msg00086.html + This test is not quite right, since xlc is allowed to + reject this program, as the initializer for xlcbug is + not one of the forms that C requires support for. + However, doing the test right would require a runtime + test, and that would make cross-compilation harder. + Let us hope that IBM fixes the xlc bug, and also adds + support for this kind of constant expression. In the + meantime, this test will reject xlc, which is OK, since + our stdbool.h substitute should suffice. We also test + this with GCC, where it should work, to detect more + quickly whether someone messes up the test in the + future. */ + char digs[] = "0123456789"; + int xlcbug = 1 / (&(digs + 5)[-2 + (bool) 1] == &digs[4] ? 1 : -1); +# endif + /* Catch a bug in an HP-UX C compiler. See + http://gcc.gnu.org/ml/gcc-patches/2003-12/msg02303.html + http://lists.gnu.org/archive/html/bug-coreutils/2005-11/msg00161.html + */ + _Bool q = true; + _Bool *pq = &q; + +int +main () +{ + + *pq |= q; + *pq |= ! q; + /* Refer to every declared value, to avoid compiler optimizations. */ + return (!a + !b + !c + !d + !e + !f + !g + !h + !i + !!j + !k + !!l + + !m + !n + !o + !p + !q + !pq); + + ; + return 0; +} +_ACEOF +if ac_fn_c_try_compile "$LINENO"; then : + ac_cv_header_stdbool_h=yes +else + ac_cv_header_stdbool_h=no +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_header_stdbool_h" >&5 +$as_echo "$ac_cv_header_stdbool_h" >&6; } +ac_fn_c_check_type "$LINENO" "_Bool" "ac_cv_type__Bool" "$ac_includes_default" +if test "x$ac_cv_type__Bool" = x""yes; then : + +cat >>confdefs.h <<_ACEOF +#define HAVE__BOOL 1 +_ACEOF + + +fi + +if test $ac_cv_header_stdbool_h = yes; then + +$as_echo "#define HAVE_STDBOOL_H 1" >>confdefs.h + +fi + +for ac_header in fcntl.h limits.h locale.h +do : + as_ac_Header=`$as_echo "ac_cv_header_$ac_header" | $as_tr_sh` +ac_fn_c_check_header_mongrel "$LINENO" "$ac_header" "$as_ac_Header" "$ac_includes_default" +if eval test \"x\$"$as_ac_Header"\" = x"yes"; then : + cat >>confdefs.h <<_ACEOF +#define `$as_echo "HAVE_$ac_header" | $as_tr_cpp` 1 +_ACEOF + +fi + +done + +for ac_header in stdlib.h string.h sys/time.h unistd.h +do : + as_ac_Header=`$as_echo "ac_cv_header_$ac_header" | $as_tr_sh` +ac_fn_c_check_header_mongrel "$LINENO" "$ac_header" "$as_ac_Header" "$ac_includes_default" +if eval test \"x\$"$as_ac_Header"\" = x"yes"; then : + cat >>confdefs.h <<_ACEOF +#define `$as_echo "HAVE_$ac_header" | $as_tr_cpp` 1 +_ACEOF + +fi + +done + +ac_fn_c_check_type "$LINENO" "size_t" "ac_cv_type_size_t" "$ac_includes_default" +if test "x$ac_cv_type_size_t" = x""yes; then : + +else + +cat >>confdefs.h <<_ACEOF +#define size_t unsigned int +_ACEOF + +fi + + +#---------------------------------------- +# Checks for library functions. +for ac_header in stdlib.h +do : + ac_fn_c_check_header_mongrel "$LINENO" "stdlib.h" "ac_cv_header_stdlib_h" "$ac_includes_default" +if test "x$ac_cv_header_stdlib_h" = x""yes; then : + cat >>confdefs.h <<_ACEOF +#define HAVE_STDLIB_H 1 +_ACEOF + +fi + +done + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for GNU libc compatible malloc" >&5 +$as_echo_n "checking for GNU libc compatible malloc... " >&6; } +if test "${ac_cv_func_malloc_0_nonnull+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test "$cross_compiling" = yes; then : + ac_cv_func_malloc_0_nonnull=no +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#if defined STDC_HEADERS || defined HAVE_STDLIB_H +# include +#else +char *malloc (); +#endif + +int +main () +{ +return ! malloc (0); + ; + return 0; +} +_ACEOF +if ac_fn_c_try_run "$LINENO"; then : + ac_cv_func_malloc_0_nonnull=yes +else + ac_cv_func_malloc_0_nonnull=no +fi +rm -f core *.core core.conftest.* gmon.out bb.out conftest$ac_exeext \ + conftest.$ac_objext conftest.beam conftest.$ac_ext +fi + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_func_malloc_0_nonnull" >&5 +$as_echo "$ac_cv_func_malloc_0_nonnull" >&6; } +if test $ac_cv_func_malloc_0_nonnull = yes; then : + +$as_echo "#define HAVE_MALLOC 1" >>confdefs.h + +else + $as_echo "#define HAVE_MALLOC 0" >>confdefs.h + + case " $LIBOBJS " in + *" malloc.$ac_objext "* ) ;; + *) LIBOBJS="$LIBOBJS malloc.$ac_objext" + ;; +esac + + +$as_echo "#define malloc rpl_malloc" >>confdefs.h + +fi + + +for ac_header in stdlib.h +do : + ac_fn_c_check_header_mongrel "$LINENO" "stdlib.h" "ac_cv_header_stdlib_h" "$ac_includes_default" +if test "x$ac_cv_header_stdlib_h" = x""yes; then : + cat >>confdefs.h <<_ACEOF +#define HAVE_STDLIB_H 1 +_ACEOF + +fi + +done + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for GNU libc compatible realloc" >&5 +$as_echo_n "checking for GNU libc compatible realloc... " >&6; } +if test "${ac_cv_func_realloc_0_nonnull+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test "$cross_compiling" = yes; then : + ac_cv_func_realloc_0_nonnull=no +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#if defined STDC_HEADERS || defined HAVE_STDLIB_H +# include +#else +char *realloc (); +#endif + +int +main () +{ +return ! realloc (0, 0); + ; + return 0; +} +_ACEOF +if ac_fn_c_try_run "$LINENO"; then : + ac_cv_func_realloc_0_nonnull=yes +else + ac_cv_func_realloc_0_nonnull=no +fi +rm -f core *.core core.conftest.* gmon.out bb.out conftest$ac_exeext \ + conftest.$ac_objext conftest.beam conftest.$ac_ext +fi + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_func_realloc_0_nonnull" >&5 +$as_echo "$ac_cv_func_realloc_0_nonnull" >&6; } +if test $ac_cv_func_realloc_0_nonnull = yes; then : + +$as_echo "#define HAVE_REALLOC 1" >>confdefs.h + +else + $as_echo "#define HAVE_REALLOC 0" >>confdefs.h + + case " $LIBOBJS " in + *" realloc.$ac_objext "* ) ;; + *) LIBOBJS="$LIBOBJS realloc.$ac_objext" + ;; +esac + + +$as_echo "#define realloc rpl_realloc" >>confdefs.h + +fi + + +# The Ultrix 4.2 mips builtin alloca declared by alloca.h only works +# for constant arguments. Useless! +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for working alloca.h" >&5 +$as_echo_n "checking for working alloca.h... " >&6; } +if test "${ac_cv_working_alloca_h+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +int +main () +{ +char *p = (char *) alloca (2 * sizeof (int)); + if (p) return 0; + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + ac_cv_working_alloca_h=yes +else + ac_cv_working_alloca_h=no +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_working_alloca_h" >&5 +$as_echo "$ac_cv_working_alloca_h" >&6; } +if test $ac_cv_working_alloca_h = yes; then + +$as_echo "#define HAVE_ALLOCA_H 1" >>confdefs.h + +fi + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for alloca" >&5 +$as_echo_n "checking for alloca... " >&6; } +if test "${ac_cv_func_alloca_works+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#ifdef __GNUC__ +# define alloca __builtin_alloca +#else +# ifdef _MSC_VER +# include +# define alloca _alloca +# else +# ifdef HAVE_ALLOCA_H +# include +# else +# ifdef _AIX + #pragma alloca +# else +# ifndef alloca /* predefined by HP cc +Olibcalls */ +char *alloca (); +# endif +# endif +# endif +# endif +#endif + +int +main () +{ +char *p = (char *) alloca (1); + if (p) return 0; + ; + return 0; +} +_ACEOF +if ac_fn_c_try_link "$LINENO"; then : + ac_cv_func_alloca_works=yes +else + ac_cv_func_alloca_works=no +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_func_alloca_works" >&5 +$as_echo "$ac_cv_func_alloca_works" >&6; } + +if test $ac_cv_func_alloca_works = yes; then + +$as_echo "#define HAVE_ALLOCA 1" >>confdefs.h + +else + # The SVR3 libPW and SVR4 libucb both contain incompatible functions +# that cause trouble. Some versions do not even contain alloca or +# contain a buggy version. If you still want to use their alloca, +# use ar to extract alloca.o from them instead of compiling alloca.c. + +ALLOCA=\${LIBOBJDIR}alloca.$ac_objext + +$as_echo "#define C_ALLOCA 1" >>confdefs.h + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether \`alloca.c' needs Cray hooks" >&5 +$as_echo_n "checking whether \`alloca.c' needs Cray hooks... " >&6; } +if test "${ac_cv_os_cray+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#if defined CRAY && ! defined CRAY2 +webecray +#else +wenotbecray +#endif + +_ACEOF +if (eval "$ac_cpp conftest.$ac_ext") 2>&5 | + $EGREP "webecray" >/dev/null 2>&1; then : + ac_cv_os_cray=yes +else + ac_cv_os_cray=no +fi +rm -f conftest* + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_os_cray" >&5 +$as_echo "$ac_cv_os_cray" >&6; } +if test $ac_cv_os_cray = yes; then + for ac_func in _getb67 GETB67 getb67; do + as_ac_var=`$as_echo "ac_cv_func_$ac_func" | $as_tr_sh` +ac_fn_c_check_func "$LINENO" "$ac_func" "$as_ac_var" +if eval test \"x\$"$as_ac_var"\" = x"yes"; then : + +cat >>confdefs.h <<_ACEOF +#define CRAY_STACKSEG_END $ac_func +_ACEOF + + break +fi + + done +fi + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking stack direction for C alloca" >&5 +$as_echo_n "checking stack direction for C alloca... " >&6; } +if test "${ac_cv_c_stack_direction+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + if test "$cross_compiling" = yes; then : + ac_cv_c_stack_direction=0 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +$ac_includes_default +int +find_stack_direction () +{ + static char *addr = 0; + auto char dummy; + if (addr == 0) + { + addr = &dummy; + return find_stack_direction (); + } + else + return (&dummy > addr) ? 1 : -1; +} + +int +main () +{ + return find_stack_direction () < 0; +} +_ACEOF +if ac_fn_c_try_run "$LINENO"; then : + ac_cv_c_stack_direction=1 +else + ac_cv_c_stack_direction=-1 +fi +rm -f core *.core core.conftest.* gmon.out bb.out conftest$ac_exeext \ + conftest.$ac_objext conftest.beam conftest.$ac_ext +fi + +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_c_stack_direction" >&5 +$as_echo "$ac_cv_c_stack_direction" >&6; } +cat >>confdefs.h <<_ACEOF +#define STACK_DIRECTION $ac_cv_c_stack_direction +_ACEOF + + +fi + +for ac_func in bzero memmove memset +do : + as_ac_var=`$as_echo "ac_cv_func_$ac_func" | $as_tr_sh` +ac_fn_c_check_func "$LINENO" "$ac_func" "$as_ac_var" +if eval test \"x\$"$as_ac_var"\" = x"yes"; then : + cat >>confdefs.h <<_ACEOF +#define `$as_echo "HAVE_$ac_func" | $as_tr_cpp` 1 +_ACEOF + +fi +done + +for ac_func in strcasecmp strchr strcspn strdup strncasecmp strpbrk strrchr strspn strtol +do : + as_ac_var=`$as_echo "ac_cv_func_$ac_func" | $as_tr_sh` +ac_fn_c_check_func "$LINENO" "$ac_func" "$as_ac_var" +if eval test \"x\$"$as_ac_var"\" = x"yes"; then : + cat >>confdefs.h <<_ACEOF +#define `$as_echo "HAVE_$ac_func" | $as_tr_cpp` 1 +_ACEOF + +fi +done + +for ac_func in gettimeofday mkdir regcomp setlocale uname +do : + as_ac_var=`$as_echo "ac_cv_func_$ac_func" | $as_tr_sh` +ac_fn_c_check_func "$LINENO" "$ac_func" "$as_ac_var" +if eval test \"x\$"$as_ac_var"\" = x"yes"; then : + cat >>confdefs.h <<_ACEOF +#define `$as_echo "HAVE_$ac_func" | $as_tr_cpp` 1 +_ACEOF + +fi +done + + +#---------------------------------------- +# Check for gettext, for the kconfig frontends +has_gettext="$enable_L10n" +if test "$has_gettext" = "yes"; then : + for ac_header in libintl.h +do : + ac_fn_c_check_header_mongrel "$LINENO" "libintl.h" "ac_cv_header_libintl_h" "$ac_includes_default" +if test "x$ac_cv_header_libintl_h" = x""yes; then : + cat >>confdefs.h <<_ACEOF +#define HAVE_LIBINTL_H 1 +_ACEOF + ac_ct_gettext_hdr=$ac_header; break +else + has_gettext=no +fi + +done + +fi +if test "$has_gettext" = "yes"; then : + ac_fn_c_check_decl "$LINENO" "gettext" "ac_cv_have_decl_gettext" "#include <$ac_ct_gettext_hdr> +" +if test "x$ac_cv_have_decl_gettext" = x""yes; then : + +else + has_gettext=no +fi + +fi +if test "$has_gettext" = "yes"; then : + LIBS_old="$LIBS" + LIBS= + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for library containing gettext" >&5 +$as_echo_n "checking for library containing gettext... " >&6; } +if test "${ac_cv_search_gettext+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_func_search_save_LIBS=$LIBS +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +/* Override any GCC internal prototype to avoid an error. + Use char because int might match the return type of a GCC + builtin and then its argument prototype would still apply. */ +#ifdef __cplusplus +extern "C" +#endif +char gettext (); +int +main () +{ +return gettext (); + ; + return 0; +} +_ACEOF +for ac_lib in '' intl; do + if test -z "$ac_lib"; then + ac_res="none required" + else + ac_res=-l$ac_lib + LIBS="-l$ac_lib $ac_func_search_save_LIBS" + fi + if ac_fn_c_try_link "$LINENO"; then : + ac_cv_search_gettext=$ac_res +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext + if test "${ac_cv_search_gettext+set}" = set; then : + break +fi +done +if test "${ac_cv_search_gettext+set}" = set; then : + +else + ac_cv_search_gettext=no +fi +rm conftest.$ac_ext +LIBS=$ac_func_search_save_LIBS +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_search_gettext" >&5 +$as_echo "$ac_cv_search_gettext" >&6; } +ac_res=$ac_cv_search_gettext +if test "$ac_res" != no; then : + test "$ac_res" = "none required" || LIBS="$ac_res $LIBS" + +else + has_gettext=no +fi + + intl_LIBS="$LIBS" + LIBS="$LIBS_old" +fi +if test "$has_gettext" = "no"; then : + intl_CPPFLAGS=-DKBUILD_NO_NLS +fi + + + +#---------------------------------------- +# Check for ncurses, for the mconf & nconf frontends +if test "$need_curses" = "yes" -o "$need_curses" = "auto"; then : + + + LIBS_old="$LIBS" + LIBS= + for ac_header in ncursesw/curses.h ncurses/ncurses.h ncurses/curses.h ncurses.h curses.h +do : + as_ac_Header=`$as_echo "ac_cv_header_$ac_header" | $as_tr_sh` +ac_fn_c_check_header_mongrel "$LINENO" "$ac_header" "$as_ac_Header" "$ac_includes_default" +if eval test \"x\$"$as_ac_Header"\" = x"yes"; then : + cat >>confdefs.h <<_ACEOF +#define `$as_echo "HAVE_$ac_header" | $as_tr_cpp` 1 +_ACEOF + CURSES_LOC=$ac_header; break +fi + +done + + if test -z "$CURSES_LOC"; then : + if test "$need_curses" = "yes"; then : + as_fn_error $? "could not find curses headers (frontends: mconf/nconf)" "$LINENO" 5 +else + has_curses=no +fi +fi + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for library containing initscr" >&5 +$as_echo_n "checking for library containing initscr... " >&6; } +if test "${ac_cv_search_initscr+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_func_search_save_LIBS=$LIBS +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +/* Override any GCC internal prototype to avoid an error. + Use char because int might match the return type of a GCC + builtin and then its argument prototype would still apply. */ +#ifdef __cplusplus +extern "C" +#endif +char initscr (); +int +main () +{ +return initscr (); + ; + return 0; +} +_ACEOF +for ac_lib in '' ncursesw ncurses curses; do + if test -z "$ac_lib"; then + ac_res="none required" + else + ac_res=-l$ac_lib + LIBS="-l$ac_lib $ac_func_search_save_LIBS" + fi + if ac_fn_c_try_link "$LINENO"; then : + ac_cv_search_initscr=$ac_res +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext + if test "${ac_cv_search_initscr+set}" = set; then : + break +fi +done +if test "${ac_cv_search_initscr+set}" = set; then : + +else + ac_cv_search_initscr=no +fi +rm conftest.$ac_ext +LIBS=$ac_func_search_save_LIBS +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_search_initscr" >&5 +$as_echo "$ac_cv_search_initscr" >&6; } +ac_res=$ac_cv_search_initscr +if test "$ac_res" != no; then : + test "$ac_res" = "none required" || LIBS="$ac_res $LIBS" + ac_ct_curses_lib_found=yes; break +fi + + if test -z "$ac_ct_curses_lib_found"; then : + if test "$need_curses" = "yes"; then : + as_fn_error $? "could not find curses library (frontends: mconf/nconf)" "$LINENO" 5 +else + has_curses=no +fi +fi + ncurses_LIBS="$LIBS" + LIBS=$LIBS_old +fi + +if test "$has_curses" = "no" ; then : + enable_mconf=no; enable_nconf=no +fi + +#---------------------------------------- +# Check for libpanel and libmenu, for the nconf frontend +if test "$need_panel_menu" = "yes" -o "$need_panel_menu" = "auto"; then : + + + case $CURSES_LOC in #( + ncursesw/*) : + ncurses_extra_CPPFLAGS="-I/usr/include/ncursesw" ;; #( + ncurses/*) : + ncurses_extra_CPPFLAGS="-I/usr/include/ncurses" ;; #( + *) : + ;; +esac + LIBS_old="$LIBS" + LIBS= + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for library containing new_panel" >&5 +$as_echo_n "checking for library containing new_panel... " >&6; } +if test "${ac_cv_search_new_panel+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_func_search_save_LIBS=$LIBS +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +/* Override any GCC internal prototype to avoid an error. + Use char because int might match the return type of a GCC + builtin and then its argument prototype would still apply. */ +#ifdef __cplusplus +extern "C" +#endif +char new_panel (); +int +main () +{ +return new_panel (); + ; + return 0; +} +_ACEOF +for ac_lib in '' panelw panel; do + if test -z "$ac_lib"; then + ac_res="none required" + else + ac_res=-l$ac_lib + LIBS="-l$ac_lib $ncurses_LIBS $ac_func_search_save_LIBS" + fi + if ac_fn_c_try_link "$LINENO"; then : + ac_cv_search_new_panel=$ac_res +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext + if test "${ac_cv_search_new_panel+set}" = set; then : + break +fi +done +if test "${ac_cv_search_new_panel+set}" = set; then : + +else + ac_cv_search_new_panel=no +fi +rm conftest.$ac_ext +LIBS=$ac_func_search_save_LIBS +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_search_new_panel" >&5 +$as_echo "$ac_cv_search_new_panel" >&6; } +ac_res=$ac_cv_search_new_panel +if test "$ac_res" != no; then : + test "$ac_res" = "none required" || LIBS="$ac_res $LIBS" + ac_ct_panel_lib_found=yes; break +fi + + if test -z "$ac_ct_panel_lib_found"; then : + if test "$need_panel_menu" = "yes"; then : + as_fn_error $? "could not find libpanel library (frontend: nconf)" "$LINENO" 5 +else + has_panel_menu=no +fi +fi + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for library containing menu_init" >&5 +$as_echo_n "checking for library containing menu_init... " >&6; } +if test "${ac_cv_search_menu_init+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + ac_func_search_save_LIBS=$LIBS +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +/* Override any GCC internal prototype to avoid an error. + Use char because int might match the return type of a GCC + builtin and then its argument prototype would still apply. */ +#ifdef __cplusplus +extern "C" +#endif +char menu_init (); +int +main () +{ +return menu_init (); + ; + return 0; +} +_ACEOF +for ac_lib in '' menuw menu; do + if test -z "$ac_lib"; then + ac_res="none required" + else + ac_res=-l$ac_lib + LIBS="-l$ac_lib $ncurses_LIBS $ac_func_search_save_LIBS" + fi + if ac_fn_c_try_link "$LINENO"; then : + ac_cv_search_menu_init=$ac_res +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext + if test "${ac_cv_search_menu_init+set}" = set; then : + break +fi +done +if test "${ac_cv_search_menu_init+set}" = set; then : + +else + ac_cv_search_menu_init=no +fi +rm conftest.$ac_ext +LIBS=$ac_func_search_save_LIBS +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_search_menu_init" >&5 +$as_echo "$ac_cv_search_menu_init" >&6; } +ac_res=$ac_cv_search_menu_init +if test "$ac_res" != no; then : + test "$ac_res" = "none required" || LIBS="$ac_res $LIBS" + ac_ct_menu_lib_found=yes; break +fi + + if test -z "$ac_ct_panel_lib_found"; then : + if test "$need_panel_menu" = "yes"; then : + as_fn_error $? "could not find libmenu library (frontend: nconf)" "$LINENO" 5 +else + has_panel_menu=no +fi +fi + ncurses_extra_LIBS="$LIBS" + LIBS=$LIBS_old +fi + +if test "$has_panel_menu" = "no" ; then : + enable_nconf=no +fi + +#---------------------------------------- +# Check headers and libs for gconf +if test "$need_gtk" = "yes" -o "$need_gtk" = "auto"; then : + +pkg_failed=no +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for gtk" >&5 +$as_echo_n "checking for gtk... " >&6; } + +if test -n "$gtk_CFLAGS"; then + pkg_cv_gtk_CFLAGS="$gtk_CFLAGS" + elif test -n "$PKG_CONFIG"; then + if test -n "$PKG_CONFIG" && \ + { { $as_echo "$as_me:${as_lineno-$LINENO}: \$PKG_CONFIG --exists --print-errors \"gtk+-2.0 gmodule-2.0 libglade-2.0\""; } >&5 + ($PKG_CONFIG --exists --print-errors "gtk+-2.0 gmodule-2.0 libglade-2.0") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + pkg_cv_gtk_CFLAGS=`$PKG_CONFIG --cflags "gtk+-2.0 gmodule-2.0 libglade-2.0" 2>/dev/null` +else + pkg_failed=yes +fi + else + pkg_failed=untried +fi +if test -n "$gtk_LIBS"; then + pkg_cv_gtk_LIBS="$gtk_LIBS" + elif test -n "$PKG_CONFIG"; then + if test -n "$PKG_CONFIG" && \ + { { $as_echo "$as_me:${as_lineno-$LINENO}: \$PKG_CONFIG --exists --print-errors \"gtk+-2.0 gmodule-2.0 libglade-2.0\""; } >&5 + ($PKG_CONFIG --exists --print-errors "gtk+-2.0 gmodule-2.0 libglade-2.0") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + pkg_cv_gtk_LIBS=`$PKG_CONFIG --libs "gtk+-2.0 gmodule-2.0 libglade-2.0" 2>/dev/null` +else + pkg_failed=yes +fi + else + pkg_failed=untried +fi + + + +if test $pkg_failed = yes; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + +if $PKG_CONFIG --atleast-pkgconfig-version 0.20; then + _pkg_short_errors_supported=yes +else + _pkg_short_errors_supported=no +fi + if test $_pkg_short_errors_supported = yes; then + gtk_PKG_ERRORS=`$PKG_CONFIG --short-errors --print-errors "gtk+-2.0 gmodule-2.0 libglade-2.0" 2>&1` + else + gtk_PKG_ERRORS=`$PKG_CONFIG --print-errors "gtk+-2.0 gmodule-2.0 libglade-2.0" 2>&1` + fi + # Put the nasty error message in config.log where it belongs + echo "$gtk_PKG_ERRORS" >&5 + + if test "$need_gtk" = "yes"; then : + as_fn_error $? "could not find GTK+ headers and/or libraries (frontend: gconf)" "$LINENO" 5 +else + has_gtk=no +fi +elif test $pkg_failed = untried; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + if test "$need_gtk" = "yes"; then : + as_fn_error $? "could not find GTK+ headers and/or libraries (frontend: gconf)" "$LINENO" 5 +else + has_gtk=no +fi +else + gtk_CFLAGS=$pkg_cv_gtk_CFLAGS + gtk_LIBS=$pkg_cv_gtk_LIBS + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } + has_gtk=yes +fi +fi + +if test "$has_gtk" = "no" ; then : + enable_gconf=no +fi + +#---------------------------------------- +# Check headers and libs for qconf +if test "$need_qt" = "yes" -o "$need_qt" = "auto"; then : + +pkg_failed=no +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for qt4" >&5 +$as_echo_n "checking for qt4... " >&6; } + +if test -n "$qt4_CFLAGS"; then + pkg_cv_qt4_CFLAGS="$qt4_CFLAGS" + elif test -n "$PKG_CONFIG"; then + if test -n "$PKG_CONFIG" && \ + { { $as_echo "$as_me:${as_lineno-$LINENO}: \$PKG_CONFIG --exists --print-errors \"QtCore QtGui Qt3Support\""; } >&5 + ($PKG_CONFIG --exists --print-errors "QtCore QtGui Qt3Support") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + pkg_cv_qt4_CFLAGS=`$PKG_CONFIG --cflags "QtCore QtGui Qt3Support" 2>/dev/null` +else + pkg_failed=yes +fi + else + pkg_failed=untried +fi +if test -n "$qt4_LIBS"; then + pkg_cv_qt4_LIBS="$qt4_LIBS" + elif test -n "$PKG_CONFIG"; then + if test -n "$PKG_CONFIG" && \ + { { $as_echo "$as_me:${as_lineno-$LINENO}: \$PKG_CONFIG --exists --print-errors \"QtCore QtGui Qt3Support\""; } >&5 + ($PKG_CONFIG --exists --print-errors "QtCore QtGui Qt3Support") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + pkg_cv_qt4_LIBS=`$PKG_CONFIG --libs "QtCore QtGui Qt3Support" 2>/dev/null` +else + pkg_failed=yes +fi + else + pkg_failed=untried +fi + + + +if test $pkg_failed = yes; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + +if $PKG_CONFIG --atleast-pkgconfig-version 0.20; then + _pkg_short_errors_supported=yes +else + _pkg_short_errors_supported=no +fi + if test $_pkg_short_errors_supported = yes; then + qt4_PKG_ERRORS=`$PKG_CONFIG --short-errors --print-errors "QtCore QtGui Qt3Support" 2>&1` + else + qt4_PKG_ERRORS=`$PKG_CONFIG --print-errors "QtCore QtGui Qt3Support" 2>&1` + fi + # Put the nasty error message in config.log where it belongs + echo "$qt4_PKG_ERRORS" >&5 + + if test "$need_qt" = "yes"; then : + as_fn_error $? "could not find QT4 headers and/or libraries (frontend: qconf)" "$LINENO" 5 +else + has_qt=no; need_moc=no +fi +elif test $pkg_failed = untried; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + if test "$need_qt" = "yes"; then : + as_fn_error $? "could not find QT4 headers and/or libraries (frontend: qconf)" "$LINENO" 5 +else + has_qt=no; need_moc=no +fi +else + qt4_CFLAGS=$pkg_cv_qt4_CFLAGS + qt4_LIBS=$pkg_cv_qt4_LIBS + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } + has_qt=yes; need_moc="$need_qt" +fi +fi + + +if test "$need_moc" = "yes" -o "$need_moc" = "auto"; then : + QT4_BINDIR=`$PKG_CONFIG Qt --variable bindir` + for ac_prog in moc-qt4 moc +do + # Extract the first word of "$ac_prog", so it can be a program name with args. +set dummy $ac_prog; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if test "${ac_cv_path_MOC+set}" = set; then : + $as_echo_n "(cached) " >&6 +else + case $MOC in + [\\/]* | ?:[\\/]*) + ac_cv_path_MOC="$MOC" # Let the user override the test with a path. + ;; + *) + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +as_dummy="$QT4_BINDIR:$PATH" +for as_dir in $as_dummy +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then + ac_cv_path_MOC="$as_dir/$ac_word$ac_exec_ext" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + + ;; +esac +fi +MOC=$ac_cv_path_MOC +if test -n "$MOC"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $MOC" >&5 +$as_echo "$MOC" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + + test -n "$MOC" && break +done + + if test -n "$MOC"; then : + has_moc=yes +else + if test "$need_moc" = "yes"; then : + as_fn_error $? "could not find moc (frontend: qconf)" "$LINENO" 5 +else + has_moc=no +fi +fi +fi + +if test "$has_qt" = "no" -o "$has_moc" = "no"; then : + enable_qconf=no +fi + +#---------------------------------------- +# Per-frontends extra libraries + + + + + + +#--------------------------------------------------------------------------- +# Now, we know what frontends to enable +if test "$enable_conf" = "auto"; then : + enable_conf=yes +fi +if test "$enable_gconf" = "auto"; then : + enable_gconf=yes +fi +if test "$enable_mconf" = "auto"; then : + enable_mconf=yes +fi +if test "$enable_nconf" = "auto"; then : + enable_nconf=yes +fi +if test "$enable_qconf" = "auto"; then : + enable_qconf=yes +fi + +#---------------------------------------- +# Check if the lxdialog library should be built +if test "$enable_mconf" = "yes"; then : + need_lxdialog=yes +else + need_lxdialog=no +fi + +#---------------------------------------- +# Check if the images library should be built +if test "$enable_gconf" = "yes" -o "$enable_qconf" = "yes"; then : + need_images=yes +else + need_images=no +fi + +#---------------------------------------- +# Setup automake conditional build + if test "$enable_conf" = "yes"; then + COND_conf_TRUE= + COND_conf_FALSE='#' +else + COND_conf_TRUE='#' + COND_conf_FALSE= +fi + + if test "$enable_mconf" = "yes"; then + COND_mconf_TRUE= + COND_mconf_FALSE='#' +else + COND_mconf_TRUE='#' + COND_mconf_FALSE= +fi + + if test "$enable_nconf" = "yes"; then + COND_nconf_TRUE= + COND_nconf_FALSE='#' +else + COND_nconf_TRUE='#' + COND_nconf_FALSE= +fi + + if test "$enable_gconf" = "yes"; then + COND_gconf_TRUE= + COND_gconf_FALSE='#' +else + COND_gconf_TRUE='#' + COND_gconf_FALSE= +fi + + if test "$enable_qconf" = "yes"; then + COND_qconf_TRUE= + COND_qconf_FALSE='#' +else + COND_qconf_TRUE='#' + COND_qconf_FALSE= +fi + + if test "$need_lxdialog" = "yes"; then + COND_lxdialog_TRUE= + COND_lxdialog_FALSE='#' +else + COND_lxdialog_TRUE='#' + COND_lxdialog_FALSE= +fi + + if test "$need_images" = "yes"; then + COND_images_TRUE= + COND_images_FALSE='#' +else + COND_images_TRUE='#' + COND_images_FALSE= +fi + + if test "$enable_utils" = "yes"; then + COND_utils_TRUE= + COND_utils_FALSE='#' +else + COND_utils_TRUE='#' + COND_utils_FALSE= +fi + + if test "$has_gettext" = "yes"; then + COND_utils_gettext_TRUE= + COND_utils_gettext_FALSE='#' +else + COND_utils_gettext_TRUE='#' + COND_utils_gettext_FALSE= +fi + + +#---------------------------------------- +# Get the version to apply to the parser shared library +KCONFIGPARSER_LIB_VERSION=3.6.0 + + +#---------------------------------------- +# Finalise +ac_config_files="$ac_config_files Makefile docs/Makefile libs/Makefile libs/images/Makefile libs/lxdialog/Makefile libs/parser/Makefile frontends/Makefile frontends/conf/Makefile frontends/mconf/Makefile frontends/nconf/Makefile frontends/gconf/Makefile frontends/qconf/Makefile utils/Makefile scripts/Makefile" + +cat >confcache <<\_ACEOF +# This file is a shell script that caches the results of configure +# tests run on this system so they can be shared between configure +# scripts and configure runs, see configure's option --config-cache. +# It is not useful on other systems. If it contains results you don't +# want to keep, you may remove or edit it. +# +# config.status only pays attention to the cache file if you give it +# the --recheck option to rerun configure. +# +# `ac_cv_env_foo' variables (set or unset) will be overridden when +# loading this file, other *unset* `ac_cv_foo' will be assigned the +# following values. + +_ACEOF + +# The following way of writing the cache mishandles newlines in values, +# but we know of no workaround that is simple, portable, and efficient. +# So, we kill variables containing newlines. +# Ultrix sh set writes to stderr and can't be redirected directly, +# and sets the high bit in the cache file unless we assign to the vars. +( + for ac_var in `(set) 2>&1 | sed -n 's/^\([a-zA-Z_][a-zA-Z0-9_]*\)=.*/\1/p'`; do + eval ac_val=\$$ac_var + case $ac_val in #( + *${as_nl}*) + case $ac_var in #( + *_cv_*) { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: cache variable $ac_var contains a newline" >&5 +$as_echo "$as_me: WARNING: cache variable $ac_var contains a newline" >&2;} ;; + esac + case $ac_var in #( + _ | IFS | as_nl) ;; #( + BASH_ARGV | BASH_SOURCE) eval $ac_var= ;; #( + *) { eval $ac_var=; unset $ac_var;} ;; + esac ;; + esac + done + + (set) 2>&1 | + case $as_nl`(ac_space=' '; set) 2>&1` in #( + *${as_nl}ac_space=\ *) + # `set' does not quote correctly, so add quotes: double-quote + # substitution turns \\\\ into \\, and sed turns \\ into \. + sed -n \ + "s/'/'\\\\''/g; + s/^\\([_$as_cr_alnum]*_cv_[_$as_cr_alnum]*\\)=\\(.*\\)/\\1='\\2'/p" + ;; #( + *) + # `set' quotes correctly as required by POSIX, so do not add quotes. + sed -n "/^[_$as_cr_alnum]*_cv_[_$as_cr_alnum]*=/p" + ;; + esac | + sort +) | + sed ' + /^ac_cv_env_/b end + t clear + :clear + s/^\([^=]*\)=\(.*[{}].*\)$/test "${\1+set}" = set || &/ + t end + s/^\([^=]*\)=\(.*\)$/\1=${\1=\2}/ + :end' >>confcache +if diff "$cache_file" confcache >/dev/null 2>&1; then :; else + if test -w "$cache_file"; then + test "x$cache_file" != "x/dev/null" && + { $as_echo "$as_me:${as_lineno-$LINENO}: updating cache $cache_file" >&5 +$as_echo "$as_me: updating cache $cache_file" >&6;} + cat confcache >$cache_file + else + { $as_echo "$as_me:${as_lineno-$LINENO}: not updating unwritable cache $cache_file" >&5 +$as_echo "$as_me: not updating unwritable cache $cache_file" >&6;} + fi +fi +rm -f confcache + +test "x$prefix" = xNONE && prefix=$ac_default_prefix +# Let make expand exec_prefix. +test "x$exec_prefix" = xNONE && exec_prefix='${prefix}' + +DEFS=-DHAVE_CONFIG_H + +ac_libobjs= +ac_ltlibobjs= +U= +for ac_i in : $LIBOBJS; do test "x$ac_i" = x: && continue + # 1. Remove the extension, and $U if already installed. + ac_script='s/\$U\././;s/\.o$//;s/\.obj$//' + ac_i=`$as_echo "$ac_i" | sed "$ac_script"` + # 2. Prepend LIBOBJDIR. When used with automake>=1.10 LIBOBJDIR + # will be set to the directory where LIBOBJS objects are built. + as_fn_append ac_libobjs " \${LIBOBJDIR}$ac_i\$U.$ac_objext" + as_fn_append ac_ltlibobjs " \${LIBOBJDIR}$ac_i"'$U.lo' +done +LIBOBJS=$ac_libobjs + +LTLIBOBJS=$ac_ltlibobjs + + + if test -n "$EXEEXT"; then + am__EXEEXT_TRUE= + am__EXEEXT_FALSE='#' +else + am__EXEEXT_TRUE='#' + am__EXEEXT_FALSE= +fi + +if test -z "${AMDEP_TRUE}" && test -z "${AMDEP_FALSE}"; then + as_fn_error $? "conditional \"AMDEP\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${am__fastdepCC_TRUE}" && test -z "${am__fastdepCC_FALSE}"; then + as_fn_error $? "conditional \"am__fastdepCC\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${am__fastdepCC_TRUE}" && test -z "${am__fastdepCC_FALSE}"; then + as_fn_error $? "conditional \"am__fastdepCC\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${am__fastdepCXX_TRUE}" && test -z "${am__fastdepCXX_FALSE}"; then + as_fn_error $? "conditional \"am__fastdepCXX\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${am__fastdepCXX_TRUE}" && test -z "${am__fastdepCXX_FALSE}"; then + as_fn_error $? "conditional \"am__fastdepCXX\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${COND_conf_TRUE}" && test -z "${COND_conf_FALSE}"; then + as_fn_error $? "conditional \"COND_conf\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${COND_mconf_TRUE}" && test -z "${COND_mconf_FALSE}"; then + as_fn_error $? "conditional \"COND_mconf\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${COND_nconf_TRUE}" && test -z "${COND_nconf_FALSE}"; then + as_fn_error $? "conditional \"COND_nconf\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${COND_gconf_TRUE}" && test -z "${COND_gconf_FALSE}"; then + as_fn_error $? "conditional \"COND_gconf\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${COND_qconf_TRUE}" && test -z "${COND_qconf_FALSE}"; then + as_fn_error $? "conditional \"COND_qconf\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${COND_lxdialog_TRUE}" && test -z "${COND_lxdialog_FALSE}"; then + as_fn_error $? "conditional \"COND_lxdialog\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${COND_images_TRUE}" && test -z "${COND_images_FALSE}"; then + as_fn_error $? "conditional \"COND_images\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${COND_utils_TRUE}" && test -z "${COND_utils_FALSE}"; then + as_fn_error $? "conditional \"COND_utils\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi +if test -z "${COND_utils_gettext_TRUE}" && test -z "${COND_utils_gettext_FALSE}"; then + as_fn_error $? "conditional \"COND_utils_gettext\" was never defined. +Usually this means the macro was only invoked conditionally." "$LINENO" 5 +fi + +: ${CONFIG_STATUS=./config.status} +ac_write_fail=0 +ac_clean_files_save=$ac_clean_files +ac_clean_files="$ac_clean_files $CONFIG_STATUS" +{ $as_echo "$as_me:${as_lineno-$LINENO}: creating $CONFIG_STATUS" >&5 +$as_echo "$as_me: creating $CONFIG_STATUS" >&6;} +as_write_fail=0 +cat >$CONFIG_STATUS <<_ASEOF || as_write_fail=1 +#! $SHELL +# Generated by $as_me. +# Run this file to recreate the current configuration. +# Compiler output produced by configure, useful for debugging +# configure, is in config.log if it exists. + +debug=false +ac_cs_recheck=false +ac_cs_silent=false + +SHELL=\${CONFIG_SHELL-$SHELL} +export SHELL +_ASEOF +cat >>$CONFIG_STATUS <<\_ASEOF || as_write_fail=1 +## -------------------- ## +## M4sh Initialization. ## +## -------------------- ## + +# Be more Bourne compatible +DUALCASE=1; export DUALCASE # for MKS sh +if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then : + emulate sh + NULLCMD=: + # Pre-4.2 versions of Zsh do word splitting on ${1+"$@"}, which + # is contrary to our usage. Disable this feature. + alias -g '${1+"$@"}'='"$@"' + setopt NO_GLOB_SUBST +else + case `(set -o) 2>/dev/null` in #( + *posix*) : + set -o posix ;; #( + *) : + ;; +esac +fi + + +as_nl=' +' +export as_nl +# Printing a long string crashes Solaris 7 /usr/bin/printf. +as_echo='\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\' +as_echo=$as_echo$as_echo$as_echo$as_echo$as_echo +as_echo=$as_echo$as_echo$as_echo$as_echo$as_echo$as_echo +# Prefer a ksh shell builtin over an external printf program on Solaris, +# but without wasting forks for bash or zsh. +if test -z "$BASH_VERSION$ZSH_VERSION" \ + && (test "X`print -r -- $as_echo`" = "X$as_echo") 2>/dev/null; then + as_echo='print -r --' + as_echo_n='print -rn --' +elif (test "X`printf %s $as_echo`" = "X$as_echo") 2>/dev/null; then + as_echo='printf %s\n' + as_echo_n='printf %s' +else + if test "X`(/usr/ucb/echo -n -n $as_echo) 2>/dev/null`" = "X-n $as_echo"; then + as_echo_body='eval /usr/ucb/echo -n "$1$as_nl"' + as_echo_n='/usr/ucb/echo -n' + else + as_echo_body='eval expr "X$1" : "X\\(.*\\)"' + as_echo_n_body='eval + arg=$1; + case $arg in #( + *"$as_nl"*) + expr "X$arg" : "X\\(.*\\)$as_nl"; + arg=`expr "X$arg" : ".*$as_nl\\(.*\\)"`;; + esac; + expr "X$arg" : "X\\(.*\\)" | tr -d "$as_nl" + ' + export as_echo_n_body + as_echo_n='sh -c $as_echo_n_body as_echo' + fi + export as_echo_body + as_echo='sh -c $as_echo_body as_echo' +fi + +# The user is always right. +if test "${PATH_SEPARATOR+set}" != set; then + PATH_SEPARATOR=: + (PATH='/bin;/bin'; FPATH=$PATH; sh -c :) >/dev/null 2>&1 && { + (PATH='/bin:/bin'; FPATH=$PATH; sh -c :) >/dev/null 2>&1 || + PATH_SEPARATOR=';' + } +fi + + +# IFS +# We need space, tab and new line, in precisely that order. Quoting is +# there to prevent editors from complaining about space-tab. +# (If _AS_PATH_WALK were called with IFS unset, it would disable word +# splitting by setting IFS to empty value.) +IFS=" "" $as_nl" + +# Find who we are. Look in the path if we contain no directory separator. +case $0 in #(( + *[\\/]* ) as_myself=$0 ;; + *) as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + test -r "$as_dir/$0" && as_myself=$as_dir/$0 && break + done +IFS=$as_save_IFS + + ;; +esac +# We did not find ourselves, most probably we were run as `sh COMMAND' +# in which case we are not to be found in the path. +if test "x$as_myself" = x; then + as_myself=$0 +fi +if test ! -f "$as_myself"; then + $as_echo "$as_myself: error: cannot find myself; rerun with an absolute file name" >&2 + exit 1 +fi + +# Unset variables that we do not need and which cause bugs (e.g. in +# pre-3.0 UWIN ksh). But do not cause bugs in bash 2.01; the "|| exit 1" +# suppresses any "Segmentation fault" message there. '((' could +# trigger a bug in pdksh 5.2.14. +for as_var in BASH_ENV ENV MAIL MAILPATH +do eval test x\${$as_var+set} = xset \ + && ( (unset $as_var) || exit 1) >/dev/null 2>&1 && unset $as_var || : +done +PS1='$ ' +PS2='> ' +PS4='+ ' + +# NLS nuisances. +LC_ALL=C +export LC_ALL +LANGUAGE=C +export LANGUAGE + +# CDPATH. +(unset CDPATH) >/dev/null 2>&1 && unset CDPATH + + +# as_fn_error STATUS ERROR [LINENO LOG_FD] +# ---------------------------------------- +# Output "`basename $0`: error: ERROR" to stderr. If LINENO and LOG_FD are +# provided, also output the error to LOG_FD, referencing LINENO. Then exit the +# script with STATUS, using 1 if that was 0. +as_fn_error () +{ + as_status=$1; test $as_status -eq 0 && as_status=1 + if test "$4"; then + as_lineno=${as_lineno-"$3"} as_lineno_stack=as_lineno_stack=$as_lineno_stack + $as_echo "$as_me:${as_lineno-$LINENO}: error: $2" >&$4 + fi + $as_echo "$as_me: error: $2" >&2 + as_fn_exit $as_status +} # as_fn_error + + +# as_fn_set_status STATUS +# ----------------------- +# Set $? to STATUS, without forking. +as_fn_set_status () +{ + return $1 +} # as_fn_set_status + +# as_fn_exit STATUS +# ----------------- +# Exit the shell with STATUS, even in a "trap 0" or "set -e" context. +as_fn_exit () +{ + set +e + as_fn_set_status $1 + exit $1 +} # as_fn_exit + +# as_fn_unset VAR +# --------------- +# Portably unset VAR. +as_fn_unset () +{ + { eval $1=; unset $1;} +} +as_unset=as_fn_unset +# as_fn_append VAR VALUE +# ---------------------- +# Append the text in VALUE to the end of the definition contained in VAR. Take +# advantage of any shell optimizations that allow amortized linear growth over +# repeated appends, instead of the typical quadratic growth present in naive +# implementations. +if (eval "as_var=1; as_var+=2; test x\$as_var = x12") 2>/dev/null; then : + eval 'as_fn_append () + { + eval $1+=\$2 + }' +else + as_fn_append () + { + eval $1=\$$1\$2 + } +fi # as_fn_append + +# as_fn_arith ARG... +# ------------------ +# Perform arithmetic evaluation on the ARGs, and store the result in the +# global $as_val. Take advantage of shells that can avoid forks. The arguments +# must be portable across $(()) and expr. +if (eval "test \$(( 1 + 1 )) = 2") 2>/dev/null; then : + eval 'as_fn_arith () + { + as_val=$(( $* )) + }' +else + as_fn_arith () + { + as_val=`expr "$@" || test $? -eq 1` + } +fi # as_fn_arith + + +if expr a : '\(a\)' >/dev/null 2>&1 && + test "X`expr 00001 : '.*\(...\)'`" = X001; then + as_expr=expr +else + as_expr=false +fi + +if (basename -- /) >/dev/null 2>&1 && test "X`basename -- / 2>&1`" = "X/"; then + as_basename=basename +else + as_basename=false +fi + +if (as_dir=`dirname -- /` && test "X$as_dir" = X/) >/dev/null 2>&1; then + as_dirname=dirname +else + as_dirname=false +fi + +as_me=`$as_basename -- "$0" || +$as_expr X/"$0" : '.*/\([^/][^/]*\)/*$' \| \ + X"$0" : 'X\(//\)$' \| \ + X"$0" : 'X\(/\)' \| . 2>/dev/null || +$as_echo X/"$0" | + sed '/^.*\/\([^/][^/]*\)\/*$/{ + s//\1/ + q + } + /^X\/\(\/\/\)$/{ + s//\1/ + q + } + /^X\/\(\/\).*/{ + s//\1/ + q + } + s/.*/./; q'` + +# Avoid depending upon Character Ranges. +as_cr_letters='abcdefghijklmnopqrstuvwxyz' +as_cr_LETTERS='ABCDEFGHIJKLMNOPQRSTUVWXYZ' +as_cr_Letters=$as_cr_letters$as_cr_LETTERS +as_cr_digits='0123456789' +as_cr_alnum=$as_cr_Letters$as_cr_digits + +ECHO_C= ECHO_N= ECHO_T= +case `echo -n x` in #((((( +-n*) + case `echo 'xy\c'` in + *c*) ECHO_T=' ';; # ECHO_T is single tab character. + xy) ECHO_C='\c';; + *) echo `echo ksh88 bug on AIX 6.1` > /dev/null + ECHO_T=' ';; + esac;; +*) + ECHO_N='-n';; +esac + +rm -f conf$$ conf$$.exe conf$$.file +if test -d conf$$.dir; then + rm -f conf$$.dir/conf$$.file +else + rm -f conf$$.dir + mkdir conf$$.dir 2>/dev/null +fi +if (echo >conf$$.file) 2>/dev/null; then + if ln -s conf$$.file conf$$ 2>/dev/null; then + as_ln_s='ln -s' + # ... but there are two gotchas: + # 1) On MSYS, both `ln -s file dir' and `ln file dir' fail. + # 2) DJGPP < 2.04 has no symlinks; `ln -s' creates a wrapper executable. + # In both cases, we have to default to `cp -p'. + ln -s conf$$.file conf$$.dir 2>/dev/null && test ! -f conf$$.exe || + as_ln_s='cp -p' + elif ln conf$$.file conf$$ 2>/dev/null; then + as_ln_s=ln + else + as_ln_s='cp -p' + fi +else + as_ln_s='cp -p' +fi +rm -f conf$$ conf$$.exe conf$$.dir/conf$$.file conf$$.file +rmdir conf$$.dir 2>/dev/null + + +# as_fn_mkdir_p +# ------------- +# Create "$as_dir" as a directory, including parents if necessary. +as_fn_mkdir_p () +{ + + case $as_dir in #( + -*) as_dir=./$as_dir;; + esac + test -d "$as_dir" || eval $as_mkdir_p || { + as_dirs= + while :; do + case $as_dir in #( + *\'*) as_qdir=`$as_echo "$as_dir" | sed "s/'/'\\\\\\\\''/g"`;; #'( + *) as_qdir=$as_dir;; + esac + as_dirs="'$as_qdir' $as_dirs" + as_dir=`$as_dirname -- "$as_dir" || +$as_expr X"$as_dir" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \ + X"$as_dir" : 'X\(//\)[^/]' \| \ + X"$as_dir" : 'X\(//\)$' \| \ + X"$as_dir" : 'X\(/\)' \| . 2>/dev/null || +$as_echo X"$as_dir" | + sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ + s//\1/ + q + } + /^X\(\/\/\)[^/].*/{ + s//\1/ + q + } + /^X\(\/\/\)$/{ + s//\1/ + q + } + /^X\(\/\).*/{ + s//\1/ + q + } + s/.*/./; q'` + test -d "$as_dir" && break + done + test -z "$as_dirs" || eval "mkdir $as_dirs" + } || test -d "$as_dir" || as_fn_error $? "cannot create directory $as_dir" + + +} # as_fn_mkdir_p +if mkdir -p . 2>/dev/null; then + as_mkdir_p='mkdir -p "$as_dir"' +else + test -d ./-p && rmdir ./-p + as_mkdir_p=false +fi + +if test -x / >/dev/null 2>&1; then + as_test_x='test -x' +else + if ls -dL / >/dev/null 2>&1; then + as_ls_L_option=L + else + as_ls_L_option= + fi + as_test_x=' + eval sh -c '\'' + if test -d "$1"; then + test -d "$1/."; + else + case $1 in #( + -*)set "./$1";; + esac; + case `ls -ld'$as_ls_L_option' "$1" 2>/dev/null` in #(( + ???[sx]*):;;*)false;;esac;fi + '\'' sh + ' +fi +as_executable_p=$as_test_x + +# Sed expression to map a string onto a valid CPP name. +as_tr_cpp="eval sed 'y%*$as_cr_letters%P$as_cr_LETTERS%;s%[^_$as_cr_alnum]%_%g'" + +# Sed expression to map a string onto a valid variable name. +as_tr_sh="eval sed 'y%*+%pp%;s%[^_$as_cr_alnum]%_%g'" + + +exec 6>&1 +## ----------------------------------- ## +## Main body of $CONFIG_STATUS script. ## +## ----------------------------------- ## +_ASEOF +test $as_write_fail = 0 && chmod +x $CONFIG_STATUS || ac_write_fail=1 + +cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 +# Save the log message, to keep $0 and so on meaningful, and to +# report actual input values of CONFIG_FILES etc. instead of their +# values after options handling. +ac_log=" +This file was extended by kconfig-frontends $as_me 3.6.0-0, which was +generated by GNU Autoconf 2.67. Invocation command line was + + CONFIG_FILES = $CONFIG_FILES + CONFIG_HEADERS = $CONFIG_HEADERS + CONFIG_LINKS = $CONFIG_LINKS + CONFIG_COMMANDS = $CONFIG_COMMANDS + $ $0 $@ + +on `(hostname || uname -n) 2>/dev/null | sed 1q` +" + +_ACEOF + +case $ac_config_files in *" +"*) set x $ac_config_files; shift; ac_config_files=$*;; +esac + +case $ac_config_headers in *" +"*) set x $ac_config_headers; shift; ac_config_headers=$*;; +esac + + +cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1 +# Files that config.status was made for. +config_files="$ac_config_files" +config_headers="$ac_config_headers" +config_commands="$ac_config_commands" + +_ACEOF + +cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 +ac_cs_usage="\ +\`$as_me' instantiates files and other configuration actions +from templates according to the current configuration. Unless the files +and actions are specified as TAGs, all are instantiated by default. + +Usage: $0 [OPTION]... [TAG]... + + -h, --help print this help, then exit + -V, --version print version number and configuration settings, then exit + --config print configuration, then exit + -q, --quiet, --silent + do not print progress messages + -d, --debug don't remove temporary files + --recheck update $as_me by reconfiguring in the same conditions + --file=FILE[:TEMPLATE] + instantiate the configuration file FILE + --header=FILE[:TEMPLATE] + instantiate the configuration header FILE + +Configuration files: +$config_files + +Configuration headers: +$config_headers + +Configuration commands: +$config_commands + +Report bugs to ." + +_ACEOF +cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1 +ac_cs_config="`$as_echo "$ac_configure_args" | sed 's/^ //; s/[\\""\`\$]/\\\\&/g'`" +ac_cs_version="\\ +kconfig-frontends config.status 3.6.0-0 +configured by $0, generated by GNU Autoconf 2.67, + with options \\"\$ac_cs_config\\" + +Copyright (C) 2010 Free Software Foundation, Inc. +This config.status script is free software; the Free Software Foundation +gives unlimited permission to copy, distribute and modify it." + +ac_pwd='$ac_pwd' +srcdir='$srcdir' +INSTALL='$INSTALL' +MKDIR_P='$MKDIR_P' +AWK='$AWK' +test -n "\$AWK" || AWK=awk +_ACEOF + +cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 +# The default lists apply if the user does not specify any file. +ac_need_defaults=: +while test $# != 0 +do + case $1 in + --*=?*) + ac_option=`expr "X$1" : 'X\([^=]*\)='` + ac_optarg=`expr "X$1" : 'X[^=]*=\(.*\)'` + ac_shift=: + ;; + --*=) + ac_option=`expr "X$1" : 'X\([^=]*\)='` + ac_optarg= + ac_shift=: + ;; + *) + ac_option=$1 + ac_optarg=$2 + ac_shift=shift + ;; + esac + + case $ac_option in + # Handling of the options. + -recheck | --recheck | --rechec | --reche | --rech | --rec | --re | --r) + ac_cs_recheck=: ;; + --version | --versio | --versi | --vers | --ver | --ve | --v | -V ) + $as_echo "$ac_cs_version"; exit ;; + --config | --confi | --conf | --con | --co | --c ) + $as_echo "$ac_cs_config"; exit ;; + --debug | --debu | --deb | --de | --d | -d ) + debug=: ;; + --file | --fil | --fi | --f ) + $ac_shift + case $ac_optarg in + *\'*) ac_optarg=`$as_echo "$ac_optarg" | sed "s/'/'\\\\\\\\''/g"` ;; + '') as_fn_error $? "missing file argument" ;; + esac + as_fn_append CONFIG_FILES " '$ac_optarg'" + ac_need_defaults=false;; + --header | --heade | --head | --hea ) + $ac_shift + case $ac_optarg in + *\'*) ac_optarg=`$as_echo "$ac_optarg" | sed "s/'/'\\\\\\\\''/g"` ;; + esac + as_fn_append CONFIG_HEADERS " '$ac_optarg'" + ac_need_defaults=false;; + --he | --h) + # Conflict between --help and --header + as_fn_error $? "ambiguous option: \`$1' +Try \`$0 --help' for more information.";; + --help | --hel | -h ) + $as_echo "$ac_cs_usage"; exit ;; + -q | -quiet | --quiet | --quie | --qui | --qu | --q \ + | -silent | --silent | --silen | --sile | --sil | --si | --s) + ac_cs_silent=: ;; + + # This is an error. + -*) as_fn_error $? "unrecognized option: \`$1' +Try \`$0 --help' for more information." ;; + + *) as_fn_append ac_config_targets " $1" + ac_need_defaults=false ;; + + esac + shift +done + +ac_configure_extra_args= + +if $ac_cs_silent; then + exec 6>/dev/null + ac_configure_extra_args="$ac_configure_extra_args --silent" +fi + +_ACEOF +cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1 +if \$ac_cs_recheck; then + set X '$SHELL' '$0' $ac_configure_args \$ac_configure_extra_args --no-create --no-recursion + shift + \$as_echo "running CONFIG_SHELL=$SHELL \$*" >&6 + CONFIG_SHELL='$SHELL' + export CONFIG_SHELL + exec "\$@" +fi + +_ACEOF +cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 +exec 5>>config.log +{ + echo + sed 'h;s/./-/g;s/^.../## /;s/...$/ ##/;p;x;p;x' <<_ASBOX +## Running $as_me. ## +_ASBOX + $as_echo "$ac_log" +} >&5 + +_ACEOF +cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1 +# +# INIT-COMMANDS +# +AMDEP_TRUE="$AMDEP_TRUE" ac_aux_dir="$ac_aux_dir" + + +# The HP-UX ksh and POSIX shell print the target directory to stdout +# if CDPATH is set. +(unset CDPATH) >/dev/null 2>&1 && unset CDPATH + +sed_quote_subst='$sed_quote_subst' +double_quote_subst='$double_quote_subst' +delay_variable_subst='$delay_variable_subst' +macro_version='`$ECHO "X$macro_version" | $Xsed -e "$delay_single_quote_subst"`' +macro_revision='`$ECHO "X$macro_revision" | $Xsed -e "$delay_single_quote_subst"`' +enable_static='`$ECHO "X$enable_static" | $Xsed -e "$delay_single_quote_subst"`' +enable_shared='`$ECHO "X$enable_shared" | $Xsed -e "$delay_single_quote_subst"`' +pic_mode='`$ECHO "X$pic_mode" | $Xsed -e "$delay_single_quote_subst"`' +enable_fast_install='`$ECHO "X$enable_fast_install" | $Xsed -e "$delay_single_quote_subst"`' +host_alias='`$ECHO "X$host_alias" | $Xsed -e "$delay_single_quote_subst"`' +host='`$ECHO "X$host" | $Xsed -e "$delay_single_quote_subst"`' +host_os='`$ECHO "X$host_os" | $Xsed -e "$delay_single_quote_subst"`' +build_alias='`$ECHO "X$build_alias" | $Xsed -e "$delay_single_quote_subst"`' +build='`$ECHO "X$build" | $Xsed -e "$delay_single_quote_subst"`' +build_os='`$ECHO "X$build_os" | $Xsed -e "$delay_single_quote_subst"`' +SED='`$ECHO "X$SED" | $Xsed -e "$delay_single_quote_subst"`' +Xsed='`$ECHO "X$Xsed" | $Xsed -e "$delay_single_quote_subst"`' +GREP='`$ECHO "X$GREP" | $Xsed -e "$delay_single_quote_subst"`' +EGREP='`$ECHO "X$EGREP" | $Xsed -e "$delay_single_quote_subst"`' +FGREP='`$ECHO "X$FGREP" | $Xsed -e "$delay_single_quote_subst"`' +LD='`$ECHO "X$LD" | $Xsed -e "$delay_single_quote_subst"`' +NM='`$ECHO "X$NM" | $Xsed -e "$delay_single_quote_subst"`' +LN_S='`$ECHO "X$LN_S" | $Xsed -e "$delay_single_quote_subst"`' +max_cmd_len='`$ECHO "X$max_cmd_len" | $Xsed -e "$delay_single_quote_subst"`' +ac_objext='`$ECHO "X$ac_objext" | $Xsed -e "$delay_single_quote_subst"`' +exeext='`$ECHO "X$exeext" | $Xsed -e "$delay_single_quote_subst"`' +lt_unset='`$ECHO "X$lt_unset" | $Xsed -e "$delay_single_quote_subst"`' +lt_SP2NL='`$ECHO "X$lt_SP2NL" | $Xsed -e "$delay_single_quote_subst"`' +lt_NL2SP='`$ECHO "X$lt_NL2SP" | $Xsed -e "$delay_single_quote_subst"`' +reload_flag='`$ECHO "X$reload_flag" | $Xsed -e "$delay_single_quote_subst"`' +reload_cmds='`$ECHO "X$reload_cmds" | $Xsed -e "$delay_single_quote_subst"`' +OBJDUMP='`$ECHO "X$OBJDUMP" | $Xsed -e "$delay_single_quote_subst"`' +deplibs_check_method='`$ECHO "X$deplibs_check_method" | $Xsed -e "$delay_single_quote_subst"`' +file_magic_cmd='`$ECHO "X$file_magic_cmd" | $Xsed -e "$delay_single_quote_subst"`' +AR='`$ECHO "X$AR" | $Xsed -e "$delay_single_quote_subst"`' +AR_FLAGS='`$ECHO "X$AR_FLAGS" | $Xsed -e "$delay_single_quote_subst"`' +STRIP='`$ECHO "X$STRIP" | $Xsed -e "$delay_single_quote_subst"`' +RANLIB='`$ECHO "X$RANLIB" | $Xsed -e "$delay_single_quote_subst"`' +old_postinstall_cmds='`$ECHO "X$old_postinstall_cmds" | $Xsed -e "$delay_single_quote_subst"`' +old_postuninstall_cmds='`$ECHO "X$old_postuninstall_cmds" | $Xsed -e "$delay_single_quote_subst"`' +old_archive_cmds='`$ECHO "X$old_archive_cmds" | $Xsed -e "$delay_single_quote_subst"`' +CC='`$ECHO "X$CC" | $Xsed -e "$delay_single_quote_subst"`' +CFLAGS='`$ECHO "X$CFLAGS" | $Xsed -e "$delay_single_quote_subst"`' +compiler='`$ECHO "X$compiler" | $Xsed -e "$delay_single_quote_subst"`' +GCC='`$ECHO "X$GCC" | $Xsed -e "$delay_single_quote_subst"`' +lt_cv_sys_global_symbol_pipe='`$ECHO "X$lt_cv_sys_global_symbol_pipe" | $Xsed -e "$delay_single_quote_subst"`' +lt_cv_sys_global_symbol_to_cdecl='`$ECHO "X$lt_cv_sys_global_symbol_to_cdecl" | $Xsed -e "$delay_single_quote_subst"`' +lt_cv_sys_global_symbol_to_c_name_address='`$ECHO "X$lt_cv_sys_global_symbol_to_c_name_address" | $Xsed -e "$delay_single_quote_subst"`' +lt_cv_sys_global_symbol_to_c_name_address_lib_prefix='`$ECHO "X$lt_cv_sys_global_symbol_to_c_name_address_lib_prefix" | $Xsed -e "$delay_single_quote_subst"`' +objdir='`$ECHO "X$objdir" | $Xsed -e "$delay_single_quote_subst"`' +SHELL='`$ECHO "X$SHELL" | $Xsed -e "$delay_single_quote_subst"`' +ECHO='`$ECHO "X$ECHO" | $Xsed -e "$delay_single_quote_subst"`' +MAGIC_CMD='`$ECHO "X$MAGIC_CMD" | $Xsed -e "$delay_single_quote_subst"`' +lt_prog_compiler_no_builtin_flag='`$ECHO "X$lt_prog_compiler_no_builtin_flag" | $Xsed -e "$delay_single_quote_subst"`' +lt_prog_compiler_wl='`$ECHO "X$lt_prog_compiler_wl" | $Xsed -e "$delay_single_quote_subst"`' +lt_prog_compiler_pic='`$ECHO "X$lt_prog_compiler_pic" | $Xsed -e "$delay_single_quote_subst"`' +lt_prog_compiler_static='`$ECHO "X$lt_prog_compiler_static" | $Xsed -e "$delay_single_quote_subst"`' +lt_cv_prog_compiler_c_o='`$ECHO "X$lt_cv_prog_compiler_c_o" | $Xsed -e "$delay_single_quote_subst"`' +need_locks='`$ECHO "X$need_locks" | $Xsed -e "$delay_single_quote_subst"`' +DSYMUTIL='`$ECHO "X$DSYMUTIL" | $Xsed -e "$delay_single_quote_subst"`' +NMEDIT='`$ECHO "X$NMEDIT" | $Xsed -e "$delay_single_quote_subst"`' +LIPO='`$ECHO "X$LIPO" | $Xsed -e "$delay_single_quote_subst"`' +OTOOL='`$ECHO "X$OTOOL" | $Xsed -e "$delay_single_quote_subst"`' +OTOOL64='`$ECHO "X$OTOOL64" | $Xsed -e "$delay_single_quote_subst"`' +libext='`$ECHO "X$libext" | $Xsed -e "$delay_single_quote_subst"`' +shrext_cmds='`$ECHO "X$shrext_cmds" | $Xsed -e "$delay_single_quote_subst"`' +extract_expsyms_cmds='`$ECHO "X$extract_expsyms_cmds" | $Xsed -e "$delay_single_quote_subst"`' +archive_cmds_need_lc='`$ECHO "X$archive_cmds_need_lc" | $Xsed -e "$delay_single_quote_subst"`' +enable_shared_with_static_runtimes='`$ECHO "X$enable_shared_with_static_runtimes" | $Xsed -e "$delay_single_quote_subst"`' +export_dynamic_flag_spec='`$ECHO "X$export_dynamic_flag_spec" | $Xsed -e "$delay_single_quote_subst"`' +whole_archive_flag_spec='`$ECHO "X$whole_archive_flag_spec" | $Xsed -e "$delay_single_quote_subst"`' +compiler_needs_object='`$ECHO "X$compiler_needs_object" | $Xsed -e "$delay_single_quote_subst"`' +old_archive_from_new_cmds='`$ECHO "X$old_archive_from_new_cmds" | $Xsed -e "$delay_single_quote_subst"`' +old_archive_from_expsyms_cmds='`$ECHO "X$old_archive_from_expsyms_cmds" | $Xsed -e "$delay_single_quote_subst"`' +archive_cmds='`$ECHO "X$archive_cmds" | $Xsed -e "$delay_single_quote_subst"`' +archive_expsym_cmds='`$ECHO "X$archive_expsym_cmds" | $Xsed -e "$delay_single_quote_subst"`' +module_cmds='`$ECHO "X$module_cmds" | $Xsed -e "$delay_single_quote_subst"`' +module_expsym_cmds='`$ECHO "X$module_expsym_cmds" | $Xsed -e "$delay_single_quote_subst"`' +with_gnu_ld='`$ECHO "X$with_gnu_ld" | $Xsed -e "$delay_single_quote_subst"`' +allow_undefined_flag='`$ECHO "X$allow_undefined_flag" | $Xsed -e "$delay_single_quote_subst"`' +no_undefined_flag='`$ECHO "X$no_undefined_flag" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_libdir_flag_spec='`$ECHO "X$hardcode_libdir_flag_spec" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_libdir_flag_spec_ld='`$ECHO "X$hardcode_libdir_flag_spec_ld" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_libdir_separator='`$ECHO "X$hardcode_libdir_separator" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_direct='`$ECHO "X$hardcode_direct" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_direct_absolute='`$ECHO "X$hardcode_direct_absolute" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_minus_L='`$ECHO "X$hardcode_minus_L" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_shlibpath_var='`$ECHO "X$hardcode_shlibpath_var" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_automatic='`$ECHO "X$hardcode_automatic" | $Xsed -e "$delay_single_quote_subst"`' +inherit_rpath='`$ECHO "X$inherit_rpath" | $Xsed -e "$delay_single_quote_subst"`' +link_all_deplibs='`$ECHO "X$link_all_deplibs" | $Xsed -e "$delay_single_quote_subst"`' +fix_srcfile_path='`$ECHO "X$fix_srcfile_path" | $Xsed -e "$delay_single_quote_subst"`' +always_export_symbols='`$ECHO "X$always_export_symbols" | $Xsed -e "$delay_single_quote_subst"`' +export_symbols_cmds='`$ECHO "X$export_symbols_cmds" | $Xsed -e "$delay_single_quote_subst"`' +exclude_expsyms='`$ECHO "X$exclude_expsyms" | $Xsed -e "$delay_single_quote_subst"`' +include_expsyms='`$ECHO "X$include_expsyms" | $Xsed -e "$delay_single_quote_subst"`' +prelink_cmds='`$ECHO "X$prelink_cmds" | $Xsed -e "$delay_single_quote_subst"`' +file_list_spec='`$ECHO "X$file_list_spec" | $Xsed -e "$delay_single_quote_subst"`' +variables_saved_for_relink='`$ECHO "X$variables_saved_for_relink" | $Xsed -e "$delay_single_quote_subst"`' +need_lib_prefix='`$ECHO "X$need_lib_prefix" | $Xsed -e "$delay_single_quote_subst"`' +need_version='`$ECHO "X$need_version" | $Xsed -e "$delay_single_quote_subst"`' +version_type='`$ECHO "X$version_type" | $Xsed -e "$delay_single_quote_subst"`' +runpath_var='`$ECHO "X$runpath_var" | $Xsed -e "$delay_single_quote_subst"`' +shlibpath_var='`$ECHO "X$shlibpath_var" | $Xsed -e "$delay_single_quote_subst"`' +shlibpath_overrides_runpath='`$ECHO "X$shlibpath_overrides_runpath" | $Xsed -e "$delay_single_quote_subst"`' +libname_spec='`$ECHO "X$libname_spec" | $Xsed -e "$delay_single_quote_subst"`' +library_names_spec='`$ECHO "X$library_names_spec" | $Xsed -e "$delay_single_quote_subst"`' +soname_spec='`$ECHO "X$soname_spec" | $Xsed -e "$delay_single_quote_subst"`' +postinstall_cmds='`$ECHO "X$postinstall_cmds" | $Xsed -e "$delay_single_quote_subst"`' +postuninstall_cmds='`$ECHO "X$postuninstall_cmds" | $Xsed -e "$delay_single_quote_subst"`' +finish_cmds='`$ECHO "X$finish_cmds" | $Xsed -e "$delay_single_quote_subst"`' +finish_eval='`$ECHO "X$finish_eval" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_into_libs='`$ECHO "X$hardcode_into_libs" | $Xsed -e "$delay_single_quote_subst"`' +sys_lib_search_path_spec='`$ECHO "X$sys_lib_search_path_spec" | $Xsed -e "$delay_single_quote_subst"`' +sys_lib_dlsearch_path_spec='`$ECHO "X$sys_lib_dlsearch_path_spec" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_action='`$ECHO "X$hardcode_action" | $Xsed -e "$delay_single_quote_subst"`' +enable_dlopen='`$ECHO "X$enable_dlopen" | $Xsed -e "$delay_single_quote_subst"`' +enable_dlopen_self='`$ECHO "X$enable_dlopen_self" | $Xsed -e "$delay_single_quote_subst"`' +enable_dlopen_self_static='`$ECHO "X$enable_dlopen_self_static" | $Xsed -e "$delay_single_quote_subst"`' +old_striplib='`$ECHO "X$old_striplib" | $Xsed -e "$delay_single_quote_subst"`' +striplib='`$ECHO "X$striplib" | $Xsed -e "$delay_single_quote_subst"`' +compiler_lib_search_dirs='`$ECHO "X$compiler_lib_search_dirs" | $Xsed -e "$delay_single_quote_subst"`' +predep_objects='`$ECHO "X$predep_objects" | $Xsed -e "$delay_single_quote_subst"`' +postdep_objects='`$ECHO "X$postdep_objects" | $Xsed -e "$delay_single_quote_subst"`' +predeps='`$ECHO "X$predeps" | $Xsed -e "$delay_single_quote_subst"`' +postdeps='`$ECHO "X$postdeps" | $Xsed -e "$delay_single_quote_subst"`' +compiler_lib_search_path='`$ECHO "X$compiler_lib_search_path" | $Xsed -e "$delay_single_quote_subst"`' +LD_CXX='`$ECHO "X$LD_CXX" | $Xsed -e "$delay_single_quote_subst"`' +old_archive_cmds_CXX='`$ECHO "X$old_archive_cmds_CXX" | $Xsed -e "$delay_single_quote_subst"`' +compiler_CXX='`$ECHO "X$compiler_CXX" | $Xsed -e "$delay_single_quote_subst"`' +GCC_CXX='`$ECHO "X$GCC_CXX" | $Xsed -e "$delay_single_quote_subst"`' +lt_prog_compiler_no_builtin_flag_CXX='`$ECHO "X$lt_prog_compiler_no_builtin_flag_CXX" | $Xsed -e "$delay_single_quote_subst"`' +lt_prog_compiler_wl_CXX='`$ECHO "X$lt_prog_compiler_wl_CXX" | $Xsed -e "$delay_single_quote_subst"`' +lt_prog_compiler_pic_CXX='`$ECHO "X$lt_prog_compiler_pic_CXX" | $Xsed -e "$delay_single_quote_subst"`' +lt_prog_compiler_static_CXX='`$ECHO "X$lt_prog_compiler_static_CXX" | $Xsed -e "$delay_single_quote_subst"`' +lt_cv_prog_compiler_c_o_CXX='`$ECHO "X$lt_cv_prog_compiler_c_o_CXX" | $Xsed -e "$delay_single_quote_subst"`' +archive_cmds_need_lc_CXX='`$ECHO "X$archive_cmds_need_lc_CXX" | $Xsed -e "$delay_single_quote_subst"`' +enable_shared_with_static_runtimes_CXX='`$ECHO "X$enable_shared_with_static_runtimes_CXX" | $Xsed -e "$delay_single_quote_subst"`' +export_dynamic_flag_spec_CXX='`$ECHO "X$export_dynamic_flag_spec_CXX" | $Xsed -e "$delay_single_quote_subst"`' +whole_archive_flag_spec_CXX='`$ECHO "X$whole_archive_flag_spec_CXX" | $Xsed -e "$delay_single_quote_subst"`' +compiler_needs_object_CXX='`$ECHO "X$compiler_needs_object_CXX" | $Xsed -e "$delay_single_quote_subst"`' +old_archive_from_new_cmds_CXX='`$ECHO "X$old_archive_from_new_cmds_CXX" | $Xsed -e "$delay_single_quote_subst"`' +old_archive_from_expsyms_cmds_CXX='`$ECHO "X$old_archive_from_expsyms_cmds_CXX" | $Xsed -e "$delay_single_quote_subst"`' +archive_cmds_CXX='`$ECHO "X$archive_cmds_CXX" | $Xsed -e "$delay_single_quote_subst"`' +archive_expsym_cmds_CXX='`$ECHO "X$archive_expsym_cmds_CXX" | $Xsed -e "$delay_single_quote_subst"`' +module_cmds_CXX='`$ECHO "X$module_cmds_CXX" | $Xsed -e "$delay_single_quote_subst"`' +module_expsym_cmds_CXX='`$ECHO "X$module_expsym_cmds_CXX" | $Xsed -e "$delay_single_quote_subst"`' +with_gnu_ld_CXX='`$ECHO "X$with_gnu_ld_CXX" | $Xsed -e "$delay_single_quote_subst"`' +allow_undefined_flag_CXX='`$ECHO "X$allow_undefined_flag_CXX" | $Xsed -e "$delay_single_quote_subst"`' +no_undefined_flag_CXX='`$ECHO "X$no_undefined_flag_CXX" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_libdir_flag_spec_CXX='`$ECHO "X$hardcode_libdir_flag_spec_CXX" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_libdir_flag_spec_ld_CXX='`$ECHO "X$hardcode_libdir_flag_spec_ld_CXX" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_libdir_separator_CXX='`$ECHO "X$hardcode_libdir_separator_CXX" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_direct_CXX='`$ECHO "X$hardcode_direct_CXX" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_direct_absolute_CXX='`$ECHO "X$hardcode_direct_absolute_CXX" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_minus_L_CXX='`$ECHO "X$hardcode_minus_L_CXX" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_shlibpath_var_CXX='`$ECHO "X$hardcode_shlibpath_var_CXX" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_automatic_CXX='`$ECHO "X$hardcode_automatic_CXX" | $Xsed -e "$delay_single_quote_subst"`' +inherit_rpath_CXX='`$ECHO "X$inherit_rpath_CXX" | $Xsed -e "$delay_single_quote_subst"`' +link_all_deplibs_CXX='`$ECHO "X$link_all_deplibs_CXX" | $Xsed -e "$delay_single_quote_subst"`' +fix_srcfile_path_CXX='`$ECHO "X$fix_srcfile_path_CXX" | $Xsed -e "$delay_single_quote_subst"`' +always_export_symbols_CXX='`$ECHO "X$always_export_symbols_CXX" | $Xsed -e "$delay_single_quote_subst"`' +export_symbols_cmds_CXX='`$ECHO "X$export_symbols_cmds_CXX" | $Xsed -e "$delay_single_quote_subst"`' +exclude_expsyms_CXX='`$ECHO "X$exclude_expsyms_CXX" | $Xsed -e "$delay_single_quote_subst"`' +include_expsyms_CXX='`$ECHO "X$include_expsyms_CXX" | $Xsed -e "$delay_single_quote_subst"`' +prelink_cmds_CXX='`$ECHO "X$prelink_cmds_CXX" | $Xsed -e "$delay_single_quote_subst"`' +file_list_spec_CXX='`$ECHO "X$file_list_spec_CXX" | $Xsed -e "$delay_single_quote_subst"`' +hardcode_action_CXX='`$ECHO "X$hardcode_action_CXX" | $Xsed -e "$delay_single_quote_subst"`' +compiler_lib_search_dirs_CXX='`$ECHO "X$compiler_lib_search_dirs_CXX" | $Xsed -e "$delay_single_quote_subst"`' +predep_objects_CXX='`$ECHO "X$predep_objects_CXX" | $Xsed -e "$delay_single_quote_subst"`' +postdep_objects_CXX='`$ECHO "X$postdep_objects_CXX" | $Xsed -e "$delay_single_quote_subst"`' +predeps_CXX='`$ECHO "X$predeps_CXX" | $Xsed -e "$delay_single_quote_subst"`' +postdeps_CXX='`$ECHO "X$postdeps_CXX" | $Xsed -e "$delay_single_quote_subst"`' +compiler_lib_search_path_CXX='`$ECHO "X$compiler_lib_search_path_CXX" | $Xsed -e "$delay_single_quote_subst"`' + +LTCC='$LTCC' +LTCFLAGS='$LTCFLAGS' +compiler='$compiler_DEFAULT' + +# Quote evaled strings. +for var in SED \ +GREP \ +EGREP \ +FGREP \ +LD \ +NM \ +LN_S \ +lt_SP2NL \ +lt_NL2SP \ +reload_flag \ +OBJDUMP \ +deplibs_check_method \ +file_magic_cmd \ +AR \ +AR_FLAGS \ +STRIP \ +RANLIB \ +CC \ +CFLAGS \ +compiler \ +lt_cv_sys_global_symbol_pipe \ +lt_cv_sys_global_symbol_to_cdecl \ +lt_cv_sys_global_symbol_to_c_name_address \ +lt_cv_sys_global_symbol_to_c_name_address_lib_prefix \ +SHELL \ +ECHO \ +lt_prog_compiler_no_builtin_flag \ +lt_prog_compiler_wl \ +lt_prog_compiler_pic \ +lt_prog_compiler_static \ +lt_cv_prog_compiler_c_o \ +need_locks \ +DSYMUTIL \ +NMEDIT \ +LIPO \ +OTOOL \ +OTOOL64 \ +shrext_cmds \ +export_dynamic_flag_spec \ +whole_archive_flag_spec \ +compiler_needs_object \ +with_gnu_ld \ +allow_undefined_flag \ +no_undefined_flag \ +hardcode_libdir_flag_spec \ +hardcode_libdir_flag_spec_ld \ +hardcode_libdir_separator \ +fix_srcfile_path \ +exclude_expsyms \ +include_expsyms \ +file_list_spec \ +variables_saved_for_relink \ +libname_spec \ +library_names_spec \ +soname_spec \ +finish_eval \ +old_striplib \ +striplib \ +compiler_lib_search_dirs \ +predep_objects \ +postdep_objects \ +predeps \ +postdeps \ +compiler_lib_search_path \ +LD_CXX \ +compiler_CXX \ +lt_prog_compiler_no_builtin_flag_CXX \ +lt_prog_compiler_wl_CXX \ +lt_prog_compiler_pic_CXX \ +lt_prog_compiler_static_CXX \ +lt_cv_prog_compiler_c_o_CXX \ +export_dynamic_flag_spec_CXX \ +whole_archive_flag_spec_CXX \ +compiler_needs_object_CXX \ +with_gnu_ld_CXX \ +allow_undefined_flag_CXX \ +no_undefined_flag_CXX \ +hardcode_libdir_flag_spec_CXX \ +hardcode_libdir_flag_spec_ld_CXX \ +hardcode_libdir_separator_CXX \ +fix_srcfile_path_CXX \ +exclude_expsyms_CXX \ +include_expsyms_CXX \ +file_list_spec_CXX \ +compiler_lib_search_dirs_CXX \ +predep_objects_CXX \ +postdep_objects_CXX \ +predeps_CXX \ +postdeps_CXX \ +compiler_lib_search_path_CXX; do + case \`eval \\\\\$ECHO "X\\\\\$\$var"\` in + *[\\\\\\\`\\"\\\$]*) + eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"X\\\$\$var\\" | \\\$Xsed -e \\"\\\$sed_quote_subst\\"\\\`\\\\\\"" + ;; + *) + eval "lt_\$var=\\\\\\"\\\$\$var\\\\\\"" + ;; + esac +done + +# Double-quote double-evaled strings. +for var in reload_cmds \ +old_postinstall_cmds \ +old_postuninstall_cmds \ +old_archive_cmds \ +extract_expsyms_cmds \ +old_archive_from_new_cmds \ +old_archive_from_expsyms_cmds \ +archive_cmds \ +archive_expsym_cmds \ +module_cmds \ +module_expsym_cmds \ +export_symbols_cmds \ +prelink_cmds \ +postinstall_cmds \ +postuninstall_cmds \ +finish_cmds \ +sys_lib_search_path_spec \ +sys_lib_dlsearch_path_spec \ +old_archive_cmds_CXX \ +old_archive_from_new_cmds_CXX \ +old_archive_from_expsyms_cmds_CXX \ +archive_cmds_CXX \ +archive_expsym_cmds_CXX \ +module_cmds_CXX \ +module_expsym_cmds_CXX \ +export_symbols_cmds_CXX \ +prelink_cmds_CXX; do + case \`eval \\\\\$ECHO "X\\\\\$\$var"\` in + *[\\\\\\\`\\"\\\$]*) + eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"X\\\$\$var\\" | \\\$Xsed -e \\"\\\$double_quote_subst\\" -e \\"\\\$sed_quote_subst\\" -e \\"\\\$delay_variable_subst\\"\\\`\\\\\\"" + ;; + *) + eval "lt_\$var=\\\\\\"\\\$\$var\\\\\\"" + ;; + esac +done + +# Fix-up fallback echo if it was mangled by the above quoting rules. +case \$lt_ECHO in +*'\\\$0 --fallback-echo"') lt_ECHO=\`\$ECHO "X\$lt_ECHO" | \$Xsed -e 's/\\\\\\\\\\\\\\\$0 --fallback-echo"\$/\$0 --fallback-echo"/'\` + ;; +esac + +ac_aux_dir='$ac_aux_dir' +xsi_shell='$xsi_shell' +lt_shell_append='$lt_shell_append' + +# See if we are running on zsh, and set the options which allow our +# commands through without removal of \ escapes INIT. +if test -n "\${ZSH_VERSION+set}" ; then + setopt NO_GLOB_SUBST +fi + + + PACKAGE='$PACKAGE' + VERSION='$VERSION' + TIMESTAMP='$TIMESTAMP' + RM='$RM' + ofile='$ofile' + + + + + + +_ACEOF + +cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 + +# Handling of arguments. +for ac_config_target in $ac_config_targets +do + case $ac_config_target in + "scripts/.autostuff/config.h") CONFIG_HEADERS="$CONFIG_HEADERS scripts/.autostuff/config.h" ;; + "depfiles") CONFIG_COMMANDS="$CONFIG_COMMANDS depfiles" ;; + "libtool") CONFIG_COMMANDS="$CONFIG_COMMANDS libtool" ;; + "Makefile") CONFIG_FILES="$CONFIG_FILES Makefile" ;; + "docs/Makefile") CONFIG_FILES="$CONFIG_FILES docs/Makefile" ;; + "libs/Makefile") CONFIG_FILES="$CONFIG_FILES libs/Makefile" ;; + "libs/images/Makefile") CONFIG_FILES="$CONFIG_FILES libs/images/Makefile" ;; + "libs/lxdialog/Makefile") CONFIG_FILES="$CONFIG_FILES libs/lxdialog/Makefile" ;; + "libs/parser/Makefile") CONFIG_FILES="$CONFIG_FILES libs/parser/Makefile" ;; + "frontends/Makefile") CONFIG_FILES="$CONFIG_FILES frontends/Makefile" ;; + "frontends/conf/Makefile") CONFIG_FILES="$CONFIG_FILES frontends/conf/Makefile" ;; + "frontends/mconf/Makefile") CONFIG_FILES="$CONFIG_FILES frontends/mconf/Makefile" ;; + "frontends/nconf/Makefile") CONFIG_FILES="$CONFIG_FILES frontends/nconf/Makefile" ;; + "frontends/gconf/Makefile") CONFIG_FILES="$CONFIG_FILES frontends/gconf/Makefile" ;; + "frontends/qconf/Makefile") CONFIG_FILES="$CONFIG_FILES frontends/qconf/Makefile" ;; + "utils/Makefile") CONFIG_FILES="$CONFIG_FILES utils/Makefile" ;; + "scripts/Makefile") CONFIG_FILES="$CONFIG_FILES scripts/Makefile" ;; + + *) as_fn_error $? "invalid argument: \`$ac_config_target'" "$LINENO" 5 ;; + esac +done + + +# If the user did not use the arguments to specify the items to instantiate, +# then the envvar interface is used. Set only those that are not. +# We use the long form for the default assignment because of an extremely +# bizarre bug on SunOS 4.1.3. +if $ac_need_defaults; then + test "${CONFIG_FILES+set}" = set || CONFIG_FILES=$config_files + test "${CONFIG_HEADERS+set}" = set || CONFIG_HEADERS=$config_headers + test "${CONFIG_COMMANDS+set}" = set || CONFIG_COMMANDS=$config_commands +fi + +# Have a temporary directory for convenience. Make it in the build tree +# simply because there is no reason against having it here, and in addition, +# creating and moving files from /tmp can sometimes cause problems. +# Hook for its removal unless debugging. +# Note that there is a small window in which the directory will not be cleaned: +# after its creation but before its name has been assigned to `$tmp'. +$debug || +{ + tmp= + trap 'exit_status=$? + { test -z "$tmp" || test ! -d "$tmp" || rm -fr "$tmp"; } && exit $exit_status +' 0 + trap 'as_fn_exit 1' 1 2 13 15 +} +# Create a (secure) tmp directory for tmp files. + +{ + tmp=`(umask 077 && mktemp -d "./confXXXXXX") 2>/dev/null` && + test -n "$tmp" && test -d "$tmp" +} || +{ + tmp=./conf$$-$RANDOM + (umask 077 && mkdir "$tmp") +} || as_fn_error $? "cannot create a temporary directory in ." "$LINENO" 5 + +# Set up the scripts for CONFIG_FILES section. +# No need to generate them if there are no CONFIG_FILES. +# This happens for instance with `./config.status config.h'. +if test -n "$CONFIG_FILES"; then + + +ac_cr=`echo X | tr X '\015'` +# On cygwin, bash can eat \r inside `` if the user requested igncr. +# But we know of no other shell where ac_cr would be empty at this +# point, so we can use a bashism as a fallback. +if test "x$ac_cr" = x; then + eval ac_cr=\$\'\\r\' +fi +ac_cs_awk_cr=`$AWK 'BEGIN { print "a\rb" }' /dev/null` +if test "$ac_cs_awk_cr" = "a${ac_cr}b"; then + ac_cs_awk_cr='\\r' +else + ac_cs_awk_cr=$ac_cr +fi + +echo 'BEGIN {' >"$tmp/subs1.awk" && +_ACEOF + + +{ + echo "cat >conf$$subs.awk <<_ACEOF" && + echo "$ac_subst_vars" | sed 's/.*/&!$&$ac_delim/' && + echo "_ACEOF" +} >conf$$subs.sh || + as_fn_error $? "could not make $CONFIG_STATUS" "$LINENO" 5 +ac_delim_num=`echo "$ac_subst_vars" | grep -c '^'` +ac_delim='%!_!# ' +for ac_last_try in false false false false false :; do + . ./conf$$subs.sh || + as_fn_error $? "could not make $CONFIG_STATUS" "$LINENO" 5 + + ac_delim_n=`sed -n "s/.*$ac_delim\$/X/p" conf$$subs.awk | grep -c X` + if test $ac_delim_n = $ac_delim_num; then + break + elif $ac_last_try; then + as_fn_error $? "could not make $CONFIG_STATUS" "$LINENO" 5 + else + ac_delim="$ac_delim!$ac_delim _$ac_delim!! " + fi +done +rm -f conf$$subs.sh + +cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1 +cat >>"\$tmp/subs1.awk" <<\\_ACAWK && +_ACEOF +sed -n ' +h +s/^/S["/; s/!.*/"]=/ +p +g +s/^[^!]*!// +:repl +t repl +s/'"$ac_delim"'$// +t delim +:nl +h +s/\(.\{148\}\)..*/\1/ +t more1 +s/["\\]/\\&/g; s/^/"/; s/$/\\n"\\/ +p +n +b repl +:more1 +s/["\\]/\\&/g; s/^/"/; s/$/"\\/ +p +g +s/.\{148\}// +t nl +:delim +h +s/\(.\{148\}\)..*/\1/ +t more2 +s/["\\]/\\&/g; s/^/"/; s/$/"/ +p +b +:more2 +s/["\\]/\\&/g; s/^/"/; s/$/"\\/ +p +g +s/.\{148\}// +t delim +' >$CONFIG_STATUS || ac_write_fail=1 +rm -f conf$$subs.awk +cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1 +_ACAWK +cat >>"\$tmp/subs1.awk" <<_ACAWK && + for (key in S) S_is_set[key] = 1 + FS = "" + +} +{ + line = $ 0 + nfields = split(line, field, "@") + substed = 0 + len = length(field[1]) + for (i = 2; i < nfields; i++) { + key = field[i] + keylen = length(key) + if (S_is_set[key]) { + value = S[key] + line = substr(line, 1, len) "" value "" substr(line, len + keylen + 3) + len += length(value) + length(field[++i]) + substed = 1 + } else + len += 1 + keylen + } + + print line +} + +_ACAWK +_ACEOF +cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 +if sed "s/$ac_cr//" < /dev/null > /dev/null 2>&1; then + sed "s/$ac_cr\$//; s/$ac_cr/$ac_cs_awk_cr/g" +else + cat +fi < "$tmp/subs1.awk" > "$tmp/subs.awk" \ + || as_fn_error $? "could not setup config files machinery" "$LINENO" 5 +_ACEOF + +# VPATH may cause trouble with some makes, so we remove sole $(srcdir), +# ${srcdir} and @srcdir@ entries from VPATH if srcdir is ".", strip leading and +# trailing colons and then remove the whole line if VPATH becomes empty +# (actually we leave an empty line to preserve line numbers). +if test "x$srcdir" = x.; then + ac_vpsub='/^[ ]*VPATH[ ]*=[ ]*/{ +h +s/// +s/^/:/ +s/[ ]*$/:/ +s/:\$(srcdir):/:/g +s/:\${srcdir}:/:/g +s/:@srcdir@:/:/g +s/^:*// +s/:*$// +x +s/\(=[ ]*\).*/\1/ +G +s/\n// +s/^[^=]*=[ ]*$// +}' +fi + +cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 +fi # test -n "$CONFIG_FILES" + +# Set up the scripts for CONFIG_HEADERS section. +# No need to generate them if there are no CONFIG_HEADERS. +# This happens for instance with `./config.status Makefile'. +if test -n "$CONFIG_HEADERS"; then +cat >"$tmp/defines.awk" <<\_ACAWK || +BEGIN { +_ACEOF + +# Transform confdefs.h into an awk script `defines.awk', embedded as +# here-document in config.status, that substitutes the proper values into +# config.h.in to produce config.h. + +# Create a delimiter string that does not exist in confdefs.h, to ease +# handling of long lines. +ac_delim='%!_!# ' +for ac_last_try in false false :; do + ac_t=`sed -n "/$ac_delim/p" confdefs.h` + if test -z "$ac_t"; then + break + elif $ac_last_try; then + as_fn_error $? "could not make $CONFIG_HEADERS" "$LINENO" 5 + else + ac_delim="$ac_delim!$ac_delim _$ac_delim!! " + fi +done + +# For the awk script, D is an array of macro values keyed by name, +# likewise P contains macro parameters if any. Preserve backslash +# newline sequences. + +ac_word_re=[_$as_cr_Letters][_$as_cr_alnum]* +sed -n ' +s/.\{148\}/&'"$ac_delim"'/g +t rset +:rset +s/^[ ]*#[ ]*define[ ][ ]*/ / +t def +d +:def +s/\\$// +t bsnl +s/["\\]/\\&/g +s/^ \('"$ac_word_re"'\)\(([^()]*)\)[ ]*\(.*\)/P["\1"]="\2"\ +D["\1"]=" \3"/p +s/^ \('"$ac_word_re"'\)[ ]*\(.*\)/D["\1"]=" \2"/p +d +:bsnl +s/["\\]/\\&/g +s/^ \('"$ac_word_re"'\)\(([^()]*)\)[ ]*\(.*\)/P["\1"]="\2"\ +D["\1"]=" \3\\\\\\n"\\/p +t cont +s/^ \('"$ac_word_re"'\)[ ]*\(.*\)/D["\1"]=" \2\\\\\\n"\\/p +t cont +d +:cont +n +s/.\{148\}/&'"$ac_delim"'/g +t clear +:clear +s/\\$// +t bsnlc +s/["\\]/\\&/g; s/^/"/; s/$/"/p +d +:bsnlc +s/["\\]/\\&/g; s/^/"/; s/$/\\\\\\n"\\/p +b cont +' >$CONFIG_STATUS || ac_write_fail=1 + +cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1 + for (key in D) D_is_set[key] = 1 + FS = "" +} +/^[\t ]*#[\t ]*(define|undef)[\t ]+$ac_word_re([\t (]|\$)/ { + line = \$ 0 + split(line, arg, " ") + if (arg[1] == "#") { + defundef = arg[2] + mac1 = arg[3] + } else { + defundef = substr(arg[1], 2) + mac1 = arg[2] + } + split(mac1, mac2, "(") #) + macro = mac2[1] + prefix = substr(line, 1, index(line, defundef) - 1) + if (D_is_set[macro]) { + # Preserve the white space surrounding the "#". + print prefix "define", macro P[macro] D[macro] + next + } else { + # Replace #undef with comments. This is necessary, for example, + # in the case of _POSIX_SOURCE, which is predefined and required + # on some systems where configure will not decide to define it. + if (defundef == "undef") { + print "/*", prefix defundef, macro, "*/" + next + } + } +} +{ print } +_ACAWK +_ACEOF +cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 + as_fn_error $? "could not setup config headers machinery" "$LINENO" 5 +fi # test -n "$CONFIG_HEADERS" + + +eval set X " :F $CONFIG_FILES :H $CONFIG_HEADERS :C $CONFIG_COMMANDS" +shift +for ac_tag +do + case $ac_tag in + :[FHLC]) ac_mode=$ac_tag; continue;; + esac + case $ac_mode$ac_tag in + :[FHL]*:*);; + :L* | :C*:*) as_fn_error $? "invalid tag \`$ac_tag'" "$LINENO" 5 ;; + :[FH]-) ac_tag=-:-;; + :[FH]*) ac_tag=$ac_tag:$ac_tag.in;; + esac + ac_save_IFS=$IFS + IFS=: + set x $ac_tag + IFS=$ac_save_IFS + shift + ac_file=$1 + shift + + case $ac_mode in + :L) ac_source=$1;; + :[FH]) + ac_file_inputs= + for ac_f + do + case $ac_f in + -) ac_f="$tmp/stdin";; + *) # Look for the file first in the build tree, then in the source tree + # (if the path is not absolute). The absolute path cannot be DOS-style, + # because $ac_f cannot contain `:'. + test -f "$ac_f" || + case $ac_f in + [\\/$]*) false;; + *) test -f "$srcdir/$ac_f" && ac_f="$srcdir/$ac_f";; + esac || + as_fn_error 1 "cannot find input file: \`$ac_f'" "$LINENO" 5 ;; + esac + case $ac_f in *\'*) ac_f=`$as_echo "$ac_f" | sed "s/'/'\\\\\\\\''/g"`;; esac + as_fn_append ac_file_inputs " '$ac_f'" + done + + # Let's still pretend it is `configure' which instantiates (i.e., don't + # use $as_me), people would be surprised to read: + # /* config.h. Generated by config.status. */ + configure_input='Generated from '` + $as_echo "$*" | sed 's|^[^:]*/||;s|:[^:]*/|, |g' + `' by configure.' + if test x"$ac_file" != x-; then + configure_input="$ac_file. $configure_input" + { $as_echo "$as_me:${as_lineno-$LINENO}: creating $ac_file" >&5 +$as_echo "$as_me: creating $ac_file" >&6;} + fi + # Neutralize special characters interpreted by sed in replacement strings. + case $configure_input in #( + *\&* | *\|* | *\\* ) + ac_sed_conf_input=`$as_echo "$configure_input" | + sed 's/[\\\\&|]/\\\\&/g'`;; #( + *) ac_sed_conf_input=$configure_input;; + esac + + case $ac_tag in + *:-:* | *:-) cat >"$tmp/stdin" \ + || as_fn_error $? "could not create $ac_file" "$LINENO" 5 ;; + esac + ;; + esac + + ac_dir=`$as_dirname -- "$ac_file" || +$as_expr X"$ac_file" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \ + X"$ac_file" : 'X\(//\)[^/]' \| \ + X"$ac_file" : 'X\(//\)$' \| \ + X"$ac_file" : 'X\(/\)' \| . 2>/dev/null || +$as_echo X"$ac_file" | + sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ + s//\1/ + q + } + /^X\(\/\/\)[^/].*/{ + s//\1/ + q + } + /^X\(\/\/\)$/{ + s//\1/ + q + } + /^X\(\/\).*/{ + s//\1/ + q + } + s/.*/./; q'` + as_dir="$ac_dir"; as_fn_mkdir_p + ac_builddir=. + +case "$ac_dir" in +.) ac_dir_suffix= ac_top_builddir_sub=. ac_top_build_prefix= ;; +*) + ac_dir_suffix=/`$as_echo "$ac_dir" | sed 's|^\.[\\/]||'` + # A ".." for each directory in $ac_dir_suffix. + ac_top_builddir_sub=`$as_echo "$ac_dir_suffix" | sed 's|/[^\\/]*|/..|g;s|/||'` + case $ac_top_builddir_sub in + "") ac_top_builddir_sub=. ac_top_build_prefix= ;; + *) ac_top_build_prefix=$ac_top_builddir_sub/ ;; + esac ;; +esac +ac_abs_top_builddir=$ac_pwd +ac_abs_builddir=$ac_pwd$ac_dir_suffix +# for backward compatibility: +ac_top_builddir=$ac_top_build_prefix + +case $srcdir in + .) # We are building in place. + ac_srcdir=. + ac_top_srcdir=$ac_top_builddir_sub + ac_abs_top_srcdir=$ac_pwd ;; + [\\/]* | ?:[\\/]* ) # Absolute name. + ac_srcdir=$srcdir$ac_dir_suffix; + ac_top_srcdir=$srcdir + ac_abs_top_srcdir=$srcdir ;; + *) # Relative name. + ac_srcdir=$ac_top_build_prefix$srcdir$ac_dir_suffix + ac_top_srcdir=$ac_top_build_prefix$srcdir + ac_abs_top_srcdir=$ac_pwd/$srcdir ;; +esac +ac_abs_srcdir=$ac_abs_top_srcdir$ac_dir_suffix + + + case $ac_mode in + :F) + # + # CONFIG_FILE + # + + case $INSTALL in + [\\/$]* | ?:[\\/]* ) ac_INSTALL=$INSTALL ;; + *) ac_INSTALL=$ac_top_build_prefix$INSTALL ;; + esac + ac_MKDIR_P=$MKDIR_P + case $MKDIR_P in + [\\/$]* | ?:[\\/]* ) ;; + */*) ac_MKDIR_P=$ac_top_build_prefix$MKDIR_P ;; + esac +_ACEOF + +cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 +# If the template does not know about datarootdir, expand it. +# FIXME: This hack should be removed a few years after 2.60. +ac_datarootdir_hack=; ac_datarootdir_seen= +ac_sed_dataroot=' +/datarootdir/ { + p + q +} +/@datadir@/p +/@docdir@/p +/@infodir@/p +/@localedir@/p +/@mandir@/p' +case `eval "sed -n \"\$ac_sed_dataroot\" $ac_file_inputs"` in +*datarootdir*) ac_datarootdir_seen=yes;; +*@datadir@*|*@docdir@*|*@infodir@*|*@localedir@*|*@mandir@*) + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $ac_file_inputs seems to ignore the --datarootdir setting" >&5 +$as_echo "$as_me: WARNING: $ac_file_inputs seems to ignore the --datarootdir setting" >&2;} +_ACEOF +cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1 + ac_datarootdir_hack=' + s&@datadir@&$datadir&g + s&@docdir@&$docdir&g + s&@infodir@&$infodir&g + s&@localedir@&$localedir&g + s&@mandir@&$mandir&g + s&\\\${datarootdir}&$datarootdir&g' ;; +esac +_ACEOF + +# Neutralize VPATH when `$srcdir' = `.'. +# Shell code in configure.ac might set extrasub. +# FIXME: do we really want to maintain this feature? +cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1 +ac_sed_extra="$ac_vpsub +$extrasub +_ACEOF +cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 +:t +/@[a-zA-Z_][a-zA-Z_0-9]*@/!b +s|@configure_input@|$ac_sed_conf_input|;t t +s&@top_builddir@&$ac_top_builddir_sub&;t t +s&@top_build_prefix@&$ac_top_build_prefix&;t t +s&@srcdir@&$ac_srcdir&;t t +s&@abs_srcdir@&$ac_abs_srcdir&;t t +s&@top_srcdir@&$ac_top_srcdir&;t t +s&@abs_top_srcdir@&$ac_abs_top_srcdir&;t t +s&@builddir@&$ac_builddir&;t t +s&@abs_builddir@&$ac_abs_builddir&;t t +s&@abs_top_builddir@&$ac_abs_top_builddir&;t t +s&@INSTALL@&$ac_INSTALL&;t t +s&@MKDIR_P@&$ac_MKDIR_P&;t t +$ac_datarootdir_hack +" +eval sed \"\$ac_sed_extra\" "$ac_file_inputs" | $AWK -f "$tmp/subs.awk" >$tmp/out \ + || as_fn_error $? "could not create $ac_file" "$LINENO" 5 + +test -z "$ac_datarootdir_hack$ac_datarootdir_seen" && + { ac_out=`sed -n '/\${datarootdir}/p' "$tmp/out"`; test -n "$ac_out"; } && + { ac_out=`sed -n '/^[ ]*datarootdir[ ]*:*=/p' "$tmp/out"`; test -z "$ac_out"; } && + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $ac_file contains a reference to the variable \`datarootdir' +which seems to be undefined. Please make sure it is defined" >&5 +$as_echo "$as_me: WARNING: $ac_file contains a reference to the variable \`datarootdir' +which seems to be undefined. Please make sure it is defined" >&2;} + + rm -f "$tmp/stdin" + case $ac_file in + -) cat "$tmp/out" && rm -f "$tmp/out";; + *) rm -f "$ac_file" && mv "$tmp/out" "$ac_file";; + esac \ + || as_fn_error $? "could not create $ac_file" "$LINENO" 5 + ;; + :H) + # + # CONFIG_HEADER + # + if test x"$ac_file" != x-; then + { + $as_echo "/* $configure_input */" \ + && eval '$AWK -f "$tmp/defines.awk"' "$ac_file_inputs" + } >"$tmp/config.h" \ + || as_fn_error $? "could not create $ac_file" "$LINENO" 5 + if diff "$ac_file" "$tmp/config.h" >/dev/null 2>&1; then + { $as_echo "$as_me:${as_lineno-$LINENO}: $ac_file is unchanged" >&5 +$as_echo "$as_me: $ac_file is unchanged" >&6;} + else + rm -f "$ac_file" + mv "$tmp/config.h" "$ac_file" \ + || as_fn_error $? "could not create $ac_file" "$LINENO" 5 + fi + else + $as_echo "/* $configure_input */" \ + && eval '$AWK -f "$tmp/defines.awk"' "$ac_file_inputs" \ + || as_fn_error $? "could not create -" "$LINENO" 5 + fi +# Compute "$ac_file"'s index in $config_headers. +_am_arg="$ac_file" +_am_stamp_count=1 +for _am_header in $config_headers :; do + case $_am_header in + $_am_arg | $_am_arg:* ) + break ;; + * ) + _am_stamp_count=`expr $_am_stamp_count + 1` ;; + esac +done +echo "timestamp for $_am_arg" >`$as_dirname -- "$_am_arg" || +$as_expr X"$_am_arg" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \ + X"$_am_arg" : 'X\(//\)[^/]' \| \ + X"$_am_arg" : 'X\(//\)$' \| \ + X"$_am_arg" : 'X\(/\)' \| . 2>/dev/null || +$as_echo X"$_am_arg" | + sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ + s//\1/ + q + } + /^X\(\/\/\)[^/].*/{ + s//\1/ + q + } + /^X\(\/\/\)$/{ + s//\1/ + q + } + /^X\(\/\).*/{ + s//\1/ + q + } + s/.*/./; q'`/stamp-h$_am_stamp_count + ;; + + :C) { $as_echo "$as_me:${as_lineno-$LINENO}: executing $ac_file commands" >&5 +$as_echo "$as_me: executing $ac_file commands" >&6;} + ;; + esac + + + case $ac_file$ac_mode in + "depfiles":C) test x"$AMDEP_TRUE" != x"" || { + # Autoconf 2.62 quotes --file arguments for eval, but not when files + # are listed without --file. Let's play safe and only enable the eval + # if we detect the quoting. + case $CONFIG_FILES in + *\'*) eval set x "$CONFIG_FILES" ;; + *) set x $CONFIG_FILES ;; + esac + shift + for mf + do + # Strip MF so we end up with the name of the file. + mf=`echo "$mf" | sed -e 's/:.*$//'` + # Check whether this is an Automake generated Makefile or not. + # We used to match only the files named `Makefile.in', but + # some people rename them; so instead we look at the file content. + # Grep'ing the first line is not enough: some people post-process + # each Makefile.in and add a new line on top of each file to say so. + # Grep'ing the whole file is not good either: AIX grep has a line + # limit of 2048, but all sed's we know have understand at least 4000. + if sed -n 's,^#.*generated by automake.*,X,p' "$mf" | grep X >/dev/null 2>&1; then + dirpart=`$as_dirname -- "$mf" || +$as_expr X"$mf" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \ + X"$mf" : 'X\(//\)[^/]' \| \ + X"$mf" : 'X\(//\)$' \| \ + X"$mf" : 'X\(/\)' \| . 2>/dev/null || +$as_echo X"$mf" | + sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ + s//\1/ + q + } + /^X\(\/\/\)[^/].*/{ + s//\1/ + q + } + /^X\(\/\/\)$/{ + s//\1/ + q + } + /^X\(\/\).*/{ + s//\1/ + q + } + s/.*/./; q'` + else + continue + fi + # Extract the definition of DEPDIR, am__include, and am__quote + # from the Makefile without running `make'. + DEPDIR=`sed -n 's/^DEPDIR = //p' < "$mf"` + test -z "$DEPDIR" && continue + am__include=`sed -n 's/^am__include = //p' < "$mf"` + test -z "am__include" && continue + am__quote=`sed -n 's/^am__quote = //p' < "$mf"` + # When using ansi2knr, U may be empty or an underscore; expand it + U=`sed -n 's/^U = //p' < "$mf"` + # Find all dependency output files, they are included files with + # $(DEPDIR) in their names. We invoke sed twice because it is the + # simplest approach to changing $(DEPDIR) to its actual value in the + # expansion. + for file in `sed -n " + s/^$am__include $am__quote\(.*(DEPDIR).*\)$am__quote"'$/\1/p' <"$mf" | \ + sed -e 's/\$(DEPDIR)/'"$DEPDIR"'/g' -e 's/\$U/'"$U"'/g'`; do + # Make sure the directory exists. + test -f "$dirpart/$file" && continue + fdir=`$as_dirname -- "$file" || +$as_expr X"$file" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \ + X"$file" : 'X\(//\)[^/]' \| \ + X"$file" : 'X\(//\)$' \| \ + X"$file" : 'X\(/\)' \| . 2>/dev/null || +$as_echo X"$file" | + sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ + s//\1/ + q + } + /^X\(\/\/\)[^/].*/{ + s//\1/ + q + } + /^X\(\/\/\)$/{ + s//\1/ + q + } + /^X\(\/\).*/{ + s//\1/ + q + } + s/.*/./; q'` + as_dir=$dirpart/$fdir; as_fn_mkdir_p + # echo "creating $dirpart/$file" + echo '# dummy' > "$dirpart/$file" + done + done +} + ;; + "libtool":C) + + # See if we are running on zsh, and set the options which allow our + # commands through without removal of \ escapes. + if test -n "${ZSH_VERSION+set}" ; then + setopt NO_GLOB_SUBST + fi + + cfgfile="${ofile}T" + trap "$RM \"$cfgfile\"; exit 1" 1 2 15 + $RM "$cfgfile" + + cat <<_LT_EOF >> "$cfgfile" +#! $SHELL + +# `$ECHO "$ofile" | sed 's%^.*/%%'` - Provide generalized library-building support services. +# Generated automatically by $as_me ($PACKAGE$TIMESTAMP) $VERSION +# Libtool was configured on host `(hostname || uname -n) 2>/dev/null | sed 1q`: +# NOTE: Changes made to this file will be lost: look at ltmain.sh. +# +# Copyright (C) 1996, 1997, 1998, 1999, 2000, 2001, 2003, 2004, 2005, +# 2006, 2007, 2008 Free Software Foundation, Inc. +# Written by Gordon Matzigkeit, 1996 +# +# This file is part of GNU Libtool. +# +# GNU Libtool is free software; you can redistribute it and/or +# modify it under the terms of the GNU General Public License as +# published by the Free Software Foundation; either version 2 of +# the License, or (at your option) any later version. +# +# As a special exception to the GNU General Public License, +# if you distribute this file as part of a program or library that +# is built using GNU Libtool, you may include this file under the +# same distribution terms that you use for the rest of that program. +# +# GNU Libtool is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with GNU Libtool; see the file COPYING. If not, a copy +# can be downloaded from http://www.gnu.org/licenses/gpl.html, or +# obtained by writing to the Free Software Foundation, Inc., +# 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. + + +# The names of the tagged configurations supported by this script. +available_tags="CXX " + +# ### BEGIN LIBTOOL CONFIG + +# Which release of libtool.m4 was used? +macro_version=$macro_version +macro_revision=$macro_revision + +# Whether or not to build static libraries. +build_old_libs=$enable_static + +# Whether or not to build shared libraries. +build_libtool_libs=$enable_shared + +# What type of objects to build. +pic_mode=$pic_mode + +# Whether or not to optimize for fast installation. +fast_install=$enable_fast_install + +# The host system. +host_alias=$host_alias +host=$host +host_os=$host_os + +# The build system. +build_alias=$build_alias +build=$build +build_os=$build_os + +# A sed program that does not truncate output. +SED=$lt_SED + +# Sed that helps us avoid accidentally triggering echo(1) options like -n. +Xsed="\$SED -e 1s/^X//" + +# A grep program that handles long lines. +GREP=$lt_GREP + +# An ERE matcher. +EGREP=$lt_EGREP + +# A literal string matcher. +FGREP=$lt_FGREP + +# A BSD- or MS-compatible name lister. +NM=$lt_NM + +# Whether we need soft or hard links. +LN_S=$lt_LN_S + +# What is the maximum length of a command? +max_cmd_len=$max_cmd_len + +# Object file suffix (normally "o"). +objext=$ac_objext + +# Executable file suffix (normally ""). +exeext=$exeext + +# whether the shell understands "unset". +lt_unset=$lt_unset + +# turn spaces into newlines. +SP2NL=$lt_lt_SP2NL + +# turn newlines into spaces. +NL2SP=$lt_lt_NL2SP + +# How to create reloadable object files. +reload_flag=$lt_reload_flag +reload_cmds=$lt_reload_cmds + +# An object symbol dumper. +OBJDUMP=$lt_OBJDUMP + +# Method to check whether dependent libraries are shared objects. +deplibs_check_method=$lt_deplibs_check_method + +# Command to use when deplibs_check_method == "file_magic". +file_magic_cmd=$lt_file_magic_cmd + +# The archiver. +AR=$lt_AR +AR_FLAGS=$lt_AR_FLAGS + +# A symbol stripping program. +STRIP=$lt_STRIP + +# Commands used to install an old-style archive. +RANLIB=$lt_RANLIB +old_postinstall_cmds=$lt_old_postinstall_cmds +old_postuninstall_cmds=$lt_old_postuninstall_cmds + +# A C compiler. +LTCC=$lt_CC + +# LTCC compiler flags. +LTCFLAGS=$lt_CFLAGS + +# Take the output of nm and produce a listing of raw symbols and C names. +global_symbol_pipe=$lt_lt_cv_sys_global_symbol_pipe + +# Transform the output of nm in a proper C declaration. +global_symbol_to_cdecl=$lt_lt_cv_sys_global_symbol_to_cdecl + +# Transform the output of nm in a C name address pair. +global_symbol_to_c_name_address=$lt_lt_cv_sys_global_symbol_to_c_name_address + +# Transform the output of nm in a C name address pair when lib prefix is needed. +global_symbol_to_c_name_address_lib_prefix=$lt_lt_cv_sys_global_symbol_to_c_name_address_lib_prefix + +# The name of the directory that contains temporary libtool files. +objdir=$objdir + +# Shell to use when invoking shell scripts. +SHELL=$lt_SHELL + +# An echo program that does not interpret backslashes. +ECHO=$lt_ECHO + +# Used to examine libraries when file_magic_cmd begins with "file". +MAGIC_CMD=$MAGIC_CMD + +# Must we lock files when doing compilation? +need_locks=$lt_need_locks + +# Tool to manipulate archived DWARF debug symbol files on Mac OS X. +DSYMUTIL=$lt_DSYMUTIL + +# Tool to change global to local symbols on Mac OS X. +NMEDIT=$lt_NMEDIT + +# Tool to manipulate fat objects and archives on Mac OS X. +LIPO=$lt_LIPO + +# ldd/readelf like tool for Mach-O binaries on Mac OS X. +OTOOL=$lt_OTOOL + +# ldd/readelf like tool for 64 bit Mach-O binaries on Mac OS X 10.4. +OTOOL64=$lt_OTOOL64 + +# Old archive suffix (normally "a"). +libext=$libext + +# Shared library suffix (normally ".so"). +shrext_cmds=$lt_shrext_cmds + +# The commands to extract the exported symbol list from a shared archive. +extract_expsyms_cmds=$lt_extract_expsyms_cmds + +# Variables whose values should be saved in libtool wrapper scripts and +# restored at link time. +variables_saved_for_relink=$lt_variables_saved_for_relink + +# Do we need the "lib" prefix for modules? +need_lib_prefix=$need_lib_prefix + +# Do we need a version for libraries? +need_version=$need_version + +# Library versioning type. +version_type=$version_type + +# Shared library runtime path variable. +runpath_var=$runpath_var + +# Shared library path variable. +shlibpath_var=$shlibpath_var + +# Is shlibpath searched before the hard-coded library search path? +shlibpath_overrides_runpath=$shlibpath_overrides_runpath + +# Format of library name prefix. +libname_spec=$lt_libname_spec + +# List of archive names. First name is the real one, the rest are links. +# The last name is the one that the linker finds with -lNAME +library_names_spec=$lt_library_names_spec + +# The coded name of the library, if different from the real name. +soname_spec=$lt_soname_spec + +# Command to use after installation of a shared archive. +postinstall_cmds=$lt_postinstall_cmds + +# Command to use after uninstallation of a shared archive. +postuninstall_cmds=$lt_postuninstall_cmds + +# Commands used to finish a libtool library installation in a directory. +finish_cmds=$lt_finish_cmds + +# As "finish_cmds", except a single script fragment to be evaled but +# not shown. +finish_eval=$lt_finish_eval + +# Whether we should hardcode library paths into libraries. +hardcode_into_libs=$hardcode_into_libs + +# Compile-time system search path for libraries. +sys_lib_search_path_spec=$lt_sys_lib_search_path_spec + +# Run-time system search path for libraries. +sys_lib_dlsearch_path_spec=$lt_sys_lib_dlsearch_path_spec + +# Whether dlopen is supported. +dlopen_support=$enable_dlopen + +# Whether dlopen of programs is supported. +dlopen_self=$enable_dlopen_self + +# Whether dlopen of statically linked programs is supported. +dlopen_self_static=$enable_dlopen_self_static + +# Commands to strip libraries. +old_striplib=$lt_old_striplib +striplib=$lt_striplib + + +# The linker used to build libraries. +LD=$lt_LD + +# Commands used to build an old-style archive. +old_archive_cmds=$lt_old_archive_cmds + +# A language specific compiler. +CC=$lt_compiler + +# Is the compiler the GNU compiler? +with_gcc=$GCC + +# Compiler flag to turn off builtin functions. +no_builtin_flag=$lt_lt_prog_compiler_no_builtin_flag + +# How to pass a linker flag through the compiler. +wl=$lt_lt_prog_compiler_wl + +# Additional compiler flags for building library objects. +pic_flag=$lt_lt_prog_compiler_pic + +# Compiler flag to prevent dynamic linking. +link_static_flag=$lt_lt_prog_compiler_static + +# Does compiler simultaneously support -c and -o options? +compiler_c_o=$lt_lt_cv_prog_compiler_c_o + +# Whether or not to add -lc for building shared libraries. +build_libtool_need_lc=$archive_cmds_need_lc + +# Whether or not to disallow shared libs when runtime libs are static. +allow_libtool_libs_with_static_runtimes=$enable_shared_with_static_runtimes + +# Compiler flag to allow reflexive dlopens. +export_dynamic_flag_spec=$lt_export_dynamic_flag_spec + +# Compiler flag to generate shared objects directly from archives. +whole_archive_flag_spec=$lt_whole_archive_flag_spec + +# Whether the compiler copes with passing no objects directly. +compiler_needs_object=$lt_compiler_needs_object + +# Create an old-style archive from a shared archive. +old_archive_from_new_cmds=$lt_old_archive_from_new_cmds + +# Create a temporary old-style archive to link instead of a shared archive. +old_archive_from_expsyms_cmds=$lt_old_archive_from_expsyms_cmds + +# Commands used to build a shared archive. +archive_cmds=$lt_archive_cmds +archive_expsym_cmds=$lt_archive_expsym_cmds + +# Commands used to build a loadable module if different from building +# a shared archive. +module_cmds=$lt_module_cmds +module_expsym_cmds=$lt_module_expsym_cmds + +# Whether we are building with GNU ld or not. +with_gnu_ld=$lt_with_gnu_ld + +# Flag that allows shared libraries with undefined symbols to be built. +allow_undefined_flag=$lt_allow_undefined_flag + +# Flag that enforces no undefined symbols. +no_undefined_flag=$lt_no_undefined_flag + +# Flag to hardcode \$libdir into a binary during linking. +# This must work even if \$libdir does not exist +hardcode_libdir_flag_spec=$lt_hardcode_libdir_flag_spec + +# If ld is used when linking, flag to hardcode \$libdir into a binary +# during linking. This must work even if \$libdir does not exist. +hardcode_libdir_flag_spec_ld=$lt_hardcode_libdir_flag_spec_ld + +# Whether we need a single "-rpath" flag with a separated argument. +hardcode_libdir_separator=$lt_hardcode_libdir_separator + +# Set to "yes" if using DIR/libNAME\${shared_ext} during linking hardcodes +# DIR into the resulting binary. +hardcode_direct=$hardcode_direct + +# Set to "yes" if using DIR/libNAME\${shared_ext} during linking hardcodes +# DIR into the resulting binary and the resulting library dependency is +# "absolute",i.e impossible to change by setting \${shlibpath_var} if the +# library is relocated. +hardcode_direct_absolute=$hardcode_direct_absolute + +# Set to "yes" if using the -LDIR flag during linking hardcodes DIR +# into the resulting binary. +hardcode_minus_L=$hardcode_minus_L + +# Set to "yes" if using SHLIBPATH_VAR=DIR during linking hardcodes DIR +# into the resulting binary. +hardcode_shlibpath_var=$hardcode_shlibpath_var + +# Set to "yes" if building a shared library automatically hardcodes DIR +# into the library and all subsequent libraries and executables linked +# against it. +hardcode_automatic=$hardcode_automatic + +# Set to yes if linker adds runtime paths of dependent libraries +# to runtime path list. +inherit_rpath=$inherit_rpath + +# Whether libtool must link a program against all its dependency libraries. +link_all_deplibs=$link_all_deplibs + +# Fix the shell variable \$srcfile for the compiler. +fix_srcfile_path=$lt_fix_srcfile_path + +# Set to "yes" if exported symbols are required. +always_export_symbols=$always_export_symbols + +# The commands to list exported symbols. +export_symbols_cmds=$lt_export_symbols_cmds + +# Symbols that should not be listed in the preloaded symbols. +exclude_expsyms=$lt_exclude_expsyms + +# Symbols that must always be exported. +include_expsyms=$lt_include_expsyms + +# Commands necessary for linking programs (against libraries) with templates. +prelink_cmds=$lt_prelink_cmds + +# Specify filename containing input files. +file_list_spec=$lt_file_list_spec + +# How to hardcode a shared library path into an executable. +hardcode_action=$hardcode_action + +# The directories searched by this compiler when creating a shared library. +compiler_lib_search_dirs=$lt_compiler_lib_search_dirs + +# Dependencies to place before and after the objects being linked to +# create a shared library. +predep_objects=$lt_predep_objects +postdep_objects=$lt_postdep_objects +predeps=$lt_predeps +postdeps=$lt_postdeps + +# The library search path used internally by the compiler when linking +# a shared library. +compiler_lib_search_path=$lt_compiler_lib_search_path + +# ### END LIBTOOL CONFIG + +_LT_EOF + + case $host_os in + aix3*) + cat <<\_LT_EOF >> "$cfgfile" +# AIX sometimes has problems with the GCC collect2 program. For some +# reason, if we set the COLLECT_NAMES environment variable, the problems +# vanish in a puff of smoke. +if test "X${COLLECT_NAMES+set}" != Xset; then + COLLECT_NAMES= + export COLLECT_NAMES +fi +_LT_EOF + ;; + esac + + +ltmain="$ac_aux_dir/ltmain.sh" + + + # We use sed instead of cat because bash on DJGPP gets confused if + # if finds mixed CR/LF and LF-only lines. Since sed operates in + # text mode, it properly converts lines to CR/LF. This bash problem + # is reportedly fixed, but why not run on old versions too? + sed '/^# Generated shell functions inserted here/q' "$ltmain" >> "$cfgfile" \ + || (rm -f "$cfgfile"; exit 1) + + case $xsi_shell in + yes) + cat << \_LT_EOF >> "$cfgfile" + +# func_dirname file append nondir_replacement +# Compute the dirname of FILE. If nonempty, add APPEND to the result, +# otherwise set result to NONDIR_REPLACEMENT. +func_dirname () +{ + case ${1} in + */*) func_dirname_result="${1%/*}${2}" ;; + * ) func_dirname_result="${3}" ;; + esac +} + +# func_basename file +func_basename () +{ + func_basename_result="${1##*/}" +} + +# func_dirname_and_basename file append nondir_replacement +# perform func_basename and func_dirname in a single function +# call: +# dirname: Compute the dirname of FILE. If nonempty, +# add APPEND to the result, otherwise set result +# to NONDIR_REPLACEMENT. +# value returned in "$func_dirname_result" +# basename: Compute filename of FILE. +# value retuned in "$func_basename_result" +# Implementation must be kept synchronized with func_dirname +# and func_basename. For efficiency, we do not delegate to +# those functions but instead duplicate the functionality here. +func_dirname_and_basename () +{ + case ${1} in + */*) func_dirname_result="${1%/*}${2}" ;; + * ) func_dirname_result="${3}" ;; + esac + func_basename_result="${1##*/}" +} + +# func_stripname prefix suffix name +# strip PREFIX and SUFFIX off of NAME. +# PREFIX and SUFFIX must not contain globbing or regex special +# characters, hashes, percent signs, but SUFFIX may contain a leading +# dot (in which case that matches only a dot). +func_stripname () +{ + # pdksh 5.2.14 does not do ${X%$Y} correctly if both X and Y are + # positional parameters, so assign one to ordinary parameter first. + func_stripname_result=${3} + func_stripname_result=${func_stripname_result#"${1}"} + func_stripname_result=${func_stripname_result%"${2}"} +} + +# func_opt_split +func_opt_split () +{ + func_opt_split_opt=${1%%=*} + func_opt_split_arg=${1#*=} +} + +# func_lo2o object +func_lo2o () +{ + case ${1} in + *.lo) func_lo2o_result=${1%.lo}.${objext} ;; + *) func_lo2o_result=${1} ;; + esac +} + +# func_xform libobj-or-source +func_xform () +{ + func_xform_result=${1%.*}.lo +} + +# func_arith arithmetic-term... +func_arith () +{ + func_arith_result=$(( $* )) +} + +# func_len string +# STRING may not start with a hyphen. +func_len () +{ + func_len_result=${#1} +} + +_LT_EOF + ;; + *) # Bourne compatible functions. + cat << \_LT_EOF >> "$cfgfile" + +# func_dirname file append nondir_replacement +# Compute the dirname of FILE. If nonempty, add APPEND to the result, +# otherwise set result to NONDIR_REPLACEMENT. +func_dirname () +{ + # Extract subdirectory from the argument. + func_dirname_result=`$ECHO "X${1}" | $Xsed -e "$dirname"` + if test "X$func_dirname_result" = "X${1}"; then + func_dirname_result="${3}" + else + func_dirname_result="$func_dirname_result${2}" + fi +} + +# func_basename file +func_basename () +{ + func_basename_result=`$ECHO "X${1}" | $Xsed -e "$basename"` +} + + +# func_stripname prefix suffix name +# strip PREFIX and SUFFIX off of NAME. +# PREFIX and SUFFIX must not contain globbing or regex special +# characters, hashes, percent signs, but SUFFIX may contain a leading +# dot (in which case that matches only a dot). +# func_strip_suffix prefix name +func_stripname () +{ + case ${2} in + .*) func_stripname_result=`$ECHO "X${3}" \ + | $Xsed -e "s%^${1}%%" -e "s%\\\\${2}\$%%"`;; + *) func_stripname_result=`$ECHO "X${3}" \ + | $Xsed -e "s%^${1}%%" -e "s%${2}\$%%"`;; + esac +} + +# sed scripts: +my_sed_long_opt='1s/^\(-[^=]*\)=.*/\1/;q' +my_sed_long_arg='1s/^-[^=]*=//' + +# func_opt_split +func_opt_split () +{ + func_opt_split_opt=`$ECHO "X${1}" | $Xsed -e "$my_sed_long_opt"` + func_opt_split_arg=`$ECHO "X${1}" | $Xsed -e "$my_sed_long_arg"` +} + +# func_lo2o object +func_lo2o () +{ + func_lo2o_result=`$ECHO "X${1}" | $Xsed -e "$lo2o"` +} + +# func_xform libobj-or-source +func_xform () +{ + func_xform_result=`$ECHO "X${1}" | $Xsed -e 's/\.[^.]*$/.lo/'` +} + +# func_arith arithmetic-term... +func_arith () +{ + func_arith_result=`expr "$@"` +} + +# func_len string +# STRING may not start with a hyphen. +func_len () +{ + func_len_result=`expr "$1" : ".*" 2>/dev/null || echo $max_cmd_len` +} + +_LT_EOF +esac + +case $lt_shell_append in + yes) + cat << \_LT_EOF >> "$cfgfile" + +# func_append var value +# Append VALUE to the end of shell variable VAR. +func_append () +{ + eval "$1+=\$2" +} +_LT_EOF + ;; + *) + cat << \_LT_EOF >> "$cfgfile" + +# func_append var value +# Append VALUE to the end of shell variable VAR. +func_append () +{ + eval "$1=\$$1\$2" +} + +_LT_EOF + ;; + esac + + + sed -n '/^# Generated shell functions inserted here/,$p' "$ltmain" >> "$cfgfile" \ + || (rm -f "$cfgfile"; exit 1) + + mv -f "$cfgfile" "$ofile" || + (rm -f "$ofile" && cp "$cfgfile" "$ofile" && rm -f "$cfgfile") + chmod +x "$ofile" + + + cat <<_LT_EOF >> "$ofile" + +# ### BEGIN LIBTOOL TAG CONFIG: CXX + +# The linker used to build libraries. +LD=$lt_LD_CXX + +# Commands used to build an old-style archive. +old_archive_cmds=$lt_old_archive_cmds_CXX + +# A language specific compiler. +CC=$lt_compiler_CXX + +# Is the compiler the GNU compiler? +with_gcc=$GCC_CXX + +# Compiler flag to turn off builtin functions. +no_builtin_flag=$lt_lt_prog_compiler_no_builtin_flag_CXX + +# How to pass a linker flag through the compiler. +wl=$lt_lt_prog_compiler_wl_CXX + +# Additional compiler flags for building library objects. +pic_flag=$lt_lt_prog_compiler_pic_CXX + +# Compiler flag to prevent dynamic linking. +link_static_flag=$lt_lt_prog_compiler_static_CXX + +# Does compiler simultaneously support -c and -o options? +compiler_c_o=$lt_lt_cv_prog_compiler_c_o_CXX + +# Whether or not to add -lc for building shared libraries. +build_libtool_need_lc=$archive_cmds_need_lc_CXX + +# Whether or not to disallow shared libs when runtime libs are static. +allow_libtool_libs_with_static_runtimes=$enable_shared_with_static_runtimes_CXX + +# Compiler flag to allow reflexive dlopens. +export_dynamic_flag_spec=$lt_export_dynamic_flag_spec_CXX + +# Compiler flag to generate shared objects directly from archives. +whole_archive_flag_spec=$lt_whole_archive_flag_spec_CXX + +# Whether the compiler copes with passing no objects directly. +compiler_needs_object=$lt_compiler_needs_object_CXX + +# Create an old-style archive from a shared archive. +old_archive_from_new_cmds=$lt_old_archive_from_new_cmds_CXX + +# Create a temporary old-style archive to link instead of a shared archive. +old_archive_from_expsyms_cmds=$lt_old_archive_from_expsyms_cmds_CXX + +# Commands used to build a shared archive. +archive_cmds=$lt_archive_cmds_CXX +archive_expsym_cmds=$lt_archive_expsym_cmds_CXX + +# Commands used to build a loadable module if different from building +# a shared archive. +module_cmds=$lt_module_cmds_CXX +module_expsym_cmds=$lt_module_expsym_cmds_CXX + +# Whether we are building with GNU ld or not. +with_gnu_ld=$lt_with_gnu_ld_CXX + +# Flag that allows shared libraries with undefined symbols to be built. +allow_undefined_flag=$lt_allow_undefined_flag_CXX + +# Flag that enforces no undefined symbols. +no_undefined_flag=$lt_no_undefined_flag_CXX + +# Flag to hardcode \$libdir into a binary during linking. +# This must work even if \$libdir does not exist +hardcode_libdir_flag_spec=$lt_hardcode_libdir_flag_spec_CXX + +# If ld is used when linking, flag to hardcode \$libdir into a binary +# during linking. This must work even if \$libdir does not exist. +hardcode_libdir_flag_spec_ld=$lt_hardcode_libdir_flag_spec_ld_CXX + +# Whether we need a single "-rpath" flag with a separated argument. +hardcode_libdir_separator=$lt_hardcode_libdir_separator_CXX + +# Set to "yes" if using DIR/libNAME\${shared_ext} during linking hardcodes +# DIR into the resulting binary. +hardcode_direct=$hardcode_direct_CXX + +# Set to "yes" if using DIR/libNAME\${shared_ext} during linking hardcodes +# DIR into the resulting binary and the resulting library dependency is +# "absolute",i.e impossible to change by setting \${shlibpath_var} if the +# library is relocated. +hardcode_direct_absolute=$hardcode_direct_absolute_CXX + +# Set to "yes" if using the -LDIR flag during linking hardcodes DIR +# into the resulting binary. +hardcode_minus_L=$hardcode_minus_L_CXX + +# Set to "yes" if using SHLIBPATH_VAR=DIR during linking hardcodes DIR +# into the resulting binary. +hardcode_shlibpath_var=$hardcode_shlibpath_var_CXX + +# Set to "yes" if building a shared library automatically hardcodes DIR +# into the library and all subsequent libraries and executables linked +# against it. +hardcode_automatic=$hardcode_automatic_CXX + +# Set to yes if linker adds runtime paths of dependent libraries +# to runtime path list. +inherit_rpath=$inherit_rpath_CXX + +# Whether libtool must link a program against all its dependency libraries. +link_all_deplibs=$link_all_deplibs_CXX + +# Fix the shell variable \$srcfile for the compiler. +fix_srcfile_path=$lt_fix_srcfile_path_CXX + +# Set to "yes" if exported symbols are required. +always_export_symbols=$always_export_symbols_CXX + +# The commands to list exported symbols. +export_symbols_cmds=$lt_export_symbols_cmds_CXX + +# Symbols that should not be listed in the preloaded symbols. +exclude_expsyms=$lt_exclude_expsyms_CXX + +# Symbols that must always be exported. +include_expsyms=$lt_include_expsyms_CXX + +# Commands necessary for linking programs (against libraries) with templates. +prelink_cmds=$lt_prelink_cmds_CXX + +# Specify filename containing input files. +file_list_spec=$lt_file_list_spec_CXX + +# How to hardcode a shared library path into an executable. +hardcode_action=$hardcode_action_CXX + +# The directories searched by this compiler when creating a shared library. +compiler_lib_search_dirs=$lt_compiler_lib_search_dirs_CXX + +# Dependencies to place before and after the objects being linked to +# create a shared library. +predep_objects=$lt_predep_objects_CXX +postdep_objects=$lt_postdep_objects_CXX +predeps=$lt_predeps_CXX +postdeps=$lt_postdeps_CXX + +# The library search path used internally by the compiler when linking +# a shared library. +compiler_lib_search_path=$lt_compiler_lib_search_path_CXX + +# ### END LIBTOOL TAG CONFIG: CXX +_LT_EOF + + ;; + + esac +done # for ac_tag + + +as_fn_exit 0 +_ACEOF +ac_clean_files=$ac_clean_files_save + +test $ac_write_fail = 0 || + as_fn_error $? "write failure creating $CONFIG_STATUS" "$LINENO" 5 + + +# configure is writing to config.log, and then calls config.status. +# config.status does its own redirection, appending to config.log. +# Unfortunately, on DOS this fails, as config.log is still kept open +# by configure, so config.status won't be able to write to it; its +# output is simply discarded. So we exec the FD to /dev/null, +# effectively closing config.log, so it can be properly (re)opened and +# appended to by config.status. When coming back to configure, we +# need to make the FD available again. +if test "$no_create" != yes; then + ac_cs_success=: + ac_config_status_args= + test "$silent" = yes && + ac_config_status_args="$ac_config_status_args --quiet" + exec 5>/dev/null + $SHELL $CONFIG_STATUS $ac_config_status_args || ac_cs_success=false + exec 5>>config.log + # Use ||, not &&, to avoid exiting from the if with $? = 1, which + # would make configure fail if this is the last instruction. + $ac_cs_success || as_fn_exit 1 +fi +if test -n "$ac_unrecognized_opts" && test "$enable_option_checking" != no; then + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: unrecognized options: $ac_unrecognized_opts" >&5 +$as_echo "$as_me: WARNING: unrecognized options: $ac_unrecognized_opts" >&2;} +fi + + +#---------------------------------------- +# Pretty-print the configuration settings +fe_list= +if test "$enable_conf" = "yes"; then : + fe_list="$fe_list conf" +fi +if test "$enable_gconf" = "yes"; then : + fe_list="$fe_list gconf" +fi +if test "$enable_mconf" = "yes"; then : + fe_list="$fe_list mconf" +fi +if test "$enable_nconf" = "yes"; then : + fe_list="$fe_list nconf" +fi +if test "$enable_qconf" = "yes"; then : + fe_list="$fe_list qconf" +fi + +lib_list= +if test "$enable_shared" = "yes"; then : + lib_list="$lib_list shared (version: $KCONFIGPARSER_LIB_VERSION)" +fi +if test "$enable_static" = "yes"; then : + lib_list="$lib_list${lib_list:+,} static" +fi + +{ $as_echo "$as_me:${as_lineno-$LINENO}: " >&5 +$as_echo "$as_me: " >&6;} +{ $as_echo "$as_me:${as_lineno-$LINENO}: Configured with:" >&5 +$as_echo "$as_me: Configured with:" >&6;} +{ $as_echo "$as_me:${as_lineno-$LINENO}: - parser library :$lib_list" >&5 +$as_echo "$as_me: - parser library :$lib_list" >&6;} +{ $as_echo "$as_me:${as_lineno-$LINENO}: - root-menu prompt : $root_menu" >&5 +$as_echo "$as_me: - root-menu prompt : $root_menu" >&6;} +{ $as_echo "$as_me:${as_lineno-$LINENO}: - config prefix : $config_prefix" >&5 +$as_echo "$as_me: - config prefix : $config_prefix" >&6;} +{ $as_echo "$as_me:${as_lineno-$LINENO}: - frontends :$fe_list" >&5 +$as_echo "$as_me: - frontends :$fe_list" >&6;} +{ $as_echo "$as_me:${as_lineno-$LINENO}: - transform name : $program_transform_name" >&5 +$as_echo "$as_me: - transform name : $program_transform_name" >&6;} +{ $as_echo "$as_me:${as_lineno-$LINENO}: - localised : $has_gettext" >&5 +$as_echo "$as_me: - localised : $has_gettext" >&6;} +{ $as_echo "$as_me:${as_lineno-$LINENO}: - install utilities : $enable_utils" >&5 +$as_echo "$as_me: - install utilities : $enable_utils" >&6;} +{ $as_echo "$as_me:${as_lineno-$LINENO}: - CFLAGS CXXFLAGS : $wall_CFLAGS $werror_CFLAGS" >&5 +$as_echo "$as_me: - CFLAGS CXXFLAGS : $wall_CFLAGS $werror_CFLAGS" >&6;} diff --git a/misc/tools/kconfig-frontends/configure.ac b/misc/tools/kconfig-frontends/configure.ac new file mode 100644 index 0000000000..895cd58cf9 --- /dev/null +++ b/misc/tools/kconfig-frontends/configure.ac @@ -0,0 +1,502 @@ +# -*- Autoconf -*- +# Process this file with autoconf to produce a configure script. + +#--------------------------------------------------------------------------- +# Global initialisation + +#---------------------------------------- +# Prepare autoconf +AC_PREREQ([2.67]) +AC_INIT( + [kconfig-frontends], + [m4_esyscmd_s([./scripts/version.sh])], + [yann.morin.1998@free.fr]) +AC_CONFIG_SRCDIR([frontends/conf/conf.c]) +# Use a config.h to avoid brazilions -DHAVE_FOO on compile lines +AC_CONFIG_HEADERS([scripts/.autostuff/config.h]) +AC_CONFIG_AUX_DIR([scripts/.autostuff/scripts]) +AC_CONFIG_MACRO_DIR([scripts/.autostuff/m4]) + +#---------------------------------------- +# Prepare automake + +# We want to allow the user to override our default program-prefix, +# so we must set-it now, before automake has a chance to interpret +# it, but after the options are parsed, so as not to overwrite the +# value (if any) set by the user +AS_IF( + [test "$program_prefix" = NONE], + [program_prefix=kconfig-]) + +AM_INIT_AUTOMAKE + +AS_IF( + [test "$(${srcdir}/scripts/version.sh --internal)" = "hg"], + [AM_SILENT_RULES], + [AM_SILENT_RULES([yes])]) + +AS_IF( + [test $AM_DEFAULT_VERBOSITY -eq 0], + [SILENT_MAKEFLAGS="--no-print-directory -s"], + [SILENT_MAKEFLAGS=""]) +AC_SUBST([SILENT_MAKEFLAGS]) + +#---------------------------------------- +# Prepare libtool +LT_PREREQ([2.2.6]) +LT_INIT([disable-static]) + +#--------------------------------------------------------------------------- +# Set misc options + +# By default, do not build with -Wall, unless the user asks for it +AC_ARG_ENABLE( + [wall], + [AS_HELP_STRING( + [--enable-wall], + [build with -Wall (default=no)])], + [AS_CASE( + ["$enableval"], + [yes], [wall_CFLAGS=-Wall], + [*], [wall_CFLAGS=""])]) +AC_SUBST([wall_CFLAGS],[${wall_CFLAGS}]) + +# By default, do not build with -Werror, unless the user asks for it +AC_ARG_ENABLE( + [werror], + [AS_HELP_STRING( + [--enable-werror], + [build with -Werror (default=no)])], + [AS_CASE( + ["$enableval"], + [yes], [werror_CFLAGS=-Werror], + [*], [werror_CFLAGS=""])]) +AC_SUBST([werror_CFLAGS],[${werror_CFLAGS}]) + +# Although there is a default (="linux") in the code, we do provide +# a default here, to get a consistent autostuff behavior +AC_ARG_ENABLE( + [root-menu-prompt], + [AS_HELP_STRING( + [--enable-root-menu-prompt=PROMPT], + [set the root-menu prompt (default=Configuration)])], + [AS_CASE( + ["$enableval"], + [yes], [root_menu=Configuration], + [no], [root_menu=], + [# Escape the $ signs, otherwise they would get munged by make + # Also, append a space at the end, to separate the package + # name from the literal 'Configuration' + root_menu="$( echo "$enableval" |sed -r -e 's/\$/\\$$/g;' )"])]) +AC_SUBST([root_menu], [${root_menu=Configuration}]) + +AC_ARG_ENABLE( + [config-prefix], + [AS_HELP_STRING( + [--enable-config-prefix=PREFIX], + [the prefix to the config option (default=CONFIG_)])], + [AS_CASE( + ["$enableval"], + [*" "*],[AC_MSG_ERROR([config prefix can not contain spaces: '$enableval'])], + [yes], [config_prefix=CONFIG_], + [no], [config_prefix=], + [config_prefix=$enableval])]) +AC_SUBST([config_prefix], [${config_prefix-CONFIG_}]) + +AC_ARG_ENABLE( + [utils], + [AS_HELP_STRING( + [--disable-utils], + [install utilities to manage .config files (default=no)])]) +AC_SUBST([enable_utils], [${enable_utils:-yes}]) + +AC_ARG_ENABLE( + [L10n], + [AS_HELP_STRING( + [--disable-L10n], + [enable localisation (L10n) (default=auto)])]) +AC_SUBST([enable_L10n], [${enable_L10n:-yes}]) + +#---------------------------------------- +# Options to selectively enable/disable frontends +# All are selected by default +AC_ARG_ENABLE( + [conf], + [AS_HELP_STRING( + [--disable-conf], + [conf, the stdin-based frontend (default=auto)])]) +AC_SUBST([enable_conf], [${enable_conf:-auto}]) +AC_ARG_ENABLE( + [mconf], + [AS_HELP_STRING( + [--disable-mconf], + [mconf, the traditional ncurses-based frontend (default=auto)])]) +AC_SUBST([enable_mconf], [${enable_mconf:-auto}]) +AC_ARG_ENABLE( + [nconf], + [AS_HELP_STRING( + [--disable-nconf], + [nconf, the modern ncurses-based frontend (default=auto)])]) +AC_SUBST([enable_nconf], [${enable_nconf:-auto}]) +AC_ARG_ENABLE( + [gconf], + [AS_HELP_STRING( + [--disable-gconf], + [gconf, the GTK-based frontend (default=auto)])]) +AC_SUBST([enable_gconf], [${enable_gconf:-auto}]) +AC_ARG_ENABLE( + [qconf], + [AS_HELP_STRING( + [--disable-qconf], + [qconf, the QT-based frontend (default=auto)])]) +AC_SUBST([enable_qconf], [${enable_qconf:-auto}]) + +AC_ARG_ENABLE( + [frontends], + [AS_HELP_STRING( + [--enable-frontends=list], + [enables only the set of frontends in comma-separated 'list' + (default: auto selection), takes precedence over all + --enable-*conf, above])], + [for f in conf mconf nconf gconf qconf; do + AS_CASE( + ["$enableval"], + [yes], [eval enable_$f=yes], + ["$f"], [eval enable_$f=yes], + ["$f",*], [eval enable_$f=yes], + [*,"$f"], [eval enable_$f=yes], + [*,"$f",*], [eval enable_$f=yes], + [eval enable_$f=no]) + done]) +AC_SUBST([enable_frontends]) + +#---------------------------------------- +# What extra CFLAGS we will be using +AC_SUBST([kf_CFLAGS], ["$wall_CFLAGS $werror_CFLAGS"]) + +#---------------------------------------- +# Dependencies that will be needed, depending on the frontends +AS_CASE( + ["$enable_mconf":"$enable_nconf"], + [*yes*], [need_curses=yes], + [*auto*], [need_curses=auto], + [need_curses=no]) +[need_panel_menu="$enable_nconf"] +AS_CASE( + ["$enable_gconf":"$enable_qconf"], + [*yes*], [need_pkgconfig=yes], + [*auto*], [need_pkgconfig=yes], + [need_pkgconfig=no ]) +[need_gtk="$enable_gconf"] +[need_qt="$enable_qconf"] + +#--------------------------------------------------------------------------- +# Now check we have the required stuff + +#---------------------------------------- +# Some program checks +AC_PROG_CC +AM_PROG_CC_C_O +AC_PROG_CXX +AC_C_INLINE +AC_PROG_MAKE_SET +AC_CHECK_PROGS( + [GPERF], + [gperf]) +AS_IF( + [test -z "$GPERF"], + [AC_MSG_ERROR([can not find gperf])]) +AS_IF( + [test "$need_pkgconfig" = "yes"], + [PKG_PROG_PKG_CONFIG()]) +AC_PROG_LEX +AC_SUBST([AM_LFLAGS], ["-L -P zconf"]) +AC_PROG_YACC +AC_SUBST([AM_YFLAGS], ["-t -l -p zconf"]) + +#---------------------------------------- +# Check for standard headers +AC_HEADER_STDC +AC_HEADER_STDBOOL +AC_CHECK_HEADERS([ fcntl.h limits.h locale.h ]) +AC_CHECK_HEADERS([ stdlib.h string.h sys/time.h unistd.h ]) +AC_TYPE_SIZE_T + +#---------------------------------------- +# Checks for library functions. +AC_FUNC_MALLOC +AC_FUNC_REALLOC +AC_FUNC_ALLOCA +AC_CHECK_FUNCS([ bzero memmove memset ]) +AC_CHECK_FUNCS([ strcasecmp strchr strcspn strdup strncasecmp strpbrk strrchr strspn strtol ]) +AC_CHECK_FUNCS([ gettimeofday mkdir regcomp setlocale uname ]) + +#---------------------------------------- +# Check for gettext, for the kconfig frontends +[has_gettext="$enable_L10n"] +AS_IF( + [test "$has_gettext" = "yes"], + [AC_CHECK_HEADERS( + [libintl.h], + [ac_ct_gettext_hdr=$ac_header; break], + [has_gettext=no])]) +AS_IF( + [test "$has_gettext" = "yes"], + [AC_CHECK_DECL( + [gettext],, + [has_gettext=no], + [#include <$ac_ct_gettext_hdr>])]) +AS_IF( + [test "$has_gettext" = "yes"], + [LIBS_old="$LIBS" + LIBS= + AC_SEARCH_LIBS( + [gettext], + [intl],, + [has_gettext=no]) + intl_LIBS="$LIBS" + LIBS="$LIBS_old"]) +AS_IF( + [test "$has_gettext" = "no"], + [intl_CPPFLAGS=-DKBUILD_NO_NLS]) +AC_SUBST([intl_CPPFLAGS]) +AC_SUBST([intl_LIBS]) + +#---------------------------------------- +# Check for ncurses, for the mconf & nconf frontends +AS_IF( + [test "$need_curses" = "yes" -o "$need_curses" = "auto"], + [AC_SUBST([CURSES_LOC]) + AC_SUBST([ncurses_LIBS]) + LIBS_old="$LIBS" + LIBS= + AC_CHECK_HEADERS( + [ncursesw/curses.h ncurses/ncurses.h ncurses/curses.h ncurses.h curses.h], + [CURSES_LOC=$ac_header; break]) + AS_IF( + [test -z "$CURSES_LOC"], + [AS_IF( + [test "$need_curses" = "yes"], + [AC_MSG_ERROR([could not find curses headers (frontends: mconf/nconf)])], + [has_curses=no])]) + AC_SEARCH_LIBS( + [initscr], + [ncursesw ncurses curses], + [ac_ct_curses_lib_found=yes; break]) + AS_IF( + [test -z "$ac_ct_curses_lib_found"], + [AS_IF( + [test "$need_curses" = "yes"], + [AC_MSG_ERROR([could not find curses library (frontends: mconf/nconf)])], + [has_curses=no])]) + ncurses_LIBS="$LIBS" + LIBS=$LIBS_old]) + +AS_IF( + [test "$has_curses" = "no" ], + [enable_mconf=no; enable_nconf=no]) + +#---------------------------------------- +# Check for libpanel and libmenu, for the nconf frontend +AS_IF( + [test "$need_panel_menu" = "yes" -o "$need_panel_menu" = "auto"], + [AC_SUBST([ncurses_extra_LIBS]) + AC_SUBST([ncurses_extra_CPPFLAGS]) + AS_CASE( + [$CURSES_LOC], + [ncursesw/*],[ncurses_extra_CPPFLAGS="-I/usr/include/ncursesw"], + [ncurses/*],[ncurses_extra_CPPFLAGS="-I/usr/include/ncurses"]) + LIBS_old="$LIBS" + LIBS= + AC_SEARCH_LIBS( + [new_panel], + [panelw panel], + [ac_ct_panel_lib_found=yes; break],, + [$ncurses_LIBS]) + AS_IF( + [test -z "$ac_ct_panel_lib_found"], + [AS_IF( + [test "$need_panel_menu" = "yes"], + [AC_MSG_ERROR([could not find libpanel library (frontend: nconf)])], + [has_panel_menu=no])]) + AC_SEARCH_LIBS( + [menu_init], + [menuw menu], + [ac_ct_menu_lib_found=yes; break],, + [$ncurses_LIBS]) + AS_IF( + [test -z "$ac_ct_panel_lib_found"], + [AS_IF( + [test "$need_panel_menu" = "yes"], + [AC_MSG_ERROR([could not find libmenu library (frontend: nconf)])], + [has_panel_menu=no])]) + ncurses_extra_LIBS="$LIBS" + LIBS=$LIBS_old]) + +AS_IF( + [test "$has_panel_menu" = "no" ], + [enable_nconf=no]) + +#---------------------------------------- +# Check headers and libs for gconf +AS_IF( + [test "$need_gtk" = "yes" -o "$need_gtk" = "auto"], + [PKG_CHECK_MODULES( + [gtk], + [gtk+-2.0 gmodule-2.0 libglade-2.0], + [has_gtk=yes], + [AS_IF( + [test "$need_gtk" = "yes"], + [AC_MSG_ERROR([could not find GTK+ headers and/or libraries (frontend: gconf)])], + [has_gtk=no])])]) + +AS_IF( + [test "$has_gtk" = "no" ], + [enable_gconf=no]) + +#---------------------------------------- +# Check headers and libs for qconf +AS_IF( + [test "$need_qt" = "yes" -o "$need_qt" = "auto"], + [PKG_CHECK_MODULES( + [qt4], + [QtCore QtGui Qt3Support], + [has_qt=yes; need_moc="$need_qt"], + [AS_IF( + [test "$need_qt" = "yes"], + [AC_MSG_ERROR([could not find QT4 headers and/or libraries (frontend: qconf)])], + [has_qt=no; need_moc=no])])]) + +AC_ARG_VAR([MOC], [Qt meta object compiler (moc) command]) +AS_IF( + [test "$need_moc" = "yes" -o "$need_moc" = "auto"], + [QT4_BINDIR=`$PKG_CONFIG Qt --variable bindir` + AC_PATH_PROGS( + [MOC], + [moc-qt4 moc],, + [$QT4_BINDIR:$PATH]) + AS_IF( + [test -n "$MOC"], + [has_moc=yes], + [AS_IF( + [test "$need_moc" = "yes"], + [AC_MSG_ERROR([could not find moc (frontend: qconf)])], + [has_moc=no])])]) + +AS_IF( + [test "$has_qt" = "no" -o "$has_moc" = "no"], + [enable_qconf=no]) + +#---------------------------------------- +# Per-frontends extra libraries +AC_ARG_VAR([conf_EXTRA_LIBS], [Extra libraries to build the conf frontend] ) +AC_ARG_VAR([gconf_EXTRA_LIBS], [Extra libraries to build the gconf frontend]) +AC_ARG_VAR([mconf_EXTRA_LIBS], [Extra libraries to build the mconf frontend]) +AC_ARG_VAR([nconf_EXTRA_LIBS], [Extra libraries to build the nconf frontend]) +AC_ARG_VAR([qconf_EXTRA_LIBS], [Extra libraries to build the qconf frontend]) + +#--------------------------------------------------------------------------- +# Now, we know what frontends to enable +AS_IF([test "$enable_conf" = "auto"], [enable_conf=yes ]) +AS_IF([test "$enable_gconf" = "auto"], [enable_gconf=yes]) +AS_IF([test "$enable_mconf" = "auto"], [enable_mconf=yes]) +AS_IF([test "$enable_nconf" = "auto"], [enable_nconf=yes]) +AS_IF([test "$enable_qconf" = "auto"], [enable_qconf=yes]) + +#---------------------------------------- +# Check if the lxdialog library should be built +AS_IF( + [test "$enable_mconf" = "yes"], + [need_lxdialog=yes], + [need_lxdialog=no]) + +#---------------------------------------- +# Check if the images library should be built +AS_IF( + [test "$enable_gconf" = "yes" -o "$enable_qconf" = "yes"], + [need_images=yes], + [need_images=no]) + +#---------------------------------------- +# Setup automake conditional build +AM_CONDITIONAL( + [COND_conf], + [test "$enable_conf" = "yes"]) +AM_CONDITIONAL( + [COND_mconf], + [test "$enable_mconf" = "yes"]) +AM_CONDITIONAL( + [COND_nconf], + [test "$enable_nconf" = "yes"]) +AM_CONDITIONAL( + [COND_gconf], + [test "$enable_gconf" = "yes"]) +AM_CONDITIONAL( + [COND_qconf], + [test "$enable_qconf" = "yes"]) +AM_CONDITIONAL( + [COND_lxdialog], + [test "$need_lxdialog" = "yes"]) +AM_CONDITIONAL( + [COND_images], + [test "$need_images" = "yes"]) +AM_CONDITIONAL( + [COND_utils], + [test "$enable_utils" = "yes"]) +AM_CONDITIONAL( + [COND_utils_gettext], + [test "$has_gettext" = "yes"]) + +#---------------------------------------- +# Get the version to apply to the parser shared library +AC_SUBST( + [KCONFIGPARSER_LIB_VERSION], + [m4_esyscmd_s([./scripts/version.sh --plain])]) + +#---------------------------------------- +# Finalise +AC_CONFIG_FILES([ + Makefile + docs/Makefile + libs/Makefile + libs/images/Makefile + libs/lxdialog/Makefile + libs/parser/Makefile + frontends/Makefile + frontends/conf/Makefile + frontends/mconf/Makefile + frontends/nconf/Makefile + frontends/gconf/Makefile + frontends/qconf/Makefile + utils/Makefile + scripts/Makefile +]) +AC_OUTPUT + +#---------------------------------------- +# Pretty-print the configuration settings +[fe_list=] +AS_IF([test "$enable_conf" = "yes"], [fe_list="$fe_list conf" ]) +AS_IF([test "$enable_gconf" = "yes"], [fe_list="$fe_list gconf"]) +AS_IF([test "$enable_mconf" = "yes"], [fe_list="$fe_list mconf"]) +AS_IF([test "$enable_nconf" = "yes"], [fe_list="$fe_list nconf"]) +AS_IF([test "$enable_qconf" = "yes"], [fe_list="$fe_list qconf"]) + +[lib_list=] +AS_IF( + [test "$enable_shared" = "yes"], + [lib_list="$lib_list shared (version: $KCONFIGPARSER_LIB_VERSION)"]) +AS_IF( + [test "$enable_static" = "yes"], + [lib_list="$lib_list${lib_list:+,} static"]) + +AC_MSG_NOTICE() +AC_MSG_NOTICE([Configured with:]) +AC_MSG_NOTICE([- parser library :$lib_list]) +AC_MSG_NOTICE([ - root-menu prompt : $root_menu]) +AC_MSG_NOTICE([ - config prefix : $config_prefix]) +AC_MSG_NOTICE([- frontends :$fe_list]) +AC_MSG_NOTICE([ - transform name : $program_transform_name]) +AC_MSG_NOTICE([ - localised : $has_gettext]) +AC_MSG_NOTICE([- install utilities : $enable_utils]) +AC_MSG_NOTICE([- CFLAGS CXXFLAGS : $wall_CFLAGS $werror_CFLAGS]) diff --git a/misc/tools/kconfig-frontends/docs/Makefile.am b/misc/tools/kconfig-frontends/docs/Makefile.am new file mode 100644 index 0000000000..58e08b5a77 --- /dev/null +++ b/misc/tools/kconfig-frontends/docs/Makefile.am @@ -0,0 +1 @@ +dist_doc_DATA = kconfig-language.txt kconfig.txt diff --git a/misc/tools/kconfig-frontends/docs/Makefile.in b/misc/tools/kconfig-frontends/docs/Makefile.in new file mode 100644 index 0000000000..be0fc7f264 --- /dev/null +++ b/misc/tools/kconfig-frontends/docs/Makefile.in @@ -0,0 +1,452 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ + +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +subdir = docs +DIST_COMMON = $(dist_doc_DATA) $(srcdir)/Makefile.am \ + $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +SOURCES = +DIST_SOURCES = +am__vpath_adj_setup = srcdirstrip=`echo "$(srcdir)" | sed 's|.|.|g'`; +am__vpath_adj = case $$p in \ + $(srcdir)/*) f=`echo "$$p" | sed "s|^$$srcdirstrip/||"`;; \ + *) f=$$p;; \ + esac; +am__strip_dir = f=`echo $$p | sed -e 's|^.*/||'`; +am__install_max = 40 +am__nobase_strip_setup = \ + srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*|]/\\\\&/g'` +am__nobase_strip = \ + for p in $$list; do echo "$$p"; done | sed -e "s|$$srcdirstrip/||" +am__nobase_list = $(am__nobase_strip_setup); \ + for p in $$list; do echo "$$p $$p"; done | \ + sed "s| $$srcdirstrip/| |;"' / .*\//!s/ .*/ ./; s,\( .*\)/[^/]*$$,\1,' | \ + $(AWK) 'BEGIN { files["."] = "" } { files[$$2] = files[$$2] " " $$1; \ + if (++n[$$2] == $(am__install_max)) \ + { print $$2, files[$$2]; n[$$2] = 0; files[$$2] = "" } } \ + END { for (dir in files) print dir, files[dir] }' +am__base_list = \ + sed '$$!N;$$!N;$$!N;$$!N;$$!N;$$!N;$$!N;s/\n/ /g' | \ + sed '$$!N;$$!N;$$!N;$$!N;s/\n/ /g' +am__installdirs = "$(DESTDIR)$(docdir)" +DATA = $(dist_doc_DATA) +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +dist_doc_DATA = kconfig-language.txt kconfig.txt +all: all-am + +.SUFFIXES: +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign docs/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign docs/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs +install-dist_docDATA: $(dist_doc_DATA) + @$(NORMAL_INSTALL) + test -z "$(docdir)" || $(MKDIR_P) "$(DESTDIR)$(docdir)" + @list='$(dist_doc_DATA)'; test -n "$(docdir)" || list=; \ + for p in $$list; do \ + if test -f "$$p"; then d=; else d="$(srcdir)/"; fi; \ + echo "$$d$$p"; \ + done | $(am__base_list) | \ + while read files; do \ + echo " $(INSTALL_DATA) $$files '$(DESTDIR)$(docdir)'"; \ + $(INSTALL_DATA) $$files "$(DESTDIR)$(docdir)" || exit $$?; \ + done + +uninstall-dist_docDATA: + @$(NORMAL_UNINSTALL) + @list='$(dist_doc_DATA)'; test -n "$(docdir)" || list=; \ + files=`for p in $$list; do echo $$p; done | sed -e 's|^.*/||'`; \ + test -n "$$files" || exit 0; \ + echo " ( cd '$(DESTDIR)$(docdir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(docdir)" && rm -f $$files +tags: TAGS +TAGS: + +ctags: CTAGS +CTAGS: + + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-am +all-am: Makefile $(DATA) +installdirs: + for dir in "$(DESTDIR)$(docdir)"; do \ + test -z "$$dir" || $(MKDIR_P) "$$dir"; \ + done +install: install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-am + +clean-am: clean-generic clean-libtool mostlyclean-am + +distclean: distclean-am + -rm -f Makefile +distclean-am: clean-am distclean-generic + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: install-dist_docDATA + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-generic mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: uninstall-dist_docDATA + +.MAKE: install-am install-strip + +.PHONY: all all-am check check-am clean clean-generic clean-libtool \ + distclean distclean-generic distclean-libtool distdir dvi \ + dvi-am html html-am info info-am install install-am \ + install-data install-data-am install-dist_docDATA install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-generic mostlyclean-libtool pdf pdf-am ps ps-am \ + uninstall uninstall-am uninstall-dist_docDATA + + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/docs/kconfig-language.txt b/misc/tools/kconfig-frontends/docs/kconfig-language.txt new file mode 100644 index 0000000000..a686f9cd69 --- /dev/null +++ b/misc/tools/kconfig-frontends/docs/kconfig-language.txt @@ -0,0 +1,413 @@ +Introduction +------------ + +The configuration database is a collection of configuration options +organized in a tree structure: + + +- Code maturity level options + | +- Prompt for development and/or incomplete code/drivers + +- General setup + | +- Networking support + | +- System V IPC + | +- BSD Process Accounting + | +- Sysctl support + +- Loadable module support + | +- Enable loadable module support + | +- Set version information on all module symbols + | +- Kernel module loader + +- ... + +Every entry has its own dependencies. These dependencies are used +to determine the visibility of an entry. Any child entry is only +visible if its parent entry is also visible. + +Menu entries +------------ + +Most entries define a config option; all other entries help to organize +them. A single configuration option is defined like this: + +config MODVERSIONS + bool "Set version information on all module symbols" + depends on MODULES + help + Usually, modules have to be recompiled whenever you switch to a new + kernel. ... + +Every line starts with a key word and can be followed by multiple +arguments. "config" starts a new config entry. The following lines +define attributes for this config option. Attributes can be the type of +the config option, input prompt, dependencies, help text and default +values. A config option can be defined multiple times with the same +name, but every definition can have only a single input prompt and the +type must not conflict. + +Menu attributes +--------------- + +A menu entry can have a number of attributes. Not all of them are +applicable everywhere (see syntax). + +- type definition: "bool"/"tristate"/"string"/"hex"/"int" + Every config option must have a type. There are only two basic types: + tristate and string; the other types are based on these two. The type + definition optionally accepts an input prompt, so these two examples + are equivalent: + + bool "Networking support" + and + bool + prompt "Networking support" + +- input prompt: "prompt" ["if" ] + Every menu entry can have at most one prompt, which is used to display + to the user. Optionally dependencies only for this prompt can be added + with "if". + +- default value: "default" ["if" ] + A config option can have any number of default values. If multiple + default values are visible, only the first defined one is active. + Default values are not limited to the menu entry where they are + defined. This means the default can be defined somewhere else or be + overridden by an earlier definition. + The default value is only assigned to the config symbol if no other + value was set by the user (via the input prompt above). If an input + prompt is visible the default value is presented to the user and can + be overridden by him. + Optionally, dependencies only for this default value can be added with + "if". + +- type definition + default value: + "def_bool"/"def_tristate" ["if" ] + This is a shorthand notation for a type definition plus a value. + Optionally dependencies for this default value can be added with "if". + +- dependencies: "depends on" + This defines a dependency for this menu entry. If multiple + dependencies are defined, they are connected with '&&'. Dependencies + are applied to all other options within this menu entry (which also + accept an "if" expression), so these two examples are equivalent: + + bool "foo" if BAR + default y if BAR + and + depends on BAR + bool "foo" + default y + +- reverse dependencies: "select" ["if" ] + While normal dependencies reduce the upper limit of a symbol (see + below), reverse dependencies can be used to force a lower limit of + another symbol. The value of the current menu symbol is used as the + minimal value can be set to. If is selected multiple + times, the limit is set to the largest selection. + Reverse dependencies can only be used with boolean or tristate + symbols. + Note: + select should be used with care. select will force + a symbol to a value without visiting the dependencies. + By abusing select you are able to select a symbol FOO even + if FOO depends on BAR that is not set. + In general use select only for non-visible symbols + (no prompts anywhere) and for symbols with no dependencies. + That will limit the usefulness but on the other hand avoid + the illegal configurations all over. + +- limiting menu display: "visible if" + This attribute is only applicable to menu blocks, if the condition is + false, the menu block is not displayed to the user (the symbols + contained there can still be selected by other symbols, though). It is + similar to a conditional "prompt" attribute for individual menu + entries. Default value of "visible" is true. + +- numerical ranges: "range" ["if" ] + This allows to limit the range of possible input values for int + and hex symbols. The user can only input a value which is larger than + or equal to the first symbol and smaller than or equal to the second + symbol. + +- help text: "help" or "---help---" + This defines a help text. The end of the help text is determined by + the indentation level, this means it ends at the first line which has + a smaller indentation than the first line of the help text. + "---help---" and "help" do not differ in behaviour, "---help---" is + used to help visually separate configuration logic from help within + the file as an aid to developers. + +- misc options: "option" [=] + Various less common options can be defined via this option syntax, + which can modify the behaviour of the menu entry and its config + symbol. These options are currently possible: + + - "defconfig_list" + This declares a list of default entries which can be used when + looking for the default configuration (which is used when the main + .config doesn't exists yet.) + + - "modules" + This declares the symbol to be used as the MODULES symbol, which + enables the third modular state for all config symbols. + + - "env"= + This imports the environment variable into Kconfig. It behaves like + a default, except that the value comes from the environment, this + also means that the behaviour when mixing it with normal defaults is + undefined at this point. The symbol is currently not exported back + to the build environment (if this is desired, it can be done via + another symbol). + +Menu dependencies +----------------- + +Dependencies define the visibility of a menu entry and can also reduce +the input range of tristate symbols. The tristate logic used in the +expressions uses one more state than normal boolean logic to express the +module state. Dependency expressions have the following syntax: + + ::= (1) + '=' (2) + '!=' (3) + '(' ')' (4) + '!' (5) + '&&' (6) + '||' (7) + +Expressions are listed in decreasing order of precedence. + +(1) Convert the symbol into an expression. Boolean and tristate symbols + are simply converted into the respective expression values. All + other symbol types result in 'n'. +(2) If the values of both symbols are equal, it returns 'y', + otherwise 'n'. +(3) If the values of both symbols are equal, it returns 'n', + otherwise 'y'. +(4) Returns the value of the expression. Used to override precedence. +(5) Returns the result of (2-/expr/). +(6) Returns the result of min(/expr/, /expr/). +(7) Returns the result of max(/expr/, /expr/). + +An expression can have a value of 'n', 'm' or 'y' (or 0, 1, 2 +respectively for calculations). A menu entry becomes visible when its +expression evaluates to 'm' or 'y'. + +There are two types of symbols: constant and non-constant symbols. +Non-constant symbols are the most common ones and are defined with the +'config' statement. Non-constant symbols consist entirely of alphanumeric +characters or underscores. +Constant symbols are only part of expressions. Constant symbols are +always surrounded by single or double quotes. Within the quote, any +other character is allowed and the quotes can be escaped using '\'. + +Menu structure +-------------- + +The position of a menu entry in the tree is determined in two ways. First +it can be specified explicitly: + +menu "Network device support" + depends on NET + +config NETDEVICES + ... + +endmenu + +All entries within the "menu" ... "endmenu" block become a submenu of +"Network device support". All subentries inherit the dependencies from +the menu entry, e.g. this means the dependency "NET" is added to the +dependency list of the config option NETDEVICES. + +The other way to generate the menu structure is done by analyzing the +dependencies. If a menu entry somehow depends on the previous entry, it +can be made a submenu of it. First, the previous (parent) symbol must +be part of the dependency list and then one of these two conditions +must be true: +- the child entry must become invisible, if the parent is set to 'n' +- the child entry must only be visible, if the parent is visible + +config MODULES + bool "Enable loadable module support" + +config MODVERSIONS + bool "Set version information on all module symbols" + depends on MODULES + +comment "module support disabled" + depends on !MODULES + +MODVERSIONS directly depends on MODULES, this means it's only visible if +MODULES is different from 'n'. The comment on the other hand is always +visible when MODULES is visible (the (empty) dependency of MODULES is +also part of the comment dependencies). + + +Kconfig syntax +-------------- + +The configuration file describes a series of menu entries, where every +line starts with a keyword (except help texts). The following keywords +end a menu entry: +- config +- menuconfig +- choice/endchoice +- comment +- menu/endmenu +- if/endif +- source +The first five also start the definition of a menu entry. + +config: + + "config" + + +This defines a config symbol and accepts any of above +attributes as options. + +menuconfig: + "menuconfig" + + +This is similar to the simple config entry above, but it also gives a +hint to front ends, that all suboptions should be displayed as a +separate list of options. + +choices: + + "choice" [symbol] + + + "endchoice" + +This defines a choice group and accepts any of the above attributes as +options. A choice can only be of type bool or tristate, while a boolean +choice only allows a single config entry to be selected, a tristate +choice also allows any number of config entries to be set to 'm'. This +can be used if multiple drivers for a single hardware exists and only a +single driver can be compiled/loaded into the kernel, but all drivers +can be compiled as modules. +A choice accepts another option "optional", which allows to set the +choice to 'n' and no entry needs to be selected. +If no [symbol] is associated with a choice, then you can not have multiple +definitions of that choice. If a [symbol] is associated to the choice, +then you may define the same choice (ie. with the same entries) in another +place. + +comment: + + "comment" + + +This defines a comment which is displayed to the user during the +configuration process and is also echoed to the output files. The only +possible options are dependencies. + +menu: + + "menu" +

    + + "endmenu" + +This defines a menu block, see "Menu structure" above for more +information. The only possible options are dependencies and "visible" +attributes. + +if: + + "if" + + "endif" + +This defines an if block. The dependency expression is appended +to all enclosed menu entries. + +source: + + "source" + +This reads the specified configuration file. This file is always parsed. + +mainmenu: + + "mainmenu" + +This sets the config program's title bar if the config program chooses +to use it. It should be placed at the top of the configuration, before any +other statement. + + +Kconfig hints +------------- +This is a collection of Kconfig tips, most of which aren't obvious at +first glance and most of which have become idioms in several Kconfig +files. + +Adding common features and make the usage configurable +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +It is a common idiom to implement a feature/functionality that are +relevant for some architectures but not all. +The recommended way to do so is to use a config variable named HAVE_* +that is defined in a common Kconfig file and selected by the relevant +architectures. +An example is the generic IOMAP functionality. + +We would in lib/Kconfig see: + +# Generic IOMAP is used to ... +config HAVE_GENERIC_IOMAP + +config GENERIC_IOMAP + depends on HAVE_GENERIC_IOMAP && FOO + +And in lib/Makefile we would see: +obj-$(CONFIG_GENERIC_IOMAP) += iomap.o + +For each architecture using the generic IOMAP functionality we would see: + +config X86 + select ... + select HAVE_GENERIC_IOMAP + select ... + +Note: we use the existing config option and avoid creating a new +config variable to select HAVE_GENERIC_IOMAP. + +Note: the use of the internal config variable HAVE_GENERIC_IOMAP, it is +introduced to overcome the limitation of select which will force a +config option to 'y' no matter the dependencies. +The dependencies are moved to the symbol GENERIC_IOMAP and we avoid the +situation where select forces a symbol equals to 'y'. + +Build as module only +~~~~~~~~~~~~~~~~~~~~ +To restrict a component build to module-only, qualify its config symbol +with "depends on m". E.g.: + +config FOO + depends on BAR && m + +limits FOO to module (=m) or disabled (=n). + +Kconfig symbol existence +~~~~~~~~~~~~~~~~~~~~~~~~ +The following two methods produce the same kconfig symbol dependencies +but differ greatly in kconfig symbol existence (production) in the +generated config file. + +case 1: + +config FOO + tristate "about foo" + depends on BAR + +vs. case 2: + +if BAR +config FOO + tristate "about foo" +endif + +In case 1, the symbol FOO will always exist in the config file (given +no other dependencies). In case 2, the symbol FOO will only exist in +the config file if BAR is enabled. diff --git a/misc/tools/kconfig-frontends/docs/kconfig.txt b/misc/tools/kconfig-frontends/docs/kconfig.txt new file mode 100644 index 0000000000..a09f1a6a83 --- /dev/null +++ b/misc/tools/kconfig-frontends/docs/kconfig.txt @@ -0,0 +1,191 @@ +This file contains some assistance for using "make *config". + +Use "make help" to list all of the possible configuration targets. + +The xconfig ('qconf') and menuconfig ('mconf') programs also +have embedded help text. Be sure to check it for navigation, +search, and other general help text. + +====================================================================== +General +-------------------------------------------------- + +New kernel releases often introduce new config symbols. Often more +important, new kernel releases may rename config symbols. When +this happens, using a previously working .config file and running +"make oldconfig" won't necessarily produce a working new kernel +for you, so you may find that you need to see what NEW kernel +symbols have been introduced. + +To see a list of new config symbols when using "make oldconfig", use + + cp user/some/old.config .config + yes "" | make oldconfig >conf.new + +and the config program will list as (NEW) any new symbols that have +unknown values. Of course, the .config file is also updated with +new (default) values, so you can use: + + grep "(NEW)" conf.new + +to see the new config symbols or you can use diffconfig to see the +differences between the previous and new .config files: + + scripts/diffconfig .config.old .config | less + +______________________________________________________________________ +Environment variables for '*config' + +KCONFIG_CONFIG +-------------------------------------------------- +This environment variable can be used to specify a default kernel config +file name to override the default name of ".config". + +KCONFIG_OVERWRITECONFIG +-------------------------------------------------- +If you set KCONFIG_OVERWRITECONFIG in the environment, Kconfig will not +break symlinks when .config is a symlink to somewhere else. + +______________________________________________________________________ +Environment variables for '{allyes/allmod/allno/rand}config' + +KCONFIG_ALLCONFIG +-------------------------------------------------- +(partially based on lkml email from/by Rob Landley, re: miniconfig) +-------------------------------------------------- +The allyesconfig/allmodconfig/allnoconfig/randconfig variants can also +use the environment variable KCONFIG_ALLCONFIG as a flag or a filename +that contains config symbols that the user requires to be set to a +specific value. If KCONFIG_ALLCONFIG is used without a filename where +KCONFIG_ALLCONFIG == "" or KCONFIG_ALLCONFIG == "1", "make *config" +checks for a file named "all{yes/mod/no/def/random}.config" +(corresponding to the *config command that was used) for symbol values +that are to be forced. If this file is not found, it checks for a +file named "all.config" to contain forced values. + +This enables you to create "miniature" config (miniconfig) or custom +config files containing just the config symbols that you are interested +in. Then the kernel config system generates the full .config file, +including symbols of your miniconfig file. + +This 'KCONFIG_ALLCONFIG' file is a config file which contains +(usually a subset of all) preset config symbols. These variable +settings are still subject to normal dependency checks. + +Examples: + KCONFIG_ALLCONFIG=custom-notebook.config make allnoconfig +or + KCONFIG_ALLCONFIG=mini.config make allnoconfig +or + make KCONFIG_ALLCONFIG=mini.config allnoconfig + +These examples will disable most options (allnoconfig) but enable or +disable the options that are explicitly listed in the specified +mini-config files. + +______________________________________________________________________ +Environment variables for 'silentoldconfig' + +KCONFIG_NOSILENTUPDATE +-------------------------------------------------- +If this variable has a non-blank value, it prevents silent kernel +config updates (requires explicit updates). + +KCONFIG_AUTOCONFIG +-------------------------------------------------- +This environment variable can be set to specify the path & name of the +"auto.conf" file. Its default value is "include/config/auto.conf". + +KCONFIG_TRISTATE +-------------------------------------------------- +This environment variable can be set to specify the path & name of the +"tristate.conf" file. Its default value is "include/config/tristate.conf". + +KCONFIG_AUTOHEADER +-------------------------------------------------- +This environment variable can be set to specify the path & name of the +"autoconf.h" (header) file. +Its default value is "include/generated/autoconf.h". + + +====================================================================== +menuconfig +-------------------------------------------------- + +SEARCHING for CONFIG symbols + +Searching in menuconfig: + + The Search function searches for kernel configuration symbol + names, so you have to know something close to what you are + looking for. + + Example: + /hotplug + This lists all config symbols that contain "hotplug", + e.g., HOTPLUG, HOTPLUG_CPU, MEMORY_HOTPLUG. + + For search help, enter / followed TAB-TAB-TAB (to highlight + ) and Enter. This will tell you that you can also use + regular expressions (regexes) in the search string, so if you + are not interested in MEMORY_HOTPLUG, you could try + + /^hotplug + +______________________________________________________________________ +User interface options for 'menuconfig' + +MENUCONFIG_COLOR +-------------------------------------------------- +It is possible to select different color themes using the variable +MENUCONFIG_COLOR. To select a theme use: + + make MENUCONFIG_COLOR= menuconfig + +Available themes are: + mono => selects colors suitable for monochrome displays + blackbg => selects a color scheme with black background + classic => theme with blue background. The classic look + bluetitle => a LCD friendly version of classic. (default) + +MENUCONFIG_MODE +-------------------------------------------------- +This mode shows all sub-menus in one large tree. + +Example: + make MENUCONFIG_MODE=single_menu menuconfig + + +====================================================================== +xconfig +-------------------------------------------------- + +Searching in xconfig: + + The Search function searches for kernel configuration symbol + names, so you have to know something close to what you are + looking for. + + Example: + Ctrl-F hotplug + or + Menu: File, Search, hotplug + + lists all config symbol entries that contain "hotplug" in + the symbol name. In this Search dialog, you may change the + config setting for any of the entries that are not grayed out. + You can also enter a different search string without having + to return to the main menu. + + +====================================================================== +gconfig +-------------------------------------------------- + +Searching in gconfig: + + None (gconfig isn't maintained as well as xconfig or menuconfig); + however, gconfig does have a few more viewing choices than + xconfig does. + +### diff --git a/misc/tools/kconfig-frontends/frontends/Makefile.am b/misc/tools/kconfig-frontends/frontends/Makefile.am new file mode 100644 index 0000000000..0badbc8c6d --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/Makefile.am @@ -0,0 +1,16 @@ +if COND_conf + MAYBE_conf = conf +endif +if COND_mconf + MAYBE_mconf = mconf +endif +if COND_nconf + MAYBE_nconf = nconf +endif +if COND_gconf + MAYBE_gconf = gconf +endif +if COND_qconf + MAYBE_qconf = qconf +endif +SUBDIRS = $(MAYBE_conf) $(MAYBE_mconf) $(MAYBE_nconf) $(MAYBE_gconf) $(MAYBE_qconf) diff --git a/misc/tools/kconfig-frontends/frontends/Makefile.in b/misc/tools/kconfig-frontends/frontends/Makefile.in new file mode 100644 index 0000000000..5953761dc1 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/Makefile.in @@ -0,0 +1,610 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +subdir = frontends +DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +SOURCES = +DIST_SOURCES = +RECURSIVE_TARGETS = all-recursive check-recursive dvi-recursive \ + html-recursive info-recursive install-data-recursive \ + install-dvi-recursive install-exec-recursive \ + install-html-recursive install-info-recursive \ + install-pdf-recursive install-ps-recursive install-recursive \ + installcheck-recursive installdirs-recursive pdf-recursive \ + ps-recursive uninstall-recursive +RECURSIVE_CLEAN_TARGETS = mostlyclean-recursive clean-recursive \ + distclean-recursive maintainer-clean-recursive +AM_RECURSIVE_TARGETS = $(RECURSIVE_TARGETS:-recursive=) \ + $(RECURSIVE_CLEAN_TARGETS:-recursive=) tags TAGS ctags CTAGS \ + distdir +ETAGS = etags +CTAGS = ctags +DIST_SUBDIRS = conf mconf nconf gconf qconf +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +am__relativize = \ + dir0=`pwd`; \ + sed_first='s,^\([^/]*\)/.*$$,\1,'; \ + sed_rest='s,^[^/]*/*,,'; \ + sed_last='s,^.*/\([^/]*\)$$,\1,'; \ + sed_butlast='s,/*[^/]*$$,,'; \ + while test -n "$$dir1"; do \ + first=`echo "$$dir1" | sed -e "$$sed_first"`; \ + if test "$$first" != "."; then \ + if test "$$first" = ".."; then \ + dir2=`echo "$$dir0" | sed -e "$$sed_last"`/"$$dir2"; \ + dir0=`echo "$$dir0" | sed -e "$$sed_butlast"`; \ + else \ + first2=`echo "$$dir2" | sed -e "$$sed_first"`; \ + if test "$$first2" = "$$first"; then \ + dir2=`echo "$$dir2" | sed -e "$$sed_rest"`; \ + else \ + dir2="../$$dir2"; \ + fi; \ + dir0="$$dir0"/"$$first"; \ + fi; \ + fi; \ + dir1=`echo "$$dir1" | sed -e "$$sed_rest"`; \ + done; \ + reldir="$$dir2" +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +@COND_conf_TRUE@MAYBE_conf = conf +@COND_mconf_TRUE@MAYBE_mconf = mconf +@COND_nconf_TRUE@MAYBE_nconf = nconf +@COND_gconf_TRUE@MAYBE_gconf = gconf +@COND_qconf_TRUE@MAYBE_qconf = qconf +SUBDIRS = $(MAYBE_conf) $(MAYBE_mconf) $(MAYBE_nconf) $(MAYBE_gconf) $(MAYBE_qconf) +all: all-recursive + +.SUFFIXES: +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign frontends/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign frontends/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs + +# This directory's subdirectories are mostly independent; you can cd +# into them and run `make' without going through this Makefile. +# To change the values of `make' variables: instead of editing Makefiles, +# (1) if the variable is set in `config.status', edit `config.status' +# (which will cause the Makefiles to be regenerated when you run `make'); +# (2) otherwise, pass the desired values on the `make' command line. +$(RECURSIVE_TARGETS): + @fail= failcom='exit 1'; \ + for f in x $$MAKEFLAGS; do \ + case $$f in \ + *=* | --[!k]*);; \ + *k*) failcom='fail=yes';; \ + esac; \ + done; \ + dot_seen=no; \ + target=`echo $@ | sed s/-recursive//`; \ + list='$(SUBDIRS)'; for subdir in $$list; do \ + echo "Making $$target in $$subdir"; \ + if test "$$subdir" = "."; then \ + dot_seen=yes; \ + local_target="$$target-am"; \ + else \ + local_target="$$target"; \ + fi; \ + ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) $$local_target) \ + || eval $$failcom; \ + done; \ + if test "$$dot_seen" = "no"; then \ + $(MAKE) $(AM_MAKEFLAGS) "$$target-am" || exit 1; \ + fi; test -z "$$fail" + +$(RECURSIVE_CLEAN_TARGETS): + @fail= failcom='exit 1'; \ + for f in x $$MAKEFLAGS; do \ + case $$f in \ + *=* | --[!k]*);; \ + *k*) failcom='fail=yes';; \ + esac; \ + done; \ + dot_seen=no; \ + case "$@" in \ + distclean-* | maintainer-clean-*) list='$(DIST_SUBDIRS)' ;; \ + *) list='$(SUBDIRS)' ;; \ + esac; \ + rev=''; for subdir in $$list; do \ + if test "$$subdir" = "."; then :; else \ + rev="$$subdir $$rev"; \ + fi; \ + done; \ + rev="$$rev ."; \ + target=`echo $@ | sed s/-recursive//`; \ + for subdir in $$rev; do \ + echo "Making $$target in $$subdir"; \ + if test "$$subdir" = "."; then \ + local_target="$$target-am"; \ + else \ + local_target="$$target"; \ + fi; \ + ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) $$local_target) \ + || eval $$failcom; \ + done && test -z "$$fail" +tags-recursive: + list='$(SUBDIRS)'; for subdir in $$list; do \ + test "$$subdir" = . || ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) tags); \ + done +ctags-recursive: + list='$(SUBDIRS)'; for subdir in $$list; do \ + test "$$subdir" = . || ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) ctags); \ + done + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: tags-recursive $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + if ($(ETAGS) --etags-include --version) >/dev/null 2>&1; then \ + include_option=--etags-include; \ + empty_fix=.; \ + else \ + include_option=--include; \ + empty_fix=; \ + fi; \ + list='$(SUBDIRS)'; for subdir in $$list; do \ + if test "$$subdir" = .; then :; else \ + test ! -f $$subdir/TAGS || \ + set "$$@" "$$include_option=$$here/$$subdir/TAGS"; \ + fi; \ + done; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: ctags-recursive $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done + @list='$(DIST_SUBDIRS)'; for subdir in $$list; do \ + if test "$$subdir" = .; then :; else \ + test -d "$(distdir)/$$subdir" \ + || $(MKDIR_P) "$(distdir)/$$subdir" \ + || exit 1; \ + fi; \ + done + @list='$(DIST_SUBDIRS)'; for subdir in $$list; do \ + if test "$$subdir" = .; then :; else \ + dir1=$$subdir; dir2="$(distdir)/$$subdir"; \ + $(am__relativize); \ + new_distdir=$$reldir; \ + dir1=$$subdir; dir2="$(top_distdir)"; \ + $(am__relativize); \ + new_top_distdir=$$reldir; \ + echo " (cd $$subdir && $(MAKE) $(AM_MAKEFLAGS) top_distdir="$$new_top_distdir" distdir="$$new_distdir" \\"; \ + echo " am__remove_distdir=: am__skip_length_check=: am__skip_mode_fix=: distdir)"; \ + ($(am__cd) $$subdir && \ + $(MAKE) $(AM_MAKEFLAGS) \ + top_distdir="$$new_top_distdir" \ + distdir="$$new_distdir" \ + am__remove_distdir=: \ + am__skip_length_check=: \ + am__skip_mode_fix=: \ + distdir) \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-recursive +all-am: Makefile +installdirs: installdirs-recursive +installdirs-am: +install: install-recursive +install-exec: install-exec-recursive +install-data: install-data-recursive +uninstall: uninstall-recursive + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-recursive +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-recursive + +clean-am: clean-generic clean-libtool mostlyclean-am + +distclean: distclean-recursive + -rm -f Makefile +distclean-am: clean-am distclean-generic distclean-tags + +dvi: dvi-recursive + +dvi-am: + +html: html-recursive + +html-am: + +info: info-recursive + +info-am: + +install-data-am: + +install-dvi: install-dvi-recursive + +install-dvi-am: + +install-exec-am: + +install-html: install-html-recursive + +install-html-am: + +install-info: install-info-recursive + +install-info-am: + +install-man: + +install-pdf: install-pdf-recursive + +install-pdf-am: + +install-ps: install-ps-recursive + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-recursive + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-recursive + +mostlyclean-am: mostlyclean-generic mostlyclean-libtool + +pdf: pdf-recursive + +pdf-am: + +ps: ps-recursive + +ps-am: + +uninstall-am: + +.MAKE: $(RECURSIVE_CLEAN_TARGETS) $(RECURSIVE_TARGETS) ctags-recursive \ + install-am install-strip tags-recursive + +.PHONY: $(RECURSIVE_CLEAN_TARGETS) $(RECURSIVE_TARGETS) CTAGS GTAGS \ + all all-am check check-am clean clean-generic clean-libtool \ + ctags ctags-recursive distclean distclean-generic \ + distclean-libtool distclean-tags distdir dvi dvi-am html \ + html-am info info-am install install-am install-data \ + install-data-am install-dvi install-dvi-am install-exec \ + install-exec-am install-html install-html-am install-info \ + install-info-am install-man install-pdf install-pdf-am \ + install-ps install-ps-am install-strip installcheck \ + installcheck-am installdirs installdirs-am maintainer-clean \ + maintainer-clean-generic mostlyclean mostlyclean-generic \ + mostlyclean-libtool pdf pdf-am ps ps-am tags tags-recursive \ + uninstall uninstall-am + + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/frontends/conf/Makefile.am b/misc/tools/kconfig-frontends/frontends/conf/Makefile.am new file mode 100644 index 0000000000..10566cc424 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/conf/Makefile.am @@ -0,0 +1,10 @@ +bin_PROGRAMS = conf + +conf_SOURCES = conf.c +conf_CPPFLAGS = $(AM_CPPFLAGS) \ + $(intl_CPPFLAGS) \ + -I$(top_srcdir)/libs/parser +conf_CFLAGS = $(AM_CFLAGS) $(kf_CFLAGS) +conf_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(intl_LIBS) \ + $(conf_EXTRA_LIBS) diff --git a/misc/tools/kconfig-frontends/frontends/conf/Makefile.in b/misc/tools/kconfig-frontends/frontends/conf/Makefile.in new file mode 100644 index 0000000000..5c6f85955a --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/conf/Makefile.in @@ -0,0 +1,600 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ + +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +bin_PROGRAMS = conf$(EXEEXT) +subdir = frontends/conf +DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +am__installdirs = "$(DESTDIR)$(bindir)" +PROGRAMS = $(bin_PROGRAMS) +am_conf_OBJECTS = conf-conf.$(OBJEXT) +conf_OBJECTS = $(am_conf_OBJECTS) +am__DEPENDENCIES_1 = +conf_DEPENDENCIES = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(am__DEPENDENCIES_1) $(am__DEPENDENCIES_1) +AM_V_lt = $(am__v_lt_$(V)) +am__v_lt_ = $(am__v_lt_$(AM_DEFAULT_VERBOSITY)) +am__v_lt_0 = --silent +conf_LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(conf_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +DEFAULT_INCLUDES = -I.@am__isrc@ -I$(top_builddir)/scripts/.autostuff +depcomp = $(SHELL) $(top_srcdir)/scripts/.autostuff/scripts/depcomp +am__depfiles_maybe = depfiles +am__mv = mv -f +COMPILE = $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) \ + $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) +LTCOMPILE = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) \ + $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) $(CPPFLAGS) \ + $(AM_CFLAGS) $(CFLAGS) +AM_V_CC = $(am__v_CC_$(V)) +am__v_CC_ = $(am__v_CC_$(AM_DEFAULT_VERBOSITY)) +am__v_CC_0 = @echo " CC " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +CCLD = $(CC) +LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(AM_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +AM_V_CCLD = $(am__v_CCLD_$(V)) +am__v_CCLD_ = $(am__v_CCLD_$(AM_DEFAULT_VERBOSITY)) +am__v_CCLD_0 = @echo " CCLD " $@; +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +SOURCES = $(conf_SOURCES) +DIST_SOURCES = $(conf_SOURCES) +ETAGS = etags +CTAGS = ctags +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +conf_SOURCES = conf.c +conf_CPPFLAGS = $(AM_CPPFLAGS) \ + $(intl_CPPFLAGS) \ + -I$(top_srcdir)/libs/parser + +conf_CFLAGS = $(AM_CFLAGS) $(kf_CFLAGS) +conf_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(intl_LIBS) \ + $(conf_EXTRA_LIBS) + +all: all-am + +.SUFFIXES: +.SUFFIXES: .c .lo .o .obj +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign frontends/conf/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign frontends/conf/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): +install-binPROGRAMS: $(bin_PROGRAMS) + @$(NORMAL_INSTALL) + test -z "$(bindir)" || $(MKDIR_P) "$(DESTDIR)$(bindir)" + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + for p in $$list; do echo "$$p $$p"; done | \ + sed 's/$(EXEEXT)$$//' | \ + while read p p1; do if test -f $$p || test -f $$p1; \ + then echo "$$p"; echo "$$p"; else :; fi; \ + done | \ + sed -e 'p;s,.*/,,;n;h' -e 's|.*|.|' \ + -e 'p;x;s,.*/,,;s/$(EXEEXT)$$//;$(transform);s/$$/$(EXEEXT)/' | \ + sed 'N;N;N;s,\n, ,g' | \ + $(AWK) 'BEGIN { files["."] = ""; dirs["."] = 1 } \ + { d=$$3; if (dirs[d] != 1) { print "d", d; dirs[d] = 1 } \ + if ($$2 == $$4) files[d] = files[d] " " $$1; \ + else { print "f", $$3 "/" $$4, $$1; } } \ + END { for (d in files) print "f", d, files[d] }' | \ + while read type dir files; do \ + if test "$$dir" = .; then dir=; else dir=/$$dir; fi; \ + test -z "$$files" || { \ + echo " $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files '$(DESTDIR)$(bindir)$$dir'"; \ + $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files "$(DESTDIR)$(bindir)$$dir" || exit $$?; \ + } \ + ; done + +uninstall-binPROGRAMS: + @$(NORMAL_UNINSTALL) + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + files=`for p in $$list; do echo "$$p"; done | \ + sed -e 'h;s,^.*/,,;s/$(EXEEXT)$$//;$(transform)' \ + -e 's/$$/$(EXEEXT)/' `; \ + test -n "$$list" || exit 0; \ + echo " ( cd '$(DESTDIR)$(bindir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(bindir)" && rm -f $$files + +clean-binPROGRAMS: + @list='$(bin_PROGRAMS)'; test -n "$$list" || exit 0; \ + echo " rm -f" $$list; \ + rm -f $$list || exit $$?; \ + test -n "$(EXEEXT)" || exit 0; \ + list=`for p in $$list; do echo "$$p"; done | sed 's/$(EXEEXT)$$//'`; \ + echo " rm -f" $$list; \ + rm -f $$list +conf$(EXEEXT): $(conf_OBJECTS) $(conf_DEPENDENCIES) + @rm -f conf$(EXEEXT) + $(AM_V_CCLD)$(conf_LINK) $(conf_OBJECTS) $(conf_LDADD) $(LIBS) + +mostlyclean-compile: + -rm -f *.$(OBJEXT) + +distclean-compile: + -rm -f *.tab.c + +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/conf-conf.Po@am__quote@ + +.c.o: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c $< + +.c.obj: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ `$(CYGPATH_W) '$<'` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c `$(CYGPATH_W) '$<'` + +.c.lo: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LTCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LTCOMPILE) -c -o $@ $< + +conf-conf.o: conf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(conf_CPPFLAGS) $(CPPFLAGS) $(conf_CFLAGS) $(CFLAGS) -MT conf-conf.o -MD -MP -MF $(DEPDIR)/conf-conf.Tpo -c -o conf-conf.o `test -f 'conf.c' || echo '$(srcdir)/'`conf.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/conf-conf.Tpo $(DEPDIR)/conf-conf.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='conf.c' object='conf-conf.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(conf_CPPFLAGS) $(CPPFLAGS) $(conf_CFLAGS) $(CFLAGS) -c -o conf-conf.o `test -f 'conf.c' || echo '$(srcdir)/'`conf.c + +conf-conf.obj: conf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(conf_CPPFLAGS) $(CPPFLAGS) $(conf_CFLAGS) $(CFLAGS) -MT conf-conf.obj -MD -MP -MF $(DEPDIR)/conf-conf.Tpo -c -o conf-conf.obj `if test -f 'conf.c'; then $(CYGPATH_W) 'conf.c'; else $(CYGPATH_W) '$(srcdir)/conf.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/conf-conf.Tpo $(DEPDIR)/conf-conf.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='conf.c' object='conf-conf.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(conf_CPPFLAGS) $(CPPFLAGS) $(conf_CFLAGS) $(CFLAGS) -c -o conf-conf.obj `if test -f 'conf.c'; then $(CYGPATH_W) 'conf.c'; else $(CYGPATH_W) '$(srcdir)/conf.c'; fi` + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-am +all-am: Makefile $(PROGRAMS) +installdirs: + for dir in "$(DESTDIR)$(bindir)"; do \ + test -z "$$dir" || $(MKDIR_P) "$$dir"; \ + done +install: install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-am + +clean-am: clean-binPROGRAMS clean-generic clean-libtool mostlyclean-am + +distclean: distclean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +distclean-am: clean-am distclean-compile distclean-generic \ + distclean-tags + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: install-binPROGRAMS + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: uninstall-binPROGRAMS + +.MAKE: install-am install-strip + +.PHONY: CTAGS GTAGS all all-am check check-am clean clean-binPROGRAMS \ + clean-generic clean-libtool ctags distclean distclean-compile \ + distclean-generic distclean-libtool distclean-tags distdir dvi \ + dvi-am html html-am info info-am install install-am \ + install-binPROGRAMS install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-compile mostlyclean-generic mostlyclean-libtool \ + pdf pdf-am ps ps-am tags uninstall uninstall-am \ + uninstall-binPROGRAMS + + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/frontends/conf/conf.c b/misc/tools/kconfig-frontends/frontends/conf/conf.c new file mode 100644 index 0000000000..0dc4a2c779 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/conf/conf.c @@ -0,0 +1,694 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "lkc.h" + +static void conf(struct menu *menu); +static void check_conf(struct menu *menu); +static void xfgets(char *str, int size, FILE *in); + +enum input_mode { + oldaskconfig, + silentoldconfig, + oldconfig, + allnoconfig, + allyesconfig, + allmodconfig, + alldefconfig, + randconfig, + defconfig, + savedefconfig, + listnewconfig, + oldnoconfig, +} input_mode = oldaskconfig; + +static int indent = 1; +static int valid_stdin = 1; +static int sync_kconfig; +static int conf_cnt; +static char line[128]; +static struct menu *rootEntry; + +static void print_help(struct menu *menu) +{ + struct gstr help = str_new(); + + menu_get_ext_help(menu, &help); + + printf("\n%s\n", str_get(&help)); + str_free(&help); +} + +static void strip(char *str) +{ + char *p = str; + int l; + + while ((isspace(*p))) + p++; + l = strlen(p); + if (p != str) + memmove(str, p, l + 1); + if (!l) + return; + p = str + l - 1; + while ((isspace(*p))) + *p-- = 0; +} + +static void check_stdin(void) +{ + if (!valid_stdin) { + printf(_("aborted!\n\n")); + printf(_("Console input/output is redirected. ")); + printf(_("Run 'make oldconfig' to update configuration.\n\n")); + exit(1); + } +} + +static int conf_askvalue(struct symbol *sym, const char *def) +{ + enum symbol_type type = sym_get_type(sym); + + if (!sym_has_value(sym)) + printf(_("(NEW) ")); + + line[0] = '\n'; + line[1] = 0; + + if (!sym_is_changable(sym)) { + printf("%s\n", def); + line[0] = '\n'; + line[1] = 0; + return 0; + } + + switch (input_mode) { + case oldconfig: + case silentoldconfig: + if (sym_has_value(sym)) { + printf("%s\n", def); + return 0; + } + check_stdin(); + /* fall through */ + case oldaskconfig: + fflush(stdout); + xfgets(line, 128, stdin); + return 1; + default: + break; + } + + switch (type) { + case S_INT: + case S_HEX: + case S_STRING: + printf("%s\n", def); + return 1; + default: + ; + } + printf("%s", line); + return 1; +} + +static int conf_string(struct menu *menu) +{ + struct symbol *sym = menu->sym; + const char *def; + + while (1) { + printf("%*s%s ", indent - 1, "", _(menu->prompt->text)); + printf("(%s) ", sym->name); + def = sym_get_string_value(sym); + if (sym_get_string_value(sym)) + printf("[%s] ", def); + if (!conf_askvalue(sym, def)) + return 0; + switch (line[0]) { + case '\n': + break; + case '?': + /* print help */ + if (line[1] == '\n') { + print_help(menu); + def = NULL; + break; + } + /* fall through */ + default: + line[strlen(line)-1] = 0; + def = line; + } + if (def && sym_set_string_value(sym, def)) + return 0; + } +} + +static int conf_sym(struct menu *menu) +{ + struct symbol *sym = menu->sym; + tristate oldval, newval; + + while (1) { + printf("%*s%s ", indent - 1, "", _(menu->prompt->text)); + if (sym->name) + printf("(%s) ", sym->name); + putchar('['); + oldval = sym_get_tristate_value(sym); + switch (oldval) { + case no: + putchar('N'); + break; + case mod: + putchar('M'); + break; + case yes: + putchar('Y'); + break; + } + if (oldval != no && sym_tristate_within_range(sym, no)) + printf("/n"); + if (oldval != mod && sym_tristate_within_range(sym, mod)) + printf("/m"); + if (oldval != yes && sym_tristate_within_range(sym, yes)) + printf("/y"); + if (menu_has_help(menu)) + printf("/?"); + printf("] "); + if (!conf_askvalue(sym, sym_get_string_value(sym))) + return 0; + strip(line); + + switch (line[0]) { + case 'n': + case 'N': + newval = no; + if (!line[1] || !strcmp(&line[1], "o")) + break; + continue; + case 'm': + case 'M': + newval = mod; + if (!line[1]) + break; + continue; + case 'y': + case 'Y': + newval = yes; + if (!line[1] || !strcmp(&line[1], "es")) + break; + continue; + case 0: + newval = oldval; + break; + case '?': + goto help; + default: + continue; + } + if (sym_set_tristate_value(sym, newval)) + return 0; +help: + print_help(menu); + } +} + +static int conf_choice(struct menu *menu) +{ + struct symbol *sym, *def_sym; + struct menu *child; + bool is_new; + + sym = menu->sym; + is_new = !sym_has_value(sym); + if (sym_is_changable(sym)) { + conf_sym(menu); + sym_calc_value(sym); + switch (sym_get_tristate_value(sym)) { + case no: + return 1; + case mod: + return 0; + case yes: + break; + } + } else { + switch (sym_get_tristate_value(sym)) { + case no: + return 1; + case mod: + printf("%*s%s\n", indent - 1, "", _(menu_get_prompt(menu))); + return 0; + case yes: + break; + } + } + + while (1) { + int cnt, def; + + printf("%*s%s\n", indent - 1, "", _(menu_get_prompt(menu))); + def_sym = sym_get_choice_value(sym); + cnt = def = 0; + line[0] = 0; + for (child = menu->list; child; child = child->next) { + if (!menu_is_visible(child)) + continue; + if (!child->sym) { + printf("%*c %s\n", indent, '*', _(menu_get_prompt(child))); + continue; + } + cnt++; + if (child->sym == def_sym) { + def = cnt; + printf("%*c", indent, '>'); + } else + printf("%*c", indent, ' '); + printf(" %d. %s", cnt, _(menu_get_prompt(child))); + if (child->sym->name) + printf(" (%s)", child->sym->name); + if (!sym_has_value(child->sym)) + printf(_(" (NEW)")); + printf("\n"); + } + printf(_("%*schoice"), indent - 1, ""); + if (cnt == 1) { + printf("[1]: 1\n"); + goto conf_childs; + } + printf("[1-%d", cnt); + if (menu_has_help(menu)) + printf("?"); + printf("]: "); + switch (input_mode) { + case oldconfig: + case silentoldconfig: + if (!is_new) { + cnt = def; + printf("%d\n", cnt); + break; + } + check_stdin(); + /* fall through */ + case oldaskconfig: + fflush(stdout); + xfgets(line, 128, stdin); + strip(line); + if (line[0] == '?') { + print_help(menu); + continue; + } + if (!line[0]) + cnt = def; + else if (isdigit(line[0])) + cnt = atoi(line); + else + continue; + break; + default: + break; + } + + conf_childs: + for (child = menu->list; child; child = child->next) { + if (!child->sym || !menu_is_visible(child)) + continue; + if (!--cnt) + break; + } + if (!child) + continue; + if (line[0] && line[strlen(line) - 1] == '?') { + print_help(child); + continue; + } + sym_set_choice_value(sym, child->sym); + for (child = child->list; child; child = child->next) { + indent += 2; + conf(child); + indent -= 2; + } + return 1; + } +} + +static void conf(struct menu *menu) +{ + struct symbol *sym; + struct property *prop; + struct menu *child; + + if (!menu_is_visible(menu)) + return; + + sym = menu->sym; + prop = menu->prompt; + if (prop) { + const char *prompt; + + switch (prop->type) { + case P_MENU: + if ((input_mode == silentoldconfig || + input_mode == listnewconfig || + input_mode == oldnoconfig) && + rootEntry != menu) { + check_conf(menu); + return; + } + /* fall through */ + case P_COMMENT: + prompt = menu_get_prompt(menu); + if (prompt) + printf("%*c\n%*c %s\n%*c\n", + indent, '*', + indent, '*', _(prompt), + indent, '*'); + default: + ; + } + } + + if (!sym) + goto conf_childs; + + if (sym_is_choice(sym)) { + conf_choice(menu); + if (sym->curr.tri != mod) + return; + goto conf_childs; + } + + switch (sym->type) { + case S_INT: + case S_HEX: + case S_STRING: + conf_string(menu); + break; + default: + conf_sym(menu); + break; + } + +conf_childs: + if (sym) + indent += 2; + for (child = menu->list; child; child = child->next) + conf(child); + if (sym) + indent -= 2; +} + +static void check_conf(struct menu *menu) +{ + struct symbol *sym; + struct menu *child; + + if (!menu_is_visible(menu)) + return; + + sym = menu->sym; + if (sym && !sym_has_value(sym)) { + if (sym_is_changable(sym) || + (sym_is_choice(sym) && sym_get_tristate_value(sym) == yes)) { + if (input_mode == listnewconfig) { + if (sym->name && !sym_is_choice_value(sym)) { + printf("%s%s\n", CONFIG_, sym->name); + } + } else if (input_mode != oldnoconfig) { + if (!conf_cnt++) + printf(_("*\n* Restart config...\n*\n")); + rootEntry = menu_get_parent_menu(menu); + conf(rootEntry); + } + } + } + + for (child = menu->list; child; child = child->next) + check_conf(child); +} + +static struct option long_opts[] = { + {"oldaskconfig", no_argument, NULL, oldaskconfig}, + {"oldconfig", no_argument, NULL, oldconfig}, + {"silentoldconfig", no_argument, NULL, silentoldconfig}, + {"defconfig", optional_argument, NULL, defconfig}, + {"savedefconfig", required_argument, NULL, savedefconfig}, + {"allnoconfig", no_argument, NULL, allnoconfig}, + {"allyesconfig", no_argument, NULL, allyesconfig}, + {"allmodconfig", no_argument, NULL, allmodconfig}, + {"alldefconfig", no_argument, NULL, alldefconfig}, + {"randconfig", no_argument, NULL, randconfig}, + {"listnewconfig", no_argument, NULL, listnewconfig}, + {"oldnoconfig", no_argument, NULL, oldnoconfig}, + {NULL, 0, NULL, 0} +}; + +static void conf_usage(const char *progname) +{ + + printf("Usage: %s [option] \n", progname); + printf("[option] is _one_ of the following:\n"); + printf(" --listnewconfig List new options\n"); + printf(" --oldaskconfig Start a new configuration using a line-oriented program\n"); + printf(" --oldconfig Update a configuration using a provided .config as base\n"); + printf(" --silentoldconfig Same as oldconfig, but quietly, additionally update deps\n"); + printf(" --oldnoconfig Same as silentoldconfig but set new symbols to no\n"); + printf(" --defconfig New config with default defined in \n"); + printf(" --savedefconfig Save the minimal current configuration to \n"); + printf(" --allnoconfig New config where all options are answered with no\n"); + printf(" --allyesconfig New config where all options are answered with yes\n"); + printf(" --allmodconfig New config where all options are answered with mod\n"); + printf(" --alldefconfig New config with all symbols set to default\n"); + printf(" --randconfig New config with random answer to all options\n"); +} + +int main(int ac, char **av) +{ + const char *progname = av[0]; + int opt; + const char *name, *defconfig_file = NULL /* gcc uninit */; + struct stat tmpstat; + + setlocale(LC_ALL, ""); + bindtextdomain(PACKAGE, LOCALEDIR); + textdomain(PACKAGE); + + while ((opt = getopt_long(ac, av, "", long_opts, NULL)) != -1) { + input_mode = (enum input_mode)opt; + switch (opt) { + case silentoldconfig: + sync_kconfig = 1; + break; + case defconfig: + case savedefconfig: + defconfig_file = optarg; + break; + case randconfig: + { + struct timeval now; + unsigned int seed; + + /* + * Use microseconds derived seed, + * compensate for systems where it may be zero + */ + gettimeofday(&now, NULL); + + seed = (unsigned int)((now.tv_sec + 1) * (now.tv_usec + 1)); + srand(seed); + break; + } + case oldaskconfig: + case oldconfig: + case allnoconfig: + case allyesconfig: + case allmodconfig: + case alldefconfig: + case listnewconfig: + case oldnoconfig: + break; + case '?': + conf_usage(progname); + exit(1); + break; + } + } + if (ac == optind) { + printf(_("%s: Kconfig file missing\n"), av[0]); + conf_usage(progname); + exit(1); + } + name = av[optind]; + conf_parse(name); + //zconfdump(stdout); + if (sync_kconfig) { + name = conf_get_configname(); + if (stat(name, &tmpstat)) { + fprintf(stderr, _("***\n" + "*** Configuration file \"%s\" not found!\n" + "***\n" + "*** Please run some configurator (e.g. \"make oldconfig\" or\n" + "*** \"make menuconfig\" or \"make xconfig\").\n" + "***\n"), name); + exit(1); + } + } + + switch (input_mode) { + case defconfig: + if (!defconfig_file) + defconfig_file = conf_get_default_confname(); + if (conf_read(defconfig_file)) { + printf(_("***\n" + "*** Can't find default configuration \"%s\"!\n" + "***\n"), defconfig_file); + exit(1); + } + break; + case savedefconfig: + case silentoldconfig: + case oldaskconfig: + case oldconfig: + case listnewconfig: + case oldnoconfig: + conf_read(NULL); + break; + case allnoconfig: + case allyesconfig: + case allmodconfig: + case alldefconfig: + case randconfig: + name = getenv("KCONFIG_ALLCONFIG"); + if (!name) + break; + if ((strcmp(name, "") != 0) && (strcmp(name, "1") != 0)) { + if (conf_read_simple(name, S_DEF_USER)) { + fprintf(stderr, + _("*** Can't read seed configuration \"%s\"!\n"), + name); + exit(1); + } + break; + } + switch (input_mode) { + case allnoconfig: name = "allno.config"; break; + case allyesconfig: name = "allyes.config"; break; + case allmodconfig: name = "allmod.config"; break; + case alldefconfig: name = "alldef.config"; break; + case randconfig: name = "allrandom.config"; break; + default: break; + } + if (conf_read_simple(name, S_DEF_USER) && + conf_read_simple("all.config", S_DEF_USER)) { + fprintf(stderr, + _("*** KCONFIG_ALLCONFIG set, but no \"%s\" or \"all.config\" file found\n"), + name); + exit(1); + } + break; + default: + break; + } + + if (sync_kconfig) { + if (conf_get_changed()) { + name = getenv("KCONFIG_NOSILENTUPDATE"); + if (name && *name) { + fprintf(stderr, + _("\n*** The configuration requires explicit update.\n\n")); + return 1; + } + } + valid_stdin = isatty(0) && isatty(1) && isatty(2); + } + + switch (input_mode) { + case allnoconfig: + conf_set_all_new_symbols(def_no); + break; + case allyesconfig: + conf_set_all_new_symbols(def_yes); + break; + case allmodconfig: + conf_set_all_new_symbols(def_mod); + break; + case alldefconfig: + conf_set_all_new_symbols(def_default); + break; + case randconfig: + conf_set_all_new_symbols(def_random); + break; + case defconfig: + conf_set_all_new_symbols(def_default); + break; + case savedefconfig: + break; + case oldaskconfig: + rootEntry = &rootmenu; + conf(&rootmenu); + input_mode = silentoldconfig; + /* fall through */ + case oldconfig: + case listnewconfig: + case oldnoconfig: + case silentoldconfig: + /* Update until a loop caused no more changes */ + do { + conf_cnt = 0; + check_conf(&rootmenu); + } while (conf_cnt && + (input_mode != listnewconfig && + input_mode != oldnoconfig)); + break; + } + + if (sync_kconfig) { + /* silentoldconfig is used during the build so we shall update autoconf. + * All other commands are only used to generate a config. + */ + if (conf_get_changed() && conf_write(NULL)) { + fprintf(stderr, _("\n*** Error during writing of the configuration.\n\n")); + exit(1); + } + if (conf_write_autoconf()) { + fprintf(stderr, _("\n*** Error during update of the configuration.\n\n")); + return 1; + } + } else if (input_mode == savedefconfig) { + if (conf_write_defconfig(defconfig_file)) { + fprintf(stderr, _("n*** Error while saving defconfig to: %s\n\n"), + defconfig_file); + return 1; + } + } else if (input_mode != listnewconfig) { + if (conf_write(NULL)) { + fprintf(stderr, _("\n*** Error during writing of the configuration.\n\n")); + exit(1); + } + } + return 0; +} + +/* + * Helper function to facilitate fgets() by Jean Sacren. + */ +void xfgets(char *str, int size, FILE *in) +{ + if (fgets(str, size, in) == NULL) + fprintf(stderr, "\nError in reading or end of file.\n"); +} diff --git a/misc/tools/kconfig-frontends/frontends/gconf/Makefile.am b/misc/tools/kconfig-frontends/frontends/gconf/Makefile.am new file mode 100644 index 0000000000..93ad7d46d0 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/gconf/Makefile.am @@ -0,0 +1,17 @@ +bin_PROGRAMS = gconf + +gconf_SOURCES = gconf.c gconf.glade +gconf_CPPFLAGS = $(AM_CPPFLAGS) \ + $(intl_CPPFLAGS) \ + -I$(top_srcdir)/libs/parser \ + -I$(top_builddir)/libs/images \ + -DGUI_PATH='"$(pkgdatadir)/gconf.glade"' +gconf_CFLAGS = $(AM_CFLAGS) \ + $(kf_CFLAGS) \ + $(gtk_CFLAGS) +gconf_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(top_builddir)/libs/images/libkconfig-images.a \ + $(intl_LIBS) $(gtk_LIBS) $(gconf_EXTRA_LIBS) +gconfdir = $(pkgdatadir) +gconf_DATA = gconf.glade +EXTRA_DIST = gconf.c.patch diff --git a/misc/tools/kconfig-frontends/frontends/gconf/Makefile.in b/misc/tools/kconfig-frontends/frontends/gconf/Makefile.in new file mode 100644 index 0000000000..ca793c47d7 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/gconf/Makefile.in @@ -0,0 +1,653 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ + + +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +bin_PROGRAMS = gconf$(EXEEXT) +subdir = frontends/gconf +DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +am__installdirs = "$(DESTDIR)$(bindir)" "$(DESTDIR)$(gconfdir)" +PROGRAMS = $(bin_PROGRAMS) +am_gconf_OBJECTS = gconf-gconf.$(OBJEXT) +gconf_OBJECTS = $(am_gconf_OBJECTS) +am__DEPENDENCIES_1 = +gconf_DEPENDENCIES = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(top_builddir)/libs/images/libkconfig-images.a \ + $(am__DEPENDENCIES_1) $(am__DEPENDENCIES_1) \ + $(am__DEPENDENCIES_1) +AM_V_lt = $(am__v_lt_$(V)) +am__v_lt_ = $(am__v_lt_$(AM_DEFAULT_VERBOSITY)) +am__v_lt_0 = --silent +gconf_LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(gconf_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +DEFAULT_INCLUDES = -I.@am__isrc@ -I$(top_builddir)/scripts/.autostuff +depcomp = $(SHELL) $(top_srcdir)/scripts/.autostuff/scripts/depcomp +am__depfiles_maybe = depfiles +am__mv = mv -f +COMPILE = $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) \ + $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) +LTCOMPILE = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) \ + $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) $(CPPFLAGS) \ + $(AM_CFLAGS) $(CFLAGS) +AM_V_CC = $(am__v_CC_$(V)) +am__v_CC_ = $(am__v_CC_$(AM_DEFAULT_VERBOSITY)) +am__v_CC_0 = @echo " CC " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +CCLD = $(CC) +LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(AM_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +AM_V_CCLD = $(am__v_CCLD_$(V)) +am__v_CCLD_ = $(am__v_CCLD_$(AM_DEFAULT_VERBOSITY)) +am__v_CCLD_0 = @echo " CCLD " $@; +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +SOURCES = $(gconf_SOURCES) +DIST_SOURCES = $(gconf_SOURCES) +am__vpath_adj_setup = srcdirstrip=`echo "$(srcdir)" | sed 's|.|.|g'`; +am__vpath_adj = case $$p in \ + $(srcdir)/*) f=`echo "$$p" | sed "s|^$$srcdirstrip/||"`;; \ + *) f=$$p;; \ + esac; +am__strip_dir = f=`echo $$p | sed -e 's|^.*/||'`; +am__install_max = 40 +am__nobase_strip_setup = \ + srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*|]/\\\\&/g'` +am__nobase_strip = \ + for p in $$list; do echo "$$p"; done | sed -e "s|$$srcdirstrip/||" +am__nobase_list = $(am__nobase_strip_setup); \ + for p in $$list; do echo "$$p $$p"; done | \ + sed "s| $$srcdirstrip/| |;"' / .*\//!s/ .*/ ./; s,\( .*\)/[^/]*$$,\1,' | \ + $(AWK) 'BEGIN { files["."] = "" } { files[$$2] = files[$$2] " " $$1; \ + if (++n[$$2] == $(am__install_max)) \ + { print $$2, files[$$2]; n[$$2] = 0; files[$$2] = "" } } \ + END { for (dir in files) print dir, files[dir] }' +am__base_list = \ + sed '$$!N;$$!N;$$!N;$$!N;$$!N;$$!N;$$!N;s/\n/ /g' | \ + sed '$$!N;$$!N;$$!N;$$!N;s/\n/ /g' +DATA = $(gconf_DATA) +ETAGS = etags +CTAGS = ctags +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +gconf_SOURCES = gconf.c gconf.glade +gconf_CPPFLAGS = $(AM_CPPFLAGS) \ + $(intl_CPPFLAGS) \ + -I$(top_srcdir)/libs/parser \ + -I$(top_builddir)/libs/images \ + -DGUI_PATH='"$(pkgdatadir)/gconf.glade"' + +gconf_CFLAGS = $(AM_CFLAGS) \ + $(kf_CFLAGS) \ + $(gtk_CFLAGS) + +gconf_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(top_builddir)/libs/images/libkconfig-images.a \ + $(intl_LIBS) $(gtk_LIBS) $(gconf_EXTRA_LIBS) + +gconfdir = $(pkgdatadir) +gconf_DATA = gconf.glade +EXTRA_DIST = gconf.c.patch +all: all-am + +.SUFFIXES: +.SUFFIXES: .c .lo .o .obj +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign frontends/gconf/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign frontends/gconf/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): +install-binPROGRAMS: $(bin_PROGRAMS) + @$(NORMAL_INSTALL) + test -z "$(bindir)" || $(MKDIR_P) "$(DESTDIR)$(bindir)" + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + for p in $$list; do echo "$$p $$p"; done | \ + sed 's/$(EXEEXT)$$//' | \ + while read p p1; do if test -f $$p || test -f $$p1; \ + then echo "$$p"; echo "$$p"; else :; fi; \ + done | \ + sed -e 'p;s,.*/,,;n;h' -e 's|.*|.|' \ + -e 'p;x;s,.*/,,;s/$(EXEEXT)$$//;$(transform);s/$$/$(EXEEXT)/' | \ + sed 'N;N;N;s,\n, ,g' | \ + $(AWK) 'BEGIN { files["."] = ""; dirs["."] = 1 } \ + { d=$$3; if (dirs[d] != 1) { print "d", d; dirs[d] = 1 } \ + if ($$2 == $$4) files[d] = files[d] " " $$1; \ + else { print "f", $$3 "/" $$4, $$1; } } \ + END { for (d in files) print "f", d, files[d] }' | \ + while read type dir files; do \ + if test "$$dir" = .; then dir=; else dir=/$$dir; fi; \ + test -z "$$files" || { \ + echo " $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files '$(DESTDIR)$(bindir)$$dir'"; \ + $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files "$(DESTDIR)$(bindir)$$dir" || exit $$?; \ + } \ + ; done + +uninstall-binPROGRAMS: + @$(NORMAL_UNINSTALL) + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + files=`for p in $$list; do echo "$$p"; done | \ + sed -e 'h;s,^.*/,,;s/$(EXEEXT)$$//;$(transform)' \ + -e 's/$$/$(EXEEXT)/' `; \ + test -n "$$list" || exit 0; \ + echo " ( cd '$(DESTDIR)$(bindir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(bindir)" && rm -f $$files + +clean-binPROGRAMS: + @list='$(bin_PROGRAMS)'; test -n "$$list" || exit 0; \ + echo " rm -f" $$list; \ + rm -f $$list || exit $$?; \ + test -n "$(EXEEXT)" || exit 0; \ + list=`for p in $$list; do echo "$$p"; done | sed 's/$(EXEEXT)$$//'`; \ + echo " rm -f" $$list; \ + rm -f $$list +gconf$(EXEEXT): $(gconf_OBJECTS) $(gconf_DEPENDENCIES) + @rm -f gconf$(EXEEXT) + $(AM_V_CCLD)$(gconf_LINK) $(gconf_OBJECTS) $(gconf_LDADD) $(LIBS) + +mostlyclean-compile: + -rm -f *.$(OBJEXT) + +distclean-compile: + -rm -f *.tab.c + +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/gconf-gconf.Po@am__quote@ + +.c.o: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c $< + +.c.obj: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ `$(CYGPATH_W) '$<'` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c `$(CYGPATH_W) '$<'` + +.c.lo: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LTCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LTCOMPILE) -c -o $@ $< + +gconf-gconf.o: gconf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(gconf_CPPFLAGS) $(CPPFLAGS) $(gconf_CFLAGS) $(CFLAGS) -MT gconf-gconf.o -MD -MP -MF $(DEPDIR)/gconf-gconf.Tpo -c -o gconf-gconf.o `test -f 'gconf.c' || echo '$(srcdir)/'`gconf.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/gconf-gconf.Tpo $(DEPDIR)/gconf-gconf.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='gconf.c' object='gconf-gconf.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(gconf_CPPFLAGS) $(CPPFLAGS) $(gconf_CFLAGS) $(CFLAGS) -c -o gconf-gconf.o `test -f 'gconf.c' || echo '$(srcdir)/'`gconf.c + +gconf-gconf.obj: gconf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(gconf_CPPFLAGS) $(CPPFLAGS) $(gconf_CFLAGS) $(CFLAGS) -MT gconf-gconf.obj -MD -MP -MF $(DEPDIR)/gconf-gconf.Tpo -c -o gconf-gconf.obj `if test -f 'gconf.c'; then $(CYGPATH_W) 'gconf.c'; else $(CYGPATH_W) '$(srcdir)/gconf.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/gconf-gconf.Tpo $(DEPDIR)/gconf-gconf.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='gconf.c' object='gconf-gconf.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(gconf_CPPFLAGS) $(CPPFLAGS) $(gconf_CFLAGS) $(CFLAGS) -c -o gconf-gconf.obj `if test -f 'gconf.c'; then $(CYGPATH_W) 'gconf.c'; else $(CYGPATH_W) '$(srcdir)/gconf.c'; fi` + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs +install-gconfDATA: $(gconf_DATA) + @$(NORMAL_INSTALL) + test -z "$(gconfdir)" || $(MKDIR_P) "$(DESTDIR)$(gconfdir)" + @list='$(gconf_DATA)'; test -n "$(gconfdir)" || list=; \ + for p in $$list; do \ + if test -f "$$p"; then d=; else d="$(srcdir)/"; fi; \ + echo "$$d$$p"; \ + done | $(am__base_list) | \ + while read files; do \ + echo " $(INSTALL_DATA) $$files '$(DESTDIR)$(gconfdir)'"; \ + $(INSTALL_DATA) $$files "$(DESTDIR)$(gconfdir)" || exit $$?; \ + done + +uninstall-gconfDATA: + @$(NORMAL_UNINSTALL) + @list='$(gconf_DATA)'; test -n "$(gconfdir)" || list=; \ + files=`for p in $$list; do echo $$p; done | sed -e 's|^.*/||'`; \ + test -n "$$files" || exit 0; \ + echo " ( cd '$(DESTDIR)$(gconfdir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(gconfdir)" && rm -f $$files + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-am +all-am: Makefile $(PROGRAMS) $(DATA) +installdirs: + for dir in "$(DESTDIR)$(bindir)" "$(DESTDIR)$(gconfdir)"; do \ + test -z "$$dir" || $(MKDIR_P) "$$dir"; \ + done +install: install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-am + +clean-am: clean-binPROGRAMS clean-generic clean-libtool mostlyclean-am + +distclean: distclean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +distclean-am: clean-am distclean-compile distclean-generic \ + distclean-tags + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: install-gconfDATA + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: install-binPROGRAMS + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: uninstall-binPROGRAMS uninstall-gconfDATA + +.MAKE: install-am install-strip + +.PHONY: CTAGS GTAGS all all-am check check-am clean clean-binPROGRAMS \ + clean-generic clean-libtool ctags distclean distclean-compile \ + distclean-generic distclean-libtool distclean-tags distdir dvi \ + dvi-am html html-am info info-am install install-am \ + install-binPROGRAMS install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-gconfDATA \ + install-html install-html-am install-info install-info-am \ + install-man install-pdf install-pdf-am install-ps \ + install-ps-am install-strip installcheck installcheck-am \ + installdirs maintainer-clean maintainer-clean-generic \ + mostlyclean mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool pdf pdf-am ps ps-am tags uninstall \ + uninstall-am uninstall-binPROGRAMS uninstall-gconfDATA + + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/frontends/gconf/gconf.c b/misc/tools/kconfig-frontends/frontends/gconf/gconf.c new file mode 100644 index 0000000000..b73a4f14a0 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/gconf/gconf.c @@ -0,0 +1,1546 @@ +/* Hey EMACS -*- linux-c -*- */ +/* + * + * Copyright (C) 2002-2003 Romain Lievin + * Released under the terms of the GNU GPL v2.0. + * + */ + +#ifdef HAVE_CONFIG_H +# include +#endif + +#include "lkc.h" +#include "images.h" + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +//#define DEBUG + +enum { + SINGLE_VIEW, SPLIT_VIEW, FULL_VIEW +}; + +enum { + OPT_NORMAL, OPT_ALL, OPT_PROMPT +}; + +static gint view_mode = FULL_VIEW; +static gboolean show_name = TRUE; +static gboolean show_range = TRUE; +static gboolean show_value = TRUE; +static gboolean resizeable = FALSE; +static int opt_mode = OPT_NORMAL; + +GtkWidget *main_wnd = NULL; +GtkWidget *tree1_w = NULL; // left frame +GtkWidget *tree2_w = NULL; // right frame +GtkWidget *text_w = NULL; +GtkWidget *hpaned = NULL; +GtkWidget *vpaned = NULL; +GtkWidget *back_btn = NULL; +GtkWidget *save_btn = NULL; +GtkWidget *save_menu_item = NULL; + +GtkTextTag *tag1, *tag2; +GdkColor color; + +GtkTreeStore *tree1, *tree2, *tree; +GtkTreeModel *model1, *model2; +static GtkTreeIter *parents[256]; +static gint indent; + +static struct menu *current; // current node for SINGLE view +static struct menu *browsed; // browsed node for SPLIT view + +enum { + COL_OPTION, COL_NAME, COL_NO, COL_MOD, COL_YES, COL_VALUE, + COL_MENU, COL_COLOR, COL_EDIT, COL_PIXBUF, + COL_PIXVIS, COL_BTNVIS, COL_BTNACT, COL_BTNINC, COL_BTNRAD, + COL_NUMBER +}; + +static void display_list(void); +static void display_tree(struct menu *menu); +static void display_tree_part(void); +static void update_tree(struct menu *src, GtkTreeIter * dst); +static void set_node(GtkTreeIter * node, struct menu *menu, gchar ** row); +static gchar **fill_row(struct menu *menu); +static void conf_changed(void); + +/* Helping/Debugging Functions */ + +const char *dbg_sym_flags(int val) +{ + static char buf[256]; + + bzero(buf, 256); + + if (val & SYMBOL_CONST) + strcat(buf, "const/"); + if (val & SYMBOL_CHECK) + strcat(buf, "check/"); + if (val & SYMBOL_CHOICE) + strcat(buf, "choice/"); + if (val & SYMBOL_CHOICEVAL) + strcat(buf, "choiceval/"); + if (val & SYMBOL_VALID) + strcat(buf, "valid/"); + if (val & SYMBOL_OPTIONAL) + strcat(buf, "optional/"); + if (val & SYMBOL_WRITE) + strcat(buf, "write/"); + if (val & SYMBOL_CHANGED) + strcat(buf, "changed/"); + if (val & SYMBOL_AUTO) + strcat(buf, "auto/"); + + buf[strlen(buf) - 1] = '\0'; + + return buf; +} + +void replace_button_icon(GladeXML * xml, GdkDrawable * window, + GtkStyle * style, gchar * btn_name, gchar ** xpm) +{ + GdkPixmap *pixmap; + GdkBitmap *mask; + GtkToolButton *button; + GtkWidget *image; + + pixmap = gdk_pixmap_create_from_xpm_d(window, &mask, + &style->bg[GTK_STATE_NORMAL], + xpm); + + button = GTK_TOOL_BUTTON(glade_xml_get_widget(xml, btn_name)); + image = gtk_image_new_from_pixmap(pixmap, mask); + gtk_widget_show(image); + gtk_tool_button_set_icon_widget(button, image); +} + +/* Main Window Initialization */ +void init_main_window(const gchar * glade_file) +{ + GladeXML *xml; + GtkWidget *widget; + GtkTextBuffer *txtbuf; + GtkStyle *style; + + xml = glade_xml_new(glade_file, "window1", NULL); + if (!xml) + g_error(_("GUI loading failed !\n")); + glade_xml_signal_autoconnect(xml); + + main_wnd = glade_xml_get_widget(xml, "window1"); + hpaned = glade_xml_get_widget(xml, "hpaned1"); + vpaned = glade_xml_get_widget(xml, "vpaned1"); + tree1_w = glade_xml_get_widget(xml, "treeview1"); + tree2_w = glade_xml_get_widget(xml, "treeview2"); + text_w = glade_xml_get_widget(xml, "textview3"); + + back_btn = glade_xml_get_widget(xml, "button1"); + gtk_widget_set_sensitive(back_btn, FALSE); + + widget = glade_xml_get_widget(xml, "show_name1"); + gtk_check_menu_item_set_active((GtkCheckMenuItem *) widget, + show_name); + + widget = glade_xml_get_widget(xml, "show_range1"); + gtk_check_menu_item_set_active((GtkCheckMenuItem *) widget, + show_range); + + widget = glade_xml_get_widget(xml, "show_data1"); + gtk_check_menu_item_set_active((GtkCheckMenuItem *) widget, + show_value); + + save_btn = glade_xml_get_widget(xml, "button3"); + save_menu_item = glade_xml_get_widget(xml, "save1"); + conf_set_changed_callback(conf_changed); + + style = gtk_widget_get_style(main_wnd); + widget = glade_xml_get_widget(xml, "toolbar1"); + +#if 0 /* Use stock Gtk icons instead */ + replace_button_icon(xml, main_wnd->window, style, + "button1", (gchar **) xpm_back); + replace_button_icon(xml, main_wnd->window, style, + "button2", (gchar **) xpm_load); + replace_button_icon(xml, main_wnd->window, style, + "button3", (gchar **) xpm_save); +#endif + replace_button_icon(xml, main_wnd->window, style, + "button4", (gchar **) xpm_single_view); + replace_button_icon(xml, main_wnd->window, style, + "button5", (gchar **) xpm_split_view); + replace_button_icon(xml, main_wnd->window, style, + "button6", (gchar **) xpm_tree_view); + +#if 0 + switch (view_mode) { + case SINGLE_VIEW: + widget = glade_xml_get_widget(xml, "button4"); + g_signal_emit_by_name(widget, "clicked"); + break; + case SPLIT_VIEW: + widget = glade_xml_get_widget(xml, "button5"); + g_signal_emit_by_name(widget, "clicked"); + break; + case FULL_VIEW: + widget = glade_xml_get_widget(xml, "button6"); + g_signal_emit_by_name(widget, "clicked"); + break; + } +#endif + txtbuf = gtk_text_view_get_buffer(GTK_TEXT_VIEW(text_w)); + tag1 = gtk_text_buffer_create_tag(txtbuf, "mytag1", + "foreground", "red", + "weight", PANGO_WEIGHT_BOLD, + NULL); + tag2 = gtk_text_buffer_create_tag(txtbuf, "mytag2", + /*"style", PANGO_STYLE_OBLIQUE, */ + NULL); + + gtk_window_set_title(GTK_WINDOW(main_wnd), rootmenu.prompt->text); + + gtk_widget_show(main_wnd); +} + +void init_tree_model(void) +{ + gint i; + + tree = tree2 = gtk_tree_store_new(COL_NUMBER, + G_TYPE_STRING, G_TYPE_STRING, + G_TYPE_STRING, G_TYPE_STRING, + G_TYPE_STRING, G_TYPE_STRING, + G_TYPE_POINTER, GDK_TYPE_COLOR, + G_TYPE_BOOLEAN, GDK_TYPE_PIXBUF, + G_TYPE_BOOLEAN, G_TYPE_BOOLEAN, + G_TYPE_BOOLEAN, G_TYPE_BOOLEAN, + G_TYPE_BOOLEAN); + model2 = GTK_TREE_MODEL(tree2); + + for (parents[0] = NULL, i = 1; i < 256; i++) + parents[i] = (GtkTreeIter *) g_malloc(sizeof(GtkTreeIter)); + + tree1 = gtk_tree_store_new(COL_NUMBER, + G_TYPE_STRING, G_TYPE_STRING, + G_TYPE_STRING, G_TYPE_STRING, + G_TYPE_STRING, G_TYPE_STRING, + G_TYPE_POINTER, GDK_TYPE_COLOR, + G_TYPE_BOOLEAN, GDK_TYPE_PIXBUF, + G_TYPE_BOOLEAN, G_TYPE_BOOLEAN, + G_TYPE_BOOLEAN, G_TYPE_BOOLEAN, + G_TYPE_BOOLEAN); + model1 = GTK_TREE_MODEL(tree1); +} + +void init_left_tree(void) +{ + GtkTreeView *view = GTK_TREE_VIEW(tree1_w); + GtkCellRenderer *renderer; + GtkTreeSelection *sel; + GtkTreeViewColumn *column; + + gtk_tree_view_set_model(view, model1); + gtk_tree_view_set_headers_visible(view, TRUE); + gtk_tree_view_set_rules_hint(view, TRUE); + + column = gtk_tree_view_column_new(); + gtk_tree_view_append_column(view, column); + gtk_tree_view_column_set_title(column, _("Options")); + + renderer = gtk_cell_renderer_toggle_new(); + gtk_tree_view_column_pack_start(GTK_TREE_VIEW_COLUMN(column), + renderer, FALSE); + gtk_tree_view_column_set_attributes(GTK_TREE_VIEW_COLUMN(column), + renderer, + "active", COL_BTNACT, + "inconsistent", COL_BTNINC, + "visible", COL_BTNVIS, + "radio", COL_BTNRAD, NULL); + renderer = gtk_cell_renderer_text_new(); + gtk_tree_view_column_pack_start(GTK_TREE_VIEW_COLUMN(column), + renderer, FALSE); + gtk_tree_view_column_set_attributes(GTK_TREE_VIEW_COLUMN(column), + renderer, + "text", COL_OPTION, + "foreground-gdk", + COL_COLOR, NULL); + + sel = gtk_tree_view_get_selection(view); + gtk_tree_selection_set_mode(sel, GTK_SELECTION_SINGLE); + gtk_widget_realize(tree1_w); +} + +static void renderer_edited(GtkCellRendererText * cell, + const gchar * path_string, + const gchar * new_text, gpointer user_data); + +void init_right_tree(void) +{ + GtkTreeView *view = GTK_TREE_VIEW(tree2_w); + GtkCellRenderer *renderer; + GtkTreeSelection *sel; + GtkTreeViewColumn *column; + gint i; + + gtk_tree_view_set_model(view, model2); + gtk_tree_view_set_headers_visible(view, TRUE); + gtk_tree_view_set_rules_hint(view, TRUE); + + column = gtk_tree_view_column_new(); + gtk_tree_view_append_column(view, column); + gtk_tree_view_column_set_title(column, _("Options")); + + renderer = gtk_cell_renderer_pixbuf_new(); + gtk_tree_view_column_pack_start(GTK_TREE_VIEW_COLUMN(column), + renderer, FALSE); + gtk_tree_view_column_set_attributes(GTK_TREE_VIEW_COLUMN(column), + renderer, + "pixbuf", COL_PIXBUF, + "visible", COL_PIXVIS, NULL); + renderer = gtk_cell_renderer_toggle_new(); + gtk_tree_view_column_pack_start(GTK_TREE_VIEW_COLUMN(column), + renderer, FALSE); + gtk_tree_view_column_set_attributes(GTK_TREE_VIEW_COLUMN(column), + renderer, + "active", COL_BTNACT, + "inconsistent", COL_BTNINC, + "visible", COL_BTNVIS, + "radio", COL_BTNRAD, NULL); + renderer = gtk_cell_renderer_text_new(); + gtk_tree_view_column_pack_start(GTK_TREE_VIEW_COLUMN(column), + renderer, FALSE); + gtk_tree_view_column_set_attributes(GTK_TREE_VIEW_COLUMN(column), + renderer, + "text", COL_OPTION, + "foreground-gdk", + COL_COLOR, NULL); + + renderer = gtk_cell_renderer_text_new(); + gtk_tree_view_insert_column_with_attributes(view, -1, + _("Name"), renderer, + "text", COL_NAME, + "foreground-gdk", + COL_COLOR, NULL); + renderer = gtk_cell_renderer_text_new(); + gtk_tree_view_insert_column_with_attributes(view, -1, + "N", renderer, + "text", COL_NO, + "foreground-gdk", + COL_COLOR, NULL); + renderer = gtk_cell_renderer_text_new(); + gtk_tree_view_insert_column_with_attributes(view, -1, + "M", renderer, + "text", COL_MOD, + "foreground-gdk", + COL_COLOR, NULL); + renderer = gtk_cell_renderer_text_new(); + gtk_tree_view_insert_column_with_attributes(view, -1, + "Y", renderer, + "text", COL_YES, + "foreground-gdk", + COL_COLOR, NULL); + renderer = gtk_cell_renderer_text_new(); + gtk_tree_view_insert_column_with_attributes(view, -1, + _("Value"), renderer, + "text", COL_VALUE, + "editable", + COL_EDIT, + "foreground-gdk", + COL_COLOR, NULL); + g_signal_connect(G_OBJECT(renderer), "edited", + G_CALLBACK(renderer_edited), NULL); + + column = gtk_tree_view_get_column(view, COL_NAME); + gtk_tree_view_column_set_visible(column, show_name); + column = gtk_tree_view_get_column(view, COL_NO); + gtk_tree_view_column_set_visible(column, show_range); + column = gtk_tree_view_get_column(view, COL_MOD); + gtk_tree_view_column_set_visible(column, show_range); + column = gtk_tree_view_get_column(view, COL_YES); + gtk_tree_view_column_set_visible(column, show_range); + column = gtk_tree_view_get_column(view, COL_VALUE); + gtk_tree_view_column_set_visible(column, show_value); + + if (resizeable) { + for (i = 0; i < COL_VALUE; i++) { + column = gtk_tree_view_get_column(view, i); + gtk_tree_view_column_set_resizable(column, TRUE); + } + } + + sel = gtk_tree_view_get_selection(view); + gtk_tree_selection_set_mode(sel, GTK_SELECTION_SINGLE); +} + + +/* Utility Functions */ + + +static void text_insert_help(struct menu *menu) +{ + GtkTextBuffer *buffer; + GtkTextIter start, end; + const char *prompt = _(menu_get_prompt(menu)); + struct gstr help = str_new(); + + menu_get_ext_help(menu, &help); + + buffer = gtk_text_view_get_buffer(GTK_TEXT_VIEW(text_w)); + gtk_text_buffer_get_bounds(buffer, &start, &end); + gtk_text_buffer_delete(buffer, &start, &end); + gtk_text_view_set_left_margin(GTK_TEXT_VIEW(text_w), 15); + + gtk_text_buffer_get_end_iter(buffer, &end); + gtk_text_buffer_insert_with_tags(buffer, &end, prompt, -1, tag1, + NULL); + gtk_text_buffer_insert_at_cursor(buffer, "\n\n", 2); + gtk_text_buffer_get_end_iter(buffer, &end); + gtk_text_buffer_insert_with_tags(buffer, &end, str_get(&help), -1, tag2, + NULL); + str_free(&help); +} + + +static void text_insert_msg(const char *title, const char *message) +{ + GtkTextBuffer *buffer; + GtkTextIter start, end; + const char *msg = message; + + buffer = gtk_text_view_get_buffer(GTK_TEXT_VIEW(text_w)); + gtk_text_buffer_get_bounds(buffer, &start, &end); + gtk_text_buffer_delete(buffer, &start, &end); + gtk_text_view_set_left_margin(GTK_TEXT_VIEW(text_w), 15); + + gtk_text_buffer_get_end_iter(buffer, &end); + gtk_text_buffer_insert_with_tags(buffer, &end, title, -1, tag1, + NULL); + gtk_text_buffer_insert_at_cursor(buffer, "\n\n", 2); + gtk_text_buffer_get_end_iter(buffer, &end); + gtk_text_buffer_insert_with_tags(buffer, &end, msg, -1, tag2, + NULL); +} + + +/* Main Windows Callbacks */ + +void on_save_activate(GtkMenuItem * menuitem, gpointer user_data); +gboolean on_window1_delete_event(GtkWidget * widget, GdkEvent * event, + gpointer user_data) +{ + GtkWidget *dialog, *label; + gint result; + + if (!conf_get_changed()) + return FALSE; + + dialog = gtk_dialog_new_with_buttons(_("Warning !"), + GTK_WINDOW(main_wnd), + (GtkDialogFlags) + (GTK_DIALOG_MODAL | + GTK_DIALOG_DESTROY_WITH_PARENT), + GTK_STOCK_OK, + GTK_RESPONSE_YES, + GTK_STOCK_NO, + GTK_RESPONSE_NO, + GTK_STOCK_CANCEL, + GTK_RESPONSE_CANCEL, NULL); + gtk_dialog_set_default_response(GTK_DIALOG(dialog), + GTK_RESPONSE_CANCEL); + + label = gtk_label_new(_("\nSave configuration ?\n")); + gtk_container_add(GTK_CONTAINER(GTK_DIALOG(dialog)->vbox), label); + gtk_widget_show(label); + + result = gtk_dialog_run(GTK_DIALOG(dialog)); + switch (result) { + case GTK_RESPONSE_YES: + on_save_activate(NULL, NULL); + return FALSE; + case GTK_RESPONSE_NO: + return FALSE; + case GTK_RESPONSE_CANCEL: + case GTK_RESPONSE_DELETE_EVENT: + default: + gtk_widget_destroy(dialog); + return TRUE; + } + + return FALSE; +} + + +void on_window1_destroy(GtkObject * object, gpointer user_data) +{ + gtk_main_quit(); +} + + +void +on_window1_size_request(GtkWidget * widget, + GtkRequisition * requisition, gpointer user_data) +{ + static gint old_h; + gint w, h; + + if (widget->window == NULL) + gtk_window_get_default_size(GTK_WINDOW(main_wnd), &w, &h); + else + gdk_window_get_size(widget->window, &w, &h); + + if (h == old_h) + return; + old_h = h; + + gtk_paned_set_position(GTK_PANED(vpaned), 2 * h / 3); +} + + +/* Menu & Toolbar Callbacks */ + + +static void +load_filename(GtkFileSelection * file_selector, gpointer user_data) +{ + const gchar *fn; + + fn = gtk_file_selection_get_filename(GTK_FILE_SELECTION + (user_data)); + + if (conf_read(fn)) + text_insert_msg(_("Error"), _("Unable to load configuration !")); + else + display_tree(&rootmenu); +} + +void on_load1_activate(GtkMenuItem * menuitem, gpointer user_data) +{ + GtkWidget *fs; + + fs = gtk_file_selection_new(_("Load file...")); + g_signal_connect(GTK_OBJECT(GTK_FILE_SELECTION(fs)->ok_button), + "clicked", + G_CALLBACK(load_filename), (gpointer) fs); + g_signal_connect_swapped(GTK_OBJECT + (GTK_FILE_SELECTION(fs)->ok_button), + "clicked", G_CALLBACK(gtk_widget_destroy), + (gpointer) fs); + g_signal_connect_swapped(GTK_OBJECT + (GTK_FILE_SELECTION(fs)->cancel_button), + "clicked", G_CALLBACK(gtk_widget_destroy), + (gpointer) fs); + gtk_widget_show(fs); +} + + +void on_save_activate(GtkMenuItem * menuitem, gpointer user_data) +{ + if (conf_write(NULL)) + text_insert_msg(_("Error"), _("Unable to save configuration !")); +} + + +static void +store_filename(GtkFileSelection * file_selector, gpointer user_data) +{ + const gchar *fn; + + fn = gtk_file_selection_get_filename(GTK_FILE_SELECTION + (user_data)); + + if (conf_write(fn)) + text_insert_msg(_("Error"), _("Unable to save configuration !")); + + gtk_widget_destroy(GTK_WIDGET(user_data)); +} + +void on_save_as1_activate(GtkMenuItem * menuitem, gpointer user_data) +{ + GtkWidget *fs; + + fs = gtk_file_selection_new(_("Save file as...")); + g_signal_connect(GTK_OBJECT(GTK_FILE_SELECTION(fs)->ok_button), + "clicked", + G_CALLBACK(store_filename), (gpointer) fs); + g_signal_connect_swapped(GTK_OBJECT + (GTK_FILE_SELECTION(fs)->ok_button), + "clicked", G_CALLBACK(gtk_widget_destroy), + (gpointer) fs); + g_signal_connect_swapped(GTK_OBJECT + (GTK_FILE_SELECTION(fs)->cancel_button), + "clicked", G_CALLBACK(gtk_widget_destroy), + (gpointer) fs); + gtk_widget_show(fs); +} + + +void on_quit1_activate(GtkMenuItem * menuitem, gpointer user_data) +{ + if (!on_window1_delete_event(NULL, NULL, NULL)) + gtk_widget_destroy(GTK_WIDGET(main_wnd)); +} + + +void on_show_name1_activate(GtkMenuItem * menuitem, gpointer user_data) +{ + GtkTreeViewColumn *col; + + show_name = GTK_CHECK_MENU_ITEM(menuitem)->active; + col = gtk_tree_view_get_column(GTK_TREE_VIEW(tree2_w), COL_NAME); + if (col) + gtk_tree_view_column_set_visible(col, show_name); +} + + +void on_show_range1_activate(GtkMenuItem * menuitem, gpointer user_data) +{ + GtkTreeViewColumn *col; + + show_range = GTK_CHECK_MENU_ITEM(menuitem)->active; + col = gtk_tree_view_get_column(GTK_TREE_VIEW(tree2_w), COL_NO); + if (col) + gtk_tree_view_column_set_visible(col, show_range); + col = gtk_tree_view_get_column(GTK_TREE_VIEW(tree2_w), COL_MOD); + if (col) + gtk_tree_view_column_set_visible(col, show_range); + col = gtk_tree_view_get_column(GTK_TREE_VIEW(tree2_w), COL_YES); + if (col) + gtk_tree_view_column_set_visible(col, show_range); + +} + + +void on_show_data1_activate(GtkMenuItem * menuitem, gpointer user_data) +{ + GtkTreeViewColumn *col; + + show_value = GTK_CHECK_MENU_ITEM(menuitem)->active; + col = gtk_tree_view_get_column(GTK_TREE_VIEW(tree2_w), COL_VALUE); + if (col) + gtk_tree_view_column_set_visible(col, show_value); +} + + +void +on_set_option_mode1_activate(GtkMenuItem *menuitem, gpointer user_data) +{ + opt_mode = OPT_NORMAL; + gtk_tree_store_clear(tree2); + display_tree(&rootmenu); /* instead of update_tree to speed-up */ +} + + +void +on_set_option_mode2_activate(GtkMenuItem *menuitem, gpointer user_data) +{ + opt_mode = OPT_ALL; + gtk_tree_store_clear(tree2); + display_tree(&rootmenu); /* instead of update_tree to speed-up */ +} + + +void +on_set_option_mode3_activate(GtkMenuItem *menuitem, gpointer user_data) +{ + opt_mode = OPT_PROMPT; + gtk_tree_store_clear(tree2); + display_tree(&rootmenu); /* instead of update_tree to speed-up */ +} + + +void on_introduction1_activate(GtkMenuItem * menuitem, gpointer user_data) +{ + GtkWidget *dialog; + const gchar *intro_text = _( + "Welcome to gkc, the GTK+ graphical configuration tool\n" + "For each option, a blank box indicates the feature is disabled, a\n" + "check indicates it is enabled, and a dot indicates that it is to\n" + "be compiled as a module. Clicking on the box will cycle through the three states.\n" + "\n" + "If you do not see an option (e.g., a device driver) that you\n" + "believe should be present, try turning on Show All Options\n" + "under the Options menu.\n" + "Although there is no cross reference yet to help you figure out\n" + "what other options must be enabled to support the option you\n" + "are interested in, you can still view the help of a grayed-out\n" + "option.\n" + "\n" + "Toggling Show Debug Info under the Options menu will show \n" + "the dependencies, which you can then match by examining other options."); + + dialog = gtk_message_dialog_new(GTK_WINDOW(main_wnd), + GTK_DIALOG_DESTROY_WITH_PARENT, + GTK_MESSAGE_INFO, + GTK_BUTTONS_CLOSE, "%s", intro_text); + g_signal_connect_swapped(GTK_OBJECT(dialog), "response", + G_CALLBACK(gtk_widget_destroy), + GTK_OBJECT(dialog)); + gtk_widget_show_all(dialog); +} + + +void on_about1_activate(GtkMenuItem * menuitem, gpointer user_data) +{ + GtkWidget *dialog; + const gchar *about_text = + _("gkc is copyright (c) 2002 Romain Lievin .\n" + "Based on the source code from Roman Zippel.\n"); + + dialog = gtk_message_dialog_new(GTK_WINDOW(main_wnd), + GTK_DIALOG_DESTROY_WITH_PARENT, + GTK_MESSAGE_INFO, + GTK_BUTTONS_CLOSE, "%s", about_text); + g_signal_connect_swapped(GTK_OBJECT(dialog), "response", + G_CALLBACK(gtk_widget_destroy), + GTK_OBJECT(dialog)); + gtk_widget_show_all(dialog); +} + + +void on_license1_activate(GtkMenuItem * menuitem, gpointer user_data) +{ + GtkWidget *dialog; + const gchar *license_text = + _("gkc is released under the terms of the GNU GPL v2.\n" + "For more information, please see the source code or\n" + "visit http://www.fsf.org/licenses/licenses.html\n"); + + dialog = gtk_message_dialog_new(GTK_WINDOW(main_wnd), + GTK_DIALOG_DESTROY_WITH_PARENT, + GTK_MESSAGE_INFO, + GTK_BUTTONS_CLOSE, "%s", license_text); + g_signal_connect_swapped(GTK_OBJECT(dialog), "response", + G_CALLBACK(gtk_widget_destroy), + GTK_OBJECT(dialog)); + gtk_widget_show_all(dialog); +} + + +void on_back_clicked(GtkButton * button, gpointer user_data) +{ + enum prop_type ptype; + + current = current->parent; + ptype = current->prompt ? current->prompt->type : P_UNKNOWN; + if (ptype != P_MENU) + current = current->parent; + display_tree_part(); + + if (current == &rootmenu) + gtk_widget_set_sensitive(back_btn, FALSE); +} + + +void on_load_clicked(GtkButton * button, gpointer user_data) +{ + on_load1_activate(NULL, user_data); +} + + +void on_single_clicked(GtkButton * button, gpointer user_data) +{ + view_mode = SINGLE_VIEW; + gtk_widget_hide(tree1_w); + current = &rootmenu; + display_tree_part(); +} + + +void on_split_clicked(GtkButton * button, gpointer user_data) +{ + gint w, h; + view_mode = SPLIT_VIEW; + gtk_widget_show(tree1_w); + gtk_window_get_default_size(GTK_WINDOW(main_wnd), &w, &h); + gtk_paned_set_position(GTK_PANED(hpaned), w / 2); + if (tree2) + gtk_tree_store_clear(tree2); + display_list(); + + /* Disable back btn, like in full mode. */ + gtk_widget_set_sensitive(back_btn, FALSE); +} + + +void on_full_clicked(GtkButton * button, gpointer user_data) +{ + view_mode = FULL_VIEW; + gtk_widget_hide(tree1_w); + if (tree2) + gtk_tree_store_clear(tree2); + display_tree(&rootmenu); + gtk_widget_set_sensitive(back_btn, FALSE); +} + + +void on_collapse_clicked(GtkButton * button, gpointer user_data) +{ + gtk_tree_view_collapse_all(GTK_TREE_VIEW(tree2_w)); +} + + +void on_expand_clicked(GtkButton * button, gpointer user_data) +{ + gtk_tree_view_expand_all(GTK_TREE_VIEW(tree2_w)); +} + + +/* CTree Callbacks */ + +/* Change hex/int/string value in the cell */ +static void renderer_edited(GtkCellRendererText * cell, + const gchar * path_string, + const gchar * new_text, gpointer user_data) +{ + GtkTreePath *path = gtk_tree_path_new_from_string(path_string); + GtkTreeIter iter; + const char *old_def, *new_def; + struct menu *menu; + struct symbol *sym; + + if (!gtk_tree_model_get_iter(model2, &iter, path)) + return; + + gtk_tree_model_get(model2, &iter, COL_MENU, &menu, -1); + sym = menu->sym; + + gtk_tree_model_get(model2, &iter, COL_VALUE, &old_def, -1); + new_def = new_text; + + sym_set_string_value(sym, new_def); + + update_tree(&rootmenu, NULL); + + gtk_tree_path_free(path); +} + +/* Change the value of a symbol and update the tree */ +static void change_sym_value(struct menu *menu, gint col) +{ + struct symbol *sym = menu->sym; + tristate newval; + + if (!sym) + return; + + if (col == COL_NO) + newval = no; + else if (col == COL_MOD) + newval = mod; + else if (col == COL_YES) + newval = yes; + else + return; + + switch (sym_get_type(sym)) { + case S_BOOLEAN: + case S_TRISTATE: + if (!sym_tristate_within_range(sym, newval)) + newval = yes; + sym_set_tristate_value(sym, newval); + if (view_mode == FULL_VIEW) + update_tree(&rootmenu, NULL); + else if (view_mode == SPLIT_VIEW) { + update_tree(browsed, NULL); + display_list(); + } + else if (view_mode == SINGLE_VIEW) + display_tree_part(); //fixme: keep exp/coll + break; + case S_INT: + case S_HEX: + case S_STRING: + default: + break; + } +} + +static void toggle_sym_value(struct menu *menu) +{ + if (!menu->sym) + return; + + sym_toggle_tristate_value(menu->sym); + if (view_mode == FULL_VIEW) + update_tree(&rootmenu, NULL); + else if (view_mode == SPLIT_VIEW) { + update_tree(browsed, NULL); + display_list(); + } + else if (view_mode == SINGLE_VIEW) + display_tree_part(); //fixme: keep exp/coll +} + +static gint column2index(GtkTreeViewColumn * column) +{ + gint i; + + for (i = 0; i < COL_NUMBER; i++) { + GtkTreeViewColumn *col; + + col = gtk_tree_view_get_column(GTK_TREE_VIEW(tree2_w), i); + if (col == column) + return i; + } + + return -1; +} + + +/* User click: update choice (full) or goes down (single) */ +gboolean +on_treeview2_button_press_event(GtkWidget * widget, + GdkEventButton * event, gpointer user_data) +{ + GtkTreeView *view = GTK_TREE_VIEW(widget); + GtkTreePath *path; + GtkTreeViewColumn *column; + GtkTreeIter iter; + struct menu *menu; + gint col; + +#if GTK_CHECK_VERSION(2,1,4) // bug in ctree with earlier version of GTK + gint tx = (gint) event->x; + gint ty = (gint) event->y; + gint cx, cy; + + gtk_tree_view_get_path_at_pos(view, tx, ty, &path, &column, &cx, + &cy); +#else + gtk_tree_view_get_cursor(view, &path, &column); +#endif + if (path == NULL) + return FALSE; + + if (!gtk_tree_model_get_iter(model2, &iter, path)) + return FALSE; + gtk_tree_model_get(model2, &iter, COL_MENU, &menu, -1); + + col = column2index(column); + if (event->type == GDK_2BUTTON_PRESS) { + enum prop_type ptype; + ptype = menu->prompt ? menu->prompt->type : P_UNKNOWN; + + if (ptype == P_MENU && view_mode != FULL_VIEW && col == COL_OPTION) { + // goes down into menu + current = menu; + display_tree_part(); + gtk_widget_set_sensitive(back_btn, TRUE); + } else if ((col == COL_OPTION)) { + toggle_sym_value(menu); + gtk_tree_view_expand_row(view, path, TRUE); + } + } else { + if (col == COL_VALUE) { + toggle_sym_value(menu); + gtk_tree_view_expand_row(view, path, TRUE); + } else if (col == COL_NO || col == COL_MOD + || col == COL_YES) { + change_sym_value(menu, col); + gtk_tree_view_expand_row(view, path, TRUE); + } + } + + return FALSE; +} + +/* Key pressed: update choice */ +gboolean +on_treeview2_key_press_event(GtkWidget * widget, + GdkEventKey * event, gpointer user_data) +{ + GtkTreeView *view = GTK_TREE_VIEW(widget); + GtkTreePath *path; + GtkTreeViewColumn *column; + GtkTreeIter iter; + struct menu *menu; + gint col; + + gtk_tree_view_get_cursor(view, &path, &column); + if (path == NULL) + return FALSE; + + if (event->keyval == GDK_space) { + if (gtk_tree_view_row_expanded(view, path)) + gtk_tree_view_collapse_row(view, path); + else + gtk_tree_view_expand_row(view, path, FALSE); + return TRUE; + } + if (event->keyval == GDK_KP_Enter) { + } + if (widget == tree1_w) + return FALSE; + + gtk_tree_model_get_iter(model2, &iter, path); + gtk_tree_model_get(model2, &iter, COL_MENU, &menu, -1); + + if (!strcasecmp(event->string, "n")) + col = COL_NO; + else if (!strcasecmp(event->string, "m")) + col = COL_MOD; + else if (!strcasecmp(event->string, "y")) + col = COL_YES; + else + col = -1; + change_sym_value(menu, col); + + return FALSE; +} + + +/* Row selection changed: update help */ +void +on_treeview2_cursor_changed(GtkTreeView * treeview, gpointer user_data) +{ + GtkTreeSelection *selection; + GtkTreeIter iter; + struct menu *menu; + + selection = gtk_tree_view_get_selection(treeview); + if (gtk_tree_selection_get_selected(selection, &model2, &iter)) { + gtk_tree_model_get(model2, &iter, COL_MENU, &menu, -1); + text_insert_help(menu); + } +} + + +/* User click: display sub-tree in the right frame. */ +gboolean +on_treeview1_button_press_event(GtkWidget * widget, + GdkEventButton * event, gpointer user_data) +{ + GtkTreeView *view = GTK_TREE_VIEW(widget); + GtkTreePath *path; + GtkTreeViewColumn *column; + GtkTreeIter iter; + struct menu *menu; + + gint tx = (gint) event->x; + gint ty = (gint) event->y; + gint cx, cy; + + gtk_tree_view_get_path_at_pos(view, tx, ty, &path, &column, &cx, + &cy); + if (path == NULL) + return FALSE; + + gtk_tree_model_get_iter(model1, &iter, path); + gtk_tree_model_get(model1, &iter, COL_MENU, &menu, -1); + + if (event->type == GDK_2BUTTON_PRESS) { + toggle_sym_value(menu); + current = menu; + display_tree_part(); + } else { + browsed = menu; + display_tree_part(); + } + + gtk_widget_realize(tree2_w); + gtk_tree_view_set_cursor(view, path, NULL, FALSE); + gtk_widget_grab_focus(tree2_w); + + return FALSE; +} + + +/* Fill a row of strings */ +static gchar **fill_row(struct menu *menu) +{ + static gchar *row[COL_NUMBER]; + struct symbol *sym = menu->sym; + const char *def; + int stype; + tristate val; + enum prop_type ptype; + int i; + + for (i = COL_OPTION; i <= COL_COLOR; i++) + g_free(row[i]); + bzero(row, sizeof(row)); + + row[COL_OPTION] = + g_strdup_printf("%s %s", _(menu_get_prompt(menu)), + sym && !sym_has_value(sym) ? "(NEW)" : ""); + + if (opt_mode == OPT_ALL && !menu_is_visible(menu)) + row[COL_COLOR] = g_strdup("DarkGray"); + else if (opt_mode == OPT_PROMPT && + menu_has_prompt(menu) && !menu_is_visible(menu)) + row[COL_COLOR] = g_strdup("DarkGray"); + else + row[COL_COLOR] = g_strdup("Black"); + + ptype = menu->prompt ? menu->prompt->type : P_UNKNOWN; + switch (ptype) { + case P_MENU: + row[COL_PIXBUF] = (gchar *) xpm_menu; + if (view_mode == SINGLE_VIEW) + row[COL_PIXVIS] = GINT_TO_POINTER(TRUE); + row[COL_BTNVIS] = GINT_TO_POINTER(FALSE); + break; + case P_COMMENT: + row[COL_PIXBUF] = (gchar *) xpm_void; + row[COL_PIXVIS] = GINT_TO_POINTER(FALSE); + row[COL_BTNVIS] = GINT_TO_POINTER(FALSE); + break; + default: + row[COL_PIXBUF] = (gchar *) xpm_void; + row[COL_PIXVIS] = GINT_TO_POINTER(FALSE); + row[COL_BTNVIS] = GINT_TO_POINTER(TRUE); + break; + } + + if (!sym) + return row; + row[COL_NAME] = g_strdup(sym->name); + + sym_calc_value(sym); + sym->flags &= ~SYMBOL_CHANGED; + + if (sym_is_choice(sym)) { // parse childs for getting final value + struct menu *child; + struct symbol *def_sym = sym_get_choice_value(sym); + struct menu *def_menu = NULL; + + row[COL_BTNVIS] = GINT_TO_POINTER(FALSE); + + for (child = menu->list; child; child = child->next) { + if (menu_is_visible(child) + && child->sym == def_sym) + def_menu = child; + } + + if (def_menu) + row[COL_VALUE] = + g_strdup(_(menu_get_prompt(def_menu))); + } + if (sym->flags & SYMBOL_CHOICEVAL) + row[COL_BTNRAD] = GINT_TO_POINTER(TRUE); + + stype = sym_get_type(sym); + switch (stype) { + case S_BOOLEAN: + if (GPOINTER_TO_INT(row[COL_PIXVIS]) == FALSE) + row[COL_BTNVIS] = GINT_TO_POINTER(TRUE); + if (sym_is_choice(sym)) + break; + /* fall through */ + case S_TRISTATE: + val = sym_get_tristate_value(sym); + switch (val) { + case no: + row[COL_NO] = g_strdup("N"); + row[COL_VALUE] = g_strdup("N"); + row[COL_BTNACT] = GINT_TO_POINTER(FALSE); + row[COL_BTNINC] = GINT_TO_POINTER(FALSE); + break; + case mod: + row[COL_MOD] = g_strdup("M"); + row[COL_VALUE] = g_strdup("M"); + row[COL_BTNINC] = GINT_TO_POINTER(TRUE); + break; + case yes: + row[COL_YES] = g_strdup("Y"); + row[COL_VALUE] = g_strdup("Y"); + row[COL_BTNACT] = GINT_TO_POINTER(TRUE); + row[COL_BTNINC] = GINT_TO_POINTER(FALSE); + break; + } + + if (val != no && sym_tristate_within_range(sym, no)) + row[COL_NO] = g_strdup("_"); + if (val != mod && sym_tristate_within_range(sym, mod)) + row[COL_MOD] = g_strdup("_"); + if (val != yes && sym_tristate_within_range(sym, yes)) + row[COL_YES] = g_strdup("_"); + break; + case S_INT: + case S_HEX: + case S_STRING: + def = sym_get_string_value(sym); + row[COL_VALUE] = g_strdup(def); + row[COL_EDIT] = GINT_TO_POINTER(TRUE); + row[COL_BTNVIS] = GINT_TO_POINTER(FALSE); + break; + } + + return row; +} + + +/* Set the node content with a row of strings */ +static void set_node(GtkTreeIter * node, struct menu *menu, gchar ** row) +{ + GdkColor color; + gboolean success; + GdkPixbuf *pix; + + pix = gdk_pixbuf_new_from_xpm_data((const char **) + row[COL_PIXBUF]); + + gdk_color_parse(row[COL_COLOR], &color); + gdk_colormap_alloc_colors(gdk_colormap_get_system(), &color, 1, + FALSE, FALSE, &success); + + gtk_tree_store_set(tree, node, + COL_OPTION, row[COL_OPTION], + COL_NAME, row[COL_NAME], + COL_NO, row[COL_NO], + COL_MOD, row[COL_MOD], + COL_YES, row[COL_YES], + COL_VALUE, row[COL_VALUE], + COL_MENU, (gpointer) menu, + COL_COLOR, &color, + COL_EDIT, GPOINTER_TO_INT(row[COL_EDIT]), + COL_PIXBUF, pix, + COL_PIXVIS, GPOINTER_TO_INT(row[COL_PIXVIS]), + COL_BTNVIS, GPOINTER_TO_INT(row[COL_BTNVIS]), + COL_BTNACT, GPOINTER_TO_INT(row[COL_BTNACT]), + COL_BTNINC, GPOINTER_TO_INT(row[COL_BTNINC]), + COL_BTNRAD, GPOINTER_TO_INT(row[COL_BTNRAD]), + -1); + + g_object_unref(pix); +} + + +/* Add a node to the tree */ +static void place_node(struct menu *menu, char **row) +{ + GtkTreeIter *parent = parents[indent - 1]; + GtkTreeIter *node = parents[indent]; + + gtk_tree_store_append(tree, node, parent); + set_node(node, menu, row); +} + + +/* Find a node in the GTK+ tree */ +static GtkTreeIter found; + +/* + * Find a menu in the GtkTree starting at parent. + */ +GtkTreeIter *gtktree_iter_find_node(GtkTreeIter * parent, + struct menu *tofind) +{ + GtkTreeIter iter; + GtkTreeIter *child = &iter; + gboolean valid; + GtkTreeIter *ret; + + valid = gtk_tree_model_iter_children(model2, child, parent); + while (valid) { + struct menu *menu; + + gtk_tree_model_get(model2, child, 6, &menu, -1); + + if (menu == tofind) { + memcpy(&found, child, sizeof(GtkTreeIter)); + return &found; + } + + ret = gtktree_iter_find_node(child, tofind); + if (ret) + return ret; + + valid = gtk_tree_model_iter_next(model2, child); + } + + return NULL; +} + + +/* + * Update the tree by adding/removing entries + * Does not change other nodes + */ +static void update_tree(struct menu *src, GtkTreeIter * dst) +{ + struct menu *child1; + GtkTreeIter iter, tmp; + GtkTreeIter *child2 = &iter; + gboolean valid; + GtkTreeIter *sibling; + struct symbol *sym; + struct menu *menu1, *menu2; + + if (src == &rootmenu) + indent = 1; + + valid = gtk_tree_model_iter_children(model2, child2, dst); + for (child1 = src->list; child1; child1 = child1->next) { + + sym = child1->sym; + + reparse: + menu1 = child1; + if (valid) + gtk_tree_model_get(model2, child2, COL_MENU, + &menu2, -1); + else + menu2 = NULL; // force adding of a first child + +#ifdef DEBUG + printf("%*c%s | %s\n", indent, ' ', + menu1 ? menu_get_prompt(menu1) : "nil", + menu2 ? menu_get_prompt(menu2) : "nil"); +#endif + + if ((opt_mode == OPT_NORMAL && !menu_is_visible(child1)) || + (opt_mode == OPT_PROMPT && !menu_has_prompt(child1)) || + (opt_mode == OPT_ALL && !menu_get_prompt(child1))) { + + /* remove node */ + if (gtktree_iter_find_node(dst, menu1) != NULL) { + memcpy(&tmp, child2, sizeof(GtkTreeIter)); + valid = gtk_tree_model_iter_next(model2, + child2); + gtk_tree_store_remove(tree2, &tmp); + if (!valid) + return; /* next parent */ + else + goto reparse; /* next child */ + } else + continue; + } + + if (menu1 != menu2) { + if (gtktree_iter_find_node(dst, menu1) == NULL) { // add node + if (!valid && !menu2) + sibling = NULL; + else + sibling = child2; + gtk_tree_store_insert_before(tree2, + child2, + dst, sibling); + set_node(child2, menu1, fill_row(menu1)); + if (menu2 == NULL) + valid = TRUE; + } else { // remove node + memcpy(&tmp, child2, sizeof(GtkTreeIter)); + valid = gtk_tree_model_iter_next(model2, + child2); + gtk_tree_store_remove(tree2, &tmp); + if (!valid) + return; // next parent + else + goto reparse; // next child + } + } else if (sym && (sym->flags & SYMBOL_CHANGED)) { + set_node(child2, menu1, fill_row(menu1)); + } + + indent++; + update_tree(child1, child2); + indent--; + + valid = gtk_tree_model_iter_next(model2, child2); + } +} + + +/* Display the whole tree (single/split/full view) */ +static void display_tree(struct menu *menu) +{ + struct symbol *sym; + struct property *prop; + struct menu *child; + enum prop_type ptype; + + if (menu == &rootmenu) { + indent = 1; + current = &rootmenu; + } + + for (child = menu->list; child; child = child->next) { + prop = child->prompt; + sym = child->sym; + ptype = prop ? prop->type : P_UNKNOWN; + + if (sym) + sym->flags &= ~SYMBOL_CHANGED; + + if ((view_mode == SPLIT_VIEW) + && !(child->flags & MENU_ROOT) && (tree == tree1)) + continue; + + if ((view_mode == SPLIT_VIEW) && (child->flags & MENU_ROOT) + && (tree == tree2)) + continue; + + if ((opt_mode == OPT_NORMAL && menu_is_visible(child)) || + (opt_mode == OPT_PROMPT && menu_has_prompt(child)) || + (opt_mode == OPT_ALL && menu_get_prompt(child))) + place_node(child, fill_row(child)); +#ifdef DEBUG + printf("%*c%s: ", indent, ' ', menu_get_prompt(child)); + printf("%s", child->flags & MENU_ROOT ? "rootmenu | " : ""); + printf("%s", prop_get_type_name(ptype)); + printf(" | "); + if (sym) { + printf("%s", sym_type_name(sym->type)); + printf(" | "); + printf("%s", dbg_sym_flags(sym->flags)); + printf("\n"); + } else + printf("\n"); +#endif + if ((view_mode != FULL_VIEW) && (ptype == P_MENU) + && (tree == tree2)) + continue; +/* + if (((menu != &rootmenu) && !(menu->flags & MENU_ROOT)) + || (view_mode == FULL_VIEW) + || (view_mode == SPLIT_VIEW))*/ + + /* Change paned position if the view is not in 'split mode' */ + if (view_mode == SINGLE_VIEW || view_mode == FULL_VIEW) { + gtk_paned_set_position(GTK_PANED(hpaned), 0); + } + + if (((view_mode == SINGLE_VIEW) && (menu->flags & MENU_ROOT)) + || (view_mode == FULL_VIEW) + || (view_mode == SPLIT_VIEW)) { + indent++; + display_tree(child); + indent--; + } + } +} + +/* Display a part of the tree starting at current node (single/split view) */ +static void display_tree_part(void) +{ + if (tree2) + gtk_tree_store_clear(tree2); + if (view_mode == SINGLE_VIEW) + display_tree(current); + else if (view_mode == SPLIT_VIEW) + display_tree(browsed); + gtk_tree_view_expand_all(GTK_TREE_VIEW(tree2_w)); +} + +/* Display the list in the left frame (split view) */ +static void display_list(void) +{ + if (tree1) + gtk_tree_store_clear(tree1); + + tree = tree1; + display_tree(&rootmenu); + gtk_tree_view_expand_all(GTK_TREE_VIEW(tree1_w)); + tree = tree2; +} + +void fixup_rootmenu(struct menu *menu) +{ + struct menu *child; + static int menu_cnt = 0; + + menu->flags |= MENU_ROOT; + for (child = menu->list; child; child = child->next) { + if (child->prompt && child->prompt->type == P_MENU) { + menu_cnt++; + fixup_rootmenu(child); + menu_cnt--; + } else if (!menu_cnt) + fixup_rootmenu(child); + } +} + + +/* Main */ +int main(int ac, char *av[]) +{ + const char *name; +#if 0 + char *env; +#endif + gchar *glade_file = GUI_PATH; + + bindtextdomain(PACKAGE, LOCALEDIR); + bind_textdomain_codeset(PACKAGE, "UTF-8"); + textdomain(PACKAGE); + + /* GTK stuffs */ + gtk_set_locale(); + gtk_init(&ac, &av); + glade_init(); + + //add_pixmap_directory (PACKAGE_DATA_DIR "/" PACKAGE "/pixmaps"); + //add_pixmap_directory (PACKAGE_SOURCE_DIR "/pixmaps"); + +#if 0 + /* Determine GUI path */ + env = getenv(SRCTREE); + if (env) + glade_file = g_strconcat(env, "/scripts/kconfig/gconf.glade", NULL); + else if (av[0][0] == '/') + glade_file = g_strconcat(av[0], ".glade", NULL); + else + glade_file = g_strconcat(g_get_current_dir(), "/", av[0], ".glade", NULL); +#endif + + /* Conf stuffs */ + if (ac > 1 && av[1][0] == '-') { + switch (av[1][1]) { + case 'a': + //showAll = 1; + break; + case 'h': + case '?': + printf("%s \n", av[0]); + exit(0); + } + name = av[2]; + } else + name = av[1]; + + conf_parse(name); + fixup_rootmenu(&rootmenu); + conf_read(NULL); + + /* Load the interface and connect signals */ + init_main_window(glade_file); + init_tree_model(); + init_left_tree(); + init_right_tree(); + + switch (view_mode) { + case SINGLE_VIEW: + display_tree_part(); + break; + case SPLIT_VIEW: + display_list(); + break; + case FULL_VIEW: + display_tree(&rootmenu); + break; + } + + gtk_main(); + + return 0; +} + +static void conf_changed(void) +{ + bool changed = conf_get_changed(); + gtk_widget_set_sensitive(save_btn, changed); + gtk_widget_set_sensitive(save_menu_item, changed); +} diff --git a/misc/tools/kconfig-frontends/frontends/gconf/gconf.c.patch b/misc/tools/kconfig-frontends/frontends/gconf/gconf.c.patch new file mode 100644 index 0000000000..fbd898010d --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/gconf/gconf.c.patch @@ -0,0 +1,40 @@ +diff --git a/frontends/gconf/gconf.c b/frontends/gconf/gconf.c +--- a/frontends/gconf/gconf.c ++++ b/frontends/gconf/gconf.c +@@ -11,7 +11,7 @@ + #endif + + #include "lkc.h" +-#include "images.c" ++#include "images.h" + + #include + #include +@@ -1468,8 +1468,10 @@ + int main(int ac, char *av[]) + { + const char *name; ++#if 0 + char *env; ++#endif +- gchar *glade_file; ++ gchar *glade_file = GUI_PATH; + + bindtextdomain(PACKAGE, LOCALEDIR); + bind_textdomain_codeset(PACKAGE, "UTF-8"); +@@ -1483,6 +1485,7 @@ + //add_pixmap_directory (PACKAGE_DATA_DIR "/" PACKAGE "/pixmaps"); + //add_pixmap_directory (PACKAGE_SOURCE_DIR "/pixmaps"); + ++#if 0 + /* Determine GUI path */ + env = getenv(SRCTREE); + if (env) +@@ -1491,6 +1494,7 @@ + glade_file = g_strconcat(av[0], ".glade", NULL); + else + glade_file = g_strconcat(g_get_current_dir(), "/", av[0], ".glade", NULL); ++#endif + + /* Conf stuffs */ + if (ac > 1 && av[1][0] == '-') { diff --git a/misc/tools/kconfig-frontends/frontends/gconf/gconf.glade b/misc/tools/kconfig-frontends/frontends/gconf/gconf.glade new file mode 100644 index 0000000000..aa483cb327 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/gconf/gconf.glade @@ -0,0 +1,661 @@ + + + + + + True + Gtk Kernel Configurator + GTK_WINDOW_TOPLEVEL + GTK_WIN_POS_NONE + False + 640 + 480 + True + False + True + False + False + GDK_WINDOW_TYPE_HINT_NORMAL + GDK_GRAVITY_NORTH_WEST + + + + + + + True + False + 0 + + + + True + + + + True + _File + True + + + + + + + True + Load a config file + _Load + True + + + + + + True + gtk-open + 1 + 0.5 + 0.5 + 0 + 0 + + + + + + + + True + Save the config in .config + _Save + True + + + + + + True + gtk-save + 1 + 0.5 + 0.5 + 0 + 0 + + + + + + + + True + Save the config in a file + Save _as + True + + + + + True + gtk-save-as + 1 + 0.5 + 0.5 + 0 + 0 + + + + + + + + True + + + + + + True + _Quit + True + + + + + + True + gtk-quit + 1 + 0.5 + 0.5 + 0 + 0 + + + + + + + + + + + + True + _Options + True + + + + + + + True + Show name + Show _name + True + False + + + + + + + True + Show range (Y/M/N) + Show _range + True + False + + + + + + + True + Show value of the option + Show _data + True + False + + + + + + + True + + + + + + True + Show normal options + Show normal options + True + True + + + + + + + True + Show all options + Show all _options + True + False + set_option_mode1 + + + + + + + True + Show all options with prompts + Show all prompt options + True + False + set_option_mode1 + + + + + + + + + + + + True + _Help + True + + + + + + + True + _Introduction + True + + + + + + True + gtk-dialog-question + 1 + 0.5 + 0.5 + 0 + 0 + + + + + + + + True + _About + True + + + + + + True + gtk-properties + 1 + 0.5 + 0.5 + 0 + 0 + + + + + + + + True + _License + True + + + + + True + gtk-justify-fill + 1 + 0.5 + 0.5 + 0 + 0 + + + + + + + + + + + 0 + False + False + + + + + + True + GTK_SHADOW_OUT + GTK_POS_LEFT + GTK_POS_TOP + + + + True + GTK_ORIENTATION_HORIZONTAL + GTK_TOOLBAR_BOTH + True + True + + + + True + Goes up of one level (single view) + Back + True + gtk-undo + True + True + False + + + + False + True + + + + + + True + True + True + False + + + + True + + + + + False + False + + + + + + True + Load a config file + Load + True + gtk-open + True + True + False + + + + False + True + + + + + + True + Save a config file + Save + True + gtk-save + True + True + False + + + + False + True + + + + + + True + True + True + False + + + + True + + + + + False + False + + + + + + True + Single view + Single + True + gtk-missing-image + True + True + False + + + + False + True + + + + + + True + Split view + Split + True + gtk-missing-image + True + True + False + + + + False + True + + + + + + True + Full view + Full + True + gtk-missing-image + True + True + False + + + + False + True + + + + + + True + True + True + False + + + + True + + + + + False + False + + + + + + True + Collapse the whole tree in the right frame + Collapse + True + gtk-remove + True + True + False + + + + False + True + + + + + + True + Expand the whole tree in the right frame + Expand + True + gtk-add + True + True + False + + + + False + True + + + + + + + 0 + False + False + + + + + + 1 + True + True + 0 + + + + True + GTK_POLICY_AUTOMATIC + GTK_POLICY_AUTOMATIC + GTK_SHADOW_IN + GTK_CORNER_TOP_LEFT + + + + True + True + True + False + False + False + + + + + + + + True + False + + + + + + True + True + 0 + + + + True + GTK_POLICY_AUTOMATIC + GTK_POLICY_AUTOMATIC + GTK_SHADOW_IN + GTK_CORNER_TOP_LEFT + + + + True + True + True + True + False + False + False + + + + + + + + True + False + + + + + + True + GTK_POLICY_NEVER + GTK_POLICY_AUTOMATIC + GTK_SHADOW_IN + GTK_CORNER_TOP_LEFT + + + + True + True + False + False + True + GTK_JUSTIFY_LEFT + GTK_WRAP_WORD + True + 0 + 0 + 0 + 0 + 0 + 0 + Sorry, no help available for this option yet. + + + + + True + True + + + + + True + True + + + + + 0 + True + True + + + + + + + diff --git a/misc/tools/kconfig-frontends/frontends/mconf/Makefile.am b/misc/tools/kconfig-frontends/frontends/mconf/Makefile.am new file mode 100644 index 0000000000..39bb77b280 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/mconf/Makefile.am @@ -0,0 +1,13 @@ +bin_PROGRAMS = mconf + +mconf_SOURCES = mconf.c +mconf_CPPFLAGS = $(AM_CPPFLAGS) \ + -DCURSES_LOC='"$(CURSES_LOC)"' \ + $(intl_CPPFLAGS) \ + -I$(top_srcdir)/libs \ + -I$(top_srcdir)/libs/parser +mconf_CFLAGS = $(AM_CFLAGS) \ + $(kf_CFLAGS) +mconf_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(top_builddir)/libs/lxdialog/libkconfig-lxdialog.a \ + $(intl_LIBS) $(ncurses_LIBS) $(mconf_EXTRA_LIBS) diff --git a/misc/tools/kconfig-frontends/frontends/mconf/Makefile.in b/misc/tools/kconfig-frontends/frontends/mconf/Makefile.in new file mode 100644 index 0000000000..7b877ff484 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/mconf/Makefile.in @@ -0,0 +1,606 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ + +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +bin_PROGRAMS = mconf$(EXEEXT) +subdir = frontends/mconf +DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +am__installdirs = "$(DESTDIR)$(bindir)" +PROGRAMS = $(bin_PROGRAMS) +am_mconf_OBJECTS = mconf-mconf.$(OBJEXT) +mconf_OBJECTS = $(am_mconf_OBJECTS) +am__DEPENDENCIES_1 = +mconf_DEPENDENCIES = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(top_builddir)/libs/lxdialog/libkconfig-lxdialog.a \ + $(am__DEPENDENCIES_1) $(am__DEPENDENCIES_1) \ + $(am__DEPENDENCIES_1) +AM_V_lt = $(am__v_lt_$(V)) +am__v_lt_ = $(am__v_lt_$(AM_DEFAULT_VERBOSITY)) +am__v_lt_0 = --silent +mconf_LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(mconf_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +DEFAULT_INCLUDES = -I.@am__isrc@ -I$(top_builddir)/scripts/.autostuff +depcomp = $(SHELL) $(top_srcdir)/scripts/.autostuff/scripts/depcomp +am__depfiles_maybe = depfiles +am__mv = mv -f +COMPILE = $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) \ + $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) +LTCOMPILE = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) \ + $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) $(CPPFLAGS) \ + $(AM_CFLAGS) $(CFLAGS) +AM_V_CC = $(am__v_CC_$(V)) +am__v_CC_ = $(am__v_CC_$(AM_DEFAULT_VERBOSITY)) +am__v_CC_0 = @echo " CC " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +CCLD = $(CC) +LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(AM_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +AM_V_CCLD = $(am__v_CCLD_$(V)) +am__v_CCLD_ = $(am__v_CCLD_$(AM_DEFAULT_VERBOSITY)) +am__v_CCLD_0 = @echo " CCLD " $@; +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +SOURCES = $(mconf_SOURCES) +DIST_SOURCES = $(mconf_SOURCES) +ETAGS = etags +CTAGS = ctags +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +mconf_SOURCES = mconf.c +mconf_CPPFLAGS = $(AM_CPPFLAGS) \ + -DCURSES_LOC='"$(CURSES_LOC)"' \ + $(intl_CPPFLAGS) \ + -I$(top_srcdir)/libs \ + -I$(top_srcdir)/libs/parser + +mconf_CFLAGS = $(AM_CFLAGS) \ + $(kf_CFLAGS) + +mconf_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(top_builddir)/libs/lxdialog/libkconfig-lxdialog.a \ + $(intl_LIBS) $(ncurses_LIBS) $(mconf_EXTRA_LIBS) + +all: all-am + +.SUFFIXES: +.SUFFIXES: .c .lo .o .obj +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign frontends/mconf/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign frontends/mconf/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): +install-binPROGRAMS: $(bin_PROGRAMS) + @$(NORMAL_INSTALL) + test -z "$(bindir)" || $(MKDIR_P) "$(DESTDIR)$(bindir)" + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + for p in $$list; do echo "$$p $$p"; done | \ + sed 's/$(EXEEXT)$$//' | \ + while read p p1; do if test -f $$p || test -f $$p1; \ + then echo "$$p"; echo "$$p"; else :; fi; \ + done | \ + sed -e 'p;s,.*/,,;n;h' -e 's|.*|.|' \ + -e 'p;x;s,.*/,,;s/$(EXEEXT)$$//;$(transform);s/$$/$(EXEEXT)/' | \ + sed 'N;N;N;s,\n, ,g' | \ + $(AWK) 'BEGIN { files["."] = ""; dirs["."] = 1 } \ + { d=$$3; if (dirs[d] != 1) { print "d", d; dirs[d] = 1 } \ + if ($$2 == $$4) files[d] = files[d] " " $$1; \ + else { print "f", $$3 "/" $$4, $$1; } } \ + END { for (d in files) print "f", d, files[d] }' | \ + while read type dir files; do \ + if test "$$dir" = .; then dir=; else dir=/$$dir; fi; \ + test -z "$$files" || { \ + echo " $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files '$(DESTDIR)$(bindir)$$dir'"; \ + $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files "$(DESTDIR)$(bindir)$$dir" || exit $$?; \ + } \ + ; done + +uninstall-binPROGRAMS: + @$(NORMAL_UNINSTALL) + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + files=`for p in $$list; do echo "$$p"; done | \ + sed -e 'h;s,^.*/,,;s/$(EXEEXT)$$//;$(transform)' \ + -e 's/$$/$(EXEEXT)/' `; \ + test -n "$$list" || exit 0; \ + echo " ( cd '$(DESTDIR)$(bindir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(bindir)" && rm -f $$files + +clean-binPROGRAMS: + @list='$(bin_PROGRAMS)'; test -n "$$list" || exit 0; \ + echo " rm -f" $$list; \ + rm -f $$list || exit $$?; \ + test -n "$(EXEEXT)" || exit 0; \ + list=`for p in $$list; do echo "$$p"; done | sed 's/$(EXEEXT)$$//'`; \ + echo " rm -f" $$list; \ + rm -f $$list +mconf$(EXEEXT): $(mconf_OBJECTS) $(mconf_DEPENDENCIES) + @rm -f mconf$(EXEEXT) + $(AM_V_CCLD)$(mconf_LINK) $(mconf_OBJECTS) $(mconf_LDADD) $(LIBS) + +mostlyclean-compile: + -rm -f *.$(OBJEXT) + +distclean-compile: + -rm -f *.tab.c + +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/mconf-mconf.Po@am__quote@ + +.c.o: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c $< + +.c.obj: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ `$(CYGPATH_W) '$<'` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c `$(CYGPATH_W) '$<'` + +.c.lo: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LTCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LTCOMPILE) -c -o $@ $< + +mconf-mconf.o: mconf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(mconf_CPPFLAGS) $(CPPFLAGS) $(mconf_CFLAGS) $(CFLAGS) -MT mconf-mconf.o -MD -MP -MF $(DEPDIR)/mconf-mconf.Tpo -c -o mconf-mconf.o `test -f 'mconf.c' || echo '$(srcdir)/'`mconf.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/mconf-mconf.Tpo $(DEPDIR)/mconf-mconf.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='mconf.c' object='mconf-mconf.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(mconf_CPPFLAGS) $(CPPFLAGS) $(mconf_CFLAGS) $(CFLAGS) -c -o mconf-mconf.o `test -f 'mconf.c' || echo '$(srcdir)/'`mconf.c + +mconf-mconf.obj: mconf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(mconf_CPPFLAGS) $(CPPFLAGS) $(mconf_CFLAGS) $(CFLAGS) -MT mconf-mconf.obj -MD -MP -MF $(DEPDIR)/mconf-mconf.Tpo -c -o mconf-mconf.obj `if test -f 'mconf.c'; then $(CYGPATH_W) 'mconf.c'; else $(CYGPATH_W) '$(srcdir)/mconf.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/mconf-mconf.Tpo $(DEPDIR)/mconf-mconf.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='mconf.c' object='mconf-mconf.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(mconf_CPPFLAGS) $(CPPFLAGS) $(mconf_CFLAGS) $(CFLAGS) -c -o mconf-mconf.obj `if test -f 'mconf.c'; then $(CYGPATH_W) 'mconf.c'; else $(CYGPATH_W) '$(srcdir)/mconf.c'; fi` + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-am +all-am: Makefile $(PROGRAMS) +installdirs: + for dir in "$(DESTDIR)$(bindir)"; do \ + test -z "$$dir" || $(MKDIR_P) "$$dir"; \ + done +install: install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-am + +clean-am: clean-binPROGRAMS clean-generic clean-libtool mostlyclean-am + +distclean: distclean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +distclean-am: clean-am distclean-compile distclean-generic \ + distclean-tags + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: install-binPROGRAMS + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: uninstall-binPROGRAMS + +.MAKE: install-am install-strip + +.PHONY: CTAGS GTAGS all all-am check check-am clean clean-binPROGRAMS \ + clean-generic clean-libtool ctags distclean distclean-compile \ + distclean-generic distclean-libtool distclean-tags distdir dvi \ + dvi-am html html-am info info-am install install-am \ + install-binPROGRAMS install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-compile mostlyclean-generic mostlyclean-libtool \ + pdf pdf-am ps ps-am tags uninstall uninstall-am \ + uninstall-binPROGRAMS + + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/frontends/mconf/mconf.c b/misc/tools/kconfig-frontends/frontends/mconf/mconf.c new file mode 100644 index 0000000000..f584a281bb --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/mconf/mconf.c @@ -0,0 +1,882 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + * + * Introduced single menu mode (show all sub-menus in one large tree). + * 2002-11-06 Petr Baudis + * + * i18n, 2005, Arnaldo Carvalho de Melo + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "lkc.h" +#include "lxdialog/dialog.h" + +static const char mconf_readme[] = N_( +"Overview\n" +"--------\n" +"This interface let you select features and parameters for the build.\n" +"Features can either be built-in, modularized, or ignored. Parameters\n" +"must be entered in as decimal or hexadecimal numbers or text.\n" +"\n" +"Menu items beginning with following braces represent features that\n" +" [ ] can be built in or removed\n" +" < > can be built in, modularized or removed\n" +" { } can be built in or modularized (selected by other feature)\n" +" - - are selected by other feature,\n" +"while *, M or whitespace inside braces means to build in, build as\n" +"a module or to exclude the feature respectively.\n" +"\n" +"To change any of these features, highlight it with the cursor\n" +"keys and press to build it in, to make it a module or\n" +" to removed it. You may also press the to cycle\n" +"through the available options (ie. Y->N->M->Y).\n" +"\n" +"Some additional keyboard hints:\n" +"\n" +"Menus\n" +"----------\n" +"o Use the Up/Down arrow keys (cursor keys) to highlight the item\n" +" you wish to change or submenu wish to select and press .\n" +" Submenus are designated by \"--->\".\n" +"\n" +" Shortcut: Press the option's highlighted letter (hotkey).\n" +" Pressing a hotkey more than once will sequence\n" +" through all visible items which use that hotkey.\n" +"\n" +" You may also use the and keys to scroll\n" +" unseen options into view.\n" +"\n" +"o To exit a menu use the cursor keys to highlight the button\n" +" and press .\n" +"\n" +" Shortcut: Press or or if there is no hotkey\n" +" using those letters. You may press a single , but\n" +" there is a delayed response which you may find annoying.\n" +"\n" +" Also, the and cursor keys will cycle between and\n" +" \n" +"\n" +"\n" +"Data Entry\n" +"-----------\n" +"o Enter the requested information and press \n" +" If you are entering hexadecimal values, it is not necessary to\n" +" add the '0x' prefix to the entry.\n" +"\n" +"o For help, use the or cursor keys to highlight the help option\n" +" and press . You can try as well.\n" +"\n" +"\n" +"Text Box (Help Window)\n" +"--------\n" +"o Use the cursor keys to scroll up/down/left/right. The VI editor\n" +" keys h,j,k,l function here as do , , and for \n" +" those who are familiar with less and lynx.\n" +"\n" +"o Press , , , or to exit.\n" +"\n" +"\n" +"Alternate Configuration Files\n" +"-----------------------------\n" +"Menuconfig supports the use of alternate configuration files for\n" +"those who, for various reasons, find it necessary to switch\n" +"between different configurations.\n" +"\n" +"At the end of the main menu you will find two options. One is\n" +"for saving the current configuration to a file of your choosing.\n" +"The other option is for loading a previously saved alternate\n" +"configuration.\n" +"\n" +"Even if you don't use alternate configuration files, but you\n" +"find during a Menuconfig session that you have completely messed\n" +"up your settings, you may use the \"Load Alternate...\" option to\n" +"restore your previously saved settings from \".config\" without\n" +"restarting Menuconfig.\n" +"\n" +"Other information\n" +"-----------------\n" +"If you use Menuconfig in an XTERM window make sure you have your\n" +"$TERM variable set to point to a xterm definition which supports color.\n" +"Otherwise, Menuconfig will look rather bad. Menuconfig will not\n" +"display correctly in a RXVT window because rxvt displays only one\n" +"intensity of color, bright.\n" +"\n" +"Menuconfig will display larger menus on screens or xterms which are\n" +"set to display more than the standard 25 row by 80 column geometry.\n" +"In order for this to work, the \"stty size\" command must be able to\n" +"display the screen's current row and column geometry. I STRONGLY\n" +"RECOMMEND that you make sure you do NOT have the shell variables\n" +"LINES and COLUMNS exported into your environment. Some distributions\n" +"export those variables via /etc/profile. Some ncurses programs can\n" +"become confused when those variables (LINES & COLUMNS) don't reflect\n" +"the true screen size.\n" +"\n" +"Optional personality available\n" +"------------------------------\n" +"If you prefer to have all of the options listed in a single menu, rather\n" +"than the default multimenu hierarchy, run the menuconfig with\n" +"MENUCONFIG_MODE environment variable set to single_menu. Example:\n" +"\n" +"make MENUCONFIG_MODE=single_menu menuconfig\n" +"\n" +" will then unroll the appropriate category, or enfold it if it\n" +"is already unrolled.\n" +"\n" +"Note that this mode can eventually be a little more CPU expensive\n" +"(especially with a larger number of unrolled categories) than the\n" +"default mode.\n" +"\n" +"Different color themes available\n" +"--------------------------------\n" +"It is possible to select different color themes using the variable\n" +"MENUCONFIG_COLOR. To select a theme use:\n" +"\n" +"make MENUCONFIG_COLOR= menuconfig\n" +"\n" +"Available themes are\n" +" mono => selects colors suitable for monochrome displays\n" +" blackbg => selects a color scheme with black background\n" +" classic => theme with blue background. The classic look\n" +" bluetitle => a LCD friendly version of classic. (default)\n" +"\n"), +menu_instructions[] = N_( + "Arrow keys navigate the menu. " + " selects submenus --->. " + "Highlighted letters are hotkeys. " + "Pressing includes, excludes, modularizes features. " + "Press to exit, for Help, for Search. " + "Legend: [*] built-in [ ] excluded module < > module capable"), +radiolist_instructions[] = N_( + "Use the arrow keys to navigate this window or " + "press the hotkey of the item you wish to select " + "followed by the . " + "Press for additional information about this option."), +inputbox_instructions_int[] = N_( + "Please enter a decimal value. " + "Fractions will not be accepted. " + "Use the key to move from the input field to the buttons below it."), +inputbox_instructions_hex[] = N_( + "Please enter a hexadecimal value. " + "Use the key to move from the input field to the buttons below it."), +inputbox_instructions_string[] = N_( + "Please enter a string value. " + "Use the key to move from the input field to the buttons below it."), +setmod_text[] = N_( + "This feature depends on another which has been configured as a module.\n" + "As a result, this feature will be built as a module."), +load_config_text[] = N_( + "Enter the name of the configuration file you wish to load. " + "Accept the name shown to restore the configuration you " + "last retrieved. Leave blank to abort."), +load_config_help[] = N_( + "\n" + "For various reasons, one may wish to keep several different\n" + "configurations available on a single machine.\n" + "\n" + "If you have saved a previous configuration in a file other than the\n" + "default one, entering its name here will allow you to modify that\n" + "configuration.\n" + "\n" + "If you are uncertain, then you have probably never used alternate\n" + "configuration files. You should therefore leave this blank to abort.\n"), +save_config_text[] = N_( + "Enter a filename to which this configuration should be saved " + "as an alternate. Leave blank to abort."), +save_config_help[] = N_( + "\n" + "For various reasons, one may wish to keep different configurations\n" + "available on a single machine.\n" + "\n" + "Entering a file name here will allow you to later retrieve, modify\n" + "and use the current configuration as an alternate to whatever\n" + "configuration options you have selected at that time.\n" + "\n" + "If you are uncertain what all this means then you should probably\n" + "leave this blank.\n"), +search_help[] = N_( + "\n" + "Search for symbols and display their relations.\n" + "Regular expressions are allowed.\n" + "Example: search for \"^FOO\"\n" + "Result:\n" + "-----------------------------------------------------------------\n" + "Symbol: FOO [=m]\n" + "Prompt: Foo bus is used to drive the bar HW\n" + "Defined at drivers/pci/Kconfig:47\n" + "Depends on: X86_LOCAL_APIC && X86_IO_APIC || IA64\n" + "Location:\n" + " -> Bus options (PCI, PCMCIA, EISA, ISA)\n" + " -> PCI support (PCI [=y])\n" + " -> PCI access mode ( [=y])\n" + "Selects: LIBCRC32\n" + "Selected by: BAR\n" + "-----------------------------------------------------------------\n" + "o The line 'Prompt:' shows the text used in the menu structure for\n" + " this symbol\n" + "o The 'Defined at' line tell at what file / line number the symbol\n" + " is defined\n" + "o The 'Depends on:' line tell what symbols needs to be defined for\n" + " this symbol to be visible in the menu (selectable)\n" + "o The 'Location:' lines tell where in the menu structure this symbol\n" + " is located\n" + " A location followed by a [=y] indicate that this is a selectable\n" + " menu item - and current value is displayed inside brackets.\n" + "o The 'Selects:' line tell what symbol will be automatically\n" + " selected if this symbol is selected (y or m)\n" + "o The 'Selected by' line tell what symbol has selected this symbol\n" + "\n" + "Only relevant lines are shown.\n" + "\n\n" + "Search examples:\n" + "Examples: USB => find all symbols containing USB\n" + " ^USB => find all symbols starting with USB\n" + " USB$ => find all symbols ending with USB\n" + "\n"); + +static int indent; +static struct menu *current_menu; +static int child_count; +static int single_menu_mode; +static int show_all_options; +static int saved_x, saved_y; + +static void conf(struct menu *menu); +static void conf_choice(struct menu *menu); +static void conf_string(struct menu *menu); +static void conf_load(void); +static void conf_save(void); +static void show_textbox(const char *title, const char *text, int r, int c); +static void show_helptext(const char *title, const char *text); +static void show_help(struct menu *menu); + +static char filename[PATH_MAX+1]; +static void set_config_filename(const char *config_filename) +{ + static char menu_backtitle[PATH_MAX+128]; + int size; + + size = snprintf(menu_backtitle, sizeof(menu_backtitle), + "%s - %s", config_filename, rootmenu.prompt->text); + if (size >= sizeof(menu_backtitle)) + menu_backtitle[sizeof(menu_backtitle)-1] = '\0'; + set_dialog_backtitle(menu_backtitle); + + size = snprintf(filename, sizeof(filename), "%s", config_filename); + if (size >= sizeof(filename)) + filename[sizeof(filename)-1] = '\0'; +} + + +static void search_conf(void) +{ + struct symbol **sym_arr; + struct gstr res; + char *dialog_input; + int dres; +again: + dialog_clear(); + dres = dialog_inputbox(_("Search Configuration Parameter"), + _("Enter " CONFIG_ " (sub)string to search for " + "(with or without \"" CONFIG_ "\")"), + 10, 75, ""); + switch (dres) { + case 0: + break; + case 1: + show_helptext(_("Search Configuration"), search_help); + goto again; + default: + return; + } + + /* strip the prefix if necessary */ + dialog_input = dialog_input_result; + if (strncasecmp(dialog_input_result, CONFIG_, strlen(CONFIG_)) == 0) + dialog_input += strlen(CONFIG_); + + sym_arr = sym_re_search(dialog_input); + res = get_relations_str(sym_arr); + free(sym_arr); + show_textbox(_("Search Results"), str_get(&res), 0, 0); + str_free(&res); +} + +static void build_conf(struct menu *menu) +{ + struct symbol *sym; + struct property *prop; + struct menu *child; + int type, tmp, doint = 2; + tristate val; + char ch; + bool visible; + + /* + * note: menu_is_visible() has side effect that it will + * recalc the value of the symbol. + */ + visible = menu_is_visible(menu); + if (show_all_options && !menu_has_prompt(menu)) + return; + else if (!show_all_options && !visible) + return; + + sym = menu->sym; + prop = menu->prompt; + if (!sym) { + if (prop && menu != current_menu) { + const char *prompt = menu_get_prompt(menu); + switch (prop->type) { + case P_MENU: + child_count++; + prompt = _(prompt); + if (single_menu_mode) { + item_make("%s%*c%s", + menu->data ? "-->" : "++>", + indent + 1, ' ', prompt); + } else + item_make(" %*c%s --->", indent + 1, ' ', prompt); + + item_set_tag('m'); + item_set_data(menu); + if (single_menu_mode && menu->data) + goto conf_childs; + return; + case P_COMMENT: + if (prompt) { + child_count++; + item_make(" %*c*** %s ***", indent + 1, ' ', _(prompt)); + item_set_tag(':'); + item_set_data(menu); + } + break; + default: + if (prompt) { + child_count++; + item_make("---%*c%s", indent + 1, ' ', _(prompt)); + item_set_tag(':'); + item_set_data(menu); + } + } + } else + doint = 0; + goto conf_childs; + } + + type = sym_get_type(sym); + if (sym_is_choice(sym)) { + struct symbol *def_sym = sym_get_choice_value(sym); + struct menu *def_menu = NULL; + + child_count++; + for (child = menu->list; child; child = child->next) { + if (menu_is_visible(child) && child->sym == def_sym) + def_menu = child; + } + + val = sym_get_tristate_value(sym); + if (sym_is_changable(sym)) { + switch (type) { + case S_BOOLEAN: + item_make("[%c]", val == no ? ' ' : '*'); + break; + case S_TRISTATE: + switch (val) { + case yes: ch = '*'; break; + case mod: ch = 'M'; break; + default: ch = ' '; break; + } + item_make("<%c>", ch); + break; + } + item_set_tag('t'); + item_set_data(menu); + } else { + item_make(" "); + item_set_tag(def_menu ? 't' : ':'); + item_set_data(menu); + } + + item_add_str("%*c%s", indent + 1, ' ', _(menu_get_prompt(menu))); + if (val == yes) { + if (def_menu) { + item_add_str(" (%s)", _(menu_get_prompt(def_menu))); + item_add_str(" --->"); + if (def_menu->list) { + indent += 2; + build_conf(def_menu); + indent -= 2; + } + } + return; + } + } else { + if (menu == current_menu) { + item_make("---%*c%s", indent + 1, ' ', _(menu_get_prompt(menu))); + item_set_tag(':'); + item_set_data(menu); + goto conf_childs; + } + child_count++; + val = sym_get_tristate_value(sym); + if (sym_is_choice_value(sym) && val == yes) { + item_make(" "); + item_set_tag(':'); + item_set_data(menu); + } else { + switch (type) { + case S_BOOLEAN: + if (sym_is_changable(sym)) + item_make("[%c]", val == no ? ' ' : '*'); + else + item_make("-%c-", val == no ? ' ' : '*'); + item_set_tag('t'); + item_set_data(menu); + break; + case S_TRISTATE: + switch (val) { + case yes: ch = '*'; break; + case mod: ch = 'M'; break; + default: ch = ' '; break; + } + if (sym_is_changable(sym)) { + if (sym->rev_dep.tri == mod) + item_make("{%c}", ch); + else + item_make("<%c>", ch); + } else + item_make("-%c-", ch); + item_set_tag('t'); + item_set_data(menu); + break; + default: + tmp = 2 + strlen(sym_get_string_value(sym)); /* () = 2 */ + item_make("(%s)", sym_get_string_value(sym)); + tmp = indent - tmp + 4; + if (tmp < 0) + tmp = 0; + item_add_str("%*c%s%s", tmp, ' ', _(menu_get_prompt(menu)), + (sym_has_value(sym) || !sym_is_changable(sym)) ? + "" : _(" (NEW)")); + item_set_tag('s'); + item_set_data(menu); + goto conf_childs; + } + } + item_add_str("%*c%s%s", indent + 1, ' ', _(menu_get_prompt(menu)), + (sym_has_value(sym) || !sym_is_changable(sym)) ? + "" : _(" (NEW)")); + if (menu->prompt->type == P_MENU) { + item_add_str(" --->"); + return; + } + } + +conf_childs: + indent += doint; + for (child = menu->list; child; child = child->next) + build_conf(child); + indent -= doint; +} + +static void conf(struct menu *menu) +{ + struct menu *submenu; + const char *prompt = menu_get_prompt(menu); + struct symbol *sym; + struct menu *active_menu = NULL; + int res; + int s_scroll = 0; + + while (1) { + item_reset(); + current_menu = menu; + build_conf(menu); + if (!child_count) + break; + if (menu == &rootmenu) { + item_make("--- "); + item_set_tag(':'); + item_make(_(" Load an Alternate Configuration File")); + item_set_tag('L'); + item_make(_(" Save an Alternate Configuration File")); + item_set_tag('S'); + } + dialog_clear(); + res = dialog_menu(prompt ? _(prompt) : _("Main Menu"), + _(menu_instructions), + active_menu, &s_scroll); + if (res == 1 || res == KEY_ESC || res == -ERRDISPLAYTOOSMALL) + break; + if (!item_activate_selected()) + continue; + if (!item_tag()) + continue; + + submenu = item_data(); + active_menu = item_data(); + if (submenu) + sym = submenu->sym; + else + sym = NULL; + + switch (res) { + case 0: + switch (item_tag()) { + case 'm': + if (single_menu_mode) + submenu->data = (void *) (long) !submenu->data; + else + conf(submenu); + break; + case 't': + if (sym_is_choice(sym) && sym_get_tristate_value(sym) == yes) + conf_choice(submenu); + else if (submenu->prompt->type == P_MENU) + conf(submenu); + break; + case 's': + conf_string(submenu); + break; + case 'L': + conf_load(); + break; + case 'S': + conf_save(); + break; + } + break; + case 2: + if (sym) + show_help(submenu); + else + show_helptext(_("README"), _(mconf_readme)); + break; + case 3: + if (item_is_tag('t')) { + if (sym_set_tristate_value(sym, yes)) + break; + if (sym_set_tristate_value(sym, mod)) + show_textbox(NULL, setmod_text, 6, 74); + } + break; + case 4: + if (item_is_tag('t')) + sym_set_tristate_value(sym, no); + break; + case 5: + if (item_is_tag('t')) + sym_set_tristate_value(sym, mod); + break; + case 6: + if (item_is_tag('t')) + sym_toggle_tristate_value(sym); + else if (item_is_tag('m')) + conf(submenu); + break; + case 7: + search_conf(); + break; + case 8: + show_all_options = !show_all_options; + break; + } + } +} + +static void show_textbox(const char *title, const char *text, int r, int c) +{ + dialog_clear(); + dialog_textbox(title, text, r, c); +} + +static void show_helptext(const char *title, const char *text) +{ + show_textbox(title, text, 0, 0); +} + +static void show_help(struct menu *menu) +{ + struct gstr help = str_new(); + + help.max_width = getmaxx(stdscr) - 10; + menu_get_ext_help(menu, &help); + + show_helptext(_(menu_get_prompt(menu)), str_get(&help)); + str_free(&help); +} + +static void conf_choice(struct menu *menu) +{ + const char *prompt = _(menu_get_prompt(menu)); + struct menu *child; + struct symbol *active; + + active = sym_get_choice_value(menu->sym); + while (1) { + int res; + int selected; + item_reset(); + + current_menu = menu; + for (child = menu->list; child; child = child->next) { + if (!menu_is_visible(child)) + continue; + if (child->sym) + item_make("%s", _(menu_get_prompt(child))); + else { + item_make("*** %s ***", _(menu_get_prompt(child))); + item_set_tag(':'); + } + item_set_data(child); + if (child->sym == active) + item_set_selected(1); + if (child->sym == sym_get_choice_value(menu->sym)) + item_set_tag('X'); + } + dialog_clear(); + res = dialog_checklist(prompt ? _(prompt) : _("Main Menu"), + _(radiolist_instructions), + 15, 70, 6); + selected = item_activate_selected(); + switch (res) { + case 0: + if (selected) { + child = item_data(); + if (!child->sym) + break; + + sym_set_tristate_value(child->sym, yes); + } + return; + case 1: + if (selected) { + child = item_data(); + show_help(child); + active = child->sym; + } else + show_help(menu); + break; + case KEY_ESC: + return; + case -ERRDISPLAYTOOSMALL: + return; + } + } +} + +static void conf_string(struct menu *menu) +{ + const char *prompt = menu_get_prompt(menu); + + while (1) { + int res; + const char *heading; + + switch (sym_get_type(menu->sym)) { + case S_INT: + heading = _(inputbox_instructions_int); + break; + case S_HEX: + heading = _(inputbox_instructions_hex); + break; + case S_STRING: + heading = _(inputbox_instructions_string); + break; + default: + heading = _("Internal mconf error!"); + } + dialog_clear(); + res = dialog_inputbox(prompt ? _(prompt) : _("Main Menu"), + heading, 10, 75, + sym_get_string_value(menu->sym)); + switch (res) { + case 0: + if (sym_set_string_value(menu->sym, dialog_input_result)) + return; + show_textbox(NULL, _("You have made an invalid entry."), 5, 43); + break; + case 1: + show_help(menu); + break; + case KEY_ESC: + return; + } + } +} + +static void conf_load(void) +{ + + while (1) { + int res; + dialog_clear(); + res = dialog_inputbox(NULL, load_config_text, + 11, 55, filename); + switch(res) { + case 0: + if (!dialog_input_result[0]) + return; + if (!conf_read(dialog_input_result)) { + set_config_filename(dialog_input_result); + sym_set_change_count(1); + return; + } + show_textbox(NULL, _("File does not exist!"), 5, 38); + break; + case 1: + show_helptext(_("Load Alternate Configuration"), load_config_help); + break; + case KEY_ESC: + return; + } + } +} + +static void conf_save(void) +{ + while (1) { + int res; + dialog_clear(); + res = dialog_inputbox(NULL, save_config_text, + 11, 55, filename); + switch(res) { + case 0: + if (!dialog_input_result[0]) + return; + if (!conf_write(dialog_input_result)) { + set_config_filename(dialog_input_result); + return; + } + show_textbox(NULL, _("Can't create file! Probably a nonexistent directory."), 5, 60); + break; + case 1: + show_helptext(_("Save Alternate Configuration"), save_config_help); + break; + case KEY_ESC: + return; + } + } +} + +static int handle_exit(void) +{ + int res; + + dialog_clear(); + if (conf_get_changed()) + res = dialog_yesno(NULL, + _("Do you wish to save your new configuration ?\n" + " to continue."), + 6, 60); + else + res = -1; + + end_dialog(saved_x, saved_y); + + switch (res) { + case 0: + if (conf_write(filename)) { + fprintf(stderr, _("\n\n" + "Error while writing of the configuration.\n" + "Your configuration changes were NOT saved." + "\n\n")); + return 1; + } + /* fall through */ + case -1: + printf(_("\n\n" + "*** End of the configuration.\n" + "*** Execute 'make' to start the build or try 'make help'." + "\n\n")); + res = 0; + break; + default: + fprintf(stderr, _("\n\n" + "Your configuration changes were NOT saved." + "\n\n")); + if (res != KEY_ESC) + res = 0; + } + + return res; +} + +static void sig_handler(int signo) +{ + exit(handle_exit()); +} + +int main(int ac, char **av) +{ + char *mode; + int res; + + setlocale(LC_ALL, ""); + bindtextdomain(PACKAGE, LOCALEDIR); + textdomain(PACKAGE); + + signal(SIGINT, sig_handler); + + conf_parse(av[1]); + conf_read(NULL); + + mode = getenv("MENUCONFIG_MODE"); + if (mode) { + if (!strcasecmp(mode, "single_menu")) + single_menu_mode = 1; + } + + initscr(); + + getyx(stdscr, saved_y, saved_x); + if (init_dialog(NULL)) { + fprintf(stderr, N_("Your display is too small to run Menuconfig!\n")); + fprintf(stderr, N_("It must be at least 19 lines by 80 columns.\n")); + return 1; + } + + set_config_filename(conf_get_configname()); + do { + conf(&rootmenu); + res = handle_exit(); + } while (res == KEY_ESC); + + return res; +} + diff --git a/misc/tools/kconfig-frontends/frontends/nconf/Makefile.am b/misc/tools/kconfig-frontends/frontends/nconf/Makefile.am new file mode 100644 index 0000000000..32096ab37d --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/nconf/Makefile.am @@ -0,0 +1,12 @@ +bin_PROGRAMS = nconf + +nconf_SOURCES = nconf.c nconf.gui.c nconf.h +nconf_CPPFLAGS = $(AM_CPPFLAGS) \ + $(intl_CPPFLAGS) \ + $(ncurses_extra_CPPFLAGS) \ + -I$(top_srcdir)/libs/parser +nconf_CFLAGS = $(AM_CFLAGS) \ + $(kf_CFLAGS) +nconf_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(intl_LIBS) $(ncurses_extra_LIBS) $(ncurses_LIBS) \ + $(nconf_EXTRA_LIBS) diff --git a/misc/tools/kconfig-frontends/frontends/nconf/Makefile.in b/misc/tools/kconfig-frontends/frontends/nconf/Makefile.in new file mode 100644 index 0000000000..c1f7cec55c --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/nconf/Makefile.in @@ -0,0 +1,621 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ + +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +bin_PROGRAMS = nconf$(EXEEXT) +subdir = frontends/nconf +DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +am__installdirs = "$(DESTDIR)$(bindir)" +PROGRAMS = $(bin_PROGRAMS) +am_nconf_OBJECTS = nconf-nconf.$(OBJEXT) nconf-nconf.gui.$(OBJEXT) +nconf_OBJECTS = $(am_nconf_OBJECTS) +am__DEPENDENCIES_1 = +nconf_DEPENDENCIES = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(am__DEPENDENCIES_1) $(am__DEPENDENCIES_1) \ + $(am__DEPENDENCIES_1) $(am__DEPENDENCIES_1) +AM_V_lt = $(am__v_lt_$(V)) +am__v_lt_ = $(am__v_lt_$(AM_DEFAULT_VERBOSITY)) +am__v_lt_0 = --silent +nconf_LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(nconf_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +DEFAULT_INCLUDES = -I.@am__isrc@ -I$(top_builddir)/scripts/.autostuff +depcomp = $(SHELL) $(top_srcdir)/scripts/.autostuff/scripts/depcomp +am__depfiles_maybe = depfiles +am__mv = mv -f +COMPILE = $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) \ + $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) +LTCOMPILE = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) \ + $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) $(CPPFLAGS) \ + $(AM_CFLAGS) $(CFLAGS) +AM_V_CC = $(am__v_CC_$(V)) +am__v_CC_ = $(am__v_CC_$(AM_DEFAULT_VERBOSITY)) +am__v_CC_0 = @echo " CC " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +CCLD = $(CC) +LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(AM_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +AM_V_CCLD = $(am__v_CCLD_$(V)) +am__v_CCLD_ = $(am__v_CCLD_$(AM_DEFAULT_VERBOSITY)) +am__v_CCLD_0 = @echo " CCLD " $@; +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +SOURCES = $(nconf_SOURCES) +DIST_SOURCES = $(nconf_SOURCES) +ETAGS = etags +CTAGS = ctags +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +nconf_SOURCES = nconf.c nconf.gui.c nconf.h +nconf_CPPFLAGS = $(AM_CPPFLAGS) \ + $(intl_CPPFLAGS) \ + $(ncurses_extra_CPPFLAGS) \ + -I$(top_srcdir)/libs/parser + +nconf_CFLAGS = $(AM_CFLAGS) \ + $(kf_CFLAGS) + +nconf_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(intl_LIBS) $(ncurses_extra_LIBS) $(ncurses_LIBS) \ + $(nconf_EXTRA_LIBS) + +all: all-am + +.SUFFIXES: +.SUFFIXES: .c .lo .o .obj +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign frontends/nconf/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign frontends/nconf/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): +install-binPROGRAMS: $(bin_PROGRAMS) + @$(NORMAL_INSTALL) + test -z "$(bindir)" || $(MKDIR_P) "$(DESTDIR)$(bindir)" + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + for p in $$list; do echo "$$p $$p"; done | \ + sed 's/$(EXEEXT)$$//' | \ + while read p p1; do if test -f $$p || test -f $$p1; \ + then echo "$$p"; echo "$$p"; else :; fi; \ + done | \ + sed -e 'p;s,.*/,,;n;h' -e 's|.*|.|' \ + -e 'p;x;s,.*/,,;s/$(EXEEXT)$$//;$(transform);s/$$/$(EXEEXT)/' | \ + sed 'N;N;N;s,\n, ,g' | \ + $(AWK) 'BEGIN { files["."] = ""; dirs["."] = 1 } \ + { d=$$3; if (dirs[d] != 1) { print "d", d; dirs[d] = 1 } \ + if ($$2 == $$4) files[d] = files[d] " " $$1; \ + else { print "f", $$3 "/" $$4, $$1; } } \ + END { for (d in files) print "f", d, files[d] }' | \ + while read type dir files; do \ + if test "$$dir" = .; then dir=; else dir=/$$dir; fi; \ + test -z "$$files" || { \ + echo " $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files '$(DESTDIR)$(bindir)$$dir'"; \ + $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files "$(DESTDIR)$(bindir)$$dir" || exit $$?; \ + } \ + ; done + +uninstall-binPROGRAMS: + @$(NORMAL_UNINSTALL) + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + files=`for p in $$list; do echo "$$p"; done | \ + sed -e 'h;s,^.*/,,;s/$(EXEEXT)$$//;$(transform)' \ + -e 's/$$/$(EXEEXT)/' `; \ + test -n "$$list" || exit 0; \ + echo " ( cd '$(DESTDIR)$(bindir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(bindir)" && rm -f $$files + +clean-binPROGRAMS: + @list='$(bin_PROGRAMS)'; test -n "$$list" || exit 0; \ + echo " rm -f" $$list; \ + rm -f $$list || exit $$?; \ + test -n "$(EXEEXT)" || exit 0; \ + list=`for p in $$list; do echo "$$p"; done | sed 's/$(EXEEXT)$$//'`; \ + echo " rm -f" $$list; \ + rm -f $$list +nconf$(EXEEXT): $(nconf_OBJECTS) $(nconf_DEPENDENCIES) + @rm -f nconf$(EXEEXT) + $(AM_V_CCLD)$(nconf_LINK) $(nconf_OBJECTS) $(nconf_LDADD) $(LIBS) + +mostlyclean-compile: + -rm -f *.$(OBJEXT) + +distclean-compile: + -rm -f *.tab.c + +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/nconf-nconf.Po@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/nconf-nconf.gui.Po@am__quote@ + +.c.o: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c $< + +.c.obj: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ `$(CYGPATH_W) '$<'` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c `$(CYGPATH_W) '$<'` + +.c.lo: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LTCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LTCOMPILE) -c -o $@ $< + +nconf-nconf.o: nconf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(nconf_CPPFLAGS) $(CPPFLAGS) $(nconf_CFLAGS) $(CFLAGS) -MT nconf-nconf.o -MD -MP -MF $(DEPDIR)/nconf-nconf.Tpo -c -o nconf-nconf.o `test -f 'nconf.c' || echo '$(srcdir)/'`nconf.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/nconf-nconf.Tpo $(DEPDIR)/nconf-nconf.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='nconf.c' object='nconf-nconf.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(nconf_CPPFLAGS) $(CPPFLAGS) $(nconf_CFLAGS) $(CFLAGS) -c -o nconf-nconf.o `test -f 'nconf.c' || echo '$(srcdir)/'`nconf.c + +nconf-nconf.obj: nconf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(nconf_CPPFLAGS) $(CPPFLAGS) $(nconf_CFLAGS) $(CFLAGS) -MT nconf-nconf.obj -MD -MP -MF $(DEPDIR)/nconf-nconf.Tpo -c -o nconf-nconf.obj `if test -f 'nconf.c'; then $(CYGPATH_W) 'nconf.c'; else $(CYGPATH_W) '$(srcdir)/nconf.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/nconf-nconf.Tpo $(DEPDIR)/nconf-nconf.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='nconf.c' object='nconf-nconf.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(nconf_CPPFLAGS) $(CPPFLAGS) $(nconf_CFLAGS) $(CFLAGS) -c -o nconf-nconf.obj `if test -f 'nconf.c'; then $(CYGPATH_W) 'nconf.c'; else $(CYGPATH_W) '$(srcdir)/nconf.c'; fi` + +nconf-nconf.gui.o: nconf.gui.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(nconf_CPPFLAGS) $(CPPFLAGS) $(nconf_CFLAGS) $(CFLAGS) -MT nconf-nconf.gui.o -MD -MP -MF $(DEPDIR)/nconf-nconf.gui.Tpo -c -o nconf-nconf.gui.o `test -f 'nconf.gui.c' || echo '$(srcdir)/'`nconf.gui.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/nconf-nconf.gui.Tpo $(DEPDIR)/nconf-nconf.gui.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='nconf.gui.c' object='nconf-nconf.gui.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(nconf_CPPFLAGS) $(CPPFLAGS) $(nconf_CFLAGS) $(CFLAGS) -c -o nconf-nconf.gui.o `test -f 'nconf.gui.c' || echo '$(srcdir)/'`nconf.gui.c + +nconf-nconf.gui.obj: nconf.gui.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(nconf_CPPFLAGS) $(CPPFLAGS) $(nconf_CFLAGS) $(CFLAGS) -MT nconf-nconf.gui.obj -MD -MP -MF $(DEPDIR)/nconf-nconf.gui.Tpo -c -o nconf-nconf.gui.obj `if test -f 'nconf.gui.c'; then $(CYGPATH_W) 'nconf.gui.c'; else $(CYGPATH_W) '$(srcdir)/nconf.gui.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/nconf-nconf.gui.Tpo $(DEPDIR)/nconf-nconf.gui.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='nconf.gui.c' object='nconf-nconf.gui.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(nconf_CPPFLAGS) $(CPPFLAGS) $(nconf_CFLAGS) $(CFLAGS) -c -o nconf-nconf.gui.obj `if test -f 'nconf.gui.c'; then $(CYGPATH_W) 'nconf.gui.c'; else $(CYGPATH_W) '$(srcdir)/nconf.gui.c'; fi` + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-am +all-am: Makefile $(PROGRAMS) +installdirs: + for dir in "$(DESTDIR)$(bindir)"; do \ + test -z "$$dir" || $(MKDIR_P) "$$dir"; \ + done +install: install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-am + +clean-am: clean-binPROGRAMS clean-generic clean-libtool mostlyclean-am + +distclean: distclean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +distclean-am: clean-am distclean-compile distclean-generic \ + distclean-tags + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: install-binPROGRAMS + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: uninstall-binPROGRAMS + +.MAKE: install-am install-strip + +.PHONY: CTAGS GTAGS all all-am check check-am clean clean-binPROGRAMS \ + clean-generic clean-libtool ctags distclean distclean-compile \ + distclean-generic distclean-libtool distclean-tags distdir dvi \ + dvi-am html html-am info info-am install install-am \ + install-binPROGRAMS install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-compile mostlyclean-generic mostlyclean-libtool \ + pdf pdf-am ps ps-am tags uninstall uninstall-am \ + uninstall-binPROGRAMS + + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/frontends/nconf/nconf.c b/misc/tools/kconfig-frontends/frontends/nconf/nconf.c new file mode 100644 index 0000000000..1704a8562a --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/nconf/nconf.c @@ -0,0 +1,1550 @@ +/* + * Copyright (C) 2008 Nir Tzachar + +#include "lkc.h" +#include "nconf.h" +#include + +static const char nconf_readme[] = N_( +"Overview\n" +"--------\n" +"This interface let you select features and parameters for the build.\n" +"Features can either be built-in, modularized, or ignored. Parameters\n" +"must be entered in as decimal or hexadecimal numbers or text.\n" +"\n" +"Menu items beginning with following braces represent features that\n" +" [ ] can be built in or removed\n" +" < > can be built in, modularized or removed\n" +" { } can be built in or modularized (selected by other feature)\n" +" - - are selected by other feature,\n" +" XXX cannot be selected. Use Symbol Info to find out why,\n" +"while *, M or whitespace inside braces means to build in, build as\n" +"a module or to exclude the feature respectively.\n" +"\n" +"To change any of these features, highlight it with the cursor\n" +"keys and press to build it in, to make it a module or\n" +" to removed it. You may also press the to cycle\n" +"through the available options (ie. Y->N->M->Y).\n" +"\n" +"Some additional keyboard hints:\n" +"\n" +"Menus\n" +"----------\n" +"o Use the Up/Down arrow keys (cursor keys) to highlight the item\n" +" you wish to change use or . Goto submenu by \n" +" pressing of . Use or to go back.\n" +" Submenus are designated by \"--->\".\n" +"\n" +" Searching: pressing '/' triggers interactive search mode.\n" +" nconfig performs a case insensitive search for the string\n" +" in the menu prompts (no regex support).\n" +" Pressing the up/down keys highlights the previous/next\n" +" matching item. Backspace removes one character from the\n" +" match string. Pressing either '/' again or ESC exits\n" +" search mode. All other keys behave normally.\n" +"\n" +" You may also use the and keys to scroll\n" +" unseen options into view.\n" +"\n" +"o To exit a menu use the just press or .\n" +"\n" +"o To get help with an item, press \n" +" Shortcut: Press or .\n" +"\n" +"\n" +"Radiolists (Choice lists)\n" +"-----------\n" +"o Use the cursor keys to select the option you wish to set and press\n" +" or the .\n" +"\n" +" Shortcut: Press the first letter of the option you wish to set then\n" +" press or .\n" +"\n" +"o To see available help for the item, press \n" +" Shortcut: Press or .\n" +"\n" +"\n" +"Data Entry\n" +"-----------\n" +"o Enter the requested information and press \n" +" If you are entering hexadecimal values, it is not necessary to\n" +" add the '0x' prefix to the entry.\n" +"\n" +"o For help, press .\n" +"\n" +"\n" +"Text Box (Help Window)\n" +"--------\n" +"o Use the cursor keys to scroll up/down/left/right. The VI editor\n" +" keys h,j,k,l function here as do , and for\n" +" those who are familiar with less and lynx.\n" +"\n" +"o Press , , , , or to exit.\n" +"\n" +"\n" +"Alternate Configuration Files\n" +"-----------------------------\n" +"nconfig supports the use of alternate configuration files for\n" +"those who, for various reasons, find it necessary to switch\n" +"between different configurations.\n" +"\n" +"At the end of the main menu you will find two options. One is\n" +"for saving the current configuration to a file of your choosing.\n" +"The other option is for loading a previously saved alternate\n" +"configuration.\n" +"\n" +"Even if you don't use alternate configuration files, but you\n" +"find during a nconfig session that you have completely messed\n" +"up your settings, you may use the \"Load Alternate...\" option to\n" +"restore your previously saved settings from \".config\" without\n" +"restarting nconfig.\n" +"\n" +"Other information\n" +"-----------------\n" +"If you use nconfig in an XTERM window make sure you have your\n" +"$TERM variable set to point to a xterm definition which supports color.\n" +"Otherwise, nconfig will look rather bad. nconfig will not\n" +"display correctly in a RXVT window because rxvt displays only one\n" +"intensity of color, bright.\n" +"\n" +"nconfig will display larger menus on screens or xterms which are\n" +"set to display more than the standard 25 row by 80 column geometry.\n" +"In order for this to work, the \"stty size\" command must be able to\n" +"display the screen's current row and column geometry. I STRONGLY\n" +"RECOMMEND that you make sure you do NOT have the shell variables\n" +"LINES and COLUMNS exported into your environment. Some distributions\n" +"export those variables via /etc/profile. Some ncurses programs can\n" +"become confused when those variables (LINES & COLUMNS) don't reflect\n" +"the true screen size.\n" +"\n" +"Optional personality available\n" +"------------------------------\n" +"If you prefer to have all of the options listed in a single menu, rather\n" +"than the default multimenu hierarchy, run the nconfig with NCONFIG_MODE\n" +"environment variable set to single_menu. Example:\n" +"\n" +"make NCONFIG_MODE=single_menu nconfig\n" +"\n" +" will then unroll the appropriate category, or enfold it if it\n" +"is already unrolled.\n" +"\n" +"Note that this mode can eventually be a little more CPU expensive\n" +"(especially with a larger number of unrolled categories) than the\n" +"default mode.\n" +"\n"), +menu_no_f_instructions[] = N_( +" You do not have function keys support. Please follow the\n" +" following instructions:\n" +" Arrow keys navigate the menu.\n" +" or selects submenus --->.\n" +" Capital Letters are hotkeys.\n" +" Pressing includes, excludes, modularizes features.\n" +" Pressing SpaceBar toggles between the above options.\n" +" Press or to go back one menu,\n" +" or for Help, for Search.\n" +" <1> is interchangeable with , <2> with , etc.\n" +" Legend: [*] built-in [ ] excluded module < > module capable.\n" +" always leaves the current window.\n"), +menu_instructions[] = N_( +" Arrow keys navigate the menu.\n" +" or selects submenus --->.\n" +" Capital Letters are hotkeys.\n" +" Pressing includes, excludes, modularizes features.\n" +" Pressing SpaceBar toggles between the above options\n" +" Press , or to go back one menu,\n" +" , or for Help, for Search.\n" +" <1> is interchangeable with , <2> with , etc.\n" +" Legend: [*] built-in [ ] excluded module < > module capable.\n" +" always leaves the current window\n"), +radiolist_instructions[] = N_( +" Use the arrow keys to navigate this window or\n" +" press the hotkey of the item you wish to select\n" +" followed by the .\n" +" Press , or for additional information about this option.\n"), +inputbox_instructions_int[] = N_( +"Please enter a decimal value.\n" +"Fractions will not be accepted.\n" +"Press to accept, to cancel."), +inputbox_instructions_hex[] = N_( +"Please enter a hexadecimal value.\n" +"Press to accept, to cancel."), +inputbox_instructions_string[] = N_( +"Please enter a string value.\n" +"Press to accept, to cancel."), +setmod_text[] = N_( +"This feature depends on another which\n" +"has been configured as a module.\n" +"As a result, this feature will be built as a module."), +load_config_text[] = N_( +"Enter the name of the configuration file you wish to load.\n" +"Accept the name shown to restore the configuration you\n" +"last retrieved. Leave blank to abort."), +load_config_help[] = N_( +"\n" +"For various reasons, one may wish to keep several different\n" +"configurations available on a single machine.\n" +"\n" +"If you have saved a previous configuration in a file other than the\n" +"default one, entering its name here will allow you to modify that\n" +"configuration.\n" +"\n" +"If you are uncertain, then you have probably never used alternate\n" +"configuration files. You should therefor leave this blank to abort.\n"), +save_config_text[] = N_( +"Enter a filename to which this configuration should be saved\n" +"as an alternate. Leave blank to abort."), +save_config_help[] = N_( +"\n" +"For various reasons, one may wish to keep different configurations\n" +"available on a single machine.\n" +"\n" +"Entering a file name here will allow you to later retrieve, modify\n" +"and use the current configuration as an alternate to whatever\n" +"configuration options you have selected at that time.\n" +"\n" +"If you are uncertain what all this means then you should probably\n" +"leave this blank.\n"), +search_help[] = N_( +"\n" +"Search for symbols and display their relations. Regular expressions\n" +"are allowed.\n" +"Example: search for \"^FOO\"\n" +"Result:\n" +"-----------------------------------------------------------------\n" +"Symbol: FOO [ = m]\n" +"Prompt: Foo bus is used to drive the bar HW\n" +"Defined at drivers/pci/Kconfig:47\n" +"Depends on: X86_LOCAL_APIC && X86_IO_APIC || IA64\n" +"Location:\n" +" -> Bus options (PCI, PCMCIA, EISA, ISA)\n" +" -> PCI support (PCI [ = y])\n" +" -> PCI access mode ( [ = y])\n" +"Selects: LIBCRC32\n" +"Selected by: BAR\n" +"-----------------------------------------------------------------\n" +"o The line 'Prompt:' shows the text used in the menu structure for\n" +" this symbol\n" +"o The 'Defined at' line tell at what file / line number the symbol\n" +" is defined\n" +"o The 'Depends on:' line tell what symbols needs to be defined for\n" +" this symbol to be visible in the menu (selectable)\n" +"o The 'Location:' lines tell where in the menu structure this symbol\n" +" is located\n" +" A location followed by a [ = y] indicate that this is a selectable\n" +" menu item - and current value is displayed inside brackets.\n" +"o The 'Selects:' line tell what symbol will be automatically\n" +" selected if this symbol is selected (y or m)\n" +"o The 'Selected by' line tell what symbol has selected this symbol\n" +"\n" +"Only relevant lines are shown.\n" +"\n\n" +"Search examples:\n" +"Examples: USB => find all symbols containing USB\n" +" ^USB => find all symbols starting with USB\n" +" USB$ => find all symbols ending with USB\n" +"\n"); + +struct mitem { + char str[256]; + char tag; + void *usrptr; + int is_visible; +}; + +#define MAX_MENU_ITEMS 4096 +static int show_all_items; +static int indent; +static struct menu *current_menu; +static int child_count; +static int single_menu_mode; +/* the window in which all information appears */ +static WINDOW *main_window; +/* the largest size of the menu window */ +static int mwin_max_lines; +static int mwin_max_cols; +/* the window in which we show option buttons */ +static MENU *curses_menu; +static ITEM *curses_menu_items[MAX_MENU_ITEMS]; +static struct mitem k_menu_items[MAX_MENU_ITEMS]; +static int items_num; +static int global_exit; +/* the currently selected button */ +const char *current_instructions = menu_instructions; + +static char *dialog_input_result; +static int dialog_input_result_len; + +static void conf(struct menu *menu); +static void conf_choice(struct menu *menu); +static void conf_string(struct menu *menu); +static void conf_load(void); +static void conf_save(void); +static void show_help(struct menu *menu); +static int do_exit(void); +static void setup_windows(void); +static void search_conf(void); + +typedef void (*function_key_handler_t)(int *key, struct menu *menu); +static void handle_f1(int *key, struct menu *current_item); +static void handle_f2(int *key, struct menu *current_item); +static void handle_f3(int *key, struct menu *current_item); +static void handle_f4(int *key, struct menu *current_item); +static void handle_f5(int *key, struct menu *current_item); +static void handle_f6(int *key, struct menu *current_item); +static void handle_f7(int *key, struct menu *current_item); +static void handle_f8(int *key, struct menu *current_item); +static void handle_f9(int *key, struct menu *current_item); + +struct function_keys { + const char *key_str; + const char *func; + function_key key; + function_key_handler_t handler; +}; + +static const int function_keys_num = 9; +struct function_keys function_keys[] = { + { + .key_str = "F1", + .func = "Help", + .key = F_HELP, + .handler = handle_f1, + }, + { + .key_str = "F2", + .func = "Sym Info", + .key = F_SYMBOL, + .handler = handle_f2, + }, + { + .key_str = "F3", + .func = "Insts", + .key = F_INSTS, + .handler = handle_f3, + }, + { + .key_str = "F4", + .func = "Config", + .key = F_CONF, + .handler = handle_f4, + }, + { + .key_str = "F5", + .func = "Back", + .key = F_BACK, + .handler = handle_f5, + }, + { + .key_str = "F6", + .func = "Save", + .key = F_SAVE, + .handler = handle_f6, + }, + { + .key_str = "F7", + .func = "Load", + .key = F_LOAD, + .handler = handle_f7, + }, + { + .key_str = "F8", + .func = "Sym Search", + .key = F_SEARCH, + .handler = handle_f8, + }, + { + .key_str = "F9", + .func = "Exit", + .key = F_EXIT, + .handler = handle_f9, + }, +}; + +static void print_function_line(void) +{ + int i; + int offset = 1; + const int skip = 1; + + for (i = 0; i < function_keys_num; i++) { + (void) wattrset(main_window, attributes[FUNCTION_HIGHLIGHT]); + mvwprintw(main_window, LINES-3, offset, + "%s", + function_keys[i].key_str); + (void) wattrset(main_window, attributes[FUNCTION_TEXT]); + offset += strlen(function_keys[i].key_str); + mvwprintw(main_window, LINES-3, + offset, "%s", + function_keys[i].func); + offset += strlen(function_keys[i].func) + skip; + } + (void) wattrset(main_window, attributes[NORMAL]); +} + +/* help */ +static void handle_f1(int *key, struct menu *current_item) +{ + show_scroll_win(main_window, + _("README"), _(nconf_readme)); + return; +} + +/* symbole help */ +static void handle_f2(int *key, struct menu *current_item) +{ + show_help(current_item); + return; +} + +/* instructions */ +static void handle_f3(int *key, struct menu *current_item) +{ + show_scroll_win(main_window, + _("Instructions"), + _(current_instructions)); + return; +} + +/* config */ +static void handle_f4(int *key, struct menu *current_item) +{ + int res = btn_dialog(main_window, + _("Show all symbols?"), + 2, + " ", + ""); + if (res == 0) + show_all_items = 1; + else if (res == 1) + show_all_items = 0; + + return; +} + +/* back */ +static void handle_f5(int *key, struct menu *current_item) +{ + *key = KEY_LEFT; + return; +} + +/* save */ +static void handle_f6(int *key, struct menu *current_item) +{ + conf_save(); + return; +} + +/* load */ +static void handle_f7(int *key, struct menu *current_item) +{ + conf_load(); + return; +} + +/* search */ +static void handle_f8(int *key, struct menu *current_item) +{ + search_conf(); + return; +} + +/* exit */ +static void handle_f9(int *key, struct menu *current_item) +{ + do_exit(); + return; +} + +/* return != 0 to indicate the key was handles */ +static int process_special_keys(int *key, struct menu *menu) +{ + int i; + + if (*key == KEY_RESIZE) { + setup_windows(); + return 1; + } + + for (i = 0; i < function_keys_num; i++) { + if (*key == KEY_F(function_keys[i].key) || + *key == '0' + function_keys[i].key){ + function_keys[i].handler(key, menu); + return 1; + } + } + + return 0; +} + +static void clean_items(void) +{ + int i; + for (i = 0; curses_menu_items[i]; i++) + free_item(curses_menu_items[i]); + bzero(curses_menu_items, sizeof(curses_menu_items)); + bzero(k_menu_items, sizeof(k_menu_items)); + items_num = 0; +} + +typedef enum {MATCH_TINKER_PATTERN_UP, MATCH_TINKER_PATTERN_DOWN, + FIND_NEXT_MATCH_DOWN, FIND_NEXT_MATCH_UP} match_f; + +/* return the index of the matched item, or -1 if no such item exists */ +static int get_mext_match(const char *match_str, match_f flag) +{ + int match_start = item_index(current_item(curses_menu)); + int index; + + if (flag == FIND_NEXT_MATCH_DOWN) + ++match_start; + else if (flag == FIND_NEXT_MATCH_UP) + --match_start; + + index = match_start; + index = (index + items_num) % items_num; + while (true) { + char *str = k_menu_items[index].str; + if (strcasestr(str, match_str) != 0) + return index; + if (flag == FIND_NEXT_MATCH_UP || + flag == MATCH_TINKER_PATTERN_UP) + --index; + else + ++index; + index = (index + items_num) % items_num; + if (index == match_start) + return -1; + } +} + +/* Make a new item. */ +static void item_make(struct menu *menu, char tag, const char *fmt, ...) +{ + va_list ap; + + if (items_num > MAX_MENU_ITEMS-1) + return; + + bzero(&k_menu_items[items_num], sizeof(k_menu_items[0])); + k_menu_items[items_num].tag = tag; + k_menu_items[items_num].usrptr = menu; + if (menu != NULL) + k_menu_items[items_num].is_visible = + menu_is_visible(menu); + else + k_menu_items[items_num].is_visible = 1; + + va_start(ap, fmt); + vsnprintf(k_menu_items[items_num].str, + sizeof(k_menu_items[items_num].str), + fmt, ap); + va_end(ap); + + if (!k_menu_items[items_num].is_visible) + memcpy(k_menu_items[items_num].str, "XXX", 3); + + curses_menu_items[items_num] = new_item( + k_menu_items[items_num].str, + k_menu_items[items_num].str); + set_item_userptr(curses_menu_items[items_num], + &k_menu_items[items_num]); + /* + if (!k_menu_items[items_num].is_visible) + item_opts_off(curses_menu_items[items_num], O_SELECTABLE); + */ + + items_num++; + curses_menu_items[items_num] = NULL; +} + +/* very hackish. adds a string to the last item added */ +static void item_add_str(const char *fmt, ...) +{ + va_list ap; + int index = items_num-1; + char new_str[256]; + char tmp_str[256]; + + if (index < 0) + return; + + va_start(ap, fmt); + vsnprintf(new_str, sizeof(new_str), fmt, ap); + va_end(ap); + snprintf(tmp_str, sizeof(tmp_str), "%s%s", + k_menu_items[index].str, new_str); + strncpy(k_menu_items[index].str, + tmp_str, + sizeof(k_menu_items[index].str)); + + free_item(curses_menu_items[index]); + curses_menu_items[index] = new_item( + k_menu_items[index].str, + k_menu_items[index].str); + set_item_userptr(curses_menu_items[index], + &k_menu_items[index]); +} + +/* get the tag of the currently selected item */ +static char item_tag(void) +{ + ITEM *cur; + struct mitem *mcur; + + cur = current_item(curses_menu); + if (cur == NULL) + return 0; + mcur = (struct mitem *) item_userptr(cur); + return mcur->tag; +} + +static int curses_item_index(void) +{ + return item_index(current_item(curses_menu)); +} + +static void *item_data(void) +{ + ITEM *cur; + struct mitem *mcur; + + cur = current_item(curses_menu); + if (!cur) + return NULL; + mcur = (struct mitem *) item_userptr(cur); + return mcur->usrptr; + +} + +static int item_is_tag(char tag) +{ + return item_tag() == tag; +} + +static char filename[PATH_MAX+1]; +static char menu_backtitle[PATH_MAX+128]; +static const char *set_config_filename(const char *config_filename) +{ + int size; + + size = snprintf(menu_backtitle, sizeof(menu_backtitle), + "%s - %s", config_filename, rootmenu.prompt->text); + if (size >= sizeof(menu_backtitle)) + menu_backtitle[sizeof(menu_backtitle)-1] = '\0'; + + size = snprintf(filename, sizeof(filename), "%s", config_filename); + if (size >= sizeof(filename)) + filename[sizeof(filename)-1] = '\0'; + return menu_backtitle; +} + +/* return = 0 means we are successful. + * -1 means go on doing what you were doing + */ +static int do_exit(void) +{ + int res; + if (!conf_get_changed()) { + global_exit = 1; + return 0; + } + res = btn_dialog(main_window, + _("Do you wish to save your new configuration?\n" + " to cancel and resume nconfig."), + 2, + " ", + ""); + if (res == KEY_EXIT) { + global_exit = 0; + return -1; + } + + /* if we got here, the user really wants to exit */ + switch (res) { + case 0: + res = conf_write(filename); + if (res) + btn_dialog( + main_window, + _("Error during writing of configuration.\n" + "Your configuration changes were NOT saved."), + 1, + ""); + break; + default: + btn_dialog( + main_window, + _("Your configuration changes were NOT saved."), + 1, + ""); + break; + } + global_exit = 1; + return 0; +} + + +static void search_conf(void) +{ + struct symbol **sym_arr; + struct gstr res; + char *dialog_input; + int dres; +again: + dres = dialog_inputbox(main_window, + _("Search Configuration Parameter"), + _("Enter " CONFIG_ " (sub)string to search for " + "(with or without \"" CONFIG_ "\")"), + "", &dialog_input_result, &dialog_input_result_len); + switch (dres) { + case 0: + break; + case 1: + show_scroll_win(main_window, + _("Search Configuration"), search_help); + goto again; + default: + return; + } + + /* strip the prefix if necessary */ + dialog_input = dialog_input_result; + if (strncasecmp(dialog_input_result, CONFIG_, strlen(CONFIG_)) == 0) + dialog_input += strlen(CONFIG_); + + sym_arr = sym_re_search(dialog_input); + res = get_relations_str(sym_arr); + free(sym_arr); + show_scroll_win(main_window, + _("Search Results"), str_get(&res)); + str_free(&res); +} + + +static void build_conf(struct menu *menu) +{ + struct symbol *sym; + struct property *prop; + struct menu *child; + int type, tmp, doint = 2; + tristate val; + char ch; + + if (!menu || (!show_all_items && !menu_is_visible(menu))) + return; + + sym = menu->sym; + prop = menu->prompt; + if (!sym) { + if (prop && menu != current_menu) { + const char *prompt = menu_get_prompt(menu); + enum prop_type ptype; + ptype = menu->prompt ? menu->prompt->type : P_UNKNOWN; + switch (ptype) { + case P_MENU: + child_count++; + prompt = _(prompt); + if (single_menu_mode) { + item_make(menu, 'm', + "%s%*c%s", + menu->data ? "-->" : "++>", + indent + 1, ' ', prompt); + } else + item_make(menu, 'm', + " %*c%s --->", + indent + 1, + ' ', prompt); + + if (single_menu_mode && menu->data) + goto conf_childs; + return; + case P_COMMENT: + if (prompt) { + child_count++; + item_make(menu, ':', + " %*c*** %s ***", + indent + 1, ' ', + _(prompt)); + } + break; + default: + if (prompt) { + child_count++; + item_make(menu, ':', "---%*c%s", + indent + 1, ' ', + _(prompt)); + } + } + } else + doint = 0; + goto conf_childs; + } + + type = sym_get_type(sym); + if (sym_is_choice(sym)) { + struct symbol *def_sym = sym_get_choice_value(sym); + struct menu *def_menu = NULL; + + child_count++; + for (child = menu->list; child; child = child->next) { + if (menu_is_visible(child) && child->sym == def_sym) + def_menu = child; + } + + val = sym_get_tristate_value(sym); + if (sym_is_changable(sym)) { + switch (type) { + case S_BOOLEAN: + item_make(menu, 't', "[%c]", + val == no ? ' ' : '*'); + break; + case S_TRISTATE: + switch (val) { + case yes: + ch = '*'; + break; + case mod: + ch = 'M'; + break; + default: + ch = ' '; + break; + } + item_make(menu, 't', "<%c>", ch); + break; + } + } else { + item_make(menu, def_menu ? 't' : ':', " "); + } + + item_add_str("%*c%s", indent + 1, + ' ', _(menu_get_prompt(menu))); + if (val == yes) { + if (def_menu) { + item_add_str(" (%s)", + _(menu_get_prompt(def_menu))); + item_add_str(" --->"); + if (def_menu->list) { + indent += 2; + build_conf(def_menu); + indent -= 2; + } + } + return; + } + } else { + if (menu == current_menu) { + item_make(menu, ':', + "---%*c%s", indent + 1, + ' ', _(menu_get_prompt(menu))); + goto conf_childs; + } + child_count++; + val = sym_get_tristate_value(sym); + if (sym_is_choice_value(sym) && val == yes) { + item_make(menu, ':', " "); + } else { + switch (type) { + case S_BOOLEAN: + if (sym_is_changable(sym)) + item_make(menu, 't', "[%c]", + val == no ? ' ' : '*'); + else + item_make(menu, 't', "-%c-", + val == no ? ' ' : '*'); + break; + case S_TRISTATE: + switch (val) { + case yes: + ch = '*'; + break; + case mod: + ch = 'M'; + break; + default: + ch = ' '; + break; + } + if (sym_is_changable(sym)) { + if (sym->rev_dep.tri == mod) + item_make(menu, + 't', "{%c}", ch); + else + item_make(menu, + 't', "<%c>", ch); + } else + item_make(menu, 't', "-%c-", ch); + break; + default: + tmp = 2 + strlen(sym_get_string_value(sym)); + item_make(menu, 's', " (%s)", + sym_get_string_value(sym)); + tmp = indent - tmp + 4; + if (tmp < 0) + tmp = 0; + item_add_str("%*c%s%s", tmp, ' ', + _(menu_get_prompt(menu)), + (sym_has_value(sym) || + !sym_is_changable(sym)) ? "" : + _(" (NEW)")); + goto conf_childs; + } + } + item_add_str("%*c%s%s", indent + 1, ' ', + _(menu_get_prompt(menu)), + (sym_has_value(sym) || !sym_is_changable(sym)) ? + "" : _(" (NEW)")); + if (menu->prompt && menu->prompt->type == P_MENU) { + item_add_str(" --->"); + return; + } + } + +conf_childs: + indent += doint; + for (child = menu->list; child; child = child->next) + build_conf(child); + indent -= doint; +} + +static void reset_menu(void) +{ + unpost_menu(curses_menu); + clean_items(); +} + +/* adjust the menu to show this item. + * prefer not to scroll the menu if possible*/ +static void center_item(int selected_index, int *last_top_row) +{ + int toprow; + + set_top_row(curses_menu, *last_top_row); + toprow = top_row(curses_menu); + if (selected_index < toprow || + selected_index >= toprow+mwin_max_lines) { + toprow = max(selected_index-mwin_max_lines/2, 0); + if (toprow >= item_count(curses_menu)-mwin_max_lines) + toprow = item_count(curses_menu)-mwin_max_lines; + set_top_row(curses_menu, toprow); + } + set_current_item(curses_menu, + curses_menu_items[selected_index]); + *last_top_row = toprow; + post_menu(curses_menu); + refresh_all_windows(main_window); +} + +/* this function assumes reset_menu has been called before */ +static void show_menu(const char *prompt, const char *instructions, + int selected_index, int *last_top_row) +{ + int maxx, maxy; + WINDOW *menu_window; + + current_instructions = instructions; + + clear(); + (void) wattrset(main_window, attributes[NORMAL]); + print_in_middle(stdscr, 1, 0, COLS, + menu_backtitle, + attributes[MAIN_HEADING]); + + (void) wattrset(main_window, attributes[MAIN_MENU_BOX]); + box(main_window, 0, 0); + (void) wattrset(main_window, attributes[MAIN_MENU_HEADING]); + mvwprintw(main_window, 0, 3, " %s ", prompt); + (void) wattrset(main_window, attributes[NORMAL]); + + set_menu_items(curses_menu, curses_menu_items); + + /* position the menu at the middle of the screen */ + scale_menu(curses_menu, &maxy, &maxx); + maxx = min(maxx, mwin_max_cols-2); + maxy = mwin_max_lines; + menu_window = derwin(main_window, + maxy, + maxx, + 2, + (mwin_max_cols-maxx)/2); + keypad(menu_window, TRUE); + set_menu_win(curses_menu, menu_window); + set_menu_sub(curses_menu, menu_window); + + /* must reassert this after changing items, otherwise returns to a + * default of 16 + */ + set_menu_format(curses_menu, maxy, 1); + center_item(selected_index, last_top_row); + set_menu_format(curses_menu, maxy, 1); + + print_function_line(); + + /* Post the menu */ + post_menu(curses_menu); + refresh_all_windows(main_window); +} + +static void adj_match_dir(match_f *match_direction) +{ + if (*match_direction == FIND_NEXT_MATCH_DOWN) + *match_direction = + MATCH_TINKER_PATTERN_DOWN; + else if (*match_direction == FIND_NEXT_MATCH_UP) + *match_direction = + MATCH_TINKER_PATTERN_UP; + /* else, do no change.. */ +} + +struct match_state +{ + int in_search; + match_f match_direction; + char pattern[256]; +}; + +/* Return 0 means I have handled the key. In such a case, ans should hold the + * item to center, or -1 otherwise. + * Else return -1 . + */ +static int do_match(int key, struct match_state *state, int *ans) +{ + char c = (char) key; + int terminate_search = 0; + *ans = -1; + if (key == '/' || (state->in_search && key == 27)) { + move(0, 0); + refresh(); + clrtoeol(); + state->in_search = 1-state->in_search; + bzero(state->pattern, sizeof(state->pattern)); + state->match_direction = MATCH_TINKER_PATTERN_DOWN; + return 0; + } else if (!state->in_search) + return 1; + + if (isalnum(c) || isgraph(c) || c == ' ') { + state->pattern[strlen(state->pattern)] = c; + state->pattern[strlen(state->pattern)] = '\0'; + adj_match_dir(&state->match_direction); + *ans = get_mext_match(state->pattern, + state->match_direction); + } else if (key == KEY_DOWN) { + state->match_direction = FIND_NEXT_MATCH_DOWN; + *ans = get_mext_match(state->pattern, + state->match_direction); + } else if (key == KEY_UP) { + state->match_direction = FIND_NEXT_MATCH_UP; + *ans = get_mext_match(state->pattern, + state->match_direction); + } else if (key == KEY_BACKSPACE || key == 127) { + state->pattern[strlen(state->pattern)-1] = '\0'; + adj_match_dir(&state->match_direction); + } else + terminate_search = 1; + + if (terminate_search) { + state->in_search = 0; + bzero(state->pattern, sizeof(state->pattern)); + move(0, 0); + refresh(); + clrtoeol(); + return -1; + } + return 0; +} + +static void conf(struct menu *menu) +{ + struct menu *submenu = 0; + const char *prompt = menu_get_prompt(menu); + struct symbol *sym; + int res; + int current_index = 0; + int last_top_row = 0; + struct match_state match_state = { + .in_search = 0, + .match_direction = MATCH_TINKER_PATTERN_DOWN, + .pattern = "", + }; + + while (!global_exit) { + reset_menu(); + current_menu = menu; + build_conf(menu); + if (!child_count) + break; + + show_menu(prompt ? _(prompt) : _("Main Menu"), + _(menu_instructions), + current_index, &last_top_row); + keypad((menu_win(curses_menu)), TRUE); + while (!global_exit) { + if (match_state.in_search) { + mvprintw(0, 0, + "searching: %s", match_state.pattern); + clrtoeol(); + } + refresh_all_windows(main_window); + res = wgetch(menu_win(curses_menu)); + if (!res) + break; + if (do_match(res, &match_state, ¤t_index) == 0) { + if (current_index != -1) + center_item(current_index, + &last_top_row); + continue; + } + if (process_special_keys(&res, + (struct menu *) item_data())) + break; + switch (res) { + case KEY_DOWN: + menu_driver(curses_menu, REQ_DOWN_ITEM); + break; + case KEY_UP: + menu_driver(curses_menu, REQ_UP_ITEM); + break; + case KEY_NPAGE: + menu_driver(curses_menu, REQ_SCR_DPAGE); + break; + case KEY_PPAGE: + menu_driver(curses_menu, REQ_SCR_UPAGE); + break; + case KEY_HOME: + menu_driver(curses_menu, REQ_FIRST_ITEM); + break; + case KEY_END: + menu_driver(curses_menu, REQ_LAST_ITEM); + break; + case 'h': + case '?': + show_help((struct menu *) item_data()); + break; + } + if (res == 10 || res == 27 || + res == 32 || res == 'n' || res == 'y' || + res == KEY_LEFT || res == KEY_RIGHT || + res == 'm') + break; + refresh_all_windows(main_window); + } + + refresh_all_windows(main_window); + /* if ESC or left*/ + if (res == 27 || (menu != &rootmenu && res == KEY_LEFT)) + break; + + /* remember location in the menu */ + last_top_row = top_row(curses_menu); + current_index = curses_item_index(); + + if (!item_tag()) + continue; + + submenu = (struct menu *) item_data(); + if (!submenu || !menu_is_visible(submenu)) + continue; + sym = submenu->sym; + + switch (res) { + case ' ': + if (item_is_tag('t')) + sym_toggle_tristate_value(sym); + else if (item_is_tag('m')) + conf(submenu); + break; + case KEY_RIGHT: + case 10: /* ENTER WAS PRESSED */ + switch (item_tag()) { + case 'm': + if (single_menu_mode) + submenu->data = + (void *) (long) !submenu->data; + else + conf(submenu); + break; + case 't': + if (sym_is_choice(sym) && + sym_get_tristate_value(sym) == yes) + conf_choice(submenu); + else if (submenu->prompt && + submenu->prompt->type == P_MENU) + conf(submenu); + else if (res == 10) + sym_toggle_tristate_value(sym); + break; + case 's': + conf_string(submenu); + break; + } + break; + case 'y': + if (item_is_tag('t')) { + if (sym_set_tristate_value(sym, yes)) + break; + if (sym_set_tristate_value(sym, mod)) + btn_dialog(main_window, setmod_text, 0); + } + break; + case 'n': + if (item_is_tag('t')) + sym_set_tristate_value(sym, no); + break; + case 'm': + if (item_is_tag('t')) + sym_set_tristate_value(sym, mod); + break; + } + } +} + +static void conf_message_callback(const char *fmt, va_list ap) +{ + char buf[1024]; + + vsnprintf(buf, sizeof(buf), fmt, ap); + btn_dialog(main_window, buf, 1, ""); +} + +static void show_help(struct menu *menu) +{ + struct gstr help; + + if (!menu) + return; + + help = str_new(); + menu_get_ext_help(menu, &help); + show_scroll_win(main_window, _(menu_get_prompt(menu)), str_get(&help)); + str_free(&help); +} + +static void conf_choice(struct menu *menu) +{ + const char *prompt = _(menu_get_prompt(menu)); + struct menu *child = 0; + struct symbol *active; + int selected_index = 0; + int last_top_row = 0; + int res, i = 0; + struct match_state match_state = { + .in_search = 0, + .match_direction = MATCH_TINKER_PATTERN_DOWN, + .pattern = "", + }; + + active = sym_get_choice_value(menu->sym); + /* this is mostly duplicated from the conf() function. */ + while (!global_exit) { + reset_menu(); + + for (i = 0, child = menu->list; child; child = child->next) { + if (!show_all_items && !menu_is_visible(child)) + continue; + + if (child->sym == sym_get_choice_value(menu->sym)) + item_make(child, ':', " %s", + _(menu_get_prompt(child))); + else if (child->sym) + item_make(child, ':', " %s", + _(menu_get_prompt(child))); + else + item_make(child, ':', "*** %s ***", + _(menu_get_prompt(child))); + + if (child->sym == active){ + last_top_row = top_row(curses_menu); + selected_index = i; + } + i++; + } + show_menu(prompt ? _(prompt) : _("Choice Menu"), + _(radiolist_instructions), + selected_index, + &last_top_row); + while (!global_exit) { + if (match_state.in_search) { + mvprintw(0, 0, "searching: %s", + match_state.pattern); + clrtoeol(); + } + refresh_all_windows(main_window); + res = wgetch(menu_win(curses_menu)); + if (!res) + break; + if (do_match(res, &match_state, &selected_index) == 0) { + if (selected_index != -1) + center_item(selected_index, + &last_top_row); + continue; + } + if (process_special_keys( + &res, + (struct menu *) item_data())) + break; + switch (res) { + case KEY_DOWN: + menu_driver(curses_menu, REQ_DOWN_ITEM); + break; + case KEY_UP: + menu_driver(curses_menu, REQ_UP_ITEM); + break; + case KEY_NPAGE: + menu_driver(curses_menu, REQ_SCR_DPAGE); + break; + case KEY_PPAGE: + menu_driver(curses_menu, REQ_SCR_UPAGE); + break; + case KEY_HOME: + menu_driver(curses_menu, REQ_FIRST_ITEM); + break; + case KEY_END: + menu_driver(curses_menu, REQ_LAST_ITEM); + break; + case 'h': + case '?': + show_help((struct menu *) item_data()); + break; + } + if (res == 10 || res == 27 || res == ' ' || + res == KEY_LEFT){ + break; + } + refresh_all_windows(main_window); + } + /* if ESC or left */ + if (res == 27 || res == KEY_LEFT) + break; + + child = item_data(); + if (!child || !menu_is_visible(child) || !child->sym) + continue; + switch (res) { + case ' ': + case 10: + case KEY_RIGHT: + sym_set_tristate_value(child->sym, yes); + return; + case 'h': + case '?': + show_help(child); + active = child->sym; + break; + case KEY_EXIT: + return; + } + } +} + +static void conf_string(struct menu *menu) +{ + const char *prompt = menu_get_prompt(menu); + + while (1) { + int res; + const char *heading; + + switch (sym_get_type(menu->sym)) { + case S_INT: + heading = _(inputbox_instructions_int); + break; + case S_HEX: + heading = _(inputbox_instructions_hex); + break; + case S_STRING: + heading = _(inputbox_instructions_string); + break; + default: + heading = _("Internal nconf error!"); + } + res = dialog_inputbox(main_window, + prompt ? _(prompt) : _("Main Menu"), + heading, + sym_get_string_value(menu->sym), + &dialog_input_result, + &dialog_input_result_len); + switch (res) { + case 0: + if (sym_set_string_value(menu->sym, + dialog_input_result)) + return; + btn_dialog(main_window, + _("You have made an invalid entry."), 0); + break; + case 1: + show_help(menu); + break; + case KEY_EXIT: + return; + } + } +} + +static void conf_load(void) +{ + while (1) { + int res; + res = dialog_inputbox(main_window, + NULL, load_config_text, + filename, + &dialog_input_result, + &dialog_input_result_len); + switch (res) { + case 0: + if (!dialog_input_result[0]) + return; + if (!conf_read(dialog_input_result)) { + set_config_filename(dialog_input_result); + sym_set_change_count(1); + return; + } + btn_dialog(main_window, _("File does not exist!"), 0); + break; + case 1: + show_scroll_win(main_window, + _("Load Alternate Configuration"), + load_config_help); + break; + case KEY_EXIT: + return; + } + } +} + +static void conf_save(void) +{ + while (1) { + int res; + res = dialog_inputbox(main_window, + NULL, save_config_text, + filename, + &dialog_input_result, + &dialog_input_result_len); + switch (res) { + case 0: + if (!dialog_input_result[0]) + return; + res = conf_write(dialog_input_result); + if (!res) { + set_config_filename(dialog_input_result); + return; + } + btn_dialog(main_window, _("Can't create file! " + "Probably a nonexistent directory."), + 1, ""); + break; + case 1: + show_scroll_win(main_window, + _("Save Alternate Configuration"), + save_config_help); + break; + case KEY_EXIT: + return; + } + } +} + +void setup_windows(void) +{ + if (main_window != NULL) + delwin(main_window); + + /* set up the menu and menu window */ + main_window = newwin(LINES-2, COLS-2, 2, 1); + keypad(main_window, TRUE); + mwin_max_lines = LINES-7; + mwin_max_cols = COLS-6; + + /* panels order is from bottom to top */ + new_panel(main_window); +} + +int main(int ac, char **av) +{ + char *mode; + + setlocale(LC_ALL, ""); + bindtextdomain(PACKAGE, LOCALEDIR); + textdomain(PACKAGE); + + conf_parse(av[1]); + conf_read(NULL); + + mode = getenv("NCONFIG_MODE"); + if (mode) { + if (!strcasecmp(mode, "single_menu")) + single_menu_mode = 1; + } + + /* Initialize curses */ + initscr(); + /* set color theme */ + set_colors(); + + cbreak(); + noecho(); + keypad(stdscr, TRUE); + curs_set(0); + + if (COLS < 75 || LINES < 20) { + endwin(); + printf("Your terminal should have at " + "least 20 lines and 75 columns\n"); + return 1; + } + + notimeout(stdscr, FALSE); +#if NCURSES_REENTRANT + set_escdelay(1); +#else + ESCDELAY = 1; +#endif + + /* set btns menu */ + curses_menu = new_menu(curses_menu_items); + menu_opts_off(curses_menu, O_SHOWDESC); + menu_opts_on(curses_menu, O_SHOWMATCH); + menu_opts_on(curses_menu, O_ONEVALUE); + menu_opts_on(curses_menu, O_NONCYCLIC); + menu_opts_on(curses_menu, O_IGNORECASE); + set_menu_mark(curses_menu, " "); + set_menu_fore(curses_menu, attributes[MAIN_MENU_FORE]); + set_menu_back(curses_menu, attributes[MAIN_MENU_BACK]); + set_menu_grey(curses_menu, attributes[MAIN_MENU_GREY]); + + set_config_filename(conf_get_configname()); + setup_windows(); + + /* check for KEY_FUNC(1) */ + if (has_key(KEY_F(1)) == FALSE) { + show_scroll_win(main_window, + _("Instructions"), + _(menu_no_f_instructions)); + } + + conf_set_message_callback(conf_message_callback); + /* do the work */ + while (!global_exit) { + conf(&rootmenu); + if (!global_exit && do_exit() == 0) + break; + } + /* ok, we are done */ + unpost_menu(curses_menu); + free_menu(curses_menu); + delwin(main_window); + clear(); + refresh(); + endwin(); + return 0; +} + diff --git a/misc/tools/kconfig-frontends/frontends/nconf/nconf.gui.c b/misc/tools/kconfig-frontends/frontends/nconf/nconf.gui.c new file mode 100644 index 0000000000..379003c7a2 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/nconf/nconf.gui.c @@ -0,0 +1,654 @@ +/* + * Copyright (C) 2008 Nir Tzachar 0) + win_rows = msg_lines+4; + else + win_rows = msg_lines+2; + + win = newwin(win_rows, total_width+4, y, x); + keypad(win, TRUE); + menu_win = derwin(win, 1, btns_width, win_rows-2, + 1+(total_width+2-btns_width)/2); + menu = new_menu(btns); + msg_win = derwin(win, win_rows-2, msg_width, 1, + 1+(total_width+2-msg_width)/2); + + set_menu_fore(menu, attributes[DIALOG_MENU_FORE]); + set_menu_back(menu, attributes[DIALOG_MENU_BACK]); + + (void) wattrset(win, attributes[DIALOG_BOX]); + box(win, 0, 0); + + /* print message */ + (void) wattrset(msg_win, attributes[DIALOG_TEXT]); + fill_window(msg_win, msg); + + set_menu_win(menu, win); + set_menu_sub(menu, menu_win); + set_menu_format(menu, 1, btn_num); + menu_opts_off(menu, O_SHOWDESC); + menu_opts_off(menu, O_SHOWMATCH); + menu_opts_on(menu, O_ONEVALUE); + menu_opts_on(menu, O_NONCYCLIC); + set_menu_mark(menu, ""); + post_menu(menu); + + + touchwin(win); + refresh_all_windows(main_window); + while ((res = wgetch(win))) { + switch (res) { + case KEY_LEFT: + menu_driver(menu, REQ_LEFT_ITEM); + break; + case KEY_RIGHT: + menu_driver(menu, REQ_RIGHT_ITEM); + break; + case 10: /* ENTER */ + case 27: /* ESCAPE */ + case ' ': + case KEY_F(F_BACK): + case KEY_F(F_EXIT): + break; + } + touchwin(win); + refresh_all_windows(main_window); + + if (res == 10 || res == ' ') { + res = item_index(current_item(menu)); + break; + } else if (res == 27 || res == KEY_F(F_BACK) || + res == KEY_F(F_EXIT)) { + res = KEY_EXIT; + break; + } + } + + unpost_menu(menu); + free_menu(menu); + for (i = 0; i < btn_num; i++) + free_item(btns[i]); + + delwin(win); + return res; +} + +int dialog_inputbox(WINDOW *main_window, + const char *title, const char *prompt, + const char *init, char **resultp, int *result_len) +{ + int prompt_lines = 0; + int prompt_width = 0; + WINDOW *win; + WINDOW *prompt_win; + WINDOW *form_win; + PANEL *panel; + int i, x, y; + int res = -1; + int cursor_position = strlen(init); + int cursor_form_win; + char *result = *resultp; + + if (strlen(init)+1 > *result_len) { + *result_len = strlen(init)+1; + *resultp = result = realloc(result, *result_len); + } + + /* find the widest line of msg: */ + prompt_lines = get_line_no(prompt); + for (i = 0; i < prompt_lines; i++) { + const char *line = get_line(prompt, i); + int len = get_line_length(line); + prompt_width = max(prompt_width, len); + } + + if (title) + prompt_width = max(prompt_width, strlen(title)); + + /* place dialog in middle of screen */ + y = (LINES-(prompt_lines+4))/2; + x = (COLS-(prompt_width+4))/2; + + strncpy(result, init, *result_len); + + /* create the windows */ + win = newwin(prompt_lines+6, prompt_width+7, y, x); + prompt_win = derwin(win, prompt_lines+1, prompt_width, 2, 2); + form_win = derwin(win, 1, prompt_width, prompt_lines+3, 2); + keypad(form_win, TRUE); + + (void) wattrset(form_win, attributes[INPUT_FIELD]); + + (void) wattrset(win, attributes[INPUT_BOX]); + box(win, 0, 0); + (void) wattrset(win, attributes[INPUT_HEADING]); + if (title) + mvwprintw(win, 0, 3, "%s", title); + + /* print message */ + (void) wattrset(prompt_win, attributes[INPUT_TEXT]); + fill_window(prompt_win, prompt); + + mvwprintw(form_win, 0, 0, "%*s", prompt_width, " "); + cursor_form_win = min(cursor_position, prompt_width-1); + mvwprintw(form_win, 0, 0, "%s", + result + cursor_position-cursor_form_win); + + /* create panels */ + panel = new_panel(win); + + /* show the cursor */ + curs_set(1); + + touchwin(win); + refresh_all_windows(main_window); + while ((res = wgetch(form_win))) { + int len = strlen(result); + switch (res) { + case 10: /* ENTER */ + case 27: /* ESCAPE */ + case KEY_F(F_HELP): + case KEY_F(F_EXIT): + case KEY_F(F_BACK): + break; + case 127: + case KEY_BACKSPACE: + if (cursor_position > 0) { + memmove(&result[cursor_position-1], + &result[cursor_position], + len-cursor_position+1); + cursor_position--; + cursor_form_win--; + len--; + } + break; + case KEY_DC: + if (cursor_position >= 0 && cursor_position < len) { + memmove(&result[cursor_position], + &result[cursor_position+1], + len-cursor_position+1); + len--; + } + break; + case KEY_UP: + case KEY_RIGHT: + if (cursor_position < len) { + cursor_position++; + cursor_form_win++; + } + break; + case KEY_DOWN: + case KEY_LEFT: + if (cursor_position > 0) { + cursor_position--; + cursor_form_win--; + } + break; + case KEY_HOME: + cursor_position = 0; + cursor_form_win = 0; + break; + case KEY_END: + cursor_position = len; + cursor_form_win = min(cursor_position, prompt_width-1); + break; + default: + if ((isgraph(res) || isspace(res))) { + /* one for new char, one for '\0' */ + if (len+2 > *result_len) { + *result_len = len+2; + *resultp = result = realloc(result, + *result_len); + } + /* insert the char at the proper position */ + memmove(&result[cursor_position+1], + &result[cursor_position], + len-cursor_position+1); + result[cursor_position] = res; + cursor_position++; + cursor_form_win++; + len++; + } else { + mvprintw(0, 0, "unknown key: %d\n", res); + } + break; + } + if (cursor_form_win < 0) + cursor_form_win = 0; + else if (cursor_form_win > prompt_width-1) + cursor_form_win = prompt_width-1; + + wmove(form_win, 0, 0); + wclrtoeol(form_win); + mvwprintw(form_win, 0, 0, "%*s", prompt_width, " "); + mvwprintw(form_win, 0, 0, "%s", + result + cursor_position-cursor_form_win); + wmove(form_win, 0, cursor_form_win); + touchwin(win); + refresh_all_windows(main_window); + + if (res == 10) { + res = 0; + break; + } else if (res == 27 || res == KEY_F(F_BACK) || + res == KEY_F(F_EXIT)) { + res = KEY_EXIT; + break; + } else if (res == KEY_F(F_HELP)) { + res = 1; + break; + } + } + + /* hide the cursor */ + curs_set(0); + del_panel(panel); + delwin(prompt_win); + delwin(form_win); + delwin(win); + return res; +} + +/* refresh all windows in the correct order */ +void refresh_all_windows(WINDOW *main_window) +{ + update_panels(); + touchwin(main_window); + refresh(); +} + +/* layman's scrollable window... */ +void show_scroll_win(WINDOW *main_window, + const char *title, + const char *text) +{ + int res; + int total_lines = get_line_no(text); + int x, y; + int start_x = 0, start_y = 0; + int text_lines = 0, text_cols = 0; + int total_cols = 0; + int win_cols = 0; + int win_lines = 0; + int i = 0; + WINDOW *win; + WINDOW *pad; + PANEL *panel; + + /* find the widest line of msg: */ + total_lines = get_line_no(text); + for (i = 0; i < total_lines; i++) { + const char *line = get_line(text, i); + int len = get_line_length(line); + total_cols = max(total_cols, len+2); + } + + /* create the pad */ + pad = newpad(total_lines+10, total_cols+10); + (void) wattrset(pad, attributes[SCROLLWIN_TEXT]); + fill_window(pad, text); + + win_lines = min(total_lines+4, LINES-2); + win_cols = min(total_cols+2, COLS-2); + text_lines = max(win_lines-4, 0); + text_cols = max(win_cols-2, 0); + + /* place window in middle of screen */ + y = (LINES-win_lines)/2; + x = (COLS-win_cols)/2; + + win = newwin(win_lines, win_cols, y, x); + keypad(win, TRUE); + /* show the help in the help window, and show the help panel */ + (void) wattrset(win, attributes[SCROLLWIN_BOX]); + box(win, 0, 0); + (void) wattrset(win, attributes[SCROLLWIN_HEADING]); + mvwprintw(win, 0, 3, " %s ", title); + panel = new_panel(win); + + /* handle scrolling */ + do { + + copywin(pad, win, start_y, start_x, 2, 2, text_lines, + text_cols, 0); + print_in_middle(win, + text_lines+2, + 0, + text_cols, + "", + attributes[DIALOG_MENU_FORE]); + wrefresh(win); + + res = wgetch(win); + switch (res) { + case KEY_NPAGE: + case ' ': + case 'd': + start_y += text_lines-2; + break; + case KEY_PPAGE: + case 'u': + start_y -= text_lines+2; + break; + case KEY_HOME: + start_y = 0; + break; + case KEY_END: + start_y = total_lines-text_lines; + break; + case KEY_DOWN: + case 'j': + start_y++; + break; + case KEY_UP: + case 'k': + start_y--; + break; + case KEY_LEFT: + case 'h': + start_x--; + break; + case KEY_RIGHT: + case 'l': + start_x++; + break; + } + if (res == 10 || res == 27 || res == 'q' || + res == KEY_F(F_HELP) || res == KEY_F(F_BACK) || + res == KEY_F(F_EXIT)) + break; + if (start_y < 0) + start_y = 0; + if (start_y >= total_lines-text_lines) + start_y = total_lines-text_lines; + if (start_x < 0) + start_x = 0; + if (start_x >= total_cols-text_cols) + start_x = total_cols-text_cols; + } while (res); + + del_panel(panel); + delwin(win); + refresh_all_windows(main_window); +} diff --git a/misc/tools/kconfig-frontends/frontends/nconf/nconf.h b/misc/tools/kconfig-frontends/frontends/nconf/nconf.h new file mode 100644 index 0000000000..0d5261705e --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/nconf/nconf.h @@ -0,0 +1,96 @@ +/* + * Copyright (C) 2008 Nir Tzachar +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ncurses.h" + +#define max(a, b) ({\ + typeof(a) _a = a;\ + typeof(b) _b = b;\ + _a > _b ? _a : _b; }) + +#define min(a, b) ({\ + typeof(a) _a = a;\ + typeof(b) _b = b;\ + _a < _b ? _a : _b; }) + +typedef enum { + NORMAL = 1, + MAIN_HEADING, + MAIN_MENU_BOX, + MAIN_MENU_FORE, + MAIN_MENU_BACK, + MAIN_MENU_GREY, + MAIN_MENU_HEADING, + SCROLLWIN_TEXT, + SCROLLWIN_HEADING, + SCROLLWIN_BOX, + DIALOG_TEXT, + DIALOG_MENU_FORE, + DIALOG_MENU_BACK, + DIALOG_BOX, + INPUT_BOX, + INPUT_HEADING, + INPUT_TEXT, + INPUT_FIELD, + FUNCTION_TEXT, + FUNCTION_HIGHLIGHT, + ATTR_MAX +} attributes_t; +extern attributes_t attributes[]; + +typedef enum { + F_HELP = 1, + F_SYMBOL = 2, + F_INSTS = 3, + F_CONF = 4, + F_BACK = 5, + F_SAVE = 6, + F_LOAD = 7, + F_SEARCH = 8, + F_EXIT = 9, +} function_key; + +void set_colors(void); + +/* this changes the windows attributes !!! */ +void print_in_middle(WINDOW *win, + int starty, + int startx, + int width, + const char *string, + chtype color); +int get_line_length(const char *line); +int get_line_no(const char *text); +const char *get_line(const char *text, int line_no); +void fill_window(WINDOW *win, const char *text); +int btn_dialog(WINDOW *main_window, const char *msg, int btn_num, ...); +int dialog_inputbox(WINDOW *main_window, + const char *title, const char *prompt, + const char *init, char **resultp, int *result_len); +void refresh_all_windows(WINDOW *main_window); +void show_scroll_win(WINDOW *main_window, + const char *title, + const char *text); diff --git a/misc/tools/kconfig-frontends/frontends/qconf/Makefile.am b/misc/tools/kconfig-frontends/frontends/qconf/Makefile.am new file mode 100644 index 0000000000..adbcc1e463 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/qconf/Makefile.am @@ -0,0 +1,23 @@ +bin_PROGRAMS = qconf + +qconf_SOURCES = qconf.cc qconf.h +BUILT_SOURCES = qconf.moc +qconf_CPPFLAGS = $(AM_CPPFLAGS) \ + $(intl_CPPFLAGS) \ + -I$(top_srcdir)/libs/parser \ + -I$(top_builddir)/libs/images +qconf_CXXFLAGS = $(AM_CXXFLAGS) \ + $(kf_CFLAGS) \ + $(qt4_CFLAGS) +qconf_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(top_builddir)/libs/images/libkconfig-images.a \ + $(intl_LIBS) $(qt4_LIBS) $(qconf_EXTRA_LIBS) +CLEANFILES = qconf.moc +EXTRA_DIST = qconf.cc.patch + +AM_V_MOC = $(AM_V_MOC_$(V)) +AM_V_MOC_ = $(AM_V_MOC_$(AM_DEFAULT_VERBOSITY)) +AM_V_MOC_0 = @echo " MOC " $@; + +.h.moc: + $(AM_V_MOC)$(MOC) -i $< -o $@ diff --git a/misc/tools/kconfig-frontends/frontends/qconf/Makefile.in b/misc/tools/kconfig-frontends/frontends/qconf/Makefile.in new file mode 100644 index 0000000000..ca5c99be4a --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/qconf/Makefile.in @@ -0,0 +1,636 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ + +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +bin_PROGRAMS = qconf$(EXEEXT) +subdir = frontends/qconf +DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +am__installdirs = "$(DESTDIR)$(bindir)" +PROGRAMS = $(bin_PROGRAMS) +am_qconf_OBJECTS = qconf-qconf.$(OBJEXT) +qconf_OBJECTS = $(am_qconf_OBJECTS) +am__DEPENDENCIES_1 = +qconf_DEPENDENCIES = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(top_builddir)/libs/images/libkconfig-images.a \ + $(am__DEPENDENCIES_1) $(am__DEPENDENCIES_1) \ + $(am__DEPENDENCIES_1) +AM_V_lt = $(am__v_lt_$(V)) +am__v_lt_ = $(am__v_lt_$(AM_DEFAULT_VERBOSITY)) +am__v_lt_0 = --silent +qconf_LINK = $(LIBTOOL) $(AM_V_lt) --tag=CXX $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CXXLD) $(qconf_CXXFLAGS) \ + $(CXXFLAGS) $(AM_LDFLAGS) $(LDFLAGS) -o $@ +DEFAULT_INCLUDES = -I.@am__isrc@ -I$(top_builddir)/scripts/.autostuff +depcomp = $(SHELL) $(top_srcdir)/scripts/.autostuff/scripts/depcomp +am__depfiles_maybe = depfiles +am__mv = mv -f +CXXCOMPILE = $(CXX) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) \ + $(AM_CPPFLAGS) $(CPPFLAGS) $(AM_CXXFLAGS) $(CXXFLAGS) +LTCXXCOMPILE = $(LIBTOOL) $(AM_V_lt) --tag=CXX $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(CXX) $(DEFS) \ + $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) $(CPPFLAGS) \ + $(AM_CXXFLAGS) $(CXXFLAGS) +AM_V_CXX = $(am__v_CXX_$(V)) +am__v_CXX_ = $(am__v_CXX_$(AM_DEFAULT_VERBOSITY)) +am__v_CXX_0 = @echo " CXX " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +CXXLD = $(CXX) +CXXLINK = $(LIBTOOL) $(AM_V_lt) --tag=CXX $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CXXLD) $(AM_CXXFLAGS) \ + $(CXXFLAGS) $(AM_LDFLAGS) $(LDFLAGS) -o $@ +AM_V_CXXLD = $(am__v_CXXLD_$(V)) +am__v_CXXLD_ = $(am__v_CXXLD_$(AM_DEFAULT_VERBOSITY)) +am__v_CXXLD_0 = @echo " CXXLD " $@; +COMPILE = $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) \ + $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) +LTCOMPILE = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) \ + $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) $(CPPFLAGS) \ + $(AM_CFLAGS) $(CFLAGS) +AM_V_CC = $(am__v_CC_$(V)) +am__v_CC_ = $(am__v_CC_$(AM_DEFAULT_VERBOSITY)) +am__v_CC_0 = @echo " CC " $@; +CCLD = $(CC) +LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(AM_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +AM_V_CCLD = $(am__v_CCLD_$(V)) +am__v_CCLD_ = $(am__v_CCLD_$(AM_DEFAULT_VERBOSITY)) +am__v_CCLD_0 = @echo " CCLD " $@; +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +SOURCES = $(qconf_SOURCES) +DIST_SOURCES = $(qconf_SOURCES) +ETAGS = etags +CTAGS = ctags +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +qconf_SOURCES = qconf.cc qconf.h +BUILT_SOURCES = qconf.moc +qconf_CPPFLAGS = $(AM_CPPFLAGS) \ + $(intl_CPPFLAGS) \ + -I$(top_srcdir)/libs/parser \ + -I$(top_builddir)/libs/images + +qconf_CXXFLAGS = $(AM_CXXFLAGS) \ + $(kf_CFLAGS) \ + $(qt4_CFLAGS) + +qconf_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(top_builddir)/libs/images/libkconfig-images.a \ + $(intl_LIBS) $(qt4_LIBS) $(qconf_EXTRA_LIBS) + +CLEANFILES = qconf.moc +EXTRA_DIST = qconf.cc.patch +AM_V_MOC = $(AM_V_MOC_$(V)) +AM_V_MOC_ = $(AM_V_MOC_$(AM_DEFAULT_VERBOSITY)) +AM_V_MOC_0 = @echo " MOC " $@; +all: $(BUILT_SOURCES) + $(MAKE) $(AM_MAKEFLAGS) all-am + +.SUFFIXES: +.SUFFIXES: .cc .h .lo .moc .o .obj +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign frontends/qconf/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign frontends/qconf/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): +install-binPROGRAMS: $(bin_PROGRAMS) + @$(NORMAL_INSTALL) + test -z "$(bindir)" || $(MKDIR_P) "$(DESTDIR)$(bindir)" + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + for p in $$list; do echo "$$p $$p"; done | \ + sed 's/$(EXEEXT)$$//' | \ + while read p p1; do if test -f $$p || test -f $$p1; \ + then echo "$$p"; echo "$$p"; else :; fi; \ + done | \ + sed -e 'p;s,.*/,,;n;h' -e 's|.*|.|' \ + -e 'p;x;s,.*/,,;s/$(EXEEXT)$$//;$(transform);s/$$/$(EXEEXT)/' | \ + sed 'N;N;N;s,\n, ,g' | \ + $(AWK) 'BEGIN { files["."] = ""; dirs["."] = 1 } \ + { d=$$3; if (dirs[d] != 1) { print "d", d; dirs[d] = 1 } \ + if ($$2 == $$4) files[d] = files[d] " " $$1; \ + else { print "f", $$3 "/" $$4, $$1; } } \ + END { for (d in files) print "f", d, files[d] }' | \ + while read type dir files; do \ + if test "$$dir" = .; then dir=; else dir=/$$dir; fi; \ + test -z "$$files" || { \ + echo " $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files '$(DESTDIR)$(bindir)$$dir'"; \ + $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files "$(DESTDIR)$(bindir)$$dir" || exit $$?; \ + } \ + ; done + +uninstall-binPROGRAMS: + @$(NORMAL_UNINSTALL) + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + files=`for p in $$list; do echo "$$p"; done | \ + sed -e 'h;s,^.*/,,;s/$(EXEEXT)$$//;$(transform)' \ + -e 's/$$/$(EXEEXT)/' `; \ + test -n "$$list" || exit 0; \ + echo " ( cd '$(DESTDIR)$(bindir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(bindir)" && rm -f $$files + +clean-binPROGRAMS: + @list='$(bin_PROGRAMS)'; test -n "$$list" || exit 0; \ + echo " rm -f" $$list; \ + rm -f $$list || exit $$?; \ + test -n "$(EXEEXT)" || exit 0; \ + list=`for p in $$list; do echo "$$p"; done | sed 's/$(EXEEXT)$$//'`; \ + echo " rm -f" $$list; \ + rm -f $$list +qconf$(EXEEXT): $(qconf_OBJECTS) $(qconf_DEPENDENCIES) + @rm -f qconf$(EXEEXT) + $(AM_V_CXXLD)$(qconf_LINK) $(qconf_OBJECTS) $(qconf_LDADD) $(LIBS) + +mostlyclean-compile: + -rm -f *.$(OBJEXT) + +distclean-compile: + -rm -f *.tab.c + +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/qconf-qconf.Po@am__quote@ + +.cc.o: +@am__fastdepCXX_TRUE@ $(AM_V_CXX)$(CXXCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCXX_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCXX_FALSE@ $(AM_V_CXX) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCXX_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCXX_FALSE@ DEPDIR=$(DEPDIR) $(CXXDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCXX_FALSE@ $(CXXCOMPILE) -c -o $@ $< + +.cc.obj: +@am__fastdepCXX_TRUE@ $(AM_V_CXX)$(CXXCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ `$(CYGPATH_W) '$<'` +@am__fastdepCXX_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCXX_FALSE@ $(AM_V_CXX) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCXX_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCXX_FALSE@ DEPDIR=$(DEPDIR) $(CXXDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCXX_FALSE@ $(CXXCOMPILE) -c -o $@ `$(CYGPATH_W) '$<'` + +.cc.lo: +@am__fastdepCXX_TRUE@ $(AM_V_CXX)$(LTCXXCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCXX_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Plo +@am__fastdepCXX_FALSE@ $(AM_V_CXX) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCXX_FALSE@ source='$<' object='$@' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCXX_FALSE@ DEPDIR=$(DEPDIR) $(CXXDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCXX_FALSE@ $(LTCXXCOMPILE) -c -o $@ $< + +qconf-qconf.o: qconf.cc +@am__fastdepCXX_TRUE@ $(AM_V_CXX)$(CXX) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(qconf_CPPFLAGS) $(CPPFLAGS) $(qconf_CXXFLAGS) $(CXXFLAGS) -MT qconf-qconf.o -MD -MP -MF $(DEPDIR)/qconf-qconf.Tpo -c -o qconf-qconf.o `test -f 'qconf.cc' || echo '$(srcdir)/'`qconf.cc +@am__fastdepCXX_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/qconf-qconf.Tpo $(DEPDIR)/qconf-qconf.Po +@am__fastdepCXX_FALSE@ $(AM_V_CXX) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCXX_FALSE@ source='qconf.cc' object='qconf-qconf.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCXX_FALSE@ DEPDIR=$(DEPDIR) $(CXXDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCXX_FALSE@ $(CXX) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(qconf_CPPFLAGS) $(CPPFLAGS) $(qconf_CXXFLAGS) $(CXXFLAGS) -c -o qconf-qconf.o `test -f 'qconf.cc' || echo '$(srcdir)/'`qconf.cc + +qconf-qconf.obj: qconf.cc +@am__fastdepCXX_TRUE@ $(AM_V_CXX)$(CXX) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(qconf_CPPFLAGS) $(CPPFLAGS) $(qconf_CXXFLAGS) $(CXXFLAGS) -MT qconf-qconf.obj -MD -MP -MF $(DEPDIR)/qconf-qconf.Tpo -c -o qconf-qconf.obj `if test -f 'qconf.cc'; then $(CYGPATH_W) 'qconf.cc'; else $(CYGPATH_W) '$(srcdir)/qconf.cc'; fi` +@am__fastdepCXX_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/qconf-qconf.Tpo $(DEPDIR)/qconf-qconf.Po +@am__fastdepCXX_FALSE@ $(AM_V_CXX) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCXX_FALSE@ source='qconf.cc' object='qconf-qconf.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCXX_FALSE@ DEPDIR=$(DEPDIR) $(CXXDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCXX_FALSE@ $(CXX) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(qconf_CPPFLAGS) $(CPPFLAGS) $(qconf_CXXFLAGS) $(CXXFLAGS) -c -o qconf-qconf.obj `if test -f 'qconf.cc'; then $(CYGPATH_W) 'qconf.cc'; else $(CYGPATH_W) '$(srcdir)/qconf.cc'; fi` + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: $(BUILT_SOURCES) + $(MAKE) $(AM_MAKEFLAGS) check-am +all-am: Makefile $(PROGRAMS) +installdirs: + for dir in "$(DESTDIR)$(bindir)"; do \ + test -z "$$dir" || $(MKDIR_P) "$$dir"; \ + done +install: $(BUILT_SOURCES) + $(MAKE) $(AM_MAKEFLAGS) install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + -test -z "$(CLEANFILES)" || rm -f $(CLEANFILES) + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." + -test -z "$(BUILT_SOURCES)" || rm -f $(BUILT_SOURCES) +clean: clean-am + +clean-am: clean-binPROGRAMS clean-generic clean-libtool mostlyclean-am + +distclean: distclean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +distclean-am: clean-am distclean-compile distclean-generic \ + distclean-tags + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: install-binPROGRAMS + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: uninstall-binPROGRAMS + +.MAKE: all check install install-am install-strip + +.PHONY: CTAGS GTAGS all all-am check check-am clean clean-binPROGRAMS \ + clean-generic clean-libtool ctags distclean distclean-compile \ + distclean-generic distclean-libtool distclean-tags distdir dvi \ + dvi-am html html-am info info-am install install-am \ + install-binPROGRAMS install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-compile mostlyclean-generic mostlyclean-libtool \ + pdf pdf-am ps ps-am tags uninstall uninstall-am \ + uninstall-binPROGRAMS + + +.h.moc: + $(AM_V_MOC)$(MOC) -i $< -o $@ + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/frontends/qconf/qconf.cc b/misc/tools/kconfig-frontends/frontends/qconf/qconf.cc new file mode 100644 index 0000000000..1b2b0864b5 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/qconf/qconf.cc @@ -0,0 +1,1789 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#include + +#if QT_VERSION < 0x040000 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#else +#include +#include +#include +#include +#include +#include +#include +#include +#include +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "lkc.h" +#include "qconf.h" + +#include "qconf.moc" +#include "images.h" + +#ifdef _ +# undef _ +# define _ qgettext +#endif + +static QApplication *configApp; +static ConfigSettings *configSettings; + +Q3Action *ConfigMainWindow::saveAction; + +static inline QString qgettext(const char* str) +{ + return QString::fromLocal8Bit(gettext(str)); +} + +static inline QString qgettext(const QString& str) +{ + return QString::fromLocal8Bit(gettext(str.latin1())); +} + +/** + * Reads a list of integer values from the application settings. + */ +Q3ValueList ConfigSettings::readSizes(const QString& key, bool *ok) +{ + Q3ValueList result; + QStringList entryList = readListEntry(key, ok); + QStringList::Iterator it; + + for (it = entryList.begin(); it != entryList.end(); ++it) + result.push_back((*it).toInt()); + + return result; +} + +/** + * Writes a list of integer values to the application settings. + */ +bool ConfigSettings::writeSizes(const QString& key, const Q3ValueList& value) +{ + QStringList stringList; + Q3ValueList::ConstIterator it; + + for (it = value.begin(); it != value.end(); ++it) + stringList.push_back(QString::number(*it)); + return writeEntry(key, stringList); +} + + +/* + * set the new data + * TODO check the value + */ +void ConfigItem::okRename(int col) +{ + Parent::okRename(col); + sym_set_string_value(menu->sym, text(dataColIdx).latin1()); + listView()->updateList(this); +} + +/* + * update the displayed of a menu entry + */ +void ConfigItem::updateMenu(void) +{ + ConfigList* list; + struct symbol* sym; + struct property *prop; + QString prompt; + int type; + tristate expr; + + list = listView(); + if (goParent) { + setPixmap(promptColIdx, list->menuBackPix); + prompt = ".."; + goto set_prompt; + } + + sym = menu->sym; + prop = menu->prompt; + prompt = _(menu_get_prompt(menu)); + + if (prop) switch (prop->type) { + case P_MENU: + if (list->mode == singleMode || list->mode == symbolMode) { + /* a menuconfig entry is displayed differently + * depending whether it's at the view root or a child. + */ + if (sym && list->rootEntry == menu) + break; + setPixmap(promptColIdx, list->menuPix); + } else { + if (sym) + break; + setPixmap(promptColIdx, 0); + } + goto set_prompt; + case P_COMMENT: + setPixmap(promptColIdx, 0); + goto set_prompt; + default: + ; + } + if (!sym) + goto set_prompt; + + setText(nameColIdx, QString::fromLocal8Bit(sym->name)); + + type = sym_get_type(sym); + switch (type) { + case S_BOOLEAN: + case S_TRISTATE: + char ch; + + if (!sym_is_changable(sym) && list->optMode == normalOpt) { + setPixmap(promptColIdx, 0); + setText(noColIdx, QString::null); + setText(modColIdx, QString::null); + setText(yesColIdx, QString::null); + break; + } + expr = sym_get_tristate_value(sym); + switch (expr) { + case yes: + if (sym_is_choice_value(sym) && type == S_BOOLEAN) + setPixmap(promptColIdx, list->choiceYesPix); + else + setPixmap(promptColIdx, list->symbolYesPix); + setText(yesColIdx, "Y"); + ch = 'Y'; + break; + case mod: + setPixmap(promptColIdx, list->symbolModPix); + setText(modColIdx, "M"); + ch = 'M'; + break; + default: + if (sym_is_choice_value(sym) && type == S_BOOLEAN) + setPixmap(promptColIdx, list->choiceNoPix); + else + setPixmap(promptColIdx, list->symbolNoPix); + setText(noColIdx, "N"); + ch = 'N'; + break; + } + if (expr != no) + setText(noColIdx, sym_tristate_within_range(sym, no) ? "_" : 0); + if (expr != mod) + setText(modColIdx, sym_tristate_within_range(sym, mod) ? "_" : 0); + if (expr != yes) + setText(yesColIdx, sym_tristate_within_range(sym, yes) ? "_" : 0); + + setText(dataColIdx, QChar(ch)); + break; + case S_INT: + case S_HEX: + case S_STRING: + const char* data; + + data = sym_get_string_value(sym); + + int i = list->mapIdx(dataColIdx); + if (i >= 0) + setRenameEnabled(i, TRUE); + setText(dataColIdx, data); + if (type == S_STRING) + prompt = QString("%1: %2").arg(prompt).arg(data); + else + prompt = QString("(%2) %1").arg(prompt).arg(data); + break; + } + if (!sym_has_value(sym) && visible) + prompt += _(" (NEW)"); +set_prompt: + setText(promptColIdx, prompt); +} + +void ConfigItem::testUpdateMenu(bool v) +{ + ConfigItem* i; + + visible = v; + if (!menu) + return; + + sym_calc_value(menu->sym); + if (menu->flags & MENU_CHANGED) { + /* the menu entry changed, so update all list items */ + menu->flags &= ~MENU_CHANGED; + for (i = (ConfigItem*)menu->data; i; i = i->nextItem) + i->updateMenu(); + } else if (listView()->updateAll) + updateMenu(); +} + +void ConfigItem::paintCell(QPainter* p, const QColorGroup& cg, int column, int width, int align) +{ + ConfigList* list = listView(); + + if (visible) { + if (isSelected() && !list->hasFocus() && list->mode == menuMode) + Parent::paintCell(p, list->inactivedColorGroup, column, width, align); + else + Parent::paintCell(p, cg, column, width, align); + } else + Parent::paintCell(p, list->disabledColorGroup, column, width, align); +} + +/* + * construct a menu entry + */ +void ConfigItem::init(void) +{ + if (menu) { + ConfigList* list = listView(); + nextItem = (ConfigItem*)menu->data; + menu->data = this; + + if (list->mode != fullMode) + setOpen(TRUE); + sym_calc_value(menu->sym); + } + updateMenu(); +} + +/* + * destruct a menu entry + */ +ConfigItem::~ConfigItem(void) +{ + if (menu) { + ConfigItem** ip = (ConfigItem**)&menu->data; + for (; *ip; ip = &(*ip)->nextItem) { + if (*ip == this) { + *ip = nextItem; + break; + } + } + } +} + +ConfigLineEdit::ConfigLineEdit(ConfigView* parent) + : Parent(parent) +{ + connect(this, SIGNAL(lostFocus()), SLOT(hide())); +} + +void ConfigLineEdit::show(ConfigItem* i) +{ + item = i; + if (sym_get_string_value(item->menu->sym)) + setText(QString::fromLocal8Bit(sym_get_string_value(item->menu->sym))); + else + setText(QString::null); + Parent::show(); + setFocus(); +} + +void ConfigLineEdit::keyPressEvent(QKeyEvent* e) +{ + switch (e->key()) { + case Qt::Key_Escape: + break; + case Qt::Key_Return: + case Qt::Key_Enter: + sym_set_string_value(item->menu->sym, text().latin1()); + parent()->updateList(item); + break; + default: + Parent::keyPressEvent(e); + return; + } + e->accept(); + parent()->list->setFocus(); + hide(); +} + +ConfigList::ConfigList(ConfigView* p, const char *name) + : Parent(p, name), + updateAll(false), + symbolYesPix(xpm_symbol_yes), symbolModPix(xpm_symbol_mod), symbolNoPix(xpm_symbol_no), + choiceYesPix(xpm_choice_yes), choiceNoPix(xpm_choice_no), + menuPix(xpm_menu), menuInvPix(xpm_menu_inv), menuBackPix(xpm_menuback), voidPix(xpm_void), + showName(false), showRange(false), showData(false), optMode(normalOpt), + rootEntry(0), headerPopup(0) +{ + int i; + + setSorting(-1); + setRootIsDecorated(TRUE); + disabledColorGroup = palette().active(); + disabledColorGroup.setColor(QColorGroup::Text, palette().disabled().text()); + inactivedColorGroup = palette().active(); + inactivedColorGroup.setColor(QColorGroup::Highlight, palette().disabled().highlight()); + + connect(this, SIGNAL(selectionChanged(void)), + SLOT(updateSelection(void))); + + if (name) { + configSettings->beginGroup(name); + showName = configSettings->readBoolEntry("/showName", false); + showRange = configSettings->readBoolEntry("/showRange", false); + showData = configSettings->readBoolEntry("/showData", false); + optMode = (enum optionMode)configSettings->readNumEntry("/optionMode", false); + configSettings->endGroup(); + connect(configApp, SIGNAL(aboutToQuit()), SLOT(saveSettings())); + } + + for (i = 0; i < colNr; i++) + colMap[i] = colRevMap[i] = -1; + addColumn(promptColIdx, _("Option")); + + reinit(); +} + +bool ConfigList::menuSkip(struct menu *menu) +{ + if (optMode == normalOpt && menu_is_visible(menu)) + return false; + if (optMode == promptOpt && menu_has_prompt(menu)) + return false; + if (optMode == allOpt) + return false; + return true; +} + +void ConfigList::reinit(void) +{ + removeColumn(dataColIdx); + removeColumn(yesColIdx); + removeColumn(modColIdx); + removeColumn(noColIdx); + removeColumn(nameColIdx); + + if (showName) + addColumn(nameColIdx, _("Name")); + if (showRange) { + addColumn(noColIdx, "N"); + addColumn(modColIdx, "M"); + addColumn(yesColIdx, "Y"); + } + if (showData) + addColumn(dataColIdx, _("Value")); + + updateListAll(); +} + +void ConfigList::saveSettings(void) +{ + if (name()) { + configSettings->beginGroup(name()); + configSettings->writeEntry("/showName", showName); + configSettings->writeEntry("/showRange", showRange); + configSettings->writeEntry("/showData", showData); + configSettings->writeEntry("/optionMode", (int)optMode); + configSettings->endGroup(); + } +} + +ConfigItem* ConfigList::findConfigItem(struct menu *menu) +{ + ConfigItem* item = (ConfigItem*)menu->data; + + for (; item; item = item->nextItem) { + if (this == item->listView()) + break; + } + + return item; +} + +void ConfigList::updateSelection(void) +{ + struct menu *menu; + enum prop_type type; + + ConfigItem* item = (ConfigItem*)selectedItem(); + if (!item) + return; + + menu = item->menu; + emit menuChanged(menu); + if (!menu) + return; + type = menu->prompt ? menu->prompt->type : P_UNKNOWN; + if (mode == menuMode && type == P_MENU) + emit menuSelected(menu); +} + +void ConfigList::updateList(ConfigItem* item) +{ + ConfigItem* last = 0; + + if (!rootEntry) { + if (mode != listMode) + goto update; + Q3ListViewItemIterator it(this); + ConfigItem* item; + + for (; it.current(); ++it) { + item = (ConfigItem*)it.current(); + if (!item->menu) + continue; + item->testUpdateMenu(menu_is_visible(item->menu)); + } + return; + } + + if (rootEntry != &rootmenu && (mode == singleMode || + (mode == symbolMode && rootEntry->parent != &rootmenu))) { + item = firstChild(); + if (!item) + item = new ConfigItem(this, 0, true); + last = item; + } + if ((mode == singleMode || (mode == symbolMode && !(rootEntry->flags & MENU_ROOT))) && + rootEntry->sym && rootEntry->prompt) { + item = last ? last->nextSibling() : firstChild(); + if (!item) + item = new ConfigItem(this, last, rootEntry, true); + else + item->testUpdateMenu(true); + + updateMenuList(item, rootEntry); + triggerUpdate(); + return; + } +update: + updateMenuList(this, rootEntry); + triggerUpdate(); +} + +void ConfigList::setValue(ConfigItem* item, tristate val) +{ + struct symbol* sym; + int type; + tristate oldval; + + sym = item->menu ? item->menu->sym : 0; + if (!sym) + return; + + type = sym_get_type(sym); + switch (type) { + case S_BOOLEAN: + case S_TRISTATE: + oldval = sym_get_tristate_value(sym); + + if (!sym_set_tristate_value(sym, val)) + return; + if (oldval == no && item->menu->list) + item->setOpen(TRUE); + parent()->updateList(item); + break; + } +} + +void ConfigList::changeValue(ConfigItem* item) +{ + struct symbol* sym; + struct menu* menu; + int type, oldexpr, newexpr; + + menu = item->menu; + if (!menu) + return; + sym = menu->sym; + if (!sym) { + if (item->menu->list) + item->setOpen(!item->isOpen()); + return; + } + + type = sym_get_type(sym); + switch (type) { + case S_BOOLEAN: + case S_TRISTATE: + oldexpr = sym_get_tristate_value(sym); + newexpr = sym_toggle_tristate_value(sym); + if (item->menu->list) { + if (oldexpr == newexpr) + item->setOpen(!item->isOpen()); + else if (oldexpr == no) + item->setOpen(TRUE); + } + if (oldexpr != newexpr) + parent()->updateList(item); + break; + case S_INT: + case S_HEX: + case S_STRING: + if (colMap[dataColIdx] >= 0) + item->startRename(colMap[dataColIdx]); + else + parent()->lineEdit->show(item); + break; + } +} + +void ConfigList::setRootMenu(struct menu *menu) +{ + enum prop_type type; + + if (rootEntry == menu) + return; + type = menu && menu->prompt ? menu->prompt->type : P_UNKNOWN; + if (type != P_MENU) + return; + updateMenuList(this, 0); + rootEntry = menu; + updateListAll(); + setSelected(currentItem(), hasFocus()); + ensureItemVisible(currentItem()); +} + +void ConfigList::setParentMenu(void) +{ + ConfigItem* item; + struct menu *oldroot; + + oldroot = rootEntry; + if (rootEntry == &rootmenu) + return; + setRootMenu(menu_get_parent_menu(rootEntry->parent)); + + Q3ListViewItemIterator it(this); + for (; (item = (ConfigItem*)it.current()); it++) { + if (item->menu == oldroot) { + setCurrentItem(item); + ensureItemVisible(item); + break; + } + } +} + +/* + * update all the children of a menu entry + * removes/adds the entries from the parent widget as necessary + * + * parent: either the menu list widget or a menu entry widget + * menu: entry to be updated + */ +template +void ConfigList::updateMenuList(P* parent, struct menu* menu) +{ + struct menu* child; + ConfigItem* item; + ConfigItem* last; + bool visible; + enum prop_type type; + + if (!menu) { + while ((item = parent->firstChild())) + delete item; + return; + } + + last = parent->firstChild(); + if (last && !last->goParent) + last = 0; + for (child = menu->list; child; child = child->next) { + item = last ? last->nextSibling() : parent->firstChild(); + type = child->prompt ? child->prompt->type : P_UNKNOWN; + + switch (mode) { + case menuMode: + if (!(child->flags & MENU_ROOT)) + goto hide; + break; + case symbolMode: + if (child->flags & MENU_ROOT) + goto hide; + break; + default: + break; + } + + visible = menu_is_visible(child); + if (!menuSkip(child)) { + if (!child->sym && !child->list && !child->prompt) + continue; + if (!item || item->menu != child) + item = new ConfigItem(parent, last, child, visible); + else + item->testUpdateMenu(visible); + + if (mode == fullMode || mode == menuMode || type != P_MENU) + updateMenuList(item, child); + else + updateMenuList(item, 0); + last = item; + continue; + } + hide: + if (item && item->menu == child) { + last = parent->firstChild(); + if (last == item) + last = 0; + else while (last->nextSibling() != item) + last = last->nextSibling(); + delete item; + } + } +} + +void ConfigList::keyPressEvent(QKeyEvent* ev) +{ + Q3ListViewItem* i = currentItem(); + ConfigItem* item; + struct menu *menu; + enum prop_type type; + + if (ev->key() == Qt::Key_Escape && mode != fullMode && mode != listMode) { + emit parentSelected(); + ev->accept(); + return; + } + + if (!i) { + Parent::keyPressEvent(ev); + return; + } + item = (ConfigItem*)i; + + switch (ev->key()) { + case Qt::Key_Return: + case Qt::Key_Enter: + if (item->goParent) { + emit parentSelected(); + break; + } + menu = item->menu; + if (!menu) + break; + type = menu->prompt ? menu->prompt->type : P_UNKNOWN; + if (type == P_MENU && rootEntry != menu && + mode != fullMode && mode != menuMode) { + emit menuSelected(menu); + break; + } + case Qt::Key_Space: + changeValue(item); + break; + case Qt::Key_N: + setValue(item, no); + break; + case Qt::Key_M: + setValue(item, mod); + break; + case Qt::Key_Y: + setValue(item, yes); + break; + default: + Parent::keyPressEvent(ev); + return; + } + ev->accept(); +} + +void ConfigList::contentsMousePressEvent(QMouseEvent* e) +{ + //QPoint p(contentsToViewport(e->pos())); + //printf("contentsMousePressEvent: %d,%d\n", p.x(), p.y()); + Parent::contentsMousePressEvent(e); +} + +void ConfigList::contentsMouseReleaseEvent(QMouseEvent* e) +{ + QPoint p(contentsToViewport(e->pos())); + ConfigItem* item = (ConfigItem*)itemAt(p); + struct menu *menu; + enum prop_type ptype; + const QPixmap* pm; + int idx, x; + + if (!item) + goto skip; + + menu = item->menu; + x = header()->offset() + p.x(); + idx = colRevMap[header()->sectionAt(x)]; + switch (idx) { + case promptColIdx: + pm = item->pixmap(promptColIdx); + if (pm) { + int off = header()->sectionPos(0) + itemMargin() + + treeStepSize() * (item->depth() + (rootIsDecorated() ? 1 : 0)); + if (x >= off && x < off + pm->width()) { + if (item->goParent) { + emit parentSelected(); + break; + } else if (!menu) + break; + ptype = menu->prompt ? menu->prompt->type : P_UNKNOWN; + if (ptype == P_MENU && rootEntry != menu && + mode != fullMode && mode != menuMode) + emit menuSelected(menu); + else + changeValue(item); + } + } + break; + case noColIdx: + setValue(item, no); + break; + case modColIdx: + setValue(item, mod); + break; + case yesColIdx: + setValue(item, yes); + break; + case dataColIdx: + changeValue(item); + break; + } + +skip: + //printf("contentsMouseReleaseEvent: %d,%d\n", p.x(), p.y()); + Parent::contentsMouseReleaseEvent(e); +} + +void ConfigList::contentsMouseMoveEvent(QMouseEvent* e) +{ + //QPoint p(contentsToViewport(e->pos())); + //printf("contentsMouseMoveEvent: %d,%d\n", p.x(), p.y()); + Parent::contentsMouseMoveEvent(e); +} + +void ConfigList::contentsMouseDoubleClickEvent(QMouseEvent* e) +{ + QPoint p(contentsToViewport(e->pos())); + ConfigItem* item = (ConfigItem*)itemAt(p); + struct menu *menu; + enum prop_type ptype; + + if (!item) + goto skip; + if (item->goParent) { + emit parentSelected(); + goto skip; + } + menu = item->menu; + if (!menu) + goto skip; + ptype = menu->prompt ? menu->prompt->type : P_UNKNOWN; + if (ptype == P_MENU && (mode == singleMode || mode == symbolMode)) + emit menuSelected(menu); + else if (menu->sym) + changeValue(item); + +skip: + //printf("contentsMouseDoubleClickEvent: %d,%d\n", p.x(), p.y()); + Parent::contentsMouseDoubleClickEvent(e); +} + +void ConfigList::focusInEvent(QFocusEvent *e) +{ + struct menu *menu = NULL; + + Parent::focusInEvent(e); + + ConfigItem* item = (ConfigItem *)currentItem(); + if (item) { + setSelected(item, TRUE); + menu = item->menu; + } + emit gotFocus(menu); +} + +void ConfigList::contextMenuEvent(QContextMenuEvent *e) +{ + if (e->y() <= header()->geometry().bottom()) { + if (!headerPopup) { + Q3Action *action; + + headerPopup = new Q3PopupMenu(this); + action = new Q3Action(NULL, _("Show Name"), 0, this); + action->setToggleAction(TRUE); + connect(action, SIGNAL(toggled(bool)), + parent(), SLOT(setShowName(bool))); + connect(parent(), SIGNAL(showNameChanged(bool)), + action, SLOT(setOn(bool))); + action->setOn(showName); + action->addTo(headerPopup); + action = new Q3Action(NULL, _("Show Range"), 0, this); + action->setToggleAction(TRUE); + connect(action, SIGNAL(toggled(bool)), + parent(), SLOT(setShowRange(bool))); + connect(parent(), SIGNAL(showRangeChanged(bool)), + action, SLOT(setOn(bool))); + action->setOn(showRange); + action->addTo(headerPopup); + action = new Q3Action(NULL, _("Show Data"), 0, this); + action->setToggleAction(TRUE); + connect(action, SIGNAL(toggled(bool)), + parent(), SLOT(setShowData(bool))); + connect(parent(), SIGNAL(showDataChanged(bool)), + action, SLOT(setOn(bool))); + action->setOn(showData); + action->addTo(headerPopup); + } + headerPopup->exec(e->globalPos()); + e->accept(); + } else + e->ignore(); +} + +ConfigView*ConfigView::viewList; +QAction *ConfigView::showNormalAction; +QAction *ConfigView::showAllAction; +QAction *ConfigView::showPromptAction; + +ConfigView::ConfigView(QWidget* parent, const char *name) + : Parent(parent, name) +{ + list = new ConfigList(this, name); + lineEdit = new ConfigLineEdit(this); + lineEdit->hide(); + + this->nextView = viewList; + viewList = this; +} + +ConfigView::~ConfigView(void) +{ + ConfigView** vp; + + for (vp = &viewList; *vp; vp = &(*vp)->nextView) { + if (*vp == this) { + *vp = nextView; + break; + } + } +} + +void ConfigView::setOptionMode(QAction *act) +{ + if (act == showNormalAction) + list->optMode = normalOpt; + else if (act == showAllAction) + list->optMode = allOpt; + else + list->optMode = promptOpt; + + list->updateListAll(); +} + +void ConfigView::setShowName(bool b) +{ + if (list->showName != b) { + list->showName = b; + list->reinit(); + emit showNameChanged(b); + } +} + +void ConfigView::setShowRange(bool b) +{ + if (list->showRange != b) { + list->showRange = b; + list->reinit(); + emit showRangeChanged(b); + } +} + +void ConfigView::setShowData(bool b) +{ + if (list->showData != b) { + list->showData = b; + list->reinit(); + emit showDataChanged(b); + } +} + +void ConfigList::setAllOpen(bool open) +{ + Q3ListViewItemIterator it(this); + + for (; it.current(); it++) + it.current()->setOpen(open); +} + +void ConfigView::updateList(ConfigItem* item) +{ + ConfigView* v; + + for (v = viewList; v; v = v->nextView) + v->list->updateList(item); +} + +void ConfigView::updateListAll(void) +{ + ConfigView* v; + + for (v = viewList; v; v = v->nextView) + v->list->updateListAll(); +} + +ConfigInfoView::ConfigInfoView(QWidget* parent, const char *name) + : Parent(parent, name), sym(0), _menu(0) +{ + if (name) { + configSettings->beginGroup(name); + _showDebug = configSettings->readBoolEntry("/showDebug", false); + configSettings->endGroup(); + connect(configApp, SIGNAL(aboutToQuit()), SLOT(saveSettings())); + } +} + +void ConfigInfoView::saveSettings(void) +{ + if (name()) { + configSettings->beginGroup(name()); + configSettings->writeEntry("/showDebug", showDebug()); + configSettings->endGroup(); + } +} + +void ConfigInfoView::setShowDebug(bool b) +{ + if (_showDebug != b) { + _showDebug = b; + if (_menu) + menuInfo(); + else if (sym) + symbolInfo(); + emit showDebugChanged(b); + } +} + +void ConfigInfoView::setInfo(struct menu *m) +{ + if (_menu == m) + return; + _menu = m; + sym = NULL; + if (!_menu) + clear(); + else + menuInfo(); +} + +void ConfigInfoView::symbolInfo(void) +{ + QString str; + + str += "Symbol: "; + str += print_filter(sym->name); + str += "

    value: "; + str += print_filter(sym_get_string_value(sym)); + str += "
    visibility: "; + str += sym->visible == yes ? "y" : sym->visible == mod ? "m" : "n"; + str += "
    "; + str += debug_info(sym); + + setText(str); +} + +void ConfigInfoView::menuInfo(void) +{ + struct symbol* sym; + QString head, debug, help; + + sym = _menu->sym; + if (sym) { + if (_menu->prompt) { + head += ""; + head += print_filter(_(_menu->prompt->text)); + head += ""; + if (sym->name) { + head += " ("; + if (showDebug()) + head += QString().sprintf("
    ", sym); + head += print_filter(sym->name); + if (showDebug()) + head += ""; + head += ")"; + } + } else if (sym->name) { + head += ""; + if (showDebug()) + head += QString().sprintf("", sym); + head += print_filter(sym->name); + if (showDebug()) + head += ""; + head += ""; + } + head += "

    "; + + if (showDebug()) + debug = debug_info(sym); + + struct gstr help_gstr = str_new(); + menu_get_ext_help(_menu, &help_gstr); + help = print_filter(str_get(&help_gstr)); + str_free(&help_gstr); + } else if (_menu->prompt) { + head += ""; + head += print_filter(_(_menu->prompt->text)); + head += "

    "; + if (showDebug()) { + if (_menu->prompt->visible.expr) { + debug += "  dep: "; + expr_print(_menu->prompt->visible.expr, expr_print_help, &debug, E_NONE); + debug += "

    "; + } + } + } + if (showDebug()) + debug += QString().sprintf("defined at %s:%d

    ", _menu->file->name, _menu->lineno); + + setText(head + debug + help); +} + +QString ConfigInfoView::debug_info(struct symbol *sym) +{ + QString debug; + + debug += "type: "; + debug += print_filter(sym_type_name(sym->type)); + if (sym_is_choice(sym)) + debug += " (choice)"; + debug += "
    "; + if (sym->rev_dep.expr) { + debug += "reverse dep: "; + expr_print(sym->rev_dep.expr, expr_print_help, &debug, E_NONE); + debug += "
    "; + } + for (struct property *prop = sym->prop; prop; prop = prop->next) { + switch (prop->type) { + case P_PROMPT: + case P_MENU: + debug += QString().sprintf("prompt: ", prop->menu); + debug += print_filter(_(prop->text)); + debug += "
    "; + break; + case P_DEFAULT: + case P_SELECT: + case P_RANGE: + case P_ENV: + debug += prop_get_type_name(prop->type); + debug += ": "; + expr_print(prop->expr, expr_print_help, &debug, E_NONE); + debug += "
    "; + break; + case P_CHOICE: + if (sym_is_choice(sym)) { + debug += "choice: "; + expr_print(prop->expr, expr_print_help, &debug, E_NONE); + debug += "
    "; + } + break; + default: + debug += "unknown property: "; + debug += prop_get_type_name(prop->type); + debug += "
    "; + } + if (prop->visible.expr) { + debug += "    dep: "; + expr_print(prop->visible.expr, expr_print_help, &debug, E_NONE); + debug += "
    "; + } + } + debug += "
    "; + + return debug; +} + +QString ConfigInfoView::print_filter(const QString &str) +{ + QRegExp re("[<>&\"\\n]"); + QString res = str; + for (int i = 0; (i = res.find(re, i)) >= 0;) { + switch (res[i].latin1()) { + case '<': + res.replace(i, 1, "<"); + i += 4; + break; + case '>': + res.replace(i, 1, ">"); + i += 4; + break; + case '&': + res.replace(i, 1, "&"); + i += 5; + break; + case '"': + res.replace(i, 1, """); + i += 6; + break; + case '\n': + res.replace(i, 1, "
    "); + i += 4; + break; + } + } + return res; +} + +void ConfigInfoView::expr_print_help(void *data, struct symbol *sym, const char *str) +{ + QString* text = reinterpret_cast(data); + QString str2 = print_filter(str); + + if (sym && sym->name && !(sym->flags & SYMBOL_CONST)) { + *text += QString().sprintf("", sym); + *text += str2; + *text += ""; + } else + *text += str2; +} + +Q3PopupMenu* ConfigInfoView::createPopupMenu(const QPoint& pos) +{ + Q3PopupMenu* popup = Parent::createPopupMenu(pos); + Q3Action* action = new Q3Action(NULL, _("Show Debug Info"), 0, popup); + action->setToggleAction(TRUE); + connect(action, SIGNAL(toggled(bool)), SLOT(setShowDebug(bool))); + connect(this, SIGNAL(showDebugChanged(bool)), action, SLOT(setOn(bool))); + action->setOn(showDebug()); + popup->insertSeparator(); + action->addTo(popup); + return popup; +} + +void ConfigInfoView::contentsContextMenuEvent(QContextMenuEvent *e) +{ + Parent::contentsContextMenuEvent(e); +} + +ConfigSearchWindow::ConfigSearchWindow(ConfigMainWindow* parent, const char *name) + : Parent(parent, name), result(NULL) +{ + setCaption("Search Config"); + + QVBoxLayout* layout1 = new QVBoxLayout(this, 11, 6); + QHBoxLayout* layout2 = new QHBoxLayout(0, 0, 6); + layout2->addWidget(new QLabel(_("Find:"), this)); + editField = new QLineEdit(this); + connect(editField, SIGNAL(returnPressed()), SLOT(search())); + layout2->addWidget(editField); + searchButton = new QPushButton(_("Search"), this); + searchButton->setAutoDefault(FALSE); + connect(searchButton, SIGNAL(clicked()), SLOT(search())); + layout2->addWidget(searchButton); + layout1->addLayout(layout2); + + split = new QSplitter(this); + split->setOrientation(Qt::Vertical); + list = new ConfigView(split, name); + list->list->mode = listMode; + info = new ConfigInfoView(split, name); + connect(list->list, SIGNAL(menuChanged(struct menu *)), + info, SLOT(setInfo(struct menu *))); + connect(list->list, SIGNAL(menuChanged(struct menu *)), + parent, SLOT(setMenuLink(struct menu *))); + + layout1->addWidget(split); + + if (name) { + int x, y, width, height; + bool ok; + + configSettings->beginGroup(name); + width = configSettings->readNumEntry("/window width", parent->width() / 2); + height = configSettings->readNumEntry("/window height", parent->height() / 2); + resize(width, height); + x = configSettings->readNumEntry("/window x", 0, &ok); + if (ok) + y = configSettings->readNumEntry("/window y", 0, &ok); + if (ok) + move(x, y); + Q3ValueList sizes = configSettings->readSizes("/split", &ok); + if (ok) + split->setSizes(sizes); + configSettings->endGroup(); + connect(configApp, SIGNAL(aboutToQuit()), SLOT(saveSettings())); + } +} + +void ConfigSearchWindow::saveSettings(void) +{ + if (name()) { + configSettings->beginGroup(name()); + configSettings->writeEntry("/window x", pos().x()); + configSettings->writeEntry("/window y", pos().y()); + configSettings->writeEntry("/window width", size().width()); + configSettings->writeEntry("/window height", size().height()); + configSettings->writeSizes("/split", split->sizes()); + configSettings->endGroup(); + } +} + +void ConfigSearchWindow::search(void) +{ + struct symbol **p; + struct property *prop; + ConfigItem *lastItem = NULL; + + free(result); + list->list->clear(); + info->clear(); + + result = sym_re_search(editField->text().latin1()); + if (!result) + return; + for (p = result; *p; p++) { + for_all_prompts((*p), prop) + lastItem = new ConfigItem(list->list, lastItem, prop->menu, + menu_is_visible(prop->menu)); + } +} + +/* + * Construct the complete config widget + */ +ConfigMainWindow::ConfigMainWindow(void) + : searchWindow(0) +{ + QMenuBar* menu; + bool ok; + int x, y, width, height; + char title[256]; + + QDesktopWidget *d = configApp->desktop(); + snprintf(title, sizeof(title), "%s%s", + rootmenu.prompt->text, +#if QT_VERSION < 0x040000 + " (Qt3)" +#else + "" +#endif + ); + setCaption(title); + + width = configSettings->readNumEntry("/window width", d->width() - 64); + height = configSettings->readNumEntry("/window height", d->height() - 64); + resize(width, height); + x = configSettings->readNumEntry("/window x", 0, &ok); + if (ok) + y = configSettings->readNumEntry("/window y", 0, &ok); + if (ok) + move(x, y); + + split1 = new QSplitter(this); + split1->setOrientation(Qt::Horizontal); + setCentralWidget(split1); + + menuView = new ConfigView(split1, "menu"); + menuList = menuView->list; + + split2 = new QSplitter(split1); + split2->setOrientation(Qt::Vertical); + + // create config tree + configView = new ConfigView(split2, "config"); + configList = configView->list; + + helpText = new ConfigInfoView(split2, "help"); + helpText->setTextFormat(Qt::RichText); + + setTabOrder(configList, helpText); + configList->setFocus(); + + menu = menuBar(); + toolBar = new Q3ToolBar("Tools", this); + + backAction = new Q3Action("Back", QPixmap(xpm_back), _("Back"), 0, this); + connect(backAction, SIGNAL(activated()), SLOT(goBack())); + backAction->setEnabled(FALSE); + Q3Action *quitAction = new Q3Action("Quit", _("&Quit"), Qt::CTRL + Qt::Key_Q, this); + connect(quitAction, SIGNAL(activated()), SLOT(close())); + Q3Action *loadAction = new Q3Action("Load", QPixmap(xpm_load), _("&Load"), Qt::CTRL + Qt::Key_L, this); + connect(loadAction, SIGNAL(activated()), SLOT(loadConfig())); + saveAction = new Q3Action("Save", QPixmap(xpm_save), _("&Save"), Qt::CTRL + Qt::Key_S, this); + connect(saveAction, SIGNAL(activated()), SLOT(saveConfig())); + conf_set_changed_callback(conf_changed); + // Set saveAction's initial state + conf_changed(); + Q3Action *saveAsAction = new Q3Action("Save As...", _("Save &As..."), 0, this); + connect(saveAsAction, SIGNAL(activated()), SLOT(saveConfigAs())); + Q3Action *searchAction = new Q3Action("Find", _("&Find"), Qt::CTRL + Qt::Key_F, this); + connect(searchAction, SIGNAL(activated()), SLOT(searchConfig())); + Q3Action *singleViewAction = new Q3Action("Single View", QPixmap(xpm_single_view), _("Single View"), 0, this); + connect(singleViewAction, SIGNAL(activated()), SLOT(showSingleView())); + Q3Action *splitViewAction = new Q3Action("Split View", QPixmap(xpm_split_view), _("Split View"), 0, this); + connect(splitViewAction, SIGNAL(activated()), SLOT(showSplitView())); + Q3Action *fullViewAction = new Q3Action("Full View", QPixmap(xpm_tree_view), _("Full View"), 0, this); + connect(fullViewAction, SIGNAL(activated()), SLOT(showFullView())); + + Q3Action *showNameAction = new Q3Action(NULL, _("Show Name"), 0, this); + showNameAction->setToggleAction(TRUE); + connect(showNameAction, SIGNAL(toggled(bool)), configView, SLOT(setShowName(bool))); + connect(configView, SIGNAL(showNameChanged(bool)), showNameAction, SLOT(setOn(bool))); + showNameAction->setOn(configView->showName()); + Q3Action *showRangeAction = new Q3Action(NULL, _("Show Range"), 0, this); + showRangeAction->setToggleAction(TRUE); + connect(showRangeAction, SIGNAL(toggled(bool)), configView, SLOT(setShowRange(bool))); + connect(configView, SIGNAL(showRangeChanged(bool)), showRangeAction, SLOT(setOn(bool))); + showRangeAction->setOn(configList->showRange); + Q3Action *showDataAction = new Q3Action(NULL, _("Show Data"), 0, this); + showDataAction->setToggleAction(TRUE); + connect(showDataAction, SIGNAL(toggled(bool)), configView, SLOT(setShowData(bool))); + connect(configView, SIGNAL(showDataChanged(bool)), showDataAction, SLOT(setOn(bool))); + showDataAction->setOn(configList->showData); + + QActionGroup *optGroup = new QActionGroup(this); + optGroup->setExclusive(TRUE); + connect(optGroup, SIGNAL(selected(QAction *)), configView, + SLOT(setOptionMode(QAction *))); + connect(optGroup, SIGNAL(selected(QAction *)), menuView, + SLOT(setOptionMode(QAction *))); + +#if QT_VERSION >= 0x040000 + configView->showNormalAction = new QAction(_("Show Normal Options"), optGroup); + configView->showAllAction = new QAction(_("Show All Options"), optGroup); + configView->showPromptAction = new QAction(_("Show Prompt Options"), optGroup); +#else + configView->showNormalAction = new QAction(_("Show Normal Options"), 0, optGroup); + configView->showAllAction = new QAction(_("Show All Options"), 0, optGroup); + configView->showPromptAction = new QAction(_("Show Prompt Options"), 0, optGroup); +#endif + configView->showNormalAction->setToggleAction(TRUE); + configView->showNormalAction->setOn(configList->optMode == normalOpt); + configView->showAllAction->setToggleAction(TRUE); + configView->showAllAction->setOn(configList->optMode == allOpt); + configView->showPromptAction->setToggleAction(TRUE); + configView->showPromptAction->setOn(configList->optMode == promptOpt); + + Q3Action *showDebugAction = new Q3Action(NULL, _("Show Debug Info"), 0, this); + showDebugAction->setToggleAction(TRUE); + connect(showDebugAction, SIGNAL(toggled(bool)), helpText, SLOT(setShowDebug(bool))); + connect(helpText, SIGNAL(showDebugChanged(bool)), showDebugAction, SLOT(setOn(bool))); + showDebugAction->setOn(helpText->showDebug()); + + Q3Action *showIntroAction = new Q3Action(NULL, _("Introduction"), 0, this); + connect(showIntroAction, SIGNAL(activated()), SLOT(showIntro())); + Q3Action *showAboutAction = new Q3Action(NULL, _("About"), 0, this); + connect(showAboutAction, SIGNAL(activated()), SLOT(showAbout())); + + // init tool bar + backAction->addTo(toolBar); + toolBar->addSeparator(); + loadAction->addTo(toolBar); + saveAction->addTo(toolBar); + toolBar->addSeparator(); + singleViewAction->addTo(toolBar); + splitViewAction->addTo(toolBar); + fullViewAction->addTo(toolBar); + + // create config menu + Q3PopupMenu* config = new Q3PopupMenu(this); + menu->insertItem(_("&File"), config); + loadAction->addTo(config); + saveAction->addTo(config); + saveAsAction->addTo(config); + config->insertSeparator(); + quitAction->addTo(config); + + // create edit menu + Q3PopupMenu* editMenu = new Q3PopupMenu(this); + menu->insertItem(_("&Edit"), editMenu); + searchAction->addTo(editMenu); + + // create options menu + Q3PopupMenu* optionMenu = new Q3PopupMenu(this); + menu->insertItem(_("&Option"), optionMenu); + showNameAction->addTo(optionMenu); + showRangeAction->addTo(optionMenu); + showDataAction->addTo(optionMenu); + optionMenu->insertSeparator(); + optGroup->addTo(optionMenu); + optionMenu->insertSeparator(); + + // create help menu + Q3PopupMenu* helpMenu = new Q3PopupMenu(this); + menu->insertSeparator(); + menu->insertItem(_("&Help"), helpMenu); + showIntroAction->addTo(helpMenu); + showAboutAction->addTo(helpMenu); + + connect(configList, SIGNAL(menuChanged(struct menu *)), + helpText, SLOT(setInfo(struct menu *))); + connect(configList, SIGNAL(menuSelected(struct menu *)), + SLOT(changeMenu(struct menu *))); + connect(configList, SIGNAL(parentSelected()), + SLOT(goBack())); + connect(menuList, SIGNAL(menuChanged(struct menu *)), + helpText, SLOT(setInfo(struct menu *))); + connect(menuList, SIGNAL(menuSelected(struct menu *)), + SLOT(changeMenu(struct menu *))); + + connect(configList, SIGNAL(gotFocus(struct menu *)), + helpText, SLOT(setInfo(struct menu *))); + connect(menuList, SIGNAL(gotFocus(struct menu *)), + helpText, SLOT(setInfo(struct menu *))); + connect(menuList, SIGNAL(gotFocus(struct menu *)), + SLOT(listFocusChanged(void))); + connect(helpText, SIGNAL(menuSelected(struct menu *)), + SLOT(setMenuLink(struct menu *))); + + QString listMode = configSettings->readEntry("/listMode", "symbol"); + if (listMode == "single") + showSingleView(); + else if (listMode == "full") + showFullView(); + else /*if (listMode == "split")*/ + showSplitView(); + + // UI setup done, restore splitter positions + Q3ValueList sizes = configSettings->readSizes("/split1", &ok); + if (ok) + split1->setSizes(sizes); + + sizes = configSettings->readSizes("/split2", &ok); + if (ok) + split2->setSizes(sizes); +} + +void ConfigMainWindow::loadConfig(void) +{ + QString s = Q3FileDialog::getOpenFileName(conf_get_configname(), NULL, this); + if (s.isNull()) + return; + if (conf_read(QFile::encodeName(s))) + QMessageBox::information(this, "qconf", _("Unable to load configuration!")); + ConfigView::updateListAll(); +} + +bool ConfigMainWindow::saveConfig(void) +{ + if (conf_write(NULL)) { + QMessageBox::information(this, "qconf", _("Unable to save configuration!")); + return false; + } + return true; +} + +void ConfigMainWindow::saveConfigAs(void) +{ + QString s = Q3FileDialog::getSaveFileName(conf_get_configname(), NULL, this); + if (s.isNull()) + return; + saveConfig(); +} + +void ConfigMainWindow::searchConfig(void) +{ + if (!searchWindow) + searchWindow = new ConfigSearchWindow(this, "search"); + searchWindow->show(); +} + +void ConfigMainWindow::changeMenu(struct menu *menu) +{ + configList->setRootMenu(menu); + if (configList->rootEntry->parent == &rootmenu) + backAction->setEnabled(FALSE); + else + backAction->setEnabled(TRUE); +} + +void ConfigMainWindow::setMenuLink(struct menu *menu) +{ + struct menu *parent; + ConfigList* list = NULL; + ConfigItem* item; + + if (configList->menuSkip(menu)) + return; + + switch (configList->mode) { + case singleMode: + list = configList; + parent = menu_get_parent_menu(menu); + if (!parent) + return; + list->setRootMenu(parent); + break; + case symbolMode: + if (menu->flags & MENU_ROOT) { + configList->setRootMenu(menu); + configList->clearSelection(); + list = menuList; + } else { + list = configList; + parent = menu_get_parent_menu(menu->parent); + if (!parent) + return; + item = menuList->findConfigItem(parent); + if (item) { + menuList->setSelected(item, TRUE); + menuList->ensureItemVisible(item); + } + list->setRootMenu(parent); + } + break; + case fullMode: + list = configList; + break; + default: + break; + } + + if (list) { + item = list->findConfigItem(menu); + if (item) { + list->setSelected(item, TRUE); + list->ensureItemVisible(item); + list->setFocus(); + } + } +} + +void ConfigMainWindow::listFocusChanged(void) +{ + if (menuList->mode == menuMode) + configList->clearSelection(); +} + +void ConfigMainWindow::goBack(void) +{ + ConfigItem* item; + + configList->setParentMenu(); + if (configList->rootEntry == &rootmenu) + backAction->setEnabled(FALSE); + item = (ConfigItem*)menuList->selectedItem(); + while (item) { + if (item->menu == configList->rootEntry) { + menuList->setSelected(item, TRUE); + break; + } + item = (ConfigItem*)item->parent(); + } +} + +void ConfigMainWindow::showSingleView(void) +{ + menuView->hide(); + menuList->setRootMenu(0); + configList->mode = singleMode; + if (configList->rootEntry == &rootmenu) + configList->updateListAll(); + else + configList->setRootMenu(&rootmenu); + configList->setAllOpen(TRUE); + configList->setFocus(); +} + +void ConfigMainWindow::showSplitView(void) +{ + configList->mode = symbolMode; + if (configList->rootEntry == &rootmenu) + configList->updateListAll(); + else + configList->setRootMenu(&rootmenu); + configList->setAllOpen(TRUE); + configApp->processEvents(); + menuList->mode = menuMode; + menuList->setRootMenu(&rootmenu); + menuList->setAllOpen(TRUE); + menuView->show(); + menuList->setFocus(); +} + +void ConfigMainWindow::showFullView(void) +{ + menuView->hide(); + menuList->setRootMenu(0); + configList->mode = fullMode; + if (configList->rootEntry == &rootmenu) + configList->updateListAll(); + else + configList->setRootMenu(&rootmenu); + configList->setAllOpen(FALSE); + configList->setFocus(); +} + +/* + * ask for saving configuration before quitting + * TODO ask only when something changed + */ +void ConfigMainWindow::closeEvent(QCloseEvent* e) +{ + if (!conf_get_changed()) { + e->accept(); + return; + } + QMessageBox mb("qconf", _("Save configuration?"), QMessageBox::Warning, + QMessageBox::Yes | QMessageBox::Default, QMessageBox::No, QMessageBox::Cancel | QMessageBox::Escape); + mb.setButtonText(QMessageBox::Yes, _("&Save Changes")); + mb.setButtonText(QMessageBox::No, _("&Discard Changes")); + mb.setButtonText(QMessageBox::Cancel, _("Cancel Exit")); + switch (mb.exec()) { + case QMessageBox::Yes: + if (saveConfig()) + e->accept(); + else + e->ignore(); + break; + case QMessageBox::No: + e->accept(); + break; + case QMessageBox::Cancel: + e->ignore(); + break; + } +} + +void ConfigMainWindow::showIntro(void) +{ + static const QString str = _("Welcome to the qconf graphical configuration tool.\n\n" + "For each option, a blank box indicates the feature is disabled, a check\n" + "indicates it is enabled, and a dot indicates that it is to be compiled\n" + "as a module. Clicking on the box will cycle through the three states.\n\n" + "If you do not see an option (e.g., a device driver) that you believe\n" + "should be present, try turning on Show All Options under the Options menu.\n" + "Although there is no cross reference yet to help you figure out what other\n" + "options must be enabled to support the option you are interested in, you can\n" + "still view the help of a grayed-out option.\n\n" + "Toggling Show Debug Info under the Options menu will show the dependencies,\n" + "which you can then match by examining other options.\n\n"); + + QMessageBox::information(this, "qconf", str); +} + +void ConfigMainWindow::showAbout(void) +{ + static const QString str = _("qconf is Copyright (C) 2002 Roman Zippel .\n\n" + "Bug reports and feature request can also be entered at http://bugzilla.kernel.org/\n"); + + QMessageBox::information(this, "qconf", str); +} + +void ConfigMainWindow::saveSettings(void) +{ + configSettings->writeEntry("/window x", pos().x()); + configSettings->writeEntry("/window y", pos().y()); + configSettings->writeEntry("/window width", size().width()); + configSettings->writeEntry("/window height", size().height()); + + QString entry; + switch(configList->mode) { + case singleMode : + entry = "single"; + break; + + case symbolMode : + entry = "split"; + break; + + case fullMode : + entry = "full"; + break; + + default: + break; + } + configSettings->writeEntry("/listMode", entry); + + configSettings->writeSizes("/split1", split1->sizes()); + configSettings->writeSizes("/split2", split2->sizes()); +} + +void ConfigMainWindow::conf_changed(void) +{ + if (saveAction) + saveAction->setEnabled(conf_get_changed()); +} + +void fixup_rootmenu(struct menu *menu) +{ + struct menu *child; + static int menu_cnt = 0; + + menu->flags |= MENU_ROOT; + for (child = menu->list; child; child = child->next) { + if (child->prompt && child->prompt->type == P_MENU) { + menu_cnt++; + fixup_rootmenu(child); + menu_cnt--; + } else if (!menu_cnt) + fixup_rootmenu(child); + } +} + +static const char *progname; + +static void usage(void) +{ + printf(_("%s \n"), progname); + exit(0); +} + +int main(int ac, char** av) +{ + ConfigMainWindow* v; + const char *name; + + bindtextdomain(PACKAGE, LOCALEDIR); + textdomain(PACKAGE); + + progname = av[0]; + configApp = new QApplication(ac, av); + if (ac > 1 && av[1][0] == '-') { + switch (av[1][1]) { + case 'h': + case '?': + usage(); + } + name = av[2]; + } else + name = av[1]; + if (!name) + usage(); + + conf_parse(name); + fixup_rootmenu(&rootmenu); + conf_read(NULL); + //zconfdump(stdout); + + configSettings = new ConfigSettings(); + configSettings->beginGroup("/kconfig/qconf"); + v = new ConfigMainWindow(); + + //zconfdump(stdout); + configApp->setMainWidget(v); + configApp->connect(configApp, SIGNAL(lastWindowClosed()), SLOT(quit())); + configApp->connect(configApp, SIGNAL(aboutToQuit()), v, SLOT(saveSettings())); + v->show(); + configApp->exec(); + + configSettings->endGroup(); + delete configSettings; + + return 0; +} diff --git a/misc/tools/kconfig-frontends/frontends/qconf/qconf.cc.patch b/misc/tools/kconfig-frontends/frontends/qconf/qconf.cc.patch new file mode 100644 index 0000000000..fb7a1292a3 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/qconf/qconf.cc.patch @@ -0,0 +1,12 @@ +diff --git a/frontends/qconf/qconf.cc b/frontends/qconf/qconf.cc +--- a/frontends/qconf/qconf.cc ++++ b/frontends/qconf/qconf.cc +@@ -46,7 +46,7 @@ + #include "qconf.h" + + #include "qconf.moc" +-#include "images.c" ++#include "images.h" + + #ifdef _ + # undef _ diff --git a/misc/tools/kconfig-frontends/frontends/qconf/qconf.h b/misc/tools/kconfig-frontends/frontends/qconf/qconf.h new file mode 100644 index 0000000000..3715b3e721 --- /dev/null +++ b/misc/tools/kconfig-frontends/frontends/qconf/qconf.h @@ -0,0 +1,337 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#if QT_VERSION < 0x040000 +#include +#else +#include +#endif +#include + +#if QT_VERSION < 0x040000 +#define Q3ValueList QValueList +#define Q3PopupMenu QPopupMenu +#define Q3ListView QListView +#define Q3ListViewItem QListViewItem +#define Q3VBox QVBox +#define Q3TextBrowser QTextBrowser +#define Q3MainWindow QMainWindow +#define Q3Action QAction +#define Q3ToolBar QToolBar +#define Q3ListViewItemIterator QListViewItemIterator +#define Q3FileDialog QFileDialog +#endif + +class ConfigView; +class ConfigList; +class ConfigItem; +class ConfigLineEdit; +class ConfigMainWindow; + +class ConfigSettings : public QSettings { +public: + Q3ValueList readSizes(const QString& key, bool *ok); + bool writeSizes(const QString& key, const Q3ValueList& value); +}; + +enum colIdx { + promptColIdx, nameColIdx, noColIdx, modColIdx, yesColIdx, dataColIdx, colNr +}; +enum listMode { + singleMode, menuMode, symbolMode, fullMode, listMode +}; +enum optionMode { + normalOpt = 0, allOpt, promptOpt +}; + +class ConfigList : public Q3ListView { + Q_OBJECT + typedef class Q3ListView Parent; +public: + ConfigList(ConfigView* p, const char *name = 0); + void reinit(void); + ConfigView* parent(void) const + { + return (ConfigView*)Parent::parent(); + } + ConfigItem* findConfigItem(struct menu *); + +protected: + void keyPressEvent(QKeyEvent *e); + void contentsMousePressEvent(QMouseEvent *e); + void contentsMouseReleaseEvent(QMouseEvent *e); + void contentsMouseMoveEvent(QMouseEvent *e); + void contentsMouseDoubleClickEvent(QMouseEvent *e); + void focusInEvent(QFocusEvent *e); + void contextMenuEvent(QContextMenuEvent *e); + +public slots: + void setRootMenu(struct menu *menu); + + void updateList(ConfigItem *item); + void setValue(ConfigItem* item, tristate val); + void changeValue(ConfigItem* item); + void updateSelection(void); + void saveSettings(void); +signals: + void menuChanged(struct menu *menu); + void menuSelected(struct menu *menu); + void parentSelected(void); + void gotFocus(struct menu *); + +public: + void updateListAll(void) + { + updateAll = true; + updateList(NULL); + updateAll = false; + } + ConfigList* listView() + { + return this; + } + ConfigItem* firstChild() const + { + return (ConfigItem *)Parent::firstChild(); + } + int mapIdx(colIdx idx) + { + return colMap[idx]; + } + void addColumn(colIdx idx, const QString& label) + { + colMap[idx] = Parent::addColumn(label); + colRevMap[colMap[idx]] = idx; + } + void removeColumn(colIdx idx) + { + int col = colMap[idx]; + if (col >= 0) { + Parent::removeColumn(col); + colRevMap[col] = colMap[idx] = -1; + } + } + void setAllOpen(bool open); + void setParentMenu(void); + + bool menuSkip(struct menu *); + + template + void updateMenuList(P*, struct menu*); + + bool updateAll; + + QPixmap symbolYesPix, symbolModPix, symbolNoPix; + QPixmap choiceYesPix, choiceNoPix; + QPixmap menuPix, menuInvPix, menuBackPix, voidPix; + + bool showName, showRange, showData; + enum listMode mode; + enum optionMode optMode; + struct menu *rootEntry; + QColorGroup disabledColorGroup; + QColorGroup inactivedColorGroup; + Q3PopupMenu* headerPopup; + +private: + int colMap[colNr]; + int colRevMap[colNr]; +}; + +class ConfigItem : public Q3ListViewItem { + typedef class Q3ListViewItem Parent; +public: + ConfigItem(Q3ListView *parent, ConfigItem *after, struct menu *m, bool v) + : Parent(parent, after), menu(m), visible(v), goParent(false) + { + init(); + } + ConfigItem(ConfigItem *parent, ConfigItem *after, struct menu *m, bool v) + : Parent(parent, after), menu(m), visible(v), goParent(false) + { + init(); + } + ConfigItem(Q3ListView *parent, ConfigItem *after, bool v) + : Parent(parent, after), menu(0), visible(v), goParent(true) + { + init(); + } + ~ConfigItem(void); + void init(void); + void okRename(int col); + void updateMenu(void); + void testUpdateMenu(bool v); + ConfigList* listView() const + { + return (ConfigList*)Parent::listView(); + } + ConfigItem* firstChild() const + { + return (ConfigItem *)Parent::firstChild(); + } + ConfigItem* nextSibling() const + { + return (ConfigItem *)Parent::nextSibling(); + } + void setText(colIdx idx, const QString& text) + { + Parent::setText(listView()->mapIdx(idx), text); + } + QString text(colIdx idx) const + { + return Parent::text(listView()->mapIdx(idx)); + } + void setPixmap(colIdx idx, const QPixmap& pm) + { + Parent::setPixmap(listView()->mapIdx(idx), pm); + } + const QPixmap* pixmap(colIdx idx) const + { + return Parent::pixmap(listView()->mapIdx(idx)); + } + void paintCell(QPainter* p, const QColorGroup& cg, int column, int width, int align); + + ConfigItem* nextItem; + struct menu *menu; + bool visible; + bool goParent; +}; + +class ConfigLineEdit : public QLineEdit { + Q_OBJECT + typedef class QLineEdit Parent; +public: + ConfigLineEdit(ConfigView* parent); + ConfigView* parent(void) const + { + return (ConfigView*)Parent::parent(); + } + void show(ConfigItem *i); + void keyPressEvent(QKeyEvent *e); + +public: + ConfigItem *item; +}; + +class ConfigView : public Q3VBox { + Q_OBJECT + typedef class Q3VBox Parent; +public: + ConfigView(QWidget* parent, const char *name = 0); + ~ConfigView(void); + static void updateList(ConfigItem* item); + static void updateListAll(void); + + bool showName(void) const { return list->showName; } + bool showRange(void) const { return list->showRange; } + bool showData(void) const { return list->showData; } +public slots: + void setShowName(bool); + void setShowRange(bool); + void setShowData(bool); + void setOptionMode(QAction *); +signals: + void showNameChanged(bool); + void showRangeChanged(bool); + void showDataChanged(bool); +public: + ConfigList* list; + ConfigLineEdit* lineEdit; + + static ConfigView* viewList; + ConfigView* nextView; + + static QAction *showNormalAction; + static QAction *showAllAction; + static QAction *showPromptAction; +}; + +class ConfigInfoView : public Q3TextBrowser { + Q_OBJECT + typedef class Q3TextBrowser Parent; +public: + ConfigInfoView(QWidget* parent, const char *name = 0); + bool showDebug(void) const { return _showDebug; } + +public slots: + void setInfo(struct menu *menu); + void saveSettings(void); + void setShowDebug(bool); + +signals: + void showDebugChanged(bool); + void menuSelected(struct menu *); + +protected: + void symbolInfo(void); + void menuInfo(void); + QString debug_info(struct symbol *sym); + static QString print_filter(const QString &str); + static void expr_print_help(void *data, struct symbol *sym, const char *str); + Q3PopupMenu* createPopupMenu(const QPoint& pos); + void contentsContextMenuEvent(QContextMenuEvent *e); + + struct symbol *sym; + struct menu *_menu; + bool _showDebug; +}; + +class ConfigSearchWindow : public QDialog { + Q_OBJECT + typedef class QDialog Parent; +public: + ConfigSearchWindow(ConfigMainWindow* parent, const char *name = 0); + +public slots: + void saveSettings(void); + void search(void); + +protected: + QLineEdit* editField; + QPushButton* searchButton; + QSplitter* split; + ConfigView* list; + ConfigInfoView* info; + + struct symbol **result; +}; + +class ConfigMainWindow : public Q3MainWindow { + Q_OBJECT + + static Q3Action *saveAction; + static void conf_changed(void); +public: + ConfigMainWindow(void); +public slots: + void changeMenu(struct menu *); + void setMenuLink(struct menu *); + void listFocusChanged(void); + void goBack(void); + void loadConfig(void); + bool saveConfig(void); + void saveConfigAs(void); + void searchConfig(void); + void showSingleView(void); + void showSplitView(void); + void showFullView(void); + void showIntro(void); + void showAbout(void); + void saveSettings(void); + +protected: + void closeEvent(QCloseEvent *e); + + ConfigSearchWindow *searchWindow; + ConfigView *menuView; + ConfigList *menuList; + ConfigView *configView; + ConfigList *configList; + ConfigInfoView *helpText; + Q3ToolBar *toolBar; + Q3Action *backAction; + QSplitter* split1; + QSplitter* split2; +}; diff --git a/misc/tools/kconfig-frontends/libs/Makefile.am b/misc/tools/kconfig-frontends/libs/Makefile.am new file mode 100644 index 0000000000..d4c5973837 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/Makefile.am @@ -0,0 +1,7 @@ +if COND_lxdialog + MAYBE_lxdialog = lxdialog +endif +if COND_images + MAYBE_images = images +endif +SUBDIRS = parser $(MAYBE_images) $(MAYBE_lxdialog) diff --git a/misc/tools/kconfig-frontends/libs/Makefile.in b/misc/tools/kconfig-frontends/libs/Makefile.in new file mode 100644 index 0000000000..2000f5f642 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/Makefile.in @@ -0,0 +1,607 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +subdir = libs +DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +SOURCES = +DIST_SOURCES = +RECURSIVE_TARGETS = all-recursive check-recursive dvi-recursive \ + html-recursive info-recursive install-data-recursive \ + install-dvi-recursive install-exec-recursive \ + install-html-recursive install-info-recursive \ + install-pdf-recursive install-ps-recursive install-recursive \ + installcheck-recursive installdirs-recursive pdf-recursive \ + ps-recursive uninstall-recursive +RECURSIVE_CLEAN_TARGETS = mostlyclean-recursive clean-recursive \ + distclean-recursive maintainer-clean-recursive +AM_RECURSIVE_TARGETS = $(RECURSIVE_TARGETS:-recursive=) \ + $(RECURSIVE_CLEAN_TARGETS:-recursive=) tags TAGS ctags CTAGS \ + distdir +ETAGS = etags +CTAGS = ctags +DIST_SUBDIRS = parser images lxdialog +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +am__relativize = \ + dir0=`pwd`; \ + sed_first='s,^\([^/]*\)/.*$$,\1,'; \ + sed_rest='s,^[^/]*/*,,'; \ + sed_last='s,^.*/\([^/]*\)$$,\1,'; \ + sed_butlast='s,/*[^/]*$$,,'; \ + while test -n "$$dir1"; do \ + first=`echo "$$dir1" | sed -e "$$sed_first"`; \ + if test "$$first" != "."; then \ + if test "$$first" = ".."; then \ + dir2=`echo "$$dir0" | sed -e "$$sed_last"`/"$$dir2"; \ + dir0=`echo "$$dir0" | sed -e "$$sed_butlast"`; \ + else \ + first2=`echo "$$dir2" | sed -e "$$sed_first"`; \ + if test "$$first2" = "$$first"; then \ + dir2=`echo "$$dir2" | sed -e "$$sed_rest"`; \ + else \ + dir2="../$$dir2"; \ + fi; \ + dir0="$$dir0"/"$$first"; \ + fi; \ + fi; \ + dir1=`echo "$$dir1" | sed -e "$$sed_rest"`; \ + done; \ + reldir="$$dir2" +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +@COND_lxdialog_TRUE@MAYBE_lxdialog = lxdialog +@COND_images_TRUE@MAYBE_images = images +SUBDIRS = parser $(MAYBE_images) $(MAYBE_lxdialog) +all: all-recursive + +.SUFFIXES: +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign libs/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign libs/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs + +# This directory's subdirectories are mostly independent; you can cd +# into them and run `make' without going through this Makefile. +# To change the values of `make' variables: instead of editing Makefiles, +# (1) if the variable is set in `config.status', edit `config.status' +# (which will cause the Makefiles to be regenerated when you run `make'); +# (2) otherwise, pass the desired values on the `make' command line. +$(RECURSIVE_TARGETS): + @fail= failcom='exit 1'; \ + for f in x $$MAKEFLAGS; do \ + case $$f in \ + *=* | --[!k]*);; \ + *k*) failcom='fail=yes';; \ + esac; \ + done; \ + dot_seen=no; \ + target=`echo $@ | sed s/-recursive//`; \ + list='$(SUBDIRS)'; for subdir in $$list; do \ + echo "Making $$target in $$subdir"; \ + if test "$$subdir" = "."; then \ + dot_seen=yes; \ + local_target="$$target-am"; \ + else \ + local_target="$$target"; \ + fi; \ + ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) $$local_target) \ + || eval $$failcom; \ + done; \ + if test "$$dot_seen" = "no"; then \ + $(MAKE) $(AM_MAKEFLAGS) "$$target-am" || exit 1; \ + fi; test -z "$$fail" + +$(RECURSIVE_CLEAN_TARGETS): + @fail= failcom='exit 1'; \ + for f in x $$MAKEFLAGS; do \ + case $$f in \ + *=* | --[!k]*);; \ + *k*) failcom='fail=yes';; \ + esac; \ + done; \ + dot_seen=no; \ + case "$@" in \ + distclean-* | maintainer-clean-*) list='$(DIST_SUBDIRS)' ;; \ + *) list='$(SUBDIRS)' ;; \ + esac; \ + rev=''; for subdir in $$list; do \ + if test "$$subdir" = "."; then :; else \ + rev="$$subdir $$rev"; \ + fi; \ + done; \ + rev="$$rev ."; \ + target=`echo $@ | sed s/-recursive//`; \ + for subdir in $$rev; do \ + echo "Making $$target in $$subdir"; \ + if test "$$subdir" = "."; then \ + local_target="$$target-am"; \ + else \ + local_target="$$target"; \ + fi; \ + ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) $$local_target) \ + || eval $$failcom; \ + done && test -z "$$fail" +tags-recursive: + list='$(SUBDIRS)'; for subdir in $$list; do \ + test "$$subdir" = . || ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) tags); \ + done +ctags-recursive: + list='$(SUBDIRS)'; for subdir in $$list; do \ + test "$$subdir" = . || ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) ctags); \ + done + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: tags-recursive $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + if ($(ETAGS) --etags-include --version) >/dev/null 2>&1; then \ + include_option=--etags-include; \ + empty_fix=.; \ + else \ + include_option=--include; \ + empty_fix=; \ + fi; \ + list='$(SUBDIRS)'; for subdir in $$list; do \ + if test "$$subdir" = .; then :; else \ + test ! -f $$subdir/TAGS || \ + set "$$@" "$$include_option=$$here/$$subdir/TAGS"; \ + fi; \ + done; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: ctags-recursive $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done + @list='$(DIST_SUBDIRS)'; for subdir in $$list; do \ + if test "$$subdir" = .; then :; else \ + test -d "$(distdir)/$$subdir" \ + || $(MKDIR_P) "$(distdir)/$$subdir" \ + || exit 1; \ + fi; \ + done + @list='$(DIST_SUBDIRS)'; for subdir in $$list; do \ + if test "$$subdir" = .; then :; else \ + dir1=$$subdir; dir2="$(distdir)/$$subdir"; \ + $(am__relativize); \ + new_distdir=$$reldir; \ + dir1=$$subdir; dir2="$(top_distdir)"; \ + $(am__relativize); \ + new_top_distdir=$$reldir; \ + echo " (cd $$subdir && $(MAKE) $(AM_MAKEFLAGS) top_distdir="$$new_top_distdir" distdir="$$new_distdir" \\"; \ + echo " am__remove_distdir=: am__skip_length_check=: am__skip_mode_fix=: distdir)"; \ + ($(am__cd) $$subdir && \ + $(MAKE) $(AM_MAKEFLAGS) \ + top_distdir="$$new_top_distdir" \ + distdir="$$new_distdir" \ + am__remove_distdir=: \ + am__skip_length_check=: \ + am__skip_mode_fix=: \ + distdir) \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-recursive +all-am: Makefile +installdirs: installdirs-recursive +installdirs-am: +install: install-recursive +install-exec: install-exec-recursive +install-data: install-data-recursive +uninstall: uninstall-recursive + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-recursive +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-recursive + +clean-am: clean-generic clean-libtool mostlyclean-am + +distclean: distclean-recursive + -rm -f Makefile +distclean-am: clean-am distclean-generic distclean-tags + +dvi: dvi-recursive + +dvi-am: + +html: html-recursive + +html-am: + +info: info-recursive + +info-am: + +install-data-am: + +install-dvi: install-dvi-recursive + +install-dvi-am: + +install-exec-am: + +install-html: install-html-recursive + +install-html-am: + +install-info: install-info-recursive + +install-info-am: + +install-man: + +install-pdf: install-pdf-recursive + +install-pdf-am: + +install-ps: install-ps-recursive + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-recursive + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-recursive + +mostlyclean-am: mostlyclean-generic mostlyclean-libtool + +pdf: pdf-recursive + +pdf-am: + +ps: ps-recursive + +ps-am: + +uninstall-am: + +.MAKE: $(RECURSIVE_CLEAN_TARGETS) $(RECURSIVE_TARGETS) ctags-recursive \ + install-am install-strip tags-recursive + +.PHONY: $(RECURSIVE_CLEAN_TARGETS) $(RECURSIVE_TARGETS) CTAGS GTAGS \ + all all-am check check-am clean clean-generic clean-libtool \ + ctags ctags-recursive distclean distclean-generic \ + distclean-libtool distclean-tags distdir dvi dvi-am html \ + html-am info info-am install install-am install-data \ + install-data-am install-dvi install-dvi-am install-exec \ + install-exec-am install-html install-html-am install-info \ + install-info-am install-man install-pdf install-pdf-am \ + install-ps install-ps-am install-strip installcheck \ + installcheck-am installdirs installdirs-am maintainer-clean \ + maintainer-clean-generic mostlyclean mostlyclean-generic \ + mostlyclean-libtool pdf pdf-am ps ps-am tags tags-recursive \ + uninstall uninstall-am + + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/libs/images/Makefile.am b/misc/tools/kconfig-frontends/libs/images/Makefile.am new file mode 100644 index 0000000000..c29b1ab4cd --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/images/Makefile.am @@ -0,0 +1,13 @@ +noinst_LIBRARIES = libkconfig-images.a + +libkconfig_images_a_SOURCES = images.c_orig +nodist_libkconfig_images_a_SOURCES = images.c +BUILT_SOURCES = images.c images.h +CLEANFILES = images.c images.h + +images.c: images.c_orig + $(AM_V_GEN)$(SED) -r -e 's/^static //' $< >$@ + +images.h: images.c_orig + $(AM_V_GEN)$(SED) -r -e '/^static (const char \*xpm_(.+)\[\]) = \{/!d; s//extern \1;/' \ + $< >$@ diff --git a/misc/tools/kconfig-frontends/libs/images/Makefile.in b/misc/tools/kconfig-frontends/libs/images/Makefile.in new file mode 100644 index 0000000000..8b4e5fe9c9 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/images/Makefile.in @@ -0,0 +1,550 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ + +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +subdir = libs/images +DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +LIBRARIES = $(noinst_LIBRARIES) +ARFLAGS = cru +AM_V_AR = $(am__v_AR_$(V)) +am__v_AR_ = $(am__v_AR_$(AM_DEFAULT_VERBOSITY)) +am__v_AR_0 = @echo " AR " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +libkconfig_images_a_AR = $(AR) $(ARFLAGS) +libkconfig_images_a_LIBADD = +am_libkconfig_images_a_OBJECTS = +nodist_libkconfig_images_a_OBJECTS = images.$(OBJEXT) +libkconfig_images_a_OBJECTS = $(am_libkconfig_images_a_OBJECTS) \ + $(nodist_libkconfig_images_a_OBJECTS) +DEFAULT_INCLUDES = -I.@am__isrc@ -I$(top_builddir)/scripts/.autostuff +depcomp = $(SHELL) $(top_srcdir)/scripts/.autostuff/scripts/depcomp +am__depfiles_maybe = depfiles +am__mv = mv -f +COMPILE = $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) \ + $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) +AM_V_lt = $(am__v_lt_$(V)) +am__v_lt_ = $(am__v_lt_$(AM_DEFAULT_VERBOSITY)) +am__v_lt_0 = --silent +LTCOMPILE = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) \ + $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) $(CPPFLAGS) \ + $(AM_CFLAGS) $(CFLAGS) +AM_V_CC = $(am__v_CC_$(V)) +am__v_CC_ = $(am__v_CC_$(AM_DEFAULT_VERBOSITY)) +am__v_CC_0 = @echo " CC " $@; +CCLD = $(CC) +LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(AM_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +AM_V_CCLD = $(am__v_CCLD_$(V)) +am__v_CCLD_ = $(am__v_CCLD_$(AM_DEFAULT_VERBOSITY)) +am__v_CCLD_0 = @echo " CCLD " $@; +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +SOURCES = $(libkconfig_images_a_SOURCES) \ + $(nodist_libkconfig_images_a_SOURCES) +DIST_SOURCES = $(libkconfig_images_a_SOURCES) +ETAGS = etags +CTAGS = ctags +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +noinst_LIBRARIES = libkconfig-images.a +libkconfig_images_a_SOURCES = images.c_orig +nodist_libkconfig_images_a_SOURCES = images.c +BUILT_SOURCES = images.c images.h +CLEANFILES = images.c images.h +all: $(BUILT_SOURCES) + $(MAKE) $(AM_MAKEFLAGS) all-am + +.SUFFIXES: +.SUFFIXES: .c .lo .o .obj +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign libs/images/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign libs/images/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): + +clean-noinstLIBRARIES: + -test -z "$(noinst_LIBRARIES)" || rm -f $(noinst_LIBRARIES) +libkconfig-images.a: $(libkconfig_images_a_OBJECTS) $(libkconfig_images_a_DEPENDENCIES) + $(AM_V_at)-rm -f libkconfig-images.a + $(AM_V_AR)$(libkconfig_images_a_AR) libkconfig-images.a $(libkconfig_images_a_OBJECTS) $(libkconfig_images_a_LIBADD) + $(AM_V_at)$(RANLIB) libkconfig-images.a + +mostlyclean-compile: + -rm -f *.$(OBJEXT) + +distclean-compile: + -rm -f *.tab.c + +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/images.Po@am__quote@ + +.c.o: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c $< + +.c.obj: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ `$(CYGPATH_W) '$<'` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c `$(CYGPATH_W) '$<'` + +.c.lo: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LTCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LTCOMPILE) -c -o $@ $< + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: $(BUILT_SOURCES) + $(MAKE) $(AM_MAKEFLAGS) check-am +all-am: Makefile $(LIBRARIES) +installdirs: +install: $(BUILT_SOURCES) + $(MAKE) $(AM_MAKEFLAGS) install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + -test -z "$(CLEANFILES)" || rm -f $(CLEANFILES) + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." + -test -z "$(BUILT_SOURCES)" || rm -f $(BUILT_SOURCES) +clean: clean-am + +clean-am: clean-generic clean-libtool clean-noinstLIBRARIES \ + mostlyclean-am + +distclean: distclean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +distclean-am: clean-am distclean-compile distclean-generic \ + distclean-tags + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: + +.MAKE: all check install install-am install-strip + +.PHONY: CTAGS GTAGS all all-am check check-am clean clean-generic \ + clean-libtool clean-noinstLIBRARIES ctags distclean \ + distclean-compile distclean-generic distclean-libtool \ + distclean-tags distdir dvi dvi-am html html-am info info-am \ + install install-am install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-compile mostlyclean-generic mostlyclean-libtool \ + pdf pdf-am ps ps-am tags uninstall uninstall-am + + +images.c: images.c_orig + $(AM_V_GEN)$(SED) -r -e 's/^static //' $< >$@ + +images.h: images.c_orig + $(AM_V_GEN)$(SED) -r -e '/^static (const char \*xpm_(.+)\[\]) = \{/!d; s//extern \1;/' \ + $< >$@ + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/libs/images/images.c_orig b/misc/tools/kconfig-frontends/libs/images/images.c_orig new file mode 100644 index 0000000000..d4f84bd4a9 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/images/images.c_orig @@ -0,0 +1,326 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +static const char *xpm_load[] = { +"22 22 5 1", +". c None", +"# c #000000", +"c c #838100", +"a c #ffff00", +"b c #ffffff", +"......................", +"......................", +"......................", +"............####....#.", +"...........#....##.##.", +"..................###.", +".................####.", +".####...........#####.", +"#abab##########.......", +"#babababababab#.......", +"#ababababababa#.......", +"#babababababab#.......", +"#ababab###############", +"#babab##cccccccccccc##", +"#abab##cccccccccccc##.", +"#bab##cccccccccccc##..", +"#ab##cccccccccccc##...", +"#b##cccccccccccc##....", +"###cccccccccccc##.....", +"##cccccccccccc##......", +"###############.......", +"......................"}; + +static const char *xpm_save[] = { +"22 22 5 1", +". c None", +"# c #000000", +"a c #838100", +"b c #c5c2c5", +"c c #cdb6d5", +"......................", +".####################.", +".#aa#bbbbbbbbbbbb#bb#.", +".#aa#bbbbbbbbbbbb#bb#.", +".#aa#bbbbbbbbbcbb####.", +".#aa#bbbccbbbbbbb#aa#.", +".#aa#bbbccbbbbbbb#aa#.", +".#aa#bbbbbbbbbbbb#aa#.", +".#aa#bbbbbbbbbbbb#aa#.", +".#aa#bbbbbbbbbbbb#aa#.", +".#aa#bbbbbbbbbbbb#aa#.", +".#aaa############aaa#.", +".#aaaaaaaaaaaaaaaaaa#.", +".#aaaaaaaaaaaaaaaaaa#.", +".#aaa#############aa#.", +".#aaa#########bbb#aa#.", +".#aaa#########bbb#aa#.", +".#aaa#########bbb#aa#.", +".#aaa#########bbb#aa#.", +".#aaa#########bbb#aa#.", +"..##################..", +"......................"}; + +static const char *xpm_back[] = { +"22 22 3 1", +". c None", +"# c #000083", +"a c #838183", +"......................", +"......................", +"......................", +"......................", +"......................", +"...........######a....", +"..#......##########...", +"..##...####......##a..", +"..###.###.........##..", +"..######..........##..", +"..#####...........##..", +"..######..........##..", +"..#######.........##..", +"..########.......##a..", +"...............a###...", +"...............###....", +"......................", +"......................", +"......................", +"......................", +"......................", +"......................"}; + +static const char *xpm_tree_view[] = { +"22 22 2 1", +". c None", +"# c #000000", +"......................", +"......................", +"......#...............", +"......#...............", +"......#...............", +"......#...............", +"......#...............", +"......########........", +"......#...............", +"......#...............", +"......#...............", +"......#...............", +"......#...............", +"......########........", +"......#...............", +"......#...............", +"......#...............", +"......#...............", +"......#...............", +"......########........", +"......................", +"......................"}; + +static const char *xpm_single_view[] = { +"22 22 2 1", +". c None", +"# c #000000", +"......................", +"......................", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"..........#...........", +"......................", +"......................"}; + +static const char *xpm_split_view[] = { +"22 22 2 1", +". c None", +"# c #000000", +"......................", +"......................", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......#......#........", +"......................", +"......................"}; + +static const char *xpm_symbol_no[] = { +"12 12 2 1", +" c white", +". c black", +" ", +" .......... ", +" . . ", +" . . ", +" . . ", +" . . ", +" . . ", +" . . ", +" . . ", +" . . ", +" .......... ", +" "}; + +static const char *xpm_symbol_mod[] = { +"12 12 2 1", +" c white", +". c black", +" ", +" .......... ", +" . . ", +" . . ", +" . .. . ", +" . .... . ", +" . .... . ", +" . .. . ", +" . . ", +" . . ", +" .......... ", +" "}; + +static const char *xpm_symbol_yes[] = { +"12 12 2 1", +" c white", +". c black", +" ", +" .......... ", +" . . ", +" . . ", +" . . . ", +" . .. . ", +" . . .. . ", +" . .... . ", +" . .. . ", +" . . ", +" .......... ", +" "}; + +static const char *xpm_choice_no[] = { +"12 12 2 1", +" c white", +". c black", +" ", +" .... ", +" .. .. ", +" . . ", +" . . ", +" . . ", +" . . ", +" . . ", +" . . ", +" .. .. ", +" .... ", +" "}; + +static const char *xpm_choice_yes[] = { +"12 12 2 1", +" c white", +". c black", +" ", +" .... ", +" .. .. ", +" . . ", +" . .. . ", +" . .... . ", +" . .... . ", +" . .. . ", +" . . ", +" .. .. ", +" .... ", +" "}; + +static const char *xpm_menu[] = { +"12 12 2 1", +" c white", +". c black", +" ", +" .......... ", +" . . ", +" . .. . ", +" . .... . ", +" . ...... . ", +" . ...... . ", +" . .... . ", +" . .. . ", +" . . ", +" .......... ", +" "}; + +static const char *xpm_menu_inv[] = { +"12 12 2 1", +" c white", +". c black", +" ", +" .......... ", +" .......... ", +" .. ...... ", +" .. .... ", +" .. .. ", +" .. .. ", +" .. .... ", +" .. ...... ", +" .......... ", +" .......... ", +" "}; + +static const char *xpm_menuback[] = { +"12 12 2 1", +" c white", +". c black", +" ", +" .......... ", +" . . ", +" . .. . ", +" . .... . ", +" . ...... . ", +" . ...... . ", +" . .... . ", +" . .. . ", +" . . ", +" .......... ", +" "}; + +static const char *xpm_void[] = { +"12 12 2 1", +" c white", +". c black", +" ", +" ", +" ", +" ", +" ", +" ", +" ", +" ", +" ", +" ", +" ", +" "}; diff --git a/misc/tools/kconfig-frontends/libs/lxdialog/Makefile.am b/misc/tools/kconfig-frontends/libs/lxdialog/Makefile.am new file mode 100644 index 0000000000..271b220f91 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/lxdialog/Makefile.am @@ -0,0 +1,15 @@ +noinst_LIBRARIES = libkconfig-lxdialog.a + +libkconfig_lxdialog_a_SOURCES = \ + checklist.c \ + dialog.h \ + inputbox.c \ + menubox.c \ + textbox.c \ + util.c \ + yesno.c + +libkconfig_lxdialog_a_CPPFLAGS = $(AM_CPPFLAGS) \ + -DCURSES_LOC='"${CURSES_LOC}"' \ + $(intl_CPPFLAGS) +liblxdialog_a_CFLAGS = $(AM_CFLAGS) $(kf_CFLAGS) diff --git a/misc/tools/kconfig-frontends/libs/lxdialog/Makefile.in b/misc/tools/kconfig-frontends/libs/lxdialog/Makefile.in new file mode 100644 index 0000000000..f8efb54df1 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/lxdialog/Makefile.in @@ -0,0 +1,652 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ + +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +subdir = libs/lxdialog +DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +LIBRARIES = $(noinst_LIBRARIES) +ARFLAGS = cru +AM_V_AR = $(am__v_AR_$(V)) +am__v_AR_ = $(am__v_AR_$(AM_DEFAULT_VERBOSITY)) +am__v_AR_0 = @echo " AR " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +libkconfig_lxdialog_a_AR = $(AR) $(ARFLAGS) +libkconfig_lxdialog_a_LIBADD = +am_libkconfig_lxdialog_a_OBJECTS = \ + libkconfig_lxdialog_a-checklist.$(OBJEXT) \ + libkconfig_lxdialog_a-inputbox.$(OBJEXT) \ + libkconfig_lxdialog_a-menubox.$(OBJEXT) \ + libkconfig_lxdialog_a-textbox.$(OBJEXT) \ + libkconfig_lxdialog_a-util.$(OBJEXT) \ + libkconfig_lxdialog_a-yesno.$(OBJEXT) +libkconfig_lxdialog_a_OBJECTS = $(am_libkconfig_lxdialog_a_OBJECTS) +DEFAULT_INCLUDES = -I.@am__isrc@ -I$(top_builddir)/scripts/.autostuff +depcomp = $(SHELL) $(top_srcdir)/scripts/.autostuff/scripts/depcomp +am__depfiles_maybe = depfiles +am__mv = mv -f +AM_V_lt = $(am__v_lt_$(V)) +am__v_lt_ = $(am__v_lt_$(AM_DEFAULT_VERBOSITY)) +am__v_lt_0 = --silent +COMPILE = $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) \ + $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) +LTCOMPILE = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) \ + $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) $(CPPFLAGS) \ + $(AM_CFLAGS) $(CFLAGS) +AM_V_CC = $(am__v_CC_$(V)) +am__v_CC_ = $(am__v_CC_$(AM_DEFAULT_VERBOSITY)) +am__v_CC_0 = @echo " CC " $@; +CCLD = $(CC) +LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(AM_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +AM_V_CCLD = $(am__v_CCLD_$(V)) +am__v_CCLD_ = $(am__v_CCLD_$(AM_DEFAULT_VERBOSITY)) +am__v_CCLD_0 = @echo " CCLD " $@; +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +SOURCES = $(libkconfig_lxdialog_a_SOURCES) +DIST_SOURCES = $(libkconfig_lxdialog_a_SOURCES) +ETAGS = etags +CTAGS = ctags +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +noinst_LIBRARIES = libkconfig-lxdialog.a +libkconfig_lxdialog_a_SOURCES = \ + checklist.c \ + dialog.h \ + inputbox.c \ + menubox.c \ + textbox.c \ + util.c \ + yesno.c + +libkconfig_lxdialog_a_CPPFLAGS = $(AM_CPPFLAGS) \ + -DCURSES_LOC='"${CURSES_LOC}"' \ + $(intl_CPPFLAGS) + +liblxdialog_a_CFLAGS = $(AM_CFLAGS) $(kf_CFLAGS) +all: all-am + +.SUFFIXES: +.SUFFIXES: .c .lo .o .obj +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign libs/lxdialog/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign libs/lxdialog/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): + +clean-noinstLIBRARIES: + -test -z "$(noinst_LIBRARIES)" || rm -f $(noinst_LIBRARIES) +libkconfig-lxdialog.a: $(libkconfig_lxdialog_a_OBJECTS) $(libkconfig_lxdialog_a_DEPENDENCIES) + $(AM_V_at)-rm -f libkconfig-lxdialog.a + $(AM_V_AR)$(libkconfig_lxdialog_a_AR) libkconfig-lxdialog.a $(libkconfig_lxdialog_a_OBJECTS) $(libkconfig_lxdialog_a_LIBADD) + $(AM_V_at)$(RANLIB) libkconfig-lxdialog.a + +mostlyclean-compile: + -rm -f *.$(OBJEXT) + +distclean-compile: + -rm -f *.tab.c + +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_lxdialog_a-checklist.Po@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_lxdialog_a-inputbox.Po@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_lxdialog_a-menubox.Po@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_lxdialog_a-textbox.Po@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_lxdialog_a-util.Po@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_lxdialog_a-yesno.Po@am__quote@ + +.c.o: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c $< + +.c.obj: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ `$(CYGPATH_W) '$<'` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c `$(CYGPATH_W) '$<'` + +.c.lo: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LTCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LTCOMPILE) -c -o $@ $< + +libkconfig_lxdialog_a-checklist.o: checklist.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-checklist.o -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-checklist.Tpo -c -o libkconfig_lxdialog_a-checklist.o `test -f 'checklist.c' || echo '$(srcdir)/'`checklist.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-checklist.Tpo $(DEPDIR)/libkconfig_lxdialog_a-checklist.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='checklist.c' object='libkconfig_lxdialog_a-checklist.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-checklist.o `test -f 'checklist.c' || echo '$(srcdir)/'`checklist.c + +libkconfig_lxdialog_a-checklist.obj: checklist.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-checklist.obj -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-checklist.Tpo -c -o libkconfig_lxdialog_a-checklist.obj `if test -f 'checklist.c'; then $(CYGPATH_W) 'checklist.c'; else $(CYGPATH_W) '$(srcdir)/checklist.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-checklist.Tpo $(DEPDIR)/libkconfig_lxdialog_a-checklist.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='checklist.c' object='libkconfig_lxdialog_a-checklist.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-checklist.obj `if test -f 'checklist.c'; then $(CYGPATH_W) 'checklist.c'; else $(CYGPATH_W) '$(srcdir)/checklist.c'; fi` + +libkconfig_lxdialog_a-inputbox.o: inputbox.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-inputbox.o -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-inputbox.Tpo -c -o libkconfig_lxdialog_a-inputbox.o `test -f 'inputbox.c' || echo '$(srcdir)/'`inputbox.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-inputbox.Tpo $(DEPDIR)/libkconfig_lxdialog_a-inputbox.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='inputbox.c' object='libkconfig_lxdialog_a-inputbox.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-inputbox.o `test -f 'inputbox.c' || echo '$(srcdir)/'`inputbox.c + +libkconfig_lxdialog_a-inputbox.obj: inputbox.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-inputbox.obj -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-inputbox.Tpo -c -o libkconfig_lxdialog_a-inputbox.obj `if test -f 'inputbox.c'; then $(CYGPATH_W) 'inputbox.c'; else $(CYGPATH_W) '$(srcdir)/inputbox.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-inputbox.Tpo $(DEPDIR)/libkconfig_lxdialog_a-inputbox.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='inputbox.c' object='libkconfig_lxdialog_a-inputbox.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-inputbox.obj `if test -f 'inputbox.c'; then $(CYGPATH_W) 'inputbox.c'; else $(CYGPATH_W) '$(srcdir)/inputbox.c'; fi` + +libkconfig_lxdialog_a-menubox.o: menubox.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-menubox.o -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-menubox.Tpo -c -o libkconfig_lxdialog_a-menubox.o `test -f 'menubox.c' || echo '$(srcdir)/'`menubox.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-menubox.Tpo $(DEPDIR)/libkconfig_lxdialog_a-menubox.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='menubox.c' object='libkconfig_lxdialog_a-menubox.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-menubox.o `test -f 'menubox.c' || echo '$(srcdir)/'`menubox.c + +libkconfig_lxdialog_a-menubox.obj: menubox.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-menubox.obj -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-menubox.Tpo -c -o libkconfig_lxdialog_a-menubox.obj `if test -f 'menubox.c'; then $(CYGPATH_W) 'menubox.c'; else $(CYGPATH_W) '$(srcdir)/menubox.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-menubox.Tpo $(DEPDIR)/libkconfig_lxdialog_a-menubox.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='menubox.c' object='libkconfig_lxdialog_a-menubox.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-menubox.obj `if test -f 'menubox.c'; then $(CYGPATH_W) 'menubox.c'; else $(CYGPATH_W) '$(srcdir)/menubox.c'; fi` + +libkconfig_lxdialog_a-textbox.o: textbox.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-textbox.o -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-textbox.Tpo -c -o libkconfig_lxdialog_a-textbox.o `test -f 'textbox.c' || echo '$(srcdir)/'`textbox.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-textbox.Tpo $(DEPDIR)/libkconfig_lxdialog_a-textbox.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='textbox.c' object='libkconfig_lxdialog_a-textbox.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-textbox.o `test -f 'textbox.c' || echo '$(srcdir)/'`textbox.c + +libkconfig_lxdialog_a-textbox.obj: textbox.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-textbox.obj -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-textbox.Tpo -c -o libkconfig_lxdialog_a-textbox.obj `if test -f 'textbox.c'; then $(CYGPATH_W) 'textbox.c'; else $(CYGPATH_W) '$(srcdir)/textbox.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-textbox.Tpo $(DEPDIR)/libkconfig_lxdialog_a-textbox.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='textbox.c' object='libkconfig_lxdialog_a-textbox.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-textbox.obj `if test -f 'textbox.c'; then $(CYGPATH_W) 'textbox.c'; else $(CYGPATH_W) '$(srcdir)/textbox.c'; fi` + +libkconfig_lxdialog_a-util.o: util.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-util.o -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-util.Tpo -c -o libkconfig_lxdialog_a-util.o `test -f 'util.c' || echo '$(srcdir)/'`util.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-util.Tpo $(DEPDIR)/libkconfig_lxdialog_a-util.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='util.c' object='libkconfig_lxdialog_a-util.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-util.o `test -f 'util.c' || echo '$(srcdir)/'`util.c + +libkconfig_lxdialog_a-util.obj: util.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-util.obj -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-util.Tpo -c -o libkconfig_lxdialog_a-util.obj `if test -f 'util.c'; then $(CYGPATH_W) 'util.c'; else $(CYGPATH_W) '$(srcdir)/util.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-util.Tpo $(DEPDIR)/libkconfig_lxdialog_a-util.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='util.c' object='libkconfig_lxdialog_a-util.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-util.obj `if test -f 'util.c'; then $(CYGPATH_W) 'util.c'; else $(CYGPATH_W) '$(srcdir)/util.c'; fi` + +libkconfig_lxdialog_a-yesno.o: yesno.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-yesno.o -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-yesno.Tpo -c -o libkconfig_lxdialog_a-yesno.o `test -f 'yesno.c' || echo '$(srcdir)/'`yesno.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-yesno.Tpo $(DEPDIR)/libkconfig_lxdialog_a-yesno.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='yesno.c' object='libkconfig_lxdialog_a-yesno.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-yesno.o `test -f 'yesno.c' || echo '$(srcdir)/'`yesno.c + +libkconfig_lxdialog_a-yesno.obj: yesno.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -MT libkconfig_lxdialog_a-yesno.obj -MD -MP -MF $(DEPDIR)/libkconfig_lxdialog_a-yesno.Tpo -c -o libkconfig_lxdialog_a-yesno.obj `if test -f 'yesno.c'; then $(CYGPATH_W) 'yesno.c'; else $(CYGPATH_W) '$(srcdir)/yesno.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_lxdialog_a-yesno.Tpo $(DEPDIR)/libkconfig_lxdialog_a-yesno.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='yesno.c' object='libkconfig_lxdialog_a-yesno.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_lxdialog_a_CPPFLAGS) $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) -c -o libkconfig_lxdialog_a-yesno.obj `if test -f 'yesno.c'; then $(CYGPATH_W) 'yesno.c'; else $(CYGPATH_W) '$(srcdir)/yesno.c'; fi` + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-am +all-am: Makefile $(LIBRARIES) +installdirs: +install: install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-am + +clean-am: clean-generic clean-libtool clean-noinstLIBRARIES \ + mostlyclean-am + +distclean: distclean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +distclean-am: clean-am distclean-compile distclean-generic \ + distclean-tags + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: + +.MAKE: install-am install-strip + +.PHONY: CTAGS GTAGS all all-am check check-am clean clean-generic \ + clean-libtool clean-noinstLIBRARIES ctags distclean \ + distclean-compile distclean-generic distclean-libtool \ + distclean-tags distdir dvi dvi-am html html-am info info-am \ + install install-am install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-compile mostlyclean-generic mostlyclean-libtool \ + pdf pdf-am ps ps-am tags uninstall uninstall-am + + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/libs/lxdialog/checklist.c b/misc/tools/kconfig-frontends/libs/lxdialog/checklist.c new file mode 100644 index 0000000000..a2eb80fbc8 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/lxdialog/checklist.c @@ -0,0 +1,332 @@ +/* + * checklist.c -- implements the checklist box + * + * ORIGINAL AUTHOR: Savio Lam (lam836@cs.cuhk.hk) + * Stuart Herbert - S.Herbert@sheffield.ac.uk: radiolist extension + * Alessandro Rubini - rubini@ipvvis.unipv.it: merged the two + * MODIFIED FOR LINUX KERNEL CONFIG BY: William Roadcap (roadcap@cfw.com) + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License + * as published by the Free Software Foundation; either version 2 + * of the License, or (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. + */ + +#include "dialog.h" + +static int list_width, check_x, item_x; + +/* + * Print list item + */ +static void print_item(WINDOW * win, int choice, int selected) +{ + int i; + char *list_item = malloc(list_width + 1); + + strncpy(list_item, item_str(), list_width - item_x); + list_item[list_width - item_x] = '\0'; + + /* Clear 'residue' of last item */ + wattrset(win, dlg.menubox.atr); + wmove(win, choice, 0); + for (i = 0; i < list_width; i++) + waddch(win, ' '); + + wmove(win, choice, check_x); + wattrset(win, selected ? dlg.check_selected.atr + : dlg.check.atr); + if (!item_is_tag(':')) + wprintw(win, "(%c)", item_is_tag('X') ? 'X' : ' '); + + wattrset(win, selected ? dlg.tag_selected.atr : dlg.tag.atr); + mvwaddch(win, choice, item_x, list_item[0]); + wattrset(win, selected ? dlg.item_selected.atr : dlg.item.atr); + waddstr(win, list_item + 1); + if (selected) { + wmove(win, choice, check_x + 1); + wrefresh(win); + } + free(list_item); +} + +/* + * Print the scroll indicators. + */ +static void print_arrows(WINDOW * win, int choice, int item_no, int scroll, + int y, int x, int height) +{ + wmove(win, y, x); + + if (scroll > 0) { + wattrset(win, dlg.uarrow.atr); + waddch(win, ACS_UARROW); + waddstr(win, "(-)"); + } else { + wattrset(win, dlg.menubox.atr); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + } + + y = y + height + 1; + wmove(win, y, x); + + if ((height < item_no) && (scroll + choice < item_no - 1)) { + wattrset(win, dlg.darrow.atr); + waddch(win, ACS_DARROW); + waddstr(win, "(+)"); + } else { + wattrset(win, dlg.menubox_border.atr); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + } +} + +/* + * Display the termination buttons + */ +static void print_buttons(WINDOW * dialog, int height, int width, int selected) +{ + int x = width / 2 - 11; + int y = height - 2; + + print_button(dialog, gettext("Select"), y, x, selected == 0); + print_button(dialog, gettext(" Help "), y, x + 14, selected == 1); + + wmove(dialog, y, x + 1 + 14 * selected); + wrefresh(dialog); +} + +/* + * Display a dialog box with a list of options that can be turned on or off + * in the style of radiolist (only one option turned on at a time). + */ +int dialog_checklist(const char *title, const char *prompt, int height, + int width, int list_height) +{ + int i, x, y, box_x, box_y; + int key = 0, button = 0, choice = 0, scroll = 0, max_choice; + WINDOW *dialog, *list; + + /* which item to highlight */ + item_foreach() { + if (item_is_tag('X')) + choice = item_n(); + if (item_is_selected()) { + choice = item_n(); + break; + } + } + +do_resize: + if (getmaxy(stdscr) < (height + 6)) + return -ERRDISPLAYTOOSMALL; + if (getmaxx(stdscr) < (width + 6)) + return -ERRDISPLAYTOOSMALL; + + max_choice = MIN(list_height, item_count()); + + /* center dialog box on screen */ + x = (COLS - width) / 2; + y = (LINES - height) / 2; + + draw_shadow(stdscr, y, x, height, width); + + dialog = newwin(height, width, y, x); + keypad(dialog, TRUE); + + draw_box(dialog, 0, 0, height, width, + dlg.dialog.atr, dlg.border.atr); + wattrset(dialog, dlg.border.atr); + mvwaddch(dialog, height - 3, 0, ACS_LTEE); + for (i = 0; i < width - 2; i++) + waddch(dialog, ACS_HLINE); + wattrset(dialog, dlg.dialog.atr); + waddch(dialog, ACS_RTEE); + + print_title(dialog, title, width); + + wattrset(dialog, dlg.dialog.atr); + print_autowrap(dialog, prompt, width - 2, 1, 3); + + list_width = width - 6; + box_y = height - list_height - 5; + box_x = (width - list_width) / 2 - 1; + + /* create new window for the list */ + list = subwin(dialog, list_height, list_width, y + box_y + 1, + x + box_x + 1); + + keypad(list, TRUE); + + /* draw a box around the list items */ + draw_box(dialog, box_y, box_x, list_height + 2, list_width + 2, + dlg.menubox_border.atr, dlg.menubox.atr); + + /* Find length of longest item in order to center checklist */ + check_x = 0; + item_foreach() + check_x = MAX(check_x, strlen(item_str()) + 4); + check_x = MIN(check_x, list_width); + + check_x = (list_width - check_x) / 2; + item_x = check_x + 4; + + if (choice >= list_height) { + scroll = choice - list_height + 1; + choice -= scroll; + } + + /* Print the list */ + for (i = 0; i < max_choice; i++) { + item_set(scroll + i); + print_item(list, i, i == choice); + } + + print_arrows(dialog, choice, item_count(), scroll, + box_y, box_x + check_x + 5, list_height); + + print_buttons(dialog, height, width, 0); + + wnoutrefresh(dialog); + wnoutrefresh(list); + doupdate(); + + while (key != KEY_ESC) { + key = wgetch(dialog); + + for (i = 0; i < max_choice; i++) { + item_set(i + scroll); + if (toupper(key) == toupper(item_str()[0])) + break; + } + + if (i < max_choice || key == KEY_UP || key == KEY_DOWN || + key == '+' || key == '-') { + if (key == KEY_UP || key == '-') { + if (!choice) { + if (!scroll) + continue; + /* Scroll list down */ + if (list_height > 1) { + /* De-highlight current first item */ + item_set(scroll); + print_item(list, 0, FALSE); + scrollok(list, TRUE); + wscrl(list, -1); + scrollok(list, FALSE); + } + scroll--; + item_set(scroll); + print_item(list, 0, TRUE); + print_arrows(dialog, choice, item_count(), + scroll, box_y, box_x + check_x + 5, list_height); + + wnoutrefresh(dialog); + wrefresh(list); + + continue; /* wait for another key press */ + } else + i = choice - 1; + } else if (key == KEY_DOWN || key == '+') { + if (choice == max_choice - 1) { + if (scroll + choice >= item_count() - 1) + continue; + /* Scroll list up */ + if (list_height > 1) { + /* De-highlight current last item before scrolling up */ + item_set(scroll + max_choice - 1); + print_item(list, + max_choice - 1, + FALSE); + scrollok(list, TRUE); + wscrl(list, 1); + scrollok(list, FALSE); + } + scroll++; + item_set(scroll + max_choice - 1); + print_item(list, max_choice - 1, TRUE); + + print_arrows(dialog, choice, item_count(), + scroll, box_y, box_x + check_x + 5, list_height); + + wnoutrefresh(dialog); + wrefresh(list); + + continue; /* wait for another key press */ + } else + i = choice + 1; + } + if (i != choice) { + /* De-highlight current item */ + item_set(scroll + choice); + print_item(list, choice, FALSE); + /* Highlight new item */ + choice = i; + item_set(scroll + choice); + print_item(list, choice, TRUE); + wnoutrefresh(dialog); + wrefresh(list); + } + continue; /* wait for another key press */ + } + switch (key) { + case 'H': + case 'h': + case '?': + button = 1; + /* fall-through */ + case 'S': + case 's': + case ' ': + case '\n': + item_foreach() + item_set_selected(0); + item_set(scroll + choice); + item_set_selected(1); + delwin(list); + delwin(dialog); + return button; + case TAB: + case KEY_LEFT: + case KEY_RIGHT: + button = ((key == KEY_LEFT ? --button : ++button) < 0) + ? 1 : (button > 1 ? 0 : button); + + print_buttons(dialog, height, width, button); + wrefresh(dialog); + break; + case 'X': + case 'x': + key = KEY_ESC; + break; + case KEY_ESC: + key = on_key_esc(dialog); + break; + case KEY_RESIZE: + delwin(list); + delwin(dialog); + on_key_resize(); + goto do_resize; + } + + /* Now, update everything... */ + doupdate(); + } + delwin(list); + delwin(dialog); + return key; /* ESC pressed */ +} diff --git a/misc/tools/kconfig-frontends/libs/lxdialog/dialog.h b/misc/tools/kconfig-frontends/libs/lxdialog/dialog.h new file mode 100644 index 0000000000..b5211fce0d --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/lxdialog/dialog.h @@ -0,0 +1,230 @@ +/* + * dialog.h -- common declarations for all dialog modules + * + * AUTHOR: Savio Lam (lam836@cs.cuhk.hk) + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License + * as published by the Free Software Foundation; either version 2 + * of the License, or (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. + */ + +#include +#include +#include +#include +#include +#include +#include + +#ifndef KBUILD_NO_NLS +# include +#else +# define gettext(Msgid) ((const char *) (Msgid)) +#endif + +#ifdef __sun__ +#define CURS_MACROS +#endif +#include CURSES_LOC + +/* + * Colors in ncurses 1.9.9e do not work properly since foreground and + * background colors are OR'd rather than separately masked. This version + * of dialog was hacked to work with ncurses 1.9.9e, making it incompatible + * with standard curses. The simplest fix (to make this work with standard + * curses) uses the wbkgdset() function, not used in the original hack. + * Turn it off if we're building with 1.9.9e, since it just confuses things. + */ +#if defined(NCURSES_VERSION) && defined(_NEED_WRAP) && !defined(GCC_PRINTFLIKE) +#define OLD_NCURSES 1 +#undef wbkgdset +#define wbkgdset(w,p) /*nothing */ +#else +#define OLD_NCURSES 0 +#endif + +#define TR(params) _tracef params + +#define KEY_ESC 27 +#define TAB 9 +#define MAX_LEN 2048 +#define BUF_SIZE (10*1024) +#define MIN(x,y) (x < y ? x : y) +#define MAX(x,y) (x > y ? x : y) + +#ifndef ACS_ULCORNER +#define ACS_ULCORNER '+' +#endif +#ifndef ACS_LLCORNER +#define ACS_LLCORNER '+' +#endif +#ifndef ACS_URCORNER +#define ACS_URCORNER '+' +#endif +#ifndef ACS_LRCORNER +#define ACS_LRCORNER '+' +#endif +#ifndef ACS_HLINE +#define ACS_HLINE '-' +#endif +#ifndef ACS_VLINE +#define ACS_VLINE '|' +#endif +#ifndef ACS_LTEE +#define ACS_LTEE '+' +#endif +#ifndef ACS_RTEE +#define ACS_RTEE '+' +#endif +#ifndef ACS_UARROW +#define ACS_UARROW '^' +#endif +#ifndef ACS_DARROW +#define ACS_DARROW 'v' +#endif + +/* error return codes */ +#define ERRDISPLAYTOOSMALL (KEY_MAX + 1) + +/* + * Color definitions + */ +struct dialog_color { + chtype atr; /* Color attribute */ + int fg; /* foreground */ + int bg; /* background */ + int hl; /* highlight this item */ +}; + +struct dialog_info { + const char *backtitle; + struct dialog_color screen; + struct dialog_color shadow; + struct dialog_color dialog; + struct dialog_color title; + struct dialog_color border; + struct dialog_color button_active; + struct dialog_color button_inactive; + struct dialog_color button_key_active; + struct dialog_color button_key_inactive; + struct dialog_color button_label_active; + struct dialog_color button_label_inactive; + struct dialog_color inputbox; + struct dialog_color inputbox_border; + struct dialog_color searchbox; + struct dialog_color searchbox_title; + struct dialog_color searchbox_border; + struct dialog_color position_indicator; + struct dialog_color menubox; + struct dialog_color menubox_border; + struct dialog_color item; + struct dialog_color item_selected; + struct dialog_color tag; + struct dialog_color tag_selected; + struct dialog_color tag_key; + struct dialog_color tag_key_selected; + struct dialog_color check; + struct dialog_color check_selected; + struct dialog_color uarrow; + struct dialog_color darrow; +}; + +/* + * Global variables + */ +extern struct dialog_info dlg; +extern char dialog_input_result[]; + +/* + * Function prototypes + */ + +/* item list as used by checklist and menubox */ +void item_reset(void); +void item_make(const char *fmt, ...); +void item_add_str(const char *fmt, ...); +void item_set_tag(char tag); +void item_set_data(void *p); +void item_set_selected(int val); +int item_activate_selected(void); +void *item_data(void); +char item_tag(void); + +/* item list manipulation for lxdialog use */ +#define MAXITEMSTR 200 +struct dialog_item { + char str[MAXITEMSTR]; /* promtp displayed */ + char tag; + void *data; /* pointer to menu item - used by menubox+checklist */ + int selected; /* Set to 1 by dialog_*() function if selected. */ +}; + +/* list of lialog_items */ +struct dialog_list { + struct dialog_item node; + struct dialog_list *next; +}; + +extern struct dialog_list *item_cur; +extern struct dialog_list item_nil; +extern struct dialog_list *item_head; + +int item_count(void); +void item_set(int n); +int item_n(void); +const char *item_str(void); +int item_is_selected(void); +int item_is_tag(char tag); +#define item_foreach() \ + for (item_cur = item_head ? item_head: item_cur; \ + item_cur && (item_cur != &item_nil); item_cur = item_cur->next) + +/* generic key handlers */ +int on_key_esc(WINDOW *win); +int on_key_resize(void); + +int init_dialog(const char *backtitle); +void set_dialog_backtitle(const char *backtitle); +void end_dialog(int x, int y); +void attr_clear(WINDOW * win, int height, int width, chtype attr); +void dialog_clear(void); +void print_autowrap(WINDOW * win, const char *prompt, int width, int y, int x); +void print_button(WINDOW * win, const char *label, int y, int x, int selected); +void print_title(WINDOW *dialog, const char *title, int width); +void draw_box(WINDOW * win, int y, int x, int height, int width, chtype box, + chtype border); +void draw_shadow(WINDOW * win, int y, int x, int height, int width); + +int first_alpha(const char *string, const char *exempt); +int dialog_yesno(const char *title, const char *prompt, int height, int width); +int dialog_msgbox(const char *title, const char *prompt, int height, + int width, int pause); +int dialog_textbox(const char *title, const char *file, int height, int width); +int dialog_menu(const char *title, const char *prompt, + const void *selected, int *s_scroll); +int dialog_checklist(const char *title, const char *prompt, int height, + int width, int list_height); +extern char dialog_input_result[]; +int dialog_inputbox(const char *title, const char *prompt, int height, + int width, const char *init); + +/* + * This is the base for fictitious keys, which activate + * the buttons. + * + * Mouse-generated keys are the following: + * -- the first 32 are used as numbers, in addition to '0'-'9' + * -- the lowercase are used to signal mouse-enter events (M_EVENT + 'o') + * -- uppercase chars are used to invoke the button (M_EVENT + 'O') + */ +#define M_EVENT (KEY_MAX+1) diff --git a/misc/tools/kconfig-frontends/libs/lxdialog/inputbox.c b/misc/tools/kconfig-frontends/libs/lxdialog/inputbox.c new file mode 100644 index 0000000000..dd8e587c50 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/lxdialog/inputbox.c @@ -0,0 +1,238 @@ +/* + * inputbox.c -- implements the input box + * + * ORIGINAL AUTHOR: Savio Lam (lam836@cs.cuhk.hk) + * MODIFIED FOR LINUX KERNEL CONFIG BY: William Roadcap (roadcap@cfw.com) + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License + * as published by the Free Software Foundation; either version 2 + * of the License, or (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. + */ + +#include "dialog.h" + +char dialog_input_result[MAX_LEN + 1]; + +/* + * Print the termination buttons + */ +static void print_buttons(WINDOW * dialog, int height, int width, int selected) +{ + int x = width / 2 - 11; + int y = height - 2; + + print_button(dialog, gettext(" Ok "), y, x, selected == 0); + print_button(dialog, gettext(" Help "), y, x + 14, selected == 1); + + wmove(dialog, y, x + 1 + 14 * selected); + wrefresh(dialog); +} + +/* + * Display a dialog box for inputing a string + */ +int dialog_inputbox(const char *title, const char *prompt, int height, int width, + const char *init) +{ + int i, x, y, box_y, box_x, box_width; + int input_x = 0, scroll = 0, key = 0, button = -1; + char *instr = dialog_input_result; + WINDOW *dialog; + + if (!init) + instr[0] = '\0'; + else + strcpy(instr, init); + +do_resize: + if (getmaxy(stdscr) <= (height - 2)) + return -ERRDISPLAYTOOSMALL; + if (getmaxx(stdscr) <= (width - 2)) + return -ERRDISPLAYTOOSMALL; + + /* center dialog box on screen */ + x = (COLS - width) / 2; + y = (LINES - height) / 2; + + draw_shadow(stdscr, y, x, height, width); + + dialog = newwin(height, width, y, x); + keypad(dialog, TRUE); + + draw_box(dialog, 0, 0, height, width, + dlg.dialog.atr, dlg.border.atr); + wattrset(dialog, dlg.border.atr); + mvwaddch(dialog, height - 3, 0, ACS_LTEE); + for (i = 0; i < width - 2; i++) + waddch(dialog, ACS_HLINE); + wattrset(dialog, dlg.dialog.atr); + waddch(dialog, ACS_RTEE); + + print_title(dialog, title, width); + + wattrset(dialog, dlg.dialog.atr); + print_autowrap(dialog, prompt, width - 2, 1, 3); + + /* Draw the input field box */ + box_width = width - 6; + getyx(dialog, y, x); + box_y = y + 2; + box_x = (width - box_width) / 2; + draw_box(dialog, y + 1, box_x - 1, 3, box_width + 2, + dlg.dialog.atr, dlg.border.atr); + + print_buttons(dialog, height, width, 0); + + /* Set up the initial value */ + wmove(dialog, box_y, box_x); + wattrset(dialog, dlg.inputbox.atr); + + input_x = strlen(instr); + + if (input_x >= box_width) { + scroll = input_x - box_width + 1; + input_x = box_width - 1; + for (i = 0; i < box_width - 1; i++) + waddch(dialog, instr[scroll + i]); + } else { + waddstr(dialog, instr); + } + + wmove(dialog, box_y, box_x + input_x); + + wrefresh(dialog); + + while (key != KEY_ESC) { + key = wgetch(dialog); + + if (button == -1) { /* Input box selected */ + switch (key) { + case TAB: + case KEY_UP: + case KEY_DOWN: + break; + case KEY_LEFT: + continue; + case KEY_RIGHT: + continue; + case KEY_BACKSPACE: + case 127: + if (input_x || scroll) { + wattrset(dialog, dlg.inputbox.atr); + if (!input_x) { + scroll = scroll < box_width - 1 ? 0 : scroll - (box_width - 1); + wmove(dialog, box_y, box_x); + for (i = 0; i < box_width; i++) + waddch(dialog, + instr[scroll + input_x + i] ? + instr[scroll + input_x + i] : ' '); + input_x = strlen(instr) - scroll; + } else + input_x--; + instr[scroll + input_x] = '\0'; + mvwaddch(dialog, box_y, input_x + box_x, ' '); + wmove(dialog, box_y, input_x + box_x); + wrefresh(dialog); + } + continue; + default: + if (key < 0x100 && isprint(key)) { + if (scroll + input_x < MAX_LEN) { + wattrset(dialog, dlg.inputbox.atr); + instr[scroll + input_x] = key; + instr[scroll + input_x + 1] = '\0'; + if (input_x == box_width - 1) { + scroll++; + wmove(dialog, box_y, box_x); + for (i = 0; i < box_width - 1; i++) + waddch(dialog, instr [scroll + i]); + } else { + wmove(dialog, box_y, input_x++ + box_x); + waddch(dialog, key); + } + wrefresh(dialog); + } else + flash(); /* Alarm user about overflow */ + continue; + } + } + } + switch (key) { + case 'O': + case 'o': + delwin(dialog); + return 0; + case 'H': + case 'h': + delwin(dialog); + return 1; + case KEY_UP: + case KEY_LEFT: + switch (button) { + case -1: + button = 1; /* Indicates "Help" button is selected */ + print_buttons(dialog, height, width, 1); + break; + case 0: + button = -1; /* Indicates input box is selected */ + print_buttons(dialog, height, width, 0); + wmove(dialog, box_y, box_x + input_x); + wrefresh(dialog); + break; + case 1: + button = 0; /* Indicates "OK" button is selected */ + print_buttons(dialog, height, width, 0); + break; + } + break; + case TAB: + case KEY_DOWN: + case KEY_RIGHT: + switch (button) { + case -1: + button = 0; /* Indicates "OK" button is selected */ + print_buttons(dialog, height, width, 0); + break; + case 0: + button = 1; /* Indicates "Help" button is selected */ + print_buttons(dialog, height, width, 1); + break; + case 1: + button = -1; /* Indicates input box is selected */ + print_buttons(dialog, height, width, 0); + wmove(dialog, box_y, box_x + input_x); + wrefresh(dialog); + break; + } + break; + case ' ': + case '\n': + delwin(dialog); + return (button == -1 ? 0 : button); + case 'X': + case 'x': + key = KEY_ESC; + break; + case KEY_ESC: + key = on_key_esc(dialog); + break; + case KEY_RESIZE: + delwin(dialog); + on_key_resize(); + goto do_resize; + } + } + + delwin(dialog); + return KEY_ESC; /* ESC pressed */ +} diff --git a/misc/tools/kconfig-frontends/libs/lxdialog/menubox.c b/misc/tools/kconfig-frontends/libs/lxdialog/menubox.c new file mode 100644 index 0000000000..1d604738fa --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/lxdialog/menubox.c @@ -0,0 +1,434 @@ +/* + * menubox.c -- implements the menu box + * + * ORIGINAL AUTHOR: Savio Lam (lam836@cs.cuhk.hk) + * MODIFIED FOR LINUX KERNEL CONFIG BY: William Roadcap (roadcapw@cfw.com) + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License + * as published by the Free Software Foundation; either version 2 + * of the License, or (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. + */ + +/* + * Changes by Clifford Wolf (god@clifford.at) + * + * [ 1998-06-13 ] + * + * *) A bugfix for the Page-Down problem + * + * *) Formerly when I used Page Down and Page Up, the cursor would be set + * to the first position in the menu box. Now lxdialog is a bit + * smarter and works more like other menu systems (just have a look at + * it). + * + * *) Formerly if I selected something my scrolling would be broken because + * lxdialog is re-invoked by the Menuconfig shell script, can't + * remember the last scrolling position, and just sets it so that the + * cursor is at the bottom of the box. Now it writes the temporary file + * lxdialog.scrltmp which contains this information. The file is + * deleted by lxdialog if the user leaves a submenu or enters a new + * one, but it would be nice if Menuconfig could make another "rm -f" + * just to be sure. Just try it out - you will recognise a difference! + * + * [ 1998-06-14 ] + * + * *) Now lxdialog is crash-safe against broken "lxdialog.scrltmp" files + * and menus change their size on the fly. + * + * *) If for some reason the last scrolling position is not saved by + * lxdialog, it sets the scrolling so that the selected item is in the + * middle of the menu box, not at the bottom. + * + * 02 January 1999, Michael Elizabeth Chastain (mec@shout.net) + * Reset 'scroll' to 0 if the value from lxdialog.scrltmp is bogus. + * This fixes a bug in Menuconfig where using ' ' to descend into menus + * would leave mis-synchronized lxdialog.scrltmp files lying around, + * fscanf would read in 'scroll', and eventually that value would get used. + */ + +#include "dialog.h" + +static int menu_width, item_x; + +/* + * Print menu item + */ +static void do_print_item(WINDOW * win, const char *item, int line_y, + int selected, int hotkey) +{ + int j; + char *menu_item = malloc(menu_width + 1); + + strncpy(menu_item, item, menu_width - item_x); + menu_item[menu_width - item_x] = '\0'; + j = first_alpha(menu_item, "YyNnMmHh"); + + /* Clear 'residue' of last item */ + wattrset(win, dlg.menubox.atr); + wmove(win, line_y, 0); +#if OLD_NCURSES + { + int i; + for (i = 0; i < menu_width; i++) + waddch(win, ' '); + } +#else + wclrtoeol(win); +#endif + wattrset(win, selected ? dlg.item_selected.atr : dlg.item.atr); + mvwaddstr(win, line_y, item_x, menu_item); + if (hotkey) { + wattrset(win, selected ? dlg.tag_key_selected.atr + : dlg.tag_key.atr); + mvwaddch(win, line_y, item_x + j, menu_item[j]); + } + if (selected) { + wmove(win, line_y, item_x + 1); + } + free(menu_item); + wrefresh(win); +} + +#define print_item(index, choice, selected) \ +do { \ + item_set(index); \ + do_print_item(menu, item_str(), choice, selected, !item_is_tag(':')); \ +} while (0) + +/* + * Print the scroll indicators. + */ +static void print_arrows(WINDOW * win, int item_no, int scroll, int y, int x, + int height) +{ + int cur_y, cur_x; + + getyx(win, cur_y, cur_x); + + wmove(win, y, x); + + if (scroll > 0) { + wattrset(win, dlg.uarrow.atr); + waddch(win, ACS_UARROW); + waddstr(win, "(-)"); + } else { + wattrset(win, dlg.menubox.atr); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + } + + y = y + height + 1; + wmove(win, y, x); + wrefresh(win); + + if ((height < item_no) && (scroll + height < item_no)) { + wattrset(win, dlg.darrow.atr); + waddch(win, ACS_DARROW); + waddstr(win, "(+)"); + } else { + wattrset(win, dlg.menubox_border.atr); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + waddch(win, ACS_HLINE); + } + + wmove(win, cur_y, cur_x); + wrefresh(win); +} + +/* + * Display the termination buttons. + */ +static void print_buttons(WINDOW * win, int height, int width, int selected) +{ + int x = width / 2 - 16; + int y = height - 2; + + print_button(win, gettext("Select"), y, x, selected == 0); + print_button(win, gettext(" Exit "), y, x + 12, selected == 1); + print_button(win, gettext(" Help "), y, x + 24, selected == 2); + + wmove(win, y, x + 1 + 12 * selected); + wrefresh(win); +} + +/* scroll up n lines (n may be negative) */ +static void do_scroll(WINDOW *win, int *scroll, int n) +{ + /* Scroll menu up */ + scrollok(win, TRUE); + wscrl(win, n); + scrollok(win, FALSE); + *scroll = *scroll + n; + wrefresh(win); +} + +/* + * Display a menu for choosing among a number of options + */ +int dialog_menu(const char *title, const char *prompt, + const void *selected, int *s_scroll) +{ + int i, j, x, y, box_x, box_y; + int height, width, menu_height; + int key = 0, button = 0, scroll = 0, choice = 0; + int first_item = 0, max_choice; + WINDOW *dialog, *menu; + +do_resize: + height = getmaxy(stdscr); + width = getmaxx(stdscr); + if (height < 15 || width < 65) + return -ERRDISPLAYTOOSMALL; + + height -= 4; + width -= 5; + menu_height = height - 10; + + max_choice = MIN(menu_height, item_count()); + + /* center dialog box on screen */ + x = (COLS - width) / 2; + y = (LINES - height) / 2; + + draw_shadow(stdscr, y, x, height, width); + + dialog = newwin(height, width, y, x); + keypad(dialog, TRUE); + + draw_box(dialog, 0, 0, height, width, + dlg.dialog.atr, dlg.border.atr); + wattrset(dialog, dlg.border.atr); + mvwaddch(dialog, height - 3, 0, ACS_LTEE); + for (i = 0; i < width - 2; i++) + waddch(dialog, ACS_HLINE); + wattrset(dialog, dlg.dialog.atr); + wbkgdset(dialog, dlg.dialog.atr & A_COLOR); + waddch(dialog, ACS_RTEE); + + print_title(dialog, title, width); + + wattrset(dialog, dlg.dialog.atr); + print_autowrap(dialog, prompt, width - 2, 1, 3); + + menu_width = width - 6; + box_y = height - menu_height - 5; + box_x = (width - menu_width) / 2 - 1; + + /* create new window for the menu */ + menu = subwin(dialog, menu_height, menu_width, + y + box_y + 1, x + box_x + 1); + keypad(menu, TRUE); + + /* draw a box around the menu items */ + draw_box(dialog, box_y, box_x, menu_height + 2, menu_width + 2, + dlg.menubox_border.atr, dlg.menubox.atr); + + if (menu_width >= 80) + item_x = (menu_width - 70) / 2; + else + item_x = 4; + + /* Set choice to default item */ + item_foreach() + if (selected && (selected == item_data())) + choice = item_n(); + /* get the saved scroll info */ + scroll = *s_scroll; + if ((scroll <= choice) && (scroll + max_choice > choice) && + (scroll >= 0) && (scroll + max_choice <= item_count())) { + first_item = scroll; + choice = choice - scroll; + } else { + scroll = 0; + } + if ((choice >= max_choice)) { + if (choice >= item_count() - max_choice / 2) + scroll = first_item = item_count() - max_choice; + else + scroll = first_item = choice - max_choice / 2; + choice = choice - scroll; + } + + /* Print the menu */ + for (i = 0; i < max_choice; i++) { + print_item(first_item + i, i, i == choice); + } + + wnoutrefresh(menu); + + print_arrows(dialog, item_count(), scroll, + box_y, box_x + item_x + 1, menu_height); + + print_buttons(dialog, height, width, 0); + wmove(menu, choice, item_x + 1); + wrefresh(menu); + + while (key != KEY_ESC) { + key = wgetch(menu); + + if (key < 256 && isalpha(key)) + key = tolower(key); + + if (strchr("ynmh", key)) + i = max_choice; + else { + for (i = choice + 1; i < max_choice; i++) { + item_set(scroll + i); + j = first_alpha(item_str(), "YyNnMmHh"); + if (key == tolower(item_str()[j])) + break; + } + if (i == max_choice) + for (i = 0; i < max_choice; i++) { + item_set(scroll + i); + j = first_alpha(item_str(), "YyNnMmHh"); + if (key == tolower(item_str()[j])) + break; + } + } + + if (i < max_choice || + key == KEY_UP || key == KEY_DOWN || + key == '-' || key == '+' || + key == KEY_PPAGE || key == KEY_NPAGE) { + /* Remove highligt of current item */ + print_item(scroll + choice, choice, FALSE); + + if (key == KEY_UP || key == '-') { + if (choice < 2 && scroll) { + /* Scroll menu down */ + do_scroll(menu, &scroll, -1); + + print_item(scroll, 0, FALSE); + } else + choice = MAX(choice - 1, 0); + + } else if (key == KEY_DOWN || key == '+') { + print_item(scroll+choice, choice, FALSE); + + if ((choice > max_choice - 3) && + (scroll + max_choice < item_count())) { + /* Scroll menu up */ + do_scroll(menu, &scroll, 1); + + print_item(scroll+max_choice - 1, + max_choice - 1, FALSE); + } else + choice = MIN(choice + 1, max_choice - 1); + + } else if (key == KEY_PPAGE) { + scrollok(menu, TRUE); + for (i = 0; (i < max_choice); i++) { + if (scroll > 0) { + do_scroll(menu, &scroll, -1); + print_item(scroll, 0, FALSE); + } else { + if (choice > 0) + choice--; + } + } + + } else if (key == KEY_NPAGE) { + for (i = 0; (i < max_choice); i++) { + if (scroll + max_choice < item_count()) { + do_scroll(menu, &scroll, 1); + print_item(scroll+max_choice-1, + max_choice - 1, FALSE); + } else { + if (choice + 1 < max_choice) + choice++; + } + } + } else + choice = i; + + print_item(scroll + choice, choice, TRUE); + + print_arrows(dialog, item_count(), scroll, + box_y, box_x + item_x + 1, menu_height); + + wnoutrefresh(dialog); + wrefresh(menu); + + continue; /* wait for another key press */ + } + + switch (key) { + case KEY_LEFT: + case TAB: + case KEY_RIGHT: + button = ((key == KEY_LEFT ? --button : ++button) < 0) + ? 2 : (button > 2 ? 0 : button); + + print_buttons(dialog, height, width, button); + wrefresh(menu); + break; + case ' ': + case 's': + case 'y': + case 'n': + case 'm': + case '/': + case 'h': + case '?': + case 'z': + case '\n': + /* save scroll info */ + *s_scroll = scroll; + delwin(menu); + delwin(dialog); + item_set(scroll + choice); + item_set_selected(1); + switch (key) { + case 'h': + case '?': + return 2; + case 's': + case 'y': + return 3; + case 'n': + return 4; + case 'm': + return 5; + case ' ': + return 6; + case '/': + return 7; + case 'z': + return 8; + case '\n': + return button; + } + return 0; + case 'e': + case 'x': + key = KEY_ESC; + break; + case KEY_ESC: + key = on_key_esc(menu); + break; + case KEY_RESIZE: + on_key_resize(); + delwin(menu); + delwin(dialog); + goto do_resize; + } + } + delwin(menu); + delwin(dialog); + return key; /* ESC pressed */ +} diff --git a/misc/tools/kconfig-frontends/libs/lxdialog/textbox.c b/misc/tools/kconfig-frontends/libs/lxdialog/textbox.c new file mode 100644 index 0000000000..4e5de60a0c --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/lxdialog/textbox.c @@ -0,0 +1,393 @@ +/* + * textbox.c -- implements the text box + * + * ORIGINAL AUTHOR: Savio Lam (lam836@cs.cuhk.hk) + * MODIFIED FOR LINUX KERNEL CONFIG BY: William Roadcap (roadcap@cfw.com) + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License + * as published by the Free Software Foundation; either version 2 + * of the License, or (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. + */ + +#include "dialog.h" + +static void back_lines(int n); +static void print_page(WINDOW * win, int height, int width); +static void print_line(WINDOW * win, int row, int width); +static char *get_line(void); +static void print_position(WINDOW * win); + +static int hscroll; +static int begin_reached, end_reached, page_length; +static const char *buf; +static const char *page; + +/* + * refresh window content + */ +static void refresh_text_box(WINDOW *dialog, WINDOW *box, int boxh, int boxw, + int cur_y, int cur_x) +{ + print_page(box, boxh, boxw); + print_position(dialog); + wmove(dialog, cur_y, cur_x); /* Restore cursor position */ + wrefresh(dialog); +} + + +/* + * Display text from a file in a dialog box. + */ +int dialog_textbox(const char *title, const char *tbuf, + int initial_height, int initial_width) +{ + int i, x, y, cur_x, cur_y, key = 0; + int height, width, boxh, boxw; + int passed_end; + WINDOW *dialog, *box; + + begin_reached = 1; + end_reached = 0; + page_length = 0; + hscroll = 0; + buf = tbuf; + page = buf; /* page is pointer to start of page to be displayed */ + +do_resize: + getmaxyx(stdscr, height, width); + if (height < 8 || width < 8) + return -ERRDISPLAYTOOSMALL; + if (initial_height != 0) + height = initial_height; + else + if (height > 4) + height -= 4; + else + height = 0; + if (initial_width != 0) + width = initial_width; + else + if (width > 5) + width -= 5; + else + width = 0; + + /* center dialog box on screen */ + x = (COLS - width) / 2; + y = (LINES - height) / 2; + + draw_shadow(stdscr, y, x, height, width); + + dialog = newwin(height, width, y, x); + keypad(dialog, TRUE); + + /* Create window for box region, used for scrolling text */ + boxh = height - 4; + boxw = width - 2; + box = subwin(dialog, boxh, boxw, y + 1, x + 1); + wattrset(box, dlg.dialog.atr); + wbkgdset(box, dlg.dialog.atr & A_COLOR); + + keypad(box, TRUE); + + /* register the new window, along with its borders */ + draw_box(dialog, 0, 0, height, width, + dlg.dialog.atr, dlg.border.atr); + + wattrset(dialog, dlg.border.atr); + mvwaddch(dialog, height - 3, 0, ACS_LTEE); + for (i = 0; i < width - 2; i++) + waddch(dialog, ACS_HLINE); + wattrset(dialog, dlg.dialog.atr); + wbkgdset(dialog, dlg.dialog.atr & A_COLOR); + waddch(dialog, ACS_RTEE); + + print_title(dialog, title, width); + + print_button(dialog, gettext(" Exit "), height - 2, width / 2 - 4, TRUE); + wnoutrefresh(dialog); + getyx(dialog, cur_y, cur_x); /* Save cursor position */ + + /* Print first page of text */ + attr_clear(box, boxh, boxw, dlg.dialog.atr); + refresh_text_box(dialog, box, boxh, boxw, cur_y, cur_x); + + while ((key != KEY_ESC) && (key != '\n')) { + key = wgetch(dialog); + switch (key) { + case 'E': /* Exit */ + case 'e': + case 'X': + case 'x': + case 'q': + delwin(box); + delwin(dialog); + return 0; + case 'g': /* First page */ + case KEY_HOME: + if (!begin_reached) { + begin_reached = 1; + page = buf; + refresh_text_box(dialog, box, boxh, boxw, + cur_y, cur_x); + } + break; + case 'G': /* Last page */ + case KEY_END: + + end_reached = 1; + /* point to last char in buf */ + page = buf + strlen(buf); + back_lines(boxh); + refresh_text_box(dialog, box, boxh, boxw, + cur_y, cur_x); + break; + case 'K': /* Previous line */ + case 'k': + case KEY_UP: + if (!begin_reached) { + back_lines(page_length + 1); + + /* We don't call print_page() here but use + * scrolling to ensure faster screen update. + * However, 'end_reached' and 'page_length' + * should still be updated, and 'page' should + * point to start of next page. This is done + * by calling get_line() in the following + * 'for' loop. */ + scrollok(box, TRUE); + wscrl(box, -1); /* Scroll box region down one line */ + scrollok(box, FALSE); + page_length = 0; + passed_end = 0; + for (i = 0; i < boxh; i++) { + if (!i) { + /* print first line of page */ + print_line(box, 0, boxw); + wnoutrefresh(box); + } else + /* Called to update 'end_reached' and 'page' */ + get_line(); + if (!passed_end) + page_length++; + if (end_reached && !passed_end) + passed_end = 1; + } + + print_position(dialog); + wmove(dialog, cur_y, cur_x); /* Restore cursor position */ + wrefresh(dialog); + } + break; + case 'B': /* Previous page */ + case 'b': + case 'u': + case KEY_PPAGE: + if (begin_reached) + break; + back_lines(page_length + boxh); + refresh_text_box(dialog, box, boxh, boxw, + cur_y, cur_x); + break; + case 'J': /* Next line */ + case 'j': + case KEY_DOWN: + if (!end_reached) { + begin_reached = 0; + scrollok(box, TRUE); + scroll(box); /* Scroll box region up one line */ + scrollok(box, FALSE); + print_line(box, boxh - 1, boxw); + wnoutrefresh(box); + print_position(dialog); + wmove(dialog, cur_y, cur_x); /* Restore cursor position */ + wrefresh(dialog); + } + break; + case KEY_NPAGE: /* Next page */ + case ' ': + case 'd': + if (end_reached) + break; + + begin_reached = 0; + refresh_text_box(dialog, box, boxh, boxw, + cur_y, cur_x); + break; + case '0': /* Beginning of line */ + case 'H': /* Scroll left */ + case 'h': + case KEY_LEFT: + if (hscroll <= 0) + break; + + if (key == '0') + hscroll = 0; + else + hscroll--; + /* Reprint current page to scroll horizontally */ + back_lines(page_length); + refresh_text_box(dialog, box, boxh, boxw, + cur_y, cur_x); + break; + case 'L': /* Scroll right */ + case 'l': + case KEY_RIGHT: + if (hscroll >= MAX_LEN) + break; + hscroll++; + /* Reprint current page to scroll horizontally */ + back_lines(page_length); + refresh_text_box(dialog, box, boxh, boxw, + cur_y, cur_x); + break; + case KEY_ESC: + key = on_key_esc(dialog); + break; + case KEY_RESIZE: + back_lines(height); + delwin(box); + delwin(dialog); + on_key_resize(); + goto do_resize; + } + } + delwin(box); + delwin(dialog); + return key; /* ESC pressed */ +} + +/* + * Go back 'n' lines in text. Called by dialog_textbox(). + * 'page' will be updated to point to the desired line in 'buf'. + */ +static void back_lines(int n) +{ + int i; + + begin_reached = 0; + /* Go back 'n' lines */ + for (i = 0; i < n; i++) { + if (*page == '\0') { + if (end_reached) { + end_reached = 0; + continue; + } + } + if (page == buf) { + begin_reached = 1; + return; + } + page--; + do { + if (page == buf) { + begin_reached = 1; + return; + } + page--; + } while (*page != '\n'); + page++; + } +} + +/* + * Print a new page of text. Called by dialog_textbox(). + */ +static void print_page(WINDOW * win, int height, int width) +{ + int i, passed_end = 0; + + page_length = 0; + for (i = 0; i < height; i++) { + print_line(win, i, width); + if (!passed_end) + page_length++; + if (end_reached && !passed_end) + passed_end = 1; + } + wnoutrefresh(win); +} + +/* + * Print a new line of text. Called by dialog_textbox() and print_page(). + */ +static void print_line(WINDOW * win, int row, int width) +{ + char *line; + + line = get_line(); + line += MIN(strlen(line), hscroll); /* Scroll horizontally */ + wmove(win, row, 0); /* move cursor to correct line */ + waddch(win, ' '); + waddnstr(win, line, MIN(strlen(line), width - 2)); + + /* Clear 'residue' of previous line */ +#if OLD_NCURSES + { + int x = getcurx(win); + int i; + for (i = 0; i < width - x; i++) + waddch(win, ' '); + } +#else + wclrtoeol(win); +#endif +} + +/* + * Return current line of text. Called by dialog_textbox() and print_line(). + * 'page' should point to start of current line before calling, and will be + * updated to point to start of next line. + */ +static char *get_line(void) +{ + int i = 0; + static char line[MAX_LEN + 1]; + + end_reached = 0; + while (*page != '\n') { + if (*page == '\0') { + if (!end_reached) { + end_reached = 1; + break; + } + } else if (i < MAX_LEN) + line[i++] = *(page++); + else { + /* Truncate lines longer than MAX_LEN characters */ + if (i == MAX_LEN) + line[i++] = '\0'; + page++; + } + } + if (i <= MAX_LEN) + line[i] = '\0'; + if (!end_reached) + page++; /* move pass '\n' */ + + return line; +} + +/* + * Print current position + */ +static void print_position(WINDOW * win) +{ + int percent; + + wattrset(win, dlg.position_indicator.atr); + wbkgdset(win, dlg.position_indicator.atr & A_COLOR); + percent = (page - buf) * 100 / strlen(buf); + wmove(win, getmaxy(win) - 3, getmaxx(win) - 9); + wprintw(win, "(%3d%%)", percent); +} diff --git a/misc/tools/kconfig-frontends/libs/lxdialog/util.c b/misc/tools/kconfig-frontends/libs/lxdialog/util.c new file mode 100644 index 0000000000..f2375ad7eb --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/lxdialog/util.c @@ -0,0 +1,657 @@ +/* + * util.c + * + * ORIGINAL AUTHOR: Savio Lam (lam836@cs.cuhk.hk) + * MODIFIED FOR LINUX KERNEL CONFIG BY: William Roadcap (roadcap@cfw.com) + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License + * as published by the Free Software Foundation; either version 2 + * of the License, or (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. + */ + +#include + +#include "dialog.h" + +struct dialog_info dlg; + +static void set_mono_theme(void) +{ + dlg.screen.atr = A_NORMAL; + dlg.shadow.atr = A_NORMAL; + dlg.dialog.atr = A_NORMAL; + dlg.title.atr = A_BOLD; + dlg.border.atr = A_NORMAL; + dlg.button_active.atr = A_REVERSE; + dlg.button_inactive.atr = A_DIM; + dlg.button_key_active.atr = A_REVERSE; + dlg.button_key_inactive.atr = A_BOLD; + dlg.button_label_active.atr = A_REVERSE; + dlg.button_label_inactive.atr = A_NORMAL; + dlg.inputbox.atr = A_NORMAL; + dlg.inputbox_border.atr = A_NORMAL; + dlg.searchbox.atr = A_NORMAL; + dlg.searchbox_title.atr = A_BOLD; + dlg.searchbox_border.atr = A_NORMAL; + dlg.position_indicator.atr = A_BOLD; + dlg.menubox.atr = A_NORMAL; + dlg.menubox_border.atr = A_NORMAL; + dlg.item.atr = A_NORMAL; + dlg.item_selected.atr = A_REVERSE; + dlg.tag.atr = A_BOLD; + dlg.tag_selected.atr = A_REVERSE; + dlg.tag_key.atr = A_BOLD; + dlg.tag_key_selected.atr = A_REVERSE; + dlg.check.atr = A_BOLD; + dlg.check_selected.atr = A_REVERSE; + dlg.uarrow.atr = A_BOLD; + dlg.darrow.atr = A_BOLD; +} + +#define DLG_COLOR(dialog, f, b, h) \ +do { \ + dlg.dialog.fg = (f); \ + dlg.dialog.bg = (b); \ + dlg.dialog.hl = (h); \ +} while (0) + +static void set_classic_theme(void) +{ + DLG_COLOR(screen, COLOR_CYAN, COLOR_BLUE, true); + DLG_COLOR(shadow, COLOR_BLACK, COLOR_BLACK, true); + DLG_COLOR(dialog, COLOR_BLACK, COLOR_WHITE, false); + DLG_COLOR(title, COLOR_YELLOW, COLOR_WHITE, true); + DLG_COLOR(border, COLOR_WHITE, COLOR_WHITE, true); + DLG_COLOR(button_active, COLOR_WHITE, COLOR_BLUE, true); + DLG_COLOR(button_inactive, COLOR_BLACK, COLOR_WHITE, false); + DLG_COLOR(button_key_active, COLOR_WHITE, COLOR_BLUE, true); + DLG_COLOR(button_key_inactive, COLOR_RED, COLOR_WHITE, false); + DLG_COLOR(button_label_active, COLOR_YELLOW, COLOR_BLUE, true); + DLG_COLOR(button_label_inactive, COLOR_BLACK, COLOR_WHITE, true); + DLG_COLOR(inputbox, COLOR_BLACK, COLOR_WHITE, false); + DLG_COLOR(inputbox_border, COLOR_BLACK, COLOR_WHITE, false); + DLG_COLOR(searchbox, COLOR_BLACK, COLOR_WHITE, false); + DLG_COLOR(searchbox_title, COLOR_YELLOW, COLOR_WHITE, true); + DLG_COLOR(searchbox_border, COLOR_WHITE, COLOR_WHITE, true); + DLG_COLOR(position_indicator, COLOR_YELLOW, COLOR_WHITE, true); + DLG_COLOR(menubox, COLOR_BLACK, COLOR_WHITE, false); + DLG_COLOR(menubox_border, COLOR_WHITE, COLOR_WHITE, true); + DLG_COLOR(item, COLOR_BLACK, COLOR_WHITE, false); + DLG_COLOR(item_selected, COLOR_WHITE, COLOR_BLUE, true); + DLG_COLOR(tag, COLOR_YELLOW, COLOR_WHITE, true); + DLG_COLOR(tag_selected, COLOR_YELLOW, COLOR_BLUE, true); + DLG_COLOR(tag_key, COLOR_YELLOW, COLOR_WHITE, true); + DLG_COLOR(tag_key_selected, COLOR_YELLOW, COLOR_BLUE, true); + DLG_COLOR(check, COLOR_BLACK, COLOR_WHITE, false); + DLG_COLOR(check_selected, COLOR_WHITE, COLOR_BLUE, true); + DLG_COLOR(uarrow, COLOR_GREEN, COLOR_WHITE, true); + DLG_COLOR(darrow, COLOR_GREEN, COLOR_WHITE, true); +} + +static void set_blackbg_theme(void) +{ + DLG_COLOR(screen, COLOR_RED, COLOR_BLACK, true); + DLG_COLOR(shadow, COLOR_BLACK, COLOR_BLACK, false); + DLG_COLOR(dialog, COLOR_WHITE, COLOR_BLACK, false); + DLG_COLOR(title, COLOR_RED, COLOR_BLACK, false); + DLG_COLOR(border, COLOR_BLACK, COLOR_BLACK, true); + + DLG_COLOR(button_active, COLOR_YELLOW, COLOR_RED, false); + DLG_COLOR(button_inactive, COLOR_YELLOW, COLOR_BLACK, false); + DLG_COLOR(button_key_active, COLOR_YELLOW, COLOR_RED, true); + DLG_COLOR(button_key_inactive, COLOR_RED, COLOR_BLACK, false); + DLG_COLOR(button_label_active, COLOR_WHITE, COLOR_RED, false); + DLG_COLOR(button_label_inactive, COLOR_BLACK, COLOR_BLACK, true); + + DLG_COLOR(inputbox, COLOR_YELLOW, COLOR_BLACK, false); + DLG_COLOR(inputbox_border, COLOR_YELLOW, COLOR_BLACK, false); + + DLG_COLOR(searchbox, COLOR_YELLOW, COLOR_BLACK, false); + DLG_COLOR(searchbox_title, COLOR_YELLOW, COLOR_BLACK, true); + DLG_COLOR(searchbox_border, COLOR_BLACK, COLOR_BLACK, true); + + DLG_COLOR(position_indicator, COLOR_RED, COLOR_BLACK, false); + + DLG_COLOR(menubox, COLOR_YELLOW, COLOR_BLACK, false); + DLG_COLOR(menubox_border, COLOR_BLACK, COLOR_BLACK, true); + + DLG_COLOR(item, COLOR_WHITE, COLOR_BLACK, false); + DLG_COLOR(item_selected, COLOR_WHITE, COLOR_RED, false); + + DLG_COLOR(tag, COLOR_RED, COLOR_BLACK, false); + DLG_COLOR(tag_selected, COLOR_YELLOW, COLOR_RED, true); + DLG_COLOR(tag_key, COLOR_RED, COLOR_BLACK, false); + DLG_COLOR(tag_key_selected, COLOR_YELLOW, COLOR_RED, true); + + DLG_COLOR(check, COLOR_YELLOW, COLOR_BLACK, false); + DLG_COLOR(check_selected, COLOR_YELLOW, COLOR_RED, true); + + DLG_COLOR(uarrow, COLOR_RED, COLOR_BLACK, false); + DLG_COLOR(darrow, COLOR_RED, COLOR_BLACK, false); +} + +static void set_bluetitle_theme(void) +{ + set_classic_theme(); + DLG_COLOR(title, COLOR_BLUE, COLOR_WHITE, true); + DLG_COLOR(button_key_active, COLOR_YELLOW, COLOR_BLUE, true); + DLG_COLOR(button_label_active, COLOR_WHITE, COLOR_BLUE, true); + DLG_COLOR(searchbox_title, COLOR_BLUE, COLOR_WHITE, true); + DLG_COLOR(position_indicator, COLOR_BLUE, COLOR_WHITE, true); + DLG_COLOR(tag, COLOR_BLUE, COLOR_WHITE, true); + DLG_COLOR(tag_key, COLOR_BLUE, COLOR_WHITE, true); + +} + +/* + * Select color theme + */ +static int set_theme(const char *theme) +{ + int use_color = 1; + if (!theme) + set_bluetitle_theme(); + else if (strcmp(theme, "classic") == 0) + set_classic_theme(); + else if (strcmp(theme, "bluetitle") == 0) + set_bluetitle_theme(); + else if (strcmp(theme, "blackbg") == 0) + set_blackbg_theme(); + else if (strcmp(theme, "mono") == 0) + use_color = 0; + + return use_color; +} + +static void init_one_color(struct dialog_color *color) +{ + static int pair = 0; + + pair++; + init_pair(pair, color->fg, color->bg); + if (color->hl) + color->atr = A_BOLD | COLOR_PAIR(pair); + else + color->atr = COLOR_PAIR(pair); +} + +static void init_dialog_colors(void) +{ + init_one_color(&dlg.screen); + init_one_color(&dlg.shadow); + init_one_color(&dlg.dialog); + init_one_color(&dlg.title); + init_one_color(&dlg.border); + init_one_color(&dlg.button_active); + init_one_color(&dlg.button_inactive); + init_one_color(&dlg.button_key_active); + init_one_color(&dlg.button_key_inactive); + init_one_color(&dlg.button_label_active); + init_one_color(&dlg.button_label_inactive); + init_one_color(&dlg.inputbox); + init_one_color(&dlg.inputbox_border); + init_one_color(&dlg.searchbox); + init_one_color(&dlg.searchbox_title); + init_one_color(&dlg.searchbox_border); + init_one_color(&dlg.position_indicator); + init_one_color(&dlg.menubox); + init_one_color(&dlg.menubox_border); + init_one_color(&dlg.item); + init_one_color(&dlg.item_selected); + init_one_color(&dlg.tag); + init_one_color(&dlg.tag_selected); + init_one_color(&dlg.tag_key); + init_one_color(&dlg.tag_key_selected); + init_one_color(&dlg.check); + init_one_color(&dlg.check_selected); + init_one_color(&dlg.uarrow); + init_one_color(&dlg.darrow); +} + +/* + * Setup for color display + */ +static void color_setup(const char *theme) +{ + int use_color; + + use_color = set_theme(theme); + if (use_color && has_colors()) { + start_color(); + init_dialog_colors(); + } else + set_mono_theme(); +} + +/* + * Set window to attribute 'attr' + */ +void attr_clear(WINDOW * win, int height, int width, chtype attr) +{ + int i, j; + + wattrset(win, attr); + for (i = 0; i < height; i++) { + wmove(win, i, 0); + for (j = 0; j < width; j++) + waddch(win, ' '); + } + touchwin(win); +} + +void dialog_clear(void) +{ + attr_clear(stdscr, LINES, COLS, dlg.screen.atr); + /* Display background title if it exists ... - SLH */ + if (dlg.backtitle != NULL) { + int i; + + wattrset(stdscr, dlg.screen.atr); + mvwaddstr(stdscr, 0, 1, (char *)dlg.backtitle); + wmove(stdscr, 1, 1); + for (i = 1; i < COLS - 1; i++) + waddch(stdscr, ACS_HLINE); + } + wnoutrefresh(stdscr); +} + +/* + * Do some initialization for dialog + */ +int init_dialog(const char *backtitle) +{ + int height, width; + + initscr(); /* Init curses */ + getmaxyx(stdscr, height, width); + if (height < 19 || width < 80) { + endwin(); + return -ERRDISPLAYTOOSMALL; + } + + dlg.backtitle = backtitle; + color_setup(getenv("MENUCONFIG_COLOR")); + + keypad(stdscr, TRUE); + cbreak(); + noecho(); + dialog_clear(); + + return 0; +} + +void set_dialog_backtitle(const char *backtitle) +{ + dlg.backtitle = backtitle; +} + +/* + * End using dialog functions. + */ +void end_dialog(int x, int y) +{ + /* move cursor back to original position */ + move(y, x); + refresh(); + endwin(); +} + +/* Print the title of the dialog. Center the title and truncate + * tile if wider than dialog (- 2 chars). + **/ +void print_title(WINDOW *dialog, const char *title, int width) +{ + if (title) { + int tlen = MIN(width - 2, strlen(title)); + wattrset(dialog, dlg.title.atr); + mvwaddch(dialog, 0, (width - tlen) / 2 - 1, ' '); + mvwaddnstr(dialog, 0, (width - tlen)/2, title, tlen); + waddch(dialog, ' '); + } +} + +/* + * Print a string of text in a window, automatically wrap around to the + * next line if the string is too long to fit on one line. Newline + * characters '\n' are replaced by spaces. We start on a new line + * if there is no room for at least 4 nonblanks following a double-space. + */ +void print_autowrap(WINDOW * win, const char *prompt, int width, int y, int x) +{ + int newl, cur_x, cur_y; + int i, prompt_len, room, wlen; + char tempstr[MAX_LEN + 1], *word, *sp, *sp2; + + strcpy(tempstr, prompt); + + prompt_len = strlen(tempstr); + + /* + * Remove newlines + */ + for (i = 0; i < prompt_len; i++) { + if (tempstr[i] == '\n') + tempstr[i] = ' '; + } + + if (prompt_len <= width - x * 2) { /* If prompt is short */ + wmove(win, y, (width - prompt_len) / 2); + waddstr(win, tempstr); + } else { + cur_x = x; + cur_y = y; + newl = 1; + word = tempstr; + while (word && *word) { + sp = strchr(word, ' '); + if (sp) + *sp++ = 0; + + /* Wrap to next line if either the word does not fit, + or it is the first word of a new sentence, and it is + short, and the next word does not fit. */ + room = width - cur_x; + wlen = strlen(word); + if (wlen > room || + (newl && wlen < 4 && sp + && wlen + 1 + strlen(sp) > room + && (!(sp2 = strchr(sp, ' ')) + || wlen + 1 + (sp2 - sp) > room))) { + cur_y++; + cur_x = x; + } + wmove(win, cur_y, cur_x); + waddstr(win, word); + getyx(win, cur_y, cur_x); + cur_x++; + if (sp && *sp == ' ') { + cur_x++; /* double space */ + while (*++sp == ' ') ; + newl = 1; + } else + newl = 0; + word = sp; + } + } +} + +/* + * Print a button + */ +void print_button(WINDOW * win, const char *label, int y, int x, int selected) +{ + int i, temp; + + wmove(win, y, x); + wattrset(win, selected ? dlg.button_active.atr + : dlg.button_inactive.atr); + waddstr(win, "<"); + temp = strspn(label, " "); + label += temp; + wattrset(win, selected ? dlg.button_label_active.atr + : dlg.button_label_inactive.atr); + for (i = 0; i < temp; i++) + waddch(win, ' '); + wattrset(win, selected ? dlg.button_key_active.atr + : dlg.button_key_inactive.atr); + waddch(win, label[0]); + wattrset(win, selected ? dlg.button_label_active.atr + : dlg.button_label_inactive.atr); + waddstr(win, (char *)label + 1); + wattrset(win, selected ? dlg.button_active.atr + : dlg.button_inactive.atr); + waddstr(win, ">"); + wmove(win, y, x + temp + 1); +} + +/* + * Draw a rectangular box with line drawing characters + */ +void +draw_box(WINDOW * win, int y, int x, int height, int width, + chtype box, chtype border) +{ + int i, j; + + wattrset(win, 0); + for (i = 0; i < height; i++) { + wmove(win, y + i, x); + for (j = 0; j < width; j++) + if (!i && !j) + waddch(win, border | ACS_ULCORNER); + else if (i == height - 1 && !j) + waddch(win, border | ACS_LLCORNER); + else if (!i && j == width - 1) + waddch(win, box | ACS_URCORNER); + else if (i == height - 1 && j == width - 1) + waddch(win, box | ACS_LRCORNER); + else if (!i) + waddch(win, border | ACS_HLINE); + else if (i == height - 1) + waddch(win, box | ACS_HLINE); + else if (!j) + waddch(win, border | ACS_VLINE); + else if (j == width - 1) + waddch(win, box | ACS_VLINE); + else + waddch(win, box | ' '); + } +} + +/* + * Draw shadows along the right and bottom edge to give a more 3D look + * to the boxes + */ +void draw_shadow(WINDOW * win, int y, int x, int height, int width) +{ + int i; + + if (has_colors()) { /* Whether terminal supports color? */ + wattrset(win, dlg.shadow.atr); + wmove(win, y + height, x + 2); + for (i = 0; i < width; i++) + waddch(win, winch(win) & A_CHARTEXT); + for (i = y + 1; i < y + height + 1; i++) { + wmove(win, i, x + width); + waddch(win, winch(win) & A_CHARTEXT); + waddch(win, winch(win) & A_CHARTEXT); + } + wnoutrefresh(win); + } +} + +/* + * Return the position of the first alphabetic character in a string. + */ +int first_alpha(const char *string, const char *exempt) +{ + int i, in_paren = 0, c; + + for (i = 0; i < strlen(string); i++) { + c = tolower(string[i]); + + if (strchr("<[(", c)) + ++in_paren; + if (strchr(">])", c) && in_paren > 0) + --in_paren; + + if ((!in_paren) && isalpha(c) && strchr(exempt, c) == 0) + return i; + } + + return 0; +} + +/* + * ncurses uses ESC to detect escaped char sequences. This resutl in + * a small timeout before ESC is actually delivered to the application. + * lxdialog suggest which is correctly translated to two + * times esc. But then we need to ignore the second esc to avoid stepping + * out one menu too much. Filter away all escaped key sequences since + * keypad(FALSE) turn off ncurses support for escape sequences - and thats + * needed to make notimeout() do as expected. + */ +int on_key_esc(WINDOW *win) +{ + int key; + int key2; + int key3; + + nodelay(win, TRUE); + keypad(win, FALSE); + key = wgetch(win); + key2 = wgetch(win); + do { + key3 = wgetch(win); + } while (key3 != ERR); + nodelay(win, FALSE); + keypad(win, TRUE); + if (key == KEY_ESC && key2 == ERR) + return KEY_ESC; + else if (key != ERR && key != KEY_ESC && key2 == ERR) + ungetch(key); + + return -1; +} + +/* redraw screen in new size */ +int on_key_resize(void) +{ + dialog_clear(); + return KEY_RESIZE; +} + +struct dialog_list *item_cur; +struct dialog_list item_nil; +struct dialog_list *item_head; + +void item_reset(void) +{ + struct dialog_list *p, *next; + + for (p = item_head; p; p = next) { + next = p->next; + free(p); + } + item_head = NULL; + item_cur = &item_nil; +} + +void item_make(const char *fmt, ...) +{ + va_list ap; + struct dialog_list *p = malloc(sizeof(*p)); + + if (item_head) + item_cur->next = p; + else + item_head = p; + item_cur = p; + memset(p, 0, sizeof(*p)); + + va_start(ap, fmt); + vsnprintf(item_cur->node.str, sizeof(item_cur->node.str), fmt, ap); + va_end(ap); +} + +void item_add_str(const char *fmt, ...) +{ + va_list ap; + size_t avail; + + avail = sizeof(item_cur->node.str) - strlen(item_cur->node.str); + + va_start(ap, fmt); + vsnprintf(item_cur->node.str + strlen(item_cur->node.str), + avail, fmt, ap); + item_cur->node.str[sizeof(item_cur->node.str) - 1] = '\0'; + va_end(ap); +} + +void item_set_tag(char tag) +{ + item_cur->node.tag = tag; +} +void item_set_data(void *ptr) +{ + item_cur->node.data = ptr; +} + +void item_set_selected(int val) +{ + item_cur->node.selected = val; +} + +int item_activate_selected(void) +{ + item_foreach() + if (item_is_selected()) + return 1; + return 0; +} + +void *item_data(void) +{ + return item_cur->node.data; +} + +char item_tag(void) +{ + return item_cur->node.tag; +} + +int item_count(void) +{ + int n = 0; + struct dialog_list *p; + + for (p = item_head; p; p = p->next) + n++; + return n; +} + +void item_set(int n) +{ + int i = 0; + item_foreach() + if (i++ == n) + return; +} + +int item_n(void) +{ + int n = 0; + struct dialog_list *p; + + for (p = item_head; p; p = p->next) { + if (p == item_cur) + return n; + n++; + } + return 0; +} + +const char *item_str(void) +{ + return item_cur->node.str; +} + +int item_is_selected(void) +{ + return (item_cur->node.selected != 0); +} + +int item_is_tag(char tag) +{ + return (item_cur->node.tag == tag); +} diff --git a/misc/tools/kconfig-frontends/libs/lxdialog/yesno.c b/misc/tools/kconfig-frontends/libs/lxdialog/yesno.c new file mode 100644 index 0000000000..4e6e8090c2 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/lxdialog/yesno.c @@ -0,0 +1,114 @@ +/* + * yesno.c -- implements the yes/no box + * + * ORIGINAL AUTHOR: Savio Lam (lam836@cs.cuhk.hk) + * MODIFIED FOR LINUX KERNEL CONFIG BY: William Roadcap (roadcap@cfw.com) + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License + * as published by the Free Software Foundation; either version 2 + * of the License, or (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. + */ + +#include "dialog.h" + +/* + * Display termination buttons + */ +static void print_buttons(WINDOW * dialog, int height, int width, int selected) +{ + int x = width / 2 - 10; + int y = height - 2; + + print_button(dialog, gettext(" Yes "), y, x, selected == 0); + print_button(dialog, gettext(" No "), y, x + 13, selected == 1); + + wmove(dialog, y, x + 1 + 13 * selected); + wrefresh(dialog); +} + +/* + * Display a dialog box with two buttons - Yes and No + */ +int dialog_yesno(const char *title, const char *prompt, int height, int width) +{ + int i, x, y, key = 0, button = 0; + WINDOW *dialog; + +do_resize: + if (getmaxy(stdscr) < (height + 4)) + return -ERRDISPLAYTOOSMALL; + if (getmaxx(stdscr) < (width + 4)) + return -ERRDISPLAYTOOSMALL; + + /* center dialog box on screen */ + x = (COLS - width) / 2; + y = (LINES - height) / 2; + + draw_shadow(stdscr, y, x, height, width); + + dialog = newwin(height, width, y, x); + keypad(dialog, TRUE); + + draw_box(dialog, 0, 0, height, width, + dlg.dialog.atr, dlg.border.atr); + wattrset(dialog, dlg.border.atr); + mvwaddch(dialog, height - 3, 0, ACS_LTEE); + for (i = 0; i < width - 2; i++) + waddch(dialog, ACS_HLINE); + wattrset(dialog, dlg.dialog.atr); + waddch(dialog, ACS_RTEE); + + print_title(dialog, title, width); + + wattrset(dialog, dlg.dialog.atr); + print_autowrap(dialog, prompt, width - 2, 1, 3); + + print_buttons(dialog, height, width, 0); + + while (key != KEY_ESC) { + key = wgetch(dialog); + switch (key) { + case 'Y': + case 'y': + delwin(dialog); + return 0; + case 'N': + case 'n': + delwin(dialog); + return 1; + + case TAB: + case KEY_LEFT: + case KEY_RIGHT: + button = ((key == KEY_LEFT ? --button : ++button) < 0) ? 1 : (button > 1 ? 0 : button); + + print_buttons(dialog, height, width, button); + wrefresh(dialog); + break; + case ' ': + case '\n': + delwin(dialog); + return button; + case KEY_ESC: + key = on_key_esc(dialog); + break; + case KEY_RESIZE: + delwin(dialog); + on_key_resize(); + goto do_resize; + } + } + + delwin(dialog); + return key; /* ESC pressed */ +} diff --git a/misc/tools/kconfig-frontends/libs/parser/Makefile.am b/misc/tools/kconfig-frontends/libs/parser/Makefile.am new file mode 100644 index 0000000000..ad6e5aa8b6 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/Makefile.am @@ -0,0 +1,46 @@ +SUFFIXES = .gperf + +lib_LTLIBRARIES = libkconfig-parser.la +libkconfig_parser_la_SOURCES = yconf.y +dist_EXTRA_libkconfig_parser_la_SOURCES = \ + hconf.gperf lconf.l \ + confdata.c menu.c symbol.c util.c \ + expr.c expr.h lkc.h lkc_proto.h +libkconfig_parser_la_CPPFLAGS = -DROOTMENU="\"$(root_menu)\"" \ + -DCONFIG_=\"$(config_prefix)\" \ + $(intl_CPPFLAGS) +libkconfig_parser_la_CFLAGS = $(AM_CFLAGS) $(kf_CFLAGS) +libkconfig_parser_la_LDFLAGS = -release $(KCONFIGPARSER_LIB_VERSION) -no-undefined +libkconfig_parser_la_LIBADD = $(intl_LIBS) + +kconfig_includedir = $(includedir)/kconfig +kconfig_include_HEADERS = lkc.h expr.h lkc_proto.h + +BUILT_SOURCES = hconf.c lconf.c +CLEANFILES = hconf.c lconf.c yconf.c +EXTRA_DIST = yconf.y.patch + +AM_V_GPERF = $(AM_V_GPERF_$(V)) +AM_V_GPERF_ = $(AM_V_GPERF_$(AM_DEFAULT_VERBOSITY)) +AM_V_GPERF_0 = @echo " GPERF " $@; + +.gperf.c: + $(AM_V_GPERF)$(GPERF) -t --output-file $@ -a -C -E -g -k 1,3,$$ -p -t $< + +# The following rule produces a warning: +# libs/parser/Makefile.am:41: user target `.l.c' defined here... +# /usr/share/automake-1.11/am/lex.am: ... overrides Automake target +# `.l.c' defined here +# +# This is expected, and can't be avoided (for now). +# That's because, when working with lex+yacc sources, the default is to +# build each files searately, and then link them together into the final +# output. But the Linux kernel's parser simply #include-s the lexer, +# so we can't put lconf.l into the _SOURCES (it's in EXTRA_SOURCES), +# and thus automake does not catch the need to call lex. +# Secondly, when flex is told to change the symbols' prefix (kconfig +# uses zconf in lieue of the original yy), then the output file is +# also renamed, but automake does not now that, and make would fail +# because it would think no file was generated. +.l.c: + $(AM_V_LEX)$(LEXCOMPILE) -o$@ $< diff --git a/misc/tools/kconfig-frontends/libs/parser/Makefile.in b/misc/tools/kconfig-frontends/libs/parser/Makefile.in new file mode 100644 index 0000000000..97793927c3 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/Makefile.in @@ -0,0 +1,749 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ + + +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +subdir = libs/parser +DIST_COMMON = $(kconfig_include_HEADERS) $(srcdir)/Makefile.am \ + $(srcdir)/Makefile.in lconf.c yconf.c +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +am__vpath_adj_setup = srcdirstrip=`echo "$(srcdir)" | sed 's|.|.|g'`; +am__vpath_adj = case $$p in \ + $(srcdir)/*) f=`echo "$$p" | sed "s|^$$srcdirstrip/||"`;; \ + *) f=$$p;; \ + esac; +am__strip_dir = f=`echo $$p | sed -e 's|^.*/||'`; +am__install_max = 40 +am__nobase_strip_setup = \ + srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*|]/\\\\&/g'` +am__nobase_strip = \ + for p in $$list; do echo "$$p"; done | sed -e "s|$$srcdirstrip/||" +am__nobase_list = $(am__nobase_strip_setup); \ + for p in $$list; do echo "$$p $$p"; done | \ + sed "s| $$srcdirstrip/| |;"' / .*\//!s/ .*/ ./; s,\( .*\)/[^/]*$$,\1,' | \ + $(AWK) 'BEGIN { files["."] = "" } { files[$$2] = files[$$2] " " $$1; \ + if (++n[$$2] == $(am__install_max)) \ + { print $$2, files[$$2]; n[$$2] = 0; files[$$2] = "" } } \ + END { for (dir in files) print dir, files[dir] }' +am__base_list = \ + sed '$$!N;$$!N;$$!N;$$!N;$$!N;$$!N;$$!N;s/\n/ /g' | \ + sed '$$!N;$$!N;$$!N;$$!N;s/\n/ /g' +am__installdirs = "$(DESTDIR)$(libdir)" \ + "$(DESTDIR)$(kconfig_includedir)" +LTLIBRARIES = $(lib_LTLIBRARIES) +am__DEPENDENCIES_1 = +libkconfig_parser_la_DEPENDENCIES = $(am__DEPENDENCIES_1) +am_libkconfig_parser_la_OBJECTS = libkconfig_parser_la-yconf.lo +libkconfig_parser_la_OBJECTS = $(am_libkconfig_parser_la_OBJECTS) +AM_V_lt = $(am__v_lt_$(V)) +am__v_lt_ = $(am__v_lt_$(AM_DEFAULT_VERBOSITY)) +am__v_lt_0 = --silent +libkconfig_parser_la_LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC \ + $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=link $(CCLD) \ + $(libkconfig_parser_la_CFLAGS) $(CFLAGS) \ + $(libkconfig_parser_la_LDFLAGS) $(LDFLAGS) -o $@ +DEFAULT_INCLUDES = -I.@am__isrc@ -I$(top_builddir)/scripts/.autostuff +depcomp = $(SHELL) $(top_srcdir)/scripts/.autostuff/scripts/depcomp +am__depfiles_maybe = depfiles +am__mv = mv -f +COMPILE = $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) \ + $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) +LTCOMPILE = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) \ + $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) $(CPPFLAGS) \ + $(AM_CFLAGS) $(CFLAGS) +AM_V_CC = $(am__v_CC_$(V)) +am__v_CC_ = $(am__v_CC_$(AM_DEFAULT_VERBOSITY)) +am__v_CC_0 = @echo " CC " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +CCLD = $(CC) +LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(AM_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +AM_V_CCLD = $(am__v_CCLD_$(V)) +am__v_CCLD_ = $(am__v_CCLD_$(AM_DEFAULT_VERBOSITY)) +am__v_CCLD_0 = @echo " CCLD " $@; +LEXCOMPILE = $(LEX) $(LFLAGS) $(AM_LFLAGS) +LTLEXCOMPILE = $(LIBTOOL) $(AM_V_lt) $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(LEX) $(LFLAGS) $(AM_LFLAGS) +AM_V_LEX = $(am__v_LEX_$(V)) +am__v_LEX_ = $(am__v_LEX_$(AM_DEFAULT_VERBOSITY)) +am__v_LEX_0 = @echo " LEX " $@; +YLWRAP = $(top_srcdir)/scripts/.autostuff/scripts/ylwrap +YACCCOMPILE = $(YACC) $(YFLAGS) $(AM_YFLAGS) +LTYACCCOMPILE = $(LIBTOOL) $(AM_V_lt) $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(YACC) $(YFLAGS) $(AM_YFLAGS) +AM_V_YACC = $(am__v_YACC_$(V)) +am__v_YACC_ = $(am__v_YACC_$(AM_DEFAULT_VERBOSITY)) +am__v_YACC_0 = @echo " YACC " $@; +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +SOURCES = $(libkconfig_parser_la_SOURCES) \ + $(dist_EXTRA_libkconfig_parser_la_SOURCES) +DIST_SOURCES = $(libkconfig_parser_la_SOURCES) \ + $(dist_EXTRA_libkconfig_parser_la_SOURCES) +HEADERS = $(kconfig_include_HEADERS) +ETAGS = etags +CTAGS = ctags +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +SUFFIXES = .gperf +lib_LTLIBRARIES = libkconfig-parser.la +libkconfig_parser_la_SOURCES = yconf.y +dist_EXTRA_libkconfig_parser_la_SOURCES = \ + hconf.gperf lconf.l \ + confdata.c menu.c symbol.c util.c \ + expr.c expr.h lkc.h lkc_proto.h + +libkconfig_parser_la_CPPFLAGS = -DROOTMENU="\"$(root_menu)\"" \ + -DCONFIG_=\"$(config_prefix)\" \ + $(intl_CPPFLAGS) + +libkconfig_parser_la_CFLAGS = $(AM_CFLAGS) $(kf_CFLAGS) +libkconfig_parser_la_LDFLAGS = -release $(KCONFIGPARSER_LIB_VERSION) -no-undefined +libkconfig_parser_la_LIBADD = $(intl_LIBS) +kconfig_includedir = $(includedir)/kconfig +kconfig_include_HEADERS = lkc.h expr.h lkc_proto.h +BUILT_SOURCES = hconf.c lconf.c +CLEANFILES = hconf.c lconf.c yconf.c +EXTRA_DIST = yconf.y.patch +AM_V_GPERF = $(AM_V_GPERF_$(V)) +AM_V_GPERF_ = $(AM_V_GPERF_$(AM_DEFAULT_VERBOSITY)) +AM_V_GPERF_0 = @echo " GPERF " $@; +all: $(BUILT_SOURCES) + $(MAKE) $(AM_MAKEFLAGS) all-am + +.SUFFIXES: +.SUFFIXES: .gperf .c .l .lo .o .obj .y +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign libs/parser/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign libs/parser/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): +install-libLTLIBRARIES: $(lib_LTLIBRARIES) + @$(NORMAL_INSTALL) + test -z "$(libdir)" || $(MKDIR_P) "$(DESTDIR)$(libdir)" + @list='$(lib_LTLIBRARIES)'; test -n "$(libdir)" || list=; \ + list2=; for p in $$list; do \ + if test -f $$p; then \ + list2="$$list2 $$p"; \ + else :; fi; \ + done; \ + test -z "$$list2" || { \ + echo " $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL) $(INSTALL_STRIP_FLAG) $$list2 '$(DESTDIR)$(libdir)'"; \ + $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL) $(INSTALL_STRIP_FLAG) $$list2 "$(DESTDIR)$(libdir)"; \ + } + +uninstall-libLTLIBRARIES: + @$(NORMAL_UNINSTALL) + @list='$(lib_LTLIBRARIES)'; test -n "$(libdir)" || list=; \ + for p in $$list; do \ + $(am__strip_dir) \ + echo " $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=uninstall rm -f '$(DESTDIR)$(libdir)/$$f'"; \ + $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=uninstall rm -f "$(DESTDIR)$(libdir)/$$f"; \ + done + +clean-libLTLIBRARIES: + -test -z "$(lib_LTLIBRARIES)" || rm -f $(lib_LTLIBRARIES) + @list='$(lib_LTLIBRARIES)'; for p in $$list; do \ + dir="`echo $$p | sed -e 's|/[^/]*$$||'`"; \ + test "$$dir" != "$$p" || dir=.; \ + echo "rm -f \"$${dir}/so_locations\""; \ + rm -f "$${dir}/so_locations"; \ + done +libkconfig-parser.la: $(libkconfig_parser_la_OBJECTS) $(libkconfig_parser_la_DEPENDENCIES) + $(AM_V_CCLD)$(libkconfig_parser_la_LINK) -rpath $(libdir) $(libkconfig_parser_la_OBJECTS) $(libkconfig_parser_la_LIBADD) $(LIBS) + +mostlyclean-compile: + -rm -f *.$(OBJEXT) + +distclean-compile: + -rm -f *.tab.c + +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_parser_la-confdata.Plo@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_parser_la-expr.Plo@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_parser_la-hconf.Plo@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_parser_la-lconf.Plo@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_parser_la-menu.Plo@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_parser_la-symbol.Plo@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_parser_la-util.Plo@am__quote@ +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/libkconfig_parser_la-yconf.Plo@am__quote@ + +.c.o: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c $< + +.c.obj: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ `$(CYGPATH_W) '$<'` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c `$(CYGPATH_W) '$<'` + +.c.lo: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LTCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LTCOMPILE) -c -o $@ $< + +libkconfig_parser_la-yconf.lo: yconf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -MT libkconfig_parser_la-yconf.lo -MD -MP -MF $(DEPDIR)/libkconfig_parser_la-yconf.Tpo -c -o libkconfig_parser_la-yconf.lo `test -f 'yconf.c' || echo '$(srcdir)/'`yconf.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_parser_la-yconf.Tpo $(DEPDIR)/libkconfig_parser_la-yconf.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='yconf.c' object='libkconfig_parser_la-yconf.lo' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -c -o libkconfig_parser_la-yconf.lo `test -f 'yconf.c' || echo '$(srcdir)/'`yconf.c + +libkconfig_parser_la-hconf.lo: hconf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -MT libkconfig_parser_la-hconf.lo -MD -MP -MF $(DEPDIR)/libkconfig_parser_la-hconf.Tpo -c -o libkconfig_parser_la-hconf.lo `test -f 'hconf.c' || echo '$(srcdir)/'`hconf.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_parser_la-hconf.Tpo $(DEPDIR)/libkconfig_parser_la-hconf.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='hconf.c' object='libkconfig_parser_la-hconf.lo' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -c -o libkconfig_parser_la-hconf.lo `test -f 'hconf.c' || echo '$(srcdir)/'`hconf.c + +libkconfig_parser_la-lconf.lo: lconf.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -MT libkconfig_parser_la-lconf.lo -MD -MP -MF $(DEPDIR)/libkconfig_parser_la-lconf.Tpo -c -o libkconfig_parser_la-lconf.lo `test -f 'lconf.c' || echo '$(srcdir)/'`lconf.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_parser_la-lconf.Tpo $(DEPDIR)/libkconfig_parser_la-lconf.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='lconf.c' object='libkconfig_parser_la-lconf.lo' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -c -o libkconfig_parser_la-lconf.lo `test -f 'lconf.c' || echo '$(srcdir)/'`lconf.c + +libkconfig_parser_la-confdata.lo: confdata.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -MT libkconfig_parser_la-confdata.lo -MD -MP -MF $(DEPDIR)/libkconfig_parser_la-confdata.Tpo -c -o libkconfig_parser_la-confdata.lo `test -f 'confdata.c' || echo '$(srcdir)/'`confdata.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_parser_la-confdata.Tpo $(DEPDIR)/libkconfig_parser_la-confdata.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='confdata.c' object='libkconfig_parser_la-confdata.lo' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -c -o libkconfig_parser_la-confdata.lo `test -f 'confdata.c' || echo '$(srcdir)/'`confdata.c + +libkconfig_parser_la-menu.lo: menu.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -MT libkconfig_parser_la-menu.lo -MD -MP -MF $(DEPDIR)/libkconfig_parser_la-menu.Tpo -c -o libkconfig_parser_la-menu.lo `test -f 'menu.c' || echo '$(srcdir)/'`menu.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_parser_la-menu.Tpo $(DEPDIR)/libkconfig_parser_la-menu.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='menu.c' object='libkconfig_parser_la-menu.lo' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -c -o libkconfig_parser_la-menu.lo `test -f 'menu.c' || echo '$(srcdir)/'`menu.c + +libkconfig_parser_la-symbol.lo: symbol.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -MT libkconfig_parser_la-symbol.lo -MD -MP -MF $(DEPDIR)/libkconfig_parser_la-symbol.Tpo -c -o libkconfig_parser_la-symbol.lo `test -f 'symbol.c' || echo '$(srcdir)/'`symbol.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_parser_la-symbol.Tpo $(DEPDIR)/libkconfig_parser_la-symbol.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='symbol.c' object='libkconfig_parser_la-symbol.lo' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -c -o libkconfig_parser_la-symbol.lo `test -f 'symbol.c' || echo '$(srcdir)/'`symbol.c + +libkconfig_parser_la-util.lo: util.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -MT libkconfig_parser_la-util.lo -MD -MP -MF $(DEPDIR)/libkconfig_parser_la-util.Tpo -c -o libkconfig_parser_la-util.lo `test -f 'util.c' || echo '$(srcdir)/'`util.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_parser_la-util.Tpo $(DEPDIR)/libkconfig_parser_la-util.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='util.c' object='libkconfig_parser_la-util.lo' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -c -o libkconfig_parser_la-util.lo `test -f 'util.c' || echo '$(srcdir)/'`util.c + +libkconfig_parser_la-expr.lo: expr.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -MT libkconfig_parser_la-expr.lo -MD -MP -MF $(DEPDIR)/libkconfig_parser_la-expr.Tpo -c -o libkconfig_parser_la-expr.lo `test -f 'expr.c' || echo '$(srcdir)/'`expr.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/libkconfig_parser_la-expr.Tpo $(DEPDIR)/libkconfig_parser_la-expr.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='expr.c' object='libkconfig_parser_la-expr.lo' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(libkconfig_parser_la_CPPFLAGS) $(CPPFLAGS) $(libkconfig_parser_la_CFLAGS) $(CFLAGS) -c -o libkconfig_parser_la-expr.lo `test -f 'expr.c' || echo '$(srcdir)/'`expr.c + +.y.c: + $(AM_V_YACC)$(am__skipyacc) $(SHELL) $(YLWRAP) $< y.tab.c $@ y.tab.h $*.h y.output $*.output -- $(YACCCOMPILE) + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs +install-kconfig_includeHEADERS: $(kconfig_include_HEADERS) + @$(NORMAL_INSTALL) + test -z "$(kconfig_includedir)" || $(MKDIR_P) "$(DESTDIR)$(kconfig_includedir)" + @list='$(kconfig_include_HEADERS)'; test -n "$(kconfig_includedir)" || list=; \ + for p in $$list; do \ + if test -f "$$p"; then d=; else d="$(srcdir)/"; fi; \ + echo "$$d$$p"; \ + done | $(am__base_list) | \ + while read files; do \ + echo " $(INSTALL_HEADER) $$files '$(DESTDIR)$(kconfig_includedir)'"; \ + $(INSTALL_HEADER) $$files "$(DESTDIR)$(kconfig_includedir)" || exit $$?; \ + done + +uninstall-kconfig_includeHEADERS: + @$(NORMAL_UNINSTALL) + @list='$(kconfig_include_HEADERS)'; test -n "$(kconfig_includedir)" || list=; \ + files=`for p in $$list; do echo $$p; done | sed -e 's|^.*/||'`; \ + test -n "$$files" || exit 0; \ + echo " ( cd '$(DESTDIR)$(kconfig_includedir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(kconfig_includedir)" && rm -f $$files + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: $(BUILT_SOURCES) + $(MAKE) $(AM_MAKEFLAGS) check-am +all-am: Makefile $(LTLIBRARIES) $(HEADERS) +installdirs: + for dir in "$(DESTDIR)$(libdir)" "$(DESTDIR)$(kconfig_includedir)"; do \ + test -z "$$dir" || $(MKDIR_P) "$$dir"; \ + done +install: $(BUILT_SOURCES) + $(MAKE) $(AM_MAKEFLAGS) install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + -test -z "$(CLEANFILES)" || rm -f $(CLEANFILES) + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." + -rm -f lconf.c + -rm -f yconf.c + -test -z "$(BUILT_SOURCES)" || rm -f $(BUILT_SOURCES) +clean: clean-am + +clean-am: clean-generic clean-libLTLIBRARIES clean-libtool \ + mostlyclean-am + +distclean: distclean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +distclean-am: clean-am distclean-compile distclean-generic \ + distclean-tags + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: install-kconfig_includeHEADERS + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: install-libLTLIBRARIES + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: uninstall-kconfig_includeHEADERS \ + uninstall-libLTLIBRARIES + +.MAKE: all check install install-am install-strip + +.PHONY: CTAGS GTAGS all all-am check check-am clean clean-generic \ + clean-libLTLIBRARIES clean-libtool ctags distclean \ + distclean-compile distclean-generic distclean-libtool \ + distclean-tags distdir dvi dvi-am html html-am info info-am \ + install install-am install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am \ + install-kconfig_includeHEADERS install-libLTLIBRARIES \ + install-man install-pdf install-pdf-am install-ps \ + install-ps-am install-strip installcheck installcheck-am \ + installdirs maintainer-clean maintainer-clean-generic \ + mostlyclean mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool pdf pdf-am ps ps-am tags uninstall \ + uninstall-am uninstall-kconfig_includeHEADERS \ + uninstall-libLTLIBRARIES + + +.gperf.c: + $(AM_V_GPERF)$(GPERF) -t --output-file $@ -a -C -E -g -k 1,3,$$ -p -t $< + +# The following rule produces a warning: +# libs/parser/Makefile.am:41: user target `.l.c' defined here... +# /usr/share/automake-1.11/am/lex.am: ... overrides Automake target +# `.l.c' defined here +# +# This is expected, and can't be avoided (for now). +# That's because, when working with lex+yacc sources, the default is to +# build each files searately, and then link them together into the final +# output. But the Linux kernel's parser simply #include-s the lexer, +# so we can't put lconf.l into the _SOURCES (it's in EXTRA_SOURCES), +# and thus automake does not catch the need to call lex. +# Secondly, when flex is told to change the symbols' prefix (kconfig +# uses zconf in lieue of the original yy), then the output file is +# also renamed, but automake does not now that, and make would fail +# because it would think no file was generated. +.l.c: + $(AM_V_LEX)$(LEXCOMPILE) -o$@ $< + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/libs/parser/confdata.c b/misc/tools/kconfig-frontends/libs/parser/confdata.c new file mode 100644 index 0000000000..13ddf1126c --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/confdata.c @@ -0,0 +1,1164 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "lkc.h" + +static void conf_warning(const char *fmt, ...) + __attribute__ ((format (printf, 1, 2))); + +static void conf_message(const char *fmt, ...) + __attribute__ ((format (printf, 1, 2))); + +static const char *conf_filename; +static int conf_lineno, conf_warnings, conf_unsaved; + +const char conf_defname[] = "arch/$ARCH/defconfig"; + +static void conf_warning(const char *fmt, ...) +{ + va_list ap; + va_start(ap, fmt); + fprintf(stderr, "%s:%d:warning: ", conf_filename, conf_lineno); + vfprintf(stderr, fmt, ap); + fprintf(stderr, "\n"); + va_end(ap); + conf_warnings++; +} + +static void conf_default_message_callback(const char *fmt, va_list ap) +{ + printf("#\n# "); + vprintf(fmt, ap); + printf("\n#\n"); +} + +static void (*conf_message_callback) (const char *fmt, va_list ap) = + conf_default_message_callback; +void conf_set_message_callback(void (*fn) (const char *fmt, va_list ap)) +{ + conf_message_callback = fn; +} + +static void conf_message(const char *fmt, ...) +{ + va_list ap; + + va_start(ap, fmt); + if (conf_message_callback) + conf_message_callback(fmt, ap); +} + +const char *conf_get_configname(void) +{ + char *name = getenv("KCONFIG_CONFIG"); + + return name ? name : ".config"; +} + +const char *conf_get_autoconfig_name(void) +{ + char *name = getenv("KCONFIG_AUTOCONFIG"); + + return name ? name : "include/config/auto.conf"; +} + +static char *conf_expand_value(const char *in) +{ + struct symbol *sym; + const char *src; + static char res_value[SYMBOL_MAXLENGTH]; + char *dst, name[SYMBOL_MAXLENGTH]; + + res_value[0] = 0; + dst = name; + while ((src = strchr(in, '$'))) { + strncat(res_value, in, src - in); + src++; + dst = name; + while (isalnum(*src) || *src == '_') + *dst++ = *src++; + *dst = 0; + sym = sym_lookup(name, 0); + sym_calc_value(sym); + strcat(res_value, sym_get_string_value(sym)); + in = src; + } + strcat(res_value, in); + + return res_value; +} + +char *conf_get_default_confname(void) +{ + struct stat buf; + static char fullname[PATH_MAX+1]; + char *env, *name; + + name = conf_expand_value(conf_defname); + env = getenv(SRCTREE); + if (env) { + sprintf(fullname, "%s/%s", env, name); + if (!stat(fullname, &buf)) + return fullname; + } + return name; +} + +static int conf_set_sym_val(struct symbol *sym, int def, int def_flags, char *p) +{ + char *p2; + + switch (sym->type) { + case S_TRISTATE: + if (p[0] == 'm') { + sym->def[def].tri = mod; + sym->flags |= def_flags; + break; + } + /* fall through */ + case S_BOOLEAN: + if (p[0] == 'y') { + sym->def[def].tri = yes; + sym->flags |= def_flags; + break; + } + if (p[0] == 'n') { + sym->def[def].tri = no; + sym->flags |= def_flags; + break; + } + conf_warning("symbol value '%s' invalid for %s", p, sym->name); + return 1; + case S_OTHER: + if (*p != '"') { + for (p2 = p; *p2 && !isspace(*p2); p2++) + ; + sym->type = S_STRING; + goto done; + } + /* fall through */ + case S_STRING: + if (*p++ != '"') + break; + for (p2 = p; (p2 = strpbrk(p2, "\"\\")); p2++) { + if (*p2 == '"') { + *p2 = 0; + break; + } + memmove(p2, p2 + 1, strlen(p2)); + } + if (!p2) { + conf_warning("invalid string found"); + return 1; + } + /* fall through */ + case S_INT: + case S_HEX: + done: + if (sym_string_valid(sym, p)) { + sym->def[def].val = strdup(p); + sym->flags |= def_flags; + } else { + conf_warning("symbol value '%s' invalid for %s", p, sym->name); + return 1; + } + break; + default: + ; + } + return 0; +} + +#define LINE_GROWTH 16 +static int add_byte(int c, char **lineptr, size_t slen, size_t *n) +{ + char *nline; + size_t new_size = slen + 1; + if (new_size > *n) { + new_size += LINE_GROWTH - 1; + new_size *= 2; + nline = realloc(*lineptr, new_size); + if (!nline) + return -1; + + *lineptr = nline; + *n = new_size; + } + + (*lineptr)[slen] = c; + + return 0; +} + +static ssize_t compat_getline(char **lineptr, size_t *n, FILE *stream) +{ + char *line = *lineptr; + size_t slen = 0; + + for (;;) { + int c = getc(stream); + + switch (c) { + case '\n': + if (add_byte(c, &line, slen, n) < 0) + goto e_out; + slen++; + /* fall through */ + case EOF: + if (add_byte('\0', &line, slen, n) < 0) + goto e_out; + *lineptr = line; + if (slen == 0) + return -1; + return slen; + default: + if (add_byte(c, &line, slen, n) < 0) + goto e_out; + slen++; + } + } + +e_out: + line[slen-1] = '\0'; + *lineptr = line; + return -1; +} + +int conf_read_simple(const char *name, int def) +{ + FILE *in = NULL; + char *line = NULL; + size_t line_asize = 0; + char *p, *p2; + struct symbol *sym; + int i, def_flags; + + if (name) { + in = zconf_fopen(name); + } else { + struct property *prop; + + name = conf_get_configname(); + in = zconf_fopen(name); + if (in) + goto load; + sym_add_change_count(1); + if (!sym_defconfig_list) { + if (modules_sym) + sym_calc_value(modules_sym); + return 1; + } + + for_all_defaults(sym_defconfig_list, prop) { + if (expr_calc_value(prop->visible.expr) == no || + prop->expr->type != E_SYMBOL) + continue; + name = conf_expand_value(prop->expr->left.sym->name); + in = zconf_fopen(name); + if (in) { + conf_message(_("using defaults found in %s"), + name); + goto load; + } + } + } + if (!in) + return 1; + +load: + conf_filename = name; + conf_lineno = 0; + conf_warnings = 0; + conf_unsaved = 0; + + def_flags = SYMBOL_DEF << def; + for_all_symbols(i, sym) { + sym->flags |= SYMBOL_CHANGED; + sym->flags &= ~(def_flags|SYMBOL_VALID); + if (sym_is_choice(sym)) + sym->flags |= def_flags; + switch (sym->type) { + case S_INT: + case S_HEX: + case S_STRING: + if (sym->def[def].val) + free(sym->def[def].val); + /* fall through */ + default: + sym->def[def].val = NULL; + sym->def[def].tri = no; + } + } + + while (compat_getline(&line, &line_asize, in) != -1) { + conf_lineno++; + sym = NULL; + if (line[0] == '#') { + if (memcmp(line + 2, CONFIG_, strlen(CONFIG_))) + continue; + p = strchr(line + 2 + strlen(CONFIG_), ' '); + if (!p) + continue; + *p++ = 0; + if (strncmp(p, "is not set", 10)) + continue; + if (def == S_DEF_USER) { + sym = sym_find(line + 2 + strlen(CONFIG_)); + if (!sym) { + sym_add_change_count(1); + goto setsym; + } + } else { + sym = sym_lookup(line + 2 + strlen(CONFIG_), 0); + if (sym->type == S_UNKNOWN) + sym->type = S_BOOLEAN; + } + if (sym->flags & def_flags) { + conf_warning("override: reassigning to symbol %s", sym->name); + } + switch (sym->type) { + case S_BOOLEAN: + case S_TRISTATE: + sym->def[def].tri = no; + sym->flags |= def_flags; + break; + default: + ; + } + } else if (memcmp(line, CONFIG_, strlen(CONFIG_)) == 0) { + p = strchr(line + strlen(CONFIG_), '='); + if (!p) + continue; + *p++ = 0; + p2 = strchr(p, '\n'); + if (p2) { + *p2-- = 0; + if (*p2 == '\r') + *p2 = 0; + } + if (def == S_DEF_USER) { + sym = sym_find(line + strlen(CONFIG_)); + if (!sym) { + sym_add_change_count(1); + goto setsym; + } + } else { + sym = sym_lookup(line + strlen(CONFIG_), 0); + if (sym->type == S_UNKNOWN) + sym->type = S_OTHER; + } + if (sym->flags & def_flags) { + conf_warning("override: reassigning to symbol %s", sym->name); + } + if (conf_set_sym_val(sym, def, def_flags, p)) + continue; + } else { + if (line[0] != '\r' && line[0] != '\n') + conf_warning("unexpected data"); + continue; + } +setsym: + if (sym && sym_is_choice_value(sym)) { + struct symbol *cs = prop_get_symbol(sym_get_choice_prop(sym)); + switch (sym->def[def].tri) { + case no: + break; + case mod: + if (cs->def[def].tri == yes) { + conf_warning("%s creates inconsistent choice state", sym->name); + cs->flags &= ~def_flags; + } + break; + case yes: + if (cs->def[def].tri != no) + conf_warning("override: %s changes choice state", sym->name); + cs->def[def].val = sym; + break; + } + cs->def[def].tri = EXPR_OR(cs->def[def].tri, sym->def[def].tri); + } + } + free(line); + fclose(in); + + if (modules_sym) + sym_calc_value(modules_sym); + return 0; +} + +int conf_read(const char *name) +{ + struct symbol *sym; + int i; + + sym_set_change_count(0); + + if (conf_read_simple(name, S_DEF_USER)) + return 1; + + for_all_symbols(i, sym) { + sym_calc_value(sym); + if (sym_is_choice(sym) || (sym->flags & SYMBOL_AUTO)) + continue; + if (sym_has_value(sym) && (sym->flags & SYMBOL_WRITE)) { + /* check that calculated value agrees with saved value */ + switch (sym->type) { + case S_BOOLEAN: + case S_TRISTATE: + if (sym->def[S_DEF_USER].tri != sym_get_tristate_value(sym)) + break; + if (!sym_is_choice(sym)) + continue; + /* fall through */ + default: + if (!strcmp(sym->curr.val, sym->def[S_DEF_USER].val)) + continue; + break; + } + } else if (!sym_has_value(sym) && !(sym->flags & SYMBOL_WRITE)) + /* no previous value and not saved */ + continue; + conf_unsaved++; + /* maybe print value in verbose mode... */ + } + + for_all_symbols(i, sym) { + if (sym_has_value(sym) && !sym_is_choice_value(sym)) { + /* Reset values of generates values, so they'll appear + * as new, if they should become visible, but that + * doesn't quite work if the Kconfig and the saved + * configuration disagree. + */ + if (sym->visible == no && !conf_unsaved) + sym->flags &= ~SYMBOL_DEF_USER; + switch (sym->type) { + case S_STRING: + case S_INT: + case S_HEX: + /* Reset a string value if it's out of range */ + if (sym_string_within_range(sym, sym->def[S_DEF_USER].val)) + break; + sym->flags &= ~(SYMBOL_VALID|SYMBOL_DEF_USER); + conf_unsaved++; + break; + default: + break; + } + } + } + + sym_add_change_count(conf_warnings || conf_unsaved); + + return 0; +} + +/* + * Kconfig configuration printer + * + * This printer is used when generating the resulting configuration after + * kconfig invocation and `defconfig' files. Unset symbol might be omitted by + * passing a non-NULL argument to the printer. + * + */ +static void +kconfig_print_symbol(FILE *fp, struct symbol *sym, const char *value, void *arg) +{ + + switch (sym->type) { + case S_BOOLEAN: + case S_TRISTATE: + if (*value == 'n') { + bool skip_unset = (arg != NULL); + + if (!skip_unset) + fprintf(fp, "# %s%s is not set\n", + CONFIG_, sym->name); + return; + } + break; + default: + break; + } + + fprintf(fp, "%s%s=%s\n", CONFIG_, sym->name, value); +} + +static void +kconfig_print_comment(FILE *fp, const char *value, void *arg) +{ + const char *p = value; + size_t l; + + for (;;) { + l = strcspn(p, "\n"); + fprintf(fp, "#"); + if (l) { + fprintf(fp, " "); + xfwrite(p, l, 1, fp); + p += l; + } + fprintf(fp, "\n"); + if (*p++ == '\0') + break; + } +} + +static struct conf_printer kconfig_printer_cb = +{ + .print_symbol = kconfig_print_symbol, + .print_comment = kconfig_print_comment, +}; + +/* + * Header printer + * + * This printer is used when generating the `include/generated/autoconf.h' file. + */ +static void +header_print_symbol(FILE *fp, struct symbol *sym, const char *value, void *arg) +{ + + switch (sym->type) { + case S_BOOLEAN: + case S_TRISTATE: { + const char *suffix = ""; + + switch (*value) { + case 'n': + break; + case 'm': + suffix = "_MODULE"; + /* fall through */ + default: + fprintf(fp, "#define %s%s%s 1\n", + CONFIG_, sym->name, suffix); + } + break; + } + case S_HEX: { + const char *prefix = ""; + + if (value[0] != '0' || (value[1] != 'x' && value[1] != 'X')) + prefix = "0x"; + fprintf(fp, "#define %s%s %s%s\n", + CONFIG_, sym->name, prefix, value); + break; + } + case S_STRING: + case S_INT: + fprintf(fp, "#define %s%s %s\n", + CONFIG_, sym->name, value); + break; + default: + break; + } + +} + +static void +header_print_comment(FILE *fp, const char *value, void *arg) +{ + const char *p = value; + size_t l; + + fprintf(fp, "/*\n"); + for (;;) { + l = strcspn(p, "\n"); + fprintf(fp, " *"); + if (l) { + fprintf(fp, " "); + xfwrite(p, l, 1, fp); + p += l; + } + fprintf(fp, "\n"); + if (*p++ == '\0') + break; + } + fprintf(fp, " */\n"); +} + +static struct conf_printer header_printer_cb = +{ + .print_symbol = header_print_symbol, + .print_comment = header_print_comment, +}; + +/* + * Tristate printer + * + * This printer is used when generating the `include/config/tristate.conf' file. + */ +static void +tristate_print_symbol(FILE *fp, struct symbol *sym, const char *value, void *arg) +{ + + if (sym->type == S_TRISTATE && *value != 'n') + fprintf(fp, "%s%s=%c\n", CONFIG_, sym->name, (char)toupper(*value)); +} + +static struct conf_printer tristate_printer_cb = +{ + .print_symbol = tristate_print_symbol, + .print_comment = kconfig_print_comment, +}; + +static void conf_write_symbol(FILE *fp, struct symbol *sym, + struct conf_printer *printer, void *printer_arg) +{ + const char *str; + + switch (sym->type) { + case S_OTHER: + case S_UNKNOWN: + break; + case S_STRING: + str = sym_get_string_value(sym); + str = sym_escape_string_value(str); + printer->print_symbol(fp, sym, str, printer_arg); + free((void *)str); + break; + default: + str = sym_get_string_value(sym); + printer->print_symbol(fp, sym, str, printer_arg); + } +} + +static void +conf_write_heading(FILE *fp, struct conf_printer *printer, void *printer_arg) +{ + char buf[256]; + + snprintf(buf, sizeof(buf), + "\n" + "Automatically generated file; DO NOT EDIT.\n" + "%s\n", + rootmenu.prompt->text); + + printer->print_comment(fp, buf, printer_arg); +} + +/* + * Write out a minimal config. + * All values that has default values are skipped as this is redundant. + */ +int conf_write_defconfig(const char *filename) +{ + struct symbol *sym; + struct menu *menu; + FILE *out; + + out = fopen(filename, "w"); + if (!out) + return 1; + + sym_clear_all_valid(); + + /* Traverse all menus to find all relevant symbols */ + menu = rootmenu.list; + + while (menu != NULL) + { + sym = menu->sym; + if (sym == NULL) { + if (!menu_is_visible(menu)) + goto next_menu; + } else if (!sym_is_choice(sym)) { + sym_calc_value(sym); + if (!(sym->flags & SYMBOL_WRITE)) + goto next_menu; + sym->flags &= ~SYMBOL_WRITE; + /* If we cannot change the symbol - skip */ + if (!sym_is_changable(sym)) + goto next_menu; + /* If symbol equals to default value - skip */ + if (strcmp(sym_get_string_value(sym), sym_get_string_default(sym)) == 0) + goto next_menu; + + /* + * If symbol is a choice value and equals to the + * default for a choice - skip. + * But only if value is bool and equal to "y" and + * choice is not "optional". + * (If choice is "optional" then all values can be "n") + */ + if (sym_is_choice_value(sym)) { + struct symbol *cs; + struct symbol *ds; + + cs = prop_get_symbol(sym_get_choice_prop(sym)); + ds = sym_choice_default(cs); + if (!sym_is_optional(cs) && sym == ds) { + if ((sym->type == S_BOOLEAN) && + sym_get_tristate_value(sym) == yes) + goto next_menu; + } + } + conf_write_symbol(out, sym, &kconfig_printer_cb, NULL); + } +next_menu: + if (menu->list != NULL) { + menu = menu->list; + } + else if (menu->next != NULL) { + menu = menu->next; + } else { + while ((menu = menu->parent)) { + if (menu->next != NULL) { + menu = menu->next; + break; + } + } + } + } + fclose(out); + return 0; +} + +int conf_write(const char *name) +{ + FILE *out; + struct symbol *sym; + struct menu *menu; + const char *basename; + const char *str; + char dirname[PATH_MAX+1], tmpname[PATH_MAX+1], newname[PATH_MAX+1]; + char *env; + + dirname[0] = 0; + if (name && name[0]) { + struct stat st; + char *slash; + + if (!stat(name, &st) && S_ISDIR(st.st_mode)) { + strcpy(dirname, name); + strcat(dirname, "/"); + basename = conf_get_configname(); + } else if ((slash = strrchr(name, '/'))) { + int size = slash - name + 1; + memcpy(dirname, name, size); + dirname[size] = 0; + if (slash[1]) + basename = slash + 1; + else + basename = conf_get_configname(); + } else + basename = name; + } else + basename = conf_get_configname(); + + sprintf(newname, "%s%s", dirname, basename); + env = getenv("KCONFIG_OVERWRITECONFIG"); + if (!env || !*env) { + sprintf(tmpname, "%s.tmpconfig.%d", dirname, (int)getpid()); + out = fopen(tmpname, "w"); + } else { + *tmpname = 0; + out = fopen(newname, "w"); + } + if (!out) + return 1; + + conf_write_heading(out, &kconfig_printer_cb, NULL); + + if (!conf_get_changed()) + sym_clear_all_valid(); + + menu = rootmenu.list; + while (menu) { + sym = menu->sym; + if (!sym) { + if (!menu_is_visible(menu)) + goto next; + str = menu_get_prompt(menu); + fprintf(out, "\n" + "#\n" + "# %s\n" + "#\n", str); + } else if (!(sym->flags & SYMBOL_CHOICE)) { + sym_calc_value(sym); + if (!(sym->flags & SYMBOL_WRITE)) + goto next; + sym->flags &= ~SYMBOL_WRITE; + + conf_write_symbol(out, sym, &kconfig_printer_cb, NULL); + } + +next: + if (menu->list) { + menu = menu->list; + continue; + } + if (menu->next) + menu = menu->next; + else while ((menu = menu->parent)) { + if (menu->next) { + menu = menu->next; + break; + } + } + } + fclose(out); + + if (*tmpname) { + strcat(dirname, basename); + strcat(dirname, ".old"); + rename(newname, dirname); + if (rename(tmpname, newname)) + return 1; + } + + conf_message(_("configuration written to %s"), newname); + + sym_set_change_count(0); + + return 0; +} + +static int conf_split_config(void) +{ + const char *name; + char path[PATH_MAX+1]; + char *s, *d, c; + struct symbol *sym; + struct stat sb; + int res, i, fd; + + name = conf_get_autoconfig_name(); + conf_read_simple(name, S_DEF_AUTO); + + if (chdir("include/config")) + return 1; + + res = 0; + for_all_symbols(i, sym) { + sym_calc_value(sym); + if ((sym->flags & SYMBOL_AUTO) || !sym->name) + continue; + if (sym->flags & SYMBOL_WRITE) { + if (sym->flags & SYMBOL_DEF_AUTO) { + /* + * symbol has old and new value, + * so compare them... + */ + switch (sym->type) { + case S_BOOLEAN: + case S_TRISTATE: + if (sym_get_tristate_value(sym) == + sym->def[S_DEF_AUTO].tri) + continue; + break; + case S_STRING: + case S_HEX: + case S_INT: + if (!strcmp(sym_get_string_value(sym), + sym->def[S_DEF_AUTO].val)) + continue; + break; + default: + break; + } + } else { + /* + * If there is no old value, only 'no' (unset) + * is allowed as new value. + */ + switch (sym->type) { + case S_BOOLEAN: + case S_TRISTATE: + if (sym_get_tristate_value(sym) == no) + continue; + break; + default: + break; + } + } + } else if (!(sym->flags & SYMBOL_DEF_AUTO)) + /* There is neither an old nor a new value. */ + continue; + /* else + * There is an old value, but no new value ('no' (unset) + * isn't saved in auto.conf, so the old value is always + * different from 'no'). + */ + + /* Replace all '_' and append ".h" */ + s = sym->name; + d = path; + while ((c = *s++)) { + c = tolower(c); + *d++ = (c == '_') ? '/' : c; + } + strcpy(d, ".h"); + + /* Assume directory path already exists. */ + fd = open(path, O_WRONLY | O_CREAT | O_TRUNC, 0644); + if (fd == -1) { + if (errno != ENOENT) { + res = 1; + break; + } + /* + * Create directory components, + * unless they exist already. + */ + d = path; + while ((d = strchr(d, '/'))) { + *d = 0; + if (stat(path, &sb) && mkdir(path, 0755)) { + res = 1; + goto out; + } + *d++ = '/'; + } + /* Try it again. */ + fd = open(path, O_WRONLY | O_CREAT | O_TRUNC, 0644); + if (fd == -1) { + res = 1; + break; + } + } + close(fd); + } +out: + if (chdir("../..")) + return 1; + + return res; +} + +int conf_write_autoconf(void) +{ + struct symbol *sym; + const char *name; + FILE *out, *tristate, *out_h; + int i; + + sym_clear_all_valid(); + + file_write_dep("include/config/auto.conf.cmd"); + + if (conf_split_config()) + return 1; + + out = fopen(".tmpconfig", "w"); + if (!out) + return 1; + + tristate = fopen(".tmpconfig_tristate", "w"); + if (!tristate) { + fclose(out); + return 1; + } + + out_h = fopen(".tmpconfig.h", "w"); + if (!out_h) { + fclose(out); + fclose(tristate); + return 1; + } + + conf_write_heading(out, &kconfig_printer_cb, NULL); + + conf_write_heading(tristate, &tristate_printer_cb, NULL); + + conf_write_heading(out_h, &header_printer_cb, NULL); + + for_all_symbols(i, sym) { + sym_calc_value(sym); + if (!(sym->flags & SYMBOL_WRITE) || !sym->name) + continue; + + /* write symbol to auto.conf, tristate and header files */ + conf_write_symbol(out, sym, &kconfig_printer_cb, (void *)1); + + conf_write_symbol(tristate, sym, &tristate_printer_cb, (void *)1); + + conf_write_symbol(out_h, sym, &header_printer_cb, NULL); + } + fclose(out); + fclose(tristate); + fclose(out_h); + + name = getenv("KCONFIG_AUTOHEADER"); + if (!name) + name = "include/generated/autoconf.h"; + if (rename(".tmpconfig.h", name)) + return 1; + name = getenv("KCONFIG_TRISTATE"); + if (!name) + name = "include/config/tristate.conf"; + if (rename(".tmpconfig_tristate", name)) + return 1; + name = conf_get_autoconfig_name(); + /* + * This must be the last step, kbuild has a dependency on auto.conf + * and this marks the successful completion of the previous steps. + */ + if (rename(".tmpconfig", name)) + return 1; + + return 0; +} + +static int sym_change_count; +static void (*conf_changed_callback)(void); + +void sym_set_change_count(int count) +{ + int _sym_change_count = sym_change_count; + sym_change_count = count; + if (conf_changed_callback && + (bool)_sym_change_count != (bool)count) + conf_changed_callback(); +} + +void sym_add_change_count(int count) +{ + sym_set_change_count(count + sym_change_count); +} + +bool conf_get_changed(void) +{ + return sym_change_count; +} + +void conf_set_changed_callback(void (*fn)(void)) +{ + conf_changed_callback = fn; +} + +static void randomize_choice_values(struct symbol *csym) +{ + struct property *prop; + struct symbol *sym; + struct expr *e; + int cnt, def; + + /* + * If choice is mod then we may have more items selected + * and if no then no-one. + * In both cases stop. + */ + if (csym->curr.tri != yes) + return; + + prop = sym_get_choice_prop(csym); + + /* count entries in choice block */ + cnt = 0; + expr_list_for_each_sym(prop->expr, e, sym) + cnt++; + + /* + * find a random value and set it to yes, + * set the rest to no so we have only one set + */ + def = (rand() % cnt); + + cnt = 0; + expr_list_for_each_sym(prop->expr, e, sym) { + if (def == cnt++) { + sym->def[S_DEF_USER].tri = yes; + csym->def[S_DEF_USER].val = sym; + } + else { + sym->def[S_DEF_USER].tri = no; + } + } + csym->flags |= SYMBOL_DEF_USER; + /* clear VALID to get value calculated */ + csym->flags &= ~(SYMBOL_VALID); +} + +static void set_all_choice_values(struct symbol *csym) +{ + struct property *prop; + struct symbol *sym; + struct expr *e; + + prop = sym_get_choice_prop(csym); + + /* + * Set all non-assinged choice values to no + */ + expr_list_for_each_sym(prop->expr, e, sym) { + if (!sym_has_value(sym)) + sym->def[S_DEF_USER].tri = no; + } + csym->flags |= SYMBOL_DEF_USER; + /* clear VALID to get value calculated */ + csym->flags &= ~(SYMBOL_VALID); +} + +void conf_set_all_new_symbols(enum conf_def_mode mode) +{ + struct symbol *sym, *csym; + int i, cnt; + + for_all_symbols(i, sym) { + if (sym_has_value(sym)) + continue; + switch (sym_get_type(sym)) { + case S_BOOLEAN: + case S_TRISTATE: + switch (mode) { + case def_yes: + sym->def[S_DEF_USER].tri = yes; + break; + case def_mod: + sym->def[S_DEF_USER].tri = mod; + break; + case def_no: + sym->def[S_DEF_USER].tri = no; + break; + case def_random: + cnt = sym_get_type(sym) == S_TRISTATE ? 3 : 2; + sym->def[S_DEF_USER].tri = (tristate)(rand() % cnt); + break; + default: + continue; + } + if (!(sym_is_choice(sym) && mode == def_random)) + sym->flags |= SYMBOL_DEF_USER; + break; + default: + break; + } + + } + + sym_clear_all_valid(); + + /* + * We have different type of choice blocks. + * If curr.tri equals to mod then we can select several + * choice symbols in one block. + * In this case we do nothing. + * If curr.tri equals yes then only one symbol can be + * selected in a choice block and we set it to yes, + * and the rest to no. + */ + for_all_symbols(i, csym) { + if (sym_has_value(csym) || !sym_is_choice(csym)) + continue; + + sym_calc_value(csym); + if (mode == def_random) + randomize_choice_values(csym); + else + set_all_choice_values(csym); + } +} diff --git a/misc/tools/kconfig-frontends/libs/parser/expr.c b/misc/tools/kconfig-frontends/libs/parser/expr.c new file mode 100644 index 0000000000..290ce41f8b --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/expr.c @@ -0,0 +1,1168 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#include +#include +#include + +#include "lkc.h" + +#define DEBUG_EXPR 0 + +struct expr *expr_alloc_symbol(struct symbol *sym) +{ + struct expr *e = calloc(1, sizeof(*e)); + e->type = E_SYMBOL; + e->left.sym = sym; + return e; +} + +struct expr *expr_alloc_one(enum expr_type type, struct expr *ce) +{ + struct expr *e = calloc(1, sizeof(*e)); + e->type = type; + e->left.expr = ce; + return e; +} + +struct expr *expr_alloc_two(enum expr_type type, struct expr *e1, struct expr *e2) +{ + struct expr *e = calloc(1, sizeof(*e)); + e->type = type; + e->left.expr = e1; + e->right.expr = e2; + return e; +} + +struct expr *expr_alloc_comp(enum expr_type type, struct symbol *s1, struct symbol *s2) +{ + struct expr *e = calloc(1, sizeof(*e)); + e->type = type; + e->left.sym = s1; + e->right.sym = s2; + return e; +} + +struct expr *expr_alloc_and(struct expr *e1, struct expr *e2) +{ + if (!e1) + return e2; + return e2 ? expr_alloc_two(E_AND, e1, e2) : e1; +} + +struct expr *expr_alloc_or(struct expr *e1, struct expr *e2) +{ + if (!e1) + return e2; + return e2 ? expr_alloc_two(E_OR, e1, e2) : e1; +} + +struct expr *expr_copy(const struct expr *org) +{ + struct expr *e; + + if (!org) + return NULL; + + e = malloc(sizeof(*org)); + memcpy(e, org, sizeof(*org)); + switch (org->type) { + case E_SYMBOL: + e->left = org->left; + break; + case E_NOT: + e->left.expr = expr_copy(org->left.expr); + break; + case E_EQUAL: + case E_UNEQUAL: + e->left.sym = org->left.sym; + e->right.sym = org->right.sym; + break; + case E_AND: + case E_OR: + case E_LIST: + e->left.expr = expr_copy(org->left.expr); + e->right.expr = expr_copy(org->right.expr); + break; + default: + printf("can't copy type %d\n", e->type); + free(e); + e = NULL; + break; + } + + return e; +} + +void expr_free(struct expr *e) +{ + if (!e) + return; + + switch (e->type) { + case E_SYMBOL: + break; + case E_NOT: + expr_free(e->left.expr); + return; + case E_EQUAL: + case E_UNEQUAL: + break; + case E_OR: + case E_AND: + expr_free(e->left.expr); + expr_free(e->right.expr); + break; + default: + printf("how to free type %d?\n", e->type); + break; + } + free(e); +} + +static int trans_count; + +#define e1 (*ep1) +#define e2 (*ep2) + +static void __expr_eliminate_eq(enum expr_type type, struct expr **ep1, struct expr **ep2) +{ + if (e1->type == type) { + __expr_eliminate_eq(type, &e1->left.expr, &e2); + __expr_eliminate_eq(type, &e1->right.expr, &e2); + return; + } + if (e2->type == type) { + __expr_eliminate_eq(type, &e1, &e2->left.expr); + __expr_eliminate_eq(type, &e1, &e2->right.expr); + return; + } + if (e1->type == E_SYMBOL && e2->type == E_SYMBOL && + e1->left.sym == e2->left.sym && + (e1->left.sym == &symbol_yes || e1->left.sym == &symbol_no)) + return; + if (!expr_eq(e1, e2)) + return; + trans_count++; + expr_free(e1); expr_free(e2); + switch (type) { + case E_OR: + e1 = expr_alloc_symbol(&symbol_no); + e2 = expr_alloc_symbol(&symbol_no); + break; + case E_AND: + e1 = expr_alloc_symbol(&symbol_yes); + e2 = expr_alloc_symbol(&symbol_yes); + break; + default: + ; + } +} + +void expr_eliminate_eq(struct expr **ep1, struct expr **ep2) +{ + if (!e1 || !e2) + return; + switch (e1->type) { + case E_OR: + case E_AND: + __expr_eliminate_eq(e1->type, ep1, ep2); + default: + ; + } + if (e1->type != e2->type) switch (e2->type) { + case E_OR: + case E_AND: + __expr_eliminate_eq(e2->type, ep1, ep2); + default: + ; + } + e1 = expr_eliminate_yn(e1); + e2 = expr_eliminate_yn(e2); +} + +#undef e1 +#undef e2 + +int expr_eq(struct expr *e1, struct expr *e2) +{ + int res, old_count; + + if (e1->type != e2->type) + return 0; + switch (e1->type) { + case E_EQUAL: + case E_UNEQUAL: + return e1->left.sym == e2->left.sym && e1->right.sym == e2->right.sym; + case E_SYMBOL: + return e1->left.sym == e2->left.sym; + case E_NOT: + return expr_eq(e1->left.expr, e2->left.expr); + case E_AND: + case E_OR: + e1 = expr_copy(e1); + e2 = expr_copy(e2); + old_count = trans_count; + expr_eliminate_eq(&e1, &e2); + res = (e1->type == E_SYMBOL && e2->type == E_SYMBOL && + e1->left.sym == e2->left.sym); + expr_free(e1); + expr_free(e2); + trans_count = old_count; + return res; + case E_LIST: + case E_RANGE: + case E_NONE: + /* panic */; + } + + if (DEBUG_EXPR) { + expr_fprint(e1, stdout); + printf(" = "); + expr_fprint(e2, stdout); + printf(" ?\n"); + } + + return 0; +} + +struct expr *expr_eliminate_yn(struct expr *e) +{ + struct expr *tmp; + + if (e) switch (e->type) { + case E_AND: + e->left.expr = expr_eliminate_yn(e->left.expr); + e->right.expr = expr_eliminate_yn(e->right.expr); + if (e->left.expr->type == E_SYMBOL) { + if (e->left.expr->left.sym == &symbol_no) { + expr_free(e->left.expr); + expr_free(e->right.expr); + e->type = E_SYMBOL; + e->left.sym = &symbol_no; + e->right.expr = NULL; + return e; + } else if (e->left.expr->left.sym == &symbol_yes) { + free(e->left.expr); + tmp = e->right.expr; + *e = *(e->right.expr); + free(tmp); + return e; + } + } + if (e->right.expr->type == E_SYMBOL) { + if (e->right.expr->left.sym == &symbol_no) { + expr_free(e->left.expr); + expr_free(e->right.expr); + e->type = E_SYMBOL; + e->left.sym = &symbol_no; + e->right.expr = NULL; + return e; + } else if (e->right.expr->left.sym == &symbol_yes) { + free(e->right.expr); + tmp = e->left.expr; + *e = *(e->left.expr); + free(tmp); + return e; + } + } + break; + case E_OR: + e->left.expr = expr_eliminate_yn(e->left.expr); + e->right.expr = expr_eliminate_yn(e->right.expr); + if (e->left.expr->type == E_SYMBOL) { + if (e->left.expr->left.sym == &symbol_no) { + free(e->left.expr); + tmp = e->right.expr; + *e = *(e->right.expr); + free(tmp); + return e; + } else if (e->left.expr->left.sym == &symbol_yes) { + expr_free(e->left.expr); + expr_free(e->right.expr); + e->type = E_SYMBOL; + e->left.sym = &symbol_yes; + e->right.expr = NULL; + return e; + } + } + if (e->right.expr->type == E_SYMBOL) { + if (e->right.expr->left.sym == &symbol_no) { + free(e->right.expr); + tmp = e->left.expr; + *e = *(e->left.expr); + free(tmp); + return e; + } else if (e->right.expr->left.sym == &symbol_yes) { + expr_free(e->left.expr); + expr_free(e->right.expr); + e->type = E_SYMBOL; + e->left.sym = &symbol_yes; + e->right.expr = NULL; + return e; + } + } + break; + default: + ; + } + return e; +} + +/* + * bool FOO!=n => FOO + */ +struct expr *expr_trans_bool(struct expr *e) +{ + if (!e) + return NULL; + switch (e->type) { + case E_AND: + case E_OR: + case E_NOT: + e->left.expr = expr_trans_bool(e->left.expr); + e->right.expr = expr_trans_bool(e->right.expr); + break; + case E_UNEQUAL: + // FOO!=n -> FOO + if (e->left.sym->type == S_TRISTATE) { + if (e->right.sym == &symbol_no) { + e->type = E_SYMBOL; + e->right.sym = NULL; + } + } + break; + default: + ; + } + return e; +} + +/* + * e1 || e2 -> ? + */ +static struct expr *expr_join_or(struct expr *e1, struct expr *e2) +{ + struct expr *tmp; + struct symbol *sym1, *sym2; + + if (expr_eq(e1, e2)) + return expr_copy(e1); + if (e1->type != E_EQUAL && e1->type != E_UNEQUAL && e1->type != E_SYMBOL && e1->type != E_NOT) + return NULL; + if (e2->type != E_EQUAL && e2->type != E_UNEQUAL && e2->type != E_SYMBOL && e2->type != E_NOT) + return NULL; + if (e1->type == E_NOT) { + tmp = e1->left.expr; + if (tmp->type != E_EQUAL && tmp->type != E_UNEQUAL && tmp->type != E_SYMBOL) + return NULL; + sym1 = tmp->left.sym; + } else + sym1 = e1->left.sym; + if (e2->type == E_NOT) { + if (e2->left.expr->type != E_SYMBOL) + return NULL; + sym2 = e2->left.expr->left.sym; + } else + sym2 = e2->left.sym; + if (sym1 != sym2) + return NULL; + if (sym1->type != S_BOOLEAN && sym1->type != S_TRISTATE) + return NULL; + if (sym1->type == S_TRISTATE) { + if (e1->type == E_EQUAL && e2->type == E_EQUAL && + ((e1->right.sym == &symbol_yes && e2->right.sym == &symbol_mod) || + (e1->right.sym == &symbol_mod && e2->right.sym == &symbol_yes))) { + // (a='y') || (a='m') -> (a!='n') + return expr_alloc_comp(E_UNEQUAL, sym1, &symbol_no); + } + if (e1->type == E_EQUAL && e2->type == E_EQUAL && + ((e1->right.sym == &symbol_yes && e2->right.sym == &symbol_no) || + (e1->right.sym == &symbol_no && e2->right.sym == &symbol_yes))) { + // (a='y') || (a='n') -> (a!='m') + return expr_alloc_comp(E_UNEQUAL, sym1, &symbol_mod); + } + if (e1->type == E_EQUAL && e2->type == E_EQUAL && + ((e1->right.sym == &symbol_mod && e2->right.sym == &symbol_no) || + (e1->right.sym == &symbol_no && e2->right.sym == &symbol_mod))) { + // (a='m') || (a='n') -> (a!='y') + return expr_alloc_comp(E_UNEQUAL, sym1, &symbol_yes); + } + } + if (sym1->type == S_BOOLEAN && sym1 == sym2) { + if ((e1->type == E_NOT && e1->left.expr->type == E_SYMBOL && e2->type == E_SYMBOL) || + (e2->type == E_NOT && e2->left.expr->type == E_SYMBOL && e1->type == E_SYMBOL)) + return expr_alloc_symbol(&symbol_yes); + } + + if (DEBUG_EXPR) { + printf("optimize ("); + expr_fprint(e1, stdout); + printf(") || ("); + expr_fprint(e2, stdout); + printf(")?\n"); + } + return NULL; +} + +static struct expr *expr_join_and(struct expr *e1, struct expr *e2) +{ + struct expr *tmp; + struct symbol *sym1, *sym2; + + if (expr_eq(e1, e2)) + return expr_copy(e1); + if (e1->type != E_EQUAL && e1->type != E_UNEQUAL && e1->type != E_SYMBOL && e1->type != E_NOT) + return NULL; + if (e2->type != E_EQUAL && e2->type != E_UNEQUAL && e2->type != E_SYMBOL && e2->type != E_NOT) + return NULL; + if (e1->type == E_NOT) { + tmp = e1->left.expr; + if (tmp->type != E_EQUAL && tmp->type != E_UNEQUAL && tmp->type != E_SYMBOL) + return NULL; + sym1 = tmp->left.sym; + } else + sym1 = e1->left.sym; + if (e2->type == E_NOT) { + if (e2->left.expr->type != E_SYMBOL) + return NULL; + sym2 = e2->left.expr->left.sym; + } else + sym2 = e2->left.sym; + if (sym1 != sym2) + return NULL; + if (sym1->type != S_BOOLEAN && sym1->type != S_TRISTATE) + return NULL; + + if ((e1->type == E_SYMBOL && e2->type == E_EQUAL && e2->right.sym == &symbol_yes) || + (e2->type == E_SYMBOL && e1->type == E_EQUAL && e1->right.sym == &symbol_yes)) + // (a) && (a='y') -> (a='y') + return expr_alloc_comp(E_EQUAL, sym1, &symbol_yes); + + if ((e1->type == E_SYMBOL && e2->type == E_UNEQUAL && e2->right.sym == &symbol_no) || + (e2->type == E_SYMBOL && e1->type == E_UNEQUAL && e1->right.sym == &symbol_no)) + // (a) && (a!='n') -> (a) + return expr_alloc_symbol(sym1); + + if ((e1->type == E_SYMBOL && e2->type == E_UNEQUAL && e2->right.sym == &symbol_mod) || + (e2->type == E_SYMBOL && e1->type == E_UNEQUAL && e1->right.sym == &symbol_mod)) + // (a) && (a!='m') -> (a='y') + return expr_alloc_comp(E_EQUAL, sym1, &symbol_yes); + + if (sym1->type == S_TRISTATE) { + if (e1->type == E_EQUAL && e2->type == E_UNEQUAL) { + // (a='b') && (a!='c') -> 'b'='c' ? 'n' : a='b' + sym2 = e1->right.sym; + if ((e2->right.sym->flags & SYMBOL_CONST) && (sym2->flags & SYMBOL_CONST)) + return sym2 != e2->right.sym ? expr_alloc_comp(E_EQUAL, sym1, sym2) + : expr_alloc_symbol(&symbol_no); + } + if (e1->type == E_UNEQUAL && e2->type == E_EQUAL) { + // (a='b') && (a!='c') -> 'b'='c' ? 'n' : a='b' + sym2 = e2->right.sym; + if ((e1->right.sym->flags & SYMBOL_CONST) && (sym2->flags & SYMBOL_CONST)) + return sym2 != e1->right.sym ? expr_alloc_comp(E_EQUAL, sym1, sym2) + : expr_alloc_symbol(&symbol_no); + } + if (e1->type == E_UNEQUAL && e2->type == E_UNEQUAL && + ((e1->right.sym == &symbol_yes && e2->right.sym == &symbol_no) || + (e1->right.sym == &symbol_no && e2->right.sym == &symbol_yes))) + // (a!='y') && (a!='n') -> (a='m') + return expr_alloc_comp(E_EQUAL, sym1, &symbol_mod); + + if (e1->type == E_UNEQUAL && e2->type == E_UNEQUAL && + ((e1->right.sym == &symbol_yes && e2->right.sym == &symbol_mod) || + (e1->right.sym == &symbol_mod && e2->right.sym == &symbol_yes))) + // (a!='y') && (a!='m') -> (a='n') + return expr_alloc_comp(E_EQUAL, sym1, &symbol_no); + + if (e1->type == E_UNEQUAL && e2->type == E_UNEQUAL && + ((e1->right.sym == &symbol_mod && e2->right.sym == &symbol_no) || + (e1->right.sym == &symbol_no && e2->right.sym == &symbol_mod))) + // (a!='m') && (a!='n') -> (a='m') + return expr_alloc_comp(E_EQUAL, sym1, &symbol_yes); + + if ((e1->type == E_SYMBOL && e2->type == E_EQUAL && e2->right.sym == &symbol_mod) || + (e2->type == E_SYMBOL && e1->type == E_EQUAL && e1->right.sym == &symbol_mod) || + (e1->type == E_SYMBOL && e2->type == E_UNEQUAL && e2->right.sym == &symbol_yes) || + (e2->type == E_SYMBOL && e1->type == E_UNEQUAL && e1->right.sym == &symbol_yes)) + return NULL; + } + + if (DEBUG_EXPR) { + printf("optimize ("); + expr_fprint(e1, stdout); + printf(") && ("); + expr_fprint(e2, stdout); + printf(")?\n"); + } + return NULL; +} + +static void expr_eliminate_dups1(enum expr_type type, struct expr **ep1, struct expr **ep2) +{ +#define e1 (*ep1) +#define e2 (*ep2) + struct expr *tmp; + + if (e1->type == type) { + expr_eliminate_dups1(type, &e1->left.expr, &e2); + expr_eliminate_dups1(type, &e1->right.expr, &e2); + return; + } + if (e2->type == type) { + expr_eliminate_dups1(type, &e1, &e2->left.expr); + expr_eliminate_dups1(type, &e1, &e2->right.expr); + return; + } + if (e1 == e2) + return; + + switch (e1->type) { + case E_OR: case E_AND: + expr_eliminate_dups1(e1->type, &e1, &e1); + default: + ; + } + + switch (type) { + case E_OR: + tmp = expr_join_or(e1, e2); + if (tmp) { + expr_free(e1); expr_free(e2); + e1 = expr_alloc_symbol(&symbol_no); + e2 = tmp; + trans_count++; + } + break; + case E_AND: + tmp = expr_join_and(e1, e2); + if (tmp) { + expr_free(e1); expr_free(e2); + e1 = expr_alloc_symbol(&symbol_yes); + e2 = tmp; + trans_count++; + } + break; + default: + ; + } +#undef e1 +#undef e2 +} + +static void expr_eliminate_dups2(enum expr_type type, struct expr **ep1, struct expr **ep2) +{ +#define e1 (*ep1) +#define e2 (*ep2) + struct expr *tmp, *tmp1, *tmp2; + + if (e1->type == type) { + expr_eliminate_dups2(type, &e1->left.expr, &e2); + expr_eliminate_dups2(type, &e1->right.expr, &e2); + return; + } + if (e2->type == type) { + expr_eliminate_dups2(type, &e1, &e2->left.expr); + expr_eliminate_dups2(type, &e1, &e2->right.expr); + } + if (e1 == e2) + return; + + switch (e1->type) { + case E_OR: + expr_eliminate_dups2(e1->type, &e1, &e1); + // (FOO || BAR) && (!FOO && !BAR) -> n + tmp1 = expr_transform(expr_alloc_one(E_NOT, expr_copy(e1))); + tmp2 = expr_copy(e2); + tmp = expr_extract_eq_and(&tmp1, &tmp2); + if (expr_is_yes(tmp1)) { + expr_free(e1); + e1 = expr_alloc_symbol(&symbol_no); + trans_count++; + } + expr_free(tmp2); + expr_free(tmp1); + expr_free(tmp); + break; + case E_AND: + expr_eliminate_dups2(e1->type, &e1, &e1); + // (FOO && BAR) || (!FOO || !BAR) -> y + tmp1 = expr_transform(expr_alloc_one(E_NOT, expr_copy(e1))); + tmp2 = expr_copy(e2); + tmp = expr_extract_eq_or(&tmp1, &tmp2); + if (expr_is_no(tmp1)) { + expr_free(e1); + e1 = expr_alloc_symbol(&symbol_yes); + trans_count++; + } + expr_free(tmp2); + expr_free(tmp1); + expr_free(tmp); + break; + default: + ; + } +#undef e1 +#undef e2 +} + +struct expr *expr_eliminate_dups(struct expr *e) +{ + int oldcount; + if (!e) + return e; + + oldcount = trans_count; + while (1) { + trans_count = 0; + switch (e->type) { + case E_OR: case E_AND: + expr_eliminate_dups1(e->type, &e, &e); + expr_eliminate_dups2(e->type, &e, &e); + default: + ; + } + if (!trans_count) + break; + e = expr_eliminate_yn(e); + } + trans_count = oldcount; + return e; +} + +struct expr *expr_transform(struct expr *e) +{ + struct expr *tmp; + + if (!e) + return NULL; + switch (e->type) { + case E_EQUAL: + case E_UNEQUAL: + case E_SYMBOL: + case E_LIST: + break; + default: + e->left.expr = expr_transform(e->left.expr); + e->right.expr = expr_transform(e->right.expr); + } + + switch (e->type) { + case E_EQUAL: + if (e->left.sym->type != S_BOOLEAN) + break; + if (e->right.sym == &symbol_no) { + e->type = E_NOT; + e->left.expr = expr_alloc_symbol(e->left.sym); + e->right.sym = NULL; + break; + } + if (e->right.sym == &symbol_mod) { + printf("boolean symbol %s tested for 'm'? test forced to 'n'\n", e->left.sym->name); + e->type = E_SYMBOL; + e->left.sym = &symbol_no; + e->right.sym = NULL; + break; + } + if (e->right.sym == &symbol_yes) { + e->type = E_SYMBOL; + e->right.sym = NULL; + break; + } + break; + case E_UNEQUAL: + if (e->left.sym->type != S_BOOLEAN) + break; + if (e->right.sym == &symbol_no) { + e->type = E_SYMBOL; + e->right.sym = NULL; + break; + } + if (e->right.sym == &symbol_mod) { + printf("boolean symbol %s tested for 'm'? test forced to 'y'\n", e->left.sym->name); + e->type = E_SYMBOL; + e->left.sym = &symbol_yes; + e->right.sym = NULL; + break; + } + if (e->right.sym == &symbol_yes) { + e->type = E_NOT; + e->left.expr = expr_alloc_symbol(e->left.sym); + e->right.sym = NULL; + break; + } + break; + case E_NOT: + switch (e->left.expr->type) { + case E_NOT: + // !!a -> a + tmp = e->left.expr->left.expr; + free(e->left.expr); + free(e); + e = tmp; + e = expr_transform(e); + break; + case E_EQUAL: + case E_UNEQUAL: + // !a='x' -> a!='x' + tmp = e->left.expr; + free(e); + e = tmp; + e->type = e->type == E_EQUAL ? E_UNEQUAL : E_EQUAL; + break; + case E_OR: + // !(a || b) -> !a && !b + tmp = e->left.expr; + e->type = E_AND; + e->right.expr = expr_alloc_one(E_NOT, tmp->right.expr); + tmp->type = E_NOT; + tmp->right.expr = NULL; + e = expr_transform(e); + break; + case E_AND: + // !(a && b) -> !a || !b + tmp = e->left.expr; + e->type = E_OR; + e->right.expr = expr_alloc_one(E_NOT, tmp->right.expr); + tmp->type = E_NOT; + tmp->right.expr = NULL; + e = expr_transform(e); + break; + case E_SYMBOL: + if (e->left.expr->left.sym == &symbol_yes) { + // !'y' -> 'n' + tmp = e->left.expr; + free(e); + e = tmp; + e->type = E_SYMBOL; + e->left.sym = &symbol_no; + break; + } + if (e->left.expr->left.sym == &symbol_mod) { + // !'m' -> 'm' + tmp = e->left.expr; + free(e); + e = tmp; + e->type = E_SYMBOL; + e->left.sym = &symbol_mod; + break; + } + if (e->left.expr->left.sym == &symbol_no) { + // !'n' -> 'y' + tmp = e->left.expr; + free(e); + e = tmp; + e->type = E_SYMBOL; + e->left.sym = &symbol_yes; + break; + } + break; + default: + ; + } + break; + default: + ; + } + return e; +} + +int expr_contains_symbol(struct expr *dep, struct symbol *sym) +{ + if (!dep) + return 0; + + switch (dep->type) { + case E_AND: + case E_OR: + return expr_contains_symbol(dep->left.expr, sym) || + expr_contains_symbol(dep->right.expr, sym); + case E_SYMBOL: + return dep->left.sym == sym; + case E_EQUAL: + case E_UNEQUAL: + return dep->left.sym == sym || + dep->right.sym == sym; + case E_NOT: + return expr_contains_symbol(dep->left.expr, sym); + default: + ; + } + return 0; +} + +bool expr_depends_symbol(struct expr *dep, struct symbol *sym) +{ + if (!dep) + return false; + + switch (dep->type) { + case E_AND: + return expr_depends_symbol(dep->left.expr, sym) || + expr_depends_symbol(dep->right.expr, sym); + case E_SYMBOL: + return dep->left.sym == sym; + case E_EQUAL: + if (dep->left.sym == sym) { + if (dep->right.sym == &symbol_yes || dep->right.sym == &symbol_mod) + return true; + } + break; + case E_UNEQUAL: + if (dep->left.sym == sym) { + if (dep->right.sym == &symbol_no) + return true; + } + break; + default: + ; + } + return false; +} + +struct expr *expr_extract_eq_and(struct expr **ep1, struct expr **ep2) +{ + struct expr *tmp = NULL; + expr_extract_eq(E_AND, &tmp, ep1, ep2); + if (tmp) { + *ep1 = expr_eliminate_yn(*ep1); + *ep2 = expr_eliminate_yn(*ep2); + } + return tmp; +} + +struct expr *expr_extract_eq_or(struct expr **ep1, struct expr **ep2) +{ + struct expr *tmp = NULL; + expr_extract_eq(E_OR, &tmp, ep1, ep2); + if (tmp) { + *ep1 = expr_eliminate_yn(*ep1); + *ep2 = expr_eliminate_yn(*ep2); + } + return tmp; +} + +void expr_extract_eq(enum expr_type type, struct expr **ep, struct expr **ep1, struct expr **ep2) +{ +#define e1 (*ep1) +#define e2 (*ep2) + if (e1->type == type) { + expr_extract_eq(type, ep, &e1->left.expr, &e2); + expr_extract_eq(type, ep, &e1->right.expr, &e2); + return; + } + if (e2->type == type) { + expr_extract_eq(type, ep, ep1, &e2->left.expr); + expr_extract_eq(type, ep, ep1, &e2->right.expr); + return; + } + if (expr_eq(e1, e2)) { + *ep = *ep ? expr_alloc_two(type, *ep, e1) : e1; + expr_free(e2); + if (type == E_AND) { + e1 = expr_alloc_symbol(&symbol_yes); + e2 = expr_alloc_symbol(&symbol_yes); + } else if (type == E_OR) { + e1 = expr_alloc_symbol(&symbol_no); + e2 = expr_alloc_symbol(&symbol_no); + } + } +#undef e1 +#undef e2 +} + +struct expr *expr_trans_compare(struct expr *e, enum expr_type type, struct symbol *sym) +{ + struct expr *e1, *e2; + + if (!e) { + e = expr_alloc_symbol(sym); + if (type == E_UNEQUAL) + e = expr_alloc_one(E_NOT, e); + return e; + } + switch (e->type) { + case E_AND: + e1 = expr_trans_compare(e->left.expr, E_EQUAL, sym); + e2 = expr_trans_compare(e->right.expr, E_EQUAL, sym); + if (sym == &symbol_yes) + e = expr_alloc_two(E_AND, e1, e2); + if (sym == &symbol_no) + e = expr_alloc_two(E_OR, e1, e2); + if (type == E_UNEQUAL) + e = expr_alloc_one(E_NOT, e); + return e; + case E_OR: + e1 = expr_trans_compare(e->left.expr, E_EQUAL, sym); + e2 = expr_trans_compare(e->right.expr, E_EQUAL, sym); + if (sym == &symbol_yes) + e = expr_alloc_two(E_OR, e1, e2); + if (sym == &symbol_no) + e = expr_alloc_two(E_AND, e1, e2); + if (type == E_UNEQUAL) + e = expr_alloc_one(E_NOT, e); + return e; + case E_NOT: + return expr_trans_compare(e->left.expr, type == E_EQUAL ? E_UNEQUAL : E_EQUAL, sym); + case E_UNEQUAL: + case E_EQUAL: + if (type == E_EQUAL) { + if (sym == &symbol_yes) + return expr_copy(e); + if (sym == &symbol_mod) + return expr_alloc_symbol(&symbol_no); + if (sym == &symbol_no) + return expr_alloc_one(E_NOT, expr_copy(e)); + } else { + if (sym == &symbol_yes) + return expr_alloc_one(E_NOT, expr_copy(e)); + if (sym == &symbol_mod) + return expr_alloc_symbol(&symbol_yes); + if (sym == &symbol_no) + return expr_copy(e); + } + break; + case E_SYMBOL: + return expr_alloc_comp(type, e->left.sym, sym); + case E_LIST: + case E_RANGE: + case E_NONE: + /* panic */; + } + return NULL; +} + +tristate expr_calc_value(struct expr *e) +{ + tristate val1, val2; + const char *str1, *str2; + + if (!e) + return yes; + + switch (e->type) { + case E_SYMBOL: + sym_calc_value(e->left.sym); + return e->left.sym->curr.tri; + case E_AND: + val1 = expr_calc_value(e->left.expr); + val2 = expr_calc_value(e->right.expr); + return EXPR_AND(val1, val2); + case E_OR: + val1 = expr_calc_value(e->left.expr); + val2 = expr_calc_value(e->right.expr); + return EXPR_OR(val1, val2); + case E_NOT: + val1 = expr_calc_value(e->left.expr); + return EXPR_NOT(val1); + case E_EQUAL: + sym_calc_value(e->left.sym); + sym_calc_value(e->right.sym); + str1 = sym_get_string_value(e->left.sym); + str2 = sym_get_string_value(e->right.sym); + return !strcmp(str1, str2) ? yes : no; + case E_UNEQUAL: + sym_calc_value(e->left.sym); + sym_calc_value(e->right.sym); + str1 = sym_get_string_value(e->left.sym); + str2 = sym_get_string_value(e->right.sym); + return !strcmp(str1, str2) ? no : yes; + default: + printf("expr_calc_value: %d?\n", e->type); + return no; + } +} + +int expr_compare_type(enum expr_type t1, enum expr_type t2) +{ +#if 0 + return 1; +#else + if (t1 == t2) + return 0; + switch (t1) { + case E_EQUAL: + case E_UNEQUAL: + if (t2 == E_NOT) + return 1; + case E_NOT: + if (t2 == E_AND) + return 1; + case E_AND: + if (t2 == E_OR) + return 1; + case E_OR: + if (t2 == E_LIST) + return 1; + case E_LIST: + if (t2 == 0) + return 1; + default: + return -1; + } + printf("[%dgt%d?]", t1, t2); + return 0; +#endif +} + +static inline struct expr * +expr_get_leftmost_symbol(const struct expr *e) +{ + + if (e == NULL) + return NULL; + + while (e->type != E_SYMBOL) + e = e->left.expr; + + return expr_copy(e); +} + +/* + * Given expression `e1' and `e2', returns the leaf of the longest + * sub-expression of `e1' not containing 'e2. + */ +struct expr *expr_simplify_unmet_dep(struct expr *e1, struct expr *e2) +{ + struct expr *ret; + + switch (e1->type) { + case E_OR: + return expr_alloc_and( + expr_simplify_unmet_dep(e1->left.expr, e2), + expr_simplify_unmet_dep(e1->right.expr, e2)); + case E_AND: { + struct expr *e; + e = expr_alloc_and(expr_copy(e1), expr_copy(e2)); + e = expr_eliminate_dups(e); + ret = (!expr_eq(e, e1)) ? e1 : NULL; + expr_free(e); + break; + } + default: + ret = e1; + break; + } + + return expr_get_leftmost_symbol(ret); +} + +void expr_print(struct expr *e, void (*fn)(void *, struct symbol *, const char *), void *data, int prevtoken) +{ + if (!e) { + fn(data, NULL, "y"); + return; + } + + if (expr_compare_type(prevtoken, e->type) > 0) + fn(data, NULL, "("); + switch (e->type) { + case E_SYMBOL: + if (e->left.sym->name) + fn(data, e->left.sym, e->left.sym->name); + else + fn(data, NULL, ""); + break; + case E_NOT: + fn(data, NULL, "!"); + expr_print(e->left.expr, fn, data, E_NOT); + break; + case E_EQUAL: + if (e->left.sym->name) + fn(data, e->left.sym, e->left.sym->name); + else + fn(data, NULL, ""); + fn(data, NULL, "="); + fn(data, e->right.sym, e->right.sym->name); + break; + case E_UNEQUAL: + if (e->left.sym->name) + fn(data, e->left.sym, e->left.sym->name); + else + fn(data, NULL, ""); + fn(data, NULL, "!="); + fn(data, e->right.sym, e->right.sym->name); + break; + case E_OR: + expr_print(e->left.expr, fn, data, E_OR); + fn(data, NULL, " || "); + expr_print(e->right.expr, fn, data, E_OR); + break; + case E_AND: + expr_print(e->left.expr, fn, data, E_AND); + fn(data, NULL, " && "); + expr_print(e->right.expr, fn, data, E_AND); + break; + case E_LIST: + fn(data, e->right.sym, e->right.sym->name); + if (e->left.expr) { + fn(data, NULL, " ^ "); + expr_print(e->left.expr, fn, data, E_LIST); + } + break; + case E_RANGE: + fn(data, NULL, "["); + fn(data, e->left.sym, e->left.sym->name); + fn(data, NULL, " "); + fn(data, e->right.sym, e->right.sym->name); + fn(data, NULL, "]"); + break; + default: + { + char buf[32]; + sprintf(buf, "", e->type); + fn(data, NULL, buf); + break; + } + } + if (expr_compare_type(prevtoken, e->type) > 0) + fn(data, NULL, ")"); +} + +static void expr_print_file_helper(void *data, struct symbol *sym, const char *str) +{ + xfwrite(str, strlen(str), 1, data); +} + +void expr_fprint(struct expr *e, FILE *out) +{ + expr_print(e, expr_print_file_helper, out, E_NONE); +} + +static void expr_print_gstr_helper(void *data, struct symbol *sym, const char *str) +{ + struct gstr *gs = (struct gstr*)data; + const char *sym_str = NULL; + + if (sym) + sym_str = sym_get_string_value(sym); + + if (gs->max_width) { + unsigned extra_length = strlen(str); + const char *last_cr = strrchr(gs->s, '\n'); + unsigned last_line_length; + + if (sym_str) + extra_length += 4 + strlen(sym_str); + + if (!last_cr) + last_cr = gs->s; + + last_line_length = strlen(gs->s) - (last_cr - gs->s); + + if ((last_line_length + extra_length) > gs->max_width) + str_append(gs, "\\\n"); + } + + str_append(gs, str); + if (sym && sym->type != S_UNKNOWN) + str_printf(gs, " [=%s]", sym_str); +} + +void expr_gstr_print(struct expr *e, struct gstr *gs) +{ + expr_print(e, expr_print_gstr_helper, gs, E_NONE); +} diff --git a/misc/tools/kconfig-frontends/libs/parser/expr.h b/misc/tools/kconfig-frontends/libs/parser/expr.h new file mode 100644 index 0000000000..d4ecce8bc3 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/expr.h @@ -0,0 +1,225 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#ifndef EXPR_H +#define EXPR_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include +#ifndef __cplusplus +#include +#endif + +struct file { + struct file *next; + struct file *parent; + const char *name; + int lineno; +}; + +typedef enum tristate { + no, mod, yes +} tristate; + +enum expr_type { + E_NONE, E_OR, E_AND, E_NOT, E_EQUAL, E_UNEQUAL, E_LIST, E_SYMBOL, E_RANGE +}; + +union expr_data { + struct expr *expr; + struct symbol *sym; +}; + +struct expr { + enum expr_type type; + union expr_data left, right; +}; + +#define EXPR_OR(dep1, dep2) (((dep1)>(dep2))?(dep1):(dep2)) +#define EXPR_AND(dep1, dep2) (((dep1)<(dep2))?(dep1):(dep2)) +#define EXPR_NOT(dep) (2-(dep)) + +#define expr_list_for_each_sym(l, e, s) \ + for (e = (l); e && (s = e->right.sym); e = e->left.expr) + +struct expr_value { + struct expr *expr; + tristate tri; +}; + +struct symbol_value { + void *val; + tristate tri; +}; + +enum symbol_type { + S_UNKNOWN, S_BOOLEAN, S_TRISTATE, S_INT, S_HEX, S_STRING, S_OTHER +}; + +/* enum values are used as index to symbol.def[] */ +enum { + S_DEF_USER, /* main user value */ + S_DEF_AUTO, /* values read from auto.conf */ + S_DEF_DEF3, /* Reserved for UI usage */ + S_DEF_DEF4, /* Reserved for UI usage */ + S_DEF_COUNT +}; + +struct symbol { + struct symbol *next; + char *name; + enum symbol_type type; + struct symbol_value curr; + struct symbol_value def[S_DEF_COUNT]; + tristate visible; + int flags; + struct property *prop; + struct expr_value dir_dep; + struct expr_value rev_dep; +}; + +#define for_all_symbols(i, sym) for (i = 0; i < SYMBOL_HASHSIZE; i++) for (sym = symbol_hash[i]; sym; sym = sym->next) if (sym->type != S_OTHER) + +#define SYMBOL_CONST 0x0001 /* symbol is const */ +#define SYMBOL_CHECK 0x0008 /* used during dependency checking */ +#define SYMBOL_CHOICE 0x0010 /* start of a choice block (null name) */ +#define SYMBOL_CHOICEVAL 0x0020 /* used as a value in a choice block */ +#define SYMBOL_VALID 0x0080 /* set when symbol.curr is calculated */ +#define SYMBOL_OPTIONAL 0x0100 /* choice is optional - values can be 'n' */ +#define SYMBOL_WRITE 0x0200 /* ? */ +#define SYMBOL_CHANGED 0x0400 /* ? */ +#define SYMBOL_AUTO 0x1000 /* value from environment variable */ +#define SYMBOL_CHECKED 0x2000 /* used during dependency checking */ +#define SYMBOL_WARNED 0x8000 /* warning has been issued */ + +/* Set when symbol.def[] is used */ +#define SYMBOL_DEF 0x10000 /* First bit of SYMBOL_DEF */ +#define SYMBOL_DEF_USER 0x10000 /* symbol.def[S_DEF_USER] is valid */ +#define SYMBOL_DEF_AUTO 0x20000 /* symbol.def[S_DEF_AUTO] is valid */ +#define SYMBOL_DEF3 0x40000 /* symbol.def[S_DEF_3] is valid */ +#define SYMBOL_DEF4 0x80000 /* symbol.def[S_DEF_4] is valid */ + +#define SYMBOL_MAXLENGTH 256 +#define SYMBOL_HASHSIZE 9973 + +/* A property represent the config options that can be associated + * with a config "symbol". + * Sample: + * config FOO + * default y + * prompt "foo prompt" + * select BAR + * config BAZ + * int "BAZ Value" + * range 1..255 + */ +enum prop_type { + P_UNKNOWN, + P_PROMPT, /* prompt "foo prompt" or "BAZ Value" */ + P_COMMENT, /* text associated with a comment */ + P_MENU, /* prompt associated with a menuconfig option */ + P_DEFAULT, /* default y */ + P_CHOICE, /* choice value */ + P_SELECT, /* select BAR */ + P_RANGE, /* range 7..100 (for a symbol) */ + P_ENV, /* value from environment variable */ + P_SYMBOL, /* where a symbol is defined */ +}; + +struct property { + struct property *next; /* next property - null if last */ + struct symbol *sym; /* the symbol for which the property is associated */ + enum prop_type type; /* type of property */ + const char *text; /* the prompt value - P_PROMPT, P_MENU, P_COMMENT */ + struct expr_value visible; + struct expr *expr; /* the optional conditional part of the property */ + struct menu *menu; /* the menu the property are associated with + * valid for: P_SELECT, P_RANGE, P_CHOICE, + * P_PROMPT, P_DEFAULT, P_MENU, P_COMMENT */ + struct file *file; /* what file was this property defined */ + int lineno; /* what lineno was this property defined */ +}; + +#define for_all_properties(sym, st, tok) \ + for (st = sym->prop; st; st = st->next) \ + if (st->type == (tok)) +#define for_all_defaults(sym, st) for_all_properties(sym, st, P_DEFAULT) +#define for_all_choices(sym, st) for_all_properties(sym, st, P_CHOICE) +#define for_all_prompts(sym, st) \ + for (st = sym->prop; st; st = st->next) \ + if (st->text) + +struct menu { + struct menu *next; + struct menu *parent; + struct menu *list; + struct symbol *sym; + struct property *prompt; + struct expr *visibility; + struct expr *dep; + unsigned int flags; + char *help; + struct file *file; + int lineno; + void *data; +}; + +#define MENU_CHANGED 0x0001 +#define MENU_ROOT 0x0002 + +extern struct file *file_list; +extern struct file *current_file; +struct file *lookup_file(const char *name); + +extern struct symbol symbol_yes, symbol_no, symbol_mod; +extern struct symbol *modules_sym; +extern struct symbol *sym_defconfig_list; +extern int cdebug; +struct expr *expr_alloc_symbol(struct symbol *sym); +struct expr *expr_alloc_one(enum expr_type type, struct expr *ce); +struct expr *expr_alloc_two(enum expr_type type, struct expr *e1, struct expr *e2); +struct expr *expr_alloc_comp(enum expr_type type, struct symbol *s1, struct symbol *s2); +struct expr *expr_alloc_and(struct expr *e1, struct expr *e2); +struct expr *expr_alloc_or(struct expr *e1, struct expr *e2); +struct expr *expr_copy(const struct expr *org); +void expr_free(struct expr *e); +int expr_eq(struct expr *e1, struct expr *e2); +void expr_eliminate_eq(struct expr **ep1, struct expr **ep2); +tristate expr_calc_value(struct expr *e); +struct expr *expr_eliminate_yn(struct expr *e); +struct expr *expr_trans_bool(struct expr *e); +struct expr *expr_eliminate_dups(struct expr *e); +struct expr *expr_transform(struct expr *e); +int expr_contains_symbol(struct expr *dep, struct symbol *sym); +bool expr_depends_symbol(struct expr *dep, struct symbol *sym); +struct expr *expr_extract_eq_and(struct expr **ep1, struct expr **ep2); +struct expr *expr_extract_eq_or(struct expr **ep1, struct expr **ep2); +void expr_extract_eq(enum expr_type type, struct expr **ep, struct expr **ep1, struct expr **ep2); +struct expr *expr_trans_compare(struct expr *e, enum expr_type type, struct symbol *sym); +struct expr *expr_simplify_unmet_dep(struct expr *e1, struct expr *e2); + +void expr_fprint(struct expr *e, FILE *out); +struct gstr; /* forward */ +void expr_gstr_print(struct expr *e, struct gstr *gs); + +static inline int expr_is_yes(struct expr *e) +{ + return !e || (e->type == E_SYMBOL && e->left.sym == &symbol_yes); +} + +static inline int expr_is_no(struct expr *e) +{ + return e && (e->type == E_SYMBOL && e->left.sym == &symbol_no); +} + +#ifdef __cplusplus +} +#endif + +#endif /* EXPR_H */ diff --git a/misc/tools/kconfig-frontends/libs/parser/hconf.gperf b/misc/tools/kconfig-frontends/libs/parser/hconf.gperf new file mode 100644 index 0000000000..f14ab41154 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/hconf.gperf @@ -0,0 +1,47 @@ +%language=ANSI-C +%define hash-function-name kconf_id_hash +%define lookup-function-name kconf_id_lookup +%define string-pool-name kconf_id_strings +%compare-strncmp +%enum +%pic +%struct-type + +struct kconf_id; + +static const struct kconf_id *kconf_id_lookup(register const char *str, register unsigned int len); + +%% +mainmenu, T_MAINMENU, TF_COMMAND +menu, T_MENU, TF_COMMAND +endmenu, T_ENDMENU, TF_COMMAND +source, T_SOURCE, TF_COMMAND +choice, T_CHOICE, TF_COMMAND +endchoice, T_ENDCHOICE, TF_COMMAND +comment, T_COMMENT, TF_COMMAND +config, T_CONFIG, TF_COMMAND +menuconfig, T_MENUCONFIG, TF_COMMAND +help, T_HELP, TF_COMMAND +if, T_IF, TF_COMMAND|TF_PARAM +endif, T_ENDIF, TF_COMMAND +depends, T_DEPENDS, TF_COMMAND +optional, T_OPTIONAL, TF_COMMAND +default, T_DEFAULT, TF_COMMAND, S_UNKNOWN +prompt, T_PROMPT, TF_COMMAND +tristate, T_TYPE, TF_COMMAND, S_TRISTATE +def_tristate, T_DEFAULT, TF_COMMAND, S_TRISTATE +bool, T_TYPE, TF_COMMAND, S_BOOLEAN +boolean, T_TYPE, TF_COMMAND, S_BOOLEAN +def_bool, T_DEFAULT, TF_COMMAND, S_BOOLEAN +int, T_TYPE, TF_COMMAND, S_INT +hex, T_TYPE, TF_COMMAND, S_HEX +string, T_TYPE, TF_COMMAND, S_STRING +select, T_SELECT, TF_COMMAND +range, T_RANGE, TF_COMMAND +visible, T_VISIBLE, TF_COMMAND +option, T_OPTION, TF_COMMAND +on, T_ON, TF_PARAM +modules, T_OPT_MODULES, TF_OPTION +defconfig_list, T_OPT_DEFCONFIG_LIST,TF_OPTION +env, T_OPT_ENV, TF_OPTION +%% diff --git a/misc/tools/kconfig-frontends/libs/parser/lconf.c b/misc/tools/kconfig-frontends/libs/parser/lconf.c new file mode 100644 index 0000000000..3e7aca0ef8 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/lconf.c @@ -0,0 +1,2434 @@ + +#line 3 "lconf.c" + +#define YY_INT_ALIGNED short int + +/* A lexical scanner generated by flex */ + +#define yy_create_buffer zconf_create_buffer +#define yy_delete_buffer zconf_delete_buffer +#define yy_flex_debug zconf_flex_debug +#define yy_init_buffer zconf_init_buffer +#define yy_flush_buffer zconf_flush_buffer +#define yy_load_buffer_state zconf_load_buffer_state +#define yy_switch_to_buffer zconf_switch_to_buffer +#define yyin zconfin +#define yyleng zconfleng +#define yylex zconflex +#define yylineno zconflineno +#define yyout zconfout +#define yyrestart zconfrestart +#define yytext zconftext +#define yywrap zconfwrap +#define yyalloc zconfalloc +#define yyrealloc zconfrealloc +#define yyfree zconffree + +#define FLEX_SCANNER +#define YY_FLEX_MAJOR_VERSION 2 +#define YY_FLEX_MINOR_VERSION 5 +#define YY_FLEX_SUBMINOR_VERSION 35 +#if YY_FLEX_SUBMINOR_VERSION > 0 +#define FLEX_BETA +#endif + +/* First, we deal with platform-specific or compiler-specific issues. */ + +/* begin standard C headers. */ +#include +#include +#include +#include + +/* end standard C headers. */ + +/* flex integer type definitions */ + +#ifndef FLEXINT_H +#define FLEXINT_H + +/* C99 systems have . Non-C99 systems may or may not. */ + +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + +/* C99 says to define __STDC_LIMIT_MACROS before including stdint.h, + * if you want the limit (max/min) macros for int types. + */ +#ifndef __STDC_LIMIT_MACROS +#define __STDC_LIMIT_MACROS 1 +#endif + +#include +typedef int8_t flex_int8_t; +typedef uint8_t flex_uint8_t; +typedef int16_t flex_int16_t; +typedef uint16_t flex_uint16_t; +typedef int32_t flex_int32_t; +typedef uint32_t flex_uint32_t; +#else +typedef signed char flex_int8_t; +typedef short int flex_int16_t; +typedef int flex_int32_t; +typedef unsigned char flex_uint8_t; +typedef unsigned short int flex_uint16_t; +typedef unsigned int flex_uint32_t; + +/* Limits of integral types. */ +#ifndef INT8_MIN +#define INT8_MIN (-128) +#endif +#ifndef INT16_MIN +#define INT16_MIN (-32767-1) +#endif +#ifndef INT32_MIN +#define INT32_MIN (-2147483647-1) +#endif +#ifndef INT8_MAX +#define INT8_MAX (127) +#endif +#ifndef INT16_MAX +#define INT16_MAX (32767) +#endif +#ifndef INT32_MAX +#define INT32_MAX (2147483647) +#endif +#ifndef UINT8_MAX +#define UINT8_MAX (255U) +#endif +#ifndef UINT16_MAX +#define UINT16_MAX (65535U) +#endif +#ifndef UINT32_MAX +#define UINT32_MAX (4294967295U) +#endif + +#endif /* ! C99 */ + +#endif /* ! FLEXINT_H */ + +#ifdef __cplusplus + +/* The "const" storage-class-modifier is valid. */ +#define YY_USE_CONST + +#else /* ! __cplusplus */ + +/* C99 requires __STDC__ to be defined as 1. */ +#if defined (__STDC__) + +#define YY_USE_CONST + +#endif /* defined (__STDC__) */ +#endif /* ! __cplusplus */ + +#ifdef YY_USE_CONST +#define yyconst const +#else +#define yyconst +#endif + +/* Returned upon end-of-file. */ +#define YY_NULL 0 + +/* Promotes a possibly negative, possibly signed char to an unsigned + * integer for use as an array index. If the signed char is negative, + * we want to instead treat it as an 8-bit unsigned char, hence the + * double cast. + */ +#define YY_SC_TO_UI(c) ((unsigned int) (unsigned char) c) + +/* Enter a start condition. This macro really ought to take a parameter, + * but we do it the disgusting crufty way forced on us by the ()-less + * definition of BEGIN. + */ +#define BEGIN (yy_start) = 1 + 2 * + +/* Translate the current start state into a value that can be later handed + * to BEGIN to return to the state. The YYSTATE alias is for lex + * compatibility. + */ +#define YY_START (((yy_start) - 1) / 2) +#define YYSTATE YY_START + +/* Action number for EOF rule of a given start state. */ +#define YY_STATE_EOF(state) (YY_END_OF_BUFFER + state + 1) + +/* Special action meaning "start processing a new file". */ +#define YY_NEW_FILE zconfrestart(zconfin ) + +#define YY_END_OF_BUFFER_CHAR 0 + +/* Size of default input buffer. */ +#ifndef YY_BUF_SIZE +#ifdef __ia64__ +/* On IA-64, the buffer size is 16k, not 8k. + * Moreover, YY_BUF_SIZE is 2*YY_READ_BUF_SIZE in the general case. + * Ditto for the __ia64__ case accordingly. + */ +#define YY_BUF_SIZE 32768 +#else +#define YY_BUF_SIZE 16384 +#endif /* __ia64__ */ +#endif + +/* The state buf must be large enough to hold one state per character in the main buffer. + */ +#define YY_STATE_BUF_SIZE ((YY_BUF_SIZE + 2) * sizeof(yy_state_type)) + +#ifndef YY_TYPEDEF_YY_BUFFER_STATE +#define YY_TYPEDEF_YY_BUFFER_STATE +typedef struct yy_buffer_state *YY_BUFFER_STATE; +#endif + +extern int zconfleng; + +extern FILE *zconfin, *zconfout; + +#define EOB_ACT_CONTINUE_SCAN 0 +#define EOB_ACT_END_OF_FILE 1 +#define EOB_ACT_LAST_MATCH 2 + + #define YY_LESS_LINENO(n) + +/* Return all but the first "n" matched characters back to the input stream. */ +#define yyless(n) \ + do \ + { \ + /* Undo effects of setting up zconftext. */ \ + int yyless_macro_arg = (n); \ + YY_LESS_LINENO(yyless_macro_arg);\ + *yy_cp = (yy_hold_char); \ + YY_RESTORE_YY_MORE_OFFSET \ + (yy_c_buf_p) = yy_cp = yy_bp + yyless_macro_arg - YY_MORE_ADJ; \ + YY_DO_BEFORE_ACTION; /* set up zconftext again */ \ + } \ + while ( 0 ) + +#define unput(c) yyunput( c, (yytext_ptr) ) + +#ifndef YY_TYPEDEF_YY_SIZE_T +#define YY_TYPEDEF_YY_SIZE_T +typedef size_t yy_size_t; +#endif + +#ifndef YY_STRUCT_YY_BUFFER_STATE +#define YY_STRUCT_YY_BUFFER_STATE +struct yy_buffer_state + { + FILE *yy_input_file; + + char *yy_ch_buf; /* input buffer */ + char *yy_buf_pos; /* current position in input buffer */ + + /* Size of input buffer in bytes, not including room for EOB + * characters. + */ + yy_size_t yy_buf_size; + + /* Number of characters read into yy_ch_buf, not including EOB + * characters. + */ + int yy_n_chars; + + /* Whether we "own" the buffer - i.e., we know we created it, + * and can realloc() it to grow it, and should free() it to + * delete it. + */ + int yy_is_our_buffer; + + /* Whether this is an "interactive" input source; if so, and + * if we're using stdio for input, then we want to use getc() + * instead of fread(), to make sure we stop fetching input after + * each newline. + */ + int yy_is_interactive; + + /* Whether we're considered to be at the beginning of a line. + * If so, '^' rules will be active on the next match, otherwise + * not. + */ + int yy_at_bol; + + int yy_bs_lineno; /**< The line count. */ + int yy_bs_column; /**< The column count. */ + + /* Whether to try to fill the input buffer when we reach the + * end of it. + */ + int yy_fill_buffer; + + int yy_buffer_status; + +#define YY_BUFFER_NEW 0 +#define YY_BUFFER_NORMAL 1 + /* When an EOF's been seen but there's still some text to process + * then we mark the buffer as YY_EOF_PENDING, to indicate that we + * shouldn't try reading from the input source any more. We might + * still have a bunch of tokens to match, though, because of + * possible backing-up. + * + * When we actually see the EOF, we change the status to "new" + * (via zconfrestart()), so that the user can continue scanning by + * just pointing zconfin at a new input file. + */ +#define YY_BUFFER_EOF_PENDING 2 + + }; +#endif /* !YY_STRUCT_YY_BUFFER_STATE */ + +/* Stack of input buffers. */ +static size_t yy_buffer_stack_top = 0; /**< index of top of stack. */ +static size_t yy_buffer_stack_max = 0; /**< capacity of stack. */ +static YY_BUFFER_STATE * yy_buffer_stack = 0; /**< Stack as an array. */ + +/* We provide macros for accessing buffer states in case in the + * future we want to put the buffer states in a more general + * "scanner state". + * + * Returns the top of the stack, or NULL. + */ +#define YY_CURRENT_BUFFER ( (yy_buffer_stack) \ + ? (yy_buffer_stack)[(yy_buffer_stack_top)] \ + : NULL) + +/* Same as previous macro, but useful when we know that the buffer stack is not + * NULL or when we need an lvalue. For internal use only. + */ +#define YY_CURRENT_BUFFER_LVALUE (yy_buffer_stack)[(yy_buffer_stack_top)] + +/* yy_hold_char holds the character lost when zconftext is formed. */ +static char yy_hold_char; +static int yy_n_chars; /* number of characters read into yy_ch_buf */ +int zconfleng; + +/* Points to current character in buffer. */ +static char *yy_c_buf_p = (char *) 0; +static int yy_init = 0; /* whether we need to initialize */ +static int yy_start = 0; /* start state number */ + +/* Flag which is used to allow zconfwrap()'s to do buffer switches + * instead of setting up a fresh zconfin. A bit of a hack ... + */ +static int yy_did_buffer_switch_on_eof; + +void zconfrestart (FILE *input_file ); +void zconf_switch_to_buffer (YY_BUFFER_STATE new_buffer ); +YY_BUFFER_STATE zconf_create_buffer (FILE *file,int size ); +void zconf_delete_buffer (YY_BUFFER_STATE b ); +void zconf_flush_buffer (YY_BUFFER_STATE b ); +void zconfpush_buffer_state (YY_BUFFER_STATE new_buffer ); +void zconfpop_buffer_state (void ); + +static void zconfensure_buffer_stack (void ); +static void zconf_load_buffer_state (void ); +static void zconf_init_buffer (YY_BUFFER_STATE b,FILE *file ); + +#define YY_FLUSH_BUFFER zconf_flush_buffer(YY_CURRENT_BUFFER ) + +YY_BUFFER_STATE zconf_scan_buffer (char *base,yy_size_t size ); +YY_BUFFER_STATE zconf_scan_string (yyconst char *yy_str ); +YY_BUFFER_STATE zconf_scan_bytes (yyconst char *bytes,int len ); + +void *zconfalloc (yy_size_t ); +void *zconfrealloc (void *,yy_size_t ); +void zconffree (void * ); + +#define yy_new_buffer zconf_create_buffer + +#define yy_set_interactive(is_interactive) \ + { \ + if ( ! YY_CURRENT_BUFFER ){ \ + zconfensure_buffer_stack (); \ + YY_CURRENT_BUFFER_LVALUE = \ + zconf_create_buffer(zconfin,YY_BUF_SIZE ); \ + } \ + YY_CURRENT_BUFFER_LVALUE->yy_is_interactive = is_interactive; \ + } + +#define yy_set_bol(at_bol) \ + { \ + if ( ! YY_CURRENT_BUFFER ){\ + zconfensure_buffer_stack (); \ + YY_CURRENT_BUFFER_LVALUE = \ + zconf_create_buffer(zconfin,YY_BUF_SIZE ); \ + } \ + YY_CURRENT_BUFFER_LVALUE->yy_at_bol = at_bol; \ + } + +#define YY_AT_BOL() (YY_CURRENT_BUFFER_LVALUE->yy_at_bol) + +/* Begin user sect3 */ + +#define zconfwrap(n) 1 +#define YY_SKIP_YYWRAP + +typedef unsigned char YY_CHAR; + +FILE *zconfin = (FILE *) 0, *zconfout = (FILE *) 0; + +typedef int yy_state_type; + +extern int zconflineno; + +int zconflineno = 1; + +extern char *zconftext; +#define yytext_ptr zconftext +static yyconst flex_int16_t yy_nxt[][17] = + { + { + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0 + }, + + { + 11, 12, 13, 14, 12, 12, 15, 12, 12, 12, + 12, 12, 12, 12, 12, 12, 12 + }, + + { + 11, 12, 13, 14, 12, 12, 15, 12, 12, 12, + 12, 12, 12, 12, 12, 12, 12 + }, + + { + 11, 16, 16, 17, 16, 16, 16, 16, 16, 16, + 16, 16, 16, 18, 16, 16, 16 + }, + + { + 11, 16, 16, 17, 16, 16, 16, 16, 16, 16, + 16, 16, 16, 18, 16, 16, 16 + + }, + + { + 11, 19, 20, 21, 19, 19, 19, 19, 19, 19, + 19, 19, 19, 19, 19, 19, 19 + }, + + { + 11, 19, 20, 21, 19, 19, 19, 19, 19, 19, + 19, 19, 19, 19, 19, 19, 19 + }, + + { + 11, 22, 22, 23, 22, 24, 22, 22, 24, 22, + 22, 22, 22, 22, 22, 25, 22 + }, + + { + 11, 22, 22, 23, 22, 24, 22, 22, 24, 22, + 22, 22, 22, 22, 22, 25, 22 + }, + + { + 11, 26, 26, 27, 28, 29, 30, 31, 29, 32, + 33, 34, 35, 35, 36, 37, 38 + + }, + + { + 11, 26, 26, 27, 28, 29, 30, 31, 29, 32, + 33, 34, 35, 35, 36, 37, 38 + }, + + { + -11, -11, -11, -11, -11, -11, -11, -11, -11, -11, + -11, -11, -11, -11, -11, -11, -11 + }, + + { + 11, -12, -12, -12, -12, -12, -12, -12, -12, -12, + -12, -12, -12, -12, -12, -12, -12 + }, + + { + 11, -13, 39, 40, -13, -13, 41, -13, -13, -13, + -13, -13, -13, -13, -13, -13, -13 + }, + + { + 11, -14, -14, -14, -14, -14, -14, -14, -14, -14, + -14, -14, -14, -14, -14, -14, -14 + + }, + + { + 11, 42, 42, 43, 42, 42, 42, 42, 42, 42, + 42, 42, 42, 42, 42, 42, 42 + }, + + { + 11, -16, -16, -16, -16, -16, -16, -16, -16, -16, + -16, -16, -16, -16, -16, -16, -16 + }, + + { + 11, -17, -17, -17, -17, -17, -17, -17, -17, -17, + -17, -17, -17, -17, -17, -17, -17 + }, + + { + 11, -18, -18, -18, -18, -18, -18, -18, -18, -18, + -18, -18, -18, 44, -18, -18, -18 + }, + + { + 11, 45, 45, -19, 45, 45, 45, 45, 45, 45, + 45, 45, 45, 45, 45, 45, 45 + + }, + + { + 11, -20, 46, 47, -20, -20, -20, -20, -20, -20, + -20, -20, -20, -20, -20, -20, -20 + }, + + { + 11, 48, -21, -21, 48, 48, 48, 48, 48, 48, + 48, 48, 48, 48, 48, 48, 48 + }, + + { + 11, 49, 49, 50, 49, -22, 49, 49, -22, 49, + 49, 49, 49, 49, 49, -22, 49 + }, + + { + 11, -23, -23, -23, -23, -23, -23, -23, -23, -23, + -23, -23, -23, -23, -23, -23, -23 + }, + + { + 11, -24, -24, -24, -24, -24, -24, -24, -24, -24, + -24, -24, -24, -24, -24, -24, -24 + + }, + + { + 11, 51, 51, 52, 51, 51, 51, 51, 51, 51, + 51, 51, 51, 51, 51, 51, 51 + }, + + { + 11, -26, -26, -26, -26, -26, -26, -26, -26, -26, + -26, -26, -26, -26, -26, -26, -26 + }, + + { + 11, -27, -27, -27, -27, -27, -27, -27, -27, -27, + -27, -27, -27, -27, -27, -27, -27 + }, + + { + 11, -28, -28, -28, -28, -28, -28, -28, -28, -28, + -28, -28, -28, -28, 53, -28, -28 + }, + + { + 11, -29, -29, -29, -29, -29, -29, -29, -29, -29, + -29, -29, -29, -29, -29, -29, -29 + + }, + + { + 11, 54, 54, -30, 54, 54, 54, 54, 54, 54, + 54, 54, 54, 54, 54, 54, 54 + }, + + { + 11, -31, -31, -31, -31, -31, -31, 55, -31, -31, + -31, -31, -31, -31, -31, -31, -31 + }, + + { + 11, -32, -32, -32, -32, -32, -32, -32, -32, -32, + -32, -32, -32, -32, -32, -32, -32 + }, + + { + 11, -33, -33, -33, -33, -33, -33, -33, -33, -33, + -33, -33, -33, -33, -33, -33, -33 + }, + + { + 11, -34, -34, -34, -34, -34, -34, -34, -34, -34, + -34, 56, 57, 57, -34, -34, -34 + + }, + + { + 11, -35, -35, -35, -35, -35, -35, -35, -35, -35, + -35, 57, 57, 57, -35, -35, -35 + }, + + { + 11, -36, -36, -36, -36, -36, -36, -36, -36, -36, + -36, -36, -36, -36, -36, -36, -36 + }, + + { + 11, -37, -37, 58, -37, -37, -37, -37, -37, -37, + -37, -37, -37, -37, -37, -37, -37 + }, + + { + 11, -38, -38, -38, -38, -38, -38, -38, -38, -38, + -38, -38, -38, -38, -38, -38, 59 + }, + + { + 11, -39, 39, 40, -39, -39, 41, -39, -39, -39, + -39, -39, -39, -39, -39, -39, -39 + + }, + + { + 11, -40, -40, -40, -40, -40, -40, -40, -40, -40, + -40, -40, -40, -40, -40, -40, -40 + }, + + { + 11, 42, 42, 43, 42, 42, 42, 42, 42, 42, + 42, 42, 42, 42, 42, 42, 42 + }, + + { + 11, 42, 42, 43, 42, 42, 42, 42, 42, 42, + 42, 42, 42, 42, 42, 42, 42 + }, + + { + 11, -43, -43, -43, -43, -43, -43, -43, -43, -43, + -43, -43, -43, -43, -43, -43, -43 + }, + + { + 11, -44, -44, -44, -44, -44, -44, -44, -44, -44, + -44, -44, -44, 44, -44, -44, -44 + + }, + + { + 11, 45, 45, -45, 45, 45, 45, 45, 45, 45, + 45, 45, 45, 45, 45, 45, 45 + }, + + { + 11, -46, 46, 47, -46, -46, -46, -46, -46, -46, + -46, -46, -46, -46, -46, -46, -46 + }, + + { + 11, 48, -47, -47, 48, 48, 48, 48, 48, 48, + 48, 48, 48, 48, 48, 48, 48 + }, + + { + 11, -48, -48, -48, -48, -48, -48, -48, -48, -48, + -48, -48, -48, -48, -48, -48, -48 + }, + + { + 11, 49, 49, 50, 49, -49, 49, 49, -49, 49, + 49, 49, 49, 49, 49, -49, 49 + + }, + + { + 11, -50, -50, -50, -50, -50, -50, -50, -50, -50, + -50, -50, -50, -50, -50, -50, -50 + }, + + { + 11, -51, -51, 52, -51, -51, -51, -51, -51, -51, + -51, -51, -51, -51, -51, -51, -51 + }, + + { + 11, -52, -52, -52, -52, -52, -52, -52, -52, -52, + -52, -52, -52, -52, -52, -52, -52 + }, + + { + 11, -53, -53, -53, -53, -53, -53, -53, -53, -53, + -53, -53, -53, -53, -53, -53, -53 + }, + + { + 11, 54, 54, -54, 54, 54, 54, 54, 54, 54, + 54, 54, 54, 54, 54, 54, 54 + + }, + + { + 11, -55, -55, -55, -55, -55, -55, -55, -55, -55, + -55, -55, -55, -55, -55, -55, -55 + }, + + { + 11, -56, -56, -56, -56, -56, -56, -56, -56, -56, + -56, 60, 57, 57, -56, -56, -56 + }, + + { + 11, -57, -57, -57, -57, -57, -57, -57, -57, -57, + -57, 57, 57, 57, -57, -57, -57 + }, + + { + 11, -58, -58, -58, -58, -58, -58, -58, -58, -58, + -58, -58, -58, -58, -58, -58, -58 + }, + + { + 11, -59, -59, -59, -59, -59, -59, -59, -59, -59, + -59, -59, -59, -59, -59, -59, -59 + + }, + + { + 11, -60, -60, -60, -60, -60, -60, -60, -60, -60, + -60, 57, 57, 57, -60, -60, -60 + }, + + } ; + +static yy_state_type yy_get_previous_state (void ); +static yy_state_type yy_try_NUL_trans (yy_state_type current_state ); +static int yy_get_next_buffer (void ); +static void yy_fatal_error (yyconst char msg[] ); + +/* Done after the current pattern has been matched and before the + * corresponding action - sets up zconftext. + */ +#define YY_DO_BEFORE_ACTION \ + (yytext_ptr) = yy_bp; \ + zconfleng = (size_t) (yy_cp - yy_bp); \ + (yy_hold_char) = *yy_cp; \ + *yy_cp = '\0'; \ + (yy_c_buf_p) = yy_cp; + +#define YY_NUM_RULES 33 +#define YY_END_OF_BUFFER 34 +/* This struct is not used in this scanner, + but its presence is necessary. */ +struct yy_trans_info + { + flex_int32_t yy_verify; + flex_int32_t yy_nxt; + }; +static yyconst flex_int16_t yy_accept[61] = + { 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 34, 5, 4, 2, 3, 7, 8, 6, 32, 29, + 31, 24, 28, 27, 26, 22, 17, 13, 16, 20, + 22, 11, 12, 19, 19, 14, 22, 22, 4, 2, + 3, 3, 1, 6, 32, 29, 31, 30, 24, 23, + 26, 25, 15, 20, 9, 19, 19, 21, 10, 18 + } ; + +static yyconst flex_int32_t yy_ec[256] = + { 0, + 1, 1, 1, 1, 1, 1, 1, 1, 2, 3, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 2, 4, 5, 6, 1, 1, 7, 8, 9, + 10, 1, 1, 1, 11, 12, 12, 13, 13, 13, + 13, 13, 13, 13, 13, 13, 13, 1, 1, 1, + 14, 1, 1, 1, 13, 13, 13, 13, 13, 13, + 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, + 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, + 1, 15, 1, 1, 13, 1, 13, 13, 13, 13, + + 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, + 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, + 13, 13, 1, 16, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1 + } ; + +extern int zconf_flex_debug; +int zconf_flex_debug = 0; + +/* The intent behind this definition is that it'll catch + * any uses of REJECT which flex missed. + */ +#define REJECT reject_used_but_not_detected +#define yymore() yymore_used_but_not_detected +#define YY_MORE_ADJ 0 +#define YY_RESTORE_YY_MORE_OFFSET +char *zconftext; +#define YY_NO_INPUT 1 + +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#include +#include +#include +#include +#include + +#include "lkc.h" + +#define START_STRSIZE 16 + +static struct { + struct file *file; + int lineno; +} current_pos; + +static char *text; +static int text_size, text_asize; + +struct buffer { + struct buffer *parent; + YY_BUFFER_STATE state; +}; + +struct buffer *current_buf; + +static int last_ts, first_ts; + +static void zconf_endhelp(void); +static void zconf_endfile(void); + +static void new_string(void) +{ + text = malloc(START_STRSIZE); + text_asize = START_STRSIZE; + text_size = 0; + *text = 0; +} + +static void append_string(const char *str, int size) +{ + int new_size = text_size + size + 1; + if (new_size > text_asize) { + new_size += START_STRSIZE - 1; + new_size &= -START_STRSIZE; + text = realloc(text, new_size); + text_asize = new_size; + } + memcpy(text + text_size, str, size); + text_size += size; + text[text_size] = 0; +} + +static void alloc_string(const char *str, int size) +{ + text = malloc(size + 1); + memcpy(text, str, size); + text[size] = 0; +} + +#define INITIAL 0 +#define COMMAND 1 +#define HELP 2 +#define STRING 3 +#define PARAM 4 + +#ifndef YY_NO_UNISTD_H +/* Special case for "unistd.h", since it is non-ANSI. We include it way + * down here because we want the user's section 1 to have been scanned first. + * The user has a chance to override it with an option. + */ +#include +#endif + +#ifndef YY_EXTRA_TYPE +#define YY_EXTRA_TYPE void * +#endif + +static int yy_init_globals (void ); + +/* Accessor methods to globals. + These are made visible to non-reentrant scanners for convenience. */ + +int zconflex_destroy (void ); + +int zconfget_debug (void ); + +void zconfset_debug (int debug_flag ); + +YY_EXTRA_TYPE zconfget_extra (void ); + +void zconfset_extra (YY_EXTRA_TYPE user_defined ); + +FILE *zconfget_in (void ); + +void zconfset_in (FILE * in_str ); + +FILE *zconfget_out (void ); + +void zconfset_out (FILE * out_str ); + +int zconfget_leng (void ); + +char *zconfget_text (void ); + +int zconfget_lineno (void ); + +void zconfset_lineno (int line_number ); + +/* Macros after this point can all be overridden by user definitions in + * section 1. + */ + +#ifndef YY_SKIP_YYWRAP +#ifdef __cplusplus +extern "C" int zconfwrap (void ); +#else +extern int zconfwrap (void ); +#endif +#endif + + static void yyunput (int c,char *buf_ptr ); + +#ifndef yytext_ptr +static void yy_flex_strncpy (char *,yyconst char *,int ); +#endif + +#ifdef YY_NEED_STRLEN +static int yy_flex_strlen (yyconst char * ); +#endif + +#ifndef YY_NO_INPUT + +#ifdef __cplusplus +static int yyinput (void ); +#else +static int input (void ); +#endif + +#endif + +/* Amount of stuff to slurp up with each read. */ +#ifndef YY_READ_BUF_SIZE +#ifdef __ia64__ +/* On IA-64, the buffer size is 16k, not 8k */ +#define YY_READ_BUF_SIZE 16384 +#else +#define YY_READ_BUF_SIZE 8192 +#endif /* __ia64__ */ +#endif + +/* Copy whatever the last rule matched to the standard output. */ +#ifndef ECHO +/* This used to be an fputs(), but since the string might contain NUL's, + * we now use fwrite(). + */ +#define ECHO do { if (fwrite( zconftext, zconfleng, 1, zconfout )) {} } while (0) +#endif + +/* Gets input and stuffs it into "buf". number of characters read, or YY_NULL, + * is returned in "result". + */ +#ifndef YY_INPUT +#define YY_INPUT(buf,result,max_size) \ + errno=0; \ + while ( (result = read( fileno(zconfin), (char *) buf, max_size )) < 0 ) \ + { \ + if( errno != EINTR) \ + { \ + YY_FATAL_ERROR( "input in flex scanner failed" ); \ + break; \ + } \ + errno=0; \ + clearerr(zconfin); \ + }\ +\ + +#endif + +/* No semi-colon after return; correct usage is to write "yyterminate();" - + * we don't want an extra ';' after the "return" because that will cause + * some compilers to complain about unreachable statements. + */ +#ifndef yyterminate +#define yyterminate() return YY_NULL +#endif + +/* Number of entries by which start-condition stack grows. */ +#ifndef YY_START_STACK_INCR +#define YY_START_STACK_INCR 25 +#endif + +/* Report a fatal error. */ +#ifndef YY_FATAL_ERROR +#define YY_FATAL_ERROR(msg) yy_fatal_error( msg ) +#endif + +/* end tables serialization structures and prototypes */ + +/* Default declaration of generated scanner - a define so the user can + * easily add parameters. + */ +#ifndef YY_DECL +#define YY_DECL_IS_OURS 1 + +extern int zconflex (void); + +#define YY_DECL int zconflex (void) +#endif /* !YY_DECL */ + +/* Code executed at the beginning of each rule, after zconftext and zconfleng + * have been set up. + */ +#ifndef YY_USER_ACTION +#define YY_USER_ACTION +#endif + +/* Code executed at the end of each rule. */ +#ifndef YY_BREAK +#define YY_BREAK break; +#endif + +#define YY_RULE_SETUP \ + YY_USER_ACTION + +/** The main scanner function which does all the work. + */ +YY_DECL +{ + register yy_state_type yy_current_state; + register char *yy_cp, *yy_bp; + register int yy_act; + + int str = 0; + int ts, i; + + if ( !(yy_init) ) + { + (yy_init) = 1; + +#ifdef YY_USER_INIT + YY_USER_INIT; +#endif + + if ( ! (yy_start) ) + (yy_start) = 1; /* first start state */ + + if ( ! zconfin ) + zconfin = stdin; + + if ( ! zconfout ) + zconfout = stdout; + + if ( ! YY_CURRENT_BUFFER ) { + zconfensure_buffer_stack (); + YY_CURRENT_BUFFER_LVALUE = + zconf_create_buffer(zconfin,YY_BUF_SIZE ); + } + + zconf_load_buffer_state( ); + } + + while ( 1 ) /* loops until end-of-file is reached */ + { + yy_cp = (yy_c_buf_p); + + /* Support of zconftext. */ + *yy_cp = (yy_hold_char); + + /* yy_bp points to the position in yy_ch_buf of the start of + * the current run. + */ + yy_bp = yy_cp; + + yy_current_state = (yy_start); +yy_match: + while ( (yy_current_state = yy_nxt[yy_current_state][ yy_ec[YY_SC_TO_UI(*yy_cp)] ]) > 0 ) + ++yy_cp; + + yy_current_state = -yy_current_state; + +yy_find_action: + yy_act = yy_accept[yy_current_state]; + + YY_DO_BEFORE_ACTION; + +do_action: /* This label is used only to access EOF actions. */ + + switch ( yy_act ) + { /* beginning of action switch */ +case 1: +/* rule 1 can match eol */ +case 2: +/* rule 2 can match eol */ +YY_RULE_SETUP +{ + current_file->lineno++; + return T_EOL; +} + YY_BREAK +case 3: +YY_RULE_SETUP + + YY_BREAK +case 4: +YY_RULE_SETUP +{ + BEGIN(COMMAND); +} + YY_BREAK +case 5: +YY_RULE_SETUP +{ + unput(zconftext[0]); + BEGIN(COMMAND); +} + YY_BREAK + +case 6: +YY_RULE_SETUP +{ + const struct kconf_id *id = kconf_id_lookup(zconftext, zconfleng); + BEGIN(PARAM); + current_pos.file = current_file; + current_pos.lineno = current_file->lineno; + if (id && id->flags & TF_COMMAND) { + zconflval.id = id; + return id->token; + } + alloc_string(zconftext, zconfleng); + zconflval.string = text; + return T_WORD; + } + YY_BREAK +case 7: +YY_RULE_SETUP + + YY_BREAK +case 8: +/* rule 8 can match eol */ +YY_RULE_SETUP +{ + BEGIN(INITIAL); + current_file->lineno++; + return T_EOL; + } + YY_BREAK + +case 9: +YY_RULE_SETUP +return T_AND; + YY_BREAK +case 10: +YY_RULE_SETUP +return T_OR; + YY_BREAK +case 11: +YY_RULE_SETUP +return T_OPEN_PAREN; + YY_BREAK +case 12: +YY_RULE_SETUP +return T_CLOSE_PAREN; + YY_BREAK +case 13: +YY_RULE_SETUP +return T_NOT; + YY_BREAK +case 14: +YY_RULE_SETUP +return T_EQUAL; + YY_BREAK +case 15: +YY_RULE_SETUP +return T_UNEQUAL; + YY_BREAK +case 16: +YY_RULE_SETUP +{ + str = zconftext[0]; + new_string(); + BEGIN(STRING); + } + YY_BREAK +case 17: +/* rule 17 can match eol */ +YY_RULE_SETUP +BEGIN(INITIAL); current_file->lineno++; return T_EOL; + YY_BREAK +case 18: +YY_RULE_SETUP +/* ignore */ + YY_BREAK +case 19: +YY_RULE_SETUP +{ + const struct kconf_id *id = kconf_id_lookup(zconftext, zconfleng); + if (id && id->flags & TF_PARAM) { + zconflval.id = id; + return id->token; + } + alloc_string(zconftext, zconfleng); + zconflval.string = text; + return T_WORD; + } + YY_BREAK +case 20: +YY_RULE_SETUP +/* comment */ + YY_BREAK +case 21: +/* rule 21 can match eol */ +YY_RULE_SETUP +current_file->lineno++; + YY_BREAK +case 22: +YY_RULE_SETUP + + YY_BREAK +case YY_STATE_EOF(PARAM): +{ + BEGIN(INITIAL); + } + YY_BREAK + +case 23: +/* rule 23 can match eol */ +*yy_cp = (yy_hold_char); /* undo effects of setting up zconftext */ +(yy_c_buf_p) = yy_cp -= 1; +YY_DO_BEFORE_ACTION; /* set up zconftext again */ +YY_RULE_SETUP +{ + append_string(zconftext, zconfleng); + zconflval.string = text; + return T_WORD_QUOTE; + } + YY_BREAK +case 24: +YY_RULE_SETUP +{ + append_string(zconftext, zconfleng); + } + YY_BREAK +case 25: +/* rule 25 can match eol */ +*yy_cp = (yy_hold_char); /* undo effects of setting up zconftext */ +(yy_c_buf_p) = yy_cp -= 1; +YY_DO_BEFORE_ACTION; /* set up zconftext again */ +YY_RULE_SETUP +{ + append_string(zconftext + 1, zconfleng - 1); + zconflval.string = text; + return T_WORD_QUOTE; + } + YY_BREAK +case 26: +YY_RULE_SETUP +{ + append_string(zconftext + 1, zconfleng - 1); + } + YY_BREAK +case 27: +YY_RULE_SETUP +{ + if (str == zconftext[0]) { + BEGIN(PARAM); + zconflval.string = text; + return T_WORD_QUOTE; + } else + append_string(zconftext, 1); + } + YY_BREAK +case 28: +/* rule 28 can match eol */ +YY_RULE_SETUP +{ + printf("%s:%d:warning: multi-line strings not supported\n", zconf_curname(), zconf_lineno()); + current_file->lineno++; + BEGIN(INITIAL); + return T_EOL; + } + YY_BREAK +case YY_STATE_EOF(STRING): +{ + BEGIN(INITIAL); + } + YY_BREAK + +case 29: +YY_RULE_SETUP +{ + ts = 0; + for (i = 0; i < zconfleng; i++) { + if (zconftext[i] == '\t') + ts = (ts & ~7) + 8; + else + ts++; + } + last_ts = ts; + if (first_ts) { + if (ts < first_ts) { + zconf_endhelp(); + return T_HELPTEXT; + } + ts -= first_ts; + while (ts > 8) { + append_string(" ", 8); + ts -= 8; + } + append_string(" ", ts); + } + } + YY_BREAK +case 30: +/* rule 30 can match eol */ +*yy_cp = (yy_hold_char); /* undo effects of setting up zconftext */ +(yy_c_buf_p) = yy_cp -= 1; +YY_DO_BEFORE_ACTION; /* set up zconftext again */ +YY_RULE_SETUP +{ + current_file->lineno++; + zconf_endhelp(); + return T_HELPTEXT; + } + YY_BREAK +case 31: +/* rule 31 can match eol */ +YY_RULE_SETUP +{ + current_file->lineno++; + append_string("\n", 1); + } + YY_BREAK +case 32: +YY_RULE_SETUP +{ + while (zconfleng) { + if ((zconftext[zconfleng-1] != ' ') && (zconftext[zconfleng-1] != '\t')) + break; + zconfleng--; + } + append_string(zconftext, zconfleng); + if (!first_ts) + first_ts = last_ts; + } + YY_BREAK +case YY_STATE_EOF(HELP): +{ + zconf_endhelp(); + return T_HELPTEXT; + } + YY_BREAK + +case YY_STATE_EOF(INITIAL): +case YY_STATE_EOF(COMMAND): +{ + if (current_file) { + zconf_endfile(); + return T_EOL; + } + fclose(zconfin); + yyterminate(); +} + YY_BREAK +case 33: +YY_RULE_SETUP +YY_FATAL_ERROR( "flex scanner jammed" ); + YY_BREAK + + case YY_END_OF_BUFFER: + { + /* Amount of text matched not including the EOB char. */ + int yy_amount_of_matched_text = (int) (yy_cp - (yytext_ptr)) - 1; + + /* Undo the effects of YY_DO_BEFORE_ACTION. */ + *yy_cp = (yy_hold_char); + YY_RESTORE_YY_MORE_OFFSET + + if ( YY_CURRENT_BUFFER_LVALUE->yy_buffer_status == YY_BUFFER_NEW ) + { + /* We're scanning a new file or input source. It's + * possible that this happened because the user + * just pointed zconfin at a new source and called + * zconflex(). If so, then we have to assure + * consistency between YY_CURRENT_BUFFER and our + * globals. Here is the right place to do so, because + * this is the first action (other than possibly a + * back-up) that will match for the new input source. + */ + (yy_n_chars) = YY_CURRENT_BUFFER_LVALUE->yy_n_chars; + YY_CURRENT_BUFFER_LVALUE->yy_input_file = zconfin; + YY_CURRENT_BUFFER_LVALUE->yy_buffer_status = YY_BUFFER_NORMAL; + } + + /* Note that here we test for yy_c_buf_p "<=" to the position + * of the first EOB in the buffer, since yy_c_buf_p will + * already have been incremented past the NUL character + * (since all states make transitions on EOB to the + * end-of-buffer state). Contrast this with the test + * in input(). + */ + if ( (yy_c_buf_p) <= &YY_CURRENT_BUFFER_LVALUE->yy_ch_buf[(yy_n_chars)] ) + { /* This was really a NUL. */ + yy_state_type yy_next_state; + + (yy_c_buf_p) = (yytext_ptr) + yy_amount_of_matched_text; + + yy_current_state = yy_get_previous_state( ); + + /* Okay, we're now positioned to make the NUL + * transition. We couldn't have + * yy_get_previous_state() go ahead and do it + * for us because it doesn't know how to deal + * with the possibility of jamming (and we don't + * want to build jamming into it because then it + * will run more slowly). + */ + + yy_next_state = yy_try_NUL_trans( yy_current_state ); + + yy_bp = (yytext_ptr) + YY_MORE_ADJ; + + if ( yy_next_state ) + { + /* Consume the NUL. */ + yy_cp = ++(yy_c_buf_p); + yy_current_state = yy_next_state; + goto yy_match; + } + + else + { + yy_cp = (yy_c_buf_p); + goto yy_find_action; + } + } + + else switch ( yy_get_next_buffer( ) ) + { + case EOB_ACT_END_OF_FILE: + { + (yy_did_buffer_switch_on_eof) = 0; + + if ( zconfwrap( ) ) + { + /* Note: because we've taken care in + * yy_get_next_buffer() to have set up + * zconftext, we can now set up + * yy_c_buf_p so that if some total + * hoser (like flex itself) wants to + * call the scanner after we return the + * YY_NULL, it'll still work - another + * YY_NULL will get returned. + */ + (yy_c_buf_p) = (yytext_ptr) + YY_MORE_ADJ; + + yy_act = YY_STATE_EOF(YY_START); + goto do_action; + } + + else + { + if ( ! (yy_did_buffer_switch_on_eof) ) + YY_NEW_FILE; + } + break; + } + + case EOB_ACT_CONTINUE_SCAN: + (yy_c_buf_p) = + (yytext_ptr) + yy_amount_of_matched_text; + + yy_current_state = yy_get_previous_state( ); + + yy_cp = (yy_c_buf_p); + yy_bp = (yytext_ptr) + YY_MORE_ADJ; + goto yy_match; + + case EOB_ACT_LAST_MATCH: + (yy_c_buf_p) = + &YY_CURRENT_BUFFER_LVALUE->yy_ch_buf[(yy_n_chars)]; + + yy_current_state = yy_get_previous_state( ); + + yy_cp = (yy_c_buf_p); + yy_bp = (yytext_ptr) + YY_MORE_ADJ; + goto yy_find_action; + } + break; + } + + default: + YY_FATAL_ERROR( + "fatal flex scanner internal error--no action found" ); + } /* end of action switch */ + } /* end of scanning one token */ +} /* end of zconflex */ + +/* yy_get_next_buffer - try to read in a new buffer + * + * Returns a code representing an action: + * EOB_ACT_LAST_MATCH - + * EOB_ACT_CONTINUE_SCAN - continue scanning from current position + * EOB_ACT_END_OF_FILE - end of file + */ +static int yy_get_next_buffer (void) +{ + register char *dest = YY_CURRENT_BUFFER_LVALUE->yy_ch_buf; + register char *source = (yytext_ptr); + register int number_to_move, i; + int ret_val; + + if ( (yy_c_buf_p) > &YY_CURRENT_BUFFER_LVALUE->yy_ch_buf[(yy_n_chars) + 1] ) + YY_FATAL_ERROR( + "fatal flex scanner internal error--end of buffer missed" ); + + if ( YY_CURRENT_BUFFER_LVALUE->yy_fill_buffer == 0 ) + { /* Don't try to fill the buffer, so this is an EOF. */ + if ( (yy_c_buf_p) - (yytext_ptr) - YY_MORE_ADJ == 1 ) + { + /* We matched a single character, the EOB, so + * treat this as a final EOF. + */ + return EOB_ACT_END_OF_FILE; + } + + else + { + /* We matched some text prior to the EOB, first + * process it. + */ + return EOB_ACT_LAST_MATCH; + } + } + + /* Try to read more data. */ + + /* First move last chars to start of buffer. */ + number_to_move = (int) ((yy_c_buf_p) - (yytext_ptr)) - 1; + + for ( i = 0; i < number_to_move; ++i ) + *(dest++) = *(source++); + + if ( YY_CURRENT_BUFFER_LVALUE->yy_buffer_status == YY_BUFFER_EOF_PENDING ) + /* don't do the read, it's not guaranteed to return an EOF, + * just force an EOF + */ + YY_CURRENT_BUFFER_LVALUE->yy_n_chars = (yy_n_chars) = 0; + + else + { + int num_to_read = + YY_CURRENT_BUFFER_LVALUE->yy_buf_size - number_to_move - 1; + + while ( num_to_read <= 0 ) + { /* Not enough room in the buffer - grow it. */ + + /* just a shorter name for the current buffer */ + YY_BUFFER_STATE b = YY_CURRENT_BUFFER; + + int yy_c_buf_p_offset = + (int) ((yy_c_buf_p) - b->yy_ch_buf); + + if ( b->yy_is_our_buffer ) + { + int new_size = b->yy_buf_size * 2; + + if ( new_size <= 0 ) + b->yy_buf_size += b->yy_buf_size / 8; + else + b->yy_buf_size *= 2; + + b->yy_ch_buf = (char *) + /* Include room in for 2 EOB chars. */ + zconfrealloc((void *) b->yy_ch_buf,b->yy_buf_size + 2 ); + } + else + /* Can't grow it, we don't own it. */ + b->yy_ch_buf = 0; + + if ( ! b->yy_ch_buf ) + YY_FATAL_ERROR( + "fatal error - scanner input buffer overflow" ); + + (yy_c_buf_p) = &b->yy_ch_buf[yy_c_buf_p_offset]; + + num_to_read = YY_CURRENT_BUFFER_LVALUE->yy_buf_size - + number_to_move - 1; + + } + + if ( num_to_read > YY_READ_BUF_SIZE ) + num_to_read = YY_READ_BUF_SIZE; + + /* Read in more data. */ + YY_INPUT( (&YY_CURRENT_BUFFER_LVALUE->yy_ch_buf[number_to_move]), + (yy_n_chars), (size_t) num_to_read ); + + YY_CURRENT_BUFFER_LVALUE->yy_n_chars = (yy_n_chars); + } + + if ( (yy_n_chars) == 0 ) + { + if ( number_to_move == YY_MORE_ADJ ) + { + ret_val = EOB_ACT_END_OF_FILE; + zconfrestart(zconfin ); + } + + else + { + ret_val = EOB_ACT_LAST_MATCH; + YY_CURRENT_BUFFER_LVALUE->yy_buffer_status = + YY_BUFFER_EOF_PENDING; + } + } + + else + ret_val = EOB_ACT_CONTINUE_SCAN; + + if ((yy_size_t) ((yy_n_chars) + number_to_move) > YY_CURRENT_BUFFER_LVALUE->yy_buf_size) { + /* Extend the array by 50%, plus the number we really need. */ + yy_size_t new_size = (yy_n_chars) + number_to_move + ((yy_n_chars) >> 1); + YY_CURRENT_BUFFER_LVALUE->yy_ch_buf = (char *) zconfrealloc((void *) YY_CURRENT_BUFFER_LVALUE->yy_ch_buf,new_size ); + if ( ! YY_CURRENT_BUFFER_LVALUE->yy_ch_buf ) + YY_FATAL_ERROR( "out of dynamic memory in yy_get_next_buffer()" ); + } + + (yy_n_chars) += number_to_move; + YY_CURRENT_BUFFER_LVALUE->yy_ch_buf[(yy_n_chars)] = YY_END_OF_BUFFER_CHAR; + YY_CURRENT_BUFFER_LVALUE->yy_ch_buf[(yy_n_chars) + 1] = YY_END_OF_BUFFER_CHAR; + + (yytext_ptr) = &YY_CURRENT_BUFFER_LVALUE->yy_ch_buf[0]; + + return ret_val; +} + +/* yy_get_previous_state - get the state just before the EOB char was reached */ + + static yy_state_type yy_get_previous_state (void) +{ + register yy_state_type yy_current_state; + register char *yy_cp; + + yy_current_state = (yy_start); + + for ( yy_cp = (yytext_ptr) + YY_MORE_ADJ; yy_cp < (yy_c_buf_p); ++yy_cp ) + { + yy_current_state = yy_nxt[yy_current_state][(*yy_cp ? yy_ec[YY_SC_TO_UI(*yy_cp)] : 1)]; + } + + return yy_current_state; +} + +/* yy_try_NUL_trans - try to make a transition on the NUL character + * + * synopsis + * next_state = yy_try_NUL_trans( current_state ); + */ + static yy_state_type yy_try_NUL_trans (yy_state_type yy_current_state ) +{ + register int yy_is_jam; + + yy_current_state = yy_nxt[yy_current_state][1]; + yy_is_jam = (yy_current_state <= 0); + + return yy_is_jam ? 0 : yy_current_state; +} + + static void yyunput (int c, register char * yy_bp ) +{ + register char *yy_cp; + + yy_cp = (yy_c_buf_p); + + /* undo effects of setting up zconftext */ + *yy_cp = (yy_hold_char); + + if ( yy_cp < YY_CURRENT_BUFFER_LVALUE->yy_ch_buf + 2 ) + { /* need to shift things up to make room */ + /* +2 for EOB chars. */ + register int number_to_move = (yy_n_chars) + 2; + register char *dest = &YY_CURRENT_BUFFER_LVALUE->yy_ch_buf[ + YY_CURRENT_BUFFER_LVALUE->yy_buf_size + 2]; + register char *source = + &YY_CURRENT_BUFFER_LVALUE->yy_ch_buf[number_to_move]; + + while ( source > YY_CURRENT_BUFFER_LVALUE->yy_ch_buf ) + *--dest = *--source; + + yy_cp += (int) (dest - source); + yy_bp += (int) (dest - source); + YY_CURRENT_BUFFER_LVALUE->yy_n_chars = + (yy_n_chars) = YY_CURRENT_BUFFER_LVALUE->yy_buf_size; + + if ( yy_cp < YY_CURRENT_BUFFER_LVALUE->yy_ch_buf + 2 ) + YY_FATAL_ERROR( "flex scanner push-back overflow" ); + } + + *--yy_cp = (char) c; + + (yytext_ptr) = yy_bp; + (yy_hold_char) = *yy_cp; + (yy_c_buf_p) = yy_cp; +} + +#ifndef YY_NO_INPUT +#ifdef __cplusplus + static int yyinput (void) +#else + static int input (void) +#endif + +{ + int c; + + *(yy_c_buf_p) = (yy_hold_char); + + if ( *(yy_c_buf_p) == YY_END_OF_BUFFER_CHAR ) + { + /* yy_c_buf_p now points to the character we want to return. + * If this occurs *before* the EOB characters, then it's a + * valid NUL; if not, then we've hit the end of the buffer. + */ + if ( (yy_c_buf_p) < &YY_CURRENT_BUFFER_LVALUE->yy_ch_buf[(yy_n_chars)] ) + /* This was really a NUL. */ + *(yy_c_buf_p) = '\0'; + + else + { /* need more input */ + int offset = (yy_c_buf_p) - (yytext_ptr); + ++(yy_c_buf_p); + + switch ( yy_get_next_buffer( ) ) + { + case EOB_ACT_LAST_MATCH: + /* This happens because yy_g_n_b() + * sees that we've accumulated a + * token and flags that we need to + * try matching the token before + * proceeding. But for input(), + * there's no matching to consider. + * So convert the EOB_ACT_LAST_MATCH + * to EOB_ACT_END_OF_FILE. + */ + + /* Reset buffer status. */ + zconfrestart(zconfin ); + + /*FALLTHROUGH*/ + + case EOB_ACT_END_OF_FILE: + { + if ( zconfwrap( ) ) + return EOF; + + if ( ! (yy_did_buffer_switch_on_eof) ) + YY_NEW_FILE; +#ifdef __cplusplus + return yyinput(); +#else + return input(); +#endif + } + + case EOB_ACT_CONTINUE_SCAN: + (yy_c_buf_p) = (yytext_ptr) + offset; + break; + } + } + } + + c = *(unsigned char *) (yy_c_buf_p); /* cast for 8-bit char's */ + *(yy_c_buf_p) = '\0'; /* preserve zconftext */ + (yy_hold_char) = *++(yy_c_buf_p); + + return c; +} +#endif /* ifndef YY_NO_INPUT */ + +/** Immediately switch to a different input stream. + * @param input_file A readable stream. + * + * @note This function does not reset the start condition to @c INITIAL . + */ + void zconfrestart (FILE * input_file ) +{ + + if ( ! YY_CURRENT_BUFFER ){ + zconfensure_buffer_stack (); + YY_CURRENT_BUFFER_LVALUE = + zconf_create_buffer(zconfin,YY_BUF_SIZE ); + } + + zconf_init_buffer(YY_CURRENT_BUFFER,input_file ); + zconf_load_buffer_state( ); +} + +/** Switch to a different input buffer. + * @param new_buffer The new input buffer. + * + */ + void zconf_switch_to_buffer (YY_BUFFER_STATE new_buffer ) +{ + + /* TODO. We should be able to replace this entire function body + * with + * zconfpop_buffer_state(); + * zconfpush_buffer_state(new_buffer); + */ + zconfensure_buffer_stack (); + if ( YY_CURRENT_BUFFER == new_buffer ) + return; + + if ( YY_CURRENT_BUFFER ) + { + /* Flush out information for old buffer. */ + *(yy_c_buf_p) = (yy_hold_char); + YY_CURRENT_BUFFER_LVALUE->yy_buf_pos = (yy_c_buf_p); + YY_CURRENT_BUFFER_LVALUE->yy_n_chars = (yy_n_chars); + } + + YY_CURRENT_BUFFER_LVALUE = new_buffer; + zconf_load_buffer_state( ); + + /* We don't actually know whether we did this switch during + * EOF (zconfwrap()) processing, but the only time this flag + * is looked at is after zconfwrap() is called, so it's safe + * to go ahead and always set it. + */ + (yy_did_buffer_switch_on_eof) = 1; +} + +static void zconf_load_buffer_state (void) +{ + (yy_n_chars) = YY_CURRENT_BUFFER_LVALUE->yy_n_chars; + (yytext_ptr) = (yy_c_buf_p) = YY_CURRENT_BUFFER_LVALUE->yy_buf_pos; + zconfin = YY_CURRENT_BUFFER_LVALUE->yy_input_file; + (yy_hold_char) = *(yy_c_buf_p); +} + +/** Allocate and initialize an input buffer state. + * @param file A readable stream. + * @param size The character buffer size in bytes. When in doubt, use @c YY_BUF_SIZE. + * + * @return the allocated buffer state. + */ + YY_BUFFER_STATE zconf_create_buffer (FILE * file, int size ) +{ + YY_BUFFER_STATE b; + + b = (YY_BUFFER_STATE) zconfalloc(sizeof( struct yy_buffer_state ) ); + if ( ! b ) + YY_FATAL_ERROR( "out of dynamic memory in zconf_create_buffer()" ); + + b->yy_buf_size = size; + + /* yy_ch_buf has to be 2 characters longer than the size given because + * we need to put in 2 end-of-buffer characters. + */ + b->yy_ch_buf = (char *) zconfalloc(b->yy_buf_size + 2 ); + if ( ! b->yy_ch_buf ) + YY_FATAL_ERROR( "out of dynamic memory in zconf_create_buffer()" ); + + b->yy_is_our_buffer = 1; + + zconf_init_buffer(b,file ); + + return b; +} + +/** Destroy the buffer. + * @param b a buffer created with zconf_create_buffer() + * + */ + void zconf_delete_buffer (YY_BUFFER_STATE b ) +{ + + if ( ! b ) + return; + + if ( b == YY_CURRENT_BUFFER ) /* Not sure if we should pop here. */ + YY_CURRENT_BUFFER_LVALUE = (YY_BUFFER_STATE) 0; + + if ( b->yy_is_our_buffer ) + zconffree((void *) b->yy_ch_buf ); + + zconffree((void *) b ); +} + +/* Initializes or reinitializes a buffer. + * This function is sometimes called more than once on the same buffer, + * such as during a zconfrestart() or at EOF. + */ + static void zconf_init_buffer (YY_BUFFER_STATE b, FILE * file ) + +{ + int oerrno = errno; + + zconf_flush_buffer(b ); + + b->yy_input_file = file; + b->yy_fill_buffer = 1; + + /* If b is the current buffer, then zconf_init_buffer was _probably_ + * called from zconfrestart() or through yy_get_next_buffer. + * In that case, we don't want to reset the lineno or column. + */ + if (b != YY_CURRENT_BUFFER){ + b->yy_bs_lineno = 1; + b->yy_bs_column = 0; + } + + b->yy_is_interactive = 0; + + errno = oerrno; +} + +/** Discard all buffered characters. On the next scan, YY_INPUT will be called. + * @param b the buffer state to be flushed, usually @c YY_CURRENT_BUFFER. + * + */ + void zconf_flush_buffer (YY_BUFFER_STATE b ) +{ + if ( ! b ) + return; + + b->yy_n_chars = 0; + + /* We always need two end-of-buffer characters. The first causes + * a transition to the end-of-buffer state. The second causes + * a jam in that state. + */ + b->yy_ch_buf[0] = YY_END_OF_BUFFER_CHAR; + b->yy_ch_buf[1] = YY_END_OF_BUFFER_CHAR; + + b->yy_buf_pos = &b->yy_ch_buf[0]; + + b->yy_at_bol = 1; + b->yy_buffer_status = YY_BUFFER_NEW; + + if ( b == YY_CURRENT_BUFFER ) + zconf_load_buffer_state( ); +} + +/** Pushes the new state onto the stack. The new state becomes + * the current state. This function will allocate the stack + * if necessary. + * @param new_buffer The new state. + * + */ +void zconfpush_buffer_state (YY_BUFFER_STATE new_buffer ) +{ + if (new_buffer == NULL) + return; + + zconfensure_buffer_stack(); + + /* This block is copied from zconf_switch_to_buffer. */ + if ( YY_CURRENT_BUFFER ) + { + /* Flush out information for old buffer. */ + *(yy_c_buf_p) = (yy_hold_char); + YY_CURRENT_BUFFER_LVALUE->yy_buf_pos = (yy_c_buf_p); + YY_CURRENT_BUFFER_LVALUE->yy_n_chars = (yy_n_chars); + } + + /* Only push if top exists. Otherwise, replace top. */ + if (YY_CURRENT_BUFFER) + (yy_buffer_stack_top)++; + YY_CURRENT_BUFFER_LVALUE = new_buffer; + + /* copied from zconf_switch_to_buffer. */ + zconf_load_buffer_state( ); + (yy_did_buffer_switch_on_eof) = 1; +} + +/** Removes and deletes the top of the stack, if present. + * The next element becomes the new top. + * + */ +void zconfpop_buffer_state (void) +{ + if (!YY_CURRENT_BUFFER) + return; + + zconf_delete_buffer(YY_CURRENT_BUFFER ); + YY_CURRENT_BUFFER_LVALUE = NULL; + if ((yy_buffer_stack_top) > 0) + --(yy_buffer_stack_top); + + if (YY_CURRENT_BUFFER) { + zconf_load_buffer_state( ); + (yy_did_buffer_switch_on_eof) = 1; + } +} + +/* Allocates the stack if it does not exist. + * Guarantees space for at least one push. + */ +static void zconfensure_buffer_stack (void) +{ + int num_to_alloc; + + if (!(yy_buffer_stack)) { + + /* First allocation is just for 2 elements, since we don't know if this + * scanner will even need a stack. We use 2 instead of 1 to avoid an + * immediate realloc on the next call. + */ + num_to_alloc = 1; + (yy_buffer_stack) = (struct yy_buffer_state**)zconfalloc + (num_to_alloc * sizeof(struct yy_buffer_state*) + ); + if ( ! (yy_buffer_stack) ) + YY_FATAL_ERROR( "out of dynamic memory in zconfensure_buffer_stack()" ); + + memset((yy_buffer_stack), 0, num_to_alloc * sizeof(struct yy_buffer_state*)); + + (yy_buffer_stack_max) = num_to_alloc; + (yy_buffer_stack_top) = 0; + return; + } + + if ((yy_buffer_stack_top) >= ((yy_buffer_stack_max)) - 1){ + + /* Increase the buffer to prepare for a possible push. */ + int grow_size = 8 /* arbitrary grow size */; + + num_to_alloc = (yy_buffer_stack_max) + grow_size; + (yy_buffer_stack) = (struct yy_buffer_state**)zconfrealloc + ((yy_buffer_stack), + num_to_alloc * sizeof(struct yy_buffer_state*) + ); + if ( ! (yy_buffer_stack) ) + YY_FATAL_ERROR( "out of dynamic memory in zconfensure_buffer_stack()" ); + + /* zero only the new slots.*/ + memset((yy_buffer_stack) + (yy_buffer_stack_max), 0, grow_size * sizeof(struct yy_buffer_state*)); + (yy_buffer_stack_max) = num_to_alloc; + } +} + +/** Setup the input buffer state to scan directly from a user-specified character buffer. + * @param base the character buffer + * @param size the size in bytes of the character buffer + * + * @return the newly allocated buffer state object. + */ +YY_BUFFER_STATE zconf_scan_buffer (char * base, yy_size_t size ) +{ + YY_BUFFER_STATE b; + + if ( size < 2 || + base[size-2] != YY_END_OF_BUFFER_CHAR || + base[size-1] != YY_END_OF_BUFFER_CHAR ) + /* They forgot to leave room for the EOB's. */ + return 0; + + b = (YY_BUFFER_STATE) zconfalloc(sizeof( struct yy_buffer_state ) ); + if ( ! b ) + YY_FATAL_ERROR( "out of dynamic memory in zconf_scan_buffer()" ); + + b->yy_buf_size = size - 2; /* "- 2" to take care of EOB's */ + b->yy_buf_pos = b->yy_ch_buf = base; + b->yy_is_our_buffer = 0; + b->yy_input_file = 0; + b->yy_n_chars = b->yy_buf_size; + b->yy_is_interactive = 0; + b->yy_at_bol = 1; + b->yy_fill_buffer = 0; + b->yy_buffer_status = YY_BUFFER_NEW; + + zconf_switch_to_buffer(b ); + + return b; +} + +/** Setup the input buffer state to scan a string. The next call to zconflex() will + * scan from a @e copy of @a str. + * @param yystr a NUL-terminated string to scan + * + * @return the newly allocated buffer state object. + * @note If you want to scan bytes that may contain NUL values, then use + * zconf_scan_bytes() instead. + */ +YY_BUFFER_STATE zconf_scan_string (yyconst char * yystr ) +{ + + return zconf_scan_bytes(yystr,strlen(yystr) ); +} + +/** Setup the input buffer state to scan the given bytes. The next call to zconflex() will + * scan from a @e copy of @a bytes. + * @param yybytes the byte buffer to scan + * @param _yybytes_len the number of bytes in the buffer pointed to by @a bytes. + * + * @return the newly allocated buffer state object. + */ +YY_BUFFER_STATE zconf_scan_bytes (yyconst char * yybytes, int _yybytes_len ) +{ + YY_BUFFER_STATE b; + char *buf; + yy_size_t n; + int i; + + /* Get memory for full buffer, including space for trailing EOB's. */ + n = _yybytes_len + 2; + buf = (char *) zconfalloc(n ); + if ( ! buf ) + YY_FATAL_ERROR( "out of dynamic memory in zconf_scan_bytes()" ); + + for ( i = 0; i < _yybytes_len; ++i ) + buf[i] = yybytes[i]; + + buf[_yybytes_len] = buf[_yybytes_len+1] = YY_END_OF_BUFFER_CHAR; + + b = zconf_scan_buffer(buf,n ); + if ( ! b ) + YY_FATAL_ERROR( "bad buffer in zconf_scan_bytes()" ); + + /* It's okay to grow etc. this buffer, and we should throw it + * away when we're done. + */ + b->yy_is_our_buffer = 1; + + return b; +} + +#ifndef YY_EXIT_FAILURE +#define YY_EXIT_FAILURE 2 +#endif + +static void yy_fatal_error (yyconst char* msg ) +{ + (void) fprintf( stderr, "%s\n", msg ); + exit( YY_EXIT_FAILURE ); +} + +/* Redefine yyless() so it works in section 3 code. */ + +#undef yyless +#define yyless(n) \ + do \ + { \ + /* Undo effects of setting up zconftext. */ \ + int yyless_macro_arg = (n); \ + YY_LESS_LINENO(yyless_macro_arg);\ + zconftext[zconfleng] = (yy_hold_char); \ + (yy_c_buf_p) = zconftext + yyless_macro_arg; \ + (yy_hold_char) = *(yy_c_buf_p); \ + *(yy_c_buf_p) = '\0'; \ + zconfleng = yyless_macro_arg; \ + } \ + while ( 0 ) + +/* Accessor methods (get/set functions) to struct members. */ + +/** Get the current line number. + * + */ +int zconfget_lineno (void) +{ + + return zconflineno; +} + +/** Get the input stream. + * + */ +FILE *zconfget_in (void) +{ + return zconfin; +} + +/** Get the output stream. + * + */ +FILE *zconfget_out (void) +{ + return zconfout; +} + +/** Get the length of the current token. + * + */ +int zconfget_leng (void) +{ + return zconfleng; +} + +/** Get the current token. + * + */ + +char *zconfget_text (void) +{ + return zconftext; +} + +/** Set the current line number. + * @param line_number + * + */ +void zconfset_lineno (int line_number ) +{ + + zconflineno = line_number; +} + +/** Set the input stream. This does not discard the current + * input buffer. + * @param in_str A readable stream. + * + * @see zconf_switch_to_buffer + */ +void zconfset_in (FILE * in_str ) +{ + zconfin = in_str ; +} + +void zconfset_out (FILE * out_str ) +{ + zconfout = out_str ; +} + +int zconfget_debug (void) +{ + return zconf_flex_debug; +} + +void zconfset_debug (int bdebug ) +{ + zconf_flex_debug = bdebug ; +} + +static int yy_init_globals (void) +{ + /* Initialization is the same as for the non-reentrant scanner. + * This function is called from zconflex_destroy(), so don't allocate here. + */ + + (yy_buffer_stack) = 0; + (yy_buffer_stack_top) = 0; + (yy_buffer_stack_max) = 0; + (yy_c_buf_p) = (char *) 0; + (yy_init) = 0; + (yy_start) = 0; + +/* Defined in main.c */ +#ifdef YY_STDINIT + zconfin = stdin; + zconfout = stdout; +#else + zconfin = (FILE *) 0; + zconfout = (FILE *) 0; +#endif + + /* For future reference: Set errno on error, since we are called by + * zconflex_init() + */ + return 0; +} + +/* zconflex_destroy is for both reentrant and non-reentrant scanners. */ +int zconflex_destroy (void) +{ + + /* Pop the buffer stack, destroying each element. */ + while(YY_CURRENT_BUFFER){ + zconf_delete_buffer(YY_CURRENT_BUFFER ); + YY_CURRENT_BUFFER_LVALUE = NULL; + zconfpop_buffer_state(); + } + + /* Destroy the stack itself. */ + zconffree((yy_buffer_stack) ); + (yy_buffer_stack) = NULL; + + /* Reset the globals. This is important in a non-reentrant scanner so the next time + * zconflex() is called, initialization will occur. */ + yy_init_globals( ); + + return 0; +} + +/* + * Internal utility routines. + */ + +#ifndef yytext_ptr +static void yy_flex_strncpy (char* s1, yyconst char * s2, int n ) +{ + register int i; + for ( i = 0; i < n; ++i ) + s1[i] = s2[i]; +} +#endif + +#ifdef YY_NEED_STRLEN +static int yy_flex_strlen (yyconst char * s ) +{ + register int n; + for ( n = 0; s[n]; ++n ) + ; + + return n; +} +#endif + +void *zconfalloc (yy_size_t size ) +{ + return (void *) malloc( size ); +} + +void *zconfrealloc (void * ptr, yy_size_t size ) +{ + /* The cast to (char *) in the following accommodates both + * implementations that use char* generic pointers, and those + * that use void* generic pointers. It works with the latter + * because both ANSI C and C++ allow castless assignment from + * any pointer type to void*, and deal with argument conversions + * as though doing an assignment. + */ + return (void *) realloc( (char *) ptr, size ); +} + +void zconffree (void * ptr ) +{ + free( (char *) ptr ); /* see zconfrealloc() for (char *) cast */ +} + +#define YYTABLES_NAME "yytables" + +void zconf_starthelp(void) +{ + new_string(); + last_ts = first_ts = 0; + BEGIN(HELP); +} + +static void zconf_endhelp(void) +{ + zconflval.string = text; + BEGIN(INITIAL); +} + +/* + * Try to open specified file with following names: + * ./name + * $(srctree)/name + * The latter is used when srctree is separate from objtree + * when compiling the kernel. + * Return NULL if file is not found. + */ +FILE *zconf_fopen(const char *name) +{ + char *env, fullname[PATH_MAX+1]; + FILE *f; + + f = fopen(name, "r"); + if (!f && name != NULL && name[0] != '/') { + env = getenv(SRCTREE); + if (env) { + sprintf(fullname, "%s/%s", env, name); + f = fopen(fullname, "r"); + } + } + return f; +} + +void zconf_initscan(const char *name) +{ + zconfin = zconf_fopen(name); + if (!zconfin) { + printf("can't find file %s\n", name); + exit(1); + } + + current_buf = malloc(sizeof(*current_buf)); + memset(current_buf, 0, sizeof(*current_buf)); + + current_file = file_lookup(name); + current_file->lineno = 1; +} + +void zconf_nextfile(const char *name) +{ + struct file *iter; + struct file *file = file_lookup(name); + struct buffer *buf = malloc(sizeof(*buf)); + memset(buf, 0, sizeof(*buf)); + + current_buf->state = YY_CURRENT_BUFFER; + zconfin = zconf_fopen(file->name); + if (!zconfin) { + printf("%s:%d: can't open file \"%s\"\n", + zconf_curname(), zconf_lineno(), file->name); + exit(1); + } + zconf_switch_to_buffer(zconf_create_buffer(zconfin,YY_BUF_SIZE)); + buf->parent = current_buf; + current_buf = buf; + + for (iter = current_file->parent; iter; iter = iter->parent ) { + if (!strcmp(current_file->name,iter->name) ) { + printf("%s:%d: recursive inclusion detected. " + "Inclusion path:\n current file : '%s'\n", + zconf_curname(), zconf_lineno(), + zconf_curname()); + iter = current_file->parent; + while (iter && \ + strcmp(iter->name,current_file->name)) { + printf(" included from: '%s:%d'\n", + iter->name, iter->lineno-1); + iter = iter->parent; + } + if (iter) + printf(" included from: '%s:%d'\n", + iter->name, iter->lineno+1); + exit(1); + } + } + file->lineno = 1; + file->parent = current_file; + current_file = file; +} + +static void zconf_endfile(void) +{ + struct buffer *parent; + + current_file = current_file->parent; + + parent = current_buf->parent; + if (parent) { + fclose(zconfin); + zconf_delete_buffer(YY_CURRENT_BUFFER); + zconf_switch_to_buffer(parent->state); + } + free(current_buf); + current_buf = parent; +} + +int zconf_lineno(void) +{ + return current_pos.lineno; +} + +const char *zconf_curname(void) +{ + return current_pos.file ? current_pos.file->name : ""; +} + diff --git a/misc/tools/kconfig-frontends/libs/parser/lconf.l b/misc/tools/kconfig-frontends/libs/parser/lconf.l new file mode 100644 index 0000000000..00f9d3a9cf --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/lconf.l @@ -0,0 +1,364 @@ +%option nostdinit noyywrap never-interactive full ecs +%option 8bit nodefault perf-report perf-report +%option noinput +%x COMMAND HELP STRING PARAM +%{ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#include +#include +#include +#include +#include + +#include "lkc.h" + +#define START_STRSIZE 16 + +static struct { + struct file *file; + int lineno; +} current_pos; + +static char *text; +static int text_size, text_asize; + +struct buffer { + struct buffer *parent; + YY_BUFFER_STATE state; +}; + +struct buffer *current_buf; + +static int last_ts, first_ts; + +static void zconf_endhelp(void); +static void zconf_endfile(void); + +static void new_string(void) +{ + text = malloc(START_STRSIZE); + text_asize = START_STRSIZE; + text_size = 0; + *text = 0; +} + +static void append_string(const char *str, int size) +{ + int new_size = text_size + size + 1; + if (new_size > text_asize) { + new_size += START_STRSIZE - 1; + new_size &= -START_STRSIZE; + text = realloc(text, new_size); + text_asize = new_size; + } + memcpy(text + text_size, str, size); + text_size += size; + text[text_size] = 0; +} + +static void alloc_string(const char *str, int size) +{ + text = malloc(size + 1); + memcpy(text, str, size); + text[size] = 0; +} +%} + +ws [ \n\t] +n [A-Za-z0-9_] + +%% + int str = 0; + int ts, i; + +[ \t]*#.*\n | +[ \t]*\n { + current_file->lineno++; + return T_EOL; +} +[ \t]*#.* + + +[ \t]+ { + BEGIN(COMMAND); +} + +. { + unput(yytext[0]); + BEGIN(COMMAND); +} + + +{ + {n}+ { + const struct kconf_id *id = kconf_id_lookup(yytext, yyleng); + BEGIN(PARAM); + current_pos.file = current_file; + current_pos.lineno = current_file->lineno; + if (id && id->flags & TF_COMMAND) { + zconflval.id = id; + return id->token; + } + alloc_string(yytext, yyleng); + zconflval.string = text; + return T_WORD; + } + . + \n { + BEGIN(INITIAL); + current_file->lineno++; + return T_EOL; + } +} + +{ + "&&" return T_AND; + "||" return T_OR; + "(" return T_OPEN_PAREN; + ")" return T_CLOSE_PAREN; + "!" return T_NOT; + "=" return T_EQUAL; + "!=" return T_UNEQUAL; + \"|\' { + str = yytext[0]; + new_string(); + BEGIN(STRING); + } + \n BEGIN(INITIAL); current_file->lineno++; return T_EOL; + --- /* ignore */ + ({n}|[-/.])+ { + const struct kconf_id *id = kconf_id_lookup(yytext, yyleng); + if (id && id->flags & TF_PARAM) { + zconflval.id = id; + return id->token; + } + alloc_string(yytext, yyleng); + zconflval.string = text; + return T_WORD; + } + #.* /* comment */ + \\\n current_file->lineno++; + . + <> { + BEGIN(INITIAL); + } +} + +{ + [^'"\\\n]+/\n { + append_string(yytext, yyleng); + zconflval.string = text; + return T_WORD_QUOTE; + } + [^'"\\\n]+ { + append_string(yytext, yyleng); + } + \\.?/\n { + append_string(yytext + 1, yyleng - 1); + zconflval.string = text; + return T_WORD_QUOTE; + } + \\.? { + append_string(yytext + 1, yyleng - 1); + } + \'|\" { + if (str == yytext[0]) { + BEGIN(PARAM); + zconflval.string = text; + return T_WORD_QUOTE; + } else + append_string(yytext, 1); + } + \n { + printf("%s:%d:warning: multi-line strings not supported\n", zconf_curname(), zconf_lineno()); + current_file->lineno++; + BEGIN(INITIAL); + return T_EOL; + } + <> { + BEGIN(INITIAL); + } +} + +{ + [ \t]+ { + ts = 0; + for (i = 0; i < yyleng; i++) { + if (yytext[i] == '\t') + ts = (ts & ~7) + 8; + else + ts++; + } + last_ts = ts; + if (first_ts) { + if (ts < first_ts) { + zconf_endhelp(); + return T_HELPTEXT; + } + ts -= first_ts; + while (ts > 8) { + append_string(" ", 8); + ts -= 8; + } + append_string(" ", ts); + } + } + [ \t]*\n/[^ \t\n] { + current_file->lineno++; + zconf_endhelp(); + return T_HELPTEXT; + } + [ \t]*\n { + current_file->lineno++; + append_string("\n", 1); + } + [^ \t\n].* { + while (yyleng) { + if ((yytext[yyleng-1] != ' ') && (yytext[yyleng-1] != '\t')) + break; + yyleng--; + } + append_string(yytext, yyleng); + if (!first_ts) + first_ts = last_ts; + } + <> { + zconf_endhelp(); + return T_HELPTEXT; + } +} + +<> { + if (current_file) { + zconf_endfile(); + return T_EOL; + } + fclose(yyin); + yyterminate(); +} + +%% +void zconf_starthelp(void) +{ + new_string(); + last_ts = first_ts = 0; + BEGIN(HELP); +} + +static void zconf_endhelp(void) +{ + zconflval.string = text; + BEGIN(INITIAL); +} + + +/* + * Try to open specified file with following names: + * ./name + * $(srctree)/name + * The latter is used when srctree is separate from objtree + * when compiling the kernel. + * Return NULL if file is not found. + */ +FILE *zconf_fopen(const char *name) +{ + char *env, fullname[PATH_MAX+1]; + FILE *f; + + f = fopen(name, "r"); + if (!f && name != NULL && name[0] != '/') { + env = getenv(SRCTREE); + if (env) { + sprintf(fullname, "%s/%s", env, name); + f = fopen(fullname, "r"); + } + } + return f; +} + +void zconf_initscan(const char *name) +{ + yyin = zconf_fopen(name); + if (!yyin) { + printf("can't find file %s\n", name); + exit(1); + } + + current_buf = malloc(sizeof(*current_buf)); + memset(current_buf, 0, sizeof(*current_buf)); + + current_file = file_lookup(name); + current_file->lineno = 1; +} + +void zconf_nextfile(const char *name) +{ + struct file *iter; + struct file *file = file_lookup(name); + struct buffer *buf = malloc(sizeof(*buf)); + memset(buf, 0, sizeof(*buf)); + + current_buf->state = YY_CURRENT_BUFFER; + yyin = zconf_fopen(file->name); + if (!yyin) { + printf("%s:%d: can't open file \"%s\"\n", + zconf_curname(), zconf_lineno(), file->name); + exit(1); + } + yy_switch_to_buffer(yy_create_buffer(yyin, YY_BUF_SIZE)); + buf->parent = current_buf; + current_buf = buf; + + for (iter = current_file->parent; iter; iter = iter->parent ) { + if (!strcmp(current_file->name,iter->name) ) { + printf("%s:%d: recursive inclusion detected. " + "Inclusion path:\n current file : '%s'\n", + zconf_curname(), zconf_lineno(), + zconf_curname()); + iter = current_file->parent; + while (iter && \ + strcmp(iter->name,current_file->name)) { + printf(" included from: '%s:%d'\n", + iter->name, iter->lineno-1); + iter = iter->parent; + } + if (iter) + printf(" included from: '%s:%d'\n", + iter->name, iter->lineno+1); + exit(1); + } + } + file->lineno = 1; + file->parent = current_file; + current_file = file; +} + +static void zconf_endfile(void) +{ + struct buffer *parent; + + current_file = current_file->parent; + + parent = current_buf->parent; + if (parent) { + fclose(yyin); + yy_delete_buffer(YY_CURRENT_BUFFER); + yy_switch_to_buffer(parent->state); + } + free(current_buf); + current_buf = parent; +} + +int zconf_lineno(void) +{ + return current_pos.lineno; +} + +const char *zconf_curname(void) +{ + return current_pos.file ? current_pos.file->name : ""; +} diff --git a/misc/tools/kconfig-frontends/libs/parser/lkc.h b/misc/tools/kconfig-frontends/libs/parser/lkc.h new file mode 100644 index 0000000000..c18f2bd9c0 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/lkc.h @@ -0,0 +1,190 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#ifndef LKC_H +#define LKC_H + +#include "expr.h" + +#ifndef KBUILD_NO_NLS +# include +#else +static inline const char *gettext(const char *txt) { return txt; } +static inline void textdomain(const char *domainname) {} +static inline void bindtextdomain(const char *name, const char *dir) {} +static inline char *bind_textdomain_codeset(const char *dn, char *c) { return c; } +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#define P(name,type,arg) extern type name arg +#include "lkc_proto.h" +#undef P + +#define SRCTREE "srctree" + +#ifndef PACKAGE +#define PACKAGE "linux" +#endif + +#define LOCALEDIR "/usr/share/locale" + +#define _(text) gettext(text) +#define N_(text) (text) + +#ifndef CONFIG_ +#define CONFIG_ "CONFIG_" +#endif + +#define TF_COMMAND 0x0001 +#define TF_PARAM 0x0002 +#define TF_OPTION 0x0004 + +enum conf_def_mode { + def_default, + def_yes, + def_mod, + def_no, + def_random +}; + +#define T_OPT_MODULES 1 +#define T_OPT_DEFCONFIG_LIST 2 +#define T_OPT_ENV 3 + +struct kconf_id { + int name; + int token; + unsigned int flags; + enum symbol_type stype; +}; + +extern int zconfdebug; + +int zconfparse(void); +void zconfdump(FILE *out); +void zconf_starthelp(void); +FILE *zconf_fopen(const char *name); +void zconf_initscan(const char *name); +void zconf_nextfile(const char *name); +int zconf_lineno(void); +const char *zconf_curname(void); + +/* confdata.c */ +const char *conf_get_configname(void); +const char *conf_get_autoconfig_name(void); +char *conf_get_default_confname(void); +void sym_set_change_count(int count); +void sym_add_change_count(int count); +void conf_set_all_new_symbols(enum conf_def_mode mode); + +struct conf_printer { + void (*print_symbol)(FILE *, struct symbol *, const char *, void *); + void (*print_comment)(FILE *, const char *, void *); +}; + +/* confdata.c and expr.c */ +static inline void xfwrite(const void *str, size_t len, size_t count, FILE *out) +{ + assert(len != 0); + + if (fwrite(str, len, count, out) != count) + fprintf(stderr, "Error in writing or end of file.\n"); +} + +/* menu.c */ +void _menu_init(void); +void menu_warn(struct menu *menu, const char *fmt, ...); +struct menu *menu_add_menu(void); +void menu_end_menu(void); +void menu_add_entry(struct symbol *sym); +void menu_end_entry(void); +void menu_add_dep(struct expr *dep); +void menu_add_visibility(struct expr *dep); +struct property *menu_add_prop(enum prop_type type, char *prompt, struct expr *expr, struct expr *dep); +struct property *menu_add_prompt(enum prop_type type, char *prompt, struct expr *dep); +void menu_add_expr(enum prop_type type, struct expr *expr, struct expr *dep); +void menu_add_symbol(enum prop_type type, struct symbol *sym, struct expr *dep); +void menu_add_option(int token, char *arg); +void menu_finalize(struct menu *parent); +void menu_set_type(int type); + +/* util.c */ +struct file *file_lookup(const char *name); +int file_write_dep(const char *name); + +struct gstr { + size_t len; + char *s; + /* + * when max_width is not zero long lines in string s (if any) get + * wrapped not to exceed the max_width value + */ + int max_width; +}; +struct gstr str_new(void); +struct gstr str_assign(const char *s); +void str_free(struct gstr *gs); +void str_append(struct gstr *gs, const char *s); +void str_printf(struct gstr *gs, const char *fmt, ...); +const char *str_get(struct gstr *gs); + +/* symbol.c */ +extern struct expr *sym_env_list; + +void sym_init(void); +void sym_clear_all_valid(void); +void sym_set_all_changed(void); +void sym_set_changed(struct symbol *sym); +struct symbol *sym_choice_default(struct symbol *sym); +const char *sym_get_string_default(struct symbol *sym); +struct symbol *sym_check_deps(struct symbol *sym); +struct property *prop_alloc(enum prop_type type, struct symbol *sym); +struct symbol *prop_get_symbol(struct property *prop); +struct property *sym_get_env_prop(struct symbol *sym); + +static inline tristate sym_get_tristate_value(struct symbol *sym) +{ + return sym->curr.tri; +} + + +static inline struct symbol *sym_get_choice_value(struct symbol *sym) +{ + return (struct symbol *)sym->curr.val; +} + +static inline bool sym_set_choice_value(struct symbol *ch, struct symbol *chval) +{ + return sym_set_tristate_value(chval, yes); +} + +static inline bool sym_is_choice(struct symbol *sym) +{ + return sym->flags & SYMBOL_CHOICE ? true : false; +} + +static inline bool sym_is_choice_value(struct symbol *sym) +{ + return sym->flags & SYMBOL_CHOICEVAL ? true : false; +} + +static inline bool sym_is_optional(struct symbol *sym) +{ + return sym->flags & SYMBOL_OPTIONAL ? true : false; +} + +static inline bool sym_has_value(struct symbol *sym) +{ + return sym->flags & SYMBOL_DEF_USER ? true : false; +} + +#ifdef __cplusplus +} +#endif + +#endif /* LKC_H */ diff --git a/misc/tools/kconfig-frontends/libs/parser/lkc_proto.h b/misc/tools/kconfig-frontends/libs/parser/lkc_proto.h new file mode 100644 index 0000000000..47fe9c340f --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/lkc_proto.h @@ -0,0 +1,54 @@ +#include + +/* confdata.c */ +P(conf_parse,void,(const char *name)); +P(conf_read,int,(const char *name)); +P(conf_read_simple,int,(const char *name, int)); +P(conf_write_defconfig,int,(const char *name)); +P(conf_write,int,(const char *name)); +P(conf_write_autoconf,int,(void)); +P(conf_get_changed,bool,(void)); +P(conf_set_changed_callback, void,(void (*fn)(void))); +P(conf_set_message_callback, void,(void (*fn)(const char *fmt, va_list ap))); + +/* menu.c */ +P(rootmenu,struct menu,); + +P(menu_is_visible, bool, (struct menu *menu)); +P(menu_has_prompt, bool, (struct menu *menu)); +P(menu_get_prompt,const char *,(struct menu *menu)); +P(menu_get_root_menu,struct menu *,(struct menu *menu)); +P(menu_get_parent_menu,struct menu *,(struct menu *menu)); +P(menu_has_help,bool,(struct menu *menu)); +P(menu_get_help,const char *,(struct menu *menu)); +P(get_symbol_str, void, (struct gstr *r, struct symbol *sym)); +P(get_relations_str, struct gstr, (struct symbol **sym_arr)); +P(menu_get_ext_help,void,(struct menu *menu, struct gstr *help)); + +/* symbol.c */ +P(symbol_hash,struct symbol *,[SYMBOL_HASHSIZE]); + +P(sym_lookup,struct symbol *,(const char *name, int flags)); +P(sym_find,struct symbol *,(const char *name)); +P(sym_expand_string_value,const char *,(const char *in)); +P(sym_escape_string_value, const char *,(const char *in)); +P(sym_re_search,struct symbol **,(const char *pattern)); +P(sym_type_name,const char *,(enum symbol_type type)); +P(sym_calc_value,void,(struct symbol *sym)); +P(sym_get_type,enum symbol_type,(struct symbol *sym)); +P(sym_tristate_within_range,bool,(struct symbol *sym,tristate tri)); +P(sym_set_tristate_value,bool,(struct symbol *sym,tristate tri)); +P(sym_toggle_tristate_value,tristate,(struct symbol *sym)); +P(sym_string_valid,bool,(struct symbol *sym, const char *newval)); +P(sym_string_within_range,bool,(struct symbol *sym, const char *str)); +P(sym_set_string_value,bool,(struct symbol *sym, const char *newval)); +P(sym_is_changable,bool,(struct symbol *sym)); +P(sym_get_choice_prop,struct property *,(struct symbol *sym)); +P(sym_get_default_prop,struct property *,(struct symbol *sym)); +P(sym_get_string_value,const char *,(struct symbol *sym)); + +P(prop_get_type_name,const char *,(enum prop_type type)); + +/* expr.c */ +P(expr_compare_type,int,(enum expr_type t1, enum expr_type t2)); +P(expr_print,void,(struct expr *e, void (*fn)(void *, struct symbol *, const char *), void *data, int prevtoken)); diff --git a/misc/tools/kconfig-frontends/libs/parser/menu.c b/misc/tools/kconfig-frontends/libs/parser/menu.c new file mode 100644 index 0000000000..8c2a97e60f --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/menu.c @@ -0,0 +1,607 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#include +#include +#include +#include + +#include "lkc.h" + +static const char nohelp_text[] = "There is no help available for this option."; + +struct menu rootmenu; +static struct menu **last_entry_ptr; + +struct file *file_list; +struct file *current_file; + +void menu_warn(struct menu *menu, const char *fmt, ...) +{ + va_list ap; + va_start(ap, fmt); + fprintf(stderr, "%s:%d:warning: ", menu->file->name, menu->lineno); + vfprintf(stderr, fmt, ap); + fprintf(stderr, "\n"); + va_end(ap); +} + +static void prop_warn(struct property *prop, const char *fmt, ...) +{ + va_list ap; + va_start(ap, fmt); + fprintf(stderr, "%s:%d:warning: ", prop->file->name, prop->lineno); + vfprintf(stderr, fmt, ap); + fprintf(stderr, "\n"); + va_end(ap); +} + +void _menu_init(void) +{ + current_entry = current_menu = &rootmenu; + last_entry_ptr = &rootmenu.list; +} + +void menu_add_entry(struct symbol *sym) +{ + struct menu *menu; + + menu = malloc(sizeof(*menu)); + memset(menu, 0, sizeof(*menu)); + menu->sym = sym; + menu->parent = current_menu; + menu->file = current_file; + menu->lineno = zconf_lineno(); + + *last_entry_ptr = menu; + last_entry_ptr = &menu->next; + current_entry = menu; + if (sym) + menu_add_symbol(P_SYMBOL, sym, NULL); +} + +void menu_end_entry(void) +{ +} + +struct menu *menu_add_menu(void) +{ + menu_end_entry(); + last_entry_ptr = ¤t_entry->list; + return current_menu = current_entry; +} + +void menu_end_menu(void) +{ + last_entry_ptr = ¤t_menu->next; + current_menu = current_menu->parent; +} + +static struct expr *menu_check_dep(struct expr *e) +{ + if (!e) + return e; + + switch (e->type) { + case E_NOT: + e->left.expr = menu_check_dep(e->left.expr); + break; + case E_OR: + case E_AND: + e->left.expr = menu_check_dep(e->left.expr); + e->right.expr = menu_check_dep(e->right.expr); + break; + case E_SYMBOL: + /* change 'm' into 'm' && MODULES */ + if (e->left.sym == &symbol_mod) + return expr_alloc_and(e, expr_alloc_symbol(modules_sym)); + break; + default: + break; + } + return e; +} + +void menu_add_dep(struct expr *dep) +{ + current_entry->dep = expr_alloc_and(current_entry->dep, menu_check_dep(dep)); +} + +void menu_set_type(int type) +{ + struct symbol *sym = current_entry->sym; + + if (sym->type == type) + return; + if (sym->type == S_UNKNOWN) { + sym->type = type; + return; + } + menu_warn(current_entry, "type of '%s' redefined from '%s' to '%s'", + sym->name ? sym->name : "", + sym_type_name(sym->type), sym_type_name(type)); +} + +struct property *menu_add_prop(enum prop_type type, char *prompt, struct expr *expr, struct expr *dep) +{ + struct property *prop = prop_alloc(type, current_entry->sym); + + prop->menu = current_entry; + prop->expr = expr; + prop->visible.expr = menu_check_dep(dep); + + if (prompt) { + if (isspace(*prompt)) { + prop_warn(prop, "leading whitespace ignored"); + while (isspace(*prompt)) + prompt++; + } + if (current_entry->prompt && current_entry != &rootmenu) + prop_warn(prop, "prompt redefined"); + + /* Apply all upper menus' visibilities to actual prompts. */ + if(type == P_PROMPT) { + struct menu *menu = current_entry; + + while ((menu = menu->parent) != NULL) { + if (!menu->visibility) + continue; + prop->visible.expr + = expr_alloc_and(prop->visible.expr, + menu->visibility); + } + } + + current_entry->prompt = prop; + } + prop->text = prompt; + + return prop; +} + +struct property *menu_add_prompt(enum prop_type type, char *prompt, struct expr *dep) +{ + return menu_add_prop(type, prompt, NULL, dep); +} + +void menu_add_visibility(struct expr *expr) +{ + current_entry->visibility = expr_alloc_and(current_entry->visibility, + expr); +} + +void menu_add_expr(enum prop_type type, struct expr *expr, struct expr *dep) +{ + menu_add_prop(type, NULL, expr, dep); +} + +void menu_add_symbol(enum prop_type type, struct symbol *sym, struct expr *dep) +{ + menu_add_prop(type, NULL, expr_alloc_symbol(sym), dep); +} + +void menu_add_option(int token, char *arg) +{ + struct property *prop; + + switch (token) { + case T_OPT_MODULES: + prop = prop_alloc(P_DEFAULT, modules_sym); + prop->expr = expr_alloc_symbol(current_entry->sym); + break; + case T_OPT_DEFCONFIG_LIST: + if (!sym_defconfig_list) + sym_defconfig_list = current_entry->sym; + else if (sym_defconfig_list != current_entry->sym) + zconf_error("trying to redefine defconfig symbol"); + break; + case T_OPT_ENV: + prop_add_env(arg); + break; + } +} + +static int menu_validate_number(struct symbol *sym, struct symbol *sym2) +{ + return sym2->type == S_INT || sym2->type == S_HEX || + (sym2->type == S_UNKNOWN && sym_string_valid(sym, sym2->name)); +} + +static void sym_check_prop(struct symbol *sym) +{ + struct property *prop; + struct symbol *sym2; + for (prop = sym->prop; prop; prop = prop->next) { + switch (prop->type) { + case P_DEFAULT: + if ((sym->type == S_STRING || sym->type == S_INT || sym->type == S_HEX) && + prop->expr->type != E_SYMBOL) + prop_warn(prop, + "default for config symbol '%s'" + " must be a single symbol", sym->name); + if (prop->expr->type != E_SYMBOL) + break; + sym2 = prop_get_symbol(prop); + if (sym->type == S_HEX || sym->type == S_INT) { + if (!menu_validate_number(sym, sym2)) + prop_warn(prop, + "'%s': number is invalid", + sym->name); + } + break; + case P_SELECT: + sym2 = prop_get_symbol(prop); + if (sym->type != S_BOOLEAN && sym->type != S_TRISTATE) + prop_warn(prop, + "config symbol '%s' uses select, but is " + "not boolean or tristate", sym->name); + else if (sym2->type != S_UNKNOWN && + sym2->type != S_BOOLEAN && + sym2->type != S_TRISTATE) + prop_warn(prop, + "'%s' has wrong type. 'select' only " + "accept arguments of boolean and " + "tristate type", sym2->name); + break; + case P_RANGE: + if (sym->type != S_INT && sym->type != S_HEX) + prop_warn(prop, "range is only allowed " + "for int or hex symbols"); + if (!menu_validate_number(sym, prop->expr->left.sym) || + !menu_validate_number(sym, prop->expr->right.sym)) + prop_warn(prop, "range is invalid"); + break; + default: + ; + } + } +} + +void menu_finalize(struct menu *parent) +{ + struct menu *menu, *last_menu; + struct symbol *sym; + struct property *prop; + struct expr *parentdep, *basedep, *dep, *dep2, **ep; + + sym = parent->sym; + if (parent->list) { + if (sym && sym_is_choice(sym)) { + if (sym->type == S_UNKNOWN) { + /* find the first choice value to find out choice type */ + current_entry = parent; + for (menu = parent->list; menu; menu = menu->next) { + if (menu->sym && menu->sym->type != S_UNKNOWN) { + menu_set_type(menu->sym->type); + break; + } + } + } + /* set the type of the remaining choice values */ + for (menu = parent->list; menu; menu = menu->next) { + current_entry = menu; + if (menu->sym && menu->sym->type == S_UNKNOWN) + menu_set_type(sym->type); + } + parentdep = expr_alloc_symbol(sym); + } else if (parent->prompt) + parentdep = parent->prompt->visible.expr; + else + parentdep = parent->dep; + + for (menu = parent->list; menu; menu = menu->next) { + basedep = expr_transform(menu->dep); + basedep = expr_alloc_and(expr_copy(parentdep), basedep); + basedep = expr_eliminate_dups(basedep); + menu->dep = basedep; + if (menu->sym) + prop = menu->sym->prop; + else + prop = menu->prompt; + for (; prop; prop = prop->next) { + if (prop->menu != menu) + continue; + dep = expr_transform(prop->visible.expr); + dep = expr_alloc_and(expr_copy(basedep), dep); + dep = expr_eliminate_dups(dep); + if (menu->sym && menu->sym->type != S_TRISTATE) + dep = expr_trans_bool(dep); + prop->visible.expr = dep; + if (prop->type == P_SELECT) { + struct symbol *es = prop_get_symbol(prop); + es->rev_dep.expr = expr_alloc_or(es->rev_dep.expr, + expr_alloc_and(expr_alloc_symbol(menu->sym), expr_copy(dep))); + } + } + } + for (menu = parent->list; menu; menu = menu->next) + menu_finalize(menu); + } else if (sym) { + basedep = parent->prompt ? parent->prompt->visible.expr : NULL; + basedep = expr_trans_compare(basedep, E_UNEQUAL, &symbol_no); + basedep = expr_eliminate_dups(expr_transform(basedep)); + last_menu = NULL; + for (menu = parent->next; menu; menu = menu->next) { + dep = menu->prompt ? menu->prompt->visible.expr : menu->dep; + if (!expr_contains_symbol(dep, sym)) + break; + if (expr_depends_symbol(dep, sym)) + goto next; + dep = expr_trans_compare(dep, E_UNEQUAL, &symbol_no); + dep = expr_eliminate_dups(expr_transform(dep)); + dep2 = expr_copy(basedep); + expr_eliminate_eq(&dep, &dep2); + expr_free(dep); + if (!expr_is_yes(dep2)) { + expr_free(dep2); + break; + } + expr_free(dep2); + next: + menu_finalize(menu); + menu->parent = parent; + last_menu = menu; + } + if (last_menu) { + parent->list = parent->next; + parent->next = last_menu->next; + last_menu->next = NULL; + } + + sym->dir_dep.expr = expr_alloc_or(sym->dir_dep.expr, parent->dep); + } + for (menu = parent->list; menu; menu = menu->next) { + if (sym && sym_is_choice(sym) && + menu->sym && !sym_is_choice_value(menu->sym)) { + current_entry = menu; + menu->sym->flags |= SYMBOL_CHOICEVAL; + if (!menu->prompt) + menu_warn(menu, "choice value must have a prompt"); + for (prop = menu->sym->prop; prop; prop = prop->next) { + if (prop->type == P_DEFAULT) + prop_warn(prop, "defaults for choice " + "values not supported"); + if (prop->menu == menu) + continue; + if (prop->type == P_PROMPT && + prop->menu->parent->sym != sym) + prop_warn(prop, "choice value used outside its choice group"); + } + /* Non-tristate choice values of tristate choices must + * depend on the choice being set to Y. The choice + * values' dependencies were propagated to their + * properties above, so the change here must be re- + * propagated. + */ + if (sym->type == S_TRISTATE && menu->sym->type != S_TRISTATE) { + basedep = expr_alloc_comp(E_EQUAL, sym, &symbol_yes); + menu->dep = expr_alloc_and(basedep, menu->dep); + for (prop = menu->sym->prop; prop; prop = prop->next) { + if (prop->menu != menu) + continue; + prop->visible.expr = expr_alloc_and(expr_copy(basedep), + prop->visible.expr); + } + } + menu_add_symbol(P_CHOICE, sym, NULL); + prop = sym_get_choice_prop(sym); + for (ep = &prop->expr; *ep; ep = &(*ep)->left.expr) + ; + *ep = expr_alloc_one(E_LIST, NULL); + (*ep)->right.sym = menu->sym; + } + if (menu->list && (!menu->prompt || !menu->prompt->text)) { + for (last_menu = menu->list; ; last_menu = last_menu->next) { + last_menu->parent = parent; + if (!last_menu->next) + break; + } + last_menu->next = menu->next; + menu->next = menu->list; + menu->list = NULL; + } + } + + if (sym && !(sym->flags & SYMBOL_WARNED)) { + if (sym->type == S_UNKNOWN) + menu_warn(parent, "config symbol defined without type"); + + if (sym_is_choice(sym) && !parent->prompt) + menu_warn(parent, "choice must have a prompt"); + + /* Check properties connected to this symbol */ + sym_check_prop(sym); + sym->flags |= SYMBOL_WARNED; + } + + if (sym && !sym_is_optional(sym) && parent->prompt) { + sym->rev_dep.expr = expr_alloc_or(sym->rev_dep.expr, + expr_alloc_and(parent->prompt->visible.expr, + expr_alloc_symbol(&symbol_mod))); + } +} + +bool menu_has_prompt(struct menu *menu) +{ + if (!menu->prompt) + return false; + return true; +} + +bool menu_is_visible(struct menu *menu) +{ + struct menu *child; + struct symbol *sym; + tristate visible; + + if (!menu->prompt) + return false; + + if (menu->visibility) { + if (expr_calc_value(menu->visibility) == no) + return no; + } + + sym = menu->sym; + if (sym) { + sym_calc_value(sym); + visible = menu->prompt->visible.tri; + } else + visible = menu->prompt->visible.tri = expr_calc_value(menu->prompt->visible.expr); + + if (visible != no) + return true; + + if (!sym || sym_get_tristate_value(menu->sym) == no) + return false; + + for (child = menu->list; child; child = child->next) { + if (menu_is_visible(child)) { + if (sym) + sym->flags |= SYMBOL_DEF_USER; + return true; + } + } + + return false; +} + +const char *menu_get_prompt(struct menu *menu) +{ + if (menu->prompt) + return menu->prompt->text; + else if (menu->sym) + return menu->sym->name; + return NULL; +} + +struct menu *menu_get_root_menu(struct menu *menu) +{ + return &rootmenu; +} + +struct menu *menu_get_parent_menu(struct menu *menu) +{ + enum prop_type type; + + for (; menu != &rootmenu; menu = menu->parent) { + type = menu->prompt ? menu->prompt->type : 0; + if (type == P_MENU) + break; + } + return menu; +} + +bool menu_has_help(struct menu *menu) +{ + return menu->help != NULL; +} + +const char *menu_get_help(struct menu *menu) +{ + if (menu->help) + return menu->help; + else + return ""; +} + +static void get_prompt_str(struct gstr *r, struct property *prop) +{ + int i, j; + struct menu *submenu[8], *menu; + + str_printf(r, _("Prompt: %s\n"), _(prop->text)); + str_printf(r, _(" Defined at %s:%d\n"), prop->menu->file->name, + prop->menu->lineno); + if (!expr_is_yes(prop->visible.expr)) { + str_append(r, _(" Depends on: ")); + expr_gstr_print(prop->visible.expr, r); + str_append(r, "\n"); + } + menu = prop->menu->parent; + for (i = 0; menu != &rootmenu && i < 8; menu = menu->parent) + submenu[i++] = menu; + if (i > 0) { + str_printf(r, _(" Location:\n")); + for (j = 4; --i >= 0; j += 2) { + menu = submenu[i]; + str_printf(r, "%*c-> %s", j, ' ', _(menu_get_prompt(menu))); + if (menu->sym) { + str_printf(r, " (%s [=%s])", menu->sym->name ? + menu->sym->name : _(""), + sym_get_string_value(menu->sym)); + } + str_append(r, "\n"); + } + } +} + +void get_symbol_str(struct gstr *r, struct symbol *sym) +{ + bool hit; + struct property *prop; + + if (sym && sym->name) { + str_printf(r, "Symbol: %s [=%s]\n", sym->name, + sym_get_string_value(sym)); + str_printf(r, "Type : %s\n", sym_type_name(sym->type)); + if (sym->type == S_INT || sym->type == S_HEX) { + prop = sym_get_range_prop(sym); + if (prop) { + str_printf(r, "Range : "); + expr_gstr_print(prop->expr, r); + str_append(r, "\n"); + } + } + } + for_all_prompts(sym, prop) + get_prompt_str(r, prop); + hit = false; + for_all_properties(sym, prop, P_SELECT) { + if (!hit) { + str_append(r, " Selects: "); + hit = true; + } else + str_printf(r, " && "); + expr_gstr_print(prop->expr, r); + } + if (hit) + str_append(r, "\n"); + if (sym->rev_dep.expr) { + str_append(r, _(" Selected by: ")); + expr_gstr_print(sym->rev_dep.expr, r); + str_append(r, "\n"); + } + str_append(r, "\n\n"); +} + +struct gstr get_relations_str(struct symbol **sym_arr) +{ + struct symbol *sym; + struct gstr res = str_new(); + int i; + + for (i = 0; sym_arr && (sym = sym_arr[i]); i++) + get_symbol_str(&res, sym); + if (!i) + str_append(&res, _("No matches found.\n")); + return res; +} + + +void menu_get_ext_help(struct menu *menu, struct gstr *help) +{ + struct symbol *sym = menu->sym; + const char *help_text = nohelp_text; + + if (menu_has_help(menu)) { + if (sym->name) + str_printf(help, "%s%s:\n\n", CONFIG_, sym->name); + help_text = menu_get_help(menu); + } + str_printf(help, "%s\n", _(help_text)); + if (sym) + get_symbol_str(help, sym); +} diff --git a/misc/tools/kconfig-frontends/libs/parser/symbol.c b/misc/tools/kconfig-frontends/libs/parser/symbol.c new file mode 100644 index 0000000000..22a3c400fc --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/symbol.c @@ -0,0 +1,1310 @@ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#include +#include +#include +#include +#include + +#include "lkc.h" + +struct symbol symbol_yes = { + .name = "y", + .curr = { "y", yes }, + .flags = SYMBOL_CONST|SYMBOL_VALID, +}, symbol_mod = { + .name = "m", + .curr = { "m", mod }, + .flags = SYMBOL_CONST|SYMBOL_VALID, +}, symbol_no = { + .name = "n", + .curr = { "n", no }, + .flags = SYMBOL_CONST|SYMBOL_VALID, +}, symbol_empty = { + .name = "", + .curr = { "", no }, + .flags = SYMBOL_VALID, +}; + +struct symbol *sym_defconfig_list; +struct symbol *modules_sym; +tristate modules_val; + +struct expr *sym_env_list; + +static void sym_add_default(struct symbol *sym, const char *def) +{ + struct property *prop = prop_alloc(P_DEFAULT, sym); + + prop->expr = expr_alloc_symbol(sym_lookup(def, SYMBOL_CONST)); +} + +void sym_init(void) +{ + struct symbol *sym; + struct utsname uts; + static bool inited = false; + + if (inited) + return; + inited = true; + + uname(&uts); + + sym = sym_lookup("UNAME_RELEASE", 0); + sym->type = S_STRING; + sym->flags |= SYMBOL_AUTO; + sym_add_default(sym, uts.release); +} + +enum symbol_type sym_get_type(struct symbol *sym) +{ + enum symbol_type type = sym->type; + + if (type == S_TRISTATE) { + if (sym_is_choice_value(sym) && sym->visible == yes) + type = S_BOOLEAN; + else if (modules_val == no) + type = S_BOOLEAN; + } + return type; +} + +const char *sym_type_name(enum symbol_type type) +{ + switch (type) { + case S_BOOLEAN: + return "boolean"; + case S_TRISTATE: + return "tristate"; + case S_INT: + return "integer"; + case S_HEX: + return "hex"; + case S_STRING: + return "string"; + case S_UNKNOWN: + return "unknown"; + case S_OTHER: + break; + } + return "???"; +} + +struct property *sym_get_choice_prop(struct symbol *sym) +{ + struct property *prop; + + for_all_choices(sym, prop) + return prop; + return NULL; +} + +struct property *sym_get_env_prop(struct symbol *sym) +{ + struct property *prop; + + for_all_properties(sym, prop, P_ENV) + return prop; + return NULL; +} + +struct property *sym_get_default_prop(struct symbol *sym) +{ + struct property *prop; + + for_all_defaults(sym, prop) { + prop->visible.tri = expr_calc_value(prop->visible.expr); + if (prop->visible.tri != no) + return prop; + } + return NULL; +} + +static struct property *sym_get_range_prop(struct symbol *sym) +{ + struct property *prop; + + for_all_properties(sym, prop, P_RANGE) { + prop->visible.tri = expr_calc_value(prop->visible.expr); + if (prop->visible.tri != no) + return prop; + } + return NULL; +} + +static int sym_get_range_val(struct symbol *sym, int base) +{ + sym_calc_value(sym); + switch (sym->type) { + case S_INT: + base = 10; + break; + case S_HEX: + base = 16; + break; + default: + break; + } + return strtol(sym->curr.val, NULL, base); +} + +static void sym_validate_range(struct symbol *sym) +{ + struct property *prop; + int base, val, val2; + char str[64]; + + switch (sym->type) { + case S_INT: + base = 10; + break; + case S_HEX: + base = 16; + break; + default: + return; + } + prop = sym_get_range_prop(sym); + if (!prop) + return; + val = strtol(sym->curr.val, NULL, base); + val2 = sym_get_range_val(prop->expr->left.sym, base); + if (val >= val2) { + val2 = sym_get_range_val(prop->expr->right.sym, base); + if (val <= val2) + return; + } + if (sym->type == S_INT) + sprintf(str, "%d", val2); + else + sprintf(str, "0x%x", val2); + sym->curr.val = strdup(str); +} + +static void sym_calc_visibility(struct symbol *sym) +{ + struct property *prop; + tristate tri; + + /* any prompt visible? */ + tri = no; + for_all_prompts(sym, prop) { + prop->visible.tri = expr_calc_value(prop->visible.expr); + tri = EXPR_OR(tri, prop->visible.tri); + } + if (tri == mod && (sym->type != S_TRISTATE || modules_val == no)) + tri = yes; + if (sym->visible != tri) { + sym->visible = tri; + sym_set_changed(sym); + } + if (sym_is_choice_value(sym)) + return; + /* defaulting to "yes" if no explicit "depends on" are given */ + tri = yes; + if (sym->dir_dep.expr) + tri = expr_calc_value(sym->dir_dep.expr); + if (tri == mod) + tri = yes; + if (sym->dir_dep.tri != tri) { + sym->dir_dep.tri = tri; + sym_set_changed(sym); + } + tri = no; + if (sym->rev_dep.expr) + tri = expr_calc_value(sym->rev_dep.expr); + if (tri == mod && sym_get_type(sym) == S_BOOLEAN) + tri = yes; + if (sym->rev_dep.tri != tri) { + sym->rev_dep.tri = tri; + sym_set_changed(sym); + } +} + +/* + * Find the default symbol for a choice. + * First try the default values for the choice symbol + * Next locate the first visible choice value + * Return NULL if none was found + */ +struct symbol *sym_choice_default(struct symbol *sym) +{ + struct symbol *def_sym; + struct property *prop; + struct expr *e; + + /* any of the defaults visible? */ + for_all_defaults(sym, prop) { + prop->visible.tri = expr_calc_value(prop->visible.expr); + if (prop->visible.tri == no) + continue; + def_sym = prop_get_symbol(prop); + if (def_sym->visible != no) + return def_sym; + } + + /* just get the first visible value */ + prop = sym_get_choice_prop(sym); + expr_list_for_each_sym(prop->expr, e, def_sym) + if (def_sym->visible != no) + return def_sym; + + /* failed to locate any defaults */ + return NULL; +} + +static struct symbol *sym_calc_choice(struct symbol *sym) +{ + struct symbol *def_sym; + struct property *prop; + struct expr *e; + int flags; + + /* first calculate all choice values' visibilities */ + flags = sym->flags; + prop = sym_get_choice_prop(sym); + expr_list_for_each_sym(prop->expr, e, def_sym) { + sym_calc_visibility(def_sym); + if (def_sym->visible != no) + flags &= def_sym->flags; + } + + sym->flags &= flags | ~SYMBOL_DEF_USER; + + /* is the user choice visible? */ + def_sym = sym->def[S_DEF_USER].val; + if (def_sym && def_sym->visible != no) + return def_sym; + + def_sym = sym_choice_default(sym); + + if (def_sym == NULL) + /* no choice? reset tristate value */ + sym->curr.tri = no; + + return def_sym; +} + +void sym_calc_value(struct symbol *sym) +{ + struct symbol_value newval, oldval; + struct property *prop; + struct expr *e; + + if (!sym) + return; + + if (sym->flags & SYMBOL_VALID) + return; + sym->flags |= SYMBOL_VALID; + + oldval = sym->curr; + + switch (sym->type) { + case S_INT: + case S_HEX: + case S_STRING: + newval = symbol_empty.curr; + break; + case S_BOOLEAN: + case S_TRISTATE: + newval = symbol_no.curr; + break; + default: + sym->curr.val = sym->name; + sym->curr.tri = no; + return; + } + if (!sym_is_choice_value(sym)) + sym->flags &= ~SYMBOL_WRITE; + + sym_calc_visibility(sym); + + /* set default if recursively called */ + sym->curr = newval; + + switch (sym_get_type(sym)) { + case S_BOOLEAN: + case S_TRISTATE: + if (sym_is_choice_value(sym) && sym->visible == yes) { + prop = sym_get_choice_prop(sym); + newval.tri = (prop_get_symbol(prop)->curr.val == sym) ? yes : no; + } else { + if (sym->visible != no) { + /* if the symbol is visible use the user value + * if available, otherwise try the default value + */ + sym->flags |= SYMBOL_WRITE; + if (sym_has_value(sym)) { + newval.tri = EXPR_AND(sym->def[S_DEF_USER].tri, + sym->visible); + goto calc_newval; + } + } + if (sym->rev_dep.tri != no) + sym->flags |= SYMBOL_WRITE; + if (!sym_is_choice(sym)) { + prop = sym_get_default_prop(sym); + if (prop) { + sym->flags |= SYMBOL_WRITE; + newval.tri = EXPR_AND(expr_calc_value(prop->expr), + prop->visible.tri); + } + } + calc_newval: + if (sym->dir_dep.tri == no && sym->rev_dep.tri != no) { + struct expr *e; + e = expr_simplify_unmet_dep(sym->rev_dep.expr, + sym->dir_dep.expr); + fprintf(stderr, "warning: ("); + expr_fprint(e, stderr); + fprintf(stderr, ") selects %s which has unmet direct dependencies (", + sym->name); + expr_fprint(sym->dir_dep.expr, stderr); + fprintf(stderr, ")\n"); + expr_free(e); + } + newval.tri = EXPR_OR(newval.tri, sym->rev_dep.tri); + } + if (newval.tri == mod && sym_get_type(sym) == S_BOOLEAN) + newval.tri = yes; + break; + case S_STRING: + case S_HEX: + case S_INT: + if (sym->visible != no) { + sym->flags |= SYMBOL_WRITE; + if (sym_has_value(sym)) { + newval.val = sym->def[S_DEF_USER].val; + break; + } + } + prop = sym_get_default_prop(sym); + if (prop) { + struct symbol *ds = prop_get_symbol(prop); + if (ds) { + sym->flags |= SYMBOL_WRITE; + sym_calc_value(ds); + newval.val = ds->curr.val; + } + } + break; + default: + ; + } + + sym->curr = newval; + if (sym_is_choice(sym) && newval.tri == yes) + sym->curr.val = sym_calc_choice(sym); + sym_validate_range(sym); + + if (memcmp(&oldval, &sym->curr, sizeof(oldval))) { + sym_set_changed(sym); + if (modules_sym == sym) { + sym_set_all_changed(); + modules_val = modules_sym->curr.tri; + } + } + + if (sym_is_choice(sym)) { + struct symbol *choice_sym; + + prop = sym_get_choice_prop(sym); + expr_list_for_each_sym(prop->expr, e, choice_sym) { + if ((sym->flags & SYMBOL_WRITE) && + choice_sym->visible != no) + choice_sym->flags |= SYMBOL_WRITE; + if (sym->flags & SYMBOL_CHANGED) + sym_set_changed(choice_sym); + } + } + + if (sym->flags & SYMBOL_AUTO) + sym->flags &= ~SYMBOL_WRITE; +} + +void sym_clear_all_valid(void) +{ + struct symbol *sym; + int i; + + for_all_symbols(i, sym) + sym->flags &= ~SYMBOL_VALID; + sym_add_change_count(1); + if (modules_sym) + sym_calc_value(modules_sym); +} + +void sym_set_changed(struct symbol *sym) +{ + struct property *prop; + + sym->flags |= SYMBOL_CHANGED; + for (prop = sym->prop; prop; prop = prop->next) { + if (prop->menu) + prop->menu->flags |= MENU_CHANGED; + } +} + +void sym_set_all_changed(void) +{ + struct symbol *sym; + int i; + + for_all_symbols(i, sym) + sym_set_changed(sym); +} + +bool sym_tristate_within_range(struct symbol *sym, tristate val) +{ + int type = sym_get_type(sym); + + if (sym->visible == no) + return false; + + if (type != S_BOOLEAN && type != S_TRISTATE) + return false; + + if (type == S_BOOLEAN && val == mod) + return false; + if (sym->visible <= sym->rev_dep.tri) + return false; + if (sym_is_choice_value(sym) && sym->visible == yes) + return val == yes; + return val >= sym->rev_dep.tri && val <= sym->visible; +} + +bool sym_set_tristate_value(struct symbol *sym, tristate val) +{ + tristate oldval = sym_get_tristate_value(sym); + + if (oldval != val && !sym_tristate_within_range(sym, val)) + return false; + + if (!(sym->flags & SYMBOL_DEF_USER)) { + sym->flags |= SYMBOL_DEF_USER; + sym_set_changed(sym); + } + /* + * setting a choice value also resets the new flag of the choice + * symbol and all other choice values. + */ + if (sym_is_choice_value(sym) && val == yes) { + struct symbol *cs = prop_get_symbol(sym_get_choice_prop(sym)); + struct property *prop; + struct expr *e; + + cs->def[S_DEF_USER].val = sym; + cs->flags |= SYMBOL_DEF_USER; + prop = sym_get_choice_prop(cs); + for (e = prop->expr; e; e = e->left.expr) { + if (e->right.sym->visible != no) + e->right.sym->flags |= SYMBOL_DEF_USER; + } + } + + sym->def[S_DEF_USER].tri = val; + if (oldval != val) + sym_clear_all_valid(); + + return true; +} + +tristate sym_toggle_tristate_value(struct symbol *sym) +{ + tristate oldval, newval; + + oldval = newval = sym_get_tristate_value(sym); + do { + switch (newval) { + case no: + newval = mod; + break; + case mod: + newval = yes; + break; + case yes: + newval = no; + break; + } + if (sym_set_tristate_value(sym, newval)) + break; + } while (oldval != newval); + return newval; +} + +bool sym_string_valid(struct symbol *sym, const char *str) +{ + signed char ch; + + switch (sym->type) { + case S_STRING: + return true; + case S_INT: + ch = *str++; + if (ch == '-') + ch = *str++; + if (!isdigit(ch)) + return false; + if (ch == '0' && *str != 0) + return false; + while ((ch = *str++)) { + if (!isdigit(ch)) + return false; + } + return true; + case S_HEX: + if (str[0] == '0' && (str[1] == 'x' || str[1] == 'X')) + str += 2; + ch = *str++; + do { + if (!isxdigit(ch)) + return false; + } while ((ch = *str++)); + return true; + case S_BOOLEAN: + case S_TRISTATE: + switch (str[0]) { + case 'y': case 'Y': + case 'm': case 'M': + case 'n': case 'N': + return true; + } + return false; + default: + return false; + } +} + +bool sym_string_within_range(struct symbol *sym, const char *str) +{ + struct property *prop; + int val; + + switch (sym->type) { + case S_STRING: + return sym_string_valid(sym, str); + case S_INT: + if (!sym_string_valid(sym, str)) + return false; + prop = sym_get_range_prop(sym); + if (!prop) + return true; + val = strtol(str, NULL, 10); + return val >= sym_get_range_val(prop->expr->left.sym, 10) && + val <= sym_get_range_val(prop->expr->right.sym, 10); + case S_HEX: + if (!sym_string_valid(sym, str)) + return false; + prop = sym_get_range_prop(sym); + if (!prop) + return true; + val = strtol(str, NULL, 16); + return val >= sym_get_range_val(prop->expr->left.sym, 16) && + val <= sym_get_range_val(prop->expr->right.sym, 16); + case S_BOOLEAN: + case S_TRISTATE: + switch (str[0]) { + case 'y': case 'Y': + return sym_tristate_within_range(sym, yes); + case 'm': case 'M': + return sym_tristate_within_range(sym, mod); + case 'n': case 'N': + return sym_tristate_within_range(sym, no); + } + return false; + default: + return false; + } +} + +bool sym_set_string_value(struct symbol *sym, const char *newval) +{ + const char *oldval; + char *val; + int size; + + switch (sym->type) { + case S_BOOLEAN: + case S_TRISTATE: + switch (newval[0]) { + case 'y': case 'Y': + return sym_set_tristate_value(sym, yes); + case 'm': case 'M': + return sym_set_tristate_value(sym, mod); + case 'n': case 'N': + return sym_set_tristate_value(sym, no); + } + return false; + default: + ; + } + + if (!sym_string_within_range(sym, newval)) + return false; + + if (!(sym->flags & SYMBOL_DEF_USER)) { + sym->flags |= SYMBOL_DEF_USER; + sym_set_changed(sym); + } + + oldval = sym->def[S_DEF_USER].val; + size = strlen(newval) + 1; + if (sym->type == S_HEX && (newval[0] != '0' || (newval[1] != 'x' && newval[1] != 'X'))) { + size += 2; + sym->def[S_DEF_USER].val = val = malloc(size); + *val++ = '0'; + *val++ = 'x'; + } else if (!oldval || strcmp(oldval, newval)) + sym->def[S_DEF_USER].val = val = malloc(size); + else + return true; + + strcpy(val, newval); + free((void *)oldval); + sym_clear_all_valid(); + + return true; +} + +/* + * Find the default value associated to a symbol. + * For tristate symbol handle the modules=n case + * in which case "m" becomes "y". + * If the symbol does not have any default then fallback + * to the fixed default values. + */ +const char *sym_get_string_default(struct symbol *sym) +{ + struct property *prop; + struct symbol *ds; + const char *str; + tristate val; + + sym_calc_visibility(sym); + sym_calc_value(modules_sym); + val = symbol_no.curr.tri; + str = symbol_empty.curr.val; + + /* If symbol has a default value look it up */ + prop = sym_get_default_prop(sym); + if (prop != NULL) { + switch (sym->type) { + case S_BOOLEAN: + case S_TRISTATE: + /* The visibility may limit the value from yes => mod */ + val = EXPR_AND(expr_calc_value(prop->expr), prop->visible.tri); + break; + default: + /* + * The following fails to handle the situation + * where a default value is further limited by + * the valid range. + */ + ds = prop_get_symbol(prop); + if (ds != NULL) { + sym_calc_value(ds); + str = (const char *)ds->curr.val; + } + } + } + + /* Handle select statements */ + val = EXPR_OR(val, sym->rev_dep.tri); + + /* transpose mod to yes if modules are not enabled */ + if (val == mod) + if (!sym_is_choice_value(sym) && modules_sym->curr.tri == no) + val = yes; + + /* transpose mod to yes if type is bool */ + if (sym->type == S_BOOLEAN && val == mod) + val = yes; + + switch (sym->type) { + case S_BOOLEAN: + case S_TRISTATE: + switch (val) { + case no: return "n"; + case mod: return "m"; + case yes: return "y"; + } + case S_INT: + case S_HEX: + return str; + case S_STRING: + return str; + case S_OTHER: + case S_UNKNOWN: + break; + } + return ""; +} + +const char *sym_get_string_value(struct symbol *sym) +{ + tristate val; + + switch (sym->type) { + case S_BOOLEAN: + case S_TRISTATE: + val = sym_get_tristate_value(sym); + switch (val) { + case no: + return "n"; + case mod: + sym_calc_value(modules_sym); + return (modules_sym->curr.tri == no) ? "n" : "m"; + case yes: + return "y"; + } + break; + default: + ; + } + return (const char *)sym->curr.val; +} + +bool sym_is_changable(struct symbol *sym) +{ + return sym->visible > sym->rev_dep.tri; +} + +static unsigned strhash(const char *s) +{ + /* fnv32 hash */ + unsigned hash = 2166136261U; + for (; *s; s++) + hash = (hash ^ *s) * 0x01000193; + return hash; +} + +struct symbol *sym_lookup(const char *name, int flags) +{ + struct symbol *symbol; + char *new_name; + int hash; + + if (name) { + if (name[0] && !name[1]) { + switch (name[0]) { + case 'y': return &symbol_yes; + case 'm': return &symbol_mod; + case 'n': return &symbol_no; + } + } + hash = strhash(name) % SYMBOL_HASHSIZE; + + for (symbol = symbol_hash[hash]; symbol; symbol = symbol->next) { + if (symbol->name && + !strcmp(symbol->name, name) && + (flags ? symbol->flags & flags + : !(symbol->flags & (SYMBOL_CONST|SYMBOL_CHOICE)))) + return symbol; + } + new_name = strdup(name); + } else { + new_name = NULL; + hash = 0; + } + + symbol = malloc(sizeof(*symbol)); + memset(symbol, 0, sizeof(*symbol)); + symbol->name = new_name; + symbol->type = S_UNKNOWN; + symbol->flags |= flags; + + symbol->next = symbol_hash[hash]; + symbol_hash[hash] = symbol; + + return symbol; +} + +struct symbol *sym_find(const char *name) +{ + struct symbol *symbol = NULL; + int hash = 0; + + if (!name) + return NULL; + + if (name[0] && !name[1]) { + switch (name[0]) { + case 'y': return &symbol_yes; + case 'm': return &symbol_mod; + case 'n': return &symbol_no; + } + } + hash = strhash(name) % SYMBOL_HASHSIZE; + + for (symbol = symbol_hash[hash]; symbol; symbol = symbol->next) { + if (symbol->name && + !strcmp(symbol->name, name) && + !(symbol->flags & SYMBOL_CONST)) + break; + } + + return symbol; +} + +/* + * Expand symbol's names embedded in the string given in argument. Symbols' + * name to be expanded shall be prefixed by a '$'. Unknown symbol expands to + * the empty string. + */ +const char *sym_expand_string_value(const char *in) +{ + const char *src; + char *res; + size_t reslen; + + reslen = strlen(in) + 1; + res = malloc(reslen); + res[0] = '\0'; + + while ((src = strchr(in, '$'))) { + char *p, name[SYMBOL_MAXLENGTH]; + const char *symval = ""; + struct symbol *sym; + size_t newlen; + + strncat(res, in, src - in); + src++; + + p = name; + while (isalnum(*src) || *src == '_') + *p++ = *src++; + *p = '\0'; + + sym = sym_find(name); + if (sym != NULL) { + sym_calc_value(sym); + symval = sym_get_string_value(sym); + } + + newlen = strlen(res) + strlen(symval) + strlen(src) + 1; + if (newlen > reslen) { + reslen = newlen; + res = realloc(res, reslen); + } + + strcat(res, symval); + in = src; + } + strcat(res, in); + + return res; +} + +const char *sym_escape_string_value(const char *in) +{ + const char *p; + size_t reslen; + char *res; + size_t l; + + reslen = strlen(in) + strlen("\"\"") + 1; + + p = in; + for (;;) { + l = strcspn(p, "\"\\"); + p += l; + + if (p[0] == '\0') + break; + + reslen++; + p++; + } + + res = malloc(reslen); + res[0] = '\0'; + + strcat(res, "\""); + + p = in; + for (;;) { + l = strcspn(p, "\"\\"); + strncat(res, p, l); + p += l; + + if (p[0] == '\0') + break; + + strcat(res, "\\"); + strncat(res, p++, 1); + } + + strcat(res, "\""); + return res; +} + +struct symbol **sym_re_search(const char *pattern) +{ + struct symbol *sym, **sym_arr = NULL; + int i, cnt, size; + regex_t re; + + cnt = size = 0; + /* Skip if empty */ + if (strlen(pattern) == 0) + return NULL; + if (regcomp(&re, pattern, REG_EXTENDED|REG_NOSUB|REG_ICASE)) + return NULL; + + for_all_symbols(i, sym) { + if (sym->flags & SYMBOL_CONST || !sym->name) + continue; + if (regexec(&re, sym->name, 0, NULL, 0)) + continue; + if (cnt + 1 >= size) { + void *tmp = sym_arr; + size += 16; + sym_arr = realloc(sym_arr, size * sizeof(struct symbol *)); + if (!sym_arr) { + free(tmp); + return NULL; + } + } + sym_calc_value(sym); + sym_arr[cnt++] = sym; + } + if (sym_arr) + sym_arr[cnt] = NULL; + regfree(&re); + + return sym_arr; +} + +/* + * When we check for recursive dependencies we use a stack to save + * current state so we can print out relevant info to user. + * The entries are located on the call stack so no need to free memory. + * Note inser() remove() must always match to properly clear the stack. + */ +static struct dep_stack { + struct dep_stack *prev, *next; + struct symbol *sym; + struct property *prop; + struct expr *expr; +} *check_top; + +static void dep_stack_insert(struct dep_stack *stack, struct symbol *sym) +{ + memset(stack, 0, sizeof(*stack)); + if (check_top) + check_top->next = stack; + stack->prev = check_top; + stack->sym = sym; + check_top = stack; +} + +static void dep_stack_remove(void) +{ + check_top = check_top->prev; + if (check_top) + check_top->next = NULL; +} + +/* + * Called when we have detected a recursive dependency. + * check_top point to the top of the stact so we use + * the ->prev pointer to locate the bottom of the stack. + */ +static void sym_check_print_recursive(struct symbol *last_sym) +{ + struct dep_stack *stack; + struct symbol *sym, *next_sym; + struct menu *menu = NULL; + struct property *prop; + struct dep_stack cv_stack; + + if (sym_is_choice_value(last_sym)) { + dep_stack_insert(&cv_stack, last_sym); + last_sym = prop_get_symbol(sym_get_choice_prop(last_sym)); + } + + for (stack = check_top; stack != NULL; stack = stack->prev) + if (stack->sym == last_sym) + break; + if (!stack) { + fprintf(stderr, "unexpected recursive dependency error\n"); + return; + } + + for (; stack; stack = stack->next) { + sym = stack->sym; + next_sym = stack->next ? stack->next->sym : last_sym; + prop = stack->prop; + if (prop == NULL) + prop = stack->sym->prop; + + /* for choice values find the menu entry (used below) */ + if (sym_is_choice(sym) || sym_is_choice_value(sym)) { + for (prop = sym->prop; prop; prop = prop->next) { + menu = prop->menu; + if (prop->menu) + break; + } + } + if (stack->sym == last_sym) + fprintf(stderr, "%s:%d:error: recursive dependency detected!\n", + prop->file->name, prop->lineno); + if (stack->expr) { + fprintf(stderr, "%s:%d:\tsymbol %s %s value contains %s\n", + prop->file->name, prop->lineno, + sym->name ? sym->name : "", + prop_get_type_name(prop->type), + next_sym->name ? next_sym->name : ""); + } else if (stack->prop) { + fprintf(stderr, "%s:%d:\tsymbol %s depends on %s\n", + prop->file->name, prop->lineno, + sym->name ? sym->name : "", + next_sym->name ? next_sym->name : ""); + } else if (sym_is_choice(sym)) { + fprintf(stderr, "%s:%d:\tchoice %s contains symbol %s\n", + menu->file->name, menu->lineno, + sym->name ? sym->name : "", + next_sym->name ? next_sym->name : ""); + } else if (sym_is_choice_value(sym)) { + fprintf(stderr, "%s:%d:\tsymbol %s is part of choice %s\n", + menu->file->name, menu->lineno, + sym->name ? sym->name : "", + next_sym->name ? next_sym->name : ""); + } else { + fprintf(stderr, "%s:%d:\tsymbol %s is selected by %s\n", + prop->file->name, prop->lineno, + sym->name ? sym->name : "", + next_sym->name ? next_sym->name : ""); + } + } + + if (check_top == &cv_stack) + dep_stack_remove(); +} + +static struct symbol *sym_check_expr_deps(struct expr *e) +{ + struct symbol *sym; + + if (!e) + return NULL; + switch (e->type) { + case E_OR: + case E_AND: + sym = sym_check_expr_deps(e->left.expr); + if (sym) + return sym; + return sym_check_expr_deps(e->right.expr); + case E_NOT: + return sym_check_expr_deps(e->left.expr); + case E_EQUAL: + case E_UNEQUAL: + sym = sym_check_deps(e->left.sym); + if (sym) + return sym; + return sym_check_deps(e->right.sym); + case E_SYMBOL: + return sym_check_deps(e->left.sym); + default: + break; + } + printf("Oops! How to check %d?\n", e->type); + return NULL; +} + +/* return NULL when dependencies are OK */ +static struct symbol *sym_check_sym_deps(struct symbol *sym) +{ + struct symbol *sym2; + struct property *prop; + struct dep_stack stack; + + dep_stack_insert(&stack, sym); + + sym2 = sym_check_expr_deps(sym->rev_dep.expr); + if (sym2) + goto out; + + for (prop = sym->prop; prop; prop = prop->next) { + if (prop->type == P_CHOICE || prop->type == P_SELECT) + continue; + stack.prop = prop; + sym2 = sym_check_expr_deps(prop->visible.expr); + if (sym2) + break; + if (prop->type != P_DEFAULT || sym_is_choice(sym)) + continue; + stack.expr = prop->expr; + sym2 = sym_check_expr_deps(prop->expr); + if (sym2) + break; + stack.expr = NULL; + } + +out: + dep_stack_remove(); + + return sym2; +} + +static struct symbol *sym_check_choice_deps(struct symbol *choice) +{ + struct symbol *sym, *sym2; + struct property *prop; + struct expr *e; + struct dep_stack stack; + + dep_stack_insert(&stack, choice); + + prop = sym_get_choice_prop(choice); + expr_list_for_each_sym(prop->expr, e, sym) + sym->flags |= (SYMBOL_CHECK | SYMBOL_CHECKED); + + choice->flags |= (SYMBOL_CHECK | SYMBOL_CHECKED); + sym2 = sym_check_sym_deps(choice); + choice->flags &= ~SYMBOL_CHECK; + if (sym2) + goto out; + + expr_list_for_each_sym(prop->expr, e, sym) { + sym2 = sym_check_sym_deps(sym); + if (sym2) + break; + } +out: + expr_list_for_each_sym(prop->expr, e, sym) + sym->flags &= ~SYMBOL_CHECK; + + if (sym2 && sym_is_choice_value(sym2) && + prop_get_symbol(sym_get_choice_prop(sym2)) == choice) + sym2 = choice; + + dep_stack_remove(); + + return sym2; +} + +struct symbol *sym_check_deps(struct symbol *sym) +{ + struct symbol *sym2; + struct property *prop; + + if (sym->flags & SYMBOL_CHECK) { + sym_check_print_recursive(sym); + return sym; + } + if (sym->flags & SYMBOL_CHECKED) + return NULL; + + if (sym_is_choice_value(sym)) { + struct dep_stack stack; + + /* for choice groups start the check with main choice symbol */ + dep_stack_insert(&stack, sym); + prop = sym_get_choice_prop(sym); + sym2 = sym_check_deps(prop_get_symbol(prop)); + dep_stack_remove(); + } else if (sym_is_choice(sym)) { + sym2 = sym_check_choice_deps(sym); + } else { + sym->flags |= (SYMBOL_CHECK | SYMBOL_CHECKED); + sym2 = sym_check_sym_deps(sym); + sym->flags &= ~SYMBOL_CHECK; + } + + if (sym2 && sym2 == sym) + sym2 = NULL; + + return sym2; +} + +struct property *prop_alloc(enum prop_type type, struct symbol *sym) +{ + struct property *prop; + struct property **propp; + + prop = malloc(sizeof(*prop)); + memset(prop, 0, sizeof(*prop)); + prop->type = type; + prop->sym = sym; + prop->file = current_file; + prop->lineno = zconf_lineno(); + + /* append property to the prop list of symbol */ + if (sym) { + for (propp = &sym->prop; *propp; propp = &(*propp)->next) + ; + *propp = prop; + } + + return prop; +} + +struct symbol *prop_get_symbol(struct property *prop) +{ + if (prop->expr && (prop->expr->type == E_SYMBOL || + prop->expr->type == E_LIST)) + return prop->expr->left.sym; + return NULL; +} + +const char *prop_get_type_name(enum prop_type type) +{ + switch (type) { + case P_PROMPT: + return "prompt"; + case P_ENV: + return "env"; + case P_COMMENT: + return "comment"; + case P_MENU: + return "menu"; + case P_DEFAULT: + return "default"; + case P_CHOICE: + return "choice"; + case P_SELECT: + return "select"; + case P_RANGE: + return "range"; + case P_SYMBOL: + return "symbol"; + case P_UNKNOWN: + break; + } + return "unknown"; +} + +static void prop_add_env(const char *env) +{ + struct symbol *sym, *sym2; + struct property *prop; + char *p; + + sym = current_entry->sym; + sym->flags |= SYMBOL_AUTO; + for_all_properties(sym, prop, P_ENV) { + sym2 = prop_get_symbol(prop); + if (strcmp(sym2->name, env)) + menu_warn(current_entry, "redefining environment symbol from %s", + sym2->name); + return; + } + + prop = prop_alloc(P_ENV, sym); + prop->expr = expr_alloc_symbol(sym_lookup(env, SYMBOL_CONST)); + + sym_env_list = expr_alloc_one(E_LIST, sym_env_list); + sym_env_list->right.sym = sym; + + p = getenv(env); + if (p) + sym_add_default(sym, p); + else + menu_warn(current_entry, "environment variable %s undefined", env); +} diff --git a/misc/tools/kconfig-frontends/libs/parser/util.c b/misc/tools/kconfig-frontends/libs/parser/util.c new file mode 100644 index 0000000000..d0b8b2318e --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/util.c @@ -0,0 +1,140 @@ +/* + * Copyright (C) 2002-2005 Roman Zippel + * Copyright (C) 2002-2005 Sam Ravnborg + * + * Released under the terms of the GNU GPL v2.0. + */ + +#include +#include +#include +#include "lkc.h" + +/* file already present in list? If not add it */ +struct file *file_lookup(const char *name) +{ + struct file *file; + const char *file_name = sym_expand_string_value(name); + + for (file = file_list; file; file = file->next) { + if (!strcmp(name, file->name)) { + free((void *)file_name); + return file; + } + } + + file = malloc(sizeof(*file)); + memset(file, 0, sizeof(*file)); + file->name = file_name; + file->next = file_list; + file_list = file; + return file; +} + +/* write a dependency file as used by kbuild to track dependencies */ +int file_write_dep(const char *name) +{ + struct symbol *sym, *env_sym; + struct expr *e; + struct file *file; + FILE *out; + + if (!name) + name = ".kconfig.d"; + out = fopen("..config.tmp", "w"); + if (!out) + return 1; + fprintf(out, "deps_config := \\\n"); + for (file = file_list; file; file = file->next) { + if (file->next) + fprintf(out, "\t%s \\\n", file->name); + else + fprintf(out, "\t%s\n", file->name); + } + fprintf(out, "\n%s: \\\n" + "\t$(deps_config)\n\n", conf_get_autoconfig_name()); + + expr_list_for_each_sym(sym_env_list, e, sym) { + struct property *prop; + const char *value; + + prop = sym_get_env_prop(sym); + env_sym = prop_get_symbol(prop); + if (!env_sym) + continue; + value = getenv(env_sym->name); + if (!value) + value = ""; + fprintf(out, "ifneq \"$(%s)\" \"%s\"\n", env_sym->name, value); + fprintf(out, "%s: FORCE\n", conf_get_autoconfig_name()); + fprintf(out, "endif\n"); + } + + fprintf(out, "\n$(deps_config): ;\n"); + fclose(out); + rename("..config.tmp", name); + return 0; +} + + +/* Allocate initial growable string */ +struct gstr str_new(void) +{ + struct gstr gs; + gs.s = malloc(sizeof(char) * 64); + gs.len = 64; + gs.max_width = 0; + strcpy(gs.s, "\0"); + return gs; +} + +/* Allocate and assign growable string */ +struct gstr str_assign(const char *s) +{ + struct gstr gs; + gs.s = strdup(s); + gs.len = strlen(s) + 1; + gs.max_width = 0; + return gs; +} + +/* Free storage for growable string */ +void str_free(struct gstr *gs) +{ + if (gs->s) + free(gs->s); + gs->s = NULL; + gs->len = 0; +} + +/* Append to growable string */ +void str_append(struct gstr *gs, const char *s) +{ + size_t l; + if (s) { + l = strlen(gs->s) + strlen(s) + 1; + if (l > gs->len) { + gs->s = realloc(gs->s, l); + gs->len = l; + } + strcat(gs->s, s); + } +} + +/* Append printf formatted string to growable string */ +void str_printf(struct gstr *gs, const char *fmt, ...) +{ + va_list ap; + char s[10000]; /* big enough... */ + va_start(ap, fmt); + vsnprintf(s, sizeof(s), fmt, ap); + str_append(gs, s); + va_end(ap); +} + +/* Retrieve value of growable string */ +const char *str_get(struct gstr *gs) +{ + return gs->s; +} + diff --git a/misc/tools/kconfig-frontends/libs/parser/yconf.c b/misc/tools/kconfig-frontends/libs/parser/yconf.c new file mode 100644 index 0000000000..b9508f79a0 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/yconf.c @@ -0,0 +1,2531 @@ + +/* A Bison parser, made by GNU Bison 2.4.1. */ + +/* Skeleton implementation for Bison's Yacc-like parsers in C + + Copyright (C) 1984, 1989, 1990, 2000, 2001, 2002, 2003, 2004, 2005, 2006 + Free Software Foundation, Inc. + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . */ + +/* As a special exception, you may create a larger work that contains + part or all of the Bison parser skeleton and distribute that work + under terms of your choice, so long as that work isn't itself a + parser generator using the skeleton or a modified version thereof + as a parser skeleton. Alternatively, if you modify or redistribute + the parser skeleton itself, you may (at your option) remove this + special exception, which will cause the skeleton and the resulting + Bison output files to be licensed under the GNU General Public + License without this special exception. + + This special exception was added by the Free Software Foundation in + version 2.2 of Bison. */ + +/* C LALR(1) parser skeleton written by Richard Stallman, by + simplifying the original so-called "semantic" parser. */ + +/* All symbols defined below should begin with yy or YY, to avoid + infringing on user name space. This should be done even for local + variables, as they might otherwise be expanded by user macros. + There are some unavoidable exceptions within include files to + define necessary library symbols; they are noted "INFRINGES ON + USER NAME SPACE" below. */ + +/* Identify Bison output. */ +#define YYBISON 1 + +/* Bison version. */ +#define YYBISON_VERSION "2.4.1" + +/* Skeleton name. */ +#define YYSKELETON_NAME "yacc.c" + +/* Pure parsers. */ +#define YYPURE 0 + +/* Push parsers. */ +#define YYPUSH 0 + +/* Pull parsers. */ +#define YYPULL 1 + +/* Using locations. */ +#define YYLSP_NEEDED 0 + +/* Substitute the variable and function names. */ +#define yyparse zconfparse +#define yylex zconflex +#define yyerror zconferror +#define yylval zconflval +#define yychar zconfchar +#define yydebug zconfdebug +#define yynerrs zconfnerrs + + +/* Copy the first part of user declarations. */ + + +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#include +#include +#include +#include +#include +#include + +#include "lkc.h" + +#define printd(mask, fmt...) if (cdebug & (mask)) printf(fmt) + +#define PRINTD 0x0001 +#define DEBUG_PARSE 0x0002 + +int cdebug = PRINTD; + +extern int zconflex(void); +static void zconfprint(const char *err, ...); +static void zconf_error(const char *err, ...); +static void zconferror(const char *err); +static bool zconf_endtoken(const struct kconf_id *id, int starttoken, int endtoken); + +struct symbol *symbol_hash[SYMBOL_HASHSIZE]; + +static struct menu *current_menu, *current_entry; + + + + +/* Enabling traces. */ +#ifndef YYDEBUG +# define YYDEBUG 1 +#endif + +/* Enabling verbose error messages. */ +#ifdef YYERROR_VERBOSE +# undef YYERROR_VERBOSE +# define YYERROR_VERBOSE 1 +#else +# define YYERROR_VERBOSE 0 +#endif + +/* Enabling the token table. */ +#ifndef YYTOKEN_TABLE +# define YYTOKEN_TABLE 0 +#endif + + +/* Tokens. */ +#ifndef YYTOKENTYPE +# define YYTOKENTYPE + /* Put the tokens into the symbol table, so that GDB and other debuggers + know about them. */ + enum yytokentype { + T_MAINMENU = 258, + T_MENU = 259, + T_ENDMENU = 260, + T_SOURCE = 261, + T_CHOICE = 262, + T_ENDCHOICE = 263, + T_COMMENT = 264, + T_CONFIG = 265, + T_MENUCONFIG = 266, + T_HELP = 267, + T_HELPTEXT = 268, + T_IF = 269, + T_ENDIF = 270, + T_DEPENDS = 271, + T_OPTIONAL = 272, + T_PROMPT = 273, + T_TYPE = 274, + T_DEFAULT = 275, + T_SELECT = 276, + T_RANGE = 277, + T_VISIBLE = 278, + T_OPTION = 279, + T_ON = 280, + T_WORD = 281, + T_WORD_QUOTE = 282, + T_UNEQUAL = 283, + T_CLOSE_PAREN = 284, + T_OPEN_PAREN = 285, + T_EOL = 286, + T_OR = 287, + T_AND = 288, + T_EQUAL = 289, + T_NOT = 290 + }; +#endif +/* Tokens. */ +#define T_MAINMENU 258 +#define T_MENU 259 +#define T_ENDMENU 260 +#define T_SOURCE 261 +#define T_CHOICE 262 +#define T_ENDCHOICE 263 +#define T_COMMENT 264 +#define T_CONFIG 265 +#define T_MENUCONFIG 266 +#define T_HELP 267 +#define T_HELPTEXT 268 +#define T_IF 269 +#define T_ENDIF 270 +#define T_DEPENDS 271 +#define T_OPTIONAL 272 +#define T_PROMPT 273 +#define T_TYPE 274 +#define T_DEFAULT 275 +#define T_SELECT 276 +#define T_RANGE 277 +#define T_VISIBLE 278 +#define T_OPTION 279 +#define T_ON 280 +#define T_WORD 281 +#define T_WORD_QUOTE 282 +#define T_UNEQUAL 283 +#define T_CLOSE_PAREN 284 +#define T_OPEN_PAREN 285 +#define T_EOL 286 +#define T_OR 287 +#define T_AND 288 +#define T_EQUAL 289 +#define T_NOT 290 + + + + +#if ! defined YYSTYPE && ! defined YYSTYPE_IS_DECLARED +typedef union YYSTYPE +{ + + + char *string; + struct file *file; + struct symbol *symbol; + struct expr *expr; + struct menu *menu; + const struct kconf_id *id; + + + +} YYSTYPE; +# define YYSTYPE_IS_TRIVIAL 1 +# define yystype YYSTYPE /* obsolescent; will be withdrawn */ +# define YYSTYPE_IS_DECLARED 1 +#endif + + +/* Copy the second part of user declarations. */ + + +/* Include zconf.hash.c here so it can see the token constants. */ +#include "hconf.c" + + + +#ifdef short +# undef short +#endif + +#ifdef YYTYPE_UINT8 +typedef YYTYPE_UINT8 yytype_uint8; +#else +typedef unsigned char yytype_uint8; +#endif + +#ifdef YYTYPE_INT8 +typedef YYTYPE_INT8 yytype_int8; +#elif (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +typedef signed char yytype_int8; +#else +typedef short int yytype_int8; +#endif + +#ifdef YYTYPE_UINT16 +typedef YYTYPE_UINT16 yytype_uint16; +#else +typedef unsigned short int yytype_uint16; +#endif + +#ifdef YYTYPE_INT16 +typedef YYTYPE_INT16 yytype_int16; +#else +typedef short int yytype_int16; +#endif + +#ifndef YYSIZE_T +# ifdef __SIZE_TYPE__ +# define YYSIZE_T __SIZE_TYPE__ +# elif defined size_t +# define YYSIZE_T size_t +# elif ! defined YYSIZE_T && (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +# include /* INFRINGES ON USER NAME SPACE */ +# define YYSIZE_T size_t +# else +# define YYSIZE_T unsigned int +# endif +#endif + +#define YYSIZE_MAXIMUM ((YYSIZE_T) -1) + +#ifndef YY_ +# if YYENABLE_NLS +# if ENABLE_NLS +# include /* INFRINGES ON USER NAME SPACE */ +# define YY_(msgid) dgettext ("bison-runtime", msgid) +# endif +# endif +# ifndef YY_ +# define YY_(msgid) msgid +# endif +#endif + +/* Suppress unused-variable warnings by "using" E. */ +#if ! defined lint || defined __GNUC__ +# define YYUSE(e) ((void) (e)) +#else +# define YYUSE(e) /* empty */ +#endif + +/* Identity function, used to suppress warnings about constant conditions. */ +#ifndef lint +# define YYID(n) (n) +#else +#if (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +static int +YYID (int yyi) +#else +static int +YYID (yyi) + int yyi; +#endif +{ + return yyi; +} +#endif + +#if ! defined yyoverflow || YYERROR_VERBOSE + +/* The parser invokes alloca or malloc; define the necessary symbols. */ + +# ifdef YYSTACK_USE_ALLOCA +# if YYSTACK_USE_ALLOCA +# ifdef __GNUC__ +# define YYSTACK_ALLOC __builtin_alloca +# elif defined __BUILTIN_VA_ARG_INCR +# include /* INFRINGES ON USER NAME SPACE */ +# elif defined _AIX +# define YYSTACK_ALLOC __alloca +# elif defined _MSC_VER +# include /* INFRINGES ON USER NAME SPACE */ +# define alloca _alloca +# else +# define YYSTACK_ALLOC alloca +# if ! defined _ALLOCA_H && ! defined _STDLIB_H && (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +# include /* INFRINGES ON USER NAME SPACE */ +# ifndef _STDLIB_H +# define _STDLIB_H 1 +# endif +# endif +# endif +# endif +# endif + +# ifdef YYSTACK_ALLOC + /* Pacify GCC's `empty if-body' warning. */ +# define YYSTACK_FREE(Ptr) do { /* empty */; } while (YYID (0)) +# ifndef YYSTACK_ALLOC_MAXIMUM + /* The OS might guarantee only one guard page at the bottom of the stack, + and a page size can be as small as 4096 bytes. So we cannot safely + invoke alloca (N) if N exceeds 4096. Use a slightly smaller number + to allow for a few compiler-allocated temporary stack slots. */ +# define YYSTACK_ALLOC_MAXIMUM 4032 /* reasonable circa 2006 */ +# endif +# else +# define YYSTACK_ALLOC YYMALLOC +# define YYSTACK_FREE YYFREE +# ifndef YYSTACK_ALLOC_MAXIMUM +# define YYSTACK_ALLOC_MAXIMUM YYSIZE_MAXIMUM +# endif +# if (defined __cplusplus && ! defined _STDLIB_H \ + && ! ((defined YYMALLOC || defined malloc) \ + && (defined YYFREE || defined free))) +# include /* INFRINGES ON USER NAME SPACE */ +# ifndef _STDLIB_H +# define _STDLIB_H 1 +# endif +# endif +# ifndef YYMALLOC +# define YYMALLOC malloc +# if ! defined malloc && ! defined _STDLIB_H && (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +void *malloc (YYSIZE_T); /* INFRINGES ON USER NAME SPACE */ +# endif +# endif +# ifndef YYFREE +# define YYFREE free +# if ! defined free && ! defined _STDLIB_H && (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +void free (void *); /* INFRINGES ON USER NAME SPACE */ +# endif +# endif +# endif +#endif /* ! defined yyoverflow || YYERROR_VERBOSE */ + + +#if (! defined yyoverflow \ + && (! defined __cplusplus \ + || (defined YYSTYPE_IS_TRIVIAL && YYSTYPE_IS_TRIVIAL))) + +/* A type that is properly aligned for any stack member. */ +union yyalloc +{ + yytype_int16 yyss_alloc; + YYSTYPE yyvs_alloc; +}; + +/* The size of the maximum gap between one aligned stack and the next. */ +# define YYSTACK_GAP_MAXIMUM (sizeof (union yyalloc) - 1) + +/* The size of an array large to enough to hold all stacks, each with + N elements. */ +# define YYSTACK_BYTES(N) \ + ((N) * (sizeof (yytype_int16) + sizeof (YYSTYPE)) \ + + YYSTACK_GAP_MAXIMUM) + +/* Copy COUNT objects from FROM to TO. The source and destination do + not overlap. */ +# ifndef YYCOPY +# if defined __GNUC__ && 1 < __GNUC__ +# define YYCOPY(To, From, Count) \ + __builtin_memcpy (To, From, (Count) * sizeof (*(From))) +# else +# define YYCOPY(To, From, Count) \ + do \ + { \ + YYSIZE_T yyi; \ + for (yyi = 0; yyi < (Count); yyi++) \ + (To)[yyi] = (From)[yyi]; \ + } \ + while (YYID (0)) +# endif +# endif + +/* Relocate STACK from its old location to the new one. The + local variables YYSIZE and YYSTACKSIZE give the old and new number of + elements in the stack, and YYPTR gives the new location of the + stack. Advance YYPTR to a properly aligned location for the next + stack. */ +# define YYSTACK_RELOCATE(Stack_alloc, Stack) \ + do \ + { \ + YYSIZE_T yynewbytes; \ + YYCOPY (&yyptr->Stack_alloc, Stack, yysize); \ + Stack = &yyptr->Stack_alloc; \ + yynewbytes = yystacksize * sizeof (*Stack) + YYSTACK_GAP_MAXIMUM; \ + yyptr += yynewbytes / sizeof (*yyptr); \ + } \ + while (YYID (0)) + +#endif + +/* YYFINAL -- State number of the termination state. */ +#define YYFINAL 11 +/* YYLAST -- Last index in YYTABLE. */ +#define YYLAST 290 + +/* YYNTOKENS -- Number of terminals. */ +#define YYNTOKENS 36 +/* YYNNTS -- Number of nonterminals. */ +#define YYNNTS 50 +/* YYNRULES -- Number of rules. */ +#define YYNRULES 118 +/* YYNRULES -- Number of states. */ +#define YYNSTATES 191 + +/* YYTRANSLATE(YYLEX) -- Bison symbol number corresponding to YYLEX. */ +#define YYUNDEFTOK 2 +#define YYMAXUTOK 290 + +#define YYTRANSLATE(YYX) \ + ((unsigned int) (YYX) <= YYMAXUTOK ? yytranslate[YYX] : YYUNDEFTOK) + +/* YYTRANSLATE[YYLEX] -- Bison symbol number corresponding to YYLEX. */ +static const yytype_uint8 yytranslate[] = +{ + 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, + 2, 2, 2, 2, 2, 2, 1, 2, 3, 4, + 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, + 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, + 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, + 35 +}; + +#if YYDEBUG +/* YYPRHS[YYN] -- Index of the first RHS symbol of rule number YYN in + YYRHS. */ +static const yytype_uint16 yyprhs[] = +{ + 0, 0, 3, 6, 8, 11, 13, 14, 17, 20, + 23, 26, 31, 36, 40, 42, 44, 46, 48, 50, + 52, 54, 56, 58, 60, 62, 64, 66, 68, 72, + 75, 79, 82, 86, 89, 90, 93, 96, 99, 102, + 105, 108, 112, 117, 122, 127, 133, 137, 138, 142, + 143, 146, 150, 153, 155, 159, 160, 163, 166, 169, + 172, 175, 180, 184, 187, 192, 193, 196, 200, 202, + 206, 207, 210, 213, 216, 220, 224, 228, 230, 234, + 235, 238, 241, 244, 248, 252, 255, 258, 261, 262, + 265, 268, 271, 276, 277, 280, 283, 286, 287, 290, + 292, 294, 297, 300, 303, 305, 308, 309, 312, 314, + 318, 322, 326, 329, 333, 337, 339, 341, 342 +}; + +/* YYRHS -- A `-1'-separated list of the rules' RHS. */ +static const yytype_int8 yyrhs[] = +{ + 37, 0, -1, 81, 38, -1, 38, -1, 63, 39, + -1, 39, -1, -1, 39, 41, -1, 39, 55, -1, + 39, 67, -1, 39, 80, -1, 39, 26, 1, 31, + -1, 39, 40, 1, 31, -1, 39, 1, 31, -1, + 16, -1, 18, -1, 19, -1, 21, -1, 17, -1, + 22, -1, 20, -1, 23, -1, 31, -1, 61, -1, + 71, -1, 44, -1, 46, -1, 69, -1, 26, 1, + 31, -1, 1, 31, -1, 10, 26, 31, -1, 43, + 47, -1, 11, 26, 31, -1, 45, 47, -1, -1, + 47, 48, -1, 47, 49, -1, 47, 75, -1, 47, + 73, -1, 47, 42, -1, 47, 31, -1, 19, 78, + 31, -1, 18, 79, 82, 31, -1, 20, 83, 82, + 31, -1, 21, 26, 82, 31, -1, 22, 84, 84, + 82, 31, -1, 24, 50, 31, -1, -1, 50, 26, + 51, -1, -1, 34, 79, -1, 7, 85, 31, -1, + 52, 56, -1, 80, -1, 53, 58, 54, -1, -1, + 56, 57, -1, 56, 75, -1, 56, 73, -1, 56, + 31, -1, 56, 42, -1, 18, 79, 82, 31, -1, + 19, 78, 31, -1, 17, 31, -1, 20, 26, 82, + 31, -1, -1, 58, 41, -1, 14, 83, 81, -1, + 80, -1, 59, 62, 60, -1, -1, 62, 41, -1, + 62, 67, -1, 62, 55, -1, 3, 79, 81, -1, + 4, 79, 31, -1, 64, 76, 74, -1, 80, -1, + 65, 68, 66, -1, -1, 68, 41, -1, 68, 67, + -1, 68, 55, -1, 6, 79, 31, -1, 9, 79, + 31, -1, 70, 74, -1, 12, 31, -1, 72, 13, + -1, -1, 74, 75, -1, 74, 31, -1, 74, 42, + -1, 16, 25, 83, 31, -1, -1, 76, 77, -1, + 76, 31, -1, 23, 82, -1, -1, 79, 82, -1, + 26, -1, 27, -1, 5, 31, -1, 8, 31, -1, + 15, 31, -1, 31, -1, 81, 31, -1, -1, 14, + 83, -1, 84, -1, 84, 34, 84, -1, 84, 28, + 84, -1, 30, 83, 29, -1, 35, 83, -1, 83, + 32, 83, -1, 83, 33, 83, -1, 26, -1, 27, + -1, -1, 26, -1 +}; + +/* YYRLINE[YYN] -- source line where rule number YYN was defined. */ +static const yytype_uint16 yyrline[] = +{ + 0, 103, 103, 103, 105, 105, 107, 109, 110, 111, + 112, 113, 114, 118, 122, 122, 122, 122, 122, 122, + 122, 122, 126, 127, 128, 129, 130, 131, 135, 136, + 142, 150, 156, 164, 174, 176, 177, 178, 179, 180, + 181, 184, 192, 198, 208, 214, 220, 223, 225, 236, + 237, 242, 251, 256, 264, 267, 269, 270, 271, 272, + 273, 276, 282, 293, 299, 309, 311, 316, 324, 332, + 335, 337, 338, 339, 344, 351, 358, 363, 371, 374, + 376, 377, 378, 381, 389, 396, 403, 409, 416, 418, + 419, 420, 423, 431, 433, 434, 437, 444, 446, 451, + 452, 455, 456, 457, 461, 462, 465, 466, 469, 470, + 471, 472, 473, 474, 475, 478, 479, 482, 483 +}; +#endif + +#if YYDEBUG || YYERROR_VERBOSE || YYTOKEN_TABLE +/* YYTNAME[SYMBOL-NUM] -- String name of the symbol SYMBOL-NUM. + First, the terminals, then, starting at YYNTOKENS, nonterminals. */ +static const char *const yytname[] = +{ + "$end", "error", "$undefined", "T_MAINMENU", "T_MENU", "T_ENDMENU", + "T_SOURCE", "T_CHOICE", "T_ENDCHOICE", "T_COMMENT", "T_CONFIG", + "T_MENUCONFIG", "T_HELP", "T_HELPTEXT", "T_IF", "T_ENDIF", "T_DEPENDS", + "T_OPTIONAL", "T_PROMPT", "T_TYPE", "T_DEFAULT", "T_SELECT", "T_RANGE", + "T_VISIBLE", "T_OPTION", "T_ON", "T_WORD", "T_WORD_QUOTE", "T_UNEQUAL", + "T_CLOSE_PAREN", "T_OPEN_PAREN", "T_EOL", "T_OR", "T_AND", "T_EQUAL", + "T_NOT", "$accept", "input", "start", "stmt_list", "option_name", + "common_stmt", "option_error", "config_entry_start", "config_stmt", + "menuconfig_entry_start", "menuconfig_stmt", "config_option_list", + "config_option", "symbol_option", "symbol_option_list", + "symbol_option_arg", "choice", "choice_entry", "choice_end", + "choice_stmt", "choice_option_list", "choice_option", "choice_block", + "if_entry", "if_end", "if_stmt", "if_block", "mainmenu_stmt", "menu", + "menu_entry", "menu_end", "menu_stmt", "menu_block", "source_stmt", + "comment", "comment_stmt", "help_start", "help", "depends_list", + "depends", "visibility_list", "visible", "prompt_stmt_opt", "prompt", + "end", "nl", "if_expr", "expr", "symbol", "word_opt", 0 +}; +#endif + +# ifdef YYPRINT +/* YYTOKNUM[YYLEX-NUM] -- Internal token number corresponding to + token YYLEX-NUM. */ +static const yytype_uint16 yytoknum[] = +{ + 0, 256, 257, 258, 259, 260, 261, 262, 263, 264, + 265, 266, 267, 268, 269, 270, 271, 272, 273, 274, + 275, 276, 277, 278, 279, 280, 281, 282, 283, 284, + 285, 286, 287, 288, 289, 290 +}; +# endif + +/* YYR1[YYN] -- Symbol number of symbol that rule YYN derives. */ +static const yytype_uint8 yyr1[] = +{ + 0, 36, 37, 37, 38, 38, 39, 39, 39, 39, + 39, 39, 39, 39, 40, 40, 40, 40, 40, 40, + 40, 40, 41, 41, 41, 41, 41, 41, 42, 42, + 43, 44, 45, 46, 47, 47, 47, 47, 47, 47, + 47, 48, 48, 48, 48, 48, 49, 50, 50, 51, + 51, 52, 53, 54, 55, 56, 56, 56, 56, 56, + 56, 57, 57, 57, 57, 58, 58, 59, 60, 61, + 62, 62, 62, 62, 63, 64, 65, 66, 67, 68, + 68, 68, 68, 69, 70, 71, 72, 73, 74, 74, + 74, 74, 75, 76, 76, 76, 77, 78, 78, 79, + 79, 80, 80, 80, 81, 81, 82, 82, 83, 83, + 83, 83, 83, 83, 83, 84, 84, 85, 85 +}; + +/* YYR2[YYN] -- Number of symbols composing right hand side of rule YYN. */ +static const yytype_uint8 yyr2[] = +{ + 0, 2, 2, 1, 2, 1, 0, 2, 2, 2, + 2, 4, 4, 3, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 3, 2, + 3, 2, 3, 2, 0, 2, 2, 2, 2, 2, + 2, 3, 4, 4, 4, 5, 3, 0, 3, 0, + 2, 3, 2, 1, 3, 0, 2, 2, 2, 2, + 2, 4, 3, 2, 4, 0, 2, 3, 1, 3, + 0, 2, 2, 2, 3, 3, 3, 1, 3, 0, + 2, 2, 2, 3, 3, 2, 2, 2, 0, 2, + 2, 2, 4, 0, 2, 2, 2, 0, 2, 1, + 1, 2, 2, 2, 1, 2, 0, 2, 1, 3, + 3, 3, 2, 3, 3, 1, 1, 0, 1 +}; + +/* YYDEFACT[STATE-NAME] -- Default rule to reduce with in state + STATE-NUM when YYTABLE doesn't specify something else to do. Zero + means the default is an error. */ +static const yytype_uint8 yydefact[] = +{ + 6, 0, 104, 0, 3, 0, 6, 6, 99, 100, + 0, 1, 0, 0, 0, 0, 117, 0, 0, 0, + 0, 0, 0, 14, 18, 15, 16, 20, 17, 19, + 21, 0, 22, 0, 7, 34, 25, 34, 26, 55, + 65, 8, 70, 23, 93, 79, 9, 27, 88, 24, + 10, 0, 105, 2, 74, 13, 0, 101, 0, 118, + 0, 102, 0, 0, 0, 115, 116, 0, 0, 0, + 108, 103, 0, 0, 0, 0, 0, 0, 0, 88, + 0, 0, 75, 83, 51, 84, 30, 32, 0, 112, + 0, 0, 67, 0, 0, 11, 12, 0, 0, 0, + 0, 97, 0, 0, 0, 47, 0, 40, 39, 35, + 36, 0, 38, 37, 0, 0, 97, 0, 59, 60, + 56, 58, 57, 66, 54, 53, 71, 73, 69, 72, + 68, 106, 95, 0, 94, 80, 82, 78, 81, 77, + 90, 91, 89, 111, 113, 114, 110, 109, 29, 86, + 0, 106, 0, 106, 106, 106, 0, 0, 0, 87, + 63, 106, 0, 106, 0, 96, 0, 0, 41, 98, + 0, 0, 106, 49, 46, 28, 0, 62, 0, 107, + 92, 42, 43, 44, 0, 0, 48, 61, 64, 45, + 50 +}; + +/* YYDEFGOTO[NTERM-NUM]. */ +static const yytype_int16 yydefgoto[] = +{ + -1, 3, 4, 5, 33, 34, 108, 35, 36, 37, + 38, 74, 109, 110, 157, 186, 39, 40, 124, 41, + 76, 120, 77, 42, 128, 43, 78, 6, 44, 45, + 137, 46, 80, 47, 48, 49, 111, 112, 81, 113, + 79, 134, 152, 153, 50, 7, 165, 69, 70, 60 +}; + +/* YYPACT[STATE-NUM] -- Index in YYTABLE of the portion describing + STATE-NUM. */ +#define YYPACT_NINF -90 +static const yytype_int16 yypact[] = +{ + 4, 42, -90, 96, -90, 111, -90, 15, -90, -90, + 75, -90, 82, 42, 104, 42, 110, 107, 42, 115, + 125, -4, 121, -90, -90, -90, -90, -90, -90, -90, + -90, 162, -90, 163, -90, -90, -90, -90, -90, -90, + -90, -90, -90, -90, -90, -90, -90, -90, -90, -90, + -90, 139, -90, -90, 138, -90, 142, -90, 143, -90, + 152, -90, 164, 167, 168, -90, -90, -4, -4, 77, + -18, -90, 177, 185, 33, 71, 195, 247, 236, -2, + 236, 171, -90, -90, -90, -90, -90, -90, 41, -90, + -4, -4, 138, 97, 97, -90, -90, 186, 187, 194, + 42, 42, -4, 196, 97, -90, 219, -90, -90, -90, + -90, 210, -90, -90, 204, 42, 42, 199, -90, -90, + -90, -90, -90, -90, -90, -90, -90, -90, -90, -90, + -90, 222, -90, 223, -90, -90, -90, -90, -90, -90, + -90, -90, -90, -90, 215, -90, -90, -90, -90, -90, + -4, 222, 228, 222, -5, 222, 97, 35, 229, -90, + -90, 222, 232, 222, -4, -90, 135, 233, -90, -90, + 234, 235, 222, 240, -90, -90, 237, -90, 239, -13, + -90, -90, -90, -90, 244, 42, -90, -90, -90, -90, + -90 +}; + +/* YYPGOTO[NTERM-NUM]. */ +static const yytype_int16 yypgoto[] = +{ + -90, -90, 269, 271, -90, 23, -70, -90, -90, -90, + -90, 243, -90, -90, -90, -90, -90, -90, -90, -48, + -90, -90, -90, -90, -90, -90, -90, -90, -90, -90, + -90, -20, -90, -90, -90, -90, -90, 206, 205, -68, + -90, -90, 169, -1, 27, -7, 118, -66, -89, -90 +}; + +/* YYTABLE[YYPACT[STATE-NUM]]. What to do in state STATE-NUM. If + positive, shift that token. If negative, reduce the rule which + number is the opposite. If zero, do what YYDEFACT says. + If YYTABLE_NINF, syntax error. */ +#define YYTABLE_NINF -86 +static const yytype_int16 yytable[] = +{ + 10, 88, 89, 54, 146, 147, 119, 1, 122, 164, + 93, 141, 56, 142, 58, 156, 94, 62, 1, 90, + 91, 131, 65, 66, 144, 145, 67, 90, 91, 132, + 127, 68, 136, -31, 97, 2, 154, -31, -31, -31, + -31, -31, -31, -31, -31, 98, 52, -31, -31, 99, + -31, 100, 101, 102, 103, 104, -31, 105, 129, 106, + 138, 173, 92, 141, 107, 142, 174, 172, 8, 9, + 143, -33, 97, 90, 91, -33, -33, -33, -33, -33, + -33, -33, -33, 98, 166, -33, -33, 99, -33, 100, + 101, 102, 103, 104, -33, 105, 11, 106, 179, 151, + 123, 126, 107, 135, 125, 130, 2, 139, 2, 90, + 91, -5, 12, 55, 161, 13, 14, 15, 16, 17, + 18, 19, 20, 65, 66, 21, 22, 23, 24, 25, + 26, 27, 28, 29, 30, 57, 59, 31, 61, -4, + 12, 63, 32, 13, 14, 15, 16, 17, 18, 19, + 20, 64, 71, 21, 22, 23, 24, 25, 26, 27, + 28, 29, 30, 72, 73, 31, 180, 90, 91, 52, + 32, -85, 97, 82, 83, -85, -85, -85, -85, -85, + -85, -85, -85, 84, 190, -85, -85, 99, -85, -85, + -85, -85, -85, -85, -85, 85, 97, 106, 86, 87, + -52, -52, 140, -52, -52, -52, -52, 98, 95, -52, + -52, 99, 114, 115, 116, 117, 96, 148, 149, 150, + 158, 106, 155, 159, 97, 163, 118, -76, -76, -76, + -76, -76, -76, -76, -76, 160, 164, -76, -76, 99, + 13, 14, 15, 16, 17, 18, 19, 20, 91, 106, + 21, 22, 14, 15, 140, 17, 18, 19, 20, 168, + 175, 21, 22, 177, 181, 182, 183, 32, 187, 167, + 188, 169, 170, 171, 185, 189, 53, 51, 32, 176, + 75, 178, 121, 0, 133, 162, 0, 0, 0, 0, + 184 +}; + +static const yytype_int16 yycheck[] = +{ + 1, 67, 68, 10, 93, 94, 76, 3, 76, 14, + 28, 81, 13, 81, 15, 104, 34, 18, 3, 32, + 33, 23, 26, 27, 90, 91, 30, 32, 33, 31, + 78, 35, 80, 0, 1, 31, 102, 4, 5, 6, + 7, 8, 9, 10, 11, 12, 31, 14, 15, 16, + 17, 18, 19, 20, 21, 22, 23, 24, 78, 26, + 80, 26, 69, 133, 31, 133, 31, 156, 26, 27, + 29, 0, 1, 32, 33, 4, 5, 6, 7, 8, + 9, 10, 11, 12, 150, 14, 15, 16, 17, 18, + 19, 20, 21, 22, 23, 24, 0, 26, 164, 100, + 77, 78, 31, 80, 77, 78, 31, 80, 31, 32, + 33, 0, 1, 31, 115, 4, 5, 6, 7, 8, + 9, 10, 11, 26, 27, 14, 15, 16, 17, 18, + 19, 20, 21, 22, 23, 31, 26, 26, 31, 0, + 1, 26, 31, 4, 5, 6, 7, 8, 9, 10, + 11, 26, 31, 14, 15, 16, 17, 18, 19, 20, + 21, 22, 23, 1, 1, 26, 31, 32, 33, 31, + 31, 0, 1, 31, 31, 4, 5, 6, 7, 8, + 9, 10, 11, 31, 185, 14, 15, 16, 17, 18, + 19, 20, 21, 22, 23, 31, 1, 26, 31, 31, + 5, 6, 31, 8, 9, 10, 11, 12, 31, 14, + 15, 16, 17, 18, 19, 20, 31, 31, 31, 25, + 1, 26, 26, 13, 1, 26, 31, 4, 5, 6, + 7, 8, 9, 10, 11, 31, 14, 14, 15, 16, + 4, 5, 6, 7, 8, 9, 10, 11, 33, 26, + 14, 15, 5, 6, 31, 8, 9, 10, 11, 31, + 31, 14, 15, 31, 31, 31, 31, 31, 31, 151, + 31, 153, 154, 155, 34, 31, 7, 6, 31, 161, + 37, 163, 76, -1, 79, 116, -1, -1, -1, -1, + 172 +}; + +/* YYSTOS[STATE-NUM] -- The (internal number of the) accessing + symbol of state STATE-NUM. */ +static const yytype_uint8 yystos[] = +{ + 0, 3, 31, 37, 38, 39, 63, 81, 26, 27, + 79, 0, 1, 4, 5, 6, 7, 8, 9, 10, + 11, 14, 15, 16, 17, 18, 19, 20, 21, 22, + 23, 26, 31, 40, 41, 43, 44, 45, 46, 52, + 53, 55, 59, 61, 64, 65, 67, 69, 70, 71, + 80, 39, 31, 38, 81, 31, 79, 31, 79, 26, + 85, 31, 79, 26, 26, 26, 27, 30, 35, 83, + 84, 31, 1, 1, 47, 47, 56, 58, 62, 76, + 68, 74, 31, 31, 31, 31, 31, 31, 83, 83, + 32, 33, 81, 28, 34, 31, 31, 1, 12, 16, + 18, 19, 20, 21, 22, 24, 26, 31, 42, 48, + 49, 72, 73, 75, 17, 18, 19, 20, 31, 42, + 57, 73, 75, 41, 54, 80, 41, 55, 60, 67, + 80, 23, 31, 74, 77, 41, 55, 66, 67, 80, + 31, 42, 75, 29, 83, 83, 84, 84, 31, 31, + 25, 79, 78, 79, 83, 26, 84, 50, 1, 13, + 31, 79, 78, 26, 14, 82, 83, 82, 31, 82, + 82, 82, 84, 26, 31, 31, 82, 31, 82, 83, + 31, 31, 31, 31, 82, 34, 51, 31, 31, 31, + 79 +}; + +#define yyerrok (yyerrstatus = 0) +#define yyclearin (yychar = YYEMPTY) +#define YYEMPTY (-2) +#define YYEOF 0 + +#define YYACCEPT goto yyacceptlab +#define YYABORT goto yyabortlab +#define YYERROR goto yyerrorlab + + +/* Like YYERROR except do call yyerror. This remains here temporarily + to ease the transition to the new meaning of YYERROR, for GCC. + Once GCC version 2 has supplanted version 1, this can go. */ + +#define YYFAIL goto yyerrlab + +#define YYRECOVERING() (!!yyerrstatus) + +#define YYBACKUP(Token, Value) \ +do \ + if (yychar == YYEMPTY && yylen == 1) \ + { \ + yychar = (Token); \ + yylval = (Value); \ + yytoken = YYTRANSLATE (yychar); \ + YYPOPSTACK (1); \ + goto yybackup; \ + } \ + else \ + { \ + yyerror (YY_("syntax error: cannot back up")); \ + YYERROR; \ + } \ +while (YYID (0)) + + +#define YYTERROR 1 +#define YYERRCODE 256 + + +/* YYLLOC_DEFAULT -- Set CURRENT to span from RHS[1] to RHS[N]. + If N is 0, then set CURRENT to the empty location which ends + the previous symbol: RHS[0] (always defined). */ + +#define YYRHSLOC(Rhs, K) ((Rhs)[K]) +#ifndef YYLLOC_DEFAULT +# define YYLLOC_DEFAULT(Current, Rhs, N) \ + do \ + if (YYID (N)) \ + { \ + (Current).first_line = YYRHSLOC (Rhs, 1).first_line; \ + (Current).first_column = YYRHSLOC (Rhs, 1).first_column; \ + (Current).last_line = YYRHSLOC (Rhs, N).last_line; \ + (Current).last_column = YYRHSLOC (Rhs, N).last_column; \ + } \ + else \ + { \ + (Current).first_line = (Current).last_line = \ + YYRHSLOC (Rhs, 0).last_line; \ + (Current).first_column = (Current).last_column = \ + YYRHSLOC (Rhs, 0).last_column; \ + } \ + while (YYID (0)) +#endif + + +/* YY_LOCATION_PRINT -- Print the location on the stream. + This macro was not mandated originally: define only if we know + we won't break user code: when these are the locations we know. */ + +#ifndef YY_LOCATION_PRINT +# if YYLTYPE_IS_TRIVIAL +# define YY_LOCATION_PRINT(File, Loc) \ + fprintf (File, "%d.%d-%d.%d", \ + (Loc).first_line, (Loc).first_column, \ + (Loc).last_line, (Loc).last_column) +# else +# define YY_LOCATION_PRINT(File, Loc) ((void) 0) +# endif +#endif + + +/* YYLEX -- calling `yylex' with the right arguments. */ + +#ifdef YYLEX_PARAM +# define YYLEX yylex (YYLEX_PARAM) +#else +# define YYLEX yylex () +#endif + +/* Enable debugging if requested. */ +#if YYDEBUG + +# ifndef YYFPRINTF +# include /* INFRINGES ON USER NAME SPACE */ +# define YYFPRINTF fprintf +# endif + +# define YYDPRINTF(Args) \ +do { \ + if (yydebug) \ + YYFPRINTF Args; \ +} while (YYID (0)) + +# define YY_SYMBOL_PRINT(Title, Type, Value, Location) \ +do { \ + if (yydebug) \ + { \ + YYFPRINTF (stderr, "%s ", Title); \ + yy_symbol_print (stderr, \ + Type, Value); \ + YYFPRINTF (stderr, "\n"); \ + } \ +} while (YYID (0)) + + +/*--------------------------------. +| Print this symbol on YYOUTPUT. | +`--------------------------------*/ + +/*ARGSUSED*/ +#if (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +static void +yy_symbol_value_print (FILE *yyoutput, int yytype, YYSTYPE const * const yyvaluep) +#else +static void +yy_symbol_value_print (yyoutput, yytype, yyvaluep) + FILE *yyoutput; + int yytype; + YYSTYPE const * const yyvaluep; +#endif +{ + if (!yyvaluep) + return; +# ifdef YYPRINT + if (yytype < YYNTOKENS) + YYPRINT (yyoutput, yytoknum[yytype], *yyvaluep); +# else + YYUSE (yyoutput); +# endif + switch (yytype) + { + default: + break; + } +} + + +/*--------------------------------. +| Print this symbol on YYOUTPUT. | +`--------------------------------*/ + +#if (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +static void +yy_symbol_print (FILE *yyoutput, int yytype, YYSTYPE const * const yyvaluep) +#else +static void +yy_symbol_print (yyoutput, yytype, yyvaluep) + FILE *yyoutput; + int yytype; + YYSTYPE const * const yyvaluep; +#endif +{ + if (yytype < YYNTOKENS) + YYFPRINTF (yyoutput, "token %s (", yytname[yytype]); + else + YYFPRINTF (yyoutput, "nterm %s (", yytname[yytype]); + + yy_symbol_value_print (yyoutput, yytype, yyvaluep); + YYFPRINTF (yyoutput, ")"); +} + +/*------------------------------------------------------------------. +| yy_stack_print -- Print the state stack from its BOTTOM up to its | +| TOP (included). | +`------------------------------------------------------------------*/ + +#if (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +static void +yy_stack_print (yytype_int16 *yybottom, yytype_int16 *yytop) +#else +static void +yy_stack_print (yybottom, yytop) + yytype_int16 *yybottom; + yytype_int16 *yytop; +#endif +{ + YYFPRINTF (stderr, "Stack now"); + for (; yybottom <= yytop; yybottom++) + { + int yybot = *yybottom; + YYFPRINTF (stderr, " %d", yybot); + } + YYFPRINTF (stderr, "\n"); +} + +# define YY_STACK_PRINT(Bottom, Top) \ +do { \ + if (yydebug) \ + yy_stack_print ((Bottom), (Top)); \ +} while (YYID (0)) + + +/*------------------------------------------------. +| Report that the YYRULE is going to be reduced. | +`------------------------------------------------*/ + +#if (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +static void +yy_reduce_print (YYSTYPE *yyvsp, int yyrule) +#else +static void +yy_reduce_print (yyvsp, yyrule) + YYSTYPE *yyvsp; + int yyrule; +#endif +{ + int yynrhs = yyr2[yyrule]; + int yyi; + unsigned long int yylno = yyrline[yyrule]; + YYFPRINTF (stderr, "Reducing stack by rule %d (line %lu):\n", + yyrule - 1, yylno); + /* The symbols being reduced. */ + for (yyi = 0; yyi < yynrhs; yyi++) + { + YYFPRINTF (stderr, " $%d = ", yyi + 1); + yy_symbol_print (stderr, yyrhs[yyprhs[yyrule] + yyi], + &(yyvsp[(yyi + 1) - (yynrhs)]) + ); + YYFPRINTF (stderr, "\n"); + } +} + +# define YY_REDUCE_PRINT(Rule) \ +do { \ + if (yydebug) \ + yy_reduce_print (yyvsp, Rule); \ +} while (YYID (0)) + +/* Nonzero means print parse trace. It is left uninitialized so that + multiple parsers can coexist. */ +int yydebug; +#else /* !YYDEBUG */ +# define YYDPRINTF(Args) +# define YY_SYMBOL_PRINT(Title, Type, Value, Location) +# define YY_STACK_PRINT(Bottom, Top) +# define YY_REDUCE_PRINT(Rule) +#endif /* !YYDEBUG */ + + +/* YYINITDEPTH -- initial size of the parser's stacks. */ +#ifndef YYINITDEPTH +# define YYINITDEPTH 200 +#endif + +/* YYMAXDEPTH -- maximum size the stacks can grow to (effective only + if the built-in stack extension method is used). + + Do not make this value too large; the results are undefined if + YYSTACK_ALLOC_MAXIMUM < YYSTACK_BYTES (YYMAXDEPTH) + evaluated with infinite-precision integer arithmetic. */ + +#ifndef YYMAXDEPTH +# define YYMAXDEPTH 10000 +#endif + + + +#if YYERROR_VERBOSE + +# ifndef yystrlen +# if defined __GLIBC__ && defined _STRING_H +# define yystrlen strlen +# else +/* Return the length of YYSTR. */ +#if (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +static YYSIZE_T +yystrlen (const char *yystr) +#else +static YYSIZE_T +yystrlen (yystr) + const char *yystr; +#endif +{ + YYSIZE_T yylen; + for (yylen = 0; yystr[yylen]; yylen++) + continue; + return yylen; +} +# endif +# endif + +# ifndef yystpcpy +# if defined __GLIBC__ && defined _STRING_H && defined _GNU_SOURCE +# define yystpcpy stpcpy +# else +/* Copy YYSRC to YYDEST, returning the address of the terminating '\0' in + YYDEST. */ +#if (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +static char * +yystpcpy (char *yydest, const char *yysrc) +#else +static char * +yystpcpy (yydest, yysrc) + char *yydest; + const char *yysrc; +#endif +{ + char *yyd = yydest; + const char *yys = yysrc; + + while ((*yyd++ = *yys++) != '\0') + continue; + + return yyd - 1; +} +# endif +# endif + +# ifndef yytnamerr +/* Copy to YYRES the contents of YYSTR after stripping away unnecessary + quotes and backslashes, so that it's suitable for yyerror. The + heuristic is that double-quoting is unnecessary unless the string + contains an apostrophe, a comma, or backslash (other than + backslash-backslash). YYSTR is taken from yytname. If YYRES is + null, do not copy; instead, return the length of what the result + would have been. */ +static YYSIZE_T +yytnamerr (char *yyres, const char *yystr) +{ + if (*yystr == '"') + { + YYSIZE_T yyn = 0; + char const *yyp = yystr; + + for (;;) + switch (*++yyp) + { + case '\'': + case ',': + goto do_not_strip_quotes; + + case '\\': + if (*++yyp != '\\') + goto do_not_strip_quotes; + /* Fall through. */ + default: + if (yyres) + yyres[yyn] = *yyp; + yyn++; + break; + + case '"': + if (yyres) + yyres[yyn] = '\0'; + return yyn; + } + do_not_strip_quotes: ; + } + + if (! yyres) + return yystrlen (yystr); + + return yystpcpy (yyres, yystr) - yyres; +} +# endif + +/* Copy into YYRESULT an error message about the unexpected token + YYCHAR while in state YYSTATE. Return the number of bytes copied, + including the terminating null byte. If YYRESULT is null, do not + copy anything; just return the number of bytes that would be + copied. As a special case, return 0 if an ordinary "syntax error" + message will do. Return YYSIZE_MAXIMUM if overflow occurs during + size calculation. */ +static YYSIZE_T +yysyntax_error (char *yyresult, int yystate, int yychar) +{ + int yyn = yypact[yystate]; + + if (! (YYPACT_NINF < yyn && yyn <= YYLAST)) + return 0; + else + { + int yytype = YYTRANSLATE (yychar); + YYSIZE_T yysize0 = yytnamerr (0, yytname[yytype]); + YYSIZE_T yysize = yysize0; + YYSIZE_T yysize1; + int yysize_overflow = 0; + enum { YYERROR_VERBOSE_ARGS_MAXIMUM = 5 }; + char const *yyarg[YYERROR_VERBOSE_ARGS_MAXIMUM]; + int yyx; + +# if 0 + /* This is so xgettext sees the translatable formats that are + constructed on the fly. */ + YY_("syntax error, unexpected %s"); + YY_("syntax error, unexpected %s, expecting %s"); + YY_("syntax error, unexpected %s, expecting %s or %s"); + YY_("syntax error, unexpected %s, expecting %s or %s or %s"); + YY_("syntax error, unexpected %s, expecting %s or %s or %s or %s"); +# endif + char *yyfmt; + char const *yyf; + static char const yyunexpected[] = "syntax error, unexpected %s"; + static char const yyexpecting[] = ", expecting %s"; + static char const yyor[] = " or %s"; + char yyformat[sizeof yyunexpected + + sizeof yyexpecting - 1 + + ((YYERROR_VERBOSE_ARGS_MAXIMUM - 2) + * (sizeof yyor - 1))]; + char const *yyprefix = yyexpecting; + + /* Start YYX at -YYN if negative to avoid negative indexes in + YYCHECK. */ + int yyxbegin = yyn < 0 ? -yyn : 0; + + /* Stay within bounds of both yycheck and yytname. */ + int yychecklim = YYLAST - yyn + 1; + int yyxend = yychecklim < YYNTOKENS ? yychecklim : YYNTOKENS; + int yycount = 1; + + yyarg[0] = yytname[yytype]; + yyfmt = yystpcpy (yyformat, yyunexpected); + + for (yyx = yyxbegin; yyx < yyxend; ++yyx) + if (yycheck[yyx + yyn] == yyx && yyx != YYTERROR) + { + if (yycount == YYERROR_VERBOSE_ARGS_MAXIMUM) + { + yycount = 1; + yysize = yysize0; + yyformat[sizeof yyunexpected - 1] = '\0'; + break; + } + yyarg[yycount++] = yytname[yyx]; + yysize1 = yysize + yytnamerr (0, yytname[yyx]); + yysize_overflow |= (yysize1 < yysize); + yysize = yysize1; + yyfmt = yystpcpy (yyfmt, yyprefix); + yyprefix = yyor; + } + + yyf = YY_(yyformat); + yysize1 = yysize + yystrlen (yyf); + yysize_overflow |= (yysize1 < yysize); + yysize = yysize1; + + if (yysize_overflow) + return YYSIZE_MAXIMUM; + + if (yyresult) + { + /* Avoid sprintf, as that infringes on the user's name space. + Don't have undefined behavior even if the translation + produced a string with the wrong number of "%s"s. */ + char *yyp = yyresult; + int yyi = 0; + while ((*yyp = *yyf) != '\0') + { + if (*yyp == '%' && yyf[1] == 's' && yyi < yycount) + { + yyp += yytnamerr (yyp, yyarg[yyi++]); + yyf += 2; + } + else + { + yyp++; + yyf++; + } + } + } + return yysize; + } +} +#endif /* YYERROR_VERBOSE */ + + +/*-----------------------------------------------. +| Release the memory associated to this symbol. | +`-----------------------------------------------*/ + +/*ARGSUSED*/ +#if (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +static void +yydestruct (const char *yymsg, int yytype, YYSTYPE *yyvaluep) +#else +static void +yydestruct (yymsg, yytype, yyvaluep) + const char *yymsg; + int yytype; + YYSTYPE *yyvaluep; +#endif +{ + YYUSE (yyvaluep); + + if (!yymsg) + yymsg = "Deleting"; + YY_SYMBOL_PRINT (yymsg, yytype, yyvaluep, yylocationp); + + switch (yytype) + { + case 53: /* "choice_entry" */ + + { + fprintf(stderr, "%s:%d: missing end statement for this entry\n", + (yyvaluep->menu)->file->name, (yyvaluep->menu)->lineno); + if (current_menu == (yyvaluep->menu)) + menu_end_menu(); +}; + + break; + case 59: /* "if_entry" */ + + { + fprintf(stderr, "%s:%d: missing end statement for this entry\n", + (yyvaluep->menu)->file->name, (yyvaluep->menu)->lineno); + if (current_menu == (yyvaluep->menu)) + menu_end_menu(); +}; + + break; + case 65: /* "menu_entry" */ + + { + fprintf(stderr, "%s:%d: missing end statement for this entry\n", + (yyvaluep->menu)->file->name, (yyvaluep->menu)->lineno); + if (current_menu == (yyvaluep->menu)) + menu_end_menu(); +}; + + break; + + default: + break; + } +} + +/* Prevent warnings from -Wmissing-prototypes. */ +#ifdef YYPARSE_PARAM +#if defined __STDC__ || defined __cplusplus +int yyparse (void *YYPARSE_PARAM); +#else +int yyparse (); +#endif +#else /* ! YYPARSE_PARAM */ +#if defined __STDC__ || defined __cplusplus +int yyparse (void); +#else +int yyparse (); +#endif +#endif /* ! YYPARSE_PARAM */ + + +/* The lookahead symbol. */ +int yychar; + +/* The semantic value of the lookahead symbol. */ +YYSTYPE yylval; + +/* Number of syntax errors so far. */ +int yynerrs; + + + +/*-------------------------. +| yyparse or yypush_parse. | +`-------------------------*/ + +#ifdef YYPARSE_PARAM +#if (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +int +yyparse (void *YYPARSE_PARAM) +#else +int +yyparse (YYPARSE_PARAM) + void *YYPARSE_PARAM; +#endif +#else /* ! YYPARSE_PARAM */ +#if (defined __STDC__ || defined __C99__FUNC__ \ + || defined __cplusplus || defined _MSC_VER) +int +yyparse (void) +#else +int +yyparse () + +#endif +#endif +{ + + + int yystate; + /* Number of tokens to shift before error messages enabled. */ + int yyerrstatus; + + /* The stacks and their tools: + `yyss': related to states. + `yyvs': related to semantic values. + + Refer to the stacks thru separate pointers, to allow yyoverflow + to reallocate them elsewhere. */ + + /* The state stack. */ + yytype_int16 yyssa[YYINITDEPTH]; + yytype_int16 *yyss; + yytype_int16 *yyssp; + + /* The semantic value stack. */ + YYSTYPE yyvsa[YYINITDEPTH]; + YYSTYPE *yyvs; + YYSTYPE *yyvsp; + + YYSIZE_T yystacksize; + + int yyn; + int yyresult; + /* Lookahead token as an internal (translated) token number. */ + int yytoken; + /* The variables used to return semantic value and location from the + action routines. */ + YYSTYPE yyval; + +#if YYERROR_VERBOSE + /* Buffer for error messages, and its allocated size. */ + char yymsgbuf[128]; + char *yymsg = yymsgbuf; + YYSIZE_T yymsg_alloc = sizeof yymsgbuf; +#endif + +#define YYPOPSTACK(N) (yyvsp -= (N), yyssp -= (N)) + + /* The number of symbols on the RHS of the reduced rule. + Keep to zero when no symbol should be popped. */ + int yylen = 0; + + yytoken = 0; + yyss = yyssa; + yyvs = yyvsa; + yystacksize = YYINITDEPTH; + + YYDPRINTF ((stderr, "Starting parse\n")); + + yystate = 0; + yyerrstatus = 0; + yynerrs = 0; + yychar = YYEMPTY; /* Cause a token to be read. */ + + /* Initialize stack pointers. + Waste one element of value and location stack + so that they stay on the same level as the state stack. + The wasted elements are never initialized. */ + yyssp = yyss; + yyvsp = yyvs; + + goto yysetstate; + +/*------------------------------------------------------------. +| yynewstate -- Push a new state, which is found in yystate. | +`------------------------------------------------------------*/ + yynewstate: + /* In all cases, when you get here, the value and location stacks + have just been pushed. So pushing a state here evens the stacks. */ + yyssp++; + + yysetstate: + *yyssp = yystate; + + if (yyss + yystacksize - 1 <= yyssp) + { + /* Get the current used size of the three stacks, in elements. */ + YYSIZE_T yysize = yyssp - yyss + 1; + +#ifdef yyoverflow + { + /* Give user a chance to reallocate the stack. Use copies of + these so that the &'s don't force the real ones into + memory. */ + YYSTYPE *yyvs1 = yyvs; + yytype_int16 *yyss1 = yyss; + + /* Each stack pointer address is followed by the size of the + data in use in that stack, in bytes. This used to be a + conditional around just the two extra args, but that might + be undefined if yyoverflow is a macro. */ + yyoverflow (YY_("memory exhausted"), + &yyss1, yysize * sizeof (*yyssp), + &yyvs1, yysize * sizeof (*yyvsp), + &yystacksize); + + yyss = yyss1; + yyvs = yyvs1; + } +#else /* no yyoverflow */ +# ifndef YYSTACK_RELOCATE + goto yyexhaustedlab; +# else + /* Extend the stack our own way. */ + if (YYMAXDEPTH <= yystacksize) + goto yyexhaustedlab; + yystacksize *= 2; + if (YYMAXDEPTH < yystacksize) + yystacksize = YYMAXDEPTH; + + { + yytype_int16 *yyss1 = yyss; + union yyalloc *yyptr = + (union yyalloc *) YYSTACK_ALLOC (YYSTACK_BYTES (yystacksize)); + if (! yyptr) + goto yyexhaustedlab; + YYSTACK_RELOCATE (yyss_alloc, yyss); + YYSTACK_RELOCATE (yyvs_alloc, yyvs); +# undef YYSTACK_RELOCATE + if (yyss1 != yyssa) + YYSTACK_FREE (yyss1); + } +# endif +#endif /* no yyoverflow */ + + yyssp = yyss + yysize - 1; + yyvsp = yyvs + yysize - 1; + + YYDPRINTF ((stderr, "Stack size increased to %lu\n", + (unsigned long int) yystacksize)); + + if (yyss + yystacksize - 1 <= yyssp) + YYABORT; + } + + YYDPRINTF ((stderr, "Entering state %d\n", yystate)); + + if (yystate == YYFINAL) + YYACCEPT; + + goto yybackup; + +/*-----------. +| yybackup. | +`-----------*/ +yybackup: + + /* Do appropriate processing given the current state. Read a + lookahead token if we need one and don't already have one. */ + + /* First try to decide what to do without reference to lookahead token. */ + yyn = yypact[yystate]; + if (yyn == YYPACT_NINF) + goto yydefault; + + /* Not known => get a lookahead token if don't already have one. */ + + /* YYCHAR is either YYEMPTY or YYEOF or a valid lookahead symbol. */ + if (yychar == YYEMPTY) + { + YYDPRINTF ((stderr, "Reading a token: ")); + yychar = YYLEX; + } + + if (yychar <= YYEOF) + { + yychar = yytoken = YYEOF; + YYDPRINTF ((stderr, "Now at end of input.\n")); + } + else + { + yytoken = YYTRANSLATE (yychar); + YY_SYMBOL_PRINT ("Next token is", yytoken, &yylval, &yylloc); + } + + /* If the proper action on seeing token YYTOKEN is to reduce or to + detect an error, take that action. */ + yyn += yytoken; + if (yyn < 0 || YYLAST < yyn || yycheck[yyn] != yytoken) + goto yydefault; + yyn = yytable[yyn]; + if (yyn <= 0) + { + if (yyn == 0 || yyn == YYTABLE_NINF) + goto yyerrlab; + yyn = -yyn; + goto yyreduce; + } + + /* Count tokens shifted since error; after three, turn off error + status. */ + if (yyerrstatus) + yyerrstatus--; + + /* Shift the lookahead token. */ + YY_SYMBOL_PRINT ("Shifting", yytoken, &yylval, &yylloc); + + /* Discard the shifted token. */ + yychar = YYEMPTY; + + yystate = yyn; + *++yyvsp = yylval; + + goto yynewstate; + + +/*-----------------------------------------------------------. +| yydefault -- do the default action for the current state. | +`-----------------------------------------------------------*/ +yydefault: + yyn = yydefact[yystate]; + if (yyn == 0) + goto yyerrlab; + goto yyreduce; + + +/*-----------------------------. +| yyreduce -- Do a reduction. | +`-----------------------------*/ +yyreduce: + /* yyn is the number of a rule to reduce with. */ + yylen = yyr2[yyn]; + + /* If YYLEN is nonzero, implement the default value of the action: + `$$ = $1'. + + Otherwise, the following line sets YYVAL to garbage. + This behavior is undocumented and Bison + users should not rely upon it. Assigning to YYVAL + unconditionally makes the parser a bit smaller, and it avoids a + GCC warning that YYVAL may be used uninitialized. */ + yyval = yyvsp[1-yylen]; + + + YY_REDUCE_PRINT (yyn); + switch (yyn) + { + case 10: + + { zconf_error("unexpected end statement"); } + break; + + case 11: + + { zconf_error("unknown statement \"%s\"", (yyvsp[(2) - (4)].string)); } + break; + + case 12: + + { + zconf_error("unexpected option \"%s\"", kconf_id_strings + (yyvsp[(2) - (4)].id)->name); +} + break; + + case 13: + + { zconf_error("invalid statement"); } + break; + + case 28: + + { zconf_error("unknown option \"%s\"", (yyvsp[(1) - (3)].string)); } + break; + + case 29: + + { zconf_error("invalid option"); } + break; + + case 30: + + { + struct symbol *sym = sym_lookup((yyvsp[(2) - (3)].string), 0); + sym->flags |= SYMBOL_OPTIONAL; + menu_add_entry(sym); + printd(DEBUG_PARSE, "%s:%d:config %s\n", zconf_curname(), zconf_lineno(), (yyvsp[(2) - (3)].string)); +} + break; + + case 31: + + { + menu_end_entry(); + printd(DEBUG_PARSE, "%s:%d:endconfig\n", zconf_curname(), zconf_lineno()); +} + break; + + case 32: + + { + struct symbol *sym = sym_lookup((yyvsp[(2) - (3)].string), 0); + sym->flags |= SYMBOL_OPTIONAL; + menu_add_entry(sym); + printd(DEBUG_PARSE, "%s:%d:menuconfig %s\n", zconf_curname(), zconf_lineno(), (yyvsp[(2) - (3)].string)); +} + break; + + case 33: + + { + if (current_entry->prompt) + current_entry->prompt->type = P_MENU; + else + zconfprint("warning: menuconfig statement without prompt"); + menu_end_entry(); + printd(DEBUG_PARSE, "%s:%d:endconfig\n", zconf_curname(), zconf_lineno()); +} + break; + + case 41: + + { + menu_set_type((yyvsp[(1) - (3)].id)->stype); + printd(DEBUG_PARSE, "%s:%d:type(%u)\n", + zconf_curname(), zconf_lineno(), + (yyvsp[(1) - (3)].id)->stype); +} + break; + + case 42: + + { + menu_add_prompt(P_PROMPT, (yyvsp[(2) - (4)].string), (yyvsp[(3) - (4)].expr)); + printd(DEBUG_PARSE, "%s:%d:prompt\n", zconf_curname(), zconf_lineno()); +} + break; + + case 43: + + { + menu_add_expr(P_DEFAULT, (yyvsp[(2) - (4)].expr), (yyvsp[(3) - (4)].expr)); + if ((yyvsp[(1) - (4)].id)->stype != S_UNKNOWN) + menu_set_type((yyvsp[(1) - (4)].id)->stype); + printd(DEBUG_PARSE, "%s:%d:default(%u)\n", + zconf_curname(), zconf_lineno(), + (yyvsp[(1) - (4)].id)->stype); +} + break; + + case 44: + + { + menu_add_symbol(P_SELECT, sym_lookup((yyvsp[(2) - (4)].string), 0), (yyvsp[(3) - (4)].expr)); + printd(DEBUG_PARSE, "%s:%d:select\n", zconf_curname(), zconf_lineno()); +} + break; + + case 45: + + { + menu_add_expr(P_RANGE, expr_alloc_comp(E_RANGE,(yyvsp[(2) - (5)].symbol), (yyvsp[(3) - (5)].symbol)), (yyvsp[(4) - (5)].expr)); + printd(DEBUG_PARSE, "%s:%d:range\n", zconf_curname(), zconf_lineno()); +} + break; + + case 48: + + { + const struct kconf_id *id = kconf_id_lookup((yyvsp[(2) - (3)].string), strlen((yyvsp[(2) - (3)].string))); + if (id && id->flags & TF_OPTION) + menu_add_option(id->token, (yyvsp[(3) - (3)].string)); + else + zconfprint("warning: ignoring unknown option %s", (yyvsp[(2) - (3)].string)); + free((yyvsp[(2) - (3)].string)); +} + break; + + case 49: + + { (yyval.string) = NULL; } + break; + + case 50: + + { (yyval.string) = (yyvsp[(2) - (2)].string); } + break; + + case 51: + + { + struct symbol *sym = sym_lookup((yyvsp[(2) - (3)].string), SYMBOL_CHOICE); + sym->flags |= SYMBOL_AUTO; + menu_add_entry(sym); + menu_add_expr(P_CHOICE, NULL, NULL); + printd(DEBUG_PARSE, "%s:%d:choice\n", zconf_curname(), zconf_lineno()); +} + break; + + case 52: + + { + (yyval.menu) = menu_add_menu(); +} + break; + + case 53: + + { + if (zconf_endtoken((yyvsp[(1) - (1)].id), T_CHOICE, T_ENDCHOICE)) { + menu_end_menu(); + printd(DEBUG_PARSE, "%s:%d:endchoice\n", zconf_curname(), zconf_lineno()); + } +} + break; + + case 61: + + { + menu_add_prompt(P_PROMPT, (yyvsp[(2) - (4)].string), (yyvsp[(3) - (4)].expr)); + printd(DEBUG_PARSE, "%s:%d:prompt\n", zconf_curname(), zconf_lineno()); +} + break; + + case 62: + + { + if ((yyvsp[(1) - (3)].id)->stype == S_BOOLEAN || (yyvsp[(1) - (3)].id)->stype == S_TRISTATE) { + menu_set_type((yyvsp[(1) - (3)].id)->stype); + printd(DEBUG_PARSE, "%s:%d:type(%u)\n", + zconf_curname(), zconf_lineno(), + (yyvsp[(1) - (3)].id)->stype); + } else + YYERROR; +} + break; + + case 63: + + { + current_entry->sym->flags |= SYMBOL_OPTIONAL; + printd(DEBUG_PARSE, "%s:%d:optional\n", zconf_curname(), zconf_lineno()); +} + break; + + case 64: + + { + if ((yyvsp[(1) - (4)].id)->stype == S_UNKNOWN) { + menu_add_symbol(P_DEFAULT, sym_lookup((yyvsp[(2) - (4)].string), 0), (yyvsp[(3) - (4)].expr)); + printd(DEBUG_PARSE, "%s:%d:default\n", + zconf_curname(), zconf_lineno()); + } else + YYERROR; +} + break; + + case 67: + + { + printd(DEBUG_PARSE, "%s:%d:if\n", zconf_curname(), zconf_lineno()); + menu_add_entry(NULL); + menu_add_dep((yyvsp[(2) - (3)].expr)); + (yyval.menu) = menu_add_menu(); +} + break; + + case 68: + + { + if (zconf_endtoken((yyvsp[(1) - (1)].id), T_IF, T_ENDIF)) { + menu_end_menu(); + printd(DEBUG_PARSE, "%s:%d:endif\n", zconf_curname(), zconf_lineno()); + } +} + break; + + case 74: + + { + menu_add_prompt(P_MENU, (yyvsp[(2) - (3)].string), NULL); +} + break; + + case 75: + + { + menu_add_entry(NULL); + menu_add_prompt(P_MENU, (yyvsp[(2) - (3)].string), NULL); + printd(DEBUG_PARSE, "%s:%d:menu\n", zconf_curname(), zconf_lineno()); +} + break; + + case 76: + + { + (yyval.menu) = menu_add_menu(); +} + break; + + case 77: + + { + if (zconf_endtoken((yyvsp[(1) - (1)].id), T_MENU, T_ENDMENU)) { + menu_end_menu(); + printd(DEBUG_PARSE, "%s:%d:endmenu\n", zconf_curname(), zconf_lineno()); + } +} + break; + + case 83: + + { + printd(DEBUG_PARSE, "%s:%d:source %s\n", zconf_curname(), zconf_lineno(), (yyvsp[(2) - (3)].string)); + zconf_nextfile((yyvsp[(2) - (3)].string)); +} + break; + + case 84: + + { + menu_add_entry(NULL); + menu_add_prompt(P_COMMENT, (yyvsp[(2) - (3)].string), NULL); + printd(DEBUG_PARSE, "%s:%d:comment\n", zconf_curname(), zconf_lineno()); +} + break; + + case 85: + + { + menu_end_entry(); +} + break; + + case 86: + + { + printd(DEBUG_PARSE, "%s:%d:help\n", zconf_curname(), zconf_lineno()); + zconf_starthelp(); +} + break; + + case 87: + + { + current_entry->help = (yyvsp[(2) - (2)].string); +} + break; + + case 92: + + { + menu_add_dep((yyvsp[(3) - (4)].expr)); + printd(DEBUG_PARSE, "%s:%d:depends on\n", zconf_curname(), zconf_lineno()); +} + break; + + case 96: + + { + menu_add_visibility((yyvsp[(2) - (2)].expr)); +} + break; + + case 98: + + { + menu_add_prompt(P_PROMPT, (yyvsp[(1) - (2)].string), (yyvsp[(2) - (2)].expr)); +} + break; + + case 101: + + { (yyval.id) = (yyvsp[(1) - (2)].id); } + break; + + case 102: + + { (yyval.id) = (yyvsp[(1) - (2)].id); } + break; + + case 103: + + { (yyval.id) = (yyvsp[(1) - (2)].id); } + break; + + case 106: + + { (yyval.expr) = NULL; } + break; + + case 107: + + { (yyval.expr) = (yyvsp[(2) - (2)].expr); } + break; + + case 108: + + { (yyval.expr) = expr_alloc_symbol((yyvsp[(1) - (1)].symbol)); } + break; + + case 109: + + { (yyval.expr) = expr_alloc_comp(E_EQUAL, (yyvsp[(1) - (3)].symbol), (yyvsp[(3) - (3)].symbol)); } + break; + + case 110: + + { (yyval.expr) = expr_alloc_comp(E_UNEQUAL, (yyvsp[(1) - (3)].symbol), (yyvsp[(3) - (3)].symbol)); } + break; + + case 111: + + { (yyval.expr) = (yyvsp[(2) - (3)].expr); } + break; + + case 112: + + { (yyval.expr) = expr_alloc_one(E_NOT, (yyvsp[(2) - (2)].expr)); } + break; + + case 113: + + { (yyval.expr) = expr_alloc_two(E_OR, (yyvsp[(1) - (3)].expr), (yyvsp[(3) - (3)].expr)); } + break; + + case 114: + + { (yyval.expr) = expr_alloc_two(E_AND, (yyvsp[(1) - (3)].expr), (yyvsp[(3) - (3)].expr)); } + break; + + case 115: + + { (yyval.symbol) = sym_lookup((yyvsp[(1) - (1)].string), 0); free((yyvsp[(1) - (1)].string)); } + break; + + case 116: + + { (yyval.symbol) = sym_lookup((yyvsp[(1) - (1)].string), SYMBOL_CONST); free((yyvsp[(1) - (1)].string)); } + break; + + case 117: + + { (yyval.string) = NULL; } + break; + + + + default: break; + } + YY_SYMBOL_PRINT ("-> $$ =", yyr1[yyn], &yyval, &yyloc); + + YYPOPSTACK (yylen); + yylen = 0; + YY_STACK_PRINT (yyss, yyssp); + + *++yyvsp = yyval; + + /* Now `shift' the result of the reduction. Determine what state + that goes to, based on the state we popped back to and the rule + number reduced by. */ + + yyn = yyr1[yyn]; + + yystate = yypgoto[yyn - YYNTOKENS] + *yyssp; + if (0 <= yystate && yystate <= YYLAST && yycheck[yystate] == *yyssp) + yystate = yytable[yystate]; + else + yystate = yydefgoto[yyn - YYNTOKENS]; + + goto yynewstate; + + +/*------------------------------------. +| yyerrlab -- here on detecting error | +`------------------------------------*/ +yyerrlab: + /* If not already recovering from an error, report this error. */ + if (!yyerrstatus) + { + ++yynerrs; +#if ! YYERROR_VERBOSE + yyerror (YY_("syntax error")); +#else + { + YYSIZE_T yysize = yysyntax_error (0, yystate, yychar); + if (yymsg_alloc < yysize && yymsg_alloc < YYSTACK_ALLOC_MAXIMUM) + { + YYSIZE_T yyalloc = 2 * yysize; + if (! (yysize <= yyalloc && yyalloc <= YYSTACK_ALLOC_MAXIMUM)) + yyalloc = YYSTACK_ALLOC_MAXIMUM; + if (yymsg != yymsgbuf) + YYSTACK_FREE (yymsg); + yymsg = (char *) YYSTACK_ALLOC (yyalloc); + if (yymsg) + yymsg_alloc = yyalloc; + else + { + yymsg = yymsgbuf; + yymsg_alloc = sizeof yymsgbuf; + } + } + + if (0 < yysize && yysize <= yymsg_alloc) + { + (void) yysyntax_error (yymsg, yystate, yychar); + yyerror (yymsg); + } + else + { + yyerror (YY_("syntax error")); + if (yysize != 0) + goto yyexhaustedlab; + } + } +#endif + } + + + + if (yyerrstatus == 3) + { + /* If just tried and failed to reuse lookahead token after an + error, discard it. */ + + if (yychar <= YYEOF) + { + /* Return failure if at end of input. */ + if (yychar == YYEOF) + YYABORT; + } + else + { + yydestruct ("Error: discarding", + yytoken, &yylval); + yychar = YYEMPTY; + } + } + + /* Else will try to reuse lookahead token after shifting the error + token. */ + goto yyerrlab1; + + +/*---------------------------------------------------. +| yyerrorlab -- error raised explicitly by YYERROR. | +`---------------------------------------------------*/ +yyerrorlab: + + /* Pacify compilers like GCC when the user code never invokes + YYERROR and the label yyerrorlab therefore never appears in user + code. */ + if (/*CONSTCOND*/ 0) + goto yyerrorlab; + + /* Do not reclaim the symbols of the rule which action triggered + this YYERROR. */ + YYPOPSTACK (yylen); + yylen = 0; + YY_STACK_PRINT (yyss, yyssp); + yystate = *yyssp; + goto yyerrlab1; + + +/*-------------------------------------------------------------. +| yyerrlab1 -- common code for both syntax error and YYERROR. | +`-------------------------------------------------------------*/ +yyerrlab1: + yyerrstatus = 3; /* Each real token shifted decrements this. */ + + for (;;) + { + yyn = yypact[yystate]; + if (yyn != YYPACT_NINF) + { + yyn += YYTERROR; + if (0 <= yyn && yyn <= YYLAST && yycheck[yyn] == YYTERROR) + { + yyn = yytable[yyn]; + if (0 < yyn) + break; + } + } + + /* Pop the current state because it cannot handle the error token. */ + if (yyssp == yyss) + YYABORT; + + + yydestruct ("Error: popping", + yystos[yystate], yyvsp); + YYPOPSTACK (1); + yystate = *yyssp; + YY_STACK_PRINT (yyss, yyssp); + } + + *++yyvsp = yylval; + + + /* Shift the error token. */ + YY_SYMBOL_PRINT ("Shifting", yystos[yyn], yyvsp, yylsp); + + yystate = yyn; + goto yynewstate; + + +/*-------------------------------------. +| yyacceptlab -- YYACCEPT comes here. | +`-------------------------------------*/ +yyacceptlab: + yyresult = 0; + goto yyreturn; + +/*-----------------------------------. +| yyabortlab -- YYABORT comes here. | +`-----------------------------------*/ +yyabortlab: + yyresult = 1; + goto yyreturn; + +#if !defined(yyoverflow) || YYERROR_VERBOSE +/*-------------------------------------------------. +| yyexhaustedlab -- memory exhaustion comes here. | +`-------------------------------------------------*/ +yyexhaustedlab: + yyerror (YY_("memory exhausted")); + yyresult = 2; + /* Fall through. */ +#endif + +yyreturn: + if (yychar != YYEMPTY) + yydestruct ("Cleanup: discarding lookahead", + yytoken, &yylval); + /* Do not reclaim the symbols of the rule which action triggered + this YYABORT or YYACCEPT. */ + YYPOPSTACK (yylen); + YY_STACK_PRINT (yyss, yyssp); + while (yyssp != yyss) + { + yydestruct ("Cleanup: popping", + yystos[*yyssp], yyvsp); + YYPOPSTACK (1); + } +#ifndef yyoverflow + if (yyss != yyssa) + YYSTACK_FREE (yyss); +#endif +#if YYERROR_VERBOSE + if (yymsg != yymsgbuf) + YYSTACK_FREE (yymsg); +#endif + /* Make sure YYID is used. */ + return YYID (yyresult); +} + + + + + +void conf_parse(const char *name) +{ + struct symbol *sym; + int i; + + zconf_initscan(name); + + sym_init(); + _menu_init(); + modules_sym = sym_lookup(NULL, 0); + modules_sym->type = S_BOOLEAN; + modules_sym->flags |= SYMBOL_AUTO; + rootmenu.prompt = menu_add_prompt(P_MENU, ROOTMENU, NULL); + + if (getenv("ZCONF_DEBUG")) + zconfdebug = 1; + zconfparse(); + if (zconfnerrs) + exit(1); + if (!modules_sym->prop) { + struct property *prop; + + prop = prop_alloc(P_DEFAULT, modules_sym); + prop->expr = expr_alloc_symbol(sym_lookup("MODULES", 0)); + } + + rootmenu.prompt->text = _(rootmenu.prompt->text); + rootmenu.prompt->text = sym_expand_string_value(rootmenu.prompt->text); + + menu_finalize(&rootmenu); + for_all_symbols(i, sym) { + if (sym_check_deps(sym)) + zconfnerrs++; + } + if (zconfnerrs) + exit(1); + sym_set_change_count(1); +} + +static const char *zconf_tokenname(int token) +{ + switch (token) { + case T_MENU: return "menu"; + case T_ENDMENU: return "endmenu"; + case T_CHOICE: return "choice"; + case T_ENDCHOICE: return "endchoice"; + case T_IF: return "if"; + case T_ENDIF: return "endif"; + case T_DEPENDS: return "depends"; + case T_VISIBLE: return "visible"; + } + return ""; +} + +static bool zconf_endtoken(const struct kconf_id *id, int starttoken, int endtoken) +{ + if (id->token != endtoken) { + zconf_error("unexpected '%s' within %s block", + kconf_id_strings + id->name, zconf_tokenname(starttoken)); + zconfnerrs++; + return false; + } + if (current_menu->file != current_file) { + zconf_error("'%s' in different file than '%s'", + kconf_id_strings + id->name, zconf_tokenname(starttoken)); + fprintf(stderr, "%s:%d: location of the '%s'\n", + current_menu->file->name, current_menu->lineno, + zconf_tokenname(starttoken)); + zconfnerrs++; + return false; + } + return true; +} + +static void zconfprint(const char *err, ...) +{ + va_list ap; + + fprintf(stderr, "%s:%d: ", zconf_curname(), zconf_lineno()); + va_start(ap, err); + vfprintf(stderr, err, ap); + va_end(ap); + fprintf(stderr, "\n"); +} + +static void zconf_error(const char *err, ...) +{ + va_list ap; + + zconfnerrs++; + fprintf(stderr, "%s:%d: ", zconf_curname(), zconf_lineno()); + va_start(ap, err); + vfprintf(stderr, err, ap); + va_end(ap); + fprintf(stderr, "\n"); +} + +static void zconferror(const char *err) +{ + fprintf(stderr, "%s:%d: %s\n", zconf_curname(), zconf_lineno() + 1, err); +} + +static void print_quoted_string(FILE *out, const char *str) +{ + const char *p; + int len; + + putc('"', out); + while ((p = strchr(str, '"'))) { + len = p - str; + if (len) + fprintf(out, "%.*s", len, str); + fputs("\\\"", out); + str = p + 1; + } + fputs(str, out); + putc('"', out); +} + +static void print_symbol(FILE *out, struct menu *menu) +{ + struct symbol *sym = menu->sym; + struct property *prop; + + if (sym_is_choice(sym)) + fprintf(out, "\nchoice\n"); + else + fprintf(out, "\nconfig %s\n", sym->name); + switch (sym->type) { + case S_BOOLEAN: + fputs(" boolean\n", out); + break; + case S_TRISTATE: + fputs(" tristate\n", out); + break; + case S_STRING: + fputs(" string\n", out); + break; + case S_INT: + fputs(" integer\n", out); + break; + case S_HEX: + fputs(" hex\n", out); + break; + default: + fputs(" ???\n", out); + break; + } + for (prop = sym->prop; prop; prop = prop->next) { + if (prop->menu != menu) + continue; + switch (prop->type) { + case P_PROMPT: + fputs(" prompt ", out); + print_quoted_string(out, prop->text); + if (!expr_is_yes(prop->visible.expr)) { + fputs(" if ", out); + expr_fprint(prop->visible.expr, out); + } + fputc('\n', out); + break; + case P_DEFAULT: + fputs( " default ", out); + expr_fprint(prop->expr, out); + if (!expr_is_yes(prop->visible.expr)) { + fputs(" if ", out); + expr_fprint(prop->visible.expr, out); + } + fputc('\n', out); + break; + case P_CHOICE: + fputs(" #choice value\n", out); + break; + case P_SELECT: + fputs( " select ", out); + expr_fprint(prop->expr, out); + fputc('\n', out); + break; + case P_RANGE: + fputs( " range ", out); + expr_fprint(prop->expr, out); + fputc('\n', out); + break; + case P_MENU: + fputs( " menu ", out); + print_quoted_string(out, prop->text); + fputc('\n', out); + break; + default: + fprintf(out, " unknown prop %d!\n", prop->type); + break; + } + } + if (menu->help) { + int len = strlen(menu->help); + while (menu->help[--len] == '\n') + menu->help[len] = 0; + fprintf(out, " help\n%s\n", menu->help); + } +} + +void zconfdump(FILE *out) +{ + struct property *prop; + struct symbol *sym; + struct menu *menu; + + menu = rootmenu.list; + while (menu) { + if ((sym = menu->sym)) + print_symbol(out, menu); + else if ((prop = menu->prompt)) { + switch (prop->type) { + case P_COMMENT: + fputs("\ncomment ", out); + print_quoted_string(out, prop->text); + fputs("\n", out); + break; + case P_MENU: + fputs("\nmenu ", out); + print_quoted_string(out, prop->text); + fputs("\n", out); + break; + default: + ; + } + if (!expr_is_yes(prop->visible.expr)) { + fputs(" depends ", out); + expr_fprint(prop->visible.expr, out); + fputc('\n', out); + } + } + + if (menu->list) + menu = menu->list; + else if (menu->next) + menu = menu->next; + else while ((menu = menu->parent)) { + if (menu->prompt && menu->prompt->type == P_MENU) + fputs("\nendmenu\n", out); + if (menu->next) { + menu = menu->next; + break; + } + } + } +} + +#include "lconf.c" +#include "util.c" +#include "confdata.c" +#include "expr.c" +#include "symbol.c" +#include "menu.c" + diff --git a/misc/tools/kconfig-frontends/libs/parser/yconf.y b/misc/tools/kconfig-frontends/libs/parser/yconf.y new file mode 100644 index 0000000000..093ec1ac27 --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/yconf.y @@ -0,0 +1,740 @@ +%{ +/* + * Copyright (C) 2002 Roman Zippel + * Released under the terms of the GNU GPL v2.0. + */ + +#include +#include +#include +#include +#include +#include + +#include "lkc.h" + +#define printd(mask, fmt...) if (cdebug & (mask)) printf(fmt) + +#define PRINTD 0x0001 +#define DEBUG_PARSE 0x0002 + +int cdebug = PRINTD; + +extern int zconflex(void); +static void zconfprint(const char *err, ...); +static void zconf_error(const char *err, ...); +static void zconferror(const char *err); +static bool zconf_endtoken(const struct kconf_id *id, int starttoken, int endtoken); + +struct symbol *symbol_hash[SYMBOL_HASHSIZE]; + +static struct menu *current_menu, *current_entry; + +%} +%expect 30 + +%union +{ + char *string; + struct file *file; + struct symbol *symbol; + struct expr *expr; + struct menu *menu; + const struct kconf_id *id; +} + +%token T_MAINMENU +%token T_MENU +%token T_ENDMENU +%token T_SOURCE +%token T_CHOICE +%token T_ENDCHOICE +%token T_COMMENT +%token T_CONFIG +%token T_MENUCONFIG +%token T_HELP +%token T_HELPTEXT +%token T_IF +%token T_ENDIF +%token T_DEPENDS +%token T_OPTIONAL +%token T_PROMPT +%token T_TYPE +%token T_DEFAULT +%token T_SELECT +%token T_RANGE +%token T_VISIBLE +%token T_OPTION +%token T_ON +%token T_WORD +%token T_WORD_QUOTE +%token T_UNEQUAL +%token T_CLOSE_PAREN +%token T_OPEN_PAREN +%token T_EOL + +%left T_OR +%left T_AND +%left T_EQUAL T_UNEQUAL +%nonassoc T_NOT + +%type prompt +%type symbol +%type expr +%type if_expr +%type end +%type option_name +%type if_entry menu_entry choice_entry +%type symbol_option_arg word_opt + +%destructor { + fprintf(stderr, "%s:%d: missing end statement for this entry\n", + $$->file->name, $$->lineno); + if (current_menu == $$) + menu_end_menu(); +} if_entry menu_entry choice_entry + +%{ +/* Include zconf.hash.c here so it can see the token constants. */ +#include "hconf.c" +%} + +%% +input: nl start | start; + +start: mainmenu_stmt stmt_list | stmt_list; + +stmt_list: + /* empty */ + | stmt_list common_stmt + | stmt_list choice_stmt + | stmt_list menu_stmt + | stmt_list end { zconf_error("unexpected end statement"); } + | stmt_list T_WORD error T_EOL { zconf_error("unknown statement \"%s\"", $2); } + | stmt_list option_name error T_EOL +{ + zconf_error("unexpected option \"%s\"", kconf_id_strings + $2->name); +} + | stmt_list error T_EOL { zconf_error("invalid statement"); } +; + +option_name: + T_DEPENDS | T_PROMPT | T_TYPE | T_SELECT | T_OPTIONAL | T_RANGE | T_DEFAULT | T_VISIBLE +; + +common_stmt: + T_EOL + | if_stmt + | comment_stmt + | config_stmt + | menuconfig_stmt + | source_stmt +; + +option_error: + T_WORD error T_EOL { zconf_error("unknown option \"%s\"", $1); } + | error T_EOL { zconf_error("invalid option"); } +; + + +/* config/menuconfig entry */ + +config_entry_start: T_CONFIG T_WORD T_EOL +{ + struct symbol *sym = sym_lookup($2, 0); + sym->flags |= SYMBOL_OPTIONAL; + menu_add_entry(sym); + printd(DEBUG_PARSE, "%s:%d:config %s\n", zconf_curname(), zconf_lineno(), $2); +}; + +config_stmt: config_entry_start config_option_list +{ + menu_end_entry(); + printd(DEBUG_PARSE, "%s:%d:endconfig\n", zconf_curname(), zconf_lineno()); +}; + +menuconfig_entry_start: T_MENUCONFIG T_WORD T_EOL +{ + struct symbol *sym = sym_lookup($2, 0); + sym->flags |= SYMBOL_OPTIONAL; + menu_add_entry(sym); + printd(DEBUG_PARSE, "%s:%d:menuconfig %s\n", zconf_curname(), zconf_lineno(), $2); +}; + +menuconfig_stmt: menuconfig_entry_start config_option_list +{ + if (current_entry->prompt) + current_entry->prompt->type = P_MENU; + else + zconfprint("warning: menuconfig statement without prompt"); + menu_end_entry(); + printd(DEBUG_PARSE, "%s:%d:endconfig\n", zconf_curname(), zconf_lineno()); +}; + +config_option_list: + /* empty */ + | config_option_list config_option + | config_option_list symbol_option + | config_option_list depends + | config_option_list help + | config_option_list option_error + | config_option_list T_EOL +; + +config_option: T_TYPE prompt_stmt_opt T_EOL +{ + menu_set_type($1->stype); + printd(DEBUG_PARSE, "%s:%d:type(%u)\n", + zconf_curname(), zconf_lineno(), + $1->stype); +}; + +config_option: T_PROMPT prompt if_expr T_EOL +{ + menu_add_prompt(P_PROMPT, $2, $3); + printd(DEBUG_PARSE, "%s:%d:prompt\n", zconf_curname(), zconf_lineno()); +}; + +config_option: T_DEFAULT expr if_expr T_EOL +{ + menu_add_expr(P_DEFAULT, $2, $3); + if ($1->stype != S_UNKNOWN) + menu_set_type($1->stype); + printd(DEBUG_PARSE, "%s:%d:default(%u)\n", + zconf_curname(), zconf_lineno(), + $1->stype); +}; + +config_option: T_SELECT T_WORD if_expr T_EOL +{ + menu_add_symbol(P_SELECT, sym_lookup($2, 0), $3); + printd(DEBUG_PARSE, "%s:%d:select\n", zconf_curname(), zconf_lineno()); +}; + +config_option: T_RANGE symbol symbol if_expr T_EOL +{ + menu_add_expr(P_RANGE, expr_alloc_comp(E_RANGE,$2, $3), $4); + printd(DEBUG_PARSE, "%s:%d:range\n", zconf_curname(), zconf_lineno()); +}; + +symbol_option: T_OPTION symbol_option_list T_EOL +; + +symbol_option_list: + /* empty */ + | symbol_option_list T_WORD symbol_option_arg +{ + const struct kconf_id *id = kconf_id_lookup($2, strlen($2)); + if (id && id->flags & TF_OPTION) + menu_add_option(id->token, $3); + else + zconfprint("warning: ignoring unknown option %s", $2); + free($2); +}; + +symbol_option_arg: + /* empty */ { $$ = NULL; } + | T_EQUAL prompt { $$ = $2; } +; + +/* choice entry */ + +choice: T_CHOICE word_opt T_EOL +{ + struct symbol *sym = sym_lookup($2, SYMBOL_CHOICE); + sym->flags |= SYMBOL_AUTO; + menu_add_entry(sym); + menu_add_expr(P_CHOICE, NULL, NULL); + printd(DEBUG_PARSE, "%s:%d:choice\n", zconf_curname(), zconf_lineno()); +}; + +choice_entry: choice choice_option_list +{ + $$ = menu_add_menu(); +}; + +choice_end: end +{ + if (zconf_endtoken($1, T_CHOICE, T_ENDCHOICE)) { + menu_end_menu(); + printd(DEBUG_PARSE, "%s:%d:endchoice\n", zconf_curname(), zconf_lineno()); + } +}; + +choice_stmt: choice_entry choice_block choice_end +; + +choice_option_list: + /* empty */ + | choice_option_list choice_option + | choice_option_list depends + | choice_option_list help + | choice_option_list T_EOL + | choice_option_list option_error +; + +choice_option: T_PROMPT prompt if_expr T_EOL +{ + menu_add_prompt(P_PROMPT, $2, $3); + printd(DEBUG_PARSE, "%s:%d:prompt\n", zconf_curname(), zconf_lineno()); +}; + +choice_option: T_TYPE prompt_stmt_opt T_EOL +{ + if ($1->stype == S_BOOLEAN || $1->stype == S_TRISTATE) { + menu_set_type($1->stype); + printd(DEBUG_PARSE, "%s:%d:type(%u)\n", + zconf_curname(), zconf_lineno(), + $1->stype); + } else + YYERROR; +}; + +choice_option: T_OPTIONAL T_EOL +{ + current_entry->sym->flags |= SYMBOL_OPTIONAL; + printd(DEBUG_PARSE, "%s:%d:optional\n", zconf_curname(), zconf_lineno()); +}; + +choice_option: T_DEFAULT T_WORD if_expr T_EOL +{ + if ($1->stype == S_UNKNOWN) { + menu_add_symbol(P_DEFAULT, sym_lookup($2, 0), $3); + printd(DEBUG_PARSE, "%s:%d:default\n", + zconf_curname(), zconf_lineno()); + } else + YYERROR; +}; + +choice_block: + /* empty */ + | choice_block common_stmt +; + +/* if entry */ + +if_entry: T_IF expr nl +{ + printd(DEBUG_PARSE, "%s:%d:if\n", zconf_curname(), zconf_lineno()); + menu_add_entry(NULL); + menu_add_dep($2); + $$ = menu_add_menu(); +}; + +if_end: end +{ + if (zconf_endtoken($1, T_IF, T_ENDIF)) { + menu_end_menu(); + printd(DEBUG_PARSE, "%s:%d:endif\n", zconf_curname(), zconf_lineno()); + } +}; + +if_stmt: if_entry if_block if_end +; + +if_block: + /* empty */ + | if_block common_stmt + | if_block menu_stmt + | if_block choice_stmt +; + +/* mainmenu entry */ + +mainmenu_stmt: T_MAINMENU prompt nl +{ + menu_add_prompt(P_MENU, $2, NULL); +}; + +/* menu entry */ + +menu: T_MENU prompt T_EOL +{ + menu_add_entry(NULL); + menu_add_prompt(P_MENU, $2, NULL); + printd(DEBUG_PARSE, "%s:%d:menu\n", zconf_curname(), zconf_lineno()); +}; + +menu_entry: menu visibility_list depends_list +{ + $$ = menu_add_menu(); +}; + +menu_end: end +{ + if (zconf_endtoken($1, T_MENU, T_ENDMENU)) { + menu_end_menu(); + printd(DEBUG_PARSE, "%s:%d:endmenu\n", zconf_curname(), zconf_lineno()); + } +}; + +menu_stmt: menu_entry menu_block menu_end +; + +menu_block: + /* empty */ + | menu_block common_stmt + | menu_block menu_stmt + | menu_block choice_stmt +; + +source_stmt: T_SOURCE prompt T_EOL +{ + printd(DEBUG_PARSE, "%s:%d:source %s\n", zconf_curname(), zconf_lineno(), $2); + zconf_nextfile($2); +}; + +/* comment entry */ + +comment: T_COMMENT prompt T_EOL +{ + menu_add_entry(NULL); + menu_add_prompt(P_COMMENT, $2, NULL); + printd(DEBUG_PARSE, "%s:%d:comment\n", zconf_curname(), zconf_lineno()); +}; + +comment_stmt: comment depends_list +{ + menu_end_entry(); +}; + +/* help option */ + +help_start: T_HELP T_EOL +{ + printd(DEBUG_PARSE, "%s:%d:help\n", zconf_curname(), zconf_lineno()); + zconf_starthelp(); +}; + +help: help_start T_HELPTEXT +{ + current_entry->help = $2; +}; + +/* depends option */ + +depends_list: + /* empty */ + | depends_list depends + | depends_list T_EOL + | depends_list option_error +; + +depends: T_DEPENDS T_ON expr T_EOL +{ + menu_add_dep($3); + printd(DEBUG_PARSE, "%s:%d:depends on\n", zconf_curname(), zconf_lineno()); +}; + +/* visibility option */ + +visibility_list: + /* empty */ + | visibility_list visible + | visibility_list T_EOL +; + +visible: T_VISIBLE if_expr +{ + menu_add_visibility($2); +}; + +/* prompt statement */ + +prompt_stmt_opt: + /* empty */ + | prompt if_expr +{ + menu_add_prompt(P_PROMPT, $1, $2); +}; + +prompt: T_WORD + | T_WORD_QUOTE +; + +end: T_ENDMENU T_EOL { $$ = $1; } + | T_ENDCHOICE T_EOL { $$ = $1; } + | T_ENDIF T_EOL { $$ = $1; } +; + +nl: + T_EOL + | nl T_EOL +; + +if_expr: /* empty */ { $$ = NULL; } + | T_IF expr { $$ = $2; } +; + +expr: symbol { $$ = expr_alloc_symbol($1); } + | symbol T_EQUAL symbol { $$ = expr_alloc_comp(E_EQUAL, $1, $3); } + | symbol T_UNEQUAL symbol { $$ = expr_alloc_comp(E_UNEQUAL, $1, $3); } + | T_OPEN_PAREN expr T_CLOSE_PAREN { $$ = $2; } + | T_NOT expr { $$ = expr_alloc_one(E_NOT, $2); } + | expr T_OR expr { $$ = expr_alloc_two(E_OR, $1, $3); } + | expr T_AND expr { $$ = expr_alloc_two(E_AND, $1, $3); } +; + +symbol: T_WORD { $$ = sym_lookup($1, 0); free($1); } + | T_WORD_QUOTE { $$ = sym_lookup($1, SYMBOL_CONST); free($1); } +; + +word_opt: /* empty */ { $$ = NULL; } + | T_WORD + +%% + +void conf_parse(const char *name) +{ + struct symbol *sym; + int i; + + zconf_initscan(name); + + sym_init(); + _menu_init(); + modules_sym = sym_lookup(NULL, 0); + modules_sym->type = S_BOOLEAN; + modules_sym->flags |= SYMBOL_AUTO; + rootmenu.prompt = menu_add_prompt(P_MENU, ROOTMENU, NULL); + + if (getenv("ZCONF_DEBUG")) + zconfdebug = 1; + zconfparse(); + if (zconfnerrs) + exit(1); + if (!modules_sym->prop) { + struct property *prop; + + prop = prop_alloc(P_DEFAULT, modules_sym); + prop->expr = expr_alloc_symbol(sym_lookup("MODULES", 0)); + } + + rootmenu.prompt->text = _(rootmenu.prompt->text); + rootmenu.prompt->text = sym_expand_string_value(rootmenu.prompt->text); + + menu_finalize(&rootmenu); + for_all_symbols(i, sym) { + if (sym_check_deps(sym)) + zconfnerrs++; + } + if (zconfnerrs) + exit(1); + sym_set_change_count(1); +} + +static const char *zconf_tokenname(int token) +{ + switch (token) { + case T_MENU: return "menu"; + case T_ENDMENU: return "endmenu"; + case T_CHOICE: return "choice"; + case T_ENDCHOICE: return "endchoice"; + case T_IF: return "if"; + case T_ENDIF: return "endif"; + case T_DEPENDS: return "depends"; + case T_VISIBLE: return "visible"; + } + return ""; +} + +static bool zconf_endtoken(const struct kconf_id *id, int starttoken, int endtoken) +{ + if (id->token != endtoken) { + zconf_error("unexpected '%s' within %s block", + kconf_id_strings + id->name, zconf_tokenname(starttoken)); + zconfnerrs++; + return false; + } + if (current_menu->file != current_file) { + zconf_error("'%s' in different file than '%s'", + kconf_id_strings + id->name, zconf_tokenname(starttoken)); + fprintf(stderr, "%s:%d: location of the '%s'\n", + current_menu->file->name, current_menu->lineno, + zconf_tokenname(starttoken)); + zconfnerrs++; + return false; + } + return true; +} + +static void zconfprint(const char *err, ...) +{ + va_list ap; + + fprintf(stderr, "%s:%d: ", zconf_curname(), zconf_lineno()); + va_start(ap, err); + vfprintf(stderr, err, ap); + va_end(ap); + fprintf(stderr, "\n"); +} + +static void zconf_error(const char *err, ...) +{ + va_list ap; + + zconfnerrs++; + fprintf(stderr, "%s:%d: ", zconf_curname(), zconf_lineno()); + va_start(ap, err); + vfprintf(stderr, err, ap); + va_end(ap); + fprintf(stderr, "\n"); +} + +static void zconferror(const char *err) +{ + fprintf(stderr, "%s:%d: %s\n", zconf_curname(), zconf_lineno() + 1, err); +} + +static void print_quoted_string(FILE *out, const char *str) +{ + const char *p; + int len; + + putc('"', out); + while ((p = strchr(str, '"'))) { + len = p - str; + if (len) + fprintf(out, "%.*s", len, str); + fputs("\\\"", out); + str = p + 1; + } + fputs(str, out); + putc('"', out); +} + +static void print_symbol(FILE *out, struct menu *menu) +{ + struct symbol *sym = menu->sym; + struct property *prop; + + if (sym_is_choice(sym)) + fprintf(out, "\nchoice\n"); + else + fprintf(out, "\nconfig %s\n", sym->name); + switch (sym->type) { + case S_BOOLEAN: + fputs(" boolean\n", out); + break; + case S_TRISTATE: + fputs(" tristate\n", out); + break; + case S_STRING: + fputs(" string\n", out); + break; + case S_INT: + fputs(" integer\n", out); + break; + case S_HEX: + fputs(" hex\n", out); + break; + default: + fputs(" ???\n", out); + break; + } + for (prop = sym->prop; prop; prop = prop->next) { + if (prop->menu != menu) + continue; + switch (prop->type) { + case P_PROMPT: + fputs(" prompt ", out); + print_quoted_string(out, prop->text); + if (!expr_is_yes(prop->visible.expr)) { + fputs(" if ", out); + expr_fprint(prop->visible.expr, out); + } + fputc('\n', out); + break; + case P_DEFAULT: + fputs( " default ", out); + expr_fprint(prop->expr, out); + if (!expr_is_yes(prop->visible.expr)) { + fputs(" if ", out); + expr_fprint(prop->visible.expr, out); + } + fputc('\n', out); + break; + case P_CHOICE: + fputs(" #choice value\n", out); + break; + case P_SELECT: + fputs( " select ", out); + expr_fprint(prop->expr, out); + fputc('\n', out); + break; + case P_RANGE: + fputs( " range ", out); + expr_fprint(prop->expr, out); + fputc('\n', out); + break; + case P_MENU: + fputs( " menu ", out); + print_quoted_string(out, prop->text); + fputc('\n', out); + break; + default: + fprintf(out, " unknown prop %d!\n", prop->type); + break; + } + } + if (menu->help) { + int len = strlen(menu->help); + while (menu->help[--len] == '\n') + menu->help[len] = 0; + fprintf(out, " help\n%s\n", menu->help); + } +} + +void zconfdump(FILE *out) +{ + struct property *prop; + struct symbol *sym; + struct menu *menu; + + menu = rootmenu.list; + while (menu) { + if ((sym = menu->sym)) + print_symbol(out, menu); + else if ((prop = menu->prompt)) { + switch (prop->type) { + case P_COMMENT: + fputs("\ncomment ", out); + print_quoted_string(out, prop->text); + fputs("\n", out); + break; + case P_MENU: + fputs("\nmenu ", out); + print_quoted_string(out, prop->text); + fputs("\n", out); + break; + default: + ; + } + if (!expr_is_yes(prop->visible.expr)) { + fputs(" depends ", out); + expr_fprint(prop->visible.expr, out); + fputc('\n', out); + } + } + + if (menu->list) + menu = menu->list; + else if (menu->next) + menu = menu->next; + else while ((menu = menu->parent)) { + if (menu->prompt && menu->prompt->type == P_MENU) + fputs("\nendmenu\n", out); + if (menu->next) { + menu = menu->next; + break; + } + } + } +} + +#include "lconf.c" +#include "util.c" +#include "confdata.c" +#include "expr.c" +#include "symbol.c" +#include "menu.c" diff --git a/misc/tools/kconfig-frontends/libs/parser/yconf.y.patch b/misc/tools/kconfig-frontends/libs/parser/yconf.y.patch new file mode 100644 index 0000000000..dc8f0e928f --- /dev/null +++ b/misc/tools/kconfig-frontends/libs/parser/yconf.y.patch @@ -0,0 +1,29 @@ +--- a/libs/parser/yconf.y 2012-01-12 22:37:17.582339777 +0100 ++++ b/libs/parser/yconf.y 2012-03-03 23:55:29.889737630 +0100 +@@ -96,7 +96,7 @@ + + %{ + /* Include zconf.hash.c here so it can see the token constants. */ +-#include "zconf.hash.c" ++#include "hconf.c" + %} + + %% +@@ -496,7 +496,7 @@ + modules_sym = sym_lookup(NULL, 0); + modules_sym->type = S_BOOLEAN; + modules_sym->flags |= SYMBOL_AUTO; +- rootmenu.prompt = menu_add_prompt(P_MENU, "Linux Kernel Configuration", NULL); ++ rootmenu.prompt = menu_add_prompt(P_MENU, ROOTMENU, NULL); + + if (getenv("ZCONF_DEBUG")) + zconfdebug = 1; +@@ -732,7 +732,7 @@ + } + } + +-#include "zconf.lex.c" ++#include "lconf.c" + #include "util.c" + #include "confdata.c" + #include "expr.c" diff --git a/misc/tools/kconfig-frontends/scripts/.autostuff/config.h.in b/misc/tools/kconfig-frontends/scripts/.autostuff/config.h.in new file mode 100644 index 0000000000..aa7413ee7e --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/.autostuff/config.h.in @@ -0,0 +1,202 @@ +/* scripts/.autostuff/config.h.in. Generated from configure.ac by autoheader. */ + +/* Define to one of `_getb67', `GETB67', `getb67' for Cray-2 and Cray-YMP + systems. This function is required for `alloca.c' support on those systems. + */ +#undef CRAY_STACKSEG_END + +/* Define to 1 if using `alloca.c'. */ +#undef C_ALLOCA + +/* Define to 1 if you have `alloca', as a function or macro. */ +#undef HAVE_ALLOCA + +/* Define to 1 if you have and it should be used (not on Ultrix). + */ +#undef HAVE_ALLOCA_H + +/* Define to 1 if you have the `bzero' function. */ +#undef HAVE_BZERO + +/* Define to 1 if you have the header file. */ +#undef HAVE_CURSES_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_DLFCN_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_FCNTL_H + +/* Define to 1 if you have the `gettimeofday' function. */ +#undef HAVE_GETTIMEOFDAY + +/* Define to 1 if you have the header file. */ +#undef HAVE_INTTYPES_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_LIBINTL_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_LIMITS_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_LOCALE_H + +/* Define to 1 if your system has a GNU libc compatible `malloc' function, and + to 0 otherwise. */ +#undef HAVE_MALLOC + +/* Define to 1 if you have the `memmove' function. */ +#undef HAVE_MEMMOVE + +/* Define to 1 if you have the header file. */ +#undef HAVE_MEMORY_H + +/* Define to 1 if you have the `memset' function. */ +#undef HAVE_MEMSET + +/* Define to 1 if you have the `mkdir' function. */ +#undef HAVE_MKDIR + +/* Define to 1 if you have the header file. */ +#undef HAVE_NCURSESW_CURSES_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_NCURSES_CURSES_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_NCURSES_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_NCURSES_NCURSES_H + +/* Define to 1 if your system has a GNU libc compatible `realloc' function, + and to 0 otherwise. */ +#undef HAVE_REALLOC + +/* Define to 1 if you have the `regcomp' function. */ +#undef HAVE_REGCOMP + +/* Define to 1 if you have the `setlocale' function. */ +#undef HAVE_SETLOCALE + +/* Define to 1 if stdbool.h conforms to C99. */ +#undef HAVE_STDBOOL_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_STDINT_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_STDLIB_H + +/* Define to 1 if you have the `strcasecmp' function. */ +#undef HAVE_STRCASECMP + +/* Define to 1 if you have the `strchr' function. */ +#undef HAVE_STRCHR + +/* Define to 1 if you have the `strcspn' function. */ +#undef HAVE_STRCSPN + +/* Define to 1 if you have the `strdup' function. */ +#undef HAVE_STRDUP + +/* Define to 1 if you have the header file. */ +#undef HAVE_STRINGS_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_STRING_H + +/* Define to 1 if you have the `strncasecmp' function. */ +#undef HAVE_STRNCASECMP + +/* Define to 1 if you have the `strpbrk' function. */ +#undef HAVE_STRPBRK + +/* Define to 1 if you have the `strrchr' function. */ +#undef HAVE_STRRCHR + +/* Define to 1 if you have the `strspn' function. */ +#undef HAVE_STRSPN + +/* Define to 1 if you have the `strtol' function. */ +#undef HAVE_STRTOL + +/* Define to 1 if you have the header file. */ +#undef HAVE_SYS_STAT_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_SYS_TIME_H + +/* Define to 1 if you have the header file. */ +#undef HAVE_SYS_TYPES_H + +/* Define to 1 if you have the `uname' function. */ +#undef HAVE_UNAME + +/* Define to 1 if you have the header file. */ +#undef HAVE_UNISTD_H + +/* Define to 1 if the system has the type `_Bool'. */ +#undef HAVE__BOOL + +/* Define to the sub-directory in which libtool stores uninstalled libraries. + */ +#undef LT_OBJDIR + +/* Define to 1 if your C compiler doesn't accept -c and -o together. */ +#undef NO_MINUS_C_MINUS_O + +/* Name of package */ +#undef PACKAGE + +/* Define to the address where bug reports for this package should be sent. */ +#undef PACKAGE_BUGREPORT + +/* Define to the full name of this package. */ +#undef PACKAGE_NAME + +/* Define to the full name and version of this package. */ +#undef PACKAGE_STRING + +/* Define to the one symbol short name of this package. */ +#undef PACKAGE_TARNAME + +/* Define to the home page for this package. */ +#undef PACKAGE_URL + +/* Define to the version of this package. */ +#undef PACKAGE_VERSION + +/* If using the C implementation of alloca, define if you know the + direction of stack growth for your system; otherwise it will be + automatically deduced at runtime. + STACK_DIRECTION > 0 => grows toward higher addresses + STACK_DIRECTION < 0 => grows toward lower addresses + STACK_DIRECTION = 0 => direction of growth unknown */ +#undef STACK_DIRECTION + +/* Define to 1 if you have the ANSI C header files. */ +#undef STDC_HEADERS + +/* Version number of package */ +#undef VERSION + +/* Define to 1 if `lex' declares `yytext' as a `char *' by default, not a + `char[]'. */ +#undef YYTEXT_POINTER + +/* Define to `__inline__' or `__inline' if that's what the C compiler + calls it, or to nothing if 'inline' is not supported under any name. */ +#ifndef __cplusplus +#undef inline +#endif + +/* Define to rpl_malloc if the replacement function should be used. */ +#undef malloc + +/* Define to rpl_realloc if the replacement function should be used. */ +#undef realloc + +/* Define to `unsigned int' if does not define. */ +#undef size_t diff --git a/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/compile b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/compile new file mode 100755 index 0000000000..c0096a7b56 --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/compile @@ -0,0 +1,143 @@ +#! /bin/sh +# Wrapper for compilers which do not understand `-c -o'. + +scriptversion=2009-10-06.20; # UTC + +# Copyright (C) 1999, 2000, 2003, 2004, 2005, 2009 Free Software +# Foundation, Inc. +# Written by Tom Tromey . +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2, or (at your option) +# any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program that contains a +# configuration script generated by Autoconf, you may include it under +# the same distribution terms that you use for the rest of that program. + +# This file is maintained in Automake, please report +# bugs to or send patches to +# . + +case $1 in + '') + echo "$0: No command. Try \`$0 --help' for more information." 1>&2 + exit 1; + ;; + -h | --h*) + cat <<\EOF +Usage: compile [--help] [--version] PROGRAM [ARGS] + +Wrapper for compilers which do not understand `-c -o'. +Remove `-o dest.o' from ARGS, run PROGRAM with the remaining +arguments, and rename the output as expected. + +If you are trying to build a whole package this is not the +right script to run: please start by reading the file `INSTALL'. + +Report bugs to . +EOF + exit $? + ;; + -v | --v*) + echo "compile $scriptversion" + exit $? + ;; +esac + +ofile= +cfile= +eat= + +for arg +do + if test -n "$eat"; then + eat= + else + case $1 in + -o) + # configure might choose to run compile as `compile cc -o foo foo.c'. + # So we strip `-o arg' only if arg is an object. + eat=1 + case $2 in + *.o | *.obj) + ofile=$2 + ;; + *) + set x "$@" -o "$2" + shift + ;; + esac + ;; + *.c) + cfile=$1 + set x "$@" "$1" + shift + ;; + *) + set x "$@" "$1" + shift + ;; + esac + fi + shift +done + +if test -z "$ofile" || test -z "$cfile"; then + # If no `-o' option was seen then we might have been invoked from a + # pattern rule where we don't need one. That is ok -- this is a + # normal compilation that the losing compiler can handle. If no + # `.c' file was seen then we are probably linking. That is also + # ok. + exec "$@" +fi + +# Name of file we expect compiler to create. +cofile=`echo "$cfile" | sed 's|^.*[\\/]||; s|^[a-zA-Z]:||; s/\.c$/.o/'` + +# Create the lock directory. +# Note: use `[/\\:.-]' here to ensure that we don't use the same name +# that we are using for the .o file. Also, base the name on the expected +# object file name, since that is what matters with a parallel build. +lockdir=`echo "$cofile" | sed -e 's|[/\\:.-]|_|g'`.d +while true; do + if mkdir "$lockdir" >/dev/null 2>&1; then + break + fi + sleep 1 +done +# FIXME: race condition here if user kills between mkdir and trap. +trap "rmdir '$lockdir'; exit 1" 1 2 15 + +# Run the compile. +"$@" +ret=$? + +if test -f "$cofile"; then + test "$cofile" = "$ofile" || mv "$cofile" "$ofile" +elif test -f "${cofile}bj"; then + test "${cofile}bj" = "$ofile" || mv "${cofile}bj" "$ofile" +fi + +rmdir "$lockdir" +exit $ret + +# Local Variables: +# mode: shell-script +# sh-indentation: 2 +# eval: (add-hook 'write-file-hooks 'time-stamp) +# time-stamp-start: "scriptversion=" +# time-stamp-format: "%:y-%02m-%02d.%02H" +# time-stamp-time-zone: "UTC" +# time-stamp-end: "; # UTC" +# End: diff --git a/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/config.guess b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/config.guess new file mode 100755 index 0000000000..c2246a4f7f --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/config.guess @@ -0,0 +1,1502 @@ +#! /bin/sh +# Attempt to guess a canonical system name. +# Copyright (C) 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, +# 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010 +# Free Software Foundation, Inc. + +timestamp='2009-12-30' + +# This file is free software; you can redistribute it and/or modify it +# under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, but +# WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +# General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program; if not, write to the Free Software +# Foundation, Inc., 51 Franklin Street - Fifth Floor, Boston, MA +# 02110-1301, USA. +# +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program that contains a +# configuration script generated by Autoconf, you may include it under +# the same distribution terms that you use for the rest of that program. + + +# Originally written by Per Bothner. Please send patches (context +# diff format) to and include a ChangeLog +# entry. +# +# This script attempts to guess a canonical system name similar to +# config.sub. If it succeeds, it prints the system name on stdout, and +# exits with 0. Otherwise, it exits with 1. +# +# You can get the latest version of this script from: +# http://git.savannah.gnu.org/gitweb/?p=config.git;a=blob_plain;f=config.guess;hb=HEAD + +me=`echo "$0" | sed -e 's,.*/,,'` + +usage="\ +Usage: $0 [OPTION] + +Output the configuration name of the system \`$me' is run on. + +Operation modes: + -h, --help print this help, then exit + -t, --time-stamp print date of last modification, then exit + -v, --version print version number, then exit + +Report bugs and patches to ." + +version="\ +GNU config.guess ($timestamp) + +Originally written by Per Bothner. +Copyright (C) 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, 2000, +2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010 Free +Software Foundation, Inc. + +This is free software; see the source for copying conditions. There is NO +warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE." + +help=" +Try \`$me --help' for more information." + +# Parse command line +while test $# -gt 0 ; do + case $1 in + --time-stamp | --time* | -t ) + echo "$timestamp" ; exit ;; + --version | -v ) + echo "$version" ; exit ;; + --help | --h* | -h ) + echo "$usage"; exit ;; + -- ) # Stop option processing + shift; break ;; + - ) # Use stdin as input. + break ;; + -* ) + echo "$me: invalid option $1$help" >&2 + exit 1 ;; + * ) + break ;; + esac +done + +if test $# != 0; then + echo "$me: too many arguments$help" >&2 + exit 1 +fi + +trap 'exit 1' 1 2 15 + +# CC_FOR_BUILD -- compiler used by this script. Note that the use of a +# compiler to aid in system detection is discouraged as it requires +# temporary files to be created and, as you can see below, it is a +# headache to deal with in a portable fashion. + +# Historically, `CC_FOR_BUILD' used to be named `HOST_CC'. We still +# use `HOST_CC' if defined, but it is deprecated. + +# Portable tmp directory creation inspired by the Autoconf team. + +set_cc_for_build=' +trap "exitcode=\$?; (rm -f \$tmpfiles 2>/dev/null; rmdir \$tmp 2>/dev/null) && exit \$exitcode" 0 ; +trap "rm -f \$tmpfiles 2>/dev/null; rmdir \$tmp 2>/dev/null; exit 1" 1 2 13 15 ; +: ${TMPDIR=/tmp} ; + { tmp=`(umask 077 && mktemp -d "$TMPDIR/cgXXXXXX") 2>/dev/null` && test -n "$tmp" && test -d "$tmp" ; } || + { test -n "$RANDOM" && tmp=$TMPDIR/cg$$-$RANDOM && (umask 077 && mkdir $tmp) ; } || + { tmp=$TMPDIR/cg-$$ && (umask 077 && mkdir $tmp) && echo "Warning: creating insecure temp directory" >&2 ; } || + { echo "$me: cannot create a temporary directory in $TMPDIR" >&2 ; exit 1 ; } ; +dummy=$tmp/dummy ; +tmpfiles="$dummy.c $dummy.o $dummy.rel $dummy" ; +case $CC_FOR_BUILD,$HOST_CC,$CC in + ,,) echo "int x;" > $dummy.c ; + for c in cc gcc c89 c99 ; do + if ($c -c -o $dummy.o $dummy.c) >/dev/null 2>&1 ; then + CC_FOR_BUILD="$c"; break ; + fi ; + done ; + if test x"$CC_FOR_BUILD" = x ; then + CC_FOR_BUILD=no_compiler_found ; + fi + ;; + ,,*) CC_FOR_BUILD=$CC ;; + ,*,*) CC_FOR_BUILD=$HOST_CC ;; +esac ; set_cc_for_build= ;' + +# This is needed to find uname on a Pyramid OSx when run in the BSD universe. +# (ghazi@noc.rutgers.edu 1994-08-24) +if (test -f /.attbin/uname) >/dev/null 2>&1 ; then + PATH=$PATH:/.attbin ; export PATH +fi + +UNAME_MACHINE=`(uname -m) 2>/dev/null` || UNAME_MACHINE=unknown +UNAME_RELEASE=`(uname -r) 2>/dev/null` || UNAME_RELEASE=unknown +UNAME_SYSTEM=`(uname -s) 2>/dev/null` || UNAME_SYSTEM=unknown +UNAME_VERSION=`(uname -v) 2>/dev/null` || UNAME_VERSION=unknown + +# Note: order is significant - the case branches are not exclusive. + +case "${UNAME_MACHINE}:${UNAME_SYSTEM}:${UNAME_RELEASE}:${UNAME_VERSION}" in + *:NetBSD:*:*) + # NetBSD (nbsd) targets should (where applicable) match one or + # more of the tupples: *-*-netbsdelf*, *-*-netbsdaout*, + # *-*-netbsdecoff* and *-*-netbsd*. For targets that recently + # switched to ELF, *-*-netbsd* would select the old + # object file format. This provides both forward + # compatibility and a consistent mechanism for selecting the + # object file format. + # + # Note: NetBSD doesn't particularly care about the vendor + # portion of the name. We always set it to "unknown". + sysctl="sysctl -n hw.machine_arch" + UNAME_MACHINE_ARCH=`(/sbin/$sysctl 2>/dev/null || \ + /usr/sbin/$sysctl 2>/dev/null || echo unknown)` + case "${UNAME_MACHINE_ARCH}" in + armeb) machine=armeb-unknown ;; + arm*) machine=arm-unknown ;; + sh3el) machine=shl-unknown ;; + sh3eb) machine=sh-unknown ;; + sh5el) machine=sh5le-unknown ;; + *) machine=${UNAME_MACHINE_ARCH}-unknown ;; + esac + # The Operating System including object format, if it has switched + # to ELF recently, or will in the future. + case "${UNAME_MACHINE_ARCH}" in + arm*|i386|m68k|ns32k|sh3*|sparc|vax) + eval $set_cc_for_build + if echo __ELF__ | $CC_FOR_BUILD -E - 2>/dev/null \ + | grep -q __ELF__ + then + # Once all utilities can be ECOFF (netbsdecoff) or a.out (netbsdaout). + # Return netbsd for either. FIX? + os=netbsd + else + os=netbsdelf + fi + ;; + *) + os=netbsd + ;; + esac + # The OS release + # Debian GNU/NetBSD machines have a different userland, and + # thus, need a distinct triplet. However, they do not need + # kernel version information, so it can be replaced with a + # suitable tag, in the style of linux-gnu. + case "${UNAME_VERSION}" in + Debian*) + release='-gnu' + ;; + *) + release=`echo ${UNAME_RELEASE}|sed -e 's/[-_].*/\./'` + ;; + esac + # Since CPU_TYPE-MANUFACTURER-KERNEL-OPERATING_SYSTEM: + # contains redundant information, the shorter form: + # CPU_TYPE-MANUFACTURER-OPERATING_SYSTEM is used. + echo "${machine}-${os}${release}" + exit ;; + *:OpenBSD:*:*) + UNAME_MACHINE_ARCH=`arch | sed 's/OpenBSD.//'` + echo ${UNAME_MACHINE_ARCH}-unknown-openbsd${UNAME_RELEASE} + exit ;; + *:ekkoBSD:*:*) + echo ${UNAME_MACHINE}-unknown-ekkobsd${UNAME_RELEASE} + exit ;; + *:SolidBSD:*:*) + echo ${UNAME_MACHINE}-unknown-solidbsd${UNAME_RELEASE} + exit ;; + macppc:MirBSD:*:*) + echo powerpc-unknown-mirbsd${UNAME_RELEASE} + exit ;; + *:MirBSD:*:*) + echo ${UNAME_MACHINE}-unknown-mirbsd${UNAME_RELEASE} + exit ;; + alpha:OSF1:*:*) + case $UNAME_RELEASE in + *4.0) + UNAME_RELEASE=`/usr/sbin/sizer -v | awk '{print $3}'` + ;; + *5.*) + UNAME_RELEASE=`/usr/sbin/sizer -v | awk '{print $4}'` + ;; + esac + # According to Compaq, /usr/sbin/psrinfo has been available on + # OSF/1 and Tru64 systems produced since 1995. I hope that + # covers most systems running today. This code pipes the CPU + # types through head -n 1, so we only detect the type of CPU 0. + ALPHA_CPU_TYPE=`/usr/sbin/psrinfo -v | sed -n -e 's/^ The alpha \(.*\) processor.*$/\1/p' | head -n 1` + case "$ALPHA_CPU_TYPE" in + "EV4 (21064)") + UNAME_MACHINE="alpha" ;; + "EV4.5 (21064)") + UNAME_MACHINE="alpha" ;; + "LCA4 (21066/21068)") + UNAME_MACHINE="alpha" ;; + "EV5 (21164)") + UNAME_MACHINE="alphaev5" ;; + "EV5.6 (21164A)") + UNAME_MACHINE="alphaev56" ;; + "EV5.6 (21164PC)") + UNAME_MACHINE="alphapca56" ;; + "EV5.7 (21164PC)") + UNAME_MACHINE="alphapca57" ;; + "EV6 (21264)") + UNAME_MACHINE="alphaev6" ;; + "EV6.7 (21264A)") + UNAME_MACHINE="alphaev67" ;; + "EV6.8CB (21264C)") + UNAME_MACHINE="alphaev68" ;; + "EV6.8AL (21264B)") + UNAME_MACHINE="alphaev68" ;; + "EV6.8CX (21264D)") + UNAME_MACHINE="alphaev68" ;; + "EV6.9A (21264/EV69A)") + UNAME_MACHINE="alphaev69" ;; + "EV7 (21364)") + UNAME_MACHINE="alphaev7" ;; + "EV7.9 (21364A)") + UNAME_MACHINE="alphaev79" ;; + esac + # A Pn.n version is a patched version. + # A Vn.n version is a released version. + # A Tn.n version is a released field test version. + # A Xn.n version is an unreleased experimental baselevel. + # 1.2 uses "1.2" for uname -r. + echo ${UNAME_MACHINE}-dec-osf`echo ${UNAME_RELEASE} | sed -e 's/^[PVTX]//' | tr 'ABCDEFGHIJKLMNOPQRSTUVWXYZ' 'abcdefghijklmnopqrstuvwxyz'` + exit ;; + Alpha\ *:Windows_NT*:*) + # How do we know it's Interix rather than the generic POSIX subsystem? + # Should we change UNAME_MACHINE based on the output of uname instead + # of the specific Alpha model? + echo alpha-pc-interix + exit ;; + 21064:Windows_NT:50:3) + echo alpha-dec-winnt3.5 + exit ;; + Amiga*:UNIX_System_V:4.0:*) + echo m68k-unknown-sysv4 + exit ;; + *:[Aa]miga[Oo][Ss]:*:*) + echo ${UNAME_MACHINE}-unknown-amigaos + exit ;; + *:[Mm]orph[Oo][Ss]:*:*) + echo ${UNAME_MACHINE}-unknown-morphos + exit ;; + *:OS/390:*:*) + echo i370-ibm-openedition + exit ;; + *:z/VM:*:*) + echo s390-ibm-zvmoe + exit ;; + *:OS400:*:*) + echo powerpc-ibm-os400 + exit ;; + arm:RISC*:1.[012]*:*|arm:riscix:1.[012]*:*) + echo arm-acorn-riscix${UNAME_RELEASE} + exit ;; + arm:riscos:*:*|arm:RISCOS:*:*) + echo arm-unknown-riscos + exit ;; + SR2?01:HI-UX/MPP:*:* | SR8000:HI-UX/MPP:*:*) + echo hppa1.1-hitachi-hiuxmpp + exit ;; + Pyramid*:OSx*:*:* | MIS*:OSx*:*:* | MIS*:SMP_DC-OSx*:*:*) + # akee@wpdis03.wpafb.af.mil (Earle F. Ake) contributed MIS and NILE. + if test "`(/bin/universe) 2>/dev/null`" = att ; then + echo pyramid-pyramid-sysv3 + else + echo pyramid-pyramid-bsd + fi + exit ;; + NILE*:*:*:dcosx) + echo pyramid-pyramid-svr4 + exit ;; + DRS?6000:unix:4.0:6*) + echo sparc-icl-nx6 + exit ;; + DRS?6000:UNIX_SV:4.2*:7* | DRS?6000:isis:4.2*:7*) + case `/usr/bin/uname -p` in + sparc) echo sparc-icl-nx7; exit ;; + esac ;; + s390x:SunOS:*:*) + echo ${UNAME_MACHINE}-ibm-solaris2`echo ${UNAME_RELEASE}|sed -e 's/[^.]*//'` + exit ;; + sun4H:SunOS:5.*:*) + echo sparc-hal-solaris2`echo ${UNAME_RELEASE}|sed -e 's/[^.]*//'` + exit ;; + sun4*:SunOS:5.*:* | tadpole*:SunOS:5.*:*) + echo sparc-sun-solaris2`echo ${UNAME_RELEASE}|sed -e 's/[^.]*//'` + exit ;; + i86pc:AuroraUX:5.*:* | i86xen:AuroraUX:5.*:*) + echo i386-pc-auroraux${UNAME_RELEASE} + exit ;; + i86pc:SunOS:5.*:* | i86xen:SunOS:5.*:*) + eval $set_cc_for_build + SUN_ARCH="i386" + # If there is a compiler, see if it is configured for 64-bit objects. + # Note that the Sun cc does not turn __LP64__ into 1 like gcc does. + # This test works for both compilers. + if [ "$CC_FOR_BUILD" != 'no_compiler_found' ]; then + if (echo '#ifdef __amd64'; echo IS_64BIT_ARCH; echo '#endif') | \ + (CCOPTS= $CC_FOR_BUILD -E - 2>/dev/null) | \ + grep IS_64BIT_ARCH >/dev/null + then + SUN_ARCH="x86_64" + fi + fi + echo ${SUN_ARCH}-pc-solaris2`echo ${UNAME_RELEASE}|sed -e 's/[^.]*//'` + exit ;; + sun4*:SunOS:6*:*) + # According to config.sub, this is the proper way to canonicalize + # SunOS6. Hard to guess exactly what SunOS6 will be like, but + # it's likely to be more like Solaris than SunOS4. + echo sparc-sun-solaris3`echo ${UNAME_RELEASE}|sed -e 's/[^.]*//'` + exit ;; + sun4*:SunOS:*:*) + case "`/usr/bin/arch -k`" in + Series*|S4*) + UNAME_RELEASE=`uname -v` + ;; + esac + # Japanese Language versions have a version number like `4.1.3-JL'. + echo sparc-sun-sunos`echo ${UNAME_RELEASE}|sed -e 's/-/_/'` + exit ;; + sun3*:SunOS:*:*) + echo m68k-sun-sunos${UNAME_RELEASE} + exit ;; + sun*:*:4.2BSD:*) + UNAME_RELEASE=`(sed 1q /etc/motd | awk '{print substr($5,1,3)}') 2>/dev/null` + test "x${UNAME_RELEASE}" = "x" && UNAME_RELEASE=3 + case "`/bin/arch`" in + sun3) + echo m68k-sun-sunos${UNAME_RELEASE} + ;; + sun4) + echo sparc-sun-sunos${UNAME_RELEASE} + ;; + esac + exit ;; + aushp:SunOS:*:*) + echo sparc-auspex-sunos${UNAME_RELEASE} + exit ;; + # The situation for MiNT is a little confusing. The machine name + # can be virtually everything (everything which is not + # "atarist" or "atariste" at least should have a processor + # > m68000). The system name ranges from "MiNT" over "FreeMiNT" + # to the lowercase version "mint" (or "freemint"). Finally + # the system name "TOS" denotes a system which is actually not + # MiNT. But MiNT is downward compatible to TOS, so this should + # be no problem. + atarist[e]:*MiNT:*:* | atarist[e]:*mint:*:* | atarist[e]:*TOS:*:*) + echo m68k-atari-mint${UNAME_RELEASE} + exit ;; + atari*:*MiNT:*:* | atari*:*mint:*:* | atarist[e]:*TOS:*:*) + echo m68k-atari-mint${UNAME_RELEASE} + exit ;; + *falcon*:*MiNT:*:* | *falcon*:*mint:*:* | *falcon*:*TOS:*:*) + echo m68k-atari-mint${UNAME_RELEASE} + exit ;; + milan*:*MiNT:*:* | milan*:*mint:*:* | *milan*:*TOS:*:*) + echo m68k-milan-mint${UNAME_RELEASE} + exit ;; + hades*:*MiNT:*:* | hades*:*mint:*:* | *hades*:*TOS:*:*) + echo m68k-hades-mint${UNAME_RELEASE} + exit ;; + *:*MiNT:*:* | *:*mint:*:* | *:*TOS:*:*) + echo m68k-unknown-mint${UNAME_RELEASE} + exit ;; + m68k:machten:*:*) + echo m68k-apple-machten${UNAME_RELEASE} + exit ;; + powerpc:machten:*:*) + echo powerpc-apple-machten${UNAME_RELEASE} + exit ;; + RISC*:Mach:*:*) + echo mips-dec-mach_bsd4.3 + exit ;; + RISC*:ULTRIX:*:*) + echo mips-dec-ultrix${UNAME_RELEASE} + exit ;; + VAX*:ULTRIX*:*:*) + echo vax-dec-ultrix${UNAME_RELEASE} + exit ;; + 2020:CLIX:*:* | 2430:CLIX:*:*) + echo clipper-intergraph-clix${UNAME_RELEASE} + exit ;; + mips:*:*:UMIPS | mips:*:*:RISCos) + eval $set_cc_for_build + sed 's/^ //' << EOF >$dummy.c +#ifdef __cplusplus +#include /* for printf() prototype */ + int main (int argc, char *argv[]) { +#else + int main (argc, argv) int argc; char *argv[]; { +#endif + #if defined (host_mips) && defined (MIPSEB) + #if defined (SYSTYPE_SYSV) + printf ("mips-mips-riscos%ssysv\n", argv[1]); exit (0); + #endif + #if defined (SYSTYPE_SVR4) + printf ("mips-mips-riscos%ssvr4\n", argv[1]); exit (0); + #endif + #if defined (SYSTYPE_BSD43) || defined(SYSTYPE_BSD) + printf ("mips-mips-riscos%sbsd\n", argv[1]); exit (0); + #endif + #endif + exit (-1); + } +EOF + $CC_FOR_BUILD -o $dummy $dummy.c && + dummyarg=`echo "${UNAME_RELEASE}" | sed -n 's/\([0-9]*\).*/\1/p'` && + SYSTEM_NAME=`$dummy $dummyarg` && + { echo "$SYSTEM_NAME"; exit; } + echo mips-mips-riscos${UNAME_RELEASE} + exit ;; + Motorola:PowerMAX_OS:*:*) + echo powerpc-motorola-powermax + exit ;; + Motorola:*:4.3:PL8-*) + echo powerpc-harris-powermax + exit ;; + Night_Hawk:*:*:PowerMAX_OS | Synergy:PowerMAX_OS:*:*) + echo powerpc-harris-powermax + exit ;; + Night_Hawk:Power_UNIX:*:*) + echo powerpc-harris-powerunix + exit ;; + m88k:CX/UX:7*:*) + echo m88k-harris-cxux7 + exit ;; + m88k:*:4*:R4*) + echo m88k-motorola-sysv4 + exit ;; + m88k:*:3*:R3*) + echo m88k-motorola-sysv3 + exit ;; + AViiON:dgux:*:*) + # DG/UX returns AViiON for all architectures + UNAME_PROCESSOR=`/usr/bin/uname -p` + if [ $UNAME_PROCESSOR = mc88100 ] || [ $UNAME_PROCESSOR = mc88110 ] + then + if [ ${TARGET_BINARY_INTERFACE}x = m88kdguxelfx ] || \ + [ ${TARGET_BINARY_INTERFACE}x = x ] + then + echo m88k-dg-dgux${UNAME_RELEASE} + else + echo m88k-dg-dguxbcs${UNAME_RELEASE} + fi + else + echo i586-dg-dgux${UNAME_RELEASE} + fi + exit ;; + M88*:DolphinOS:*:*) # DolphinOS (SVR3) + echo m88k-dolphin-sysv3 + exit ;; + M88*:*:R3*:*) + # Delta 88k system running SVR3 + echo m88k-motorola-sysv3 + exit ;; + XD88*:*:*:*) # Tektronix XD88 system running UTekV (SVR3) + echo m88k-tektronix-sysv3 + exit ;; + Tek43[0-9][0-9]:UTek:*:*) # Tektronix 4300 system running UTek (BSD) + echo m68k-tektronix-bsd + exit ;; + *:IRIX*:*:*) + echo mips-sgi-irix`echo ${UNAME_RELEASE}|sed -e 's/-/_/g'` + exit ;; + ????????:AIX?:[12].1:2) # AIX 2.2.1 or AIX 2.1.1 is RT/PC AIX. + echo romp-ibm-aix # uname -m gives an 8 hex-code CPU id + exit ;; # Note that: echo "'`uname -s`'" gives 'AIX ' + i*86:AIX:*:*) + echo i386-ibm-aix + exit ;; + ia64:AIX:*:*) + if [ -x /usr/bin/oslevel ] ; then + IBM_REV=`/usr/bin/oslevel` + else + IBM_REV=${UNAME_VERSION}.${UNAME_RELEASE} + fi + echo ${UNAME_MACHINE}-ibm-aix${IBM_REV} + exit ;; + *:AIX:2:3) + if grep bos325 /usr/include/stdio.h >/dev/null 2>&1; then + eval $set_cc_for_build + sed 's/^ //' << EOF >$dummy.c + #include + + main() + { + if (!__power_pc()) + exit(1); + puts("powerpc-ibm-aix3.2.5"); + exit(0); + } +EOF + if $CC_FOR_BUILD -o $dummy $dummy.c && SYSTEM_NAME=`$dummy` + then + echo "$SYSTEM_NAME" + else + echo rs6000-ibm-aix3.2.5 + fi + elif grep bos324 /usr/include/stdio.h >/dev/null 2>&1; then + echo rs6000-ibm-aix3.2.4 + else + echo rs6000-ibm-aix3.2 + fi + exit ;; + *:AIX:*:[456]) + IBM_CPU_ID=`/usr/sbin/lsdev -C -c processor -S available | sed 1q | awk '{ print $1 }'` + if /usr/sbin/lsattr -El ${IBM_CPU_ID} | grep ' POWER' >/dev/null 2>&1; then + IBM_ARCH=rs6000 + else + IBM_ARCH=powerpc + fi + if [ -x /usr/bin/oslevel ] ; then + IBM_REV=`/usr/bin/oslevel` + else + IBM_REV=${UNAME_VERSION}.${UNAME_RELEASE} + fi + echo ${IBM_ARCH}-ibm-aix${IBM_REV} + exit ;; + *:AIX:*:*) + echo rs6000-ibm-aix + exit ;; + ibmrt:4.4BSD:*|romp-ibm:BSD:*) + echo romp-ibm-bsd4.4 + exit ;; + ibmrt:*BSD:*|romp-ibm:BSD:*) # covers RT/PC BSD and + echo romp-ibm-bsd${UNAME_RELEASE} # 4.3 with uname added to + exit ;; # report: romp-ibm BSD 4.3 + *:BOSX:*:*) + echo rs6000-bull-bosx + exit ;; + DPX/2?00:B.O.S.:*:*) + echo m68k-bull-sysv3 + exit ;; + 9000/[34]??:4.3bsd:1.*:*) + echo m68k-hp-bsd + exit ;; + hp300:4.4BSD:*:* | 9000/[34]??:4.3bsd:2.*:*) + echo m68k-hp-bsd4.4 + exit ;; + 9000/[34678]??:HP-UX:*:*) + HPUX_REV=`echo ${UNAME_RELEASE}|sed -e 's/[^.]*.[0B]*//'` + case "${UNAME_MACHINE}" in + 9000/31? ) HP_ARCH=m68000 ;; + 9000/[34]?? ) HP_ARCH=m68k ;; + 9000/[678][0-9][0-9]) + if [ -x /usr/bin/getconf ]; then + sc_cpu_version=`/usr/bin/getconf SC_CPU_VERSION 2>/dev/null` + sc_kernel_bits=`/usr/bin/getconf SC_KERNEL_BITS 2>/dev/null` + case "${sc_cpu_version}" in + 523) HP_ARCH="hppa1.0" ;; # CPU_PA_RISC1_0 + 528) HP_ARCH="hppa1.1" ;; # CPU_PA_RISC1_1 + 532) # CPU_PA_RISC2_0 + case "${sc_kernel_bits}" in + 32) HP_ARCH="hppa2.0n" ;; + 64) HP_ARCH="hppa2.0w" ;; + '') HP_ARCH="hppa2.0" ;; # HP-UX 10.20 + esac ;; + esac + fi + if [ "${HP_ARCH}" = "" ]; then + eval $set_cc_for_build + sed 's/^ //' << EOF >$dummy.c + + #define _HPUX_SOURCE + #include + #include + + int main () + { + #if defined(_SC_KERNEL_BITS) + long bits = sysconf(_SC_KERNEL_BITS); + #endif + long cpu = sysconf (_SC_CPU_VERSION); + + switch (cpu) + { + case CPU_PA_RISC1_0: puts ("hppa1.0"); break; + case CPU_PA_RISC1_1: puts ("hppa1.1"); break; + case CPU_PA_RISC2_0: + #if defined(_SC_KERNEL_BITS) + switch (bits) + { + case 64: puts ("hppa2.0w"); break; + case 32: puts ("hppa2.0n"); break; + default: puts ("hppa2.0"); break; + } break; + #else /* !defined(_SC_KERNEL_BITS) */ + puts ("hppa2.0"); break; + #endif + default: puts ("hppa1.0"); break; + } + exit (0); + } +EOF + (CCOPTS= $CC_FOR_BUILD -o $dummy $dummy.c 2>/dev/null) && HP_ARCH=`$dummy` + test -z "$HP_ARCH" && HP_ARCH=hppa + fi ;; + esac + if [ ${HP_ARCH} = "hppa2.0w" ] + then + eval $set_cc_for_build + + # hppa2.0w-hp-hpux* has a 64-bit kernel and a compiler generating + # 32-bit code. hppa64-hp-hpux* has the same kernel and a compiler + # generating 64-bit code. GNU and HP use different nomenclature: + # + # $ CC_FOR_BUILD=cc ./config.guess + # => hppa2.0w-hp-hpux11.23 + # $ CC_FOR_BUILD="cc +DA2.0w" ./config.guess + # => hppa64-hp-hpux11.23 + + if echo __LP64__ | (CCOPTS= $CC_FOR_BUILD -E - 2>/dev/null) | + grep -q __LP64__ + then + HP_ARCH="hppa2.0w" + else + HP_ARCH="hppa64" + fi + fi + echo ${HP_ARCH}-hp-hpux${HPUX_REV} + exit ;; + ia64:HP-UX:*:*) + HPUX_REV=`echo ${UNAME_RELEASE}|sed -e 's/[^.]*.[0B]*//'` + echo ia64-hp-hpux${HPUX_REV} + exit ;; + 3050*:HI-UX:*:*) + eval $set_cc_for_build + sed 's/^ //' << EOF >$dummy.c + #include + int + main () + { + long cpu = sysconf (_SC_CPU_VERSION); + /* The order matters, because CPU_IS_HP_MC68K erroneously returns + true for CPU_PA_RISC1_0. CPU_IS_PA_RISC returns correct + results, however. */ + if (CPU_IS_PA_RISC (cpu)) + { + switch (cpu) + { + case CPU_PA_RISC1_0: puts ("hppa1.0-hitachi-hiuxwe2"); break; + case CPU_PA_RISC1_1: puts ("hppa1.1-hitachi-hiuxwe2"); break; + case CPU_PA_RISC2_0: puts ("hppa2.0-hitachi-hiuxwe2"); break; + default: puts ("hppa-hitachi-hiuxwe2"); break; + } + } + else if (CPU_IS_HP_MC68K (cpu)) + puts ("m68k-hitachi-hiuxwe2"); + else puts ("unknown-hitachi-hiuxwe2"); + exit (0); + } +EOF + $CC_FOR_BUILD -o $dummy $dummy.c && SYSTEM_NAME=`$dummy` && + { echo "$SYSTEM_NAME"; exit; } + echo unknown-hitachi-hiuxwe2 + exit ;; + 9000/7??:4.3bsd:*:* | 9000/8?[79]:4.3bsd:*:* ) + echo hppa1.1-hp-bsd + exit ;; + 9000/8??:4.3bsd:*:*) + echo hppa1.0-hp-bsd + exit ;; + *9??*:MPE/iX:*:* | *3000*:MPE/iX:*:*) + echo hppa1.0-hp-mpeix + exit ;; + hp7??:OSF1:*:* | hp8?[79]:OSF1:*:* ) + echo hppa1.1-hp-osf + exit ;; + hp8??:OSF1:*:*) + echo hppa1.0-hp-osf + exit ;; + i*86:OSF1:*:*) + if [ -x /usr/sbin/sysversion ] ; then + echo ${UNAME_MACHINE}-unknown-osf1mk + else + echo ${UNAME_MACHINE}-unknown-osf1 + fi + exit ;; + parisc*:Lites*:*:*) + echo hppa1.1-hp-lites + exit ;; + C1*:ConvexOS:*:* | convex:ConvexOS:C1*:*) + echo c1-convex-bsd + exit ;; + C2*:ConvexOS:*:* | convex:ConvexOS:C2*:*) + if getsysinfo -f scalar_acc + then echo c32-convex-bsd + else echo c2-convex-bsd + fi + exit ;; + C34*:ConvexOS:*:* | convex:ConvexOS:C34*:*) + echo c34-convex-bsd + exit ;; + C38*:ConvexOS:*:* | convex:ConvexOS:C38*:*) + echo c38-convex-bsd + exit ;; + C4*:ConvexOS:*:* | convex:ConvexOS:C4*:*) + echo c4-convex-bsd + exit ;; + CRAY*Y-MP:*:*:*) + echo ymp-cray-unicos${UNAME_RELEASE} | sed -e 's/\.[^.]*$/.X/' + exit ;; + CRAY*[A-Z]90:*:*:*) + echo ${UNAME_MACHINE}-cray-unicos${UNAME_RELEASE} \ + | sed -e 's/CRAY.*\([A-Z]90\)/\1/' \ + -e y/ABCDEFGHIJKLMNOPQRSTUVWXYZ/abcdefghijklmnopqrstuvwxyz/ \ + -e 's/\.[^.]*$/.X/' + exit ;; + CRAY*TS:*:*:*) + echo t90-cray-unicos${UNAME_RELEASE} | sed -e 's/\.[^.]*$/.X/' + exit ;; + CRAY*T3E:*:*:*) + echo alphaev5-cray-unicosmk${UNAME_RELEASE} | sed -e 's/\.[^.]*$/.X/' + exit ;; + CRAY*SV1:*:*:*) + echo sv1-cray-unicos${UNAME_RELEASE} | sed -e 's/\.[^.]*$/.X/' + exit ;; + *:UNICOS/mp:*:*) + echo craynv-cray-unicosmp${UNAME_RELEASE} | sed -e 's/\.[^.]*$/.X/' + exit ;; + F30[01]:UNIX_System_V:*:* | F700:UNIX_System_V:*:*) + FUJITSU_PROC=`uname -m | tr 'ABCDEFGHIJKLMNOPQRSTUVWXYZ' 'abcdefghijklmnopqrstuvwxyz'` + FUJITSU_SYS=`uname -p | tr 'ABCDEFGHIJKLMNOPQRSTUVWXYZ' 'abcdefghijklmnopqrstuvwxyz' | sed -e 's/\///'` + FUJITSU_REL=`echo ${UNAME_RELEASE} | sed -e 's/ /_/'` + echo "${FUJITSU_PROC}-fujitsu-${FUJITSU_SYS}${FUJITSU_REL}" + exit ;; + 5000:UNIX_System_V:4.*:*) + FUJITSU_SYS=`uname -p | tr 'ABCDEFGHIJKLMNOPQRSTUVWXYZ' 'abcdefghijklmnopqrstuvwxyz' | sed -e 's/\///'` + FUJITSU_REL=`echo ${UNAME_RELEASE} | tr 'ABCDEFGHIJKLMNOPQRSTUVWXYZ' 'abcdefghijklmnopqrstuvwxyz' | sed -e 's/ /_/'` + echo "sparc-fujitsu-${FUJITSU_SYS}${FUJITSU_REL}" + exit ;; + i*86:BSD/386:*:* | i*86:BSD/OS:*:* | *:Ascend\ Embedded/OS:*:*) + echo ${UNAME_MACHINE}-pc-bsdi${UNAME_RELEASE} + exit ;; + sparc*:BSD/OS:*:*) + echo sparc-unknown-bsdi${UNAME_RELEASE} + exit ;; + *:BSD/OS:*:*) + echo ${UNAME_MACHINE}-unknown-bsdi${UNAME_RELEASE} + exit ;; + *:FreeBSD:*:*) + case ${UNAME_MACHINE} in + pc98) + echo i386-unknown-freebsd`echo ${UNAME_RELEASE}|sed -e 's/[-(].*//'` ;; + amd64) + echo x86_64-unknown-freebsd`echo ${UNAME_RELEASE}|sed -e 's/[-(].*//'` ;; + *) + echo ${UNAME_MACHINE}-unknown-freebsd`echo ${UNAME_RELEASE}|sed -e 's/[-(].*//'` ;; + esac + exit ;; + i*:CYGWIN*:*) + echo ${UNAME_MACHINE}-pc-cygwin + exit ;; + *:MINGW*:*) + echo ${UNAME_MACHINE}-pc-mingw32 + exit ;; + i*:windows32*:*) + # uname -m includes "-pc" on this system. + echo ${UNAME_MACHINE}-mingw32 + exit ;; + i*:PW*:*) + echo ${UNAME_MACHINE}-pc-pw32 + exit ;; + *:Interix*:*) + case ${UNAME_MACHINE} in + x86) + echo i586-pc-interix${UNAME_RELEASE} + exit ;; + authenticamd | genuineintel | EM64T) + echo x86_64-unknown-interix${UNAME_RELEASE} + exit ;; + IA64) + echo ia64-unknown-interix${UNAME_RELEASE} + exit ;; + esac ;; + [345]86:Windows_95:* | [345]86:Windows_98:* | [345]86:Windows_NT:*) + echo i${UNAME_MACHINE}-pc-mks + exit ;; + 8664:Windows_NT:*) + echo x86_64-pc-mks + exit ;; + i*:Windows_NT*:* | Pentium*:Windows_NT*:*) + # How do we know it's Interix rather than the generic POSIX subsystem? + # It also conflicts with pre-2.0 versions of AT&T UWIN. Should we + # UNAME_MACHINE based on the output of uname instead of i386? + echo i586-pc-interix + exit ;; + i*:UWIN*:*) + echo ${UNAME_MACHINE}-pc-uwin + exit ;; + amd64:CYGWIN*:*:* | x86_64:CYGWIN*:*:*) + echo x86_64-unknown-cygwin + exit ;; + p*:CYGWIN*:*) + echo powerpcle-unknown-cygwin + exit ;; + prep*:SunOS:5.*:*) + echo powerpcle-unknown-solaris2`echo ${UNAME_RELEASE}|sed -e 's/[^.]*//'` + exit ;; + *:GNU:*:*) + # the GNU system + echo `echo ${UNAME_MACHINE}|sed -e 's,[-/].*$,,'`-unknown-gnu`echo ${UNAME_RELEASE}|sed -e 's,/.*$,,'` + exit ;; + *:GNU/*:*:*) + # other systems with GNU libc and userland + echo ${UNAME_MACHINE}-unknown-`echo ${UNAME_SYSTEM} | sed 's,^[^/]*/,,' | tr '[A-Z]' '[a-z]'``echo ${UNAME_RELEASE}|sed -e 's/[-(].*//'`-gnu + exit ;; + i*86:Minix:*:*) + echo ${UNAME_MACHINE}-pc-minix + exit ;; + alpha:Linux:*:*) + case `sed -n '/^cpu model/s/^.*: \(.*\)/\1/p' < /proc/cpuinfo` in + EV5) UNAME_MACHINE=alphaev5 ;; + EV56) UNAME_MACHINE=alphaev56 ;; + PCA56) UNAME_MACHINE=alphapca56 ;; + PCA57) UNAME_MACHINE=alphapca56 ;; + EV6) UNAME_MACHINE=alphaev6 ;; + EV67) UNAME_MACHINE=alphaev67 ;; + EV68*) UNAME_MACHINE=alphaev68 ;; + esac + objdump --private-headers /bin/sh | grep -q ld.so.1 + if test "$?" = 0 ; then LIBC="libc1" ; else LIBC="" ; fi + echo ${UNAME_MACHINE}-unknown-linux-gnu${LIBC} + exit ;; + arm*:Linux:*:*) + eval $set_cc_for_build + if echo __ARM_EABI__ | $CC_FOR_BUILD -E - 2>/dev/null \ + | grep -q __ARM_EABI__ + then + echo ${UNAME_MACHINE}-unknown-linux-gnu + else + echo ${UNAME_MACHINE}-unknown-linux-gnueabi + fi + exit ;; + avr32*:Linux:*:*) + echo ${UNAME_MACHINE}-unknown-linux-gnu + exit ;; + cris:Linux:*:*) + echo cris-axis-linux-gnu + exit ;; + crisv32:Linux:*:*) + echo crisv32-axis-linux-gnu + exit ;; + frv:Linux:*:*) + echo frv-unknown-linux-gnu + exit ;; + i*86:Linux:*:*) + LIBC=gnu + eval $set_cc_for_build + sed 's/^ //' << EOF >$dummy.c + #ifdef __dietlibc__ + LIBC=dietlibc + #endif +EOF + eval `$CC_FOR_BUILD -E $dummy.c 2>/dev/null | grep '^LIBC'` + echo "${UNAME_MACHINE}-pc-linux-${LIBC}" + exit ;; + ia64:Linux:*:*) + echo ${UNAME_MACHINE}-unknown-linux-gnu + exit ;; + m32r*:Linux:*:*) + echo ${UNAME_MACHINE}-unknown-linux-gnu + exit ;; + m68*:Linux:*:*) + echo ${UNAME_MACHINE}-unknown-linux-gnu + exit ;; + mips:Linux:*:* | mips64:Linux:*:*) + eval $set_cc_for_build + sed 's/^ //' << EOF >$dummy.c + #undef CPU + #undef ${UNAME_MACHINE} + #undef ${UNAME_MACHINE}el + #if defined(__MIPSEL__) || defined(__MIPSEL) || defined(_MIPSEL) || defined(MIPSEL) + CPU=${UNAME_MACHINE}el + #else + #if defined(__MIPSEB__) || defined(__MIPSEB) || defined(_MIPSEB) || defined(MIPSEB) + CPU=${UNAME_MACHINE} + #else + CPU= + #endif + #endif +EOF + eval `$CC_FOR_BUILD -E $dummy.c 2>/dev/null | grep '^CPU'` + test x"${CPU}" != x && { echo "${CPU}-unknown-linux-gnu"; exit; } + ;; + or32:Linux:*:*) + echo or32-unknown-linux-gnu + exit ;; + padre:Linux:*:*) + echo sparc-unknown-linux-gnu + exit ;; + parisc64:Linux:*:* | hppa64:Linux:*:*) + echo hppa64-unknown-linux-gnu + exit ;; + parisc:Linux:*:* | hppa:Linux:*:*) + # Look for CPU level + case `grep '^cpu[^a-z]*:' /proc/cpuinfo 2>/dev/null | cut -d' ' -f2` in + PA7*) echo hppa1.1-unknown-linux-gnu ;; + PA8*) echo hppa2.0-unknown-linux-gnu ;; + *) echo hppa-unknown-linux-gnu ;; + esac + exit ;; + ppc64:Linux:*:*) + echo powerpc64-unknown-linux-gnu + exit ;; + ppc:Linux:*:*) + echo powerpc-unknown-linux-gnu + exit ;; + s390:Linux:*:* | s390x:Linux:*:*) + echo ${UNAME_MACHINE}-ibm-linux + exit ;; + sh64*:Linux:*:*) + echo ${UNAME_MACHINE}-unknown-linux-gnu + exit ;; + sh*:Linux:*:*) + echo ${UNAME_MACHINE}-unknown-linux-gnu + exit ;; + sparc:Linux:*:* | sparc64:Linux:*:*) + echo ${UNAME_MACHINE}-unknown-linux-gnu + exit ;; + vax:Linux:*:*) + echo ${UNAME_MACHINE}-dec-linux-gnu + exit ;; + x86_64:Linux:*:*) + echo x86_64-unknown-linux-gnu + exit ;; + xtensa*:Linux:*:*) + echo ${UNAME_MACHINE}-unknown-linux-gnu + exit ;; + i*86:DYNIX/ptx:4*:*) + # ptx 4.0 does uname -s correctly, with DYNIX/ptx in there. + # earlier versions are messed up and put the nodename in both + # sysname and nodename. + echo i386-sequent-sysv4 + exit ;; + i*86:UNIX_SV:4.2MP:2.*) + # Unixware is an offshoot of SVR4, but it has its own version + # number series starting with 2... + # I am not positive that other SVR4 systems won't match this, + # I just have to hope. -- rms. + # Use sysv4.2uw... so that sysv4* matches it. + echo ${UNAME_MACHINE}-pc-sysv4.2uw${UNAME_VERSION} + exit ;; + i*86:OS/2:*:*) + # If we were able to find `uname', then EMX Unix compatibility + # is probably installed. + echo ${UNAME_MACHINE}-pc-os2-emx + exit ;; + i*86:XTS-300:*:STOP) + echo ${UNAME_MACHINE}-unknown-stop + exit ;; + i*86:atheos:*:*) + echo ${UNAME_MACHINE}-unknown-atheos + exit ;; + i*86:syllable:*:*) + echo ${UNAME_MACHINE}-pc-syllable + exit ;; + i*86:LynxOS:2.*:* | i*86:LynxOS:3.[01]*:* | i*86:LynxOS:4.[02]*:*) + echo i386-unknown-lynxos${UNAME_RELEASE} + exit ;; + i*86:*DOS:*:*) + echo ${UNAME_MACHINE}-pc-msdosdjgpp + exit ;; + i*86:*:4.*:* | i*86:SYSTEM_V:4.*:*) + UNAME_REL=`echo ${UNAME_RELEASE} | sed 's/\/MP$//'` + if grep Novell /usr/include/link.h >/dev/null 2>/dev/null; then + echo ${UNAME_MACHINE}-univel-sysv${UNAME_REL} + else + echo ${UNAME_MACHINE}-pc-sysv${UNAME_REL} + fi + exit ;; + i*86:*:5:[678]*) + # UnixWare 7.x, OpenUNIX and OpenServer 6. + case `/bin/uname -X | grep "^Machine"` in + *486*) UNAME_MACHINE=i486 ;; + *Pentium) UNAME_MACHINE=i586 ;; + *Pent*|*Celeron) UNAME_MACHINE=i686 ;; + esac + echo ${UNAME_MACHINE}-unknown-sysv${UNAME_RELEASE}${UNAME_SYSTEM}${UNAME_VERSION} + exit ;; + i*86:*:3.2:*) + if test -f /usr/options/cb.name; then + UNAME_REL=`sed -n 's/.*Version //p' /dev/null >/dev/null ; then + UNAME_REL=`(/bin/uname -X|grep Release|sed -e 's/.*= //')` + (/bin/uname -X|grep i80486 >/dev/null) && UNAME_MACHINE=i486 + (/bin/uname -X|grep '^Machine.*Pentium' >/dev/null) \ + && UNAME_MACHINE=i586 + (/bin/uname -X|grep '^Machine.*Pent *II' >/dev/null) \ + && UNAME_MACHINE=i686 + (/bin/uname -X|grep '^Machine.*Pentium Pro' >/dev/null) \ + && UNAME_MACHINE=i686 + echo ${UNAME_MACHINE}-pc-sco$UNAME_REL + else + echo ${UNAME_MACHINE}-pc-sysv32 + fi + exit ;; + pc:*:*:*) + # Left here for compatibility: + # uname -m prints for DJGPP always 'pc', but it prints nothing about + # the processor, so we play safe by assuming i586. + # Note: whatever this is, it MUST be the same as what config.sub + # prints for the "djgpp" host, or else GDB configury will decide that + # this is a cross-build. + echo i586-pc-msdosdjgpp + exit ;; + Intel:Mach:3*:*) + echo i386-pc-mach3 + exit ;; + paragon:*:*:*) + echo i860-intel-osf1 + exit ;; + i860:*:4.*:*) # i860-SVR4 + if grep Stardent /usr/include/sys/uadmin.h >/dev/null 2>&1 ; then + echo i860-stardent-sysv${UNAME_RELEASE} # Stardent Vistra i860-SVR4 + else # Add other i860-SVR4 vendors below as they are discovered. + echo i860-unknown-sysv${UNAME_RELEASE} # Unknown i860-SVR4 + fi + exit ;; + mini*:CTIX:SYS*5:*) + # "miniframe" + echo m68010-convergent-sysv + exit ;; + mc68k:UNIX:SYSTEM5:3.51m) + echo m68k-convergent-sysv + exit ;; + M680?0:D-NIX:5.3:*) + echo m68k-diab-dnix + exit ;; + M68*:*:R3V[5678]*:*) + test -r /sysV68 && { echo 'm68k-motorola-sysv'; exit; } ;; + 3[345]??:*:4.0:3.0 | 3[34]??A:*:4.0:3.0 | 3[34]??,*:*:4.0:3.0 | 3[34]??/*:*:4.0:3.0 | 4400:*:4.0:3.0 | 4850:*:4.0:3.0 | SKA40:*:4.0:3.0 | SDS2:*:4.0:3.0 | SHG2:*:4.0:3.0 | S7501*:*:4.0:3.0) + OS_REL='' + test -r /etc/.relid \ + && OS_REL=.`sed -n 's/[^ ]* [^ ]* \([0-9][0-9]\).*/\1/p' < /etc/.relid` + /bin/uname -p 2>/dev/null | grep 86 >/dev/null \ + && { echo i486-ncr-sysv4.3${OS_REL}; exit; } + /bin/uname -p 2>/dev/null | /bin/grep entium >/dev/null \ + && { echo i586-ncr-sysv4.3${OS_REL}; exit; } ;; + 3[34]??:*:4.0:* | 3[34]??,*:*:4.0:*) + /bin/uname -p 2>/dev/null | grep 86 >/dev/null \ + && { echo i486-ncr-sysv4; exit; } ;; + NCR*:*:4.2:* | MPRAS*:*:4.2:*) + OS_REL='.3' + test -r /etc/.relid \ + && OS_REL=.`sed -n 's/[^ ]* [^ ]* \([0-9][0-9]\).*/\1/p' < /etc/.relid` + /bin/uname -p 2>/dev/null | grep 86 >/dev/null \ + && { echo i486-ncr-sysv4.3${OS_REL}; exit; } + /bin/uname -p 2>/dev/null | /bin/grep entium >/dev/null \ + && { echo i586-ncr-sysv4.3${OS_REL}; exit; } + /bin/uname -p 2>/dev/null | /bin/grep pteron >/dev/null \ + && { echo i586-ncr-sysv4.3${OS_REL}; exit; } ;; + m68*:LynxOS:2.*:* | m68*:LynxOS:3.0*:*) + echo m68k-unknown-lynxos${UNAME_RELEASE} + exit ;; + mc68030:UNIX_System_V:4.*:*) + echo m68k-atari-sysv4 + exit ;; + TSUNAMI:LynxOS:2.*:*) + echo sparc-unknown-lynxos${UNAME_RELEASE} + exit ;; + rs6000:LynxOS:2.*:*) + echo rs6000-unknown-lynxos${UNAME_RELEASE} + exit ;; + PowerPC:LynxOS:2.*:* | PowerPC:LynxOS:3.[01]*:* | PowerPC:LynxOS:4.[02]*:*) + echo powerpc-unknown-lynxos${UNAME_RELEASE} + exit ;; + SM[BE]S:UNIX_SV:*:*) + echo mips-dde-sysv${UNAME_RELEASE} + exit ;; + RM*:ReliantUNIX-*:*:*) + echo mips-sni-sysv4 + exit ;; + RM*:SINIX-*:*:*) + echo mips-sni-sysv4 + exit ;; + *:SINIX-*:*:*) + if uname -p 2>/dev/null >/dev/null ; then + UNAME_MACHINE=`(uname -p) 2>/dev/null` + echo ${UNAME_MACHINE}-sni-sysv4 + else + echo ns32k-sni-sysv + fi + exit ;; + PENTIUM:*:4.0*:*) # Unisys `ClearPath HMP IX 4000' SVR4/MP effort + # says + echo i586-unisys-sysv4 + exit ;; + *:UNIX_System_V:4*:FTX*) + # From Gerald Hewes . + # How about differentiating between stratus architectures? -djm + echo hppa1.1-stratus-sysv4 + exit ;; + *:*:*:FTX*) + # From seanf@swdc.stratus.com. + echo i860-stratus-sysv4 + exit ;; + i*86:VOS:*:*) + # From Paul.Green@stratus.com. + echo ${UNAME_MACHINE}-stratus-vos + exit ;; + *:VOS:*:*) + # From Paul.Green@stratus.com. + echo hppa1.1-stratus-vos + exit ;; + mc68*:A/UX:*:*) + echo m68k-apple-aux${UNAME_RELEASE} + exit ;; + news*:NEWS-OS:6*:*) + echo mips-sony-newsos6 + exit ;; + R[34]000:*System_V*:*:* | R4000:UNIX_SYSV:*:* | R*000:UNIX_SV:*:*) + if [ -d /usr/nec ]; then + echo mips-nec-sysv${UNAME_RELEASE} + else + echo mips-unknown-sysv${UNAME_RELEASE} + fi + exit ;; + BeBox:BeOS:*:*) # BeOS running on hardware made by Be, PPC only. + echo powerpc-be-beos + exit ;; + BeMac:BeOS:*:*) # BeOS running on Mac or Mac clone, PPC only. + echo powerpc-apple-beos + exit ;; + BePC:BeOS:*:*) # BeOS running on Intel PC compatible. + echo i586-pc-beos + exit ;; + BePC:Haiku:*:*) # Haiku running on Intel PC compatible. + echo i586-pc-haiku + exit ;; + SX-4:SUPER-UX:*:*) + echo sx4-nec-superux${UNAME_RELEASE} + exit ;; + SX-5:SUPER-UX:*:*) + echo sx5-nec-superux${UNAME_RELEASE} + exit ;; + SX-6:SUPER-UX:*:*) + echo sx6-nec-superux${UNAME_RELEASE} + exit ;; + SX-7:SUPER-UX:*:*) + echo sx7-nec-superux${UNAME_RELEASE} + exit ;; + SX-8:SUPER-UX:*:*) + echo sx8-nec-superux${UNAME_RELEASE} + exit ;; + SX-8R:SUPER-UX:*:*) + echo sx8r-nec-superux${UNAME_RELEASE} + exit ;; + Power*:Rhapsody:*:*) + echo powerpc-apple-rhapsody${UNAME_RELEASE} + exit ;; + *:Rhapsody:*:*) + echo ${UNAME_MACHINE}-apple-rhapsody${UNAME_RELEASE} + exit ;; + *:Darwin:*:*) + UNAME_PROCESSOR=`uname -p` || UNAME_PROCESSOR=unknown + case $UNAME_PROCESSOR in + i386) + eval $set_cc_for_build + if [ "$CC_FOR_BUILD" != 'no_compiler_found' ]; then + if (echo '#ifdef __LP64__'; echo IS_64BIT_ARCH; echo '#endif') | \ + (CCOPTS= $CC_FOR_BUILD -E - 2>/dev/null) | \ + grep IS_64BIT_ARCH >/dev/null + then + UNAME_PROCESSOR="x86_64" + fi + fi ;; + unknown) UNAME_PROCESSOR=powerpc ;; + esac + echo ${UNAME_PROCESSOR}-apple-darwin${UNAME_RELEASE} + exit ;; + *:procnto*:*:* | *:QNX:[0123456789]*:*) + UNAME_PROCESSOR=`uname -p` + if test "$UNAME_PROCESSOR" = "x86"; then + UNAME_PROCESSOR=i386 + UNAME_MACHINE=pc + fi + echo ${UNAME_PROCESSOR}-${UNAME_MACHINE}-nto-qnx${UNAME_RELEASE} + exit ;; + *:QNX:*:4*) + echo i386-pc-qnx + exit ;; + NSE-?:NONSTOP_KERNEL:*:*) + echo nse-tandem-nsk${UNAME_RELEASE} + exit ;; + NSR-?:NONSTOP_KERNEL:*:*) + echo nsr-tandem-nsk${UNAME_RELEASE} + exit ;; + *:NonStop-UX:*:*) + echo mips-compaq-nonstopux + exit ;; + BS2000:POSIX*:*:*) + echo bs2000-siemens-sysv + exit ;; + DS/*:UNIX_System_V:*:*) + echo ${UNAME_MACHINE}-${UNAME_SYSTEM}-${UNAME_RELEASE} + exit ;; + *:Plan9:*:*) + # "uname -m" is not consistent, so use $cputype instead. 386 + # is converted to i386 for consistency with other x86 + # operating systems. + if test "$cputype" = "386"; then + UNAME_MACHINE=i386 + else + UNAME_MACHINE="$cputype" + fi + echo ${UNAME_MACHINE}-unknown-plan9 + exit ;; + *:TOPS-10:*:*) + echo pdp10-unknown-tops10 + exit ;; + *:TENEX:*:*) + echo pdp10-unknown-tenex + exit ;; + KS10:TOPS-20:*:* | KL10:TOPS-20:*:* | TYPE4:TOPS-20:*:*) + echo pdp10-dec-tops20 + exit ;; + XKL-1:TOPS-20:*:* | TYPE5:TOPS-20:*:*) + echo pdp10-xkl-tops20 + exit ;; + *:TOPS-20:*:*) + echo pdp10-unknown-tops20 + exit ;; + *:ITS:*:*) + echo pdp10-unknown-its + exit ;; + SEI:*:*:SEIUX) + echo mips-sei-seiux${UNAME_RELEASE} + exit ;; + *:DragonFly:*:*) + echo ${UNAME_MACHINE}-unknown-dragonfly`echo ${UNAME_RELEASE}|sed -e 's/[-(].*//'` + exit ;; + *:*VMS:*:*) + UNAME_MACHINE=`(uname -p) 2>/dev/null` + case "${UNAME_MACHINE}" in + A*) echo alpha-dec-vms ; exit ;; + I*) echo ia64-dec-vms ; exit ;; + V*) echo vax-dec-vms ; exit ;; + esac ;; + *:XENIX:*:SysV) + echo i386-pc-xenix + exit ;; + i*86:skyos:*:*) + echo ${UNAME_MACHINE}-pc-skyos`echo ${UNAME_RELEASE}` | sed -e 's/ .*$//' + exit ;; + i*86:rdos:*:*) + echo ${UNAME_MACHINE}-pc-rdos + exit ;; + i*86:AROS:*:*) + echo ${UNAME_MACHINE}-pc-aros + exit ;; +esac + +#echo '(No uname command or uname output not recognized.)' 1>&2 +#echo "${UNAME_MACHINE}:${UNAME_SYSTEM}:${UNAME_RELEASE}:${UNAME_VERSION}" 1>&2 + +eval $set_cc_for_build +cat >$dummy.c < +# include +#endif +main () +{ +#if defined (sony) +#if defined (MIPSEB) + /* BFD wants "bsd" instead of "newsos". Perhaps BFD should be changed, + I don't know.... */ + printf ("mips-sony-bsd\n"); exit (0); +#else +#include + printf ("m68k-sony-newsos%s\n", +#ifdef NEWSOS4 + "4" +#else + "" +#endif + ); exit (0); +#endif +#endif + +#if defined (__arm) && defined (__acorn) && defined (__unix) + printf ("arm-acorn-riscix\n"); exit (0); +#endif + +#if defined (hp300) && !defined (hpux) + printf ("m68k-hp-bsd\n"); exit (0); +#endif + +#if defined (NeXT) +#if !defined (__ARCHITECTURE__) +#define __ARCHITECTURE__ "m68k" +#endif + int version; + version=`(hostinfo | sed -n 's/.*NeXT Mach \([0-9]*\).*/\1/p') 2>/dev/null`; + if (version < 4) + printf ("%s-next-nextstep%d\n", __ARCHITECTURE__, version); + else + printf ("%s-next-openstep%d\n", __ARCHITECTURE__, version); + exit (0); +#endif + +#if defined (MULTIMAX) || defined (n16) +#if defined (UMAXV) + printf ("ns32k-encore-sysv\n"); exit (0); +#else +#if defined (CMU) + printf ("ns32k-encore-mach\n"); exit (0); +#else + printf ("ns32k-encore-bsd\n"); exit (0); +#endif +#endif +#endif + +#if defined (__386BSD__) + printf ("i386-pc-bsd\n"); exit (0); +#endif + +#if defined (sequent) +#if defined (i386) + printf ("i386-sequent-dynix\n"); exit (0); +#endif +#if defined (ns32000) + printf ("ns32k-sequent-dynix\n"); exit (0); +#endif +#endif + +#if defined (_SEQUENT_) + struct utsname un; + + uname(&un); + + if (strncmp(un.version, "V2", 2) == 0) { + printf ("i386-sequent-ptx2\n"); exit (0); + } + if (strncmp(un.version, "V1", 2) == 0) { /* XXX is V1 correct? */ + printf ("i386-sequent-ptx1\n"); exit (0); + } + printf ("i386-sequent-ptx\n"); exit (0); + +#endif + +#if defined (vax) +# if !defined (ultrix) +# include +# if defined (BSD) +# if BSD == 43 + printf ("vax-dec-bsd4.3\n"); exit (0); +# else +# if BSD == 199006 + printf ("vax-dec-bsd4.3reno\n"); exit (0); +# else + printf ("vax-dec-bsd\n"); exit (0); +# endif +# endif +# else + printf ("vax-dec-bsd\n"); exit (0); +# endif +# else + printf ("vax-dec-ultrix\n"); exit (0); +# endif +#endif + +#if defined (alliant) && defined (i860) + printf ("i860-alliant-bsd\n"); exit (0); +#endif + + exit (1); +} +EOF + +$CC_FOR_BUILD -o $dummy $dummy.c 2>/dev/null && SYSTEM_NAME=`$dummy` && + { echo "$SYSTEM_NAME"; exit; } + +# Apollos put the system type in the environment. + +test -d /usr/apollo && { echo ${ISP}-apollo-${SYSTYPE}; exit; } + +# Convex versions that predate uname can use getsysinfo(1) + +if [ -x /usr/convex/getsysinfo ] +then + case `getsysinfo -f cpu_type` in + c1*) + echo c1-convex-bsd + exit ;; + c2*) + if getsysinfo -f scalar_acc + then echo c32-convex-bsd + else echo c2-convex-bsd + fi + exit ;; + c34*) + echo c34-convex-bsd + exit ;; + c38*) + echo c38-convex-bsd + exit ;; + c4*) + echo c4-convex-bsd + exit ;; + esac +fi + +cat >&2 < in order to provide the needed +information to handle your system. + +config.guess timestamp = $timestamp + +uname -m = `(uname -m) 2>/dev/null || echo unknown` +uname -r = `(uname -r) 2>/dev/null || echo unknown` +uname -s = `(uname -s) 2>/dev/null || echo unknown` +uname -v = `(uname -v) 2>/dev/null || echo unknown` + +/usr/bin/uname -p = `(/usr/bin/uname -p) 2>/dev/null` +/bin/uname -X = `(/bin/uname -X) 2>/dev/null` + +hostinfo = `(hostinfo) 2>/dev/null` +/bin/universe = `(/bin/universe) 2>/dev/null` +/usr/bin/arch -k = `(/usr/bin/arch -k) 2>/dev/null` +/bin/arch = `(/bin/arch) 2>/dev/null` +/usr/bin/oslevel = `(/usr/bin/oslevel) 2>/dev/null` +/usr/convex/getsysinfo = `(/usr/convex/getsysinfo) 2>/dev/null` + +UNAME_MACHINE = ${UNAME_MACHINE} +UNAME_RELEASE = ${UNAME_RELEASE} +UNAME_SYSTEM = ${UNAME_SYSTEM} +UNAME_VERSION = ${UNAME_VERSION} +EOF + +exit 1 + +# Local variables: +# eval: (add-hook 'write-file-hooks 'time-stamp) +# time-stamp-start: "timestamp='" +# time-stamp-format: "%:y-%02m-%02d" +# time-stamp-end: "'" +# End: diff --git a/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/config.sub b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/config.sub new file mode 100755 index 0000000000..c2d125724c --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/config.sub @@ -0,0 +1,1714 @@ +#! /bin/sh +# Configuration validation subroutine script. +# Copyright (C) 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, +# 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010 +# Free Software Foundation, Inc. + +timestamp='2010-01-22' + +# This file is (in principle) common to ALL GNU software. +# The presence of a machine in this file suggests that SOME GNU software +# can handle that machine. It does not imply ALL GNU software can. +# +# This file is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program; if not, write to the Free Software +# Foundation, Inc., 51 Franklin Street - Fifth Floor, Boston, MA +# 02110-1301, USA. +# +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program that contains a +# configuration script generated by Autoconf, you may include it under +# the same distribution terms that you use for the rest of that program. + + +# Please send patches to . Submit a context +# diff and a properly formatted GNU ChangeLog entry. +# +# Configuration subroutine to validate and canonicalize a configuration type. +# Supply the specified configuration type as an argument. +# If it is invalid, we print an error message on stderr and exit with code 1. +# Otherwise, we print the canonical config type on stdout and succeed. + +# You can get the latest version of this script from: +# http://git.savannah.gnu.org/gitweb/?p=config.git;a=blob_plain;f=config.sub;hb=HEAD + +# This file is supposed to be the same for all GNU packages +# and recognize all the CPU types, system types and aliases +# that are meaningful with *any* GNU software. +# Each package is responsible for reporting which valid configurations +# it does not support. The user should be able to distinguish +# a failure to support a valid configuration from a meaningless +# configuration. + +# The goal of this file is to map all the various variations of a given +# machine specification into a single specification in the form: +# CPU_TYPE-MANUFACTURER-OPERATING_SYSTEM +# or in some cases, the newer four-part form: +# CPU_TYPE-MANUFACTURER-KERNEL-OPERATING_SYSTEM +# It is wrong to echo any other type of specification. + +me=`echo "$0" | sed -e 's,.*/,,'` + +usage="\ +Usage: $0 [OPTION] CPU-MFR-OPSYS + $0 [OPTION] ALIAS + +Canonicalize a configuration name. + +Operation modes: + -h, --help print this help, then exit + -t, --time-stamp print date of last modification, then exit + -v, --version print version number, then exit + +Report bugs and patches to ." + +version="\ +GNU config.sub ($timestamp) + +Copyright (C) 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, 2000, +2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010 Free +Software Foundation, Inc. + +This is free software; see the source for copying conditions. There is NO +warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE." + +help=" +Try \`$me --help' for more information." + +# Parse command line +while test $# -gt 0 ; do + case $1 in + --time-stamp | --time* | -t ) + echo "$timestamp" ; exit ;; + --version | -v ) + echo "$version" ; exit ;; + --help | --h* | -h ) + echo "$usage"; exit ;; + -- ) # Stop option processing + shift; break ;; + - ) # Use stdin as input. + break ;; + -* ) + echo "$me: invalid option $1$help" + exit 1 ;; + + *local*) + # First pass through any local machine types. + echo $1 + exit ;; + + * ) + break ;; + esac +done + +case $# in + 0) echo "$me: missing argument$help" >&2 + exit 1;; + 1) ;; + *) echo "$me: too many arguments$help" >&2 + exit 1;; +esac + +# Separate what the user gave into CPU-COMPANY and OS or KERNEL-OS (if any). +# Here we must recognize all the valid KERNEL-OS combinations. +maybe_os=`echo $1 | sed 's/^\(.*\)-\([^-]*-[^-]*\)$/\2/'` +case $maybe_os in + nto-qnx* | linux-gnu* | linux-dietlibc | linux-newlib* | linux-uclibc* | \ + uclinux-uclibc* | uclinux-gnu* | kfreebsd*-gnu* | knetbsd*-gnu* | netbsd*-gnu* | \ + kopensolaris*-gnu* | \ + storm-chaos* | os2-emx* | rtmk-nova*) + os=-$maybe_os + basic_machine=`echo $1 | sed 's/^\(.*\)-\([^-]*-[^-]*\)$/\1/'` + ;; + *) + basic_machine=`echo $1 | sed 's/-[^-]*$//'` + if [ $basic_machine != $1 ] + then os=`echo $1 | sed 's/.*-/-/'` + else os=; fi + ;; +esac + +### Let's recognize common machines as not being operating systems so +### that things like config.sub decstation-3100 work. We also +### recognize some manufacturers as not being operating systems, so we +### can provide default operating systems below. +case $os in + -sun*os*) + # Prevent following clause from handling this invalid input. + ;; + -dec* | -mips* | -sequent* | -encore* | -pc532* | -sgi* | -sony* | \ + -att* | -7300* | -3300* | -delta* | -motorola* | -sun[234]* | \ + -unicom* | -ibm* | -next | -hp | -isi* | -apollo | -altos* | \ + -convergent* | -ncr* | -news | -32* | -3600* | -3100* | -hitachi* |\ + -c[123]* | -convex* | -sun | -crds | -omron* | -dg | -ultra | -tti* | \ + -harris | -dolphin | -highlevel | -gould | -cbm | -ns | -masscomp | \ + -apple | -axis | -knuth | -cray | -microblaze) + os= + basic_machine=$1 + ;; + -bluegene*) + os=-cnk + ;; + -sim | -cisco | -oki | -wec | -winbond) + os= + basic_machine=$1 + ;; + -scout) + ;; + -wrs) + os=-vxworks + basic_machine=$1 + ;; + -chorusos*) + os=-chorusos + basic_machine=$1 + ;; + -chorusrdb) + os=-chorusrdb + basic_machine=$1 + ;; + -hiux*) + os=-hiuxwe2 + ;; + -sco6) + os=-sco5v6 + basic_machine=`echo $1 | sed -e 's/86-.*/86-pc/'` + ;; + -sco5) + os=-sco3.2v5 + basic_machine=`echo $1 | sed -e 's/86-.*/86-pc/'` + ;; + -sco4) + os=-sco3.2v4 + basic_machine=`echo $1 | sed -e 's/86-.*/86-pc/'` + ;; + -sco3.2.[4-9]*) + os=`echo $os | sed -e 's/sco3.2./sco3.2v/'` + basic_machine=`echo $1 | sed -e 's/86-.*/86-pc/'` + ;; + -sco3.2v[4-9]*) + # Don't forget version if it is 3.2v4 or newer. + basic_machine=`echo $1 | sed -e 's/86-.*/86-pc/'` + ;; + -sco5v6*) + # Don't forget version if it is 3.2v4 or newer. + basic_machine=`echo $1 | sed -e 's/86-.*/86-pc/'` + ;; + -sco*) + os=-sco3.2v2 + basic_machine=`echo $1 | sed -e 's/86-.*/86-pc/'` + ;; + -udk*) + basic_machine=`echo $1 | sed -e 's/86-.*/86-pc/'` + ;; + -isc) + os=-isc2.2 + basic_machine=`echo $1 | sed -e 's/86-.*/86-pc/'` + ;; + -clix*) + basic_machine=clipper-intergraph + ;; + -isc*) + basic_machine=`echo $1 | sed -e 's/86-.*/86-pc/'` + ;; + -lynx*) + os=-lynxos + ;; + -ptx*) + basic_machine=`echo $1 | sed -e 's/86-.*/86-sequent/'` + ;; + -windowsnt*) + os=`echo $os | sed -e 's/windowsnt/winnt/'` + ;; + -psos*) + os=-psos + ;; + -mint | -mint[0-9]*) + basic_machine=m68k-atari + os=-mint + ;; +esac + +# Decode aliases for certain CPU-COMPANY combinations. +case $basic_machine in + # Recognize the basic CPU types without company name. + # Some are omitted here because they have special meanings below. + 1750a | 580 \ + | a29k \ + | alpha | alphaev[4-8] | alphaev56 | alphaev6[78] | alphapca5[67] \ + | alpha64 | alpha64ev[4-8] | alpha64ev56 | alpha64ev6[78] | alpha64pca5[67] \ + | am33_2.0 \ + | arc | arm | arm[bl]e | arme[lb] | armv[2345] | armv[345][lb] | avr | avr32 \ + | bfin \ + | c4x | clipper \ + | d10v | d30v | dlx | dsp16xx \ + | fido | fr30 | frv \ + | h8300 | h8500 | hppa | hppa1.[01] | hppa2.0 | hppa2.0[nw] | hppa64 \ + | i370 | i860 | i960 | ia64 \ + | ip2k | iq2000 \ + | lm32 \ + | m32c | m32r | m32rle | m68000 | m68k | m88k \ + | maxq | mb | microblaze | mcore | mep | metag \ + | mips | mipsbe | mipseb | mipsel | mipsle \ + | mips16 \ + | mips64 | mips64el \ + | mips64octeon | mips64octeonel \ + | mips64orion | mips64orionel \ + | mips64r5900 | mips64r5900el \ + | mips64vr | mips64vrel \ + | mips64vr4100 | mips64vr4100el \ + | mips64vr4300 | mips64vr4300el \ + | mips64vr5000 | mips64vr5000el \ + | mips64vr5900 | mips64vr5900el \ + | mipsisa32 | mipsisa32el \ + | mipsisa32r2 | mipsisa32r2el \ + | mipsisa64 | mipsisa64el \ + | mipsisa64r2 | mipsisa64r2el \ + | mipsisa64sb1 | mipsisa64sb1el \ + | mipsisa64sr71k | mipsisa64sr71kel \ + | mipstx39 | mipstx39el \ + | mn10200 | mn10300 \ + | moxie \ + | mt \ + | msp430 \ + | nios | nios2 \ + | ns16k | ns32k \ + | or32 \ + | pdp10 | pdp11 | pj | pjl \ + | powerpc | powerpc64 | powerpc64le | powerpcle | ppcbe \ + | pyramid \ + | rx \ + | score \ + | sh | sh[1234] | sh[24]a | sh[24]aeb | sh[23]e | sh[34]eb | sheb | shbe | shle | sh[1234]le | sh3ele \ + | sh64 | sh64le \ + | sparc | sparc64 | sparc64b | sparc64v | sparc86x | sparclet | sparclite \ + | sparcv8 | sparcv9 | sparcv9b | sparcv9v \ + | spu | strongarm \ + | tahoe | thumb | tic4x | tic80 | tron \ + | ubicom32 \ + | v850 | v850e \ + | we32k \ + | x86 | xc16x | xscale | xscalee[bl] | xstormy16 | xtensa \ + | z8k | z80) + basic_machine=$basic_machine-unknown + ;; + m6811 | m68hc11 | m6812 | m68hc12 | picochip) + # Motorola 68HC11/12. + basic_machine=$basic_machine-unknown + os=-none + ;; + m88110 | m680[12346]0 | m683?2 | m68360 | m5200 | v70 | w65 | z8k) + ;; + ms1) + basic_machine=mt-unknown + ;; + + # We use `pc' rather than `unknown' + # because (1) that's what they normally are, and + # (2) the word "unknown" tends to confuse beginning users. + i*86 | x86_64) + basic_machine=$basic_machine-pc + ;; + # Object if more than one company name word. + *-*-*) + echo Invalid configuration \`$1\': machine \`$basic_machine\' not recognized 1>&2 + exit 1 + ;; + # Recognize the basic CPU types with company name. + 580-* \ + | a29k-* \ + | alpha-* | alphaev[4-8]-* | alphaev56-* | alphaev6[78]-* \ + | alpha64-* | alpha64ev[4-8]-* | alpha64ev56-* | alpha64ev6[78]-* \ + | alphapca5[67]-* | alpha64pca5[67]-* | arc-* \ + | arm-* | armbe-* | armle-* | armeb-* | armv*-* \ + | avr-* | avr32-* \ + | bfin-* | bs2000-* \ + | c[123]* | c30-* | [cjt]90-* | c4x-* | c54x-* | c55x-* | c6x-* \ + | clipper-* | craynv-* | cydra-* \ + | d10v-* | d30v-* | dlx-* \ + | elxsi-* \ + | f30[01]-* | f700-* | fido-* | fr30-* | frv-* | fx80-* \ + | h8300-* | h8500-* \ + | hppa-* | hppa1.[01]-* | hppa2.0-* | hppa2.0[nw]-* | hppa64-* \ + | i*86-* | i860-* | i960-* | ia64-* \ + | ip2k-* | iq2000-* \ + | lm32-* \ + | m32c-* | m32r-* | m32rle-* \ + | m68000-* | m680[012346]0-* | m68360-* | m683?2-* | m68k-* \ + | m88110-* | m88k-* | maxq-* | mcore-* | metag-* | microblaze-* \ + | mips-* | mipsbe-* | mipseb-* | mipsel-* | mipsle-* \ + | mips16-* \ + | mips64-* | mips64el-* \ + | mips64octeon-* | mips64octeonel-* \ + | mips64orion-* | mips64orionel-* \ + | mips64r5900-* | mips64r5900el-* \ + | mips64vr-* | mips64vrel-* \ + | mips64vr4100-* | mips64vr4100el-* \ + | mips64vr4300-* | mips64vr4300el-* \ + | mips64vr5000-* | mips64vr5000el-* \ + | mips64vr5900-* | mips64vr5900el-* \ + | mipsisa32-* | mipsisa32el-* \ + | mipsisa32r2-* | mipsisa32r2el-* \ + | mipsisa64-* | mipsisa64el-* \ + | mipsisa64r2-* | mipsisa64r2el-* \ + | mipsisa64sb1-* | mipsisa64sb1el-* \ + | mipsisa64sr71k-* | mipsisa64sr71kel-* \ + | mipstx39-* | mipstx39el-* \ + | mmix-* \ + | mt-* \ + | msp430-* \ + | nios-* | nios2-* \ + | none-* | np1-* | ns16k-* | ns32k-* \ + | orion-* \ + | pdp10-* | pdp11-* | pj-* | pjl-* | pn-* | power-* \ + | powerpc-* | powerpc64-* | powerpc64le-* | powerpcle-* | ppcbe-* \ + | pyramid-* \ + | romp-* | rs6000-* | rx-* \ + | sh-* | sh[1234]-* | sh[24]a-* | sh[24]aeb-* | sh[23]e-* | sh[34]eb-* | sheb-* | shbe-* \ + | shle-* | sh[1234]le-* | sh3ele-* | sh64-* | sh64le-* \ + | sparc-* | sparc64-* | sparc64b-* | sparc64v-* | sparc86x-* | sparclet-* \ + | sparclite-* \ + | sparcv8-* | sparcv9-* | sparcv9b-* | sparcv9v-* | strongarm-* | sv1-* | sx?-* \ + | tahoe-* | thumb-* \ + | tic30-* | tic4x-* | tic54x-* | tic55x-* | tic6x-* | tic80-* \ + | tile-* | tilegx-* \ + | tron-* \ + | ubicom32-* \ + | v850-* | v850e-* | vax-* \ + | we32k-* \ + | x86-* | x86_64-* | xc16x-* | xps100-* | xscale-* | xscalee[bl]-* \ + | xstormy16-* | xtensa*-* \ + | ymp-* \ + | z8k-* | z80-*) + ;; + # Recognize the basic CPU types without company name, with glob match. + xtensa*) + basic_machine=$basic_machine-unknown + ;; + # Recognize the various machine names and aliases which stand + # for a CPU type and a company and sometimes even an OS. + 386bsd) + basic_machine=i386-unknown + os=-bsd + ;; + 3b1 | 7300 | 7300-att | att-7300 | pc7300 | safari | unixpc) + basic_machine=m68000-att + ;; + 3b*) + basic_machine=we32k-att + ;; + a29khif) + basic_machine=a29k-amd + os=-udi + ;; + abacus) + basic_machine=abacus-unknown + ;; + adobe68k) + basic_machine=m68010-adobe + os=-scout + ;; + alliant | fx80) + basic_machine=fx80-alliant + ;; + altos | altos3068) + basic_machine=m68k-altos + ;; + am29k) + basic_machine=a29k-none + os=-bsd + ;; + amd64) + basic_machine=x86_64-pc + ;; + amd64-*) + basic_machine=x86_64-`echo $basic_machine | sed 's/^[^-]*-//'` + ;; + amdahl) + basic_machine=580-amdahl + os=-sysv + ;; + amiga | amiga-*) + basic_machine=m68k-unknown + ;; + amigaos | amigados) + basic_machine=m68k-unknown + os=-amigaos + ;; + amigaunix | amix) + basic_machine=m68k-unknown + os=-sysv4 + ;; + apollo68) + basic_machine=m68k-apollo + os=-sysv + ;; + apollo68bsd) + basic_machine=m68k-apollo + os=-bsd + ;; + aros) + basic_machine=i386-pc + os=-aros + ;; + aux) + basic_machine=m68k-apple + os=-aux + ;; + balance) + basic_machine=ns32k-sequent + os=-dynix + ;; + blackfin) + basic_machine=bfin-unknown + os=-linux + ;; + blackfin-*) + basic_machine=bfin-`echo $basic_machine | sed 's/^[^-]*-//'` + os=-linux + ;; + bluegene*) + basic_machine=powerpc-ibm + os=-cnk + ;; + c90) + basic_machine=c90-cray + os=-unicos + ;; + cegcc) + basic_machine=arm-unknown + os=-cegcc + ;; + convex-c1) + basic_machine=c1-convex + os=-bsd + ;; + convex-c2) + basic_machine=c2-convex + os=-bsd + ;; + convex-c32) + basic_machine=c32-convex + os=-bsd + ;; + convex-c34) + basic_machine=c34-convex + os=-bsd + ;; + convex-c38) + basic_machine=c38-convex + os=-bsd + ;; + cray | j90) + basic_machine=j90-cray + os=-unicos + ;; + craynv) + basic_machine=craynv-cray + os=-unicosmp + ;; + cr16) + basic_machine=cr16-unknown + os=-elf + ;; + crds | unos) + basic_machine=m68k-crds + ;; + crisv32 | crisv32-* | etraxfs*) + basic_machine=crisv32-axis + ;; + cris | cris-* | etrax*) + basic_machine=cris-axis + ;; + crx) + basic_machine=crx-unknown + os=-elf + ;; + da30 | da30-*) + basic_machine=m68k-da30 + ;; + decstation | decstation-3100 | pmax | pmax-* | pmin | dec3100 | decstatn) + basic_machine=mips-dec + ;; + decsystem10* | dec10*) + basic_machine=pdp10-dec + os=-tops10 + ;; + decsystem20* | dec20*) + basic_machine=pdp10-dec + os=-tops20 + ;; + delta | 3300 | motorola-3300 | motorola-delta \ + | 3300-motorola | delta-motorola) + basic_machine=m68k-motorola + ;; + delta88) + basic_machine=m88k-motorola + os=-sysv3 + ;; + dicos) + basic_machine=i686-pc + os=-dicos + ;; + djgpp) + basic_machine=i586-pc + os=-msdosdjgpp + ;; + dpx20 | dpx20-*) + basic_machine=rs6000-bull + os=-bosx + ;; + dpx2* | dpx2*-bull) + basic_machine=m68k-bull + os=-sysv3 + ;; + ebmon29k) + basic_machine=a29k-amd + os=-ebmon + ;; + elxsi) + basic_machine=elxsi-elxsi + os=-bsd + ;; + encore | umax | mmax) + basic_machine=ns32k-encore + ;; + es1800 | OSE68k | ose68k | ose | OSE) + basic_machine=m68k-ericsson + os=-ose + ;; + fx2800) + basic_machine=i860-alliant + ;; + genix) + basic_machine=ns32k-ns + ;; + gmicro) + basic_machine=tron-gmicro + os=-sysv + ;; + go32) + basic_machine=i386-pc + os=-go32 + ;; + h3050r* | hiux*) + basic_machine=hppa1.1-hitachi + os=-hiuxwe2 + ;; + h8300hms) + basic_machine=h8300-hitachi + os=-hms + ;; + h8300xray) + basic_machine=h8300-hitachi + os=-xray + ;; + h8500hms) + basic_machine=h8500-hitachi + os=-hms + ;; + harris) + basic_machine=m88k-harris + os=-sysv3 + ;; + hp300-*) + basic_machine=m68k-hp + ;; + hp300bsd) + basic_machine=m68k-hp + os=-bsd + ;; + hp300hpux) + basic_machine=m68k-hp + os=-hpux + ;; + hp3k9[0-9][0-9] | hp9[0-9][0-9]) + basic_machine=hppa1.0-hp + ;; + hp9k2[0-9][0-9] | hp9k31[0-9]) + basic_machine=m68000-hp + ;; + hp9k3[2-9][0-9]) + basic_machine=m68k-hp + ;; + hp9k6[0-9][0-9] | hp6[0-9][0-9]) + basic_machine=hppa1.0-hp + ;; + hp9k7[0-79][0-9] | hp7[0-79][0-9]) + basic_machine=hppa1.1-hp + ;; + hp9k78[0-9] | hp78[0-9]) + # FIXME: really hppa2.0-hp + basic_machine=hppa1.1-hp + ;; + hp9k8[67]1 | hp8[67]1 | hp9k80[24] | hp80[24] | hp9k8[78]9 | hp8[78]9 | hp9k893 | hp893) + # FIXME: really hppa2.0-hp + basic_machine=hppa1.1-hp + ;; + hp9k8[0-9][13679] | hp8[0-9][13679]) + basic_machine=hppa1.1-hp + ;; + hp9k8[0-9][0-9] | hp8[0-9][0-9]) + basic_machine=hppa1.0-hp + ;; + hppa-next) + os=-nextstep3 + ;; + hppaosf) + basic_machine=hppa1.1-hp + os=-osf + ;; + hppro) + basic_machine=hppa1.1-hp + os=-proelf + ;; + i370-ibm* | ibm*) + basic_machine=i370-ibm + ;; +# I'm not sure what "Sysv32" means. Should this be sysv3.2? + i*86v32) + basic_machine=`echo $1 | sed -e 's/86.*/86-pc/'` + os=-sysv32 + ;; + i*86v4*) + basic_machine=`echo $1 | sed -e 's/86.*/86-pc/'` + os=-sysv4 + ;; + i*86v) + basic_machine=`echo $1 | sed -e 's/86.*/86-pc/'` + os=-sysv + ;; + i*86sol2) + basic_machine=`echo $1 | sed -e 's/86.*/86-pc/'` + os=-solaris2 + ;; + i386mach) + basic_machine=i386-mach + os=-mach + ;; + i386-vsta | vsta) + basic_machine=i386-unknown + os=-vsta + ;; + iris | iris4d) + basic_machine=mips-sgi + case $os in + -irix*) + ;; + *) + os=-irix4 + ;; + esac + ;; + isi68 | isi) + basic_machine=m68k-isi + os=-sysv + ;; + m68knommu) + basic_machine=m68k-unknown + os=-linux + ;; + m68knommu-*) + basic_machine=m68k-`echo $basic_machine | sed 's/^[^-]*-//'` + os=-linux + ;; + m88k-omron*) + basic_machine=m88k-omron + ;; + magnum | m3230) + basic_machine=mips-mips + os=-sysv + ;; + merlin) + basic_machine=ns32k-utek + os=-sysv + ;; + microblaze) + basic_machine=microblaze-xilinx + ;; + mingw32) + basic_machine=i386-pc + os=-mingw32 + ;; + mingw32ce) + basic_machine=arm-unknown + os=-mingw32ce + ;; + miniframe) + basic_machine=m68000-convergent + ;; + *mint | -mint[0-9]* | *MiNT | *MiNT[0-9]*) + basic_machine=m68k-atari + os=-mint + ;; + mips3*-*) + basic_machine=`echo $basic_machine | sed -e 's/mips3/mips64/'` + ;; + mips3*) + basic_machine=`echo $basic_machine | sed -e 's/mips3/mips64/'`-unknown + ;; + monitor) + basic_machine=m68k-rom68k + os=-coff + ;; + morphos) + basic_machine=powerpc-unknown + os=-morphos + ;; + msdos) + basic_machine=i386-pc + os=-msdos + ;; + ms1-*) + basic_machine=`echo $basic_machine | sed -e 's/ms1-/mt-/'` + ;; + mvs) + basic_machine=i370-ibm + os=-mvs + ;; + ncr3000) + basic_machine=i486-ncr + os=-sysv4 + ;; + netbsd386) + basic_machine=i386-unknown + os=-netbsd + ;; + netwinder) + basic_machine=armv4l-rebel + os=-linux + ;; + news | news700 | news800 | news900) + basic_machine=m68k-sony + os=-newsos + ;; + news1000) + basic_machine=m68030-sony + os=-newsos + ;; + news-3600 | risc-news) + basic_machine=mips-sony + os=-newsos + ;; + necv70) + basic_machine=v70-nec + os=-sysv + ;; + next | m*-next ) + basic_machine=m68k-next + case $os in + -nextstep* ) + ;; + -ns2*) + os=-nextstep2 + ;; + *) + os=-nextstep3 + ;; + esac + ;; + nh3000) + basic_machine=m68k-harris + os=-cxux + ;; + nh[45]000) + basic_machine=m88k-harris + os=-cxux + ;; + nindy960) + basic_machine=i960-intel + os=-nindy + ;; + mon960) + basic_machine=i960-intel + os=-mon960 + ;; + nonstopux) + basic_machine=mips-compaq + os=-nonstopux + ;; + np1) + basic_machine=np1-gould + ;; + nsr-tandem) + basic_machine=nsr-tandem + ;; + op50n-* | op60c-*) + basic_machine=hppa1.1-oki + os=-proelf + ;; + openrisc | openrisc-*) + basic_machine=or32-unknown + ;; + os400) + basic_machine=powerpc-ibm + os=-os400 + ;; + OSE68000 | ose68000) + basic_machine=m68000-ericsson + os=-ose + ;; + os68k) + basic_machine=m68k-none + os=-os68k + ;; + pa-hitachi) + basic_machine=hppa1.1-hitachi + os=-hiuxwe2 + ;; + paragon) + basic_machine=i860-intel + os=-osf + ;; + parisc) + basic_machine=hppa-unknown + os=-linux + ;; + parisc-*) + basic_machine=hppa-`echo $basic_machine | sed 's/^[^-]*-//'` + os=-linux + ;; + pbd) + basic_machine=sparc-tti + ;; + pbb) + basic_machine=m68k-tti + ;; + pc532 | pc532-*) + basic_machine=ns32k-pc532 + ;; + pc98) + basic_machine=i386-pc + ;; + pc98-*) + basic_machine=i386-`echo $basic_machine | sed 's/^[^-]*-//'` + ;; + pentium | p5 | k5 | k6 | nexgen | viac3) + basic_machine=i586-pc + ;; + pentiumpro | p6 | 6x86 | athlon | athlon_*) + basic_machine=i686-pc + ;; + pentiumii | pentium2 | pentiumiii | pentium3) + basic_machine=i686-pc + ;; + pentium4) + basic_machine=i786-pc + ;; + pentium-* | p5-* | k5-* | k6-* | nexgen-* | viac3-*) + basic_machine=i586-`echo $basic_machine | sed 's/^[^-]*-//'` + ;; + pentiumpro-* | p6-* | 6x86-* | athlon-*) + basic_machine=i686-`echo $basic_machine | sed 's/^[^-]*-//'` + ;; + pentiumii-* | pentium2-* | pentiumiii-* | pentium3-*) + basic_machine=i686-`echo $basic_machine | sed 's/^[^-]*-//'` + ;; + pentium4-*) + basic_machine=i786-`echo $basic_machine | sed 's/^[^-]*-//'` + ;; + pn) + basic_machine=pn-gould + ;; + power) basic_machine=power-ibm + ;; + ppc) basic_machine=powerpc-unknown + ;; + ppc-*) basic_machine=powerpc-`echo $basic_machine | sed 's/^[^-]*-//'` + ;; + ppcle | powerpclittle | ppc-le | powerpc-little) + basic_machine=powerpcle-unknown + ;; + ppcle-* | powerpclittle-*) + basic_machine=powerpcle-`echo $basic_machine | sed 's/^[^-]*-//'` + ;; + ppc64) basic_machine=powerpc64-unknown + ;; + ppc64-*) basic_machine=powerpc64-`echo $basic_machine | sed 's/^[^-]*-//'` + ;; + ppc64le | powerpc64little | ppc64-le | powerpc64-little) + basic_machine=powerpc64le-unknown + ;; + ppc64le-* | powerpc64little-*) + basic_machine=powerpc64le-`echo $basic_machine | sed 's/^[^-]*-//'` + ;; + ps2) + basic_machine=i386-ibm + ;; + pw32) + basic_machine=i586-unknown + os=-pw32 + ;; + rdos) + basic_machine=i386-pc + os=-rdos + ;; + rom68k) + basic_machine=m68k-rom68k + os=-coff + ;; + rm[46]00) + basic_machine=mips-siemens + ;; + rtpc | rtpc-*) + basic_machine=romp-ibm + ;; + s390 | s390-*) + basic_machine=s390-ibm + ;; + s390x | s390x-*) + basic_machine=s390x-ibm + ;; + sa29200) + basic_machine=a29k-amd + os=-udi + ;; + sb1) + basic_machine=mipsisa64sb1-unknown + ;; + sb1el) + basic_machine=mipsisa64sb1el-unknown + ;; + sde) + basic_machine=mipsisa32-sde + os=-elf + ;; + sei) + basic_machine=mips-sei + os=-seiux + ;; + sequent) + basic_machine=i386-sequent + ;; + sh) + basic_machine=sh-hitachi + os=-hms + ;; + sh5el) + basic_machine=sh5le-unknown + ;; + sh64) + basic_machine=sh64-unknown + ;; + sparclite-wrs | simso-wrs) + basic_machine=sparclite-wrs + os=-vxworks + ;; + sps7) + basic_machine=m68k-bull + os=-sysv2 + ;; + spur) + basic_machine=spur-unknown + ;; + st2000) + basic_machine=m68k-tandem + ;; + stratus) + basic_machine=i860-stratus + os=-sysv4 + ;; + sun2) + basic_machine=m68000-sun + ;; + sun2os3) + basic_machine=m68000-sun + os=-sunos3 + ;; + sun2os4) + basic_machine=m68000-sun + os=-sunos4 + ;; + sun3os3) + basic_machine=m68k-sun + os=-sunos3 + ;; + sun3os4) + basic_machine=m68k-sun + os=-sunos4 + ;; + sun4os3) + basic_machine=sparc-sun + os=-sunos3 + ;; + sun4os4) + basic_machine=sparc-sun + os=-sunos4 + ;; + sun4sol2) + basic_machine=sparc-sun + os=-solaris2 + ;; + sun3 | sun3-*) + basic_machine=m68k-sun + ;; + sun4) + basic_machine=sparc-sun + ;; + sun386 | sun386i | roadrunner) + basic_machine=i386-sun + ;; + sv1) + basic_machine=sv1-cray + os=-unicos + ;; + symmetry) + basic_machine=i386-sequent + os=-dynix + ;; + t3e) + basic_machine=alphaev5-cray + os=-unicos + ;; + t90) + basic_machine=t90-cray + os=-unicos + ;; + tic54x | c54x*) + basic_machine=tic54x-unknown + os=-coff + ;; + tic55x | c55x*) + basic_machine=tic55x-unknown + os=-coff + ;; + tic6x | c6x*) + basic_machine=tic6x-unknown + os=-coff + ;; + # This must be matched before tile*. + tilegx*) + basic_machine=tilegx-unknown + os=-linux-gnu + ;; + tile*) + basic_machine=tile-unknown + os=-linux-gnu + ;; + tx39) + basic_machine=mipstx39-unknown + ;; + tx39el) + basic_machine=mipstx39el-unknown + ;; + toad1) + basic_machine=pdp10-xkl + os=-tops20 + ;; + tower | tower-32) + basic_machine=m68k-ncr + ;; + tpf) + basic_machine=s390x-ibm + os=-tpf + ;; + udi29k) + basic_machine=a29k-amd + os=-udi + ;; + ultra3) + basic_machine=a29k-nyu + os=-sym1 + ;; + v810 | necv810) + basic_machine=v810-nec + os=-none + ;; + vaxv) + basic_machine=vax-dec + os=-sysv + ;; + vms) + basic_machine=vax-dec + os=-vms + ;; + vpp*|vx|vx-*) + basic_machine=f301-fujitsu + ;; + vxworks960) + basic_machine=i960-wrs + os=-vxworks + ;; + vxworks68) + basic_machine=m68k-wrs + os=-vxworks + ;; + vxworks29k) + basic_machine=a29k-wrs + os=-vxworks + ;; + w65*) + basic_machine=w65-wdc + os=-none + ;; + w89k-*) + basic_machine=hppa1.1-winbond + os=-proelf + ;; + xbox) + basic_machine=i686-pc + os=-mingw32 + ;; + xps | xps100) + basic_machine=xps100-honeywell + ;; + ymp) + basic_machine=ymp-cray + os=-unicos + ;; + z8k-*-coff) + basic_machine=z8k-unknown + os=-sim + ;; + z80-*-coff) + basic_machine=z80-unknown + os=-sim + ;; + none) + basic_machine=none-none + os=-none + ;; + +# Here we handle the default manufacturer of certain CPU types. It is in +# some cases the only manufacturer, in others, it is the most popular. + w89k) + basic_machine=hppa1.1-winbond + ;; + op50n) + basic_machine=hppa1.1-oki + ;; + op60c) + basic_machine=hppa1.1-oki + ;; + romp) + basic_machine=romp-ibm + ;; + mmix) + basic_machine=mmix-knuth + ;; + rs6000) + basic_machine=rs6000-ibm + ;; + vax) + basic_machine=vax-dec + ;; + pdp10) + # there are many clones, so DEC is not a safe bet + basic_machine=pdp10-unknown + ;; + pdp11) + basic_machine=pdp11-dec + ;; + we32k) + basic_machine=we32k-att + ;; + sh[1234] | sh[24]a | sh[24]aeb | sh[34]eb | sh[1234]le | sh[23]ele) + basic_machine=sh-unknown + ;; + sparc | sparcv8 | sparcv9 | sparcv9b | sparcv9v) + basic_machine=sparc-sun + ;; + cydra) + basic_machine=cydra-cydrome + ;; + orion) + basic_machine=orion-highlevel + ;; + orion105) + basic_machine=clipper-highlevel + ;; + mac | mpw | mac-mpw) + basic_machine=m68k-apple + ;; + pmac | pmac-mpw) + basic_machine=powerpc-apple + ;; + *-unknown) + # Make sure to match an already-canonicalized machine name. + ;; + *) + echo Invalid configuration \`$1\': machine \`$basic_machine\' not recognized 1>&2 + exit 1 + ;; +esac + +# Here we canonicalize certain aliases for manufacturers. +case $basic_machine in + *-digital*) + basic_machine=`echo $basic_machine | sed 's/digital.*/dec/'` + ;; + *-commodore*) + basic_machine=`echo $basic_machine | sed 's/commodore.*/cbm/'` + ;; + *) + ;; +esac + +# Decode manufacturer-specific aliases for certain operating systems. + +if [ x"$os" != x"" ] +then +case $os in + # First match some system type aliases + # that might get confused with valid system types. + # -solaris* is a basic system type, with this one exception. + -auroraux) + os=-auroraux + ;; + -solaris1 | -solaris1.*) + os=`echo $os | sed -e 's|solaris1|sunos4|'` + ;; + -solaris) + os=-solaris2 + ;; + -svr4*) + os=-sysv4 + ;; + -unixware*) + os=-sysv4.2uw + ;; + -gnu/linux*) + os=`echo $os | sed -e 's|gnu/linux|linux-gnu|'` + ;; + # First accept the basic system types. + # The portable systems comes first. + # Each alternative MUST END IN A *, to match a version number. + # -sysv* is not here because it comes later, after sysvr4. + -gnu* | -bsd* | -mach* | -minix* | -genix* | -ultrix* | -irix* \ + | -*vms* | -sco* | -esix* | -isc* | -aix* | -cnk* | -sunos | -sunos[34]*\ + | -hpux* | -unos* | -osf* | -luna* | -dgux* | -auroraux* | -solaris* \ + | -sym* | -kopensolaris* \ + | -amigaos* | -amigados* | -msdos* | -newsos* | -unicos* | -aof* \ + | -aos* | -aros* \ + | -nindy* | -vxsim* | -vxworks* | -ebmon* | -hms* | -mvs* \ + | -clix* | -riscos* | -uniplus* | -iris* | -rtu* | -xenix* \ + | -hiux* | -386bsd* | -knetbsd* | -mirbsd* | -netbsd* \ + | -openbsd* | -solidbsd* \ + | -ekkobsd* | -kfreebsd* | -freebsd* | -riscix* | -lynxos* \ + | -bosx* | -nextstep* | -cxux* | -aout* | -elf* | -oabi* \ + | -ptx* | -coff* | -ecoff* | -winnt* | -domain* | -vsta* \ + | -udi* | -eabi* | -lites* | -ieee* | -go32* | -aux* \ + | -chorusos* | -chorusrdb* | -cegcc* \ + | -cygwin* | -pe* | -psos* | -moss* | -proelf* | -rtems* \ + | -mingw32* | -linux-gnu* | -linux-newlib* | -linux-uclibc* \ + | -uxpv* | -beos* | -mpeix* | -udk* \ + | -interix* | -uwin* | -mks* | -rhapsody* | -darwin* | -opened* \ + | -openstep* | -oskit* | -conix* | -pw32* | -nonstopux* \ + | -storm-chaos* | -tops10* | -tenex* | -tops20* | -its* \ + | -os2* | -vos* | -palmos* | -uclinux* | -nucleus* \ + | -morphos* | -superux* | -rtmk* | -rtmk-nova* | -windiss* \ + | -powermax* | -dnix* | -nx6 | -nx7 | -sei* | -dragonfly* \ + | -skyos* | -haiku* | -rdos* | -toppers* | -drops* | -es*) + # Remember, each alternative MUST END IN *, to match a version number. + ;; + -qnx*) + case $basic_machine in + x86-* | i*86-*) + ;; + *) + os=-nto$os + ;; + esac + ;; + -nto-qnx*) + ;; + -nto*) + os=`echo $os | sed -e 's|nto|nto-qnx|'` + ;; + -sim | -es1800* | -hms* | -xray | -os68k* | -none* | -v88r* \ + | -windows* | -osx | -abug | -netware* | -os9* | -beos* | -haiku* \ + | -macos* | -mpw* | -magic* | -mmixware* | -mon960* | -lnews*) + ;; + -mac*) + os=`echo $os | sed -e 's|mac|macos|'` + ;; + -linux-dietlibc) + os=-linux-dietlibc + ;; + -linux*) + os=`echo $os | sed -e 's|linux|linux-gnu|'` + ;; + -sunos5*) + os=`echo $os | sed -e 's|sunos5|solaris2|'` + ;; + -sunos6*) + os=`echo $os | sed -e 's|sunos6|solaris3|'` + ;; + -opened*) + os=-openedition + ;; + -os400*) + os=-os400 + ;; + -wince*) + os=-wince + ;; + -osfrose*) + os=-osfrose + ;; + -osf*) + os=-osf + ;; + -utek*) + os=-bsd + ;; + -dynix*) + os=-bsd + ;; + -acis*) + os=-aos + ;; + -atheos*) + os=-atheos + ;; + -syllable*) + os=-syllable + ;; + -386bsd) + os=-bsd + ;; + -ctix* | -uts*) + os=-sysv + ;; + -nova*) + os=-rtmk-nova + ;; + -ns2 ) + os=-nextstep2 + ;; + -nsk*) + os=-nsk + ;; + # Preserve the version number of sinix5. + -sinix5.*) + os=`echo $os | sed -e 's|sinix|sysv|'` + ;; + -sinix*) + os=-sysv4 + ;; + -tpf*) + os=-tpf + ;; + -triton*) + os=-sysv3 + ;; + -oss*) + os=-sysv3 + ;; + -svr4) + os=-sysv4 + ;; + -svr3) + os=-sysv3 + ;; + -sysvr4) + os=-sysv4 + ;; + # This must come after -sysvr4. + -sysv*) + ;; + -ose*) + os=-ose + ;; + -es1800*) + os=-ose + ;; + -xenix) + os=-xenix + ;; + -*mint | -mint[0-9]* | -*MiNT | -MiNT[0-9]*) + os=-mint + ;; + -aros*) + os=-aros + ;; + -kaos*) + os=-kaos + ;; + -zvmoe) + os=-zvmoe + ;; + -dicos*) + os=-dicos + ;; + -nacl*) + ;; + -none) + ;; + *) + # Get rid of the `-' at the beginning of $os. + os=`echo $os | sed 's/[^-]*-//'` + echo Invalid configuration \`$1\': system \`$os\' not recognized 1>&2 + exit 1 + ;; +esac +else + +# Here we handle the default operating systems that come with various machines. +# The value should be what the vendor currently ships out the door with their +# machine or put another way, the most popular os provided with the machine. + +# Note that if you're going to try to match "-MANUFACTURER" here (say, +# "-sun"), then you have to tell the case statement up towards the top +# that MANUFACTURER isn't an operating system. Otherwise, code above +# will signal an error saying that MANUFACTURER isn't an operating +# system, and we'll never get to this point. + +case $basic_machine in + score-*) + os=-elf + ;; + spu-*) + os=-elf + ;; + *-acorn) + os=-riscix1.2 + ;; + arm*-rebel) + os=-linux + ;; + arm*-semi) + os=-aout + ;; + c4x-* | tic4x-*) + os=-coff + ;; + # This must come before the *-dec entry. + pdp10-*) + os=-tops20 + ;; + pdp11-*) + os=-none + ;; + *-dec | vax-*) + os=-ultrix4.2 + ;; + m68*-apollo) + os=-domain + ;; + i386-sun) + os=-sunos4.0.2 + ;; + m68000-sun) + os=-sunos3 + # This also exists in the configure program, but was not the + # default. + # os=-sunos4 + ;; + m68*-cisco) + os=-aout + ;; + mep-*) + os=-elf + ;; + mips*-cisco) + os=-elf + ;; + mips*-*) + os=-elf + ;; + or32-*) + os=-coff + ;; + *-tti) # must be before sparc entry or we get the wrong os. + os=-sysv3 + ;; + sparc-* | *-sun) + os=-sunos4.1.1 + ;; + *-be) + os=-beos + ;; + *-haiku) + os=-haiku + ;; + *-ibm) + os=-aix + ;; + *-knuth) + os=-mmixware + ;; + *-wec) + os=-proelf + ;; + *-winbond) + os=-proelf + ;; + *-oki) + os=-proelf + ;; + *-hp) + os=-hpux + ;; + *-hitachi) + os=-hiux + ;; + i860-* | *-att | *-ncr | *-altos | *-motorola | *-convergent) + os=-sysv + ;; + *-cbm) + os=-amigaos + ;; + *-dg) + os=-dgux + ;; + *-dolphin) + os=-sysv3 + ;; + m68k-ccur) + os=-rtu + ;; + m88k-omron*) + os=-luna + ;; + *-next ) + os=-nextstep + ;; + *-sequent) + os=-ptx + ;; + *-crds) + os=-unos + ;; + *-ns) + os=-genix + ;; + i370-*) + os=-mvs + ;; + *-next) + os=-nextstep3 + ;; + *-gould) + os=-sysv + ;; + *-highlevel) + os=-bsd + ;; + *-encore) + os=-bsd + ;; + *-sgi) + os=-irix + ;; + *-siemens) + os=-sysv4 + ;; + *-masscomp) + os=-rtu + ;; + f30[01]-fujitsu | f700-fujitsu) + os=-uxpv + ;; + *-rom68k) + os=-coff + ;; + *-*bug) + os=-coff + ;; + *-apple) + os=-macos + ;; + *-atari*) + os=-mint + ;; + *) + os=-none + ;; +esac +fi + +# Here we handle the case where we know the os, and the CPU type, but not the +# manufacturer. We pick the logical manufacturer. +vendor=unknown +case $basic_machine in + *-unknown) + case $os in + -riscix*) + vendor=acorn + ;; + -sunos*) + vendor=sun + ;; + -cnk*|-aix*) + vendor=ibm + ;; + -beos*) + vendor=be + ;; + -hpux*) + vendor=hp + ;; + -mpeix*) + vendor=hp + ;; + -hiux*) + vendor=hitachi + ;; + -unos*) + vendor=crds + ;; + -dgux*) + vendor=dg + ;; + -luna*) + vendor=omron + ;; + -genix*) + vendor=ns + ;; + -mvs* | -opened*) + vendor=ibm + ;; + -os400*) + vendor=ibm + ;; + -ptx*) + vendor=sequent + ;; + -tpf*) + vendor=ibm + ;; + -vxsim* | -vxworks* | -windiss*) + vendor=wrs + ;; + -aux*) + vendor=apple + ;; + -hms*) + vendor=hitachi + ;; + -mpw* | -macos*) + vendor=apple + ;; + -*mint | -mint[0-9]* | -*MiNT | -MiNT[0-9]*) + vendor=atari + ;; + -vos*) + vendor=stratus + ;; + esac + basic_machine=`echo $basic_machine | sed "s/unknown/$vendor/"` + ;; +esac + +echo $basic_machine$os +exit + +# Local variables: +# eval: (add-hook 'write-file-hooks 'time-stamp) +# time-stamp-start: "timestamp='" +# time-stamp-format: "%:y-%02m-%02d" +# time-stamp-end: "'" +# End: diff --git a/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/depcomp b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/depcomp new file mode 100755 index 0000000000..df8eea7e4c --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/depcomp @@ -0,0 +1,630 @@ +#! /bin/sh +# depcomp - compile a program generating dependencies as side-effects + +scriptversion=2009-04-28.21; # UTC + +# Copyright (C) 1999, 2000, 2003, 2004, 2005, 2006, 2007, 2009 Free +# Software Foundation, Inc. + +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2, or (at your option) +# any later version. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. + +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program that contains a +# configuration script generated by Autoconf, you may include it under +# the same distribution terms that you use for the rest of that program. + +# Originally written by Alexandre Oliva . + +case $1 in + '') + echo "$0: No command. Try \`$0 --help' for more information." 1>&2 + exit 1; + ;; + -h | --h*) + cat <<\EOF +Usage: depcomp [--help] [--version] PROGRAM [ARGS] + +Run PROGRAMS ARGS to compile a file, generating dependencies +as side-effects. + +Environment variables: + depmode Dependency tracking mode. + source Source file read by `PROGRAMS ARGS'. + object Object file output by `PROGRAMS ARGS'. + DEPDIR directory where to store dependencies. + depfile Dependency file to output. + tmpdepfile Temporary file to use when outputing dependencies. + libtool Whether libtool is used (yes/no). + +Report bugs to . +EOF + exit $? + ;; + -v | --v*) + echo "depcomp $scriptversion" + exit $? + ;; +esac + +if test -z "$depmode" || test -z "$source" || test -z "$object"; then + echo "depcomp: Variables source, object and depmode must be set" 1>&2 + exit 1 +fi + +# Dependencies for sub/bar.o or sub/bar.obj go into sub/.deps/bar.Po. +depfile=${depfile-`echo "$object" | + sed 's|[^\\/]*$|'${DEPDIR-.deps}'/&|;s|\.\([^.]*\)$|.P\1|;s|Pobj$|Po|'`} +tmpdepfile=${tmpdepfile-`echo "$depfile" | sed 's/\.\([^.]*\)$/.T\1/'`} + +rm -f "$tmpdepfile" + +# Some modes work just like other modes, but use different flags. We +# parameterize here, but still list the modes in the big case below, +# to make depend.m4 easier to write. Note that we *cannot* use a case +# here, because this file can only contain one case statement. +if test "$depmode" = hp; then + # HP compiler uses -M and no extra arg. + gccflag=-M + depmode=gcc +fi + +if test "$depmode" = dashXmstdout; then + # This is just like dashmstdout with a different argument. + dashmflag=-xM + depmode=dashmstdout +fi + +cygpath_u="cygpath -u -f -" +if test "$depmode" = msvcmsys; then + # This is just like msvisualcpp but w/o cygpath translation. + # Just convert the backslash-escaped backslashes to single forward + # slashes to satisfy depend.m4 + cygpath_u="sed s,\\\\\\\\,/,g" + depmode=msvisualcpp +fi + +case "$depmode" in +gcc3) +## gcc 3 implements dependency tracking that does exactly what +## we want. Yay! Note: for some reason libtool 1.4 doesn't like +## it if -MD -MP comes after the -MF stuff. Hmm. +## Unfortunately, FreeBSD c89 acceptance of flags depends upon +## the command line argument order; so add the flags where they +## appear in depend2.am. Note that the slowdown incurred here +## affects only configure: in makefiles, %FASTDEP% shortcuts this. + for arg + do + case $arg in + -c) set fnord "$@" -MT "$object" -MD -MP -MF "$tmpdepfile" "$arg" ;; + *) set fnord "$@" "$arg" ;; + esac + shift # fnord + shift # $arg + done + "$@" + stat=$? + if test $stat -eq 0; then : + else + rm -f "$tmpdepfile" + exit $stat + fi + mv "$tmpdepfile" "$depfile" + ;; + +gcc) +## There are various ways to get dependency output from gcc. Here's +## why we pick this rather obscure method: +## - Don't want to use -MD because we'd like the dependencies to end +## up in a subdir. Having to rename by hand is ugly. +## (We might end up doing this anyway to support other compilers.) +## - The DEPENDENCIES_OUTPUT environment variable makes gcc act like +## -MM, not -M (despite what the docs say). +## - Using -M directly means running the compiler twice (even worse +## than renaming). + if test -z "$gccflag"; then + gccflag=-MD, + fi + "$@" -Wp,"$gccflag$tmpdepfile" + stat=$? + if test $stat -eq 0; then : + else + rm -f "$tmpdepfile" + exit $stat + fi + rm -f "$depfile" + echo "$object : \\" > "$depfile" + alpha=ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz +## The second -e expression handles DOS-style file names with drive letters. + sed -e 's/^[^:]*: / /' \ + -e 's/^['$alpha']:\/[^:]*: / /' < "$tmpdepfile" >> "$depfile" +## This next piece of magic avoids the `deleted header file' problem. +## The problem is that when a header file which appears in a .P file +## is deleted, the dependency causes make to die (because there is +## typically no way to rebuild the header). We avoid this by adding +## dummy dependencies for each header file. Too bad gcc doesn't do +## this for us directly. + tr ' ' ' +' < "$tmpdepfile" | +## Some versions of gcc put a space before the `:'. On the theory +## that the space means something, we add a space to the output as +## well. +## Some versions of the HPUX 10.20 sed can't process this invocation +## correctly. Breaking it into two sed invocations is a workaround. + sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' | sed -e 's/$/ :/' >> "$depfile" + rm -f "$tmpdepfile" + ;; + +hp) + # This case exists only to let depend.m4 do its work. It works by + # looking at the text of this script. This case will never be run, + # since it is checked for above. + exit 1 + ;; + +sgi) + if test "$libtool" = yes; then + "$@" "-Wp,-MDupdate,$tmpdepfile" + else + "$@" -MDupdate "$tmpdepfile" + fi + stat=$? + if test $stat -eq 0; then : + else + rm -f "$tmpdepfile" + exit $stat + fi + rm -f "$depfile" + + if test -f "$tmpdepfile"; then # yes, the sourcefile depend on other files + echo "$object : \\" > "$depfile" + + # Clip off the initial element (the dependent). Don't try to be + # clever and replace this with sed code, as IRIX sed won't handle + # lines with more than a fixed number of characters (4096 in + # IRIX 6.2 sed, 8192 in IRIX 6.5). We also remove comment lines; + # the IRIX cc adds comments like `#:fec' to the end of the + # dependency line. + tr ' ' ' +' < "$tmpdepfile" \ + | sed -e 's/^.*\.o://' -e 's/#.*$//' -e '/^$/ d' | \ + tr ' +' ' ' >> "$depfile" + echo >> "$depfile" + + # The second pass generates a dummy entry for each header file. + tr ' ' ' +' < "$tmpdepfile" \ + | sed -e 's/^.*\.o://' -e 's/#.*$//' -e '/^$/ d' -e 's/$/:/' \ + >> "$depfile" + else + # The sourcefile does not contain any dependencies, so just + # store a dummy comment line, to avoid errors with the Makefile + # "include basename.Plo" scheme. + echo "#dummy" > "$depfile" + fi + rm -f "$tmpdepfile" + ;; + +aix) + # The C for AIX Compiler uses -M and outputs the dependencies + # in a .u file. In older versions, this file always lives in the + # current directory. Also, the AIX compiler puts `$object:' at the + # start of each line; $object doesn't have directory information. + # Version 6 uses the directory in both cases. + dir=`echo "$object" | sed -e 's|/[^/]*$|/|'` + test "x$dir" = "x$object" && dir= + base=`echo "$object" | sed -e 's|^.*/||' -e 's/\.o$//' -e 's/\.lo$//'` + if test "$libtool" = yes; then + tmpdepfile1=$dir$base.u + tmpdepfile2=$base.u + tmpdepfile3=$dir.libs/$base.u + "$@" -Wc,-M + else + tmpdepfile1=$dir$base.u + tmpdepfile2=$dir$base.u + tmpdepfile3=$dir$base.u + "$@" -M + fi + stat=$? + + if test $stat -eq 0; then : + else + rm -f "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" + exit $stat + fi + + for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" + do + test -f "$tmpdepfile" && break + done + if test -f "$tmpdepfile"; then + # Each line is of the form `foo.o: dependent.h'. + # Do two passes, one to just change these to + # `$object: dependent.h' and one to simply `dependent.h:'. + sed -e "s,^.*\.[a-z]*:,$object:," < "$tmpdepfile" > "$depfile" + # That's a tab and a space in the []. + sed -e 's,^.*\.[a-z]*:[ ]*,,' -e 's,$,:,' < "$tmpdepfile" >> "$depfile" + else + # The sourcefile does not contain any dependencies, so just + # store a dummy comment line, to avoid errors with the Makefile + # "include basename.Plo" scheme. + echo "#dummy" > "$depfile" + fi + rm -f "$tmpdepfile" + ;; + +icc) + # Intel's C compiler understands `-MD -MF file'. However on + # icc -MD -MF foo.d -c -o sub/foo.o sub/foo.c + # ICC 7.0 will fill foo.d with something like + # foo.o: sub/foo.c + # foo.o: sub/foo.h + # which is wrong. We want: + # sub/foo.o: sub/foo.c + # sub/foo.o: sub/foo.h + # sub/foo.c: + # sub/foo.h: + # ICC 7.1 will output + # foo.o: sub/foo.c sub/foo.h + # and will wrap long lines using \ : + # foo.o: sub/foo.c ... \ + # sub/foo.h ... \ + # ... + + "$@" -MD -MF "$tmpdepfile" + stat=$? + if test $stat -eq 0; then : + else + rm -f "$tmpdepfile" + exit $stat + fi + rm -f "$depfile" + # Each line is of the form `foo.o: dependent.h', + # or `foo.o: dep1.h dep2.h \', or ` dep3.h dep4.h \'. + # Do two passes, one to just change these to + # `$object: dependent.h' and one to simply `dependent.h:'. + sed "s,^[^:]*:,$object :," < "$tmpdepfile" > "$depfile" + # Some versions of the HPUX 10.20 sed can't process this invocation + # correctly. Breaking it into two sed invocations is a workaround. + sed 's,^[^:]*: \(.*\)$,\1,;s/^\\$//;/^$/d;/:$/d' < "$tmpdepfile" | + sed -e 's/$/ :/' >> "$depfile" + rm -f "$tmpdepfile" + ;; + +hp2) + # The "hp" stanza above does not work with aCC (C++) and HP's ia64 + # compilers, which have integrated preprocessors. The correct option + # to use with these is +Maked; it writes dependencies to a file named + # 'foo.d', which lands next to the object file, wherever that + # happens to be. + # Much of this is similar to the tru64 case; see comments there. + dir=`echo "$object" | sed -e 's|/[^/]*$|/|'` + test "x$dir" = "x$object" && dir= + base=`echo "$object" | sed -e 's|^.*/||' -e 's/\.o$//' -e 's/\.lo$//'` + if test "$libtool" = yes; then + tmpdepfile1=$dir$base.d + tmpdepfile2=$dir.libs/$base.d + "$@" -Wc,+Maked + else + tmpdepfile1=$dir$base.d + tmpdepfile2=$dir$base.d + "$@" +Maked + fi + stat=$? + if test $stat -eq 0; then : + else + rm -f "$tmpdepfile1" "$tmpdepfile2" + exit $stat + fi + + for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2" + do + test -f "$tmpdepfile" && break + done + if test -f "$tmpdepfile"; then + sed -e "s,^.*\.[a-z]*:,$object:," "$tmpdepfile" > "$depfile" + # Add `dependent.h:' lines. + sed -ne '2,${ + s/^ *// + s/ \\*$// + s/$/:/ + p + }' "$tmpdepfile" >> "$depfile" + else + echo "#dummy" > "$depfile" + fi + rm -f "$tmpdepfile" "$tmpdepfile2" + ;; + +tru64) + # The Tru64 compiler uses -MD to generate dependencies as a side + # effect. `cc -MD -o foo.o ...' puts the dependencies into `foo.o.d'. + # At least on Alpha/Redhat 6.1, Compaq CCC V6.2-504 seems to put + # dependencies in `foo.d' instead, so we check for that too. + # Subdirectories are respected. + dir=`echo "$object" | sed -e 's|/[^/]*$|/|'` + test "x$dir" = "x$object" && dir= + base=`echo "$object" | sed -e 's|^.*/||' -e 's/\.o$//' -e 's/\.lo$//'` + + if test "$libtool" = yes; then + # With Tru64 cc, shared objects can also be used to make a + # static library. This mechanism is used in libtool 1.4 series to + # handle both shared and static libraries in a single compilation. + # With libtool 1.4, dependencies were output in $dir.libs/$base.lo.d. + # + # With libtool 1.5 this exception was removed, and libtool now + # generates 2 separate objects for the 2 libraries. These two + # compilations output dependencies in $dir.libs/$base.o.d and + # in $dir$base.o.d. We have to check for both files, because + # one of the two compilations can be disabled. We should prefer + # $dir$base.o.d over $dir.libs/$base.o.d because the latter is + # automatically cleaned when .libs/ is deleted, while ignoring + # the former would cause a distcleancheck panic. + tmpdepfile1=$dir.libs/$base.lo.d # libtool 1.4 + tmpdepfile2=$dir$base.o.d # libtool 1.5 + tmpdepfile3=$dir.libs/$base.o.d # libtool 1.5 + tmpdepfile4=$dir.libs/$base.d # Compaq CCC V6.2-504 + "$@" -Wc,-MD + else + tmpdepfile1=$dir$base.o.d + tmpdepfile2=$dir$base.d + tmpdepfile3=$dir$base.d + tmpdepfile4=$dir$base.d + "$@" -MD + fi + + stat=$? + if test $stat -eq 0; then : + else + rm -f "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" "$tmpdepfile4" + exit $stat + fi + + for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" "$tmpdepfile4" + do + test -f "$tmpdepfile" && break + done + if test -f "$tmpdepfile"; then + sed -e "s,^.*\.[a-z]*:,$object:," < "$tmpdepfile" > "$depfile" + # That's a tab and a space in the []. + sed -e 's,^.*\.[a-z]*:[ ]*,,' -e 's,$,:,' < "$tmpdepfile" >> "$depfile" + else + echo "#dummy" > "$depfile" + fi + rm -f "$tmpdepfile" + ;; + +#nosideeffect) + # This comment above is used by automake to tell side-effect + # dependency tracking mechanisms from slower ones. + +dashmstdout) + # Important note: in order to support this mode, a compiler *must* + # always write the preprocessed file to stdout, regardless of -o. + "$@" || exit $? + + # Remove the call to Libtool. + if test "$libtool" = yes; then + while test "X$1" != 'X--mode=compile'; do + shift + done + shift + fi + + # Remove `-o $object'. + IFS=" " + for arg + do + case $arg in + -o) + shift + ;; + $object) + shift + ;; + *) + set fnord "$@" "$arg" + shift # fnord + shift # $arg + ;; + esac + done + + test -z "$dashmflag" && dashmflag=-M + # Require at least two characters before searching for `:' + # in the target name. This is to cope with DOS-style filenames: + # a dependency such as `c:/foo/bar' could be seen as target `c' otherwise. + "$@" $dashmflag | + sed 's:^[ ]*[^: ][^:][^:]*\:[ ]*:'"$object"'\: :' > "$tmpdepfile" + rm -f "$depfile" + cat < "$tmpdepfile" > "$depfile" + tr ' ' ' +' < "$tmpdepfile" | \ +## Some versions of the HPUX 10.20 sed can't process this invocation +## correctly. Breaking it into two sed invocations is a workaround. + sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' | sed -e 's/$/ :/' >> "$depfile" + rm -f "$tmpdepfile" + ;; + +dashXmstdout) + # This case only exists to satisfy depend.m4. It is never actually + # run, as this mode is specially recognized in the preamble. + exit 1 + ;; + +makedepend) + "$@" || exit $? + # Remove any Libtool call + if test "$libtool" = yes; then + while test "X$1" != 'X--mode=compile'; do + shift + done + shift + fi + # X makedepend + shift + cleared=no eat=no + for arg + do + case $cleared in + no) + set ""; shift + cleared=yes ;; + esac + if test $eat = yes; then + eat=no + continue + fi + case "$arg" in + -D*|-I*) + set fnord "$@" "$arg"; shift ;; + # Strip any option that makedepend may not understand. Remove + # the object too, otherwise makedepend will parse it as a source file. + -arch) + eat=yes ;; + -*|$object) + ;; + *) + set fnord "$@" "$arg"; shift ;; + esac + done + obj_suffix=`echo "$object" | sed 's/^.*\././'` + touch "$tmpdepfile" + ${MAKEDEPEND-makedepend} -o"$obj_suffix" -f"$tmpdepfile" "$@" + rm -f "$depfile" + cat < "$tmpdepfile" > "$depfile" + sed '1,2d' "$tmpdepfile" | tr ' ' ' +' | \ +## Some versions of the HPUX 10.20 sed can't process this invocation +## correctly. Breaking it into two sed invocations is a workaround. + sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' | sed -e 's/$/ :/' >> "$depfile" + rm -f "$tmpdepfile" "$tmpdepfile".bak + ;; + +cpp) + # Important note: in order to support this mode, a compiler *must* + # always write the preprocessed file to stdout. + "$@" || exit $? + + # Remove the call to Libtool. + if test "$libtool" = yes; then + while test "X$1" != 'X--mode=compile'; do + shift + done + shift + fi + + # Remove `-o $object'. + IFS=" " + for arg + do + case $arg in + -o) + shift + ;; + $object) + shift + ;; + *) + set fnord "$@" "$arg" + shift # fnord + shift # $arg + ;; + esac + done + + "$@" -E | + sed -n -e '/^# [0-9][0-9]* "\([^"]*\)".*/ s:: \1 \\:p' \ + -e '/^#line [0-9][0-9]* "\([^"]*\)".*/ s:: \1 \\:p' | + sed '$ s: \\$::' > "$tmpdepfile" + rm -f "$depfile" + echo "$object : \\" > "$depfile" + cat < "$tmpdepfile" >> "$depfile" + sed < "$tmpdepfile" '/^$/d;s/^ //;s/ \\$//;s/$/ :/' >> "$depfile" + rm -f "$tmpdepfile" + ;; + +msvisualcpp) + # Important note: in order to support this mode, a compiler *must* + # always write the preprocessed file to stdout. + "$@" || exit $? + + # Remove the call to Libtool. + if test "$libtool" = yes; then + while test "X$1" != 'X--mode=compile'; do + shift + done + shift + fi + + IFS=" " + for arg + do + case "$arg" in + -o) + shift + ;; + $object) + shift + ;; + "-Gm"|"/Gm"|"-Gi"|"/Gi"|"-ZI"|"/ZI") + set fnord "$@" + shift + shift + ;; + *) + set fnord "$@" "$arg" + shift + shift + ;; + esac + done + "$@" -E 2>/dev/null | + sed -n '/^#line [0-9][0-9]* "\([^"]*\)"/ s::\1:p' | $cygpath_u | sort -u > "$tmpdepfile" + rm -f "$depfile" + echo "$object : \\" > "$depfile" + sed < "$tmpdepfile" -n -e 's% %\\ %g' -e '/^\(.*\)$/ s:: \1 \\:p' >> "$depfile" + echo " " >> "$depfile" + sed < "$tmpdepfile" -n -e 's% %\\ %g' -e '/^\(.*\)$/ s::\1\::p' >> "$depfile" + rm -f "$tmpdepfile" + ;; + +msvcmsys) + # This case exists only to let depend.m4 do its work. It works by + # looking at the text of this script. This case will never be run, + # since it is checked for above. + exit 1 + ;; + +none) + exec "$@" + ;; + +*) + echo "Unknown depmode $depmode" 1>&2 + exit 1 + ;; +esac + +exit 0 + +# Local Variables: +# mode: shell-script +# sh-indentation: 2 +# eval: (add-hook 'write-file-hooks 'time-stamp) +# time-stamp-start: "scriptversion=" +# time-stamp-format: "%:y-%02m-%02d.%02H" +# time-stamp-time-zone: "UTC" +# time-stamp-end: "; # UTC" +# End: diff --git a/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/install-sh b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/install-sh new file mode 100755 index 0000000000..6781b987bd --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/install-sh @@ -0,0 +1,520 @@ +#!/bin/sh +# install - install a program, script, or datafile + +scriptversion=2009-04-28.21; # UTC + +# This originates from X11R5 (mit/util/scripts/install.sh), which was +# later released in X11R6 (xc/config/util/install.sh) with the +# following copyright and license. +# +# Copyright (C) 1994 X Consortium +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to +# deal in the Software without restriction, including without limitation the +# rights to use, copy, modify, merge, publish, distribute, sublicense, and/or +# sell copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# X CONSORTIUM BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN +# AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNEC- +# TION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +# +# Except as contained in this notice, the name of the X Consortium shall not +# be used in advertising or otherwise to promote the sale, use or other deal- +# ings in this Software without prior written authorization from the X Consor- +# tium. +# +# +# FSF changes to this file are in the public domain. +# +# Calling this script install-sh is preferred over install.sh, to prevent +# `make' implicit rules from creating a file called install from it +# when there is no Makefile. +# +# This script is compatible with the BSD install script, but was written +# from scratch. + +nl=' +' +IFS=" "" $nl" + +# set DOITPROG to echo to test this script + +# Don't use :- since 4.3BSD and earlier shells don't like it. +doit=${DOITPROG-} +if test -z "$doit"; then + doit_exec=exec +else + doit_exec=$doit +fi + +# Put in absolute file names if you don't have them in your path; +# or use environment vars. + +chgrpprog=${CHGRPPROG-chgrp} +chmodprog=${CHMODPROG-chmod} +chownprog=${CHOWNPROG-chown} +cmpprog=${CMPPROG-cmp} +cpprog=${CPPROG-cp} +mkdirprog=${MKDIRPROG-mkdir} +mvprog=${MVPROG-mv} +rmprog=${RMPROG-rm} +stripprog=${STRIPPROG-strip} + +posix_glob='?' +initialize_posix_glob=' + test "$posix_glob" != "?" || { + if (set -f) 2>/dev/null; then + posix_glob= + else + posix_glob=: + fi + } +' + +posix_mkdir= + +# Desired mode of installed file. +mode=0755 + +chgrpcmd= +chmodcmd=$chmodprog +chowncmd= +mvcmd=$mvprog +rmcmd="$rmprog -f" +stripcmd= + +src= +dst= +dir_arg= +dst_arg= + +copy_on_change=false +no_target_directory= + +usage="\ +Usage: $0 [OPTION]... [-T] SRCFILE DSTFILE + or: $0 [OPTION]... SRCFILES... DIRECTORY + or: $0 [OPTION]... -t DIRECTORY SRCFILES... + or: $0 [OPTION]... -d DIRECTORIES... + +In the 1st form, copy SRCFILE to DSTFILE. +In the 2nd and 3rd, copy all SRCFILES to DIRECTORY. +In the 4th, create DIRECTORIES. + +Options: + --help display this help and exit. + --version display version info and exit. + + -c (ignored) + -C install only if different (preserve the last data modification time) + -d create directories instead of installing files. + -g GROUP $chgrpprog installed files to GROUP. + -m MODE $chmodprog installed files to MODE. + -o USER $chownprog installed files to USER. + -s $stripprog installed files. + -t DIRECTORY install into DIRECTORY. + -T report an error if DSTFILE is a directory. + +Environment variables override the default commands: + CHGRPPROG CHMODPROG CHOWNPROG CMPPROG CPPROG MKDIRPROG MVPROG + RMPROG STRIPPROG +" + +while test $# -ne 0; do + case $1 in + -c) ;; + + -C) copy_on_change=true;; + + -d) dir_arg=true;; + + -g) chgrpcmd="$chgrpprog $2" + shift;; + + --help) echo "$usage"; exit $?;; + + -m) mode=$2 + case $mode in + *' '* | *' '* | *' +'* | *'*'* | *'?'* | *'['*) + echo "$0: invalid mode: $mode" >&2 + exit 1;; + esac + shift;; + + -o) chowncmd="$chownprog $2" + shift;; + + -s) stripcmd=$stripprog;; + + -t) dst_arg=$2 + shift;; + + -T) no_target_directory=true;; + + --version) echo "$0 $scriptversion"; exit $?;; + + --) shift + break;; + + -*) echo "$0: invalid option: $1" >&2 + exit 1;; + + *) break;; + esac + shift +done + +if test $# -ne 0 && test -z "$dir_arg$dst_arg"; then + # When -d is used, all remaining arguments are directories to create. + # When -t is used, the destination is already specified. + # Otherwise, the last argument is the destination. Remove it from $@. + for arg + do + if test -n "$dst_arg"; then + # $@ is not empty: it contains at least $arg. + set fnord "$@" "$dst_arg" + shift # fnord + fi + shift # arg + dst_arg=$arg + done +fi + +if test $# -eq 0; then + if test -z "$dir_arg"; then + echo "$0: no input file specified." >&2 + exit 1 + fi + # It's OK to call `install-sh -d' without argument. + # This can happen when creating conditional directories. + exit 0 +fi + +if test -z "$dir_arg"; then + trap '(exit $?); exit' 1 2 13 15 + + # Set umask so as not to create temps with too-generous modes. + # However, 'strip' requires both read and write access to temps. + case $mode in + # Optimize common cases. + *644) cp_umask=133;; + *755) cp_umask=22;; + + *[0-7]) + if test -z "$stripcmd"; then + u_plus_rw= + else + u_plus_rw='% 200' + fi + cp_umask=`expr '(' 777 - $mode % 1000 ')' $u_plus_rw`;; + *) + if test -z "$stripcmd"; then + u_plus_rw= + else + u_plus_rw=,u+rw + fi + cp_umask=$mode$u_plus_rw;; + esac +fi + +for src +do + # Protect names starting with `-'. + case $src in + -*) src=./$src;; + esac + + if test -n "$dir_arg"; then + dst=$src + dstdir=$dst + test -d "$dstdir" + dstdir_status=$? + else + + # Waiting for this to be detected by the "$cpprog $src $dsttmp" command + # might cause directories to be created, which would be especially bad + # if $src (and thus $dsttmp) contains '*'. + if test ! -f "$src" && test ! -d "$src"; then + echo "$0: $src does not exist." >&2 + exit 1 + fi + + if test -z "$dst_arg"; then + echo "$0: no destination specified." >&2 + exit 1 + fi + + dst=$dst_arg + # Protect names starting with `-'. + case $dst in + -*) dst=./$dst;; + esac + + # If destination is a directory, append the input filename; won't work + # if double slashes aren't ignored. + if test -d "$dst"; then + if test -n "$no_target_directory"; then + echo "$0: $dst_arg: Is a directory" >&2 + exit 1 + fi + dstdir=$dst + dst=$dstdir/`basename "$src"` + dstdir_status=0 + else + # Prefer dirname, but fall back on a substitute if dirname fails. + dstdir=` + (dirname "$dst") 2>/dev/null || + expr X"$dst" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \ + X"$dst" : 'X\(//\)[^/]' \| \ + X"$dst" : 'X\(//\)$' \| \ + X"$dst" : 'X\(/\)' \| . 2>/dev/null || + echo X"$dst" | + sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ + s//\1/ + q + } + /^X\(\/\/\)[^/].*/{ + s//\1/ + q + } + /^X\(\/\/\)$/{ + s//\1/ + q + } + /^X\(\/\).*/{ + s//\1/ + q + } + s/.*/./; q' + ` + + test -d "$dstdir" + dstdir_status=$? + fi + fi + + obsolete_mkdir_used=false + + if test $dstdir_status != 0; then + case $posix_mkdir in + '') + # Create intermediate dirs using mode 755 as modified by the umask. + # This is like FreeBSD 'install' as of 1997-10-28. + umask=`umask` + case $stripcmd.$umask in + # Optimize common cases. + *[2367][2367]) mkdir_umask=$umask;; + .*0[02][02] | .[02][02] | .[02]) mkdir_umask=22;; + + *[0-7]) + mkdir_umask=`expr $umask + 22 \ + - $umask % 100 % 40 + $umask % 20 \ + - $umask % 10 % 4 + $umask % 2 + `;; + *) mkdir_umask=$umask,go-w;; + esac + + # With -d, create the new directory with the user-specified mode. + # Otherwise, rely on $mkdir_umask. + if test -n "$dir_arg"; then + mkdir_mode=-m$mode + else + mkdir_mode= + fi + + posix_mkdir=false + case $umask in + *[123567][0-7][0-7]) + # POSIX mkdir -p sets u+wx bits regardless of umask, which + # is incompatible with FreeBSD 'install' when (umask & 300) != 0. + ;; + *) + tmpdir=${TMPDIR-/tmp}/ins$RANDOM-$$ + trap 'ret=$?; rmdir "$tmpdir/d" "$tmpdir" 2>/dev/null; exit $ret' 0 + + if (umask $mkdir_umask && + exec $mkdirprog $mkdir_mode -p -- "$tmpdir/d") >/dev/null 2>&1 + then + if test -z "$dir_arg" || { + # Check for POSIX incompatibilities with -m. + # HP-UX 11.23 and IRIX 6.5 mkdir -m -p sets group- or + # other-writeable bit of parent directory when it shouldn't. + # FreeBSD 6.1 mkdir -m -p sets mode of existing directory. + ls_ld_tmpdir=`ls -ld "$tmpdir"` + case $ls_ld_tmpdir in + d????-?r-*) different_mode=700;; + d????-?--*) different_mode=755;; + *) false;; + esac && + $mkdirprog -m$different_mode -p -- "$tmpdir" && { + ls_ld_tmpdir_1=`ls -ld "$tmpdir"` + test "$ls_ld_tmpdir" = "$ls_ld_tmpdir_1" + } + } + then posix_mkdir=: + fi + rmdir "$tmpdir/d" "$tmpdir" + else + # Remove any dirs left behind by ancient mkdir implementations. + rmdir ./$mkdir_mode ./-p ./-- 2>/dev/null + fi + trap '' 0;; + esac;; + esac + + if + $posix_mkdir && ( + umask $mkdir_umask && + $doit_exec $mkdirprog $mkdir_mode -p -- "$dstdir" + ) + then : + else + + # The umask is ridiculous, or mkdir does not conform to POSIX, + # or it failed possibly due to a race condition. Create the + # directory the slow way, step by step, checking for races as we go. + + case $dstdir in + /*) prefix='/';; + -*) prefix='./';; + *) prefix='';; + esac + + eval "$initialize_posix_glob" + + oIFS=$IFS + IFS=/ + $posix_glob set -f + set fnord $dstdir + shift + $posix_glob set +f + IFS=$oIFS + + prefixes= + + for d + do + test -z "$d" && continue + + prefix=$prefix$d + if test -d "$prefix"; then + prefixes= + else + if $posix_mkdir; then + (umask=$mkdir_umask && + $doit_exec $mkdirprog $mkdir_mode -p -- "$dstdir") && break + # Don't fail if two instances are running concurrently. + test -d "$prefix" || exit 1 + else + case $prefix in + *\'*) qprefix=`echo "$prefix" | sed "s/'/'\\\\\\\\''/g"`;; + *) qprefix=$prefix;; + esac + prefixes="$prefixes '$qprefix'" + fi + fi + prefix=$prefix/ + done + + if test -n "$prefixes"; then + # Don't fail if two instances are running concurrently. + (umask $mkdir_umask && + eval "\$doit_exec \$mkdirprog $prefixes") || + test -d "$dstdir" || exit 1 + obsolete_mkdir_used=true + fi + fi + fi + + if test -n "$dir_arg"; then + { test -z "$chowncmd" || $doit $chowncmd "$dst"; } && + { test -z "$chgrpcmd" || $doit $chgrpcmd "$dst"; } && + { test "$obsolete_mkdir_used$chowncmd$chgrpcmd" = false || + test -z "$chmodcmd" || $doit $chmodcmd $mode "$dst"; } || exit 1 + else + + # Make a couple of temp file names in the proper directory. + dsttmp=$dstdir/_inst.$$_ + rmtmp=$dstdir/_rm.$$_ + + # Trap to clean up those temp files at exit. + trap 'ret=$?; rm -f "$dsttmp" "$rmtmp" && exit $ret' 0 + + # Copy the file name to the temp name. + (umask $cp_umask && $doit_exec $cpprog "$src" "$dsttmp") && + + # and set any options; do chmod last to preserve setuid bits. + # + # If any of these fail, we abort the whole thing. If we want to + # ignore errors from any of these, just make sure not to ignore + # errors from the above "$doit $cpprog $src $dsttmp" command. + # + { test -z "$chowncmd" || $doit $chowncmd "$dsttmp"; } && + { test -z "$chgrpcmd" || $doit $chgrpcmd "$dsttmp"; } && + { test -z "$stripcmd" || $doit $stripcmd "$dsttmp"; } && + { test -z "$chmodcmd" || $doit $chmodcmd $mode "$dsttmp"; } && + + # If -C, don't bother to copy if it wouldn't change the file. + if $copy_on_change && + old=`LC_ALL=C ls -dlL "$dst" 2>/dev/null` && + new=`LC_ALL=C ls -dlL "$dsttmp" 2>/dev/null` && + + eval "$initialize_posix_glob" && + $posix_glob set -f && + set X $old && old=:$2:$4:$5:$6 && + set X $new && new=:$2:$4:$5:$6 && + $posix_glob set +f && + + test "$old" = "$new" && + $cmpprog "$dst" "$dsttmp" >/dev/null 2>&1 + then + rm -f "$dsttmp" + else + # Rename the file to the real destination. + $doit $mvcmd -f "$dsttmp" "$dst" 2>/dev/null || + + # The rename failed, perhaps because mv can't rename something else + # to itself, or perhaps because mv is so ancient that it does not + # support -f. + { + # Now remove or move aside any old file at destination location. + # We try this two ways since rm can't unlink itself on some + # systems and the destination file might be busy for other + # reasons. In this case, the final cleanup might fail but the new + # file should still install successfully. + { + test ! -f "$dst" || + $doit $rmcmd -f "$dst" 2>/dev/null || + { $doit $mvcmd -f "$dst" "$rmtmp" 2>/dev/null && + { $doit $rmcmd -f "$rmtmp" 2>/dev/null; :; } + } || + { echo "$0: cannot unlink or rename $dst" >&2 + (exit 1); exit 1 + } + } && + + # Now rename the file to the real destination. + $doit $mvcmd "$dsttmp" "$dst" + } + fi || exit 1 + + trap '' 0 + fi +done + +# Local variables: +# eval: (add-hook 'write-file-hooks 'time-stamp) +# time-stamp-start: "scriptversion=" +# time-stamp-format: "%:y-%02m-%02d.%02H" +# time-stamp-time-zone: "UTC" +# time-stamp-end: "; # UTC" +# End: diff --git a/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/ltmain.sh b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/ltmain.sh new file mode 100755 index 0000000000..d88da2c264 --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/ltmain.sh @@ -0,0 +1,8413 @@ +# Generated from ltmain.m4sh. + +# ltmain.sh (GNU libtool) 2.2.6b +# Written by Gordon Matzigkeit , 1996 + +# Copyright (C) 1996, 1997, 1998, 1999, 2000, 2001, 2003, 2004, 2005, 2006, 2007 2008 Free Software Foundation, Inc. +# This is free software; see the source for copying conditions. There is NO +# warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + +# GNU Libtool is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2 of the License, or +# (at your option) any later version. +# +# As a special exception to the GNU General Public License, +# if you distribute this file as part of a program or library that +# is built using GNU Libtool, you may include this file under the +# same distribution terms that you use for the rest of that program. +# +# GNU Libtool is distributed in the hope that it will be useful, but +# WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +# General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with GNU Libtool; see the file COPYING. If not, a copy +# can be downloaded from http://www.gnu.org/licenses/gpl.html, +# or obtained by writing to the Free Software Foundation, Inc., +# 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. + +# Usage: $progname [OPTION]... [MODE-ARG]... +# +# Provide generalized library-building support services. +# +# --config show all configuration variables +# --debug enable verbose shell tracing +# -n, --dry-run display commands without modifying any files +# --features display basic configuration information and exit +# --mode=MODE use operation mode MODE +# --preserve-dup-deps don't remove duplicate dependency libraries +# --quiet, --silent don't print informational messages +# --tag=TAG use configuration variables from tag TAG +# -v, --verbose print informational messages (default) +# --version print version information +# -h, --help print short or long help message +# +# MODE must be one of the following: +# +# clean remove files from the build directory +# compile compile a source file into a libtool object +# execute automatically set library path, then run a program +# finish complete the installation of libtool libraries +# install install libraries or executables +# link create a library or an executable +# uninstall remove libraries from an installed directory +# +# MODE-ARGS vary depending on the MODE. +# Try `$progname --help --mode=MODE' for a more detailed description of MODE. +# +# When reporting a bug, please describe a test case to reproduce it and +# include the following information: +# +# host-triplet: $host +# shell: $SHELL +# compiler: $LTCC +# compiler flags: $LTCFLAGS +# linker: $LD (gnu? $with_gnu_ld) +# $progname: (GNU libtool) 2.2.6b Debian-2.2.6b-2 +# automake: $automake_version +# autoconf: $autoconf_version +# +# Report bugs to . + +PROGRAM=ltmain.sh +PACKAGE=libtool +VERSION="2.2.6b Debian-2.2.6b-2" +TIMESTAMP="" +package_revision=1.3017 + +# Be Bourne compatible +if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then + emulate sh + NULLCMD=: + # Zsh 3.x and 4.x performs word splitting on ${1+"$@"}, which + # is contrary to our usage. Disable this feature. + alias -g '${1+"$@"}'='"$@"' + setopt NO_GLOB_SUBST +else + case `(set -o) 2>/dev/null` in *posix*) set -o posix;; esac +fi +BIN_SH=xpg4; export BIN_SH # for Tru64 +DUALCASE=1; export DUALCASE # for MKS sh + +# NLS nuisances: We save the old values to restore during execute mode. +# Only set LANG and LC_ALL to C if already set. +# These must not be set unconditionally because not all systems understand +# e.g. LANG=C (notably SCO). +lt_user_locale= +lt_safe_locale= +for lt_var in LANG LANGUAGE LC_ALL LC_CTYPE LC_COLLATE LC_MESSAGES +do + eval "if test \"\${$lt_var+set}\" = set; then + save_$lt_var=\$$lt_var + $lt_var=C + export $lt_var + lt_user_locale=\"$lt_var=\\\$save_\$lt_var; \$lt_user_locale\" + lt_safe_locale=\"$lt_var=C; \$lt_safe_locale\" + fi" +done + +$lt_unset CDPATH + + + + + +: ${CP="cp -f"} +: ${ECHO="echo"} +: ${EGREP="/bin/grep -E"} +: ${FGREP="/bin/grep -F"} +: ${GREP="/bin/grep"} +: ${LN_S="ln -s"} +: ${MAKE="make"} +: ${MKDIR="mkdir"} +: ${MV="mv -f"} +: ${RM="rm -f"} +: ${SED="/bin/sed"} +: ${SHELL="${CONFIG_SHELL-/bin/sh}"} +: ${Xsed="$SED -e 1s/^X//"} + +# Global variables: +EXIT_SUCCESS=0 +EXIT_FAILURE=1 +EXIT_MISMATCH=63 # $? = 63 is used to indicate version mismatch to missing. +EXIT_SKIP=77 # $? = 77 is used to indicate a skipped test to automake. + +exit_status=$EXIT_SUCCESS + +# Make sure IFS has a sensible default +lt_nl=' +' +IFS=" $lt_nl" + +dirname="s,/[^/]*$,," +basename="s,^.*/,," + +# func_dirname_and_basename file append nondir_replacement +# perform func_basename and func_dirname in a single function +# call: +# dirname: Compute the dirname of FILE. If nonempty, +# add APPEND to the result, otherwise set result +# to NONDIR_REPLACEMENT. +# value returned in "$func_dirname_result" +# basename: Compute filename of FILE. +# value retuned in "$func_basename_result" +# Implementation must be kept synchronized with func_dirname +# and func_basename. For efficiency, we do not delegate to +# those functions but instead duplicate the functionality here. +func_dirname_and_basename () +{ + # Extract subdirectory from the argument. + func_dirname_result=`$ECHO "X${1}" | $Xsed -e "$dirname"` + if test "X$func_dirname_result" = "X${1}"; then + func_dirname_result="${3}" + else + func_dirname_result="$func_dirname_result${2}" + fi + func_basename_result=`$ECHO "X${1}" | $Xsed -e "$basename"` +} + +# Generated shell functions inserted here. + +# Work around backward compatibility issue on IRIX 6.5. On IRIX 6.4+, sh +# is ksh but when the shell is invoked as "sh" and the current value of +# the _XPG environment variable is not equal to 1 (one), the special +# positional parameter $0, within a function call, is the name of the +# function. +progpath="$0" + +# The name of this program: +# In the unlikely event $progname began with a '-', it would play havoc with +# func_echo (imagine progname=-n), so we prepend ./ in that case: +func_dirname_and_basename "$progpath" +progname=$func_basename_result +case $progname in + -*) progname=./$progname ;; +esac + +# Make sure we have an absolute path for reexecution: +case $progpath in + [\\/]*|[A-Za-z]:\\*) ;; + *[\\/]*) + progdir=$func_dirname_result + progdir=`cd "$progdir" && pwd` + progpath="$progdir/$progname" + ;; + *) + save_IFS="$IFS" + IFS=: + for progdir in $PATH; do + IFS="$save_IFS" + test -x "$progdir/$progname" && break + done + IFS="$save_IFS" + test -n "$progdir" || progdir=`pwd` + progpath="$progdir/$progname" + ;; +esac + +# Sed substitution that helps us do robust quoting. It backslashifies +# metacharacters that are still active within double-quoted strings. +Xsed="${SED}"' -e 1s/^X//' +sed_quote_subst='s/\([`"$\\]\)/\\\1/g' + +# Same as above, but do not quote variable references. +double_quote_subst='s/\(["`\\]\)/\\\1/g' + +# Re-`\' parameter expansions in output of double_quote_subst that were +# `\'-ed in input to the same. If an odd number of `\' preceded a '$' +# in input to double_quote_subst, that '$' was protected from expansion. +# Since each input `\' is now two `\'s, look for any number of runs of +# four `\'s followed by two `\'s and then a '$'. `\' that '$'. +bs='\\' +bs2='\\\\' +bs4='\\\\\\\\' +dollar='\$' +sed_double_backslash="\ + s/$bs4/&\\ +/g + s/^$bs2$dollar/$bs&/ + s/\\([^$bs]\\)$bs2$dollar/\\1$bs2$bs$dollar/g + s/\n//g" + +# Standard options: +opt_dry_run=false +opt_help=false +opt_quiet=false +opt_verbose=false +opt_warning=: + +# func_echo arg... +# Echo program name prefixed message, along with the current mode +# name if it has been set yet. +func_echo () +{ + $ECHO "$progname${mode+: }$mode: $*" +} + +# func_verbose arg... +# Echo program name prefixed message in verbose mode only. +func_verbose () +{ + $opt_verbose && func_echo ${1+"$@"} + + # A bug in bash halts the script if the last line of a function + # fails when set -e is in force, so we need another command to + # work around that: + : +} + +# func_error arg... +# Echo program name prefixed message to standard error. +func_error () +{ + $ECHO "$progname${mode+: }$mode: "${1+"$@"} 1>&2 +} + +# func_warning arg... +# Echo program name prefixed warning message to standard error. +func_warning () +{ + $opt_warning && $ECHO "$progname${mode+: }$mode: warning: "${1+"$@"} 1>&2 + + # bash bug again: + : +} + +# func_fatal_error arg... +# Echo program name prefixed message to standard error, and exit. +func_fatal_error () +{ + func_error ${1+"$@"} + exit $EXIT_FAILURE +} + +# func_fatal_help arg... +# Echo program name prefixed message to standard error, followed by +# a help hint, and exit. +func_fatal_help () +{ + func_error ${1+"$@"} + func_fatal_error "$help" +} +help="Try \`$progname --help' for more information." ## default + + +# func_grep expression filename +# Check whether EXPRESSION matches any line of FILENAME, without output. +func_grep () +{ + $GREP "$1" "$2" >/dev/null 2>&1 +} + + +# func_mkdir_p directory-path +# Make sure the entire path to DIRECTORY-PATH is available. +func_mkdir_p () +{ + my_directory_path="$1" + my_dir_list= + + if test -n "$my_directory_path" && test "$opt_dry_run" != ":"; then + + # Protect directory names starting with `-' + case $my_directory_path in + -*) my_directory_path="./$my_directory_path" ;; + esac + + # While some portion of DIR does not yet exist... + while test ! -d "$my_directory_path"; do + # ...make a list in topmost first order. Use a colon delimited + # list incase some portion of path contains whitespace. + my_dir_list="$my_directory_path:$my_dir_list" + + # If the last portion added has no slash in it, the list is done + case $my_directory_path in */*) ;; *) break ;; esac + + # ...otherwise throw away the child directory and loop + my_directory_path=`$ECHO "X$my_directory_path" | $Xsed -e "$dirname"` + done + my_dir_list=`$ECHO "X$my_dir_list" | $Xsed -e 's,:*$,,'` + + save_mkdir_p_IFS="$IFS"; IFS=':' + for my_dir in $my_dir_list; do + IFS="$save_mkdir_p_IFS" + # mkdir can fail with a `File exist' error if two processes + # try to create one of the directories concurrently. Don't + # stop in that case! + $MKDIR "$my_dir" 2>/dev/null || : + done + IFS="$save_mkdir_p_IFS" + + # Bail out if we (or some other process) failed to create a directory. + test -d "$my_directory_path" || \ + func_fatal_error "Failed to create \`$1'" + fi +} + + +# func_mktempdir [string] +# Make a temporary directory that won't clash with other running +# libtool processes, and avoids race conditions if possible. If +# given, STRING is the basename for that directory. +func_mktempdir () +{ + my_template="${TMPDIR-/tmp}/${1-$progname}" + + if test "$opt_dry_run" = ":"; then + # Return a directory name, but don't create it in dry-run mode + my_tmpdir="${my_template}-$$" + else + + # If mktemp works, use that first and foremost + my_tmpdir=`mktemp -d "${my_template}-XXXXXXXX" 2>/dev/null` + + if test ! -d "$my_tmpdir"; then + # Failing that, at least try and use $RANDOM to avoid a race + my_tmpdir="${my_template}-${RANDOM-0}$$" + + save_mktempdir_umask=`umask` + umask 0077 + $MKDIR "$my_tmpdir" + umask $save_mktempdir_umask + fi + + # If we're not in dry-run mode, bomb out on failure + test -d "$my_tmpdir" || \ + func_fatal_error "cannot create temporary directory \`$my_tmpdir'" + fi + + $ECHO "X$my_tmpdir" | $Xsed +} + + +# func_quote_for_eval arg +# Aesthetically quote ARG to be evaled later. +# This function returns two values: FUNC_QUOTE_FOR_EVAL_RESULT +# is double-quoted, suitable for a subsequent eval, whereas +# FUNC_QUOTE_FOR_EVAL_UNQUOTED_RESULT has merely all characters +# which are still active within double quotes backslashified. +func_quote_for_eval () +{ + case $1 in + *[\\\`\"\$]*) + func_quote_for_eval_unquoted_result=`$ECHO "X$1" | $Xsed -e "$sed_quote_subst"` ;; + *) + func_quote_for_eval_unquoted_result="$1" ;; + esac + + case $func_quote_for_eval_unquoted_result in + # Double-quote args containing shell metacharacters to delay + # word splitting, command substitution and and variable + # expansion for a subsequent eval. + # Many Bourne shells cannot handle close brackets correctly + # in scan sets, so we specify it separately. + *[\[\~\#\^\&\*\(\)\{\}\|\;\<\>\?\'\ \ ]*|*]*|"") + func_quote_for_eval_result="\"$func_quote_for_eval_unquoted_result\"" + ;; + *) + func_quote_for_eval_result="$func_quote_for_eval_unquoted_result" + esac +} + + +# func_quote_for_expand arg +# Aesthetically quote ARG to be evaled later; same as above, +# but do not quote variable references. +func_quote_for_expand () +{ + case $1 in + *[\\\`\"]*) + my_arg=`$ECHO "X$1" | $Xsed \ + -e "$double_quote_subst" -e "$sed_double_backslash"` ;; + *) + my_arg="$1" ;; + esac + + case $my_arg in + # Double-quote args containing shell metacharacters to delay + # word splitting and command substitution for a subsequent eval. + # Many Bourne shells cannot handle close brackets correctly + # in scan sets, so we specify it separately. + *[\[\~\#\^\&\*\(\)\{\}\|\;\<\>\?\'\ \ ]*|*]*|"") + my_arg="\"$my_arg\"" + ;; + esac + + func_quote_for_expand_result="$my_arg" +} + + +# func_show_eval cmd [fail_exp] +# Unless opt_silent is true, then output CMD. Then, if opt_dryrun is +# not true, evaluate CMD. If the evaluation of CMD fails, and FAIL_EXP +# is given, then evaluate it. +func_show_eval () +{ + my_cmd="$1" + my_fail_exp="${2-:}" + + ${opt_silent-false} || { + func_quote_for_expand "$my_cmd" + eval "func_echo $func_quote_for_expand_result" + } + + if ${opt_dry_run-false}; then :; else + eval "$my_cmd" + my_status=$? + if test "$my_status" -eq 0; then :; else + eval "(exit $my_status); $my_fail_exp" + fi + fi +} + + +# func_show_eval_locale cmd [fail_exp] +# Unless opt_silent is true, then output CMD. Then, if opt_dryrun is +# not true, evaluate CMD. If the evaluation of CMD fails, and FAIL_EXP +# is given, then evaluate it. Use the saved locale for evaluation. +func_show_eval_locale () +{ + my_cmd="$1" + my_fail_exp="${2-:}" + + ${opt_silent-false} || { + func_quote_for_expand "$my_cmd" + eval "func_echo $func_quote_for_expand_result" + } + + if ${opt_dry_run-false}; then :; else + eval "$lt_user_locale + $my_cmd" + my_status=$? + eval "$lt_safe_locale" + if test "$my_status" -eq 0; then :; else + eval "(exit $my_status); $my_fail_exp" + fi + fi +} + + + + + +# func_version +# Echo version message to standard output and exit. +func_version () +{ + $SED -n '/^# '$PROGRAM' (GNU /,/# warranty; / { + s/^# // + s/^# *$// + s/\((C)\)[ 0-9,-]*\( [1-9][0-9]*\)/\1\2/ + p + }' < "$progpath" + exit $? +} + +# func_usage +# Echo short help message to standard output and exit. +func_usage () +{ + $SED -n '/^# Usage:/,/# -h/ { + s/^# // + s/^# *$// + s/\$progname/'$progname'/ + p + }' < "$progpath" + $ECHO + $ECHO "run \`$progname --help | more' for full usage" + exit $? +} + +# func_help +# Echo long help message to standard output and exit. +func_help () +{ + $SED -n '/^# Usage:/,/# Report bugs to/ { + s/^# // + s/^# *$// + s*\$progname*'$progname'* + s*\$host*'"$host"'* + s*\$SHELL*'"$SHELL"'* + s*\$LTCC*'"$LTCC"'* + s*\$LTCFLAGS*'"$LTCFLAGS"'* + s*\$LD*'"$LD"'* + s/\$with_gnu_ld/'"$with_gnu_ld"'/ + s/\$automake_version/'"`(automake --version) 2>/dev/null |$SED 1q`"'/ + s/\$autoconf_version/'"`(autoconf --version) 2>/dev/null |$SED 1q`"'/ + p + }' < "$progpath" + exit $? +} + +# func_missing_arg argname +# Echo program name prefixed message to standard error and set global +# exit_cmd. +func_missing_arg () +{ + func_error "missing argument for $1" + exit_cmd=exit +} + +exit_cmd=: + + + + + +# Check that we have a working $ECHO. +if test "X$1" = X--no-reexec; then + # Discard the --no-reexec flag, and continue. + shift +elif test "X$1" = X--fallback-echo; then + # Avoid inline document here, it may be left over + : +elif test "X`{ $ECHO '\t'; } 2>/dev/null`" = 'X\t'; then + # Yippee, $ECHO works! + : +else + # Restart under the correct shell, and then maybe $ECHO will work. + exec $SHELL "$progpath" --no-reexec ${1+"$@"} +fi + +if test "X$1" = X--fallback-echo; then + # used as fallback echo + shift + cat </dev/null 2>&1; then + taglist="$taglist $tagname" + + # Evaluate the configuration. Be careful to quote the path + # and the sed script, to avoid splitting on whitespace, but + # also don't use non-portable quotes within backquotes within + # quotes we have to do it in 2 steps: + extractedcf=`$SED -n -e "$sed_extractcf" < "$progpath"` + eval "$extractedcf" + else + func_error "ignoring unknown tag $tagname" + fi + ;; + esac +} + +# Parse options once, thoroughly. This comes as soon as possible in +# the script to make things like `libtool --version' happen quickly. +{ + + # Shorthand for --mode=foo, only valid as the first argument + case $1 in + clean|clea|cle|cl) + shift; set dummy --mode clean ${1+"$@"}; shift + ;; + compile|compil|compi|comp|com|co|c) + shift; set dummy --mode compile ${1+"$@"}; shift + ;; + execute|execut|execu|exec|exe|ex|e) + shift; set dummy --mode execute ${1+"$@"}; shift + ;; + finish|finis|fini|fin|fi|f) + shift; set dummy --mode finish ${1+"$@"}; shift + ;; + install|instal|insta|inst|ins|in|i) + shift; set dummy --mode install ${1+"$@"}; shift + ;; + link|lin|li|l) + shift; set dummy --mode link ${1+"$@"}; shift + ;; + uninstall|uninstal|uninsta|uninst|unins|unin|uni|un|u) + shift; set dummy --mode uninstall ${1+"$@"}; shift + ;; + esac + + # Parse non-mode specific arguments: + while test "$#" -gt 0; do + opt="$1" + shift + + case $opt in + --config) func_config ;; + + --debug) preserve_args="$preserve_args $opt" + func_echo "enabling shell trace mode" + opt_debug='set -x' + $opt_debug + ;; + + -dlopen) test "$#" -eq 0 && func_missing_arg "$opt" && break + execute_dlfiles="$execute_dlfiles $1" + shift + ;; + + --dry-run | -n) opt_dry_run=: ;; + --features) func_features ;; + --finish) mode="finish" ;; + + --mode) test "$#" -eq 0 && func_missing_arg "$opt" && break + case $1 in + # Valid mode arguments: + clean) ;; + compile) ;; + execute) ;; + finish) ;; + install) ;; + link) ;; + relink) ;; + uninstall) ;; + + # Catch anything else as an error + *) func_error "invalid argument for $opt" + exit_cmd=exit + break + ;; + esac + + mode="$1" + shift + ;; + + --preserve-dup-deps) + opt_duplicate_deps=: ;; + + --quiet|--silent) preserve_args="$preserve_args $opt" + opt_silent=: + ;; + + --verbose| -v) preserve_args="$preserve_args $opt" + opt_silent=false + ;; + + --tag) test "$#" -eq 0 && func_missing_arg "$opt" && break + preserve_args="$preserve_args $opt $1" + func_enable_tag "$1" # tagname is set here + shift + ;; + + # Separate optargs to long options: + -dlopen=*|--mode=*|--tag=*) + func_opt_split "$opt" + set dummy "$func_opt_split_opt" "$func_opt_split_arg" ${1+"$@"} + shift + ;; + + -\?|-h) func_usage ;; + --help) opt_help=: ;; + --version) func_version ;; + + -*) func_fatal_help "unrecognized option \`$opt'" ;; + + *) nonopt="$opt" + break + ;; + esac + done + + + case $host in + *cygwin* | *mingw* | *pw32* | *cegcc*) + # don't eliminate duplications in $postdeps and $predeps + opt_duplicate_compiler_generated_deps=: + ;; + *) + opt_duplicate_compiler_generated_deps=$opt_duplicate_deps + ;; + esac + + # Having warned about all mis-specified options, bail out if + # anything was wrong. + $exit_cmd $EXIT_FAILURE +} + +# func_check_version_match +# Ensure that we are using m4 macros, and libtool script from the same +# release of libtool. +func_check_version_match () +{ + if test "$package_revision" != "$macro_revision"; then + if test "$VERSION" != "$macro_version"; then + if test -z "$macro_version"; then + cat >&2 <<_LT_EOF +$progname: Version mismatch error. This is $PACKAGE $VERSION, but the +$progname: definition of this LT_INIT comes from an older release. +$progname: You should recreate aclocal.m4 with macros from $PACKAGE $VERSION +$progname: and run autoconf again. +_LT_EOF + else + cat >&2 <<_LT_EOF +$progname: Version mismatch error. This is $PACKAGE $VERSION, but the +$progname: definition of this LT_INIT comes from $PACKAGE $macro_version. +$progname: You should recreate aclocal.m4 with macros from $PACKAGE $VERSION +$progname: and run autoconf again. +_LT_EOF + fi + else + cat >&2 <<_LT_EOF +$progname: Version mismatch error. This is $PACKAGE $VERSION, revision $package_revision, +$progname: but the definition of this LT_INIT comes from revision $macro_revision. +$progname: You should recreate aclocal.m4 with macros from revision $package_revision +$progname: of $PACKAGE $VERSION and run autoconf again. +_LT_EOF + fi + + exit $EXIT_MISMATCH + fi +} + + +## ----------- ## +## Main. ## +## ----------- ## + +$opt_help || { + # Sanity checks first: + func_check_version_match + + if test "$build_libtool_libs" != yes && test "$build_old_libs" != yes; then + func_fatal_configuration "not configured to build any kind of library" + fi + + test -z "$mode" && func_fatal_error "error: you must specify a MODE." + + + # Darwin sucks + eval std_shrext=\"$shrext_cmds\" + + + # Only execute mode is allowed to have -dlopen flags. + if test -n "$execute_dlfiles" && test "$mode" != execute; then + func_error "unrecognized option \`-dlopen'" + $ECHO "$help" 1>&2 + exit $EXIT_FAILURE + fi + + # Change the help message to a mode-specific one. + generic_help="$help" + help="Try \`$progname --help --mode=$mode' for more information." +} + + +# func_lalib_p file +# True iff FILE is a libtool `.la' library or `.lo' object file. +# This function is only a basic sanity check; it will hardly flush out +# determined imposters. +func_lalib_p () +{ + test -f "$1" && + $SED -e 4q "$1" 2>/dev/null \ + | $GREP "^# Generated by .*$PACKAGE" > /dev/null 2>&1 +} + +# func_lalib_unsafe_p file +# True iff FILE is a libtool `.la' library or `.lo' object file. +# This function implements the same check as func_lalib_p without +# resorting to external programs. To this end, it redirects stdin and +# closes it afterwards, without saving the original file descriptor. +# As a safety measure, use it only where a negative result would be +# fatal anyway. Works if `file' does not exist. +func_lalib_unsafe_p () +{ + lalib_p=no + if test -f "$1" && test -r "$1" && exec 5<&0 <"$1"; then + for lalib_p_l in 1 2 3 4 + do + read lalib_p_line + case "$lalib_p_line" in + \#\ Generated\ by\ *$PACKAGE* ) lalib_p=yes; break;; + esac + done + exec 0<&5 5<&- + fi + test "$lalib_p" = yes +} + +# func_ltwrapper_script_p file +# True iff FILE is a libtool wrapper script +# This function is only a basic sanity check; it will hardly flush out +# determined imposters. +func_ltwrapper_script_p () +{ + func_lalib_p "$1" +} + +# func_ltwrapper_executable_p file +# True iff FILE is a libtool wrapper executable +# This function is only a basic sanity check; it will hardly flush out +# determined imposters. +func_ltwrapper_executable_p () +{ + func_ltwrapper_exec_suffix= + case $1 in + *.exe) ;; + *) func_ltwrapper_exec_suffix=.exe ;; + esac + $GREP "$magic_exe" "$1$func_ltwrapper_exec_suffix" >/dev/null 2>&1 +} + +# func_ltwrapper_scriptname file +# Assumes file is an ltwrapper_executable +# uses $file to determine the appropriate filename for a +# temporary ltwrapper_script. +func_ltwrapper_scriptname () +{ + func_ltwrapper_scriptname_result="" + if func_ltwrapper_executable_p "$1"; then + func_dirname_and_basename "$1" "" "." + func_stripname '' '.exe' "$func_basename_result" + func_ltwrapper_scriptname_result="$func_dirname_result/$objdir/${func_stripname_result}_ltshwrapper" + fi +} + +# func_ltwrapper_p file +# True iff FILE is a libtool wrapper script or wrapper executable +# This function is only a basic sanity check; it will hardly flush out +# determined imposters. +func_ltwrapper_p () +{ + func_ltwrapper_script_p "$1" || func_ltwrapper_executable_p "$1" +} + + +# func_execute_cmds commands fail_cmd +# Execute tilde-delimited COMMANDS. +# If FAIL_CMD is given, eval that upon failure. +# FAIL_CMD may read-access the current command in variable CMD! +func_execute_cmds () +{ + $opt_debug + save_ifs=$IFS; IFS='~' + for cmd in $1; do + IFS=$save_ifs + eval cmd=\"$cmd\" + func_show_eval "$cmd" "${2-:}" + done + IFS=$save_ifs +} + + +# func_source file +# Source FILE, adding directory component if necessary. +# Note that it is not necessary on cygwin/mingw to append a dot to +# FILE even if both FILE and FILE.exe exist: automatic-append-.exe +# behavior happens only for exec(3), not for open(2)! Also, sourcing +# `FILE.' does not work on cygwin managed mounts. +func_source () +{ + $opt_debug + case $1 in + */* | *\\*) . "$1" ;; + *) . "./$1" ;; + esac +} + + +# func_infer_tag arg +# Infer tagged configuration to use if any are available and +# if one wasn't chosen via the "--tag" command line option. +# Only attempt this if the compiler in the base compile +# command doesn't match the default compiler. +# arg is usually of the form 'gcc ...' +func_infer_tag () +{ + $opt_debug + if test -n "$available_tags" && test -z "$tagname"; then + CC_quoted= + for arg in $CC; do + func_quote_for_eval "$arg" + CC_quoted="$CC_quoted $func_quote_for_eval_result" + done + case $@ in + # Blanks in the command may have been stripped by the calling shell, + # but not from the CC environment variable when configure was run. + " $CC "* | "$CC "* | " `$ECHO $CC` "* | "`$ECHO $CC` "* | " $CC_quoted"* | "$CC_quoted "* | " `$ECHO $CC_quoted` "* | "`$ECHO $CC_quoted` "*) ;; + # Blanks at the start of $base_compile will cause this to fail + # if we don't check for them as well. + *) + for z in $available_tags; do + if $GREP "^# ### BEGIN LIBTOOL TAG CONFIG: $z$" < "$progpath" > /dev/null; then + # Evaluate the configuration. + eval "`${SED} -n -e '/^# ### BEGIN LIBTOOL TAG CONFIG: '$z'$/,/^# ### END LIBTOOL TAG CONFIG: '$z'$/p' < $progpath`" + CC_quoted= + for arg in $CC; do + # Double-quote args containing other shell metacharacters. + func_quote_for_eval "$arg" + CC_quoted="$CC_quoted $func_quote_for_eval_result" + done + case "$@ " in + " $CC "* | "$CC "* | " `$ECHO $CC` "* | "`$ECHO $CC` "* | " $CC_quoted"* | "$CC_quoted "* | " `$ECHO $CC_quoted` "* | "`$ECHO $CC_quoted` "*) + # The compiler in the base compile command matches + # the one in the tagged configuration. + # Assume this is the tagged configuration we want. + tagname=$z + break + ;; + esac + fi + done + # If $tagname still isn't set, then no tagged configuration + # was found and let the user know that the "--tag" command + # line option must be used. + if test -z "$tagname"; then + func_echo "unable to infer tagged configuration" + func_fatal_error "specify a tag with \`--tag'" +# else +# func_verbose "using $tagname tagged configuration" + fi + ;; + esac + fi +} + + + +# func_write_libtool_object output_name pic_name nonpic_name +# Create a libtool object file (analogous to a ".la" file), +# but don't create it if we're doing a dry run. +func_write_libtool_object () +{ + write_libobj=${1} + if test "$build_libtool_libs" = yes; then + write_lobj=\'${2}\' + else + write_lobj=none + fi + + if test "$build_old_libs" = yes; then + write_oldobj=\'${3}\' + else + write_oldobj=none + fi + + $opt_dry_run || { + cat >${write_libobj}T <?"'"'"' &()|`$[]' \ + && func_warning "libobj name \`$libobj' may not contain shell special characters." + func_dirname_and_basename "$obj" "/" "" + objname="$func_basename_result" + xdir="$func_dirname_result" + lobj=${xdir}$objdir/$objname + + test -z "$base_compile" && \ + func_fatal_help "you must specify a compilation command" + + # Delete any leftover library objects. + if test "$build_old_libs" = yes; then + removelist="$obj $lobj $libobj ${libobj}T" + else + removelist="$lobj $libobj ${libobj}T" + fi + + # On Cygwin there's no "real" PIC flag so we must build both object types + case $host_os in + cygwin* | mingw* | pw32* | os2* | cegcc*) + pic_mode=default + ;; + esac + if test "$pic_mode" = no && test "$deplibs_check_method" != pass_all; then + # non-PIC code in shared libraries is not supported + pic_mode=default + fi + + # Calculate the filename of the output object if compiler does + # not support -o with -c + if test "$compiler_c_o" = no; then + output_obj=`$ECHO "X$srcfile" | $Xsed -e 's%^.*/%%' -e 's%\.[^.]*$%%'`.${objext} + lockfile="$output_obj.lock" + else + output_obj= + need_locks=no + lockfile= + fi + + # Lock this critical section if it is needed + # We use this script file to make the link, it avoids creating a new file + if test "$need_locks" = yes; then + until $opt_dry_run || ln "$progpath" "$lockfile" 2>/dev/null; do + func_echo "Waiting for $lockfile to be removed" + sleep 2 + done + elif test "$need_locks" = warn; then + if test -f "$lockfile"; then + $ECHO "\ +*** ERROR, $lockfile exists and contains: +`cat $lockfile 2>/dev/null` + +This indicates that another process is trying to use the same +temporary object file, and libtool could not work around it because +your compiler does not support \`-c' and \`-o' together. If you +repeat this compilation, it may succeed, by chance, but you had better +avoid parallel builds (make -j) in this platform, or get a better +compiler." + + $opt_dry_run || $RM $removelist + exit $EXIT_FAILURE + fi + removelist="$removelist $output_obj" + $ECHO "$srcfile" > "$lockfile" + fi + + $opt_dry_run || $RM $removelist + removelist="$removelist $lockfile" + trap '$opt_dry_run || $RM $removelist; exit $EXIT_FAILURE' 1 2 15 + + if test -n "$fix_srcfile_path"; then + eval srcfile=\"$fix_srcfile_path\" + fi + func_quote_for_eval "$srcfile" + qsrcfile=$func_quote_for_eval_result + + # Only build a PIC object if we are building libtool libraries. + if test "$build_libtool_libs" = yes; then + # Without this assignment, base_compile gets emptied. + fbsd_hideous_sh_bug=$base_compile + + if test "$pic_mode" != no; then + command="$base_compile $qsrcfile $pic_flag" + else + # Don't build PIC code + command="$base_compile $qsrcfile" + fi + + func_mkdir_p "$xdir$objdir" + + if test -z "$output_obj"; then + # Place PIC objects in $objdir + command="$command -o $lobj" + fi + + func_show_eval_locale "$command" \ + 'test -n "$output_obj" && $RM $removelist; exit $EXIT_FAILURE' + + if test "$need_locks" = warn && + test "X`cat $lockfile 2>/dev/null`" != "X$srcfile"; then + $ECHO "\ +*** ERROR, $lockfile contains: +`cat $lockfile 2>/dev/null` + +but it should contain: +$srcfile + +This indicates that another process is trying to use the same +temporary object file, and libtool could not work around it because +your compiler does not support \`-c' and \`-o' together. If you +repeat this compilation, it may succeed, by chance, but you had better +avoid parallel builds (make -j) in this platform, or get a better +compiler." + + $opt_dry_run || $RM $removelist + exit $EXIT_FAILURE + fi + + # Just move the object if needed, then go on to compile the next one + if test -n "$output_obj" && test "X$output_obj" != "X$lobj"; then + func_show_eval '$MV "$output_obj" "$lobj"' \ + 'error=$?; $opt_dry_run || $RM $removelist; exit $error' + fi + + # Allow error messages only from the first compilation. + if test "$suppress_opt" = yes; then + suppress_output=' >/dev/null 2>&1' + fi + fi + + # Only build a position-dependent object if we build old libraries. + if test "$build_old_libs" = yes; then + if test "$pic_mode" != yes; then + # Don't build PIC code + command="$base_compile $qsrcfile$pie_flag" + else + command="$base_compile $qsrcfile $pic_flag" + fi + if test "$compiler_c_o" = yes; then + command="$command -o $obj" + fi + + # Suppress compiler output if we already did a PIC compilation. + command="$command$suppress_output" + func_show_eval_locale "$command" \ + '$opt_dry_run || $RM $removelist; exit $EXIT_FAILURE' + + if test "$need_locks" = warn && + test "X`cat $lockfile 2>/dev/null`" != "X$srcfile"; then + $ECHO "\ +*** ERROR, $lockfile contains: +`cat $lockfile 2>/dev/null` + +but it should contain: +$srcfile + +This indicates that another process is trying to use the same +temporary object file, and libtool could not work around it because +your compiler does not support \`-c' and \`-o' together. If you +repeat this compilation, it may succeed, by chance, but you had better +avoid parallel builds (make -j) in this platform, or get a better +compiler." + + $opt_dry_run || $RM $removelist + exit $EXIT_FAILURE + fi + + # Just move the object if needed + if test -n "$output_obj" && test "X$output_obj" != "X$obj"; then + func_show_eval '$MV "$output_obj" "$obj"' \ + 'error=$?; $opt_dry_run || $RM $removelist; exit $error' + fi + fi + + $opt_dry_run || { + func_write_libtool_object "$libobj" "$objdir/$objname" "$objname" + + # Unlock the critical section if it was locked + if test "$need_locks" != no; then + removelist=$lockfile + $RM "$lockfile" + fi + } + + exit $EXIT_SUCCESS +} + +$opt_help || { +test "$mode" = compile && func_mode_compile ${1+"$@"} +} + +func_mode_help () +{ + # We need to display help for each of the modes. + case $mode in + "") + # Generic help is extracted from the usage comments + # at the start of this file. + func_help + ;; + + clean) + $ECHO \ +"Usage: $progname [OPTION]... --mode=clean RM [RM-OPTION]... FILE... + +Remove files from the build directory. + +RM is the name of the program to use to delete files associated with each FILE +(typically \`/bin/rm'). RM-OPTIONS are options (such as \`-f') to be passed +to RM. + +If FILE is a libtool library, object or program, all the files associated +with it are deleted. Otherwise, only FILE itself is deleted using RM." + ;; + + compile) + $ECHO \ +"Usage: $progname [OPTION]... --mode=compile COMPILE-COMMAND... SOURCEFILE + +Compile a source file into a libtool library object. + +This mode accepts the following additional options: + + -o OUTPUT-FILE set the output file name to OUTPUT-FILE + -no-suppress do not suppress compiler output for multiple passes + -prefer-pic try to building PIC objects only + -prefer-non-pic try to building non-PIC objects only + -shared do not build a \`.o' file suitable for static linking + -static only build a \`.o' file suitable for static linking + +COMPILE-COMMAND is a command to be used in creating a \`standard' object file +from the given SOURCEFILE. + +The output file name is determined by removing the directory component from +SOURCEFILE, then substituting the C source code suffix \`.c' with the +library object suffix, \`.lo'." + ;; + + execute) + $ECHO \ +"Usage: $progname [OPTION]... --mode=execute COMMAND [ARGS]... + +Automatically set library path, then run a program. + +This mode accepts the following additional options: + + -dlopen FILE add the directory containing FILE to the library path + +This mode sets the library path environment variable according to \`-dlopen' +flags. + +If any of the ARGS are libtool executable wrappers, then they are translated +into their corresponding uninstalled binary, and any of their required library +directories are added to the library path. + +Then, COMMAND is executed, with ARGS as arguments." + ;; + + finish) + $ECHO \ +"Usage: $progname [OPTION]... --mode=finish [LIBDIR]... + +Complete the installation of libtool libraries. + +Each LIBDIR is a directory that contains libtool libraries. + +The commands that this mode executes may require superuser privileges. Use +the \`--dry-run' option if you just want to see what would be executed." + ;; + + install) + $ECHO \ +"Usage: $progname [OPTION]... --mode=install INSTALL-COMMAND... + +Install executables or libraries. + +INSTALL-COMMAND is the installation command. The first component should be +either the \`install' or \`cp' program. + +The following components of INSTALL-COMMAND are treated specially: + + -inst-prefix PREFIX-DIR Use PREFIX-DIR as a staging area for installation + +The rest of the components are interpreted as arguments to that command (only +BSD-compatible install options are recognized)." + ;; + + link) + $ECHO \ +"Usage: $progname [OPTION]... --mode=link LINK-COMMAND... + +Link object files or libraries together to form another library, or to +create an executable program. + +LINK-COMMAND is a command using the C compiler that you would use to create +a program from several object files. + +The following components of LINK-COMMAND are treated specially: + + -all-static do not do any dynamic linking at all + -avoid-version do not add a version suffix if possible + -dlopen FILE \`-dlpreopen' FILE if it cannot be dlopened at runtime + -dlpreopen FILE link in FILE and add its symbols to lt_preloaded_symbols + -export-dynamic allow symbols from OUTPUT-FILE to be resolved with dlsym(3) + -export-symbols SYMFILE + try to export only the symbols listed in SYMFILE + -export-symbols-regex REGEX + try to export only the symbols matching REGEX + -LLIBDIR search LIBDIR for required installed libraries + -lNAME OUTPUT-FILE requires the installed library libNAME + -module build a library that can dlopened + -no-fast-install disable the fast-install mode + -no-install link a not-installable executable + -no-undefined declare that a library does not refer to external symbols + -o OUTPUT-FILE create OUTPUT-FILE from the specified objects + -objectlist FILE Use a list of object files found in FILE to specify objects + -precious-files-regex REGEX + don't remove output files matching REGEX + -release RELEASE specify package release information + -rpath LIBDIR the created library will eventually be installed in LIBDIR + -R[ ]LIBDIR add LIBDIR to the runtime path of programs and libraries + -shared only do dynamic linking of libtool libraries + -shrext SUFFIX override the standard shared library file extension + -static do not do any dynamic linking of uninstalled libtool libraries + -static-libtool-libs + do not do any dynamic linking of libtool libraries + -version-info CURRENT[:REVISION[:AGE]] + specify library version info [each variable defaults to 0] + -weak LIBNAME declare that the target provides the LIBNAME interface + +All other options (arguments beginning with \`-') are ignored. + +Every other argument is treated as a filename. Files ending in \`.la' are +treated as uninstalled libtool libraries, other files are standard or library +object files. + +If the OUTPUT-FILE ends in \`.la', then a libtool library is created, +only library objects (\`.lo' files) may be specified, and \`-rpath' is +required, except when creating a convenience library. + +If OUTPUT-FILE ends in \`.a' or \`.lib', then a standard library is created +using \`ar' and \`ranlib', or on Windows using \`lib'. + +If OUTPUT-FILE ends in \`.lo' or \`.${objext}', then a reloadable object file +is created, otherwise an executable program is created." + ;; + + uninstall) + $ECHO \ +"Usage: $progname [OPTION]... --mode=uninstall RM [RM-OPTION]... FILE... + +Remove libraries from an installation directory. + +RM is the name of the program to use to delete files associated with each FILE +(typically \`/bin/rm'). RM-OPTIONS are options (such as \`-f') to be passed +to RM. + +If FILE is a libtool library, all the files associated with it are deleted. +Otherwise, only FILE itself is deleted using RM." + ;; + + *) + func_fatal_help "invalid operation mode \`$mode'" + ;; + esac + + $ECHO + $ECHO "Try \`$progname --help' for more information about other modes." + + exit $? +} + + # Now that we've collected a possible --mode arg, show help if necessary + $opt_help && func_mode_help + + +# func_mode_execute arg... +func_mode_execute () +{ + $opt_debug + # The first argument is the command name. + cmd="$nonopt" + test -z "$cmd" && \ + func_fatal_help "you must specify a COMMAND" + + # Handle -dlopen flags immediately. + for file in $execute_dlfiles; do + test -f "$file" \ + || func_fatal_help "\`$file' is not a file" + + dir= + case $file in + *.la) + # Check to see that this really is a libtool archive. + func_lalib_unsafe_p "$file" \ + || func_fatal_help "\`$lib' is not a valid libtool archive" + + # Read the libtool library. + dlname= + library_names= + func_source "$file" + + # Skip this library if it cannot be dlopened. + if test -z "$dlname"; then + # Warn if it was a shared library. + test -n "$library_names" && \ + func_warning "\`$file' was not linked with \`-export-dynamic'" + continue + fi + + func_dirname "$file" "" "." + dir="$func_dirname_result" + + if test -f "$dir/$objdir/$dlname"; then + dir="$dir/$objdir" + else + if test ! -f "$dir/$dlname"; then + func_fatal_error "cannot find \`$dlname' in \`$dir' or \`$dir/$objdir'" + fi + fi + ;; + + *.lo) + # Just add the directory containing the .lo file. + func_dirname "$file" "" "." + dir="$func_dirname_result" + ;; + + *) + func_warning "\`-dlopen' is ignored for non-libtool libraries and objects" + continue + ;; + esac + + # Get the absolute pathname. + absdir=`cd "$dir" && pwd` + test -n "$absdir" && dir="$absdir" + + # Now add the directory to shlibpath_var. + if eval "test -z \"\$$shlibpath_var\""; then + eval "$shlibpath_var=\"\$dir\"" + else + eval "$shlibpath_var=\"\$dir:\$$shlibpath_var\"" + fi + done + + # This variable tells wrapper scripts just to set shlibpath_var + # rather than running their programs. + libtool_execute_magic="$magic" + + # Check if any of the arguments is a wrapper script. + args= + for file + do + case $file in + -*) ;; + *) + # Do a test to see if this is really a libtool program. + if func_ltwrapper_script_p "$file"; then + func_source "$file" + # Transform arg to wrapped name. + file="$progdir/$program" + elif func_ltwrapper_executable_p "$file"; then + func_ltwrapper_scriptname "$file" + func_source "$func_ltwrapper_scriptname_result" + # Transform arg to wrapped name. + file="$progdir/$program" + fi + ;; + esac + # Quote arguments (to preserve shell metacharacters). + func_quote_for_eval "$file" + args="$args $func_quote_for_eval_result" + done + + if test "X$opt_dry_run" = Xfalse; then + if test -n "$shlibpath_var"; then + # Export the shlibpath_var. + eval "export $shlibpath_var" + fi + + # Restore saved environment variables + for lt_var in LANG LANGUAGE LC_ALL LC_CTYPE LC_COLLATE LC_MESSAGES + do + eval "if test \"\${save_$lt_var+set}\" = set; then + $lt_var=\$save_$lt_var; export $lt_var + else + $lt_unset $lt_var + fi" + done + + # Now prepare to actually exec the command. + exec_cmd="\$cmd$args" + else + # Display what would be done. + if test -n "$shlibpath_var"; then + eval "\$ECHO \"\$shlibpath_var=\$$shlibpath_var\"" + $ECHO "export $shlibpath_var" + fi + $ECHO "$cmd$args" + exit $EXIT_SUCCESS + fi +} + +test "$mode" = execute && func_mode_execute ${1+"$@"} + + +# func_mode_finish arg... +func_mode_finish () +{ + $opt_debug + libdirs="$nonopt" + admincmds= + + if test -n "$finish_cmds$finish_eval" && test -n "$libdirs"; then + for dir + do + libdirs="$libdirs $dir" + done + + for libdir in $libdirs; do + if test -n "$finish_cmds"; then + # Do each command in the finish commands. + func_execute_cmds "$finish_cmds" 'admincmds="$admincmds +'"$cmd"'"' + fi + if test -n "$finish_eval"; then + # Do the single finish_eval. + eval cmds=\"$finish_eval\" + $opt_dry_run || eval "$cmds" || admincmds="$admincmds + $cmds" + fi + done + fi + + # Exit here if they wanted silent mode. + $opt_silent && exit $EXIT_SUCCESS + + $ECHO "X----------------------------------------------------------------------" | $Xsed + $ECHO "Libraries have been installed in:" + for libdir in $libdirs; do + $ECHO " $libdir" + done + $ECHO + $ECHO "If you ever happen to want to link against installed libraries" + $ECHO "in a given directory, LIBDIR, you must either use libtool, and" + $ECHO "specify the full pathname of the library, or use the \`-LLIBDIR'" + $ECHO "flag during linking and do at least one of the following:" + if test -n "$shlibpath_var"; then + $ECHO " - add LIBDIR to the \`$shlibpath_var' environment variable" + $ECHO " during execution" + fi + if test -n "$runpath_var"; then + $ECHO " - add LIBDIR to the \`$runpath_var' environment variable" + $ECHO " during linking" + fi + if test -n "$hardcode_libdir_flag_spec"; then + libdir=LIBDIR + eval flag=\"$hardcode_libdir_flag_spec\" + + $ECHO " - use the \`$flag' linker flag" + fi + if test -n "$admincmds"; then + $ECHO " - have your system administrator run these commands:$admincmds" + fi + if test -f /etc/ld.so.conf; then + $ECHO " - have your system administrator add LIBDIR to \`/etc/ld.so.conf'" + fi + $ECHO + + $ECHO "See any operating system documentation about shared libraries for" + case $host in + solaris2.[6789]|solaris2.1[0-9]) + $ECHO "more information, such as the ld(1), crle(1) and ld.so(8) manual" + $ECHO "pages." + ;; + *) + $ECHO "more information, such as the ld(1) and ld.so(8) manual pages." + ;; + esac + $ECHO "X----------------------------------------------------------------------" | $Xsed + exit $EXIT_SUCCESS +} + +test "$mode" = finish && func_mode_finish ${1+"$@"} + + +# func_mode_install arg... +func_mode_install () +{ + $opt_debug + # There may be an optional sh(1) argument at the beginning of + # install_prog (especially on Windows NT). + if test "$nonopt" = "$SHELL" || test "$nonopt" = /bin/sh || + # Allow the use of GNU shtool's install command. + $ECHO "X$nonopt" | $GREP shtool >/dev/null; then + # Aesthetically quote it. + func_quote_for_eval "$nonopt" + install_prog="$func_quote_for_eval_result " + arg=$1 + shift + else + install_prog= + arg=$nonopt + fi + + # The real first argument should be the name of the installation program. + # Aesthetically quote it. + func_quote_for_eval "$arg" + install_prog="$install_prog$func_quote_for_eval_result" + + # We need to accept at least all the BSD install flags. + dest= + files= + opts= + prev= + install_type= + isdir=no + stripme= + for arg + do + if test -n "$dest"; then + files="$files $dest" + dest=$arg + continue + fi + + case $arg in + -d) isdir=yes ;; + -f) + case " $install_prog " in + *[\\\ /]cp\ *) ;; + *) prev=$arg ;; + esac + ;; + -g | -m | -o) + prev=$arg + ;; + -s) + stripme=" -s" + continue + ;; + -*) + ;; + *) + # If the previous option needed an argument, then skip it. + if test -n "$prev"; then + prev= + else + dest=$arg + continue + fi + ;; + esac + + # Aesthetically quote the argument. + func_quote_for_eval "$arg" + install_prog="$install_prog $func_quote_for_eval_result" + done + + test -z "$install_prog" && \ + func_fatal_help "you must specify an install program" + + test -n "$prev" && \ + func_fatal_help "the \`$prev' option requires an argument" + + if test -z "$files"; then + if test -z "$dest"; then + func_fatal_help "no file or destination specified" + else + func_fatal_help "you must specify a destination" + fi + fi + + # Strip any trailing slash from the destination. + func_stripname '' '/' "$dest" + dest=$func_stripname_result + + # Check to see that the destination is a directory. + test -d "$dest" && isdir=yes + if test "$isdir" = yes; then + destdir="$dest" + destname= + else + func_dirname_and_basename "$dest" "" "." + destdir="$func_dirname_result" + destname="$func_basename_result" + + # Not a directory, so check to see that there is only one file specified. + set dummy $files; shift + test "$#" -gt 1 && \ + func_fatal_help "\`$dest' is not a directory" + fi + case $destdir in + [\\/]* | [A-Za-z]:[\\/]*) ;; + *) + for file in $files; do + case $file in + *.lo) ;; + *) + func_fatal_help "\`$destdir' must be an absolute directory name" + ;; + esac + done + ;; + esac + + # This variable tells wrapper scripts just to set variables rather + # than running their programs. + libtool_install_magic="$magic" + + staticlibs= + future_libdirs= + current_libdirs= + for file in $files; do + + # Do each installation. + case $file in + *.$libext) + # Do the static libraries later. + staticlibs="$staticlibs $file" + ;; + + *.la) + # Check to see that this really is a libtool archive. + func_lalib_unsafe_p "$file" \ + || func_fatal_help "\`$file' is not a valid libtool archive" + + library_names= + old_library= + relink_command= + func_source "$file" + + # Add the libdir to current_libdirs if it is the destination. + if test "X$destdir" = "X$libdir"; then + case "$current_libdirs " in + *" $libdir "*) ;; + *) current_libdirs="$current_libdirs $libdir" ;; + esac + else + # Note the libdir as a future libdir. + case "$future_libdirs " in + *" $libdir "*) ;; + *) future_libdirs="$future_libdirs $libdir" ;; + esac + fi + + func_dirname "$file" "/" "" + dir="$func_dirname_result" + dir="$dir$objdir" + + if test -n "$relink_command"; then + # Determine the prefix the user has applied to our future dir. + inst_prefix_dir=`$ECHO "X$destdir" | $Xsed -e "s%$libdir\$%%"` + + # Don't allow the user to place us outside of our expected + # location b/c this prevents finding dependent libraries that + # are installed to the same prefix. + # At present, this check doesn't affect windows .dll's that + # are installed into $libdir/../bin (currently, that works fine) + # but it's something to keep an eye on. + test "$inst_prefix_dir" = "$destdir" && \ + func_fatal_error "error: cannot install \`$file' to a directory not ending in $libdir" + + if test -n "$inst_prefix_dir"; then + # Stick the inst_prefix_dir data into the link command. + relink_command=`$ECHO "X$relink_command" | $Xsed -e "s%@inst_prefix_dir@%-inst-prefix-dir $inst_prefix_dir%"` + else + relink_command=`$ECHO "X$relink_command" | $Xsed -e "s%@inst_prefix_dir@%%"` + fi + + func_warning "relinking \`$file'" + func_show_eval "$relink_command" \ + 'func_fatal_error "error: relink \`$file'\'' with the above command before installing it"' + fi + + # See the names of the shared library. + set dummy $library_names; shift + if test -n "$1"; then + realname="$1" + shift + + srcname="$realname" + test -n "$relink_command" && srcname="$realname"T + + # Install the shared library and build the symlinks. + func_show_eval "$install_prog $dir/$srcname $destdir/$realname" \ + 'exit $?' + tstripme="$stripme" + case $host_os in + cygwin* | mingw* | pw32* | cegcc*) + case $realname in + *.dll.a) + tstripme="" + ;; + esac + ;; + esac + if test -n "$tstripme" && test -n "$striplib"; then + func_show_eval "$striplib $destdir/$realname" 'exit $?' + fi + + if test "$#" -gt 0; then + # Delete the old symlinks, and create new ones. + # Try `ln -sf' first, because the `ln' binary might depend on + # the symlink we replace! Solaris /bin/ln does not understand -f, + # so we also need to try rm && ln -s. + for linkname + do + test "$linkname" != "$realname" \ + && func_show_eval "(cd $destdir && { $LN_S -f $realname $linkname || { $RM $linkname && $LN_S $realname $linkname; }; })" + done + fi + + # Do each command in the postinstall commands. + lib="$destdir/$realname" + func_execute_cmds "$postinstall_cmds" 'exit $?' + fi + + # Install the pseudo-library for information purposes. + func_basename "$file" + name="$func_basename_result" + instname="$dir/$name"i + func_show_eval "$install_prog $instname $destdir/$name" 'exit $?' + + # Maybe install the static library, too. + test -n "$old_library" && staticlibs="$staticlibs $dir/$old_library" + ;; + + *.lo) + # Install (i.e. copy) a libtool object. + + # Figure out destination file name, if it wasn't already specified. + if test -n "$destname"; then + destfile="$destdir/$destname" + else + func_basename "$file" + destfile="$func_basename_result" + destfile="$destdir/$destfile" + fi + + # Deduce the name of the destination old-style object file. + case $destfile in + *.lo) + func_lo2o "$destfile" + staticdest=$func_lo2o_result + ;; + *.$objext) + staticdest="$destfile" + destfile= + ;; + *) + func_fatal_help "cannot copy a libtool object to \`$destfile'" + ;; + esac + + # Install the libtool object if requested. + test -n "$destfile" && \ + func_show_eval "$install_prog $file $destfile" 'exit $?' + + # Install the old object if enabled. + if test "$build_old_libs" = yes; then + # Deduce the name of the old-style object file. + func_lo2o "$file" + staticobj=$func_lo2o_result + func_show_eval "$install_prog \$staticobj \$staticdest" 'exit $?' + fi + exit $EXIT_SUCCESS + ;; + + *) + # Figure out destination file name, if it wasn't already specified. + if test -n "$destname"; then + destfile="$destdir/$destname" + else + func_basename "$file" + destfile="$func_basename_result" + destfile="$destdir/$destfile" + fi + + # If the file is missing, and there is a .exe on the end, strip it + # because it is most likely a libtool script we actually want to + # install + stripped_ext="" + case $file in + *.exe) + if test ! -f "$file"; then + func_stripname '' '.exe' "$file" + file=$func_stripname_result + stripped_ext=".exe" + fi + ;; + esac + + # Do a test to see if this is really a libtool program. + case $host in + *cygwin* | *mingw*) + if func_ltwrapper_executable_p "$file"; then + func_ltwrapper_scriptname "$file" + wrapper=$func_ltwrapper_scriptname_result + else + func_stripname '' '.exe' "$file" + wrapper=$func_stripname_result + fi + ;; + *) + wrapper=$file + ;; + esac + if func_ltwrapper_script_p "$wrapper"; then + notinst_deplibs= + relink_command= + + func_source "$wrapper" + + # Check the variables that should have been set. + test -z "$generated_by_libtool_version" && \ + func_fatal_error "invalid libtool wrapper script \`$wrapper'" + + finalize=yes + for lib in $notinst_deplibs; do + # Check to see that each library is installed. + libdir= + if test -f "$lib"; then + func_source "$lib" + fi + libfile="$libdir/"`$ECHO "X$lib" | $Xsed -e 's%^.*/%%g'` ### testsuite: skip nested quoting test + if test -n "$libdir" && test ! -f "$libfile"; then + func_warning "\`$lib' has not been installed in \`$libdir'" + finalize=no + fi + done + + relink_command= + func_source "$wrapper" + + outputname= + if test "$fast_install" = no && test -n "$relink_command"; then + $opt_dry_run || { + if test "$finalize" = yes; then + tmpdir=`func_mktempdir` + func_basename "$file$stripped_ext" + file="$func_basename_result" + outputname="$tmpdir/$file" + # Replace the output file specification. + relink_command=`$ECHO "X$relink_command" | $Xsed -e 's%@OUTPUT@%'"$outputname"'%g'` + + $opt_silent || { + func_quote_for_expand "$relink_command" + eval "func_echo $func_quote_for_expand_result" + } + if eval "$relink_command"; then : + else + func_error "error: relink \`$file' with the above command before installing it" + $opt_dry_run || ${RM}r "$tmpdir" + continue + fi + file="$outputname" + else + func_warning "cannot relink \`$file'" + fi + } + else + # Install the binary that we compiled earlier. + file=`$ECHO "X$file$stripped_ext" | $Xsed -e "s%\([^/]*\)$%$objdir/\1%"` + fi + fi + + # remove .exe since cygwin /usr/bin/install will append another + # one anyway + case $install_prog,$host in + */usr/bin/install*,*cygwin*) + case $file:$destfile in + *.exe:*.exe) + # this is ok + ;; + *.exe:*) + destfile=$destfile.exe + ;; + *:*.exe) + func_stripname '' '.exe' "$destfile" + destfile=$func_stripname_result + ;; + esac + ;; + esac + func_show_eval "$install_prog\$stripme \$file \$destfile" 'exit $?' + $opt_dry_run || if test -n "$outputname"; then + ${RM}r "$tmpdir" + fi + ;; + esac + done + + for file in $staticlibs; do + func_basename "$file" + name="$func_basename_result" + + # Set up the ranlib parameters. + oldlib="$destdir/$name" + + func_show_eval "$install_prog \$file \$oldlib" 'exit $?' + + if test -n "$stripme" && test -n "$old_striplib"; then + func_show_eval "$old_striplib $oldlib" 'exit $?' + fi + + # Do each command in the postinstall commands. + func_execute_cmds "$old_postinstall_cmds" 'exit $?' + done + + test -n "$future_libdirs" && \ + func_warning "remember to run \`$progname --finish$future_libdirs'" + + if test -n "$current_libdirs"; then + # Maybe just do a dry run. + $opt_dry_run && current_libdirs=" -n$current_libdirs" + exec_cmd='$SHELL $progpath $preserve_args --finish$current_libdirs' + else + exit $EXIT_SUCCESS + fi +} + +test "$mode" = install && func_mode_install ${1+"$@"} + + +# func_generate_dlsyms outputname originator pic_p +# Extract symbols from dlprefiles and create ${outputname}S.o with +# a dlpreopen symbol table. +func_generate_dlsyms () +{ + $opt_debug + my_outputname="$1" + my_originator="$2" + my_pic_p="${3-no}" + my_prefix=`$ECHO "$my_originator" | sed 's%[^a-zA-Z0-9]%_%g'` + my_dlsyms= + + if test -n "$dlfiles$dlprefiles" || test "$dlself" != no; then + if test -n "$NM" && test -n "$global_symbol_pipe"; then + my_dlsyms="${my_outputname}S.c" + else + func_error "not configured to extract global symbols from dlpreopened files" + fi + fi + + if test -n "$my_dlsyms"; then + case $my_dlsyms in + "") ;; + *.c) + # Discover the nlist of each of the dlfiles. + nlist="$output_objdir/${my_outputname}.nm" + + func_show_eval "$RM $nlist ${nlist}S ${nlist}T" + + # Parse the name list into a source file. + func_verbose "creating $output_objdir/$my_dlsyms" + + $opt_dry_run || $ECHO > "$output_objdir/$my_dlsyms" "\ +/* $my_dlsyms - symbol resolution table for \`$my_outputname' dlsym emulation. */ +/* Generated by $PROGRAM (GNU $PACKAGE$TIMESTAMP) $VERSION */ + +#ifdef __cplusplus +extern \"C\" { +#endif + +/* External symbol declarations for the compiler. */\ +" + + if test "$dlself" = yes; then + func_verbose "generating symbol list for \`$output'" + + $opt_dry_run || echo ': @PROGRAM@ ' > "$nlist" + + # Add our own program objects to the symbol list. + progfiles=`$ECHO "X$objs$old_deplibs" | $SP2NL | $Xsed -e "$lo2o" | $NL2SP` + for progfile in $progfiles; do + func_verbose "extracting global C symbols from \`$progfile'" + $opt_dry_run || eval "$NM $progfile | $global_symbol_pipe >> '$nlist'" + done + + if test -n "$exclude_expsyms"; then + $opt_dry_run || { + eval '$EGREP -v " ($exclude_expsyms)$" "$nlist" > "$nlist"T' + eval '$MV "$nlist"T "$nlist"' + } + fi + + if test -n "$export_symbols_regex"; then + $opt_dry_run || { + eval '$EGREP -e "$export_symbols_regex" "$nlist" > "$nlist"T' + eval '$MV "$nlist"T "$nlist"' + } + fi + + # Prepare the list of exported symbols + if test -z "$export_symbols"; then + export_symbols="$output_objdir/$outputname.exp" + $opt_dry_run || { + $RM $export_symbols + eval "${SED} -n -e '/^: @PROGRAM@ $/d' -e 's/^.* \(.*\)$/\1/p' "'< "$nlist" > "$export_symbols"' + case $host in + *cygwin* | *mingw* | *cegcc* ) + eval "echo EXPORTS "'> "$output_objdir/$outputname.def"' + eval 'cat "$export_symbols" >> "$output_objdir/$outputname.def"' + ;; + esac + } + else + $opt_dry_run || { + eval "${SED} -e 's/\([].[*^$]\)/\\\\\1/g' -e 's/^/ /' -e 's/$/$/'"' < "$export_symbols" > "$output_objdir/$outputname.exp"' + eval '$GREP -f "$output_objdir/$outputname.exp" < "$nlist" > "$nlist"T' + eval '$MV "$nlist"T "$nlist"' + case $host in + *cygwin | *mingw* | *cegcc* ) + eval "echo EXPORTS "'> "$output_objdir/$outputname.def"' + eval 'cat "$nlist" >> "$output_objdir/$outputname.def"' + ;; + esac + } + fi + fi + + for dlprefile in $dlprefiles; do + func_verbose "extracting global C symbols from \`$dlprefile'" + func_basename "$dlprefile" + name="$func_basename_result" + $opt_dry_run || { + eval '$ECHO ": $name " >> "$nlist"' + eval "$NM $dlprefile 2>/dev/null | $global_symbol_pipe >> '$nlist'" + } + done + + $opt_dry_run || { + # Make sure we have at least an empty file. + test -f "$nlist" || : > "$nlist" + + if test -n "$exclude_expsyms"; then + $EGREP -v " ($exclude_expsyms)$" "$nlist" > "$nlist"T + $MV "$nlist"T "$nlist" + fi + + # Try sorting and uniquifying the output. + if $GREP -v "^: " < "$nlist" | + if sort -k 3 /dev/null 2>&1; then + sort -k 3 + else + sort +2 + fi | + uniq > "$nlist"S; then + : + else + $GREP -v "^: " < "$nlist" > "$nlist"S + fi + + if test -f "$nlist"S; then + eval "$global_symbol_to_cdecl"' < "$nlist"S >> "$output_objdir/$my_dlsyms"' + else + $ECHO '/* NONE */' >> "$output_objdir/$my_dlsyms" + fi + + $ECHO >> "$output_objdir/$my_dlsyms" "\ + +/* The mapping between symbol names and symbols. */ +typedef struct { + const char *name; + void *address; +} lt_dlsymlist; +" + case $host in + *cygwin* | *mingw* | *cegcc* ) + $ECHO >> "$output_objdir/$my_dlsyms" "\ +/* DATA imports from DLLs on WIN32 con't be const, because + runtime relocations are performed -- see ld's documentation + on pseudo-relocs. */" + lt_dlsym_const= ;; + *osf5*) + echo >> "$output_objdir/$my_dlsyms" "\ +/* This system does not cope well with relocations in const data */" + lt_dlsym_const= ;; + *) + lt_dlsym_const=const ;; + esac + + $ECHO >> "$output_objdir/$my_dlsyms" "\ +extern $lt_dlsym_const lt_dlsymlist +lt_${my_prefix}_LTX_preloaded_symbols[]; +$lt_dlsym_const lt_dlsymlist +lt_${my_prefix}_LTX_preloaded_symbols[] = +{\ + { \"$my_originator\", (void *) 0 }," + + case $need_lib_prefix in + no) + eval "$global_symbol_to_c_name_address" < "$nlist" >> "$output_objdir/$my_dlsyms" + ;; + *) + eval "$global_symbol_to_c_name_address_lib_prefix" < "$nlist" >> "$output_objdir/$my_dlsyms" + ;; + esac + $ECHO >> "$output_objdir/$my_dlsyms" "\ + {0, (void *) 0} +}; + +/* This works around a problem in FreeBSD linker */ +#ifdef FREEBSD_WORKAROUND +static const void *lt_preloaded_setup() { + return lt_${my_prefix}_LTX_preloaded_symbols; +} +#endif + +#ifdef __cplusplus +} +#endif\ +" + } # !$opt_dry_run + + pic_flag_for_symtable= + case "$compile_command " in + *" -static "*) ;; + *) + case $host in + # compiling the symbol table file with pic_flag works around + # a FreeBSD bug that causes programs to crash when -lm is + # linked before any other PIC object. But we must not use + # pic_flag when linking with -static. The problem exists in + # FreeBSD 2.2.6 and is fixed in FreeBSD 3.1. + *-*-freebsd2*|*-*-freebsd3.0*|*-*-freebsdelf3.0*) + pic_flag_for_symtable=" $pic_flag -DFREEBSD_WORKAROUND" ;; + *-*-hpux*) + pic_flag_for_symtable=" $pic_flag" ;; + *) + if test "X$my_pic_p" != Xno; then + pic_flag_for_symtable=" $pic_flag" + fi + ;; + esac + ;; + esac + symtab_cflags= + for arg in $LTCFLAGS; do + case $arg in + -pie | -fpie | -fPIE) ;; + *) symtab_cflags="$symtab_cflags $arg" ;; + esac + done + + # Now compile the dynamic symbol file. + func_show_eval '(cd $output_objdir && $LTCC$symtab_cflags -c$no_builtin_flag$pic_flag_for_symtable "$my_dlsyms")' 'exit $?' + + # Clean up the generated files. + func_show_eval '$RM "$output_objdir/$my_dlsyms" "$nlist" "${nlist}S" "${nlist}T"' + + # Transform the symbol file into the correct name. + symfileobj="$output_objdir/${my_outputname}S.$objext" + case $host in + *cygwin* | *mingw* | *cegcc* ) + if test -f "$output_objdir/$my_outputname.def"; then + compile_command=`$ECHO "X$compile_command" | $Xsed -e "s%@SYMFILE@%$output_objdir/$my_outputname.def $symfileobj%"` + finalize_command=`$ECHO "X$finalize_command" | $Xsed -e "s%@SYMFILE@%$output_objdir/$my_outputname.def $symfileobj%"` + else + compile_command=`$ECHO "X$compile_command" | $Xsed -e "s%@SYMFILE@%$symfileobj%"` + finalize_command=`$ECHO "X$finalize_command" | $Xsed -e "s%@SYMFILE@%$symfileobj%"` + fi + ;; + *) + compile_command=`$ECHO "X$compile_command" | $Xsed -e "s%@SYMFILE@%$symfileobj%"` + finalize_command=`$ECHO "X$finalize_command" | $Xsed -e "s%@SYMFILE@%$symfileobj%"` + ;; + esac + ;; + *) + func_fatal_error "unknown suffix for \`$my_dlsyms'" + ;; + esac + else + # We keep going just in case the user didn't refer to + # lt_preloaded_symbols. The linker will fail if global_symbol_pipe + # really was required. + + # Nullify the symbol file. + compile_command=`$ECHO "X$compile_command" | $Xsed -e "s% @SYMFILE@%%"` + finalize_command=`$ECHO "X$finalize_command" | $Xsed -e "s% @SYMFILE@%%"` + fi +} + +# func_win32_libid arg +# return the library type of file 'arg' +# +# Need a lot of goo to handle *both* DLLs and import libs +# Has to be a shell function in order to 'eat' the argument +# that is supplied when $file_magic_command is called. +func_win32_libid () +{ + $opt_debug + win32_libid_type="unknown" + win32_fileres=`file -L $1 2>/dev/null` + case $win32_fileres in + *ar\ archive\ import\ library*) # definitely import + win32_libid_type="x86 archive import" + ;; + *ar\ archive*) # could be an import, or static + if eval $OBJDUMP -f $1 | $SED -e '10q' 2>/dev/null | + $EGREP 'file format pe-i386(.*architecture: i386)?' >/dev/null ; then + win32_nmres=`eval $NM -f posix -A $1 | + $SED -n -e ' + 1,100{ + / I /{ + s,.*,import, + p + q + } + }'` + case $win32_nmres in + import*) win32_libid_type="x86 archive import";; + *) win32_libid_type="x86 archive static";; + esac + fi + ;; + *DLL*) + win32_libid_type="x86 DLL" + ;; + *executable*) # but shell scripts are "executable" too... + case $win32_fileres in + *MS\ Windows\ PE\ Intel*) + win32_libid_type="x86 DLL" + ;; + esac + ;; + esac + $ECHO "$win32_libid_type" +} + + + +# func_extract_an_archive dir oldlib +func_extract_an_archive () +{ + $opt_debug + f_ex_an_ar_dir="$1"; shift + f_ex_an_ar_oldlib="$1" + func_show_eval "(cd \$f_ex_an_ar_dir && $AR x \"\$f_ex_an_ar_oldlib\")" 'exit $?' + if ($AR t "$f_ex_an_ar_oldlib" | sort | sort -uc >/dev/null 2>&1); then + : + else + func_fatal_error "object name conflicts in archive: $f_ex_an_ar_dir/$f_ex_an_ar_oldlib" + fi +} + + +# func_extract_archives gentop oldlib ... +func_extract_archives () +{ + $opt_debug + my_gentop="$1"; shift + my_oldlibs=${1+"$@"} + my_oldobjs="" + my_xlib="" + my_xabs="" + my_xdir="" + + for my_xlib in $my_oldlibs; do + # Extract the objects. + case $my_xlib in + [\\/]* | [A-Za-z]:[\\/]*) my_xabs="$my_xlib" ;; + *) my_xabs=`pwd`"/$my_xlib" ;; + esac + func_basename "$my_xlib" + my_xlib="$func_basename_result" + my_xlib_u=$my_xlib + while :; do + case " $extracted_archives " in + *" $my_xlib_u "*) + func_arith $extracted_serial + 1 + extracted_serial=$func_arith_result + my_xlib_u=lt$extracted_serial-$my_xlib ;; + *) break ;; + esac + done + extracted_archives="$extracted_archives $my_xlib_u" + my_xdir="$my_gentop/$my_xlib_u" + + func_mkdir_p "$my_xdir" + + case $host in + *-darwin*) + func_verbose "Extracting $my_xabs" + # Do not bother doing anything if just a dry run + $opt_dry_run || { + darwin_orig_dir=`pwd` + cd $my_xdir || exit $? + darwin_archive=$my_xabs + darwin_curdir=`pwd` + darwin_base_archive=`basename "$darwin_archive"` + darwin_arches=`$LIPO -info "$darwin_archive" 2>/dev/null | $GREP Architectures 2>/dev/null || true` + if test -n "$darwin_arches"; then + darwin_arches=`$ECHO "$darwin_arches" | $SED -e 's/.*are://'` + darwin_arch= + func_verbose "$darwin_base_archive has multiple architectures $darwin_arches" + for darwin_arch in $darwin_arches ; do + func_mkdir_p "unfat-$$/${darwin_base_archive}-${darwin_arch}" + $LIPO -thin $darwin_arch -output "unfat-$$/${darwin_base_archive}-${darwin_arch}/${darwin_base_archive}" "${darwin_archive}" + cd "unfat-$$/${darwin_base_archive}-${darwin_arch}" + func_extract_an_archive "`pwd`" "${darwin_base_archive}" + cd "$darwin_curdir" + $RM "unfat-$$/${darwin_base_archive}-${darwin_arch}/${darwin_base_archive}" + done # $darwin_arches + ## Okay now we've a bunch of thin objects, gotta fatten them up :) + darwin_filelist=`find unfat-$$ -type f -name \*.o -print -o -name \*.lo -print | $SED -e "$basename" | sort -u` + darwin_file= + darwin_files= + for darwin_file in $darwin_filelist; do + darwin_files=`find unfat-$$ -name $darwin_file -print | $NL2SP` + $LIPO -create -output "$darwin_file" $darwin_files + done # $darwin_filelist + $RM -rf unfat-$$ + cd "$darwin_orig_dir" + else + cd $darwin_orig_dir + func_extract_an_archive "$my_xdir" "$my_xabs" + fi # $darwin_arches + } # !$opt_dry_run + ;; + *) + func_extract_an_archive "$my_xdir" "$my_xabs" + ;; + esac + my_oldobjs="$my_oldobjs "`find $my_xdir -name \*.$objext -print -o -name \*.lo -print | $NL2SP` + done + + func_extract_archives_result="$my_oldobjs" +} + + + +# func_emit_wrapper_part1 [arg=no] +# +# Emit the first part of a libtool wrapper script on stdout. +# For more information, see the description associated with +# func_emit_wrapper(), below. +func_emit_wrapper_part1 () +{ + func_emit_wrapper_part1_arg1=no + if test -n "$1" ; then + func_emit_wrapper_part1_arg1=$1 + fi + + $ECHO "\ +#! $SHELL + +# $output - temporary wrapper script for $objdir/$outputname +# Generated by $PROGRAM (GNU $PACKAGE$TIMESTAMP) $VERSION +# +# The $output program cannot be directly executed until all the libtool +# libraries that it depends on are installed. +# +# This wrapper script should never be moved out of the build directory. +# If it is, it will not operate correctly. + +# Sed substitution that helps us do robust quoting. It backslashifies +# metacharacters that are still active within double-quoted strings. +Xsed='${SED} -e 1s/^X//' +sed_quote_subst='$sed_quote_subst' + +# Be Bourne compatible +if test -n \"\${ZSH_VERSION+set}\" && (emulate sh) >/dev/null 2>&1; then + emulate sh + NULLCMD=: + # Zsh 3.x and 4.x performs word splitting on \${1+\"\$@\"}, which + # is contrary to our usage. Disable this feature. + alias -g '\${1+\"\$@\"}'='\"\$@\"' + setopt NO_GLOB_SUBST +else + case \`(set -o) 2>/dev/null\` in *posix*) set -o posix;; esac +fi +BIN_SH=xpg4; export BIN_SH # for Tru64 +DUALCASE=1; export DUALCASE # for MKS sh + +# The HP-UX ksh and POSIX shell print the target directory to stdout +# if CDPATH is set. +(unset CDPATH) >/dev/null 2>&1 && unset CDPATH + +relink_command=\"$relink_command\" + +# This environment variable determines our operation mode. +if test \"\$libtool_install_magic\" = \"$magic\"; then + # install mode needs the following variables: + generated_by_libtool_version='$macro_version' + notinst_deplibs='$notinst_deplibs' +else + # When we are sourced in execute mode, \$file and \$ECHO are already set. + if test \"\$libtool_execute_magic\" != \"$magic\"; then + ECHO=\"$qecho\" + file=\"\$0\" + # Make sure echo works. + if test \"X\$1\" = X--no-reexec; then + # Discard the --no-reexec flag, and continue. + shift + elif test \"X\`{ \$ECHO '\t'; } 2>/dev/null\`\" = 'X\t'; then + # Yippee, \$ECHO works! + : + else + # Restart under the correct shell, and then maybe \$ECHO will work. + exec $SHELL \"\$0\" --no-reexec \${1+\"\$@\"} + fi + fi\ +" + $ECHO "\ + + # Find the directory that this script lives in. + thisdir=\`\$ECHO \"X\$file\" | \$Xsed -e 's%/[^/]*$%%'\` + test \"x\$thisdir\" = \"x\$file\" && thisdir=. + + # Follow symbolic links until we get to the real thisdir. + file=\`ls -ld \"\$file\" | ${SED} -n 's/.*-> //p'\` + while test -n \"\$file\"; do + destdir=\`\$ECHO \"X\$file\" | \$Xsed -e 's%/[^/]*\$%%'\` + + # If there was a directory component, then change thisdir. + if test \"x\$destdir\" != \"x\$file\"; then + case \"\$destdir\" in + [\\\\/]* | [A-Za-z]:[\\\\/]*) thisdir=\"\$destdir\" ;; + *) thisdir=\"\$thisdir/\$destdir\" ;; + esac + fi + + file=\`\$ECHO \"X\$file\" | \$Xsed -e 's%^.*/%%'\` + file=\`ls -ld \"\$thisdir/\$file\" | ${SED} -n 's/.*-> //p'\` + done +" +} +# end: func_emit_wrapper_part1 + +# func_emit_wrapper_part2 [arg=no] +# +# Emit the second part of a libtool wrapper script on stdout. +# For more information, see the description associated with +# func_emit_wrapper(), below. +func_emit_wrapper_part2 () +{ + func_emit_wrapper_part2_arg1=no + if test -n "$1" ; then + func_emit_wrapper_part2_arg1=$1 + fi + + $ECHO "\ + + # Usually 'no', except on cygwin/mingw when embedded into + # the cwrapper. + WRAPPER_SCRIPT_BELONGS_IN_OBJDIR=$func_emit_wrapper_part2_arg1 + if test \"\$WRAPPER_SCRIPT_BELONGS_IN_OBJDIR\" = \"yes\"; then + # special case for '.' + if test \"\$thisdir\" = \".\"; then + thisdir=\`pwd\` + fi + # remove .libs from thisdir + case \"\$thisdir\" in + *[\\\\/]$objdir ) thisdir=\`\$ECHO \"X\$thisdir\" | \$Xsed -e 's%[\\\\/][^\\\\/]*$%%'\` ;; + $objdir ) thisdir=. ;; + esac + fi + + # Try to get the absolute directory name. + absdir=\`cd \"\$thisdir\" && pwd\` + test -n \"\$absdir\" && thisdir=\"\$absdir\" +" + + if test "$fast_install" = yes; then + $ECHO "\ + program=lt-'$outputname'$exeext + progdir=\"\$thisdir/$objdir\" + + if test ! -f \"\$progdir/\$program\" || + { file=\`ls -1dt \"\$progdir/\$program\" \"\$progdir/../\$program\" 2>/dev/null | ${SED} 1q\`; \\ + test \"X\$file\" != \"X\$progdir/\$program\"; }; then + + file=\"\$\$-\$program\" + + if test ! -d \"\$progdir\"; then + $MKDIR \"\$progdir\" + else + $RM \"\$progdir/\$file\" + fi" + + $ECHO "\ + + # relink executable if necessary + if test -n \"\$relink_command\"; then + if relink_command_output=\`eval \$relink_command 2>&1\`; then : + else + $ECHO \"\$relink_command_output\" >&2 + $RM \"\$progdir/\$file\" + exit 1 + fi + fi + + $MV \"\$progdir/\$file\" \"\$progdir/\$program\" 2>/dev/null || + { $RM \"\$progdir/\$program\"; + $MV \"\$progdir/\$file\" \"\$progdir/\$program\"; } + $RM \"\$progdir/\$file\" + fi" + else + $ECHO "\ + program='$outputname' + progdir=\"\$thisdir/$objdir\" +" + fi + + $ECHO "\ + + if test -f \"\$progdir/\$program\"; then" + + # Export our shlibpath_var if we have one. + if test "$shlibpath_overrides_runpath" = yes && test -n "$shlibpath_var" && test -n "$temp_rpath"; then + $ECHO "\ + # Add our own library path to $shlibpath_var + $shlibpath_var=\"$temp_rpath\$$shlibpath_var\" + + # Some systems cannot cope with colon-terminated $shlibpath_var + # The second colon is a workaround for a bug in BeOS R4 sed + $shlibpath_var=\`\$ECHO \"X\$$shlibpath_var\" | \$Xsed -e 's/::*\$//'\` + + export $shlibpath_var +" + fi + + # fixup the dll searchpath if we need to. + if test -n "$dllsearchpath"; then + $ECHO "\ + # Add the dll search path components to the executable PATH + PATH=$dllsearchpath:\$PATH +" + fi + + $ECHO "\ + if test \"\$libtool_execute_magic\" != \"$magic\"; then + # Run the actual program with our arguments. +" + case $host in + # Backslashes separate directories on plain windows + *-*-mingw | *-*-os2* | *-cegcc*) + $ECHO "\ + exec \"\$progdir\\\\\$program\" \${1+\"\$@\"} +" + ;; + + *) + $ECHO "\ + exec \"\$progdir/\$program\" \${1+\"\$@\"} +" + ;; + esac + $ECHO "\ + \$ECHO \"\$0: cannot exec \$program \$*\" 1>&2 + exit 1 + fi + else + # The program doesn't exist. + \$ECHO \"\$0: error: \\\`\$progdir/\$program' does not exist\" 1>&2 + \$ECHO \"This script is just a wrapper for \$program.\" 1>&2 + $ECHO \"See the $PACKAGE documentation for more information.\" 1>&2 + exit 1 + fi +fi\ +" +} +# end: func_emit_wrapper_part2 + + +# func_emit_wrapper [arg=no] +# +# Emit a libtool wrapper script on stdout. +# Don't directly open a file because we may want to +# incorporate the script contents within a cygwin/mingw +# wrapper executable. Must ONLY be called from within +# func_mode_link because it depends on a number of variables +# set therein. +# +# ARG is the value that the WRAPPER_SCRIPT_BELONGS_IN_OBJDIR +# variable will take. If 'yes', then the emitted script +# will assume that the directory in which it is stored is +# the $objdir directory. This is a cygwin/mingw-specific +# behavior. +func_emit_wrapper () +{ + func_emit_wrapper_arg1=no + if test -n "$1" ; then + func_emit_wrapper_arg1=$1 + fi + + # split this up so that func_emit_cwrapperexe_src + # can call each part independently. + func_emit_wrapper_part1 "${func_emit_wrapper_arg1}" + func_emit_wrapper_part2 "${func_emit_wrapper_arg1}" +} + + +# func_to_host_path arg +# +# Convert paths to host format when used with build tools. +# Intended for use with "native" mingw (where libtool itself +# is running under the msys shell), or in the following cross- +# build environments: +# $build $host +# mingw (msys) mingw [e.g. native] +# cygwin mingw +# *nix + wine mingw +# where wine is equipped with the `winepath' executable. +# In the native mingw case, the (msys) shell automatically +# converts paths for any non-msys applications it launches, +# but that facility isn't available from inside the cwrapper. +# Similar accommodations are necessary for $host mingw and +# $build cygwin. Calling this function does no harm for other +# $host/$build combinations not listed above. +# +# ARG is the path (on $build) that should be converted to +# the proper representation for $host. The result is stored +# in $func_to_host_path_result. +func_to_host_path () +{ + func_to_host_path_result="$1" + if test -n "$1" ; then + case $host in + *mingw* ) + lt_sed_naive_backslashify='s|\\\\*|\\|g;s|/|\\|g;s|\\|\\\\|g' + case $build in + *mingw* ) # actually, msys + # awkward: cmd appends spaces to result + lt_sed_strip_trailing_spaces="s/[ ]*\$//" + func_to_host_path_tmp1=`( cmd //c echo "$1" |\ + $SED -e "$lt_sed_strip_trailing_spaces" ) 2>/dev/null || echo ""` + func_to_host_path_result=`echo "$func_to_host_path_tmp1" |\ + $SED -e "$lt_sed_naive_backslashify"` + ;; + *cygwin* ) + func_to_host_path_tmp1=`cygpath -w "$1"` + func_to_host_path_result=`echo "$func_to_host_path_tmp1" |\ + $SED -e "$lt_sed_naive_backslashify"` + ;; + * ) + # Unfortunately, winepath does not exit with a non-zero + # error code, so we are forced to check the contents of + # stdout. On the other hand, if the command is not + # found, the shell will set an exit code of 127 and print + # *an error message* to stdout. So we must check for both + # error code of zero AND non-empty stdout, which explains + # the odd construction: + func_to_host_path_tmp1=`winepath -w "$1" 2>/dev/null` + if test "$?" -eq 0 && test -n "${func_to_host_path_tmp1}"; then + func_to_host_path_result=`echo "$func_to_host_path_tmp1" |\ + $SED -e "$lt_sed_naive_backslashify"` + else + # Allow warning below. + func_to_host_path_result="" + fi + ;; + esac + if test -z "$func_to_host_path_result" ; then + func_error "Could not determine host path corresponding to" + func_error " '$1'" + func_error "Continuing, but uninstalled executables may not work." + # Fallback: + func_to_host_path_result="$1" + fi + ;; + esac + fi +} +# end: func_to_host_path + +# func_to_host_pathlist arg +# +# Convert pathlists to host format when used with build tools. +# See func_to_host_path(), above. This function supports the +# following $build/$host combinations (but does no harm for +# combinations not listed here): +# $build $host +# mingw (msys) mingw [e.g. native] +# cygwin mingw +# *nix + wine mingw +# +# Path separators are also converted from $build format to +# $host format. If ARG begins or ends with a path separator +# character, it is preserved (but converted to $host format) +# on output. +# +# ARG is a pathlist (on $build) that should be converted to +# the proper representation on $host. The result is stored +# in $func_to_host_pathlist_result. +func_to_host_pathlist () +{ + func_to_host_pathlist_result="$1" + if test -n "$1" ; then + case $host in + *mingw* ) + lt_sed_naive_backslashify='s|\\\\*|\\|g;s|/|\\|g;s|\\|\\\\|g' + # Remove leading and trailing path separator characters from + # ARG. msys behavior is inconsistent here, cygpath turns them + # into '.;' and ';.', and winepath ignores them completely. + func_to_host_pathlist_tmp2="$1" + # Once set for this call, this variable should not be + # reassigned. It is used in tha fallback case. + func_to_host_pathlist_tmp1=`echo "$func_to_host_pathlist_tmp2" |\ + $SED -e 's|^:*||' -e 's|:*$||'` + case $build in + *mingw* ) # Actually, msys. + # Awkward: cmd appends spaces to result. + lt_sed_strip_trailing_spaces="s/[ ]*\$//" + func_to_host_pathlist_tmp2=`( cmd //c echo "$func_to_host_pathlist_tmp1" |\ + $SED -e "$lt_sed_strip_trailing_spaces" ) 2>/dev/null || echo ""` + func_to_host_pathlist_result=`echo "$func_to_host_pathlist_tmp2" |\ + $SED -e "$lt_sed_naive_backslashify"` + ;; + *cygwin* ) + func_to_host_pathlist_tmp2=`cygpath -w -p "$func_to_host_pathlist_tmp1"` + func_to_host_pathlist_result=`echo "$func_to_host_pathlist_tmp2" |\ + $SED -e "$lt_sed_naive_backslashify"` + ;; + * ) + # unfortunately, winepath doesn't convert pathlists + func_to_host_pathlist_result="" + func_to_host_pathlist_oldIFS=$IFS + IFS=: + for func_to_host_pathlist_f in $func_to_host_pathlist_tmp1 ; do + IFS=$func_to_host_pathlist_oldIFS + if test -n "$func_to_host_pathlist_f" ; then + func_to_host_path "$func_to_host_pathlist_f" + if test -n "$func_to_host_path_result" ; then + if test -z "$func_to_host_pathlist_result" ; then + func_to_host_pathlist_result="$func_to_host_path_result" + else + func_to_host_pathlist_result="$func_to_host_pathlist_result;$func_to_host_path_result" + fi + fi + fi + IFS=: + done + IFS=$func_to_host_pathlist_oldIFS + ;; + esac + if test -z "$func_to_host_pathlist_result" ; then + func_error "Could not determine the host path(s) corresponding to" + func_error " '$1'" + func_error "Continuing, but uninstalled executables may not work." + # Fallback. This may break if $1 contains DOS-style drive + # specifications. The fix is not to complicate the expression + # below, but for the user to provide a working wine installation + # with winepath so that path translation in the cross-to-mingw + # case works properly. + lt_replace_pathsep_nix_to_dos="s|:|;|g" + func_to_host_pathlist_result=`echo "$func_to_host_pathlist_tmp1" |\ + $SED -e "$lt_replace_pathsep_nix_to_dos"` + fi + # Now, add the leading and trailing path separators back + case "$1" in + :* ) func_to_host_pathlist_result=";$func_to_host_pathlist_result" + ;; + esac + case "$1" in + *: ) func_to_host_pathlist_result="$func_to_host_pathlist_result;" + ;; + esac + ;; + esac + fi +} +# end: func_to_host_pathlist + +# func_emit_cwrapperexe_src +# emit the source code for a wrapper executable on stdout +# Must ONLY be called from within func_mode_link because +# it depends on a number of variable set therein. +func_emit_cwrapperexe_src () +{ + cat < +#include +#ifdef _MSC_VER +# include +# include +# include +# define setmode _setmode +#else +# include +# include +# ifdef __CYGWIN__ +# include +# define HAVE_SETENV +# ifdef __STRICT_ANSI__ +char *realpath (const char *, char *); +int putenv (char *); +int setenv (const char *, const char *, int); +# endif +# endif +#endif +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined(PATH_MAX) +# define LT_PATHMAX PATH_MAX +#elif defined(MAXPATHLEN) +# define LT_PATHMAX MAXPATHLEN +#else +# define LT_PATHMAX 1024 +#endif + +#ifndef S_IXOTH +# define S_IXOTH 0 +#endif +#ifndef S_IXGRP +# define S_IXGRP 0 +#endif + +#ifdef _MSC_VER +# define S_IXUSR _S_IEXEC +# define stat _stat +# ifndef _INTPTR_T_DEFINED +# define intptr_t int +# endif +#endif + +#ifndef DIR_SEPARATOR +# define DIR_SEPARATOR '/' +# define PATH_SEPARATOR ':' +#endif + +#if defined (_WIN32) || defined (__MSDOS__) || defined (__DJGPP__) || \ + defined (__OS2__) +# define HAVE_DOS_BASED_FILE_SYSTEM +# define FOPEN_WB "wb" +# ifndef DIR_SEPARATOR_2 +# define DIR_SEPARATOR_2 '\\' +# endif +# ifndef PATH_SEPARATOR_2 +# define PATH_SEPARATOR_2 ';' +# endif +#endif + +#ifndef DIR_SEPARATOR_2 +# define IS_DIR_SEPARATOR(ch) ((ch) == DIR_SEPARATOR) +#else /* DIR_SEPARATOR_2 */ +# define IS_DIR_SEPARATOR(ch) \ + (((ch) == DIR_SEPARATOR) || ((ch) == DIR_SEPARATOR_2)) +#endif /* DIR_SEPARATOR_2 */ + +#ifndef PATH_SEPARATOR_2 +# define IS_PATH_SEPARATOR(ch) ((ch) == PATH_SEPARATOR) +#else /* PATH_SEPARATOR_2 */ +# define IS_PATH_SEPARATOR(ch) ((ch) == PATH_SEPARATOR_2) +#endif /* PATH_SEPARATOR_2 */ + +#ifdef __CYGWIN__ +# define FOPEN_WB "wb" +#endif + +#ifndef FOPEN_WB +# define FOPEN_WB "w" +#endif +#ifndef _O_BINARY +# define _O_BINARY 0 +#endif + +#define XMALLOC(type, num) ((type *) xmalloc ((num) * sizeof(type))) +#define XFREE(stale) do { \ + if (stale) { free ((void *) stale); stale = 0; } \ +} while (0) + +#undef LTWRAPPER_DEBUGPRINTF +#if defined DEBUGWRAPPER +# define LTWRAPPER_DEBUGPRINTF(args) ltwrapper_debugprintf args +static void +ltwrapper_debugprintf (const char *fmt, ...) +{ + va_list args; + va_start (args, fmt); + (void) vfprintf (stderr, fmt, args); + va_end (args); +} +#else +# define LTWRAPPER_DEBUGPRINTF(args) +#endif + +const char *program_name = NULL; + +void *xmalloc (size_t num); +char *xstrdup (const char *string); +const char *base_name (const char *name); +char *find_executable (const char *wrapper); +char *chase_symlinks (const char *pathspec); +int make_executable (const char *path); +int check_executable (const char *path); +char *strendzap (char *str, const char *pat); +void lt_fatal (const char *message, ...); +void lt_setenv (const char *name, const char *value); +char *lt_extend_str (const char *orig_value, const char *add, int to_end); +void lt_opt_process_env_set (const char *arg); +void lt_opt_process_env_prepend (const char *arg); +void lt_opt_process_env_append (const char *arg); +int lt_split_name_value (const char *arg, char** name, char** value); +void lt_update_exe_path (const char *name, const char *value); +void lt_update_lib_path (const char *name, const char *value); + +static const char *script_text_part1 = +EOF + + func_emit_wrapper_part1 yes | + $SED -e 's/\([\\"]\)/\\\1/g' \ + -e 's/^/ "/' -e 's/$/\\n"/' + echo ";" + cat <"))); + for (i = 0; i < newargc; i++) + { + LTWRAPPER_DEBUGPRINTF (("(main) newargz[%d] : %s\n", i, (newargz[i] ? newargz[i] : ""))); + } + +EOF + + case $host_os in + mingw*) + cat <<"EOF" + /* execv doesn't actually work on mingw as expected on unix */ + rval = _spawnv (_P_WAIT, lt_argv_zero, (const char * const *) newargz); + if (rval == -1) + { + /* failed to start process */ + LTWRAPPER_DEBUGPRINTF (("(main) failed to launch target \"%s\": errno = %d\n", lt_argv_zero, errno)); + return 127; + } + return rval; +EOF + ;; + *) + cat <<"EOF" + execv (lt_argv_zero, newargz); + return rval; /* =127, but avoids unused variable warning */ +EOF + ;; + esac + + cat <<"EOF" +} + +void * +xmalloc (size_t num) +{ + void *p = (void *) malloc (num); + if (!p) + lt_fatal ("Memory exhausted"); + + return p; +} + +char * +xstrdup (const char *string) +{ + return string ? strcpy ((char *) xmalloc (strlen (string) + 1), + string) : NULL; +} + +const char * +base_name (const char *name) +{ + const char *base; + +#if defined (HAVE_DOS_BASED_FILE_SYSTEM) + /* Skip over the disk name in MSDOS pathnames. */ + if (isalpha ((unsigned char) name[0]) && name[1] == ':') + name += 2; +#endif + + for (base = name; *name; name++) + if (IS_DIR_SEPARATOR (*name)) + base = name + 1; + return base; +} + +int +check_executable (const char *path) +{ + struct stat st; + + LTWRAPPER_DEBUGPRINTF (("(check_executable) : %s\n", + path ? (*path ? path : "EMPTY!") : "NULL!")); + if ((!path) || (!*path)) + return 0; + + if ((stat (path, &st) >= 0) + && (st.st_mode & (S_IXUSR | S_IXGRP | S_IXOTH))) + return 1; + else + return 0; +} + +int +make_executable (const char *path) +{ + int rval = 0; + struct stat st; + + LTWRAPPER_DEBUGPRINTF (("(make_executable) : %s\n", + path ? (*path ? path : "EMPTY!") : "NULL!")); + if ((!path) || (!*path)) + return 0; + + if (stat (path, &st) >= 0) + { + rval = chmod (path, st.st_mode | S_IXOTH | S_IXGRP | S_IXUSR); + } + return rval; +} + +/* Searches for the full path of the wrapper. Returns + newly allocated full path name if found, NULL otherwise + Does not chase symlinks, even on platforms that support them. +*/ +char * +find_executable (const char *wrapper) +{ + int has_slash = 0; + const char *p; + const char *p_next; + /* static buffer for getcwd */ + char tmp[LT_PATHMAX + 1]; + int tmp_len; + char *concat_name; + + LTWRAPPER_DEBUGPRINTF (("(find_executable) : %s\n", + wrapper ? (*wrapper ? wrapper : "EMPTY!") : "NULL!")); + + if ((wrapper == NULL) || (*wrapper == '\0')) + return NULL; + + /* Absolute path? */ +#if defined (HAVE_DOS_BASED_FILE_SYSTEM) + if (isalpha ((unsigned char) wrapper[0]) && wrapper[1] == ':') + { + concat_name = xstrdup (wrapper); + if (check_executable (concat_name)) + return concat_name; + XFREE (concat_name); + } + else + { +#endif + if (IS_DIR_SEPARATOR (wrapper[0])) + { + concat_name = xstrdup (wrapper); + if (check_executable (concat_name)) + return concat_name; + XFREE (concat_name); + } +#if defined (HAVE_DOS_BASED_FILE_SYSTEM) + } +#endif + + for (p = wrapper; *p; p++) + if (*p == '/') + { + has_slash = 1; + break; + } + if (!has_slash) + { + /* no slashes; search PATH */ + const char *path = getenv ("PATH"); + if (path != NULL) + { + for (p = path; *p; p = p_next) + { + const char *q; + size_t p_len; + for (q = p; *q; q++) + if (IS_PATH_SEPARATOR (*q)) + break; + p_len = q - p; + p_next = (*q == '\0' ? q : q + 1); + if (p_len == 0) + { + /* empty path: current directory */ + if (getcwd (tmp, LT_PATHMAX) == NULL) + lt_fatal ("getcwd failed"); + tmp_len = strlen (tmp); + concat_name = + XMALLOC (char, tmp_len + 1 + strlen (wrapper) + 1); + memcpy (concat_name, tmp, tmp_len); + concat_name[tmp_len] = '/'; + strcpy (concat_name + tmp_len + 1, wrapper); + } + else + { + concat_name = + XMALLOC (char, p_len + 1 + strlen (wrapper) + 1); + memcpy (concat_name, p, p_len); + concat_name[p_len] = '/'; + strcpy (concat_name + p_len + 1, wrapper); + } + if (check_executable (concat_name)) + return concat_name; + XFREE (concat_name); + } + } + /* not found in PATH; assume curdir */ + } + /* Relative path | not found in path: prepend cwd */ + if (getcwd (tmp, LT_PATHMAX) == NULL) + lt_fatal ("getcwd failed"); + tmp_len = strlen (tmp); + concat_name = XMALLOC (char, tmp_len + 1 + strlen (wrapper) + 1); + memcpy (concat_name, tmp, tmp_len); + concat_name[tmp_len] = '/'; + strcpy (concat_name + tmp_len + 1, wrapper); + + if (check_executable (concat_name)) + return concat_name; + XFREE (concat_name); + return NULL; +} + +char * +chase_symlinks (const char *pathspec) +{ +#ifndef S_ISLNK + return xstrdup (pathspec); +#else + char buf[LT_PATHMAX]; + struct stat s; + char *tmp_pathspec = xstrdup (pathspec); + char *p; + int has_symlinks = 0; + while (strlen (tmp_pathspec) && !has_symlinks) + { + LTWRAPPER_DEBUGPRINTF (("checking path component for symlinks: %s\n", + tmp_pathspec)); + if (lstat (tmp_pathspec, &s) == 0) + { + if (S_ISLNK (s.st_mode) != 0) + { + has_symlinks = 1; + break; + } + + /* search backwards for last DIR_SEPARATOR */ + p = tmp_pathspec + strlen (tmp_pathspec) - 1; + while ((p > tmp_pathspec) && (!IS_DIR_SEPARATOR (*p))) + p--; + if ((p == tmp_pathspec) && (!IS_DIR_SEPARATOR (*p))) + { + /* no more DIR_SEPARATORS left */ + break; + } + *p = '\0'; + } + else + { + char *errstr = strerror (errno); + lt_fatal ("Error accessing file %s (%s)", tmp_pathspec, errstr); + } + } + XFREE (tmp_pathspec); + + if (!has_symlinks) + { + return xstrdup (pathspec); + } + + tmp_pathspec = realpath (pathspec, buf); + if (tmp_pathspec == 0) + { + lt_fatal ("Could not follow symlinks for %s", pathspec); + } + return xstrdup (tmp_pathspec); +#endif +} + +char * +strendzap (char *str, const char *pat) +{ + size_t len, patlen; + + assert (str != NULL); + assert (pat != NULL); + + len = strlen (str); + patlen = strlen (pat); + + if (patlen <= len) + { + str += len - patlen; + if (strcmp (str, pat) == 0) + *str = '\0'; + } + return str; +} + +static void +lt_error_core (int exit_status, const char *mode, + const char *message, va_list ap) +{ + fprintf (stderr, "%s: %s: ", program_name, mode); + vfprintf (stderr, message, ap); + fprintf (stderr, ".\n"); + + if (exit_status >= 0) + exit (exit_status); +} + +void +lt_fatal (const char *message, ...) +{ + va_list ap; + va_start (ap, message); + lt_error_core (EXIT_FAILURE, "FATAL", message, ap); + va_end (ap); +} + +void +lt_setenv (const char *name, const char *value) +{ + LTWRAPPER_DEBUGPRINTF (("(lt_setenv) setting '%s' to '%s'\n", + (name ? name : ""), + (value ? value : ""))); + { +#ifdef HAVE_SETENV + /* always make a copy, for consistency with !HAVE_SETENV */ + char *str = xstrdup (value); + setenv (name, str, 1); +#else + int len = strlen (name) + 1 + strlen (value) + 1; + char *str = XMALLOC (char, len); + sprintf (str, "%s=%s", name, value); + if (putenv (str) != EXIT_SUCCESS) + { + XFREE (str); + } +#endif + } +} + +char * +lt_extend_str (const char *orig_value, const char *add, int to_end) +{ + char *new_value; + if (orig_value && *orig_value) + { + int orig_value_len = strlen (orig_value); + int add_len = strlen (add); + new_value = XMALLOC (char, add_len + orig_value_len + 1); + if (to_end) + { + strcpy (new_value, orig_value); + strcpy (new_value + orig_value_len, add); + } + else + { + strcpy (new_value, add); + strcpy (new_value + add_len, orig_value); + } + } + else + { + new_value = xstrdup (add); + } + return new_value; +} + +int +lt_split_name_value (const char *arg, char** name, char** value) +{ + const char *p; + int len; + if (!arg || !*arg) + return 1; + + p = strchr (arg, (int)'='); + + if (!p) + return 1; + + *value = xstrdup (++p); + + len = strlen (arg) - strlen (*value); + *name = XMALLOC (char, len); + strncpy (*name, arg, len-1); + (*name)[len - 1] = '\0'; + + return 0; +} + +void +lt_opt_process_env_set (const char *arg) +{ + char *name = NULL; + char *value = NULL; + + if (lt_split_name_value (arg, &name, &value) != 0) + { + XFREE (name); + XFREE (value); + lt_fatal ("bad argument for %s: '%s'", env_set_opt, arg); + } + + lt_setenv (name, value); + XFREE (name); + XFREE (value); +} + +void +lt_opt_process_env_prepend (const char *arg) +{ + char *name = NULL; + char *value = NULL; + char *new_value = NULL; + + if (lt_split_name_value (arg, &name, &value) != 0) + { + XFREE (name); + XFREE (value); + lt_fatal ("bad argument for %s: '%s'", env_prepend_opt, arg); + } + + new_value = lt_extend_str (getenv (name), value, 0); + lt_setenv (name, new_value); + XFREE (new_value); + XFREE (name); + XFREE (value); +} + +void +lt_opt_process_env_append (const char *arg) +{ + char *name = NULL; + char *value = NULL; + char *new_value = NULL; + + if (lt_split_name_value (arg, &name, &value) != 0) + { + XFREE (name); + XFREE (value); + lt_fatal ("bad argument for %s: '%s'", env_append_opt, arg); + } + + new_value = lt_extend_str (getenv (name), value, 1); + lt_setenv (name, new_value); + XFREE (new_value); + XFREE (name); + XFREE (value); +} + +void +lt_update_exe_path (const char *name, const char *value) +{ + LTWRAPPER_DEBUGPRINTF (("(lt_update_exe_path) modifying '%s' by prepending '%s'\n", + (name ? name : ""), + (value ? value : ""))); + + if (name && *name && value && *value) + { + char *new_value = lt_extend_str (getenv (name), value, 0); + /* some systems can't cope with a ':'-terminated path #' */ + int len = strlen (new_value); + while (((len = strlen (new_value)) > 0) && IS_PATH_SEPARATOR (new_value[len-1])) + { + new_value[len-1] = '\0'; + } + lt_setenv (name, new_value); + XFREE (new_value); + } +} + +void +lt_update_lib_path (const char *name, const char *value) +{ + LTWRAPPER_DEBUGPRINTF (("(lt_update_lib_path) modifying '%s' by prepending '%s'\n", + (name ? name : ""), + (value ? value : ""))); + + if (name && *name && value && *value) + { + char *new_value = lt_extend_str (getenv (name), value, 0); + lt_setenv (name, new_value); + XFREE (new_value); + } +} + + +EOF +} +# end: func_emit_cwrapperexe_src + +# func_mode_link arg... +func_mode_link () +{ + $opt_debug + case $host in + *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-os2* | *-cegcc*) + # It is impossible to link a dll without this setting, and + # we shouldn't force the makefile maintainer to figure out + # which system we are compiling for in order to pass an extra + # flag for every libtool invocation. + # allow_undefined=no + + # FIXME: Unfortunately, there are problems with the above when trying + # to make a dll which has undefined symbols, in which case not + # even a static library is built. For now, we need to specify + # -no-undefined on the libtool link line when we can be certain + # that all symbols are satisfied, otherwise we get a static library. + allow_undefined=yes + ;; + *) + allow_undefined=yes + ;; + esac + libtool_args=$nonopt + base_compile="$nonopt $@" + compile_command=$nonopt + finalize_command=$nonopt + + compile_rpath= + finalize_rpath= + compile_shlibpath= + finalize_shlibpath= + convenience= + old_convenience= + deplibs= + old_deplibs= + compiler_flags= + linker_flags= + dllsearchpath= + lib_search_path=`pwd` + inst_prefix_dir= + new_inherited_linker_flags= + + avoid_version=no + dlfiles= + dlprefiles= + dlself=no + export_dynamic=no + export_symbols= + export_symbols_regex= + generated= + libobjs= + ltlibs= + module=no + no_install=no + objs= + non_pic_objects= + precious_files_regex= + prefer_static_libs=no + preload=no + prev= + prevarg= + release= + rpath= + xrpath= + perm_rpath= + temp_rpath= + thread_safe=no + vinfo= + vinfo_number=no + weak_libs= + single_module="${wl}-single_module" + func_infer_tag $base_compile + + # We need to know -static, to get the right output filenames. + for arg + do + case $arg in + -shared) + test "$build_libtool_libs" != yes && \ + func_fatal_configuration "can not build a shared library" + build_old_libs=no + break + ;; + -all-static | -static | -static-libtool-libs) + case $arg in + -all-static) + if test "$build_libtool_libs" = yes && test -z "$link_static_flag"; then + func_warning "complete static linking is impossible in this configuration" + fi + if test -n "$link_static_flag"; then + dlopen_self=$dlopen_self_static + fi + prefer_static_libs=yes + ;; + -static) + if test -z "$pic_flag" && test -n "$link_static_flag"; then + dlopen_self=$dlopen_self_static + fi + prefer_static_libs=built + ;; + -static-libtool-libs) + if test -z "$pic_flag" && test -n "$link_static_flag"; then + dlopen_self=$dlopen_self_static + fi + prefer_static_libs=yes + ;; + esac + build_libtool_libs=no + build_old_libs=yes + break + ;; + esac + done + + # See if our shared archives depend on static archives. + test -n "$old_archive_from_new_cmds" && build_old_libs=yes + + # Go through the arguments, transforming them on the way. + while test "$#" -gt 0; do + arg="$1" + shift + func_quote_for_eval "$arg" + qarg=$func_quote_for_eval_unquoted_result + func_append libtool_args " $func_quote_for_eval_result" + + # If the previous option needs an argument, assign it. + if test -n "$prev"; then + case $prev in + output) + func_append compile_command " @OUTPUT@" + func_append finalize_command " @OUTPUT@" + ;; + esac + + case $prev in + dlfiles|dlprefiles) + if test "$preload" = no; then + # Add the symbol object into the linking commands. + func_append compile_command " @SYMFILE@" + func_append finalize_command " @SYMFILE@" + preload=yes + fi + case $arg in + *.la | *.lo) ;; # We handle these cases below. + force) + if test "$dlself" = no; then + dlself=needless + export_dynamic=yes + fi + prev= + continue + ;; + self) + if test "$prev" = dlprefiles; then + dlself=yes + elif test "$prev" = dlfiles && test "$dlopen_self" != yes; then + dlself=yes + else + dlself=needless + export_dynamic=yes + fi + prev= + continue + ;; + *) + if test "$prev" = dlfiles; then + dlfiles="$dlfiles $arg" + else + dlprefiles="$dlprefiles $arg" + fi + prev= + continue + ;; + esac + ;; + expsyms) + export_symbols="$arg" + test -f "$arg" \ + || func_fatal_error "symbol file \`$arg' does not exist" + prev= + continue + ;; + expsyms_regex) + export_symbols_regex="$arg" + prev= + continue + ;; + framework) + case $host in + *-*-darwin*) + case "$deplibs " in + *" $qarg.ltframework "*) ;; + *) deplibs="$deplibs $qarg.ltframework" # this is fixed later + ;; + esac + ;; + esac + prev= + continue + ;; + inst_prefix) + inst_prefix_dir="$arg" + prev= + continue + ;; + objectlist) + if test -f "$arg"; then + save_arg=$arg + moreargs= + for fil in `cat "$save_arg"` + do +# moreargs="$moreargs $fil" + arg=$fil + # A libtool-controlled object. + + # Check to see that this really is a libtool object. + if func_lalib_unsafe_p "$arg"; then + pic_object= + non_pic_object= + + # Read the .lo file + func_source "$arg" + + if test -z "$pic_object" || + test -z "$non_pic_object" || + test "$pic_object" = none && + test "$non_pic_object" = none; then + func_fatal_error "cannot find name of object for \`$arg'" + fi + + # Extract subdirectory from the argument. + func_dirname "$arg" "/" "" + xdir="$func_dirname_result" + + if test "$pic_object" != none; then + # Prepend the subdirectory the object is found in. + pic_object="$xdir$pic_object" + + if test "$prev" = dlfiles; then + if test "$build_libtool_libs" = yes && test "$dlopen_support" = yes; then + dlfiles="$dlfiles $pic_object" + prev= + continue + else + # If libtool objects are unsupported, then we need to preload. + prev=dlprefiles + fi + fi + + # CHECK ME: I think I busted this. -Ossama + if test "$prev" = dlprefiles; then + # Preload the old-style object. + dlprefiles="$dlprefiles $pic_object" + prev= + fi + + # A PIC object. + func_append libobjs " $pic_object" + arg="$pic_object" + fi + + # Non-PIC object. + if test "$non_pic_object" != none; then + # Prepend the subdirectory the object is found in. + non_pic_object="$xdir$non_pic_object" + + # A standard non-PIC object + func_append non_pic_objects " $non_pic_object" + if test -z "$pic_object" || test "$pic_object" = none ; then + arg="$non_pic_object" + fi + else + # If the PIC object exists, use it instead. + # $xdir was prepended to $pic_object above. + non_pic_object="$pic_object" + func_append non_pic_objects " $non_pic_object" + fi + else + # Only an error if not doing a dry-run. + if $opt_dry_run; then + # Extract subdirectory from the argument. + func_dirname "$arg" "/" "" + xdir="$func_dirname_result" + + func_lo2o "$arg" + pic_object=$xdir$objdir/$func_lo2o_result + non_pic_object=$xdir$func_lo2o_result + func_append libobjs " $pic_object" + func_append non_pic_objects " $non_pic_object" + else + func_fatal_error "\`$arg' is not a valid libtool object" + fi + fi + done + else + func_fatal_error "link input file \`$arg' does not exist" + fi + arg=$save_arg + prev= + continue + ;; + precious_regex) + precious_files_regex="$arg" + prev= + continue + ;; + release) + release="-$arg" + prev= + continue + ;; + rpath | xrpath) + # We need an absolute path. + case $arg in + [\\/]* | [A-Za-z]:[\\/]*) ;; + *) + func_fatal_error "only absolute run-paths are allowed" + ;; + esac + if test "$prev" = rpath; then + case "$rpath " in + *" $arg "*) ;; + *) rpath="$rpath $arg" ;; + esac + else + case "$xrpath " in + *" $arg "*) ;; + *) xrpath="$xrpath $arg" ;; + esac + fi + prev= + continue + ;; + shrext) + shrext_cmds="$arg" + prev= + continue + ;; + weak) + weak_libs="$weak_libs $arg" + prev= + continue + ;; + xcclinker) + linker_flags="$linker_flags $qarg" + compiler_flags="$compiler_flags $qarg" + prev= + func_append compile_command " $qarg" + func_append finalize_command " $qarg" + continue + ;; + xcompiler) + compiler_flags="$compiler_flags $qarg" + prev= + func_append compile_command " $qarg" + func_append finalize_command " $qarg" + continue + ;; + xlinker) + linker_flags="$linker_flags $qarg" + compiler_flags="$compiler_flags $wl$qarg" + prev= + func_append compile_command " $wl$qarg" + func_append finalize_command " $wl$qarg" + continue + ;; + *) + eval "$prev=\"\$arg\"" + prev= + continue + ;; + esac + fi # test -n "$prev" + + prevarg="$arg" + + case $arg in + -all-static) + if test -n "$link_static_flag"; then + # See comment for -static flag below, for more details. + func_append compile_command " $link_static_flag" + func_append finalize_command " $link_static_flag" + fi + continue + ;; + + -allow-undefined) + # FIXME: remove this flag sometime in the future. + func_fatal_error "\`-allow-undefined' must not be used because it is the default" + ;; + + -avoid-version) + avoid_version=yes + continue + ;; + + -dlopen) + prev=dlfiles + continue + ;; + + -dlpreopen) + prev=dlprefiles + continue + ;; + + -export-dynamic) + export_dynamic=yes + continue + ;; + + -export-symbols | -export-symbols-regex) + if test -n "$export_symbols" || test -n "$export_symbols_regex"; then + func_fatal_error "more than one -exported-symbols argument is not allowed" + fi + if test "X$arg" = "X-export-symbols"; then + prev=expsyms + else + prev=expsyms_regex + fi + continue + ;; + + -framework) + prev=framework + continue + ;; + + -inst-prefix-dir) + prev=inst_prefix + continue + ;; + + # The native IRIX linker understands -LANG:*, -LIST:* and -LNO:* + # so, if we see these flags be careful not to treat them like -L + -L[A-Z][A-Z]*:*) + case $with_gcc/$host in + no/*-*-irix* | /*-*-irix*) + func_append compile_command " $arg" + func_append finalize_command " $arg" + ;; + esac + continue + ;; + + -L*) + func_stripname '-L' '' "$arg" + dir=$func_stripname_result + if test -z "$dir"; then + if test "$#" -gt 0; then + func_fatal_error "require no space between \`-L' and \`$1'" + else + func_fatal_error "need path for \`-L' option" + fi + fi + # We need an absolute path. + case $dir in + [\\/]* | [A-Za-z]:[\\/]*) ;; + *) + absdir=`cd "$dir" && pwd` + test -z "$absdir" && \ + func_fatal_error "cannot determine absolute directory name of \`$dir'" + dir="$absdir" + ;; + esac + case "$deplibs " in + *" -L$dir "*) ;; + *) + deplibs="$deplibs -L$dir" + lib_search_path="$lib_search_path $dir" + ;; + esac + case $host in + *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-os2* | *-cegcc*) + testbindir=`$ECHO "X$dir" | $Xsed -e 's*/lib$*/bin*'` + case :$dllsearchpath: in + *":$dir:"*) ;; + ::) dllsearchpath=$dir;; + *) dllsearchpath="$dllsearchpath:$dir";; + esac + case :$dllsearchpath: in + *":$testbindir:"*) ;; + ::) dllsearchpath=$testbindir;; + *) dllsearchpath="$dllsearchpath:$testbindir";; + esac + ;; + esac + continue + ;; + + -l*) + if test "X$arg" = "X-lc" || test "X$arg" = "X-lm"; then + case $host in + *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-beos* | *-cegcc*) + # These systems don't actually have a C or math library (as such) + continue + ;; + *-*-os2*) + # These systems don't actually have a C library (as such) + test "X$arg" = "X-lc" && continue + ;; + *-*-openbsd* | *-*-freebsd* | *-*-dragonfly*) + # Do not include libc due to us having libc/libc_r. + test "X$arg" = "X-lc" && continue + ;; + *-*-rhapsody* | *-*-darwin1.[012]) + # Rhapsody C and math libraries are in the System framework + deplibs="$deplibs System.ltframework" + continue + ;; + *-*-sco3.2v5* | *-*-sco5v6*) + # Causes problems with __ctype + test "X$arg" = "X-lc" && continue + ;; + *-*-sysv4.2uw2* | *-*-sysv5* | *-*-unixware* | *-*-OpenUNIX*) + # Compiler inserts libc in the correct place for threads to work + test "X$arg" = "X-lc" && continue + ;; + esac + elif test "X$arg" = "X-lc_r"; then + case $host in + *-*-openbsd* | *-*-freebsd* | *-*-dragonfly*) + # Do not include libc_r directly, use -pthread flag. + continue + ;; + esac + fi + deplibs="$deplibs $arg" + continue + ;; + + -module) + module=yes + continue + ;; + + # Tru64 UNIX uses -model [arg] to determine the layout of C++ + # classes, name mangling, and exception handling. + # Darwin uses the -arch flag to determine output architecture. + -model|-arch|-isysroot) + compiler_flags="$compiler_flags $arg" + func_append compile_command " $arg" + func_append finalize_command " $arg" + prev=xcompiler + continue + ;; + + -mt|-mthreads|-kthread|-Kthread|-pthread|-pthreads|--thread-safe|-threads) + compiler_flags="$compiler_flags $arg" + func_append compile_command " $arg" + func_append finalize_command " $arg" + case "$new_inherited_linker_flags " in + *" $arg "*) ;; + * ) new_inherited_linker_flags="$new_inherited_linker_flags $arg" ;; + esac + continue + ;; + + -multi_module) + single_module="${wl}-multi_module" + continue + ;; + + -no-fast-install) + fast_install=no + continue + ;; + + -no-install) + case $host in + *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-os2* | *-*-darwin* | *-cegcc*) + # The PATH hackery in wrapper scripts is required on Windows + # and Darwin in order for the loader to find any dlls it needs. + func_warning "\`-no-install' is ignored for $host" + func_warning "assuming \`-no-fast-install' instead" + fast_install=no + ;; + *) no_install=yes ;; + esac + continue + ;; + + -no-undefined) + allow_undefined=no + continue + ;; + + -objectlist) + prev=objectlist + continue + ;; + + -o) prev=output ;; + + -precious-files-regex) + prev=precious_regex + continue + ;; + + -release) + prev=release + continue + ;; + + -rpath) + prev=rpath + continue + ;; + + -R) + prev=xrpath + continue + ;; + + -R*) + func_stripname '-R' '' "$arg" + dir=$func_stripname_result + # We need an absolute path. + case $dir in + [\\/]* | [A-Za-z]:[\\/]*) ;; + *) + func_fatal_error "only absolute run-paths are allowed" + ;; + esac + case "$xrpath " in + *" $dir "*) ;; + *) xrpath="$xrpath $dir" ;; + esac + continue + ;; + + -shared) + # The effects of -shared are defined in a previous loop. + continue + ;; + + -shrext) + prev=shrext + continue + ;; + + -static | -static-libtool-libs) + # The effects of -static are defined in a previous loop. + # We used to do the same as -all-static on platforms that + # didn't have a PIC flag, but the assumption that the effects + # would be equivalent was wrong. It would break on at least + # Digital Unix and AIX. + continue + ;; + + -thread-safe) + thread_safe=yes + continue + ;; + + -version-info) + prev=vinfo + continue + ;; + + -version-number) + prev=vinfo + vinfo_number=yes + continue + ;; + + -weak) + prev=weak + continue + ;; + + -Wc,*) + func_stripname '-Wc,' '' "$arg" + args=$func_stripname_result + arg= + save_ifs="$IFS"; IFS=',' + for flag in $args; do + IFS="$save_ifs" + func_quote_for_eval "$flag" + arg="$arg $wl$func_quote_for_eval_result" + compiler_flags="$compiler_flags $func_quote_for_eval_result" + done + IFS="$save_ifs" + func_stripname ' ' '' "$arg" + arg=$func_stripname_result + ;; + + -Wl,*) + func_stripname '-Wl,' '' "$arg" + args=$func_stripname_result + arg= + save_ifs="$IFS"; IFS=',' + for flag in $args; do + IFS="$save_ifs" + func_quote_for_eval "$flag" + arg="$arg $wl$func_quote_for_eval_result" + compiler_flags="$compiler_flags $wl$func_quote_for_eval_result" + linker_flags="$linker_flags $func_quote_for_eval_result" + done + IFS="$save_ifs" + func_stripname ' ' '' "$arg" + arg=$func_stripname_result + ;; + + -Xcompiler) + prev=xcompiler + continue + ;; + + -Xlinker) + prev=xlinker + continue + ;; + + -XCClinker) + prev=xcclinker + continue + ;; + + # -msg_* for osf cc + -msg_*) + func_quote_for_eval "$arg" + arg="$func_quote_for_eval_result" + ;; + + # -64, -mips[0-9] enable 64-bit mode on the SGI compiler + # -r[0-9][0-9]* specifies the processor on the SGI compiler + # -xarch=*, -xtarget=* enable 64-bit mode on the Sun compiler + # +DA*, +DD* enable 64-bit mode on the HP compiler + # -q* pass through compiler args for the IBM compiler + # -m*, -t[45]*, -txscale* pass through architecture-specific + # compiler args for GCC + # -F/path gives path to uninstalled frameworks, gcc on darwin + # -p, -pg, --coverage, -fprofile-* pass through profiling flag for GCC + # @file GCC response files + -64|-mips[0-9]|-r[0-9][0-9]*|-xarch=*|-xtarget=*|+DA*|+DD*|-q*|-m*| \ + -t[45]*|-txscale*|-p|-pg|--coverage|-fprofile-*|-F*|@*) + func_quote_for_eval "$arg" + arg="$func_quote_for_eval_result" + func_append compile_command " $arg" + func_append finalize_command " $arg" + compiler_flags="$compiler_flags $arg" + continue + ;; + + # Some other compiler flag. + -* | +*) + func_quote_for_eval "$arg" + arg="$func_quote_for_eval_result" + ;; + + *.$objext) + # A standard object. + objs="$objs $arg" + ;; + + *.lo) + # A libtool-controlled object. + + # Check to see that this really is a libtool object. + if func_lalib_unsafe_p "$arg"; then + pic_object= + non_pic_object= + + # Read the .lo file + func_source "$arg" + + if test -z "$pic_object" || + test -z "$non_pic_object" || + test "$pic_object" = none && + test "$non_pic_object" = none; then + func_fatal_error "cannot find name of object for \`$arg'" + fi + + # Extract subdirectory from the argument. + func_dirname "$arg" "/" "" + xdir="$func_dirname_result" + + if test "$pic_object" != none; then + # Prepend the subdirectory the object is found in. + pic_object="$xdir$pic_object" + + if test "$prev" = dlfiles; then + if test "$build_libtool_libs" = yes && test "$dlopen_support" = yes; then + dlfiles="$dlfiles $pic_object" + prev= + continue + else + # If libtool objects are unsupported, then we need to preload. + prev=dlprefiles + fi + fi + + # CHECK ME: I think I busted this. -Ossama + if test "$prev" = dlprefiles; then + # Preload the old-style object. + dlprefiles="$dlprefiles $pic_object" + prev= + fi + + # A PIC object. + func_append libobjs " $pic_object" + arg="$pic_object" + fi + + # Non-PIC object. + if test "$non_pic_object" != none; then + # Prepend the subdirectory the object is found in. + non_pic_object="$xdir$non_pic_object" + + # A standard non-PIC object + func_append non_pic_objects " $non_pic_object" + if test -z "$pic_object" || test "$pic_object" = none ; then + arg="$non_pic_object" + fi + else + # If the PIC object exists, use it instead. + # $xdir was prepended to $pic_object above. + non_pic_object="$pic_object" + func_append non_pic_objects " $non_pic_object" + fi + else + # Only an error if not doing a dry-run. + if $opt_dry_run; then + # Extract subdirectory from the argument. + func_dirname "$arg" "/" "" + xdir="$func_dirname_result" + + func_lo2o "$arg" + pic_object=$xdir$objdir/$func_lo2o_result + non_pic_object=$xdir$func_lo2o_result + func_append libobjs " $pic_object" + func_append non_pic_objects " $non_pic_object" + else + func_fatal_error "\`$arg' is not a valid libtool object" + fi + fi + ;; + + *.$libext) + # An archive. + deplibs="$deplibs $arg" + old_deplibs="$old_deplibs $arg" + continue + ;; + + *.la) + # A libtool-controlled library. + + if test "$prev" = dlfiles; then + # This library was specified with -dlopen. + dlfiles="$dlfiles $arg" + prev= + elif test "$prev" = dlprefiles; then + # The library was specified with -dlpreopen. + dlprefiles="$dlprefiles $arg" + prev= + else + deplibs="$deplibs $arg" + fi + continue + ;; + + # Some other compiler argument. + *) + # Unknown arguments in both finalize_command and compile_command need + # to be aesthetically quoted because they are evaled later. + func_quote_for_eval "$arg" + arg="$func_quote_for_eval_result" + ;; + esac # arg + + # Now actually substitute the argument into the commands. + if test -n "$arg"; then + func_append compile_command " $arg" + func_append finalize_command " $arg" + fi + done # argument parsing loop + + test -n "$prev" && \ + func_fatal_help "the \`$prevarg' option requires an argument" + + if test "$export_dynamic" = yes && test -n "$export_dynamic_flag_spec"; then + eval arg=\"$export_dynamic_flag_spec\" + func_append compile_command " $arg" + func_append finalize_command " $arg" + fi + + oldlibs= + # calculate the name of the file, without its directory + func_basename "$output" + outputname="$func_basename_result" + libobjs_save="$libobjs" + + if test -n "$shlibpath_var"; then + # get the directories listed in $shlibpath_var + eval shlib_search_path=\`\$ECHO \"X\${$shlibpath_var}\" \| \$Xsed -e \'s/:/ /g\'\` + else + shlib_search_path= + fi + eval sys_lib_search_path=\"$sys_lib_search_path_spec\" + eval sys_lib_dlsearch_path=\"$sys_lib_dlsearch_path_spec\" + + func_dirname "$output" "/" "" + output_objdir="$func_dirname_result$objdir" + # Create the object directory. + func_mkdir_p "$output_objdir" + + # Determine the type of output + case $output in + "") + func_fatal_help "you must specify an output file" + ;; + *.$libext) linkmode=oldlib ;; + *.lo | *.$objext) linkmode=obj ;; + *.la) linkmode=lib ;; + *) linkmode=prog ;; # Anything else should be a program. + esac + + specialdeplibs= + + libs= + # Find all interdependent deplibs by searching for libraries + # that are linked more than once (e.g. -la -lb -la) + for deplib in $deplibs; do + if $opt_duplicate_deps ; then + case "$libs " in + *" $deplib "*) specialdeplibs="$specialdeplibs $deplib" ;; + esac + fi + libs="$libs $deplib" + done + + if test "$linkmode" = lib; then + libs="$predeps $libs $compiler_lib_search_path $postdeps" + + # Compute libraries that are listed more than once in $predeps + # $postdeps and mark them as special (i.e., whose duplicates are + # not to be eliminated). + pre_post_deps= + if $opt_duplicate_compiler_generated_deps; then + for pre_post_dep in $predeps $postdeps; do + case "$pre_post_deps " in + *" $pre_post_dep "*) specialdeplibs="$specialdeplibs $pre_post_deps" ;; + esac + pre_post_deps="$pre_post_deps $pre_post_dep" + done + fi + pre_post_deps= + fi + + deplibs= + newdependency_libs= + newlib_search_path= + need_relink=no # whether we're linking any uninstalled libtool libraries + notinst_deplibs= # not-installed libtool libraries + notinst_path= # paths that contain not-installed libtool libraries + + case $linkmode in + lib) + passes="conv dlpreopen link" + for file in $dlfiles $dlprefiles; do + case $file in + *.la) ;; + *) + func_fatal_help "libraries can \`-dlopen' only libtool libraries: $file" + ;; + esac + done + ;; + prog) + compile_deplibs= + finalize_deplibs= + alldeplibs=no + newdlfiles= + newdlprefiles= + passes="conv scan dlopen dlpreopen link" + ;; + *) passes="conv" + ;; + esac + + for pass in $passes; do + # The preopen pass in lib mode reverses $deplibs; put it back here + # so that -L comes before libs that need it for instance... + if test "$linkmode,$pass" = "lib,link"; then + ## FIXME: Find the place where the list is rebuilt in the wrong + ## order, and fix it there properly + tmp_deplibs= + for deplib in $deplibs; do + tmp_deplibs="$deplib $tmp_deplibs" + done + deplibs="$tmp_deplibs" + fi + + if test "$linkmode,$pass" = "lib,link" || + test "$linkmode,$pass" = "prog,scan"; then + libs="$deplibs" + deplibs= + fi + if test "$linkmode" = prog; then + case $pass in + dlopen) libs="$dlfiles" ;; + dlpreopen) libs="$dlprefiles" ;; + link) + libs="$deplibs %DEPLIBS%" + test "X$link_all_deplibs" != Xno && libs="$libs $dependency_libs" + ;; + esac + fi + if test "$linkmode,$pass" = "lib,dlpreopen"; then + # Collect and forward deplibs of preopened libtool libs + for lib in $dlprefiles; do + # Ignore non-libtool-libs + dependency_libs= + case $lib in + *.la) func_source "$lib" ;; + esac + + # Collect preopened libtool deplibs, except any this library + # has declared as weak libs + for deplib in $dependency_libs; do + deplib_base=`$ECHO "X$deplib" | $Xsed -e "$basename"` + case " $weak_libs " in + *" $deplib_base "*) ;; + *) deplibs="$deplibs $deplib" ;; + esac + done + done + libs="$dlprefiles" + fi + if test "$pass" = dlopen; then + # Collect dlpreopened libraries + save_deplibs="$deplibs" + deplibs= + fi + + for deplib in $libs; do + lib= + found=no + case $deplib in + -mt|-mthreads|-kthread|-Kthread|-pthread|-pthreads|--thread-safe|-threads) + if test "$linkmode,$pass" = "prog,link"; then + compile_deplibs="$deplib $compile_deplibs" + finalize_deplibs="$deplib $finalize_deplibs" + else + compiler_flags="$compiler_flags $deplib" + if test "$linkmode" = lib ; then + case "$new_inherited_linker_flags " in + *" $deplib "*) ;; + * ) new_inherited_linker_flags="$new_inherited_linker_flags $deplib" ;; + esac + fi + fi + continue + ;; + -l*) + if test "$linkmode" != lib && test "$linkmode" != prog; then + func_warning "\`-l' is ignored for archives/objects" + continue + fi + func_stripname '-l' '' "$deplib" + name=$func_stripname_result + if test "$linkmode" = lib; then + searchdirs="$newlib_search_path $lib_search_path $compiler_lib_search_dirs $sys_lib_search_path $shlib_search_path" + else + searchdirs="$newlib_search_path $lib_search_path $sys_lib_search_path $shlib_search_path" + fi + for searchdir in $searchdirs; do + for search_ext in .la $std_shrext .so .a; do + # Search the libtool library + lib="$searchdir/lib${name}${search_ext}" + if test -f "$lib"; then + if test "$search_ext" = ".la"; then + found=yes + else + found=no + fi + break 2 + fi + done + done + if test "$found" != yes; then + # deplib doesn't seem to be a libtool library + if test "$linkmode,$pass" = "prog,link"; then + compile_deplibs="$deplib $compile_deplibs" + finalize_deplibs="$deplib $finalize_deplibs" + else + deplibs="$deplib $deplibs" + test "$linkmode" = lib && newdependency_libs="$deplib $newdependency_libs" + fi + continue + else # deplib is a libtool library + # If $allow_libtool_libs_with_static_runtimes && $deplib is a stdlib, + # We need to do some special things here, and not later. + if test "X$allow_libtool_libs_with_static_runtimes" = "Xyes" ; then + case " $predeps $postdeps " in + *" $deplib "*) + if func_lalib_p "$lib"; then + library_names= + old_library= + func_source "$lib" + for l in $old_library $library_names; do + ll="$l" + done + if test "X$ll" = "X$old_library" ; then # only static version available + found=no + func_dirname "$lib" "" "." + ladir="$func_dirname_result" + lib=$ladir/$old_library + if test "$linkmode,$pass" = "prog,link"; then + compile_deplibs="$deplib $compile_deplibs" + finalize_deplibs="$deplib $finalize_deplibs" + else + deplibs="$deplib $deplibs" + test "$linkmode" = lib && newdependency_libs="$deplib $newdependency_libs" + fi + continue + fi + fi + ;; + *) ;; + esac + fi + fi + ;; # -l + *.ltframework) + if test "$linkmode,$pass" = "prog,link"; then + compile_deplibs="$deplib $compile_deplibs" + finalize_deplibs="$deplib $finalize_deplibs" + else + deplibs="$deplib $deplibs" + if test "$linkmode" = lib ; then + case "$new_inherited_linker_flags " in + *" $deplib "*) ;; + * ) new_inherited_linker_flags="$new_inherited_linker_flags $deplib" ;; + esac + fi + fi + continue + ;; + -L*) + case $linkmode in + lib) + deplibs="$deplib $deplibs" + test "$pass" = conv && continue + newdependency_libs="$deplib $newdependency_libs" + func_stripname '-L' '' "$deplib" + newlib_search_path="$newlib_search_path $func_stripname_result" + ;; + prog) + if test "$pass" = conv; then + deplibs="$deplib $deplibs" + continue + fi + if test "$pass" = scan; then + deplibs="$deplib $deplibs" + else + compile_deplibs="$deplib $compile_deplibs" + finalize_deplibs="$deplib $finalize_deplibs" + fi + func_stripname '-L' '' "$deplib" + newlib_search_path="$newlib_search_path $func_stripname_result" + ;; + *) + func_warning "\`-L' is ignored for archives/objects" + ;; + esac # linkmode + continue + ;; # -L + -R*) + if test "$pass" = link; then + func_stripname '-R' '' "$deplib" + dir=$func_stripname_result + # Make sure the xrpath contains only unique directories. + case "$xrpath " in + *" $dir "*) ;; + *) xrpath="$xrpath $dir" ;; + esac + fi + deplibs="$deplib $deplibs" + continue + ;; + *.la) lib="$deplib" ;; + *.$libext) + if test "$pass" = conv; then + deplibs="$deplib $deplibs" + continue + fi + case $linkmode in + lib) + # Linking convenience modules into shared libraries is allowed, + # but linking other static libraries is non-portable. + case " $dlpreconveniencelibs " in + *" $deplib "*) ;; + *) + valid_a_lib=no + case $deplibs_check_method in + match_pattern*) + set dummy $deplibs_check_method; shift + match_pattern_regex=`expr "$deplibs_check_method" : "$1 \(.*\)"` + if eval "\$ECHO \"X$deplib\"" 2>/dev/null | $Xsed -e 10q \ + | $EGREP "$match_pattern_regex" > /dev/null; then + valid_a_lib=yes + fi + ;; + pass_all) + valid_a_lib=yes + ;; + esac + if test "$valid_a_lib" != yes; then + $ECHO + $ECHO "*** Warning: Trying to link with static lib archive $deplib." + $ECHO "*** I have the capability to make that library automatically link in when" + $ECHO "*** you link to this library. But I can only do this if you have a" + $ECHO "*** shared version of the library, which you do not appear to have" + $ECHO "*** because the file extensions .$libext of this argument makes me believe" + $ECHO "*** that it is just a static archive that I should not use here." + else + $ECHO + $ECHO "*** Warning: Linking the shared library $output against the" + $ECHO "*** static library $deplib is not portable!" + deplibs="$deplib $deplibs" + fi + ;; + esac + continue + ;; + prog) + if test "$pass" != link; then + deplibs="$deplib $deplibs" + else + compile_deplibs="$deplib $compile_deplibs" + finalize_deplibs="$deplib $finalize_deplibs" + fi + continue + ;; + esac # linkmode + ;; # *.$libext + *.lo | *.$objext) + if test "$pass" = conv; then + deplibs="$deplib $deplibs" + elif test "$linkmode" = prog; then + if test "$pass" = dlpreopen || test "$dlopen_support" != yes || test "$build_libtool_libs" = no; then + # If there is no dlopen support or we're linking statically, + # we need to preload. + newdlprefiles="$newdlprefiles $deplib" + compile_deplibs="$deplib $compile_deplibs" + finalize_deplibs="$deplib $finalize_deplibs" + else + newdlfiles="$newdlfiles $deplib" + fi + fi + continue + ;; + %DEPLIBS%) + alldeplibs=yes + continue + ;; + esac # case $deplib + + if test "$found" = yes || test -f "$lib"; then : + else + func_fatal_error "cannot find the library \`$lib' or unhandled argument \`$deplib'" + fi + + # Check to see that this really is a libtool archive. + func_lalib_unsafe_p "$lib" \ + || func_fatal_error "\`$lib' is not a valid libtool archive" + + func_dirname "$lib" "" "." + ladir="$func_dirname_result" + + dlname= + dlopen= + dlpreopen= + libdir= + library_names= + old_library= + inherited_linker_flags= + # If the library was installed with an old release of libtool, + # it will not redefine variables installed, or shouldnotlink + installed=yes + shouldnotlink=no + avoidtemprpath= + + + # Read the .la file + func_source "$lib" + + # Convert "-framework foo" to "foo.ltframework" + if test -n "$inherited_linker_flags"; then + tmp_inherited_linker_flags=`$ECHO "X$inherited_linker_flags" | $Xsed -e 's/-framework \([^ $]*\)/\1.ltframework/g'` + for tmp_inherited_linker_flag in $tmp_inherited_linker_flags; do + case " $new_inherited_linker_flags " in + *" $tmp_inherited_linker_flag "*) ;; + *) new_inherited_linker_flags="$new_inherited_linker_flags $tmp_inherited_linker_flag";; + esac + done + fi + dependency_libs=`$ECHO "X $dependency_libs" | $Xsed -e 's% \([^ $]*\).ltframework% -framework \1%g'` + if test "$linkmode,$pass" = "lib,link" || + test "$linkmode,$pass" = "prog,scan" || + { test "$linkmode" != prog && test "$linkmode" != lib; }; then + test -n "$dlopen" && dlfiles="$dlfiles $dlopen" + test -n "$dlpreopen" && dlprefiles="$dlprefiles $dlpreopen" + fi + + if test "$pass" = conv; then + # Only check for convenience libraries + deplibs="$lib $deplibs" + if test -z "$libdir"; then + if test -z "$old_library"; then + func_fatal_error "cannot find name of link library for \`$lib'" + fi + # It is a libtool convenience library, so add in its objects. + convenience="$convenience $ladir/$objdir/$old_library" + old_convenience="$old_convenience $ladir/$objdir/$old_library" + tmp_libs= + for deplib in $dependency_libs; do + deplibs="$deplib $deplibs" + if $opt_duplicate_deps ; then + case "$tmp_libs " in + *" $deplib "*) specialdeplibs="$specialdeplibs $deplib" ;; + esac + fi + tmp_libs="$tmp_libs $deplib" + done + elif test "$linkmode" != prog && test "$linkmode" != lib; then + func_fatal_error "\`$lib' is not a convenience library" + fi + continue + fi # $pass = conv + + + # Get the name of the library we link against. + linklib= + for l in $old_library $library_names; do + linklib="$l" + done + if test -z "$linklib"; then + func_fatal_error "cannot find name of link library for \`$lib'" + fi + + # This library was specified with -dlopen. + if test "$pass" = dlopen; then + if test -z "$libdir"; then + func_fatal_error "cannot -dlopen a convenience library: \`$lib'" + fi + if test -z "$dlname" || + test "$dlopen_support" != yes || + test "$build_libtool_libs" = no; then + # If there is no dlname, no dlopen support or we're linking + # statically, we need to preload. We also need to preload any + # dependent libraries so libltdl's deplib preloader doesn't + # bomb out in the load deplibs phase. + dlprefiles="$dlprefiles $lib $dependency_libs" + else + newdlfiles="$newdlfiles $lib" + fi + continue + fi # $pass = dlopen + + # We need an absolute path. + case $ladir in + [\\/]* | [A-Za-z]:[\\/]*) abs_ladir="$ladir" ;; + *) + abs_ladir=`cd "$ladir" && pwd` + if test -z "$abs_ladir"; then + func_warning "cannot determine absolute directory name of \`$ladir'" + func_warning "passing it literally to the linker, although it might fail" + abs_ladir="$ladir" + fi + ;; + esac + func_basename "$lib" + laname="$func_basename_result" + + # Find the relevant object directory and library name. + if test "X$installed" = Xyes; then + if test ! -f "$libdir/$linklib" && test -f "$abs_ladir/$linklib"; then + func_warning "library \`$lib' was moved." + dir="$ladir" + absdir="$abs_ladir" + libdir="$abs_ladir" + else + dir="$libdir" + absdir="$libdir" + fi + test "X$hardcode_automatic" = Xyes && avoidtemprpath=yes + else + if test ! -f "$ladir/$objdir/$linklib" && test -f "$abs_ladir/$linklib"; then + dir="$ladir" + absdir="$abs_ladir" + # Remove this search path later + notinst_path="$notinst_path $abs_ladir" + else + dir="$ladir/$objdir" + absdir="$abs_ladir/$objdir" + # Remove this search path later + notinst_path="$notinst_path $abs_ladir" + fi + fi # $installed = yes + func_stripname 'lib' '.la' "$laname" + name=$func_stripname_result + + # This library was specified with -dlpreopen. + if test "$pass" = dlpreopen; then + if test -z "$libdir" && test "$linkmode" = prog; then + func_fatal_error "only libraries may -dlpreopen a convenience library: \`$lib'" + fi + # Prefer using a static library (so that no silly _DYNAMIC symbols + # are required to link). + if test -n "$old_library"; then + newdlprefiles="$newdlprefiles $dir/$old_library" + # Keep a list of preopened convenience libraries to check + # that they are being used correctly in the link pass. + test -z "$libdir" && \ + dlpreconveniencelibs="$dlpreconveniencelibs $dir/$old_library" + # Otherwise, use the dlname, so that lt_dlopen finds it. + elif test -n "$dlname"; then + newdlprefiles="$newdlprefiles $dir/$dlname" + else + newdlprefiles="$newdlprefiles $dir/$linklib" + fi + fi # $pass = dlpreopen + + if test -z "$libdir"; then + # Link the convenience library + if test "$linkmode" = lib; then + deplibs="$dir/$old_library $deplibs" + elif test "$linkmode,$pass" = "prog,link"; then + compile_deplibs="$dir/$old_library $compile_deplibs" + finalize_deplibs="$dir/$old_library $finalize_deplibs" + else + deplibs="$lib $deplibs" # used for prog,scan pass + fi + continue + fi + + + if test "$linkmode" = prog && test "$pass" != link; then + newlib_search_path="$newlib_search_path $ladir" + deplibs="$lib $deplibs" + + linkalldeplibs=no + if test "$link_all_deplibs" != no || test -z "$library_names" || + test "$build_libtool_libs" = no; then + linkalldeplibs=yes + fi + + tmp_libs= + for deplib in $dependency_libs; do + case $deplib in + -L*) func_stripname '-L' '' "$deplib" + newlib_search_path="$newlib_search_path $func_stripname_result" + ;; + esac + # Need to link against all dependency_libs? + if test "$linkalldeplibs" = yes; then + deplibs="$deplib $deplibs" + else + # Need to hardcode shared library paths + # or/and link against static libraries + newdependency_libs="$deplib $newdependency_libs" + fi + if $opt_duplicate_deps ; then + case "$tmp_libs " in + *" $deplib "*) specialdeplibs="$specialdeplibs $deplib" ;; + esac + fi + tmp_libs="$tmp_libs $deplib" + done # for deplib + continue + fi # $linkmode = prog... + + if test "$linkmode,$pass" = "prog,link"; then + if test -n "$library_names" && + { { test "$prefer_static_libs" = no || + test "$prefer_static_libs,$installed" = "built,yes"; } || + test -z "$old_library"; }; then + # We need to hardcode the library path + if test -n "$shlibpath_var" && test -z "$avoidtemprpath" ; then + # Make sure the rpath contains only unique directories. + case "$temp_rpath:" in + *"$absdir:"*) ;; + *) temp_rpath="$temp_rpath$absdir:" ;; + esac + fi + + # Hardcode the library path. + # Skip directories that are in the system default run-time + # search path. + case " $sys_lib_dlsearch_path " in + *" $absdir "*) ;; + *) + case "$compile_rpath " in + *" $absdir "*) ;; + *) compile_rpath="$compile_rpath $absdir" + esac + ;; + esac + case " $sys_lib_dlsearch_path " in + *" $libdir "*) ;; + *) + case "$finalize_rpath " in + *" $libdir "*) ;; + *) finalize_rpath="$finalize_rpath $libdir" + esac + ;; + esac + fi # $linkmode,$pass = prog,link... + + if test "$alldeplibs" = yes && + { test "$deplibs_check_method" = pass_all || + { test "$build_libtool_libs" = yes && + test -n "$library_names"; }; }; then + # We only need to search for static libraries + continue + fi + fi + + link_static=no # Whether the deplib will be linked statically + use_static_libs=$prefer_static_libs + if test "$use_static_libs" = built && test "$installed" = yes; then + use_static_libs=no + fi + if test -n "$library_names" && + { test "$use_static_libs" = no || test -z "$old_library"; }; then + case $host in + *cygwin* | *mingw* | *cegcc*) + # No point in relinking DLLs because paths are not encoded + notinst_deplibs="$notinst_deplibs $lib" + need_relink=no + ;; + *) + if test "$installed" = no; then + notinst_deplibs="$notinst_deplibs $lib" + need_relink=yes + fi + ;; + esac + # This is a shared library + + # Warn about portability, can't link against -module's on some + # systems (darwin). Don't bleat about dlopened modules though! + dlopenmodule="" + for dlpremoduletest in $dlprefiles; do + if test "X$dlpremoduletest" = "X$lib"; then + dlopenmodule="$dlpremoduletest" + break + fi + done + if test -z "$dlopenmodule" && test "$shouldnotlink" = yes && test "$pass" = link; then + $ECHO + if test "$linkmode" = prog; then + $ECHO "*** Warning: Linking the executable $output against the loadable module" + else + $ECHO "*** Warning: Linking the shared library $output against the loadable module" + fi + $ECHO "*** $linklib is not portable!" + fi + if test "$linkmode" = lib && + test "$hardcode_into_libs" = yes; then + # Hardcode the library path. + # Skip directories that are in the system default run-time + # search path. + case " $sys_lib_dlsearch_path " in + *" $absdir "*) ;; + *) + case "$compile_rpath " in + *" $absdir "*) ;; + *) compile_rpath="$compile_rpath $absdir" + esac + ;; + esac + case " $sys_lib_dlsearch_path " in + *" $libdir "*) ;; + *) + case "$finalize_rpath " in + *" $libdir "*) ;; + *) finalize_rpath="$finalize_rpath $libdir" + esac + ;; + esac + fi + + if test -n "$old_archive_from_expsyms_cmds"; then + # figure out the soname + set dummy $library_names + shift + realname="$1" + shift + libname=`eval "\\$ECHO \"$libname_spec\""` + # use dlname if we got it. it's perfectly good, no? + if test -n "$dlname"; then + soname="$dlname" + elif test -n "$soname_spec"; then + # bleh windows + case $host in + *cygwin* | mingw* | *cegcc*) + func_arith $current - $age + major=$func_arith_result + versuffix="-$major" + ;; + esac + eval soname=\"$soname_spec\" + else + soname="$realname" + fi + + # Make a new name for the extract_expsyms_cmds to use + soroot="$soname" + func_basename "$soroot" + soname="$func_basename_result" + func_stripname 'lib' '.dll' "$soname" + newlib=libimp-$func_stripname_result.a + + # If the library has no export list, then create one now + if test -f "$output_objdir/$soname-def"; then : + else + func_verbose "extracting exported symbol list from \`$soname'" + func_execute_cmds "$extract_expsyms_cmds" 'exit $?' + fi + + # Create $newlib + if test -f "$output_objdir/$newlib"; then :; else + func_verbose "generating import library for \`$soname'" + func_execute_cmds "$old_archive_from_expsyms_cmds" 'exit $?' + fi + # make sure the library variables are pointing to the new library + dir=$output_objdir + linklib=$newlib + fi # test -n "$old_archive_from_expsyms_cmds" + + if test "$linkmode" = prog || test "$mode" != relink; then + add_shlibpath= + add_dir= + add= + lib_linked=yes + case $hardcode_action in + immediate | unsupported) + if test "$hardcode_direct" = no; then + add="$dir/$linklib" + case $host in + *-*-sco3.2v5.0.[024]*) add_dir="-L$dir" ;; + *-*-sysv4*uw2*) add_dir="-L$dir" ;; + *-*-sysv5OpenUNIX* | *-*-sysv5UnixWare7.[01].[10]* | \ + *-*-unixware7*) add_dir="-L$dir" ;; + *-*-darwin* ) + # if the lib is a (non-dlopened) module then we can not + # link against it, someone is ignoring the earlier warnings + if /usr/bin/file -L $add 2> /dev/null | + $GREP ": [^:]* bundle" >/dev/null ; then + if test "X$dlopenmodule" != "X$lib"; then + $ECHO "*** Warning: lib $linklib is a module, not a shared library" + if test -z "$old_library" ; then + $ECHO + $ECHO "*** And there doesn't seem to be a static archive available" + $ECHO "*** The link will probably fail, sorry" + else + add="$dir/$old_library" + fi + elif test -n "$old_library"; then + add="$dir/$old_library" + fi + fi + esac + elif test "$hardcode_minus_L" = no; then + case $host in + *-*-sunos*) add_shlibpath="$dir" ;; + esac + add_dir="-L$dir" + add="-l$name" + elif test "$hardcode_shlibpath_var" = no; then + add_shlibpath="$dir" + add="-l$name" + else + lib_linked=no + fi + ;; + relink) + if test "$hardcode_direct" = yes && + test "$hardcode_direct_absolute" = no; then + add="$dir/$linklib" + elif test "$hardcode_minus_L" = yes; then + add_dir="-L$dir" + # Try looking first in the location we're being installed to. + if test -n "$inst_prefix_dir"; then + case $libdir in + [\\/]*) + add_dir="$add_dir -L$inst_prefix_dir$libdir" + ;; + esac + fi + add="-l$name" + elif test "$hardcode_shlibpath_var" = yes; then + add_shlibpath="$dir" + add="-l$name" + else + lib_linked=no + fi + ;; + *) lib_linked=no ;; + esac + + if test "$lib_linked" != yes; then + func_fatal_configuration "unsupported hardcode properties" + fi + + if test -n "$add_shlibpath"; then + case :$compile_shlibpath: in + *":$add_shlibpath:"*) ;; + *) compile_shlibpath="$compile_shlibpath$add_shlibpath:" ;; + esac + fi + if test "$linkmode" = prog; then + test -n "$add_dir" && compile_deplibs="$add_dir $compile_deplibs" + test -n "$add" && compile_deplibs="$add $compile_deplibs" + else + test -n "$add_dir" && deplibs="$add_dir $deplibs" + test -n "$add" && deplibs="$add $deplibs" + if test "$hardcode_direct" != yes && + test "$hardcode_minus_L" != yes && + test "$hardcode_shlibpath_var" = yes; then + case :$finalize_shlibpath: in + *":$libdir:"*) ;; + *) finalize_shlibpath="$finalize_shlibpath$libdir:" ;; + esac + fi + fi + fi + + if test "$linkmode" = prog || test "$mode" = relink; then + add_shlibpath= + add_dir= + add= + # Finalize command for both is simple: just hardcode it. + if test "$hardcode_direct" = yes && + test "$hardcode_direct_absolute" = no; then + add="$libdir/$linklib" + elif test "$hardcode_minus_L" = yes; then + add_dir="-L$libdir" + add="-l$name" + elif test "$hardcode_shlibpath_var" = yes; then + case :$finalize_shlibpath: in + *":$libdir:"*) ;; + *) finalize_shlibpath="$finalize_shlibpath$libdir:" ;; + esac + add="-l$name" + elif test "$hardcode_automatic" = yes; then + if test -n "$inst_prefix_dir" && + test -f "$inst_prefix_dir$libdir/$linklib" ; then + add="$inst_prefix_dir$libdir/$linklib" + else + add="$libdir/$linklib" + fi + else + # We cannot seem to hardcode it, guess we'll fake it. + add_dir="-L$libdir" + # Try looking first in the location we're being installed to. + if test -n "$inst_prefix_dir"; then + case $libdir in + [\\/]*) + add_dir="$add_dir -L$inst_prefix_dir$libdir" + ;; + esac + fi + add="-l$name" + fi + + if test "$linkmode" = prog; then + test -n "$add_dir" && finalize_deplibs="$add_dir $finalize_deplibs" + test -n "$add" && finalize_deplibs="$add $finalize_deplibs" + else + test -n "$add_dir" && deplibs="$add_dir $deplibs" + test -n "$add" && deplibs="$add $deplibs" + fi + fi + elif test "$linkmode" = prog; then + # Here we assume that one of hardcode_direct or hardcode_minus_L + # is not unsupported. This is valid on all known static and + # shared platforms. + if test "$hardcode_direct" != unsupported; then + test -n "$old_library" && linklib="$old_library" + compile_deplibs="$dir/$linklib $compile_deplibs" + finalize_deplibs="$dir/$linklib $finalize_deplibs" + else + compile_deplibs="-l$name -L$dir $compile_deplibs" + finalize_deplibs="-l$name -L$dir $finalize_deplibs" + fi + elif test "$build_libtool_libs" = yes; then + # Not a shared library + if test "$deplibs_check_method" != pass_all; then + # We're trying link a shared library against a static one + # but the system doesn't support it. + + # Just print a warning and add the library to dependency_libs so + # that the program can be linked against the static library. + $ECHO + $ECHO "*** Warning: This system can not link to static lib archive $lib." + $ECHO "*** I have the capability to make that library automatically link in when" + $ECHO "*** you link to this library. But I can only do this if you have a" + $ECHO "*** shared version of the library, which you do not appear to have." + if test "$module" = yes; then + $ECHO "*** But as you try to build a module library, libtool will still create " + $ECHO "*** a static module, that should work as long as the dlopening application" + $ECHO "*** is linked with the -dlopen flag to resolve symbols at runtime." + if test -z "$global_symbol_pipe"; then + $ECHO + $ECHO "*** However, this would only work if libtool was able to extract symbol" + $ECHO "*** lists from a program, using \`nm' or equivalent, but libtool could" + $ECHO "*** not find such a program. So, this module is probably useless." + $ECHO "*** \`nm' from GNU binutils and a full rebuild may help." + fi + if test "$build_old_libs" = no; then + build_libtool_libs=module + build_old_libs=yes + else + build_libtool_libs=no + fi + fi + else + deplibs="$dir/$old_library $deplibs" + link_static=yes + fi + fi # link shared/static library? + + if test "$linkmode" = lib; then + if test -n "$dependency_libs" && + { test "$hardcode_into_libs" != yes || + test "$build_old_libs" = yes || + test "$link_static" = yes; }; then + # Extract -R from dependency_libs + temp_deplibs= + for libdir in $dependency_libs; do + case $libdir in + -R*) func_stripname '-R' '' "$libdir" + temp_xrpath=$func_stripname_result + case " $xrpath " in + *" $temp_xrpath "*) ;; + *) xrpath="$xrpath $temp_xrpath";; + esac;; + *) temp_deplibs="$temp_deplibs $libdir";; + esac + done + dependency_libs="$temp_deplibs" + fi + + newlib_search_path="$newlib_search_path $absdir" + # Link against this library + test "$link_static" = no && newdependency_libs="$abs_ladir/$laname $newdependency_libs" + # ... and its dependency_libs + tmp_libs= + for deplib in $dependency_libs; do + newdependency_libs="$deplib $newdependency_libs" + if $opt_duplicate_deps ; then + case "$tmp_libs " in + *" $deplib "*) specialdeplibs="$specialdeplibs $deplib" ;; + esac + fi + tmp_libs="$tmp_libs $deplib" + done + + if test "$link_all_deplibs" != no; then + # Add the search paths of all dependency libraries + for deplib in $dependency_libs; do + path= + case $deplib in + -L*) path="$deplib" ;; + *.la) + func_dirname "$deplib" "" "." + dir="$func_dirname_result" + # We need an absolute path. + case $dir in + [\\/]* | [A-Za-z]:[\\/]*) absdir="$dir" ;; + *) + absdir=`cd "$dir" && pwd` + if test -z "$absdir"; then + func_warning "cannot determine absolute directory name of \`$dir'" + absdir="$dir" + fi + ;; + esac + if $GREP "^installed=no" $deplib > /dev/null; then + case $host in + *-*-darwin*) + depdepl= + eval deplibrary_names=`${SED} -n -e 's/^library_names=\(.*\)$/\1/p' $deplib` + if test -n "$deplibrary_names" ; then + for tmp in $deplibrary_names ; do + depdepl=$tmp + done + if test -f "$absdir/$objdir/$depdepl" ; then + depdepl="$absdir/$objdir/$depdepl" + darwin_install_name=`${OTOOL} -L $depdepl | awk '{if (NR == 2) {print $1;exit}}'` + if test -z "$darwin_install_name"; then + darwin_install_name=`${OTOOL64} -L $depdepl | awk '{if (NR == 2) {print $1;exit}}'` + fi + compiler_flags="$compiler_flags ${wl}-dylib_file ${wl}${darwin_install_name}:${depdepl}" + linker_flags="$linker_flags -dylib_file ${darwin_install_name}:${depdepl}" + path= + fi + fi + ;; + *) + path="-L$absdir/$objdir" + ;; + esac + else + eval libdir=`${SED} -n -e 's/^libdir=\(.*\)$/\1/p' $deplib` + test -z "$libdir" && \ + func_fatal_error "\`$deplib' is not a valid libtool archive" + test "$absdir" != "$libdir" && \ + func_warning "\`$deplib' seems to be moved" + + path="-L$absdir" + fi + ;; + esac + case " $deplibs " in + *" $path "*) ;; + *) deplibs="$path $deplibs" ;; + esac + done + fi # link_all_deplibs != no + fi # linkmode = lib + done # for deplib in $libs + if test "$pass" = link; then + if test "$linkmode" = "prog"; then + compile_deplibs="$new_inherited_linker_flags $compile_deplibs" + finalize_deplibs="$new_inherited_linker_flags $finalize_deplibs" + else + compiler_flags="$compiler_flags "`$ECHO "X $new_inherited_linker_flags" | $Xsed -e 's% \([^ $]*\).ltframework% -framework \1%g'` + fi + fi + dependency_libs="$newdependency_libs" + if test "$pass" = dlpreopen; then + # Link the dlpreopened libraries before other libraries + for deplib in $save_deplibs; do + deplibs="$deplib $deplibs" + done + fi + if test "$pass" != dlopen; then + if test "$pass" != conv; then + # Make sure lib_search_path contains only unique directories. + lib_search_path= + for dir in $newlib_search_path; do + case "$lib_search_path " in + *" $dir "*) ;; + *) lib_search_path="$lib_search_path $dir" ;; + esac + done + newlib_search_path= + fi + + if test "$linkmode,$pass" != "prog,link"; then + vars="deplibs" + else + vars="compile_deplibs finalize_deplibs" + fi + for var in $vars dependency_libs; do + # Add libraries to $var in reverse order + eval tmp_libs=\"\$$var\" + new_libs= + for deplib in $tmp_libs; do + # FIXME: Pedantically, this is the right thing to do, so + # that some nasty dependency loop isn't accidentally + # broken: + #new_libs="$deplib $new_libs" + # Pragmatically, this seems to cause very few problems in + # practice: + case $deplib in + -L*) new_libs="$deplib $new_libs" ;; + -R*) ;; + *) + # And here is the reason: when a library appears more + # than once as an explicit dependence of a library, or + # is implicitly linked in more than once by the + # compiler, it is considered special, and multiple + # occurrences thereof are not removed. Compare this + # with having the same library being listed as a + # dependency of multiple other libraries: in this case, + # we know (pedantically, we assume) the library does not + # need to be listed more than once, so we keep only the + # last copy. This is not always right, but it is rare + # enough that we require users that really mean to play + # such unportable linking tricks to link the library + # using -Wl,-lname, so that libtool does not consider it + # for duplicate removal. + case " $specialdeplibs " in + *" $deplib "*) new_libs="$deplib $new_libs" ;; + *) + case " $new_libs " in + *" $deplib "*) ;; + *) new_libs="$deplib $new_libs" ;; + esac + ;; + esac + ;; + esac + done + tmp_libs= + for deplib in $new_libs; do + case $deplib in + -L*) + case " $tmp_libs " in + *" $deplib "*) ;; + *) tmp_libs="$tmp_libs $deplib" ;; + esac + ;; + *) tmp_libs="$tmp_libs $deplib" ;; + esac + done + eval $var=\"$tmp_libs\" + done # for var + fi + # Last step: remove runtime libs from dependency_libs + # (they stay in deplibs) + tmp_libs= + for i in $dependency_libs ; do + case " $predeps $postdeps $compiler_lib_search_path " in + *" $i "*) + i="" + ;; + esac + if test -n "$i" ; then + tmp_libs="$tmp_libs $i" + fi + done + dependency_libs=$tmp_libs + done # for pass + if test "$linkmode" = prog; then + dlfiles="$newdlfiles" + fi + if test "$linkmode" = prog || test "$linkmode" = lib; then + dlprefiles="$newdlprefiles" + fi + + case $linkmode in + oldlib) + if test -n "$dlfiles$dlprefiles" || test "$dlself" != no; then + func_warning "\`-dlopen' is ignored for archives" + fi + + case " $deplibs" in + *\ -l* | *\ -L*) + func_warning "\`-l' and \`-L' are ignored for archives" ;; + esac + + test -n "$rpath" && \ + func_warning "\`-rpath' is ignored for archives" + + test -n "$xrpath" && \ + func_warning "\`-R' is ignored for archives" + + test -n "$vinfo" && \ + func_warning "\`-version-info/-version-number' is ignored for archives" + + test -n "$release" && \ + func_warning "\`-release' is ignored for archives" + + test -n "$export_symbols$export_symbols_regex" && \ + func_warning "\`-export-symbols' is ignored for archives" + + # Now set the variables for building old libraries. + build_libtool_libs=no + oldlibs="$output" + objs="$objs$old_deplibs" + ;; + + lib) + # Make sure we only generate libraries of the form `libNAME.la'. + case $outputname in + lib*) + func_stripname 'lib' '.la' "$outputname" + name=$func_stripname_result + eval shared_ext=\"$shrext_cmds\" + eval libname=\"$libname_spec\" + ;; + *) + test "$module" = no && \ + func_fatal_help "libtool library \`$output' must begin with \`lib'" + + if test "$need_lib_prefix" != no; then + # Add the "lib" prefix for modules if required + func_stripname '' '.la' "$outputname" + name=$func_stripname_result + eval shared_ext=\"$shrext_cmds\" + eval libname=\"$libname_spec\" + else + func_stripname '' '.la' "$outputname" + libname=$func_stripname_result + fi + ;; + esac + + if test -n "$objs"; then + if test "$deplibs_check_method" != pass_all; then + func_fatal_error "cannot build libtool library \`$output' from non-libtool objects on this host:$objs" + else + $ECHO + $ECHO "*** Warning: Linking the shared library $output against the non-libtool" + $ECHO "*** objects $objs is not portable!" + libobjs="$libobjs $objs" + fi + fi + + test "$dlself" != no && \ + func_warning "\`-dlopen self' is ignored for libtool libraries" + + set dummy $rpath + shift + test "$#" -gt 1 && \ + func_warning "ignoring multiple \`-rpath's for a libtool library" + + install_libdir="$1" + + oldlibs= + if test -z "$rpath"; then + if test "$build_libtool_libs" = yes; then + # Building a libtool convenience library. + # Some compilers have problems with a `.al' extension so + # convenience libraries should have the same extension an + # archive normally would. + oldlibs="$output_objdir/$libname.$libext $oldlibs" + build_libtool_libs=convenience + build_old_libs=yes + fi + + test -n "$vinfo" && \ + func_warning "\`-version-info/-version-number' is ignored for convenience libraries" + + test -n "$release" && \ + func_warning "\`-release' is ignored for convenience libraries" + else + + # Parse the version information argument. + save_ifs="$IFS"; IFS=':' + set dummy $vinfo 0 0 0 + shift + IFS="$save_ifs" + + test -n "$7" && \ + func_fatal_help "too many parameters to \`-version-info'" + + # convert absolute version numbers to libtool ages + # this retains compatibility with .la files and attempts + # to make the code below a bit more comprehensible + + case $vinfo_number in + yes) + number_major="$1" + number_minor="$2" + number_revision="$3" + # + # There are really only two kinds -- those that + # use the current revision as the major version + # and those that subtract age and use age as + # a minor version. But, then there is irix + # which has an extra 1 added just for fun + # + case $version_type in + darwin|linux|osf|windows|none) + func_arith $number_major + $number_minor + current=$func_arith_result + age="$number_minor" + revision="$number_revision" + ;; + freebsd-aout|freebsd-elf|sunos) + current="$number_major" + revision="$number_minor" + age="0" + ;; + irix|nonstopux) + func_arith $number_major + $number_minor + current=$func_arith_result + age="$number_minor" + revision="$number_minor" + lt_irix_increment=no + ;; + *) + func_fatal_configuration "$modename: unknown library version type \`$version_type'" + ;; + esac + ;; + no) + current="$1" + revision="$2" + age="$3" + ;; + esac + + # Check that each of the things are valid numbers. + case $current in + 0|[1-9]|[1-9][0-9]|[1-9][0-9][0-9]|[1-9][0-9][0-9][0-9]|[1-9][0-9][0-9][0-9][0-9]) ;; + *) + func_error "CURRENT \`$current' must be a nonnegative integer" + func_fatal_error "\`$vinfo' is not valid version information" + ;; + esac + + case $revision in + 0|[1-9]|[1-9][0-9]|[1-9][0-9][0-9]|[1-9][0-9][0-9][0-9]|[1-9][0-9][0-9][0-9][0-9]) ;; + *) + func_error "REVISION \`$revision' must be a nonnegative integer" + func_fatal_error "\`$vinfo' is not valid version information" + ;; + esac + + case $age in + 0|[1-9]|[1-9][0-9]|[1-9][0-9][0-9]|[1-9][0-9][0-9][0-9]|[1-9][0-9][0-9][0-9][0-9]) ;; + *) + func_error "AGE \`$age' must be a nonnegative integer" + func_fatal_error "\`$vinfo' is not valid version information" + ;; + esac + + if test "$age" -gt "$current"; then + func_error "AGE \`$age' is greater than the current interface number \`$current'" + func_fatal_error "\`$vinfo' is not valid version information" + fi + + # Calculate the version variables. + major= + versuffix= + verstring= + case $version_type in + none) ;; + + darwin) + # Like Linux, but with the current version available in + # verstring for coding it into the library header + func_arith $current - $age + major=.$func_arith_result + versuffix="$major.$age.$revision" + # Darwin ld doesn't like 0 for these options... + func_arith $current + 1 + minor_current=$func_arith_result + xlcverstring="${wl}-compatibility_version ${wl}$minor_current ${wl}-current_version ${wl}$minor_current.$revision" + verstring="-compatibility_version $minor_current -current_version $minor_current.$revision" + ;; + + freebsd-aout) + major=".$current" + versuffix=".$current.$revision"; + ;; + + freebsd-elf) + major=".$current" + versuffix=".$current" + ;; + + irix | nonstopux) + if test "X$lt_irix_increment" = "Xno"; then + func_arith $current - $age + else + func_arith $current - $age + 1 + fi + major=$func_arith_result + + case $version_type in + nonstopux) verstring_prefix=nonstopux ;; + *) verstring_prefix=sgi ;; + esac + verstring="$verstring_prefix$major.$revision" + + # Add in all the interfaces that we are compatible with. + loop=$revision + while test "$loop" -ne 0; do + func_arith $revision - $loop + iface=$func_arith_result + func_arith $loop - 1 + loop=$func_arith_result + verstring="$verstring_prefix$major.$iface:$verstring" + done + + # Before this point, $major must not contain `.'. + major=.$major + versuffix="$major.$revision" + ;; + + linux) + func_arith $current - $age + major=.$func_arith_result + versuffix="$major.$age.$revision" + ;; + + osf) + func_arith $current - $age + major=.$func_arith_result + versuffix=".$current.$age.$revision" + verstring="$current.$age.$revision" + + # Add in all the interfaces that we are compatible with. + loop=$age + while test "$loop" -ne 0; do + func_arith $current - $loop + iface=$func_arith_result + func_arith $loop - 1 + loop=$func_arith_result + verstring="$verstring:${iface}.0" + done + + # Make executables depend on our current version. + verstring="$verstring:${current}.0" + ;; + + qnx) + major=".$current" + versuffix=".$current" + ;; + + sunos) + major=".$current" + versuffix=".$current.$revision" + ;; + + windows) + # Use '-' rather than '.', since we only want one + # extension on DOS 8.3 filesystems. + func_arith $current - $age + major=$func_arith_result + versuffix="-$major" + ;; + + *) + func_fatal_configuration "unknown library version type \`$version_type'" + ;; + esac + + # Clear the version info if we defaulted, and they specified a release. + if test -z "$vinfo" && test -n "$release"; then + major= + case $version_type in + darwin) + # we can't check for "0.0" in archive_cmds due to quoting + # problems, so we reset it completely + verstring= + ;; + *) + verstring="0.0" + ;; + esac + if test "$need_version" = no; then + versuffix= + else + versuffix=".0.0" + fi + fi + + # Remove version info from name if versioning should be avoided + if test "$avoid_version" = yes && test "$need_version" = no; then + major= + versuffix= + verstring="" + fi + + # Check to see if the archive will have undefined symbols. + if test "$allow_undefined" = yes; then + if test "$allow_undefined_flag" = unsupported; then + func_warning "undefined symbols not allowed in $host shared libraries" + build_libtool_libs=no + build_old_libs=yes + fi + else + # Don't allow undefined symbols. + allow_undefined_flag="$no_undefined_flag" + fi + + fi + + func_generate_dlsyms "$libname" "$libname" "yes" + libobjs="$libobjs $symfileobj" + test "X$libobjs" = "X " && libobjs= + + if test "$mode" != relink; then + # Remove our outputs, but don't remove object files since they + # may have been created when compiling PIC objects. + removelist= + tempremovelist=`$ECHO "$output_objdir/*"` + for p in $tempremovelist; do + case $p in + *.$objext | *.gcno) + ;; + $output_objdir/$outputname | $output_objdir/$libname.* | $output_objdir/${libname}${release}.*) + if test "X$precious_files_regex" != "X"; then + if $ECHO "$p" | $EGREP -e "$precious_files_regex" >/dev/null 2>&1 + then + continue + fi + fi + removelist="$removelist $p" + ;; + *) ;; + esac + done + test -n "$removelist" && \ + func_show_eval "${RM}r \$removelist" + fi + + # Now set the variables for building old libraries. + if test "$build_old_libs" = yes && test "$build_libtool_libs" != convenience ; then + oldlibs="$oldlibs $output_objdir/$libname.$libext" + + # Transform .lo files to .o files. + oldobjs="$objs "`$ECHO "X$libobjs" | $SP2NL | $Xsed -e '/\.'${libext}'$/d' -e "$lo2o" | $NL2SP` + fi + + # Eliminate all temporary directories. + #for path in $notinst_path; do + # lib_search_path=`$ECHO "X$lib_search_path " | $Xsed -e "s% $path % %g"` + # deplibs=`$ECHO "X$deplibs " | $Xsed -e "s% -L$path % %g"` + # dependency_libs=`$ECHO "X$dependency_libs " | $Xsed -e "s% -L$path % %g"` + #done + + if test -n "$xrpath"; then + # If the user specified any rpath flags, then add them. + temp_xrpath= + for libdir in $xrpath; do + temp_xrpath="$temp_xrpath -R$libdir" + case "$finalize_rpath " in + *" $libdir "*) ;; + *) finalize_rpath="$finalize_rpath $libdir" ;; + esac + done + if test "$hardcode_into_libs" != yes || test "$build_old_libs" = yes; then + dependency_libs="$temp_xrpath $dependency_libs" + fi + fi + + # Make sure dlfiles contains only unique files that won't be dlpreopened + old_dlfiles="$dlfiles" + dlfiles= + for lib in $old_dlfiles; do + case " $dlprefiles $dlfiles " in + *" $lib "*) ;; + *) dlfiles="$dlfiles $lib" ;; + esac + done + + # Make sure dlprefiles contains only unique files + old_dlprefiles="$dlprefiles" + dlprefiles= + for lib in $old_dlprefiles; do + case "$dlprefiles " in + *" $lib "*) ;; + *) dlprefiles="$dlprefiles $lib" ;; + esac + done + + if test "$build_libtool_libs" = yes; then + if test -n "$rpath"; then + case $host in + *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-os2* | *-*-beos* | *-cegcc*) + # these systems don't actually have a c library (as such)! + ;; + *-*-rhapsody* | *-*-darwin1.[012]) + # Rhapsody C library is in the System framework + deplibs="$deplibs System.ltframework" + ;; + *-*-netbsd*) + # Don't link with libc until the a.out ld.so is fixed. + ;; + *-*-openbsd* | *-*-freebsd* | *-*-dragonfly*) + # Do not include libc due to us having libc/libc_r. + ;; + *-*-sco3.2v5* | *-*-sco5v6*) + # Causes problems with __ctype + ;; + *-*-sysv4.2uw2* | *-*-sysv5* | *-*-unixware* | *-*-OpenUNIX*) + # Compiler inserts libc in the correct place for threads to work + ;; + *) + # Add libc to deplibs on all other systems if necessary. + if test "$build_libtool_need_lc" = "yes"; then + deplibs="$deplibs -lc" + fi + ;; + esac + fi + + # Transform deplibs into only deplibs that can be linked in shared. + name_save=$name + libname_save=$libname + release_save=$release + versuffix_save=$versuffix + major_save=$major + # I'm not sure if I'm treating the release correctly. I think + # release should show up in the -l (ie -lgmp5) so we don't want to + # add it in twice. Is that correct? + release="" + versuffix="" + major="" + newdeplibs= + droppeddeps=no + case $deplibs_check_method in + pass_all) + # Don't check for shared/static. Everything works. + # This might be a little naive. We might want to check + # whether the library exists or not. But this is on + # osf3 & osf4 and I'm not really sure... Just + # implementing what was already the behavior. + newdeplibs=$deplibs + ;; + test_compile) + # This code stresses the "libraries are programs" paradigm to its + # limits. Maybe even breaks it. We compile a program, linking it + # against the deplibs as a proxy for the library. Then we can check + # whether they linked in statically or dynamically with ldd. + $opt_dry_run || $RM conftest.c + cat > conftest.c </dev/null` + for potent_lib in $potential_libs; do + # Follow soft links. + if ls -lLd "$potent_lib" 2>/dev/null | + $GREP " -> " >/dev/null; then + continue + fi + # The statement above tries to avoid entering an + # endless loop below, in case of cyclic links. + # We might still enter an endless loop, since a link + # loop can be closed while we follow links, + # but so what? + potlib="$potent_lib" + while test -h "$potlib" 2>/dev/null; do + potliblink=`ls -ld $potlib | ${SED} 's/.* -> //'` + case $potliblink in + [\\/]* | [A-Za-z]:[\\/]*) potlib="$potliblink";; + *) potlib=`$ECHO "X$potlib" | $Xsed -e 's,[^/]*$,,'`"$potliblink";; + esac + done + if eval $file_magic_cmd \"\$potlib\" 2>/dev/null | + $SED -e 10q | + $EGREP "$file_magic_regex" > /dev/null; then + newdeplibs="$newdeplibs $a_deplib" + a_deplib="" + break 2 + fi + done + done + fi + if test -n "$a_deplib" ; then + droppeddeps=yes + $ECHO + $ECHO "*** Warning: linker path does not have real file for library $a_deplib." + $ECHO "*** I have the capability to make that library automatically link in when" + $ECHO "*** you link to this library. But I can only do this if you have a" + $ECHO "*** shared version of the library, which you do not appear to have" + $ECHO "*** because I did check the linker path looking for a file starting" + if test -z "$potlib" ; then + $ECHO "*** with $libname but no candidates were found. (...for file magic test)" + else + $ECHO "*** with $libname and none of the candidates passed a file format test" + $ECHO "*** using a file magic. Last file checked: $potlib" + fi + fi + ;; + *) + # Add a -L argument. + newdeplibs="$newdeplibs $a_deplib" + ;; + esac + done # Gone through all deplibs. + ;; + match_pattern*) + set dummy $deplibs_check_method; shift + match_pattern_regex=`expr "$deplibs_check_method" : "$1 \(.*\)"` + for a_deplib in $deplibs; do + case $a_deplib in + -l*) + func_stripname -l '' "$a_deplib" + name=$func_stripname_result + if test "X$allow_libtool_libs_with_static_runtimes" = "Xyes" ; then + case " $predeps $postdeps " in + *" $a_deplib "*) + newdeplibs="$newdeplibs $a_deplib" + a_deplib="" + ;; + esac + fi + if test -n "$a_deplib" ; then + libname=`eval "\\$ECHO \"$libname_spec\""` + for i in $lib_search_path $sys_lib_search_path $shlib_search_path; do + potential_libs=`ls $i/$libname[.-]* 2>/dev/null` + for potent_lib in $potential_libs; do + potlib="$potent_lib" # see symlink-check above in file_magic test + if eval "\$ECHO \"X$potent_lib\"" 2>/dev/null | $Xsed -e 10q | \ + $EGREP "$match_pattern_regex" > /dev/null; then + newdeplibs="$newdeplibs $a_deplib" + a_deplib="" + break 2 + fi + done + done + fi + if test -n "$a_deplib" ; then + droppeddeps=yes + $ECHO + $ECHO "*** Warning: linker path does not have real file for library $a_deplib." + $ECHO "*** I have the capability to make that library automatically link in when" + $ECHO "*** you link to this library. But I can only do this if you have a" + $ECHO "*** shared version of the library, which you do not appear to have" + $ECHO "*** because I did check the linker path looking for a file starting" + if test -z "$potlib" ; then + $ECHO "*** with $libname but no candidates were found. (...for regex pattern test)" + else + $ECHO "*** with $libname and none of the candidates passed a file format test" + $ECHO "*** using a regex pattern. Last file checked: $potlib" + fi + fi + ;; + *) + # Add a -L argument. + newdeplibs="$newdeplibs $a_deplib" + ;; + esac + done # Gone through all deplibs. + ;; + none | unknown | *) + newdeplibs="" + tmp_deplibs=`$ECHO "X $deplibs" | $Xsed \ + -e 's/ -lc$//' -e 's/ -[LR][^ ]*//g'` + if test "X$allow_libtool_libs_with_static_runtimes" = "Xyes" ; then + for i in $predeps $postdeps ; do + # can't use Xsed below, because $i might contain '/' + tmp_deplibs=`$ECHO "X $tmp_deplibs" | $Xsed -e "s,$i,,"` + done + fi + if $ECHO "X $tmp_deplibs" | $Xsed -e 's/[ ]//g' | + $GREP . >/dev/null; then + $ECHO + if test "X$deplibs_check_method" = "Xnone"; then + $ECHO "*** Warning: inter-library dependencies are not supported in this platform." + else + $ECHO "*** Warning: inter-library dependencies are not known to be supported." + fi + $ECHO "*** All declared inter-library dependencies are being dropped." + droppeddeps=yes + fi + ;; + esac + versuffix=$versuffix_save + major=$major_save + release=$release_save + libname=$libname_save + name=$name_save + + case $host in + *-*-rhapsody* | *-*-darwin1.[012]) + # On Rhapsody replace the C library with the System framework + newdeplibs=`$ECHO "X $newdeplibs" | $Xsed -e 's/ -lc / System.ltframework /'` + ;; + esac + + if test "$droppeddeps" = yes; then + if test "$module" = yes; then + $ECHO + $ECHO "*** Warning: libtool could not satisfy all declared inter-library" + $ECHO "*** dependencies of module $libname. Therefore, libtool will create" + $ECHO "*** a static module, that should work as long as the dlopening" + $ECHO "*** application is linked with the -dlopen flag." + if test -z "$global_symbol_pipe"; then + $ECHO + $ECHO "*** However, this would only work if libtool was able to extract symbol" + $ECHO "*** lists from a program, using \`nm' or equivalent, but libtool could" + $ECHO "*** not find such a program. So, this module is probably useless." + $ECHO "*** \`nm' from GNU binutils and a full rebuild may help." + fi + if test "$build_old_libs" = no; then + oldlibs="$output_objdir/$libname.$libext" + build_libtool_libs=module + build_old_libs=yes + else + build_libtool_libs=no + fi + else + $ECHO "*** The inter-library dependencies that have been dropped here will be" + $ECHO "*** automatically added whenever a program is linked with this library" + $ECHO "*** or is declared to -dlopen it." + + if test "$allow_undefined" = no; then + $ECHO + $ECHO "*** Since this library must not contain undefined symbols," + $ECHO "*** because either the platform does not support them or" + $ECHO "*** it was explicitly requested with -no-undefined," + $ECHO "*** libtool will only create a static version of it." + if test "$build_old_libs" = no; then + oldlibs="$output_objdir/$libname.$libext" + build_libtool_libs=module + build_old_libs=yes + else + build_libtool_libs=no + fi + fi + fi + fi + # Done checking deplibs! + deplibs=$newdeplibs + fi + # Time to change all our "foo.ltframework" stuff back to "-framework foo" + case $host in + *-*-darwin*) + newdeplibs=`$ECHO "X $newdeplibs" | $Xsed -e 's% \([^ $]*\).ltframework% -framework \1%g'` + new_inherited_linker_flags=`$ECHO "X $new_inherited_linker_flags" | $Xsed -e 's% \([^ $]*\).ltframework% -framework \1%g'` + deplibs=`$ECHO "X $deplibs" | $Xsed -e 's% \([^ $]*\).ltframework% -framework \1%g'` + ;; + esac + + # move library search paths that coincide with paths to not yet + # installed libraries to the beginning of the library search list + new_libs= + for path in $notinst_path; do + case " $new_libs " in + *" -L$path/$objdir "*) ;; + *) + case " $deplibs " in + *" -L$path/$objdir "*) + new_libs="$new_libs -L$path/$objdir" ;; + esac + ;; + esac + done + for deplib in $deplibs; do + case $deplib in + -L*) + case " $new_libs " in + *" $deplib "*) ;; + *) new_libs="$new_libs $deplib" ;; + esac + ;; + *) new_libs="$new_libs $deplib" ;; + esac + done + deplibs="$new_libs" + + # All the library-specific variables (install_libdir is set above). + library_names= + old_library= + dlname= + + # Test again, we may have decided not to build it any more + if test "$build_libtool_libs" = yes; then + if test "$hardcode_into_libs" = yes; then + # Hardcode the library paths + hardcode_libdirs= + dep_rpath= + rpath="$finalize_rpath" + test "$mode" != relink && rpath="$compile_rpath$rpath" + for libdir in $rpath; do + if test -n "$hardcode_libdir_flag_spec"; then + if test -n "$hardcode_libdir_separator"; then + if test -z "$hardcode_libdirs"; then + hardcode_libdirs="$libdir" + else + # Just accumulate the unique libdirs. + case $hardcode_libdir_separator$hardcode_libdirs$hardcode_libdir_separator in + *"$hardcode_libdir_separator$libdir$hardcode_libdir_separator"*) + ;; + *) + hardcode_libdirs="$hardcode_libdirs$hardcode_libdir_separator$libdir" + ;; + esac + fi + else + eval flag=\"$hardcode_libdir_flag_spec\" + dep_rpath="$dep_rpath $flag" + fi + elif test -n "$runpath_var"; then + case "$perm_rpath " in + *" $libdir "*) ;; + *) perm_rpath="$perm_rpath $libdir" ;; + esac + fi + done + # Substitute the hardcoded libdirs into the rpath. + if test -n "$hardcode_libdir_separator" && + test -n "$hardcode_libdirs"; then + libdir="$hardcode_libdirs" + if test -n "$hardcode_libdir_flag_spec_ld"; then + eval dep_rpath=\"$hardcode_libdir_flag_spec_ld\" + else + eval dep_rpath=\"$hardcode_libdir_flag_spec\" + fi + fi + if test -n "$runpath_var" && test -n "$perm_rpath"; then + # We should set the runpath_var. + rpath= + for dir in $perm_rpath; do + rpath="$rpath$dir:" + done + eval "$runpath_var='$rpath\$$runpath_var'; export $runpath_var" + fi + test -n "$dep_rpath" && deplibs="$dep_rpath $deplibs" + fi + + shlibpath="$finalize_shlibpath" + test "$mode" != relink && shlibpath="$compile_shlibpath$shlibpath" + if test -n "$shlibpath"; then + eval "$shlibpath_var='$shlibpath\$$shlibpath_var'; export $shlibpath_var" + fi + + # Get the real and link names of the library. + eval shared_ext=\"$shrext_cmds\" + eval library_names=\"$library_names_spec\" + set dummy $library_names + shift + realname="$1" + shift + + if test -n "$soname_spec"; then + eval soname=\"$soname_spec\" + else + soname="$realname" + fi + if test -z "$dlname"; then + dlname=$soname + fi + + lib="$output_objdir/$realname" + linknames= + for link + do + linknames="$linknames $link" + done + + # Use standard objects if they are pic + test -z "$pic_flag" && libobjs=`$ECHO "X$libobjs" | $SP2NL | $Xsed -e "$lo2o" | $NL2SP` + test "X$libobjs" = "X " && libobjs= + + delfiles= + if test -n "$export_symbols" && test -n "$include_expsyms"; then + $opt_dry_run || cp "$export_symbols" "$output_objdir/$libname.uexp" + export_symbols="$output_objdir/$libname.uexp" + delfiles="$delfiles $export_symbols" + fi + + orig_export_symbols= + case $host_os in + cygwin* | mingw* | cegcc*) + if test -n "$export_symbols" && test -z "$export_symbols_regex"; then + # exporting using user supplied symfile + if test "x`$SED 1q $export_symbols`" != xEXPORTS; then + # and it's NOT already a .def file. Must figure out + # which of the given symbols are data symbols and tag + # them as such. So, trigger use of export_symbols_cmds. + # export_symbols gets reassigned inside the "prepare + # the list of exported symbols" if statement, so the + # include_expsyms logic still works. + orig_export_symbols="$export_symbols" + export_symbols= + always_export_symbols=yes + fi + fi + ;; + esac + + # Prepare the list of exported symbols + if test -z "$export_symbols"; then + if test "$always_export_symbols" = yes || test -n "$export_symbols_regex"; then + func_verbose "generating symbol list for \`$libname.la'" + export_symbols="$output_objdir/$libname.exp" + $opt_dry_run || $RM $export_symbols + cmds=$export_symbols_cmds + save_ifs="$IFS"; IFS='~' + for cmd in $cmds; do + IFS="$save_ifs" + eval cmd=\"$cmd\" + func_len " $cmd" + len=$func_len_result + if test "$len" -lt "$max_cmd_len" || test "$max_cmd_len" -le -1; then + func_show_eval "$cmd" 'exit $?' + skipped_export=false + else + # The command line is too long to execute in one step. + func_verbose "using reloadable object file for export list..." + skipped_export=: + # Break out early, otherwise skipped_export may be + # set to false by a later but shorter cmd. + break + fi + done + IFS="$save_ifs" + if test -n "$export_symbols_regex" && test "X$skipped_export" != "X:"; then + func_show_eval '$EGREP -e "$export_symbols_regex" "$export_symbols" > "${export_symbols}T"' + func_show_eval '$MV "${export_symbols}T" "$export_symbols"' + fi + fi + fi + + if test -n "$export_symbols" && test -n "$include_expsyms"; then + tmp_export_symbols="$export_symbols" + test -n "$orig_export_symbols" && tmp_export_symbols="$orig_export_symbols" + $opt_dry_run || eval '$ECHO "X$include_expsyms" | $Xsed | $SP2NL >> "$tmp_export_symbols"' + fi + + if test "X$skipped_export" != "X:" && test -n "$orig_export_symbols"; then + # The given exports_symbols file has to be filtered, so filter it. + func_verbose "filter symbol list for \`$libname.la' to tag DATA exports" + # FIXME: $output_objdir/$libname.filter potentially contains lots of + # 's' commands which not all seds can handle. GNU sed should be fine + # though. Also, the filter scales superlinearly with the number of + # global variables. join(1) would be nice here, but unfortunately + # isn't a blessed tool. + $opt_dry_run || $SED -e '/[ ,]DATA/!d;s,\(.*\)\([ \,].*\),s|^\1$|\1\2|,' < $export_symbols > $output_objdir/$libname.filter + delfiles="$delfiles $export_symbols $output_objdir/$libname.filter" + export_symbols=$output_objdir/$libname.def + $opt_dry_run || $SED -f $output_objdir/$libname.filter < $orig_export_symbols > $export_symbols + fi + + tmp_deplibs= + for test_deplib in $deplibs; do + case " $convenience " in + *" $test_deplib "*) ;; + *) + tmp_deplibs="$tmp_deplibs $test_deplib" + ;; + esac + done + deplibs="$tmp_deplibs" + + if test -n "$convenience"; then + if test -n "$whole_archive_flag_spec" && + test "$compiler_needs_object" = yes && + test -z "$libobjs"; then + # extract the archives, so we have objects to list. + # TODO: could optimize this to just extract one archive. + whole_archive_flag_spec= + fi + if test -n "$whole_archive_flag_spec"; then + save_libobjs=$libobjs + eval libobjs=\"\$libobjs $whole_archive_flag_spec\" + test "X$libobjs" = "X " && libobjs= + else + gentop="$output_objdir/${outputname}x" + generated="$generated $gentop" + + func_extract_archives $gentop $convenience + libobjs="$libobjs $func_extract_archives_result" + test "X$libobjs" = "X " && libobjs= + fi + fi + + if test "$thread_safe" = yes && test -n "$thread_safe_flag_spec"; then + eval flag=\"$thread_safe_flag_spec\" + linker_flags="$linker_flags $flag" + fi + + # Make a backup of the uninstalled library when relinking + if test "$mode" = relink; then + $opt_dry_run || eval '(cd $output_objdir && $RM ${realname}U && $MV $realname ${realname}U)' || exit $? + fi + + # Do each of the archive commands. + if test "$module" = yes && test -n "$module_cmds" ; then + if test -n "$export_symbols" && test -n "$module_expsym_cmds"; then + eval test_cmds=\"$module_expsym_cmds\" + cmds=$module_expsym_cmds + else + eval test_cmds=\"$module_cmds\" + cmds=$module_cmds + fi + else + if test -n "$export_symbols" && test -n "$archive_expsym_cmds"; then + eval test_cmds=\"$archive_expsym_cmds\" + cmds=$archive_expsym_cmds + else + eval test_cmds=\"$archive_cmds\" + cmds=$archive_cmds + fi + fi + + if test "X$skipped_export" != "X:" && + func_len " $test_cmds" && + len=$func_len_result && + test "$len" -lt "$max_cmd_len" || test "$max_cmd_len" -le -1; then + : + else + # The command line is too long to link in one step, link piecewise + # or, if using GNU ld and skipped_export is not :, use a linker + # script. + + # Save the value of $output and $libobjs because we want to + # use them later. If we have whole_archive_flag_spec, we + # want to use save_libobjs as it was before + # whole_archive_flag_spec was expanded, because we can't + # assume the linker understands whole_archive_flag_spec. + # This may have to be revisited, in case too many + # convenience libraries get linked in and end up exceeding + # the spec. + if test -z "$convenience" || test -z "$whole_archive_flag_spec"; then + save_libobjs=$libobjs + fi + save_output=$output + output_la=`$ECHO "X$output" | $Xsed -e "$basename"` + + # Clear the reloadable object creation command queue and + # initialize k to one. + test_cmds= + concat_cmds= + objlist= + last_robj= + k=1 + + if test -n "$save_libobjs" && test "X$skipped_export" != "X:" && test "$with_gnu_ld" = yes; then + output=${output_objdir}/${output_la}.lnkscript + func_verbose "creating GNU ld script: $output" + $ECHO 'INPUT (' > $output + for obj in $save_libobjs + do + $ECHO "$obj" >> $output + done + $ECHO ')' >> $output + delfiles="$delfiles $output" + elif test -n "$save_libobjs" && test "X$skipped_export" != "X:" && test "X$file_list_spec" != X; then + output=${output_objdir}/${output_la}.lnk + func_verbose "creating linker input file list: $output" + : > $output + set x $save_libobjs + shift + firstobj= + if test "$compiler_needs_object" = yes; then + firstobj="$1 " + shift + fi + for obj + do + $ECHO "$obj" >> $output + done + delfiles="$delfiles $output" + output=$firstobj\"$file_list_spec$output\" + else + if test -n "$save_libobjs"; then + func_verbose "creating reloadable object files..." + output=$output_objdir/$output_la-${k}.$objext + eval test_cmds=\"$reload_cmds\" + func_len " $test_cmds" + len0=$func_len_result + len=$len0 + + # Loop over the list of objects to be linked. + for obj in $save_libobjs + do + func_len " $obj" + func_arith $len + $func_len_result + len=$func_arith_result + if test "X$objlist" = X || + test "$len" -lt "$max_cmd_len"; then + func_append objlist " $obj" + else + # The command $test_cmds is almost too long, add a + # command to the queue. + if test "$k" -eq 1 ; then + # The first file doesn't have a previous command to add. + eval concat_cmds=\"$reload_cmds $objlist $last_robj\" + else + # All subsequent reloadable object files will link in + # the last one created. + eval concat_cmds=\"\$concat_cmds~$reload_cmds $objlist $last_robj~\$RM $last_robj\" + fi + last_robj=$output_objdir/$output_la-${k}.$objext + func_arith $k + 1 + k=$func_arith_result + output=$output_objdir/$output_la-${k}.$objext + objlist=$obj + func_len " $last_robj" + func_arith $len0 + $func_len_result + len=$func_arith_result + fi + done + # Handle the remaining objects by creating one last + # reloadable object file. All subsequent reloadable object + # files will link in the last one created. + test -z "$concat_cmds" || concat_cmds=$concat_cmds~ + eval concat_cmds=\"\${concat_cmds}$reload_cmds $objlist $last_robj\" + if test -n "$last_robj"; then + eval concat_cmds=\"\${concat_cmds}~\$RM $last_robj\" + fi + delfiles="$delfiles $output" + + else + output= + fi + + if ${skipped_export-false}; then + func_verbose "generating symbol list for \`$libname.la'" + export_symbols="$output_objdir/$libname.exp" + $opt_dry_run || $RM $export_symbols + libobjs=$output + # Append the command to create the export file. + test -z "$concat_cmds" || concat_cmds=$concat_cmds~ + eval concat_cmds=\"\$concat_cmds$export_symbols_cmds\" + if test -n "$last_robj"; then + eval concat_cmds=\"\$concat_cmds~\$RM $last_robj\" + fi + fi + + test -n "$save_libobjs" && + func_verbose "creating a temporary reloadable object file: $output" + + # Loop through the commands generated above and execute them. + save_ifs="$IFS"; IFS='~' + for cmd in $concat_cmds; do + IFS="$save_ifs" + $opt_silent || { + func_quote_for_expand "$cmd" + eval "func_echo $func_quote_for_expand_result" + } + $opt_dry_run || eval "$cmd" || { + lt_exit=$? + + # Restore the uninstalled library and exit + if test "$mode" = relink; then + ( cd "$output_objdir" && \ + $RM "${realname}T" && \ + $MV "${realname}U" "$realname" ) + fi + + exit $lt_exit + } + done + IFS="$save_ifs" + + if test -n "$export_symbols_regex" && ${skipped_export-false}; then + func_show_eval '$EGREP -e "$export_symbols_regex" "$export_symbols" > "${export_symbols}T"' + func_show_eval '$MV "${export_symbols}T" "$export_symbols"' + fi + fi + + if ${skipped_export-false}; then + if test -n "$export_symbols" && test -n "$include_expsyms"; then + tmp_export_symbols="$export_symbols" + test -n "$orig_export_symbols" && tmp_export_symbols="$orig_export_symbols" + $opt_dry_run || eval '$ECHO "X$include_expsyms" | $Xsed | $SP2NL >> "$tmp_export_symbols"' + fi + + if test -n "$orig_export_symbols"; then + # The given exports_symbols file has to be filtered, so filter it. + func_verbose "filter symbol list for \`$libname.la' to tag DATA exports" + # FIXME: $output_objdir/$libname.filter potentially contains lots of + # 's' commands which not all seds can handle. GNU sed should be fine + # though. Also, the filter scales superlinearly with the number of + # global variables. join(1) would be nice here, but unfortunately + # isn't a blessed tool. + $opt_dry_run || $SED -e '/[ ,]DATA/!d;s,\(.*\)\([ \,].*\),s|^\1$|\1\2|,' < $export_symbols > $output_objdir/$libname.filter + delfiles="$delfiles $export_symbols $output_objdir/$libname.filter" + export_symbols=$output_objdir/$libname.def + $opt_dry_run || $SED -f $output_objdir/$libname.filter < $orig_export_symbols > $export_symbols + fi + fi + + libobjs=$output + # Restore the value of output. + output=$save_output + + if test -n "$convenience" && test -n "$whole_archive_flag_spec"; then + eval libobjs=\"\$libobjs $whole_archive_flag_spec\" + test "X$libobjs" = "X " && libobjs= + fi + # Expand the library linking commands again to reset the + # value of $libobjs for piecewise linking. + + # Do each of the archive commands. + if test "$module" = yes && test -n "$module_cmds" ; then + if test -n "$export_symbols" && test -n "$module_expsym_cmds"; then + cmds=$module_expsym_cmds + else + cmds=$module_cmds + fi + else + if test -n "$export_symbols" && test -n "$archive_expsym_cmds"; then + cmds=$archive_expsym_cmds + else + cmds=$archive_cmds + fi + fi + fi + + if test -n "$delfiles"; then + # Append the command to remove temporary files to $cmds. + eval cmds=\"\$cmds~\$RM $delfiles\" + fi + + # Add any objects from preloaded convenience libraries + if test -n "$dlprefiles"; then + gentop="$output_objdir/${outputname}x" + generated="$generated $gentop" + + func_extract_archives $gentop $dlprefiles + libobjs="$libobjs $func_extract_archives_result" + test "X$libobjs" = "X " && libobjs= + fi + + save_ifs="$IFS"; IFS='~' + for cmd in $cmds; do + IFS="$save_ifs" + eval cmd=\"$cmd\" + $opt_silent || { + func_quote_for_expand "$cmd" + eval "func_echo $func_quote_for_expand_result" + } + $opt_dry_run || eval "$cmd" || { + lt_exit=$? + + # Restore the uninstalled library and exit + if test "$mode" = relink; then + ( cd "$output_objdir" && \ + $RM "${realname}T" && \ + $MV "${realname}U" "$realname" ) + fi + + exit $lt_exit + } + done + IFS="$save_ifs" + + # Restore the uninstalled library and exit + if test "$mode" = relink; then + $opt_dry_run || eval '(cd $output_objdir && $RM ${realname}T && $MV $realname ${realname}T && $MV ${realname}U $realname)' || exit $? + + if test -n "$convenience"; then + if test -z "$whole_archive_flag_spec"; then + func_show_eval '${RM}r "$gentop"' + fi + fi + + exit $EXIT_SUCCESS + fi + + # Create links to the real library. + for linkname in $linknames; do + if test "$realname" != "$linkname"; then + func_show_eval '(cd "$output_objdir" && $RM "$linkname" && $LN_S "$realname" "$linkname")' 'exit $?' + fi + done + + # If -module or -export-dynamic was specified, set the dlname. + if test "$module" = yes || test "$export_dynamic" = yes; then + # On all known operating systems, these are identical. + dlname="$soname" + fi + fi + ;; + + obj) + if test -n "$dlfiles$dlprefiles" || test "$dlself" != no; then + func_warning "\`-dlopen' is ignored for objects" + fi + + case " $deplibs" in + *\ -l* | *\ -L*) + func_warning "\`-l' and \`-L' are ignored for objects" ;; + esac + + test -n "$rpath" && \ + func_warning "\`-rpath' is ignored for objects" + + test -n "$xrpath" && \ + func_warning "\`-R' is ignored for objects" + + test -n "$vinfo" && \ + func_warning "\`-version-info' is ignored for objects" + + test -n "$release" && \ + func_warning "\`-release' is ignored for objects" + + case $output in + *.lo) + test -n "$objs$old_deplibs" && \ + func_fatal_error "cannot build library object \`$output' from non-libtool objects" + + libobj=$output + func_lo2o "$libobj" + obj=$func_lo2o_result + ;; + *) + libobj= + obj="$output" + ;; + esac + + # Delete the old objects. + $opt_dry_run || $RM $obj $libobj + + # Objects from convenience libraries. This assumes + # single-version convenience libraries. Whenever we create + # different ones for PIC/non-PIC, this we'll have to duplicate + # the extraction. + reload_conv_objs= + gentop= + # reload_cmds runs $LD directly, so let us get rid of + # -Wl from whole_archive_flag_spec and hope we can get by with + # turning comma into space.. + wl= + + if test -n "$convenience"; then + if test -n "$whole_archive_flag_spec"; then + eval tmp_whole_archive_flags=\"$whole_archive_flag_spec\" + reload_conv_objs=$reload_objs\ `$ECHO "X$tmp_whole_archive_flags" | $Xsed -e 's|,| |g'` + else + gentop="$output_objdir/${obj}x" + generated="$generated $gentop" + + func_extract_archives $gentop $convenience + reload_conv_objs="$reload_objs $func_extract_archives_result" + fi + fi + + # Create the old-style object. + reload_objs="$objs$old_deplibs "`$ECHO "X$libobjs" | $SP2NL | $Xsed -e '/\.'${libext}$'/d' -e '/\.lib$/d' -e "$lo2o" | $NL2SP`" $reload_conv_objs" ### testsuite: skip nested quoting test + + output="$obj" + func_execute_cmds "$reload_cmds" 'exit $?' + + # Exit if we aren't doing a library object file. + if test -z "$libobj"; then + if test -n "$gentop"; then + func_show_eval '${RM}r "$gentop"' + fi + + exit $EXIT_SUCCESS + fi + + if test "$build_libtool_libs" != yes; then + if test -n "$gentop"; then + func_show_eval '${RM}r "$gentop"' + fi + + # Create an invalid libtool object if no PIC, so that we don't + # accidentally link it into a program. + # $show "echo timestamp > $libobj" + # $opt_dry_run || eval "echo timestamp > $libobj" || exit $? + exit $EXIT_SUCCESS + fi + + if test -n "$pic_flag" || test "$pic_mode" != default; then + # Only do commands if we really have different PIC objects. + reload_objs="$libobjs $reload_conv_objs" + output="$libobj" + func_execute_cmds "$reload_cmds" 'exit $?' + fi + + if test -n "$gentop"; then + func_show_eval '${RM}r "$gentop"' + fi + + exit $EXIT_SUCCESS + ;; + + prog) + case $host in + *cygwin*) func_stripname '' '.exe' "$output" + output=$func_stripname_result.exe;; + esac + test -n "$vinfo" && \ + func_warning "\`-version-info' is ignored for programs" + + test -n "$release" && \ + func_warning "\`-release' is ignored for programs" + + test "$preload" = yes \ + && test "$dlopen_support" = unknown \ + && test "$dlopen_self" = unknown \ + && test "$dlopen_self_static" = unknown && \ + func_warning "\`LT_INIT([dlopen])' not used. Assuming no dlopen support." + + case $host in + *-*-rhapsody* | *-*-darwin1.[012]) + # On Rhapsody replace the C library is the System framework + compile_deplibs=`$ECHO "X $compile_deplibs" | $Xsed -e 's/ -lc / System.ltframework /'` + finalize_deplibs=`$ECHO "X $finalize_deplibs" | $Xsed -e 's/ -lc / System.ltframework /'` + ;; + esac + + case $host in + *-*-darwin*) + # Don't allow lazy linking, it breaks C++ global constructors + # But is supposedly fixed on 10.4 or later (yay!). + if test "$tagname" = CXX ; then + case ${MACOSX_DEPLOYMENT_TARGET-10.0} in + 10.[0123]) + compile_command="$compile_command ${wl}-bind_at_load" + finalize_command="$finalize_command ${wl}-bind_at_load" + ;; + esac + fi + # Time to change all our "foo.ltframework" stuff back to "-framework foo" + compile_deplibs=`$ECHO "X $compile_deplibs" | $Xsed -e 's% \([^ $]*\).ltframework% -framework \1%g'` + finalize_deplibs=`$ECHO "X $finalize_deplibs" | $Xsed -e 's% \([^ $]*\).ltframework% -framework \1%g'` + ;; + esac + + + # move library search paths that coincide with paths to not yet + # installed libraries to the beginning of the library search list + new_libs= + for path in $notinst_path; do + case " $new_libs " in + *" -L$path/$objdir "*) ;; + *) + case " $compile_deplibs " in + *" -L$path/$objdir "*) + new_libs="$new_libs -L$path/$objdir" ;; + esac + ;; + esac + done + for deplib in $compile_deplibs; do + case $deplib in + -L*) + case " $new_libs " in + *" $deplib "*) ;; + *) new_libs="$new_libs $deplib" ;; + esac + ;; + *) new_libs="$new_libs $deplib" ;; + esac + done + compile_deplibs="$new_libs" + + + compile_command="$compile_command $compile_deplibs" + finalize_command="$finalize_command $finalize_deplibs" + + if test -n "$rpath$xrpath"; then + # If the user specified any rpath flags, then add them. + for libdir in $rpath $xrpath; do + # This is the magic to use -rpath. + case "$finalize_rpath " in + *" $libdir "*) ;; + *) finalize_rpath="$finalize_rpath $libdir" ;; + esac + done + fi + + # Now hardcode the library paths + rpath= + hardcode_libdirs= + for libdir in $compile_rpath $finalize_rpath; do + if test -n "$hardcode_libdir_flag_spec"; then + if test -n "$hardcode_libdir_separator"; then + if test -z "$hardcode_libdirs"; then + hardcode_libdirs="$libdir" + else + # Just accumulate the unique libdirs. + case $hardcode_libdir_separator$hardcode_libdirs$hardcode_libdir_separator in + *"$hardcode_libdir_separator$libdir$hardcode_libdir_separator"*) + ;; + *) + hardcode_libdirs="$hardcode_libdirs$hardcode_libdir_separator$libdir" + ;; + esac + fi + else + eval flag=\"$hardcode_libdir_flag_spec\" + rpath="$rpath $flag" + fi + elif test -n "$runpath_var"; then + case "$perm_rpath " in + *" $libdir "*) ;; + *) perm_rpath="$perm_rpath $libdir" ;; + esac + fi + case $host in + *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-os2* | *-cegcc*) + testbindir=`${ECHO} "$libdir" | ${SED} -e 's*/lib$*/bin*'` + case :$dllsearchpath: in + *":$libdir:"*) ;; + ::) dllsearchpath=$libdir;; + *) dllsearchpath="$dllsearchpath:$libdir";; + esac + case :$dllsearchpath: in + *":$testbindir:"*) ;; + ::) dllsearchpath=$testbindir;; + *) dllsearchpath="$dllsearchpath:$testbindir";; + esac + ;; + esac + done + # Substitute the hardcoded libdirs into the rpath. + if test -n "$hardcode_libdir_separator" && + test -n "$hardcode_libdirs"; then + libdir="$hardcode_libdirs" + eval rpath=\" $hardcode_libdir_flag_spec\" + fi + compile_rpath="$rpath" + + rpath= + hardcode_libdirs= + for libdir in $finalize_rpath; do + if test -n "$hardcode_libdir_flag_spec"; then + if test -n "$hardcode_libdir_separator"; then + if test -z "$hardcode_libdirs"; then + hardcode_libdirs="$libdir" + else + # Just accumulate the unique libdirs. + case $hardcode_libdir_separator$hardcode_libdirs$hardcode_libdir_separator in + *"$hardcode_libdir_separator$libdir$hardcode_libdir_separator"*) + ;; + *) + hardcode_libdirs="$hardcode_libdirs$hardcode_libdir_separator$libdir" + ;; + esac + fi + else + eval flag=\"$hardcode_libdir_flag_spec\" + rpath="$rpath $flag" + fi + elif test -n "$runpath_var"; then + case "$finalize_perm_rpath " in + *" $libdir "*) ;; + *) finalize_perm_rpath="$finalize_perm_rpath $libdir" ;; + esac + fi + done + # Substitute the hardcoded libdirs into the rpath. + if test -n "$hardcode_libdir_separator" && + test -n "$hardcode_libdirs"; then + libdir="$hardcode_libdirs" + eval rpath=\" $hardcode_libdir_flag_spec\" + fi + finalize_rpath="$rpath" + + if test -n "$libobjs" && test "$build_old_libs" = yes; then + # Transform all the library objects into standard objects. + compile_command=`$ECHO "X$compile_command" | $SP2NL | $Xsed -e "$lo2o" | $NL2SP` + finalize_command=`$ECHO "X$finalize_command" | $SP2NL | $Xsed -e "$lo2o" | $NL2SP` + fi + + func_generate_dlsyms "$outputname" "@PROGRAM@" "no" + + # template prelinking step + if test -n "$prelink_cmds"; then + func_execute_cmds "$prelink_cmds" 'exit $?' + fi + + wrappers_required=yes + case $host in + *cygwin* | *mingw* ) + if test "$build_libtool_libs" != yes; then + wrappers_required=no + fi + ;; + *cegcc) + # Disable wrappers for cegcc, we are cross compiling anyway. + wrappers_required=no + ;; + *) + if test "$need_relink" = no || test "$build_libtool_libs" != yes; then + wrappers_required=no + fi + ;; + esac + if test "$wrappers_required" = no; then + # Replace the output file specification. + compile_command=`$ECHO "X$compile_command" | $Xsed -e 's%@OUTPUT@%'"$output"'%g'` + link_command="$compile_command$compile_rpath" + + # We have no uninstalled library dependencies, so finalize right now. + exit_status=0 + func_show_eval "$link_command" 'exit_status=$?' + + # Delete the generated files. + if test -f "$output_objdir/${outputname}S.${objext}"; then + func_show_eval '$RM "$output_objdir/${outputname}S.${objext}"' + fi + + exit $exit_status + fi + + if test -n "$compile_shlibpath$finalize_shlibpath"; then + compile_command="$shlibpath_var=\"$compile_shlibpath$finalize_shlibpath\$$shlibpath_var\" $compile_command" + fi + if test -n "$finalize_shlibpath"; then + finalize_command="$shlibpath_var=\"$finalize_shlibpath\$$shlibpath_var\" $finalize_command" + fi + + compile_var= + finalize_var= + if test -n "$runpath_var"; then + if test -n "$perm_rpath"; then + # We should set the runpath_var. + rpath= + for dir in $perm_rpath; do + rpath="$rpath$dir:" + done + compile_var="$runpath_var=\"$rpath\$$runpath_var\" " + fi + if test -n "$finalize_perm_rpath"; then + # We should set the runpath_var. + rpath= + for dir in $finalize_perm_rpath; do + rpath="$rpath$dir:" + done + finalize_var="$runpath_var=\"$rpath\$$runpath_var\" " + fi + fi + + if test "$no_install" = yes; then + # We don't need to create a wrapper script. + link_command="$compile_var$compile_command$compile_rpath" + # Replace the output file specification. + link_command=`$ECHO "X$link_command" | $Xsed -e 's%@OUTPUT@%'"$output"'%g'` + # Delete the old output file. + $opt_dry_run || $RM $output + # Link the executable and exit + func_show_eval "$link_command" 'exit $?' + exit $EXIT_SUCCESS + fi + + if test "$hardcode_action" = relink; then + # Fast installation is not supported + link_command="$compile_var$compile_command$compile_rpath" + relink_command="$finalize_var$finalize_command$finalize_rpath" + + func_warning "this platform does not like uninstalled shared libraries" + func_warning "\`$output' will be relinked during installation" + else + if test "$fast_install" != no; then + link_command="$finalize_var$compile_command$finalize_rpath" + if test "$fast_install" = yes; then + relink_command=`$ECHO "X$compile_var$compile_command$compile_rpath" | $Xsed -e 's%@OUTPUT@%\$progdir/\$file%g'` + else + # fast_install is set to needless + relink_command= + fi + else + link_command="$compile_var$compile_command$compile_rpath" + relink_command="$finalize_var$finalize_command$finalize_rpath" + fi + fi + + # Replace the output file specification. + link_command=`$ECHO "X$link_command" | $Xsed -e 's%@OUTPUT@%'"$output_objdir/$outputname"'%g'` + + # Delete the old output files. + $opt_dry_run || $RM $output $output_objdir/$outputname $output_objdir/lt-$outputname + + func_show_eval "$link_command" 'exit $?' + + # Now create the wrapper script. + func_verbose "creating $output" + + # Quote the relink command for shipping. + if test -n "$relink_command"; then + # Preserve any variables that may affect compiler behavior + for var in $variables_saved_for_relink; do + if eval test -z \"\${$var+set}\"; then + relink_command="{ test -z \"\${$var+set}\" || $lt_unset $var || { $var=; export $var; }; }; $relink_command" + elif eval var_value=\$$var; test -z "$var_value"; then + relink_command="$var=; export $var; $relink_command" + else + func_quote_for_eval "$var_value" + relink_command="$var=$func_quote_for_eval_result; export $var; $relink_command" + fi + done + relink_command="(cd `pwd`; $relink_command)" + relink_command=`$ECHO "X$relink_command" | $Xsed -e "$sed_quote_subst"` + fi + + # Quote $ECHO for shipping. + if test "X$ECHO" = "X$SHELL $progpath --fallback-echo"; then + case $progpath in + [\\/]* | [A-Za-z]:[\\/]*) qecho="$SHELL $progpath --fallback-echo";; + *) qecho="$SHELL `pwd`/$progpath --fallback-echo";; + esac + qecho=`$ECHO "X$qecho" | $Xsed -e "$sed_quote_subst"` + else + qecho=`$ECHO "X$ECHO" | $Xsed -e "$sed_quote_subst"` + fi + + # Only actually do things if not in dry run mode. + $opt_dry_run || { + # win32 will think the script is a binary if it has + # a .exe suffix, so we strip it off here. + case $output in + *.exe) func_stripname '' '.exe' "$output" + output=$func_stripname_result ;; + esac + # test for cygwin because mv fails w/o .exe extensions + case $host in + *cygwin*) + exeext=.exe + func_stripname '' '.exe' "$outputname" + outputname=$func_stripname_result ;; + *) exeext= ;; + esac + case $host in + *cygwin* | *mingw* ) + func_dirname_and_basename "$output" "" "." + output_name=$func_basename_result + output_path=$func_dirname_result + cwrappersource="$output_path/$objdir/lt-$output_name.c" + cwrapper="$output_path/$output_name.exe" + $RM $cwrappersource $cwrapper + trap "$RM $cwrappersource $cwrapper; exit $EXIT_FAILURE" 1 2 15 + + func_emit_cwrapperexe_src > $cwrappersource + + # The wrapper executable is built using the $host compiler, + # because it contains $host paths and files. If cross- + # compiling, it, like the target executable, must be + # executed on the $host or under an emulation environment. + $opt_dry_run || { + $LTCC $LTCFLAGS -o $cwrapper $cwrappersource + $STRIP $cwrapper + } + + # Now, create the wrapper script for func_source use: + func_ltwrapper_scriptname $cwrapper + $RM $func_ltwrapper_scriptname_result + trap "$RM $func_ltwrapper_scriptname_result; exit $EXIT_FAILURE" 1 2 15 + $opt_dry_run || { + # note: this script will not be executed, so do not chmod. + if test "x$build" = "x$host" ; then + $cwrapper --lt-dump-script > $func_ltwrapper_scriptname_result + else + func_emit_wrapper no > $func_ltwrapper_scriptname_result + fi + } + ;; + * ) + $RM $output + trap "$RM $output; exit $EXIT_FAILURE" 1 2 15 + + func_emit_wrapper no > $output + chmod +x $output + ;; + esac + } + exit $EXIT_SUCCESS + ;; + esac + + # See if we need to build an old-fashioned archive. + for oldlib in $oldlibs; do + + if test "$build_libtool_libs" = convenience; then + oldobjs="$libobjs_save $symfileobj" + addlibs="$convenience" + build_libtool_libs=no + else + if test "$build_libtool_libs" = module; then + oldobjs="$libobjs_save" + build_libtool_libs=no + else + oldobjs="$old_deplibs $non_pic_objects" + if test "$preload" = yes && test -f "$symfileobj"; then + oldobjs="$oldobjs $symfileobj" + fi + fi + addlibs="$old_convenience" + fi + + if test -n "$addlibs"; then + gentop="$output_objdir/${outputname}x" + generated="$generated $gentop" + + func_extract_archives $gentop $addlibs + oldobjs="$oldobjs $func_extract_archives_result" + fi + + # Do each command in the archive commands. + if test -n "$old_archive_from_new_cmds" && test "$build_libtool_libs" = yes; then + cmds=$old_archive_from_new_cmds + else + + # Add any objects from preloaded convenience libraries + if test -n "$dlprefiles"; then + gentop="$output_objdir/${outputname}x" + generated="$generated $gentop" + + func_extract_archives $gentop $dlprefiles + oldobjs="$oldobjs $func_extract_archives_result" + fi + + # POSIX demands no paths to be encoded in archives. We have + # to avoid creating archives with duplicate basenames if we + # might have to extract them afterwards, e.g., when creating a + # static archive out of a convenience library, or when linking + # the entirety of a libtool archive into another (currently + # not supported by libtool). + if (for obj in $oldobjs + do + func_basename "$obj" + $ECHO "$func_basename_result" + done | sort | sort -uc >/dev/null 2>&1); then + : + else + $ECHO "copying selected object files to avoid basename conflicts..." + gentop="$output_objdir/${outputname}x" + generated="$generated $gentop" + func_mkdir_p "$gentop" + save_oldobjs=$oldobjs + oldobjs= + counter=1 + for obj in $save_oldobjs + do + func_basename "$obj" + objbase="$func_basename_result" + case " $oldobjs " in + " ") oldobjs=$obj ;; + *[\ /]"$objbase "*) + while :; do + # Make sure we don't pick an alternate name that also + # overlaps. + newobj=lt$counter-$objbase + func_arith $counter + 1 + counter=$func_arith_result + case " $oldobjs " in + *[\ /]"$newobj "*) ;; + *) if test ! -f "$gentop/$newobj"; then break; fi ;; + esac + done + func_show_eval "ln $obj $gentop/$newobj || cp $obj $gentop/$newobj" + oldobjs="$oldobjs $gentop/$newobj" + ;; + *) oldobjs="$oldobjs $obj" ;; + esac + done + fi + eval cmds=\"$old_archive_cmds\" + + func_len " $cmds" + len=$func_len_result + if test "$len" -lt "$max_cmd_len" || test "$max_cmd_len" -le -1; then + cmds=$old_archive_cmds + else + # the command line is too long to link in one step, link in parts + func_verbose "using piecewise archive linking..." + save_RANLIB=$RANLIB + RANLIB=: + objlist= + concat_cmds= + save_oldobjs=$oldobjs + oldobjs= + # Is there a better way of finding the last object in the list? + for obj in $save_oldobjs + do + last_oldobj=$obj + done + eval test_cmds=\"$old_archive_cmds\" + func_len " $test_cmds" + len0=$func_len_result + len=$len0 + for obj in $save_oldobjs + do + func_len " $obj" + func_arith $len + $func_len_result + len=$func_arith_result + func_append objlist " $obj" + if test "$len" -lt "$max_cmd_len"; then + : + else + # the above command should be used before it gets too long + oldobjs=$objlist + if test "$obj" = "$last_oldobj" ; then + RANLIB=$save_RANLIB + fi + test -z "$concat_cmds" || concat_cmds=$concat_cmds~ + eval concat_cmds=\"\${concat_cmds}$old_archive_cmds\" + objlist= + len=$len0 + fi + done + RANLIB=$save_RANLIB + oldobjs=$objlist + if test "X$oldobjs" = "X" ; then + eval cmds=\"\$concat_cmds\" + else + eval cmds=\"\$concat_cmds~\$old_archive_cmds\" + fi + fi + fi + func_execute_cmds "$cmds" 'exit $?' + done + + test -n "$generated" && \ + func_show_eval "${RM}r$generated" + + # Now create the libtool archive. + case $output in + *.la) + old_library= + test "$build_old_libs" = yes && old_library="$libname.$libext" + func_verbose "creating $output" + + # Preserve any variables that may affect compiler behavior + for var in $variables_saved_for_relink; do + if eval test -z \"\${$var+set}\"; then + relink_command="{ test -z \"\${$var+set}\" || $lt_unset $var || { $var=; export $var; }; }; $relink_command" + elif eval var_value=\$$var; test -z "$var_value"; then + relink_command="$var=; export $var; $relink_command" + else + func_quote_for_eval "$var_value" + relink_command="$var=$func_quote_for_eval_result; export $var; $relink_command" + fi + done + # Quote the link command for shipping. + relink_command="(cd `pwd`; $SHELL $progpath $preserve_args --mode=relink $libtool_args @inst_prefix_dir@)" + relink_command=`$ECHO "X$relink_command" | $Xsed -e "$sed_quote_subst"` + if test "$hardcode_automatic" = yes ; then + relink_command= + fi + + # Only create the output if not a dry run. + $opt_dry_run || { + for installed in no yes; do + if test "$installed" = yes; then + if test -z "$install_libdir"; then + break + fi + output="$output_objdir/$outputname"i + # Replace all uninstalled libtool libraries with the installed ones + newdependency_libs= + for deplib in $dependency_libs; do + case $deplib in + *.la) + func_basename "$deplib" + name="$func_basename_result" + eval libdir=`${SED} -n -e 's/^libdir=\(.*\)$/\1/p' $deplib` + test -z "$libdir" && \ + func_fatal_error "\`$deplib' is not a valid libtool archive" + newdependency_libs="$newdependency_libs $libdir/$name" + ;; + *) newdependency_libs="$newdependency_libs $deplib" ;; + esac + done + dependency_libs="$newdependency_libs" + newdlfiles= + + for lib in $dlfiles; do + case $lib in + *.la) + func_basename "$lib" + name="$func_basename_result" + eval libdir=`${SED} -n -e 's/^libdir=\(.*\)$/\1/p' $lib` + test -z "$libdir" && \ + func_fatal_error "\`$lib' is not a valid libtool archive" + newdlfiles="$newdlfiles $libdir/$name" + ;; + *) newdlfiles="$newdlfiles $lib" ;; + esac + done + dlfiles="$newdlfiles" + newdlprefiles= + for lib in $dlprefiles; do + case $lib in + *.la) + # Only pass preopened files to the pseudo-archive (for + # eventual linking with the app. that links it) if we + # didn't already link the preopened objects directly into + # the library: + func_basename "$lib" + name="$func_basename_result" + eval libdir=`${SED} -n -e 's/^libdir=\(.*\)$/\1/p' $lib` + test -z "$libdir" && \ + func_fatal_error "\`$lib' is not a valid libtool archive" + newdlprefiles="$newdlprefiles $libdir/$name" + ;; + esac + done + dlprefiles="$newdlprefiles" + else + newdlfiles= + for lib in $dlfiles; do + case $lib in + [\\/]* | [A-Za-z]:[\\/]*) abs="$lib" ;; + *) abs=`pwd`"/$lib" ;; + esac + newdlfiles="$newdlfiles $abs" + done + dlfiles="$newdlfiles" + newdlprefiles= + for lib in $dlprefiles; do + case $lib in + [\\/]* | [A-Za-z]:[\\/]*) abs="$lib" ;; + *) abs=`pwd`"/$lib" ;; + esac + newdlprefiles="$newdlprefiles $abs" + done + dlprefiles="$newdlprefiles" + fi + $RM $output + # place dlname in correct position for cygwin + tdlname=$dlname + case $host,$output,$installed,$module,$dlname in + *cygwin*,*lai,yes,no,*.dll | *mingw*,*lai,yes,no,*.dll | *cegcc*,*lai,yes,no,*.dll) tdlname=../bin/$dlname ;; + esac + $ECHO > $output "\ +# $outputname - a libtool library file +# Generated by $PROGRAM (GNU $PACKAGE$TIMESTAMP) $VERSION +# +# Please DO NOT delete this file! +# It is necessary for linking the library. + +# The name that we can dlopen(3). +dlname='$tdlname' + +# Names of this library. +library_names='$library_names' + +# The name of the static archive. +old_library='$old_library' + +# Linker flags that can not go in dependency_libs. +inherited_linker_flags='$new_inherited_linker_flags' + +# Libraries that this one depends upon. +dependency_libs='$dependency_libs' + +# Names of additional weak libraries provided by this library +weak_library_names='$weak_libs' + +# Version information for $libname. +current=$current +age=$age +revision=$revision + +# Is this an already installed library? +installed=$installed + +# Should we warn about portability when linking against -modules? +shouldnotlink=$module + +# Files to dlopen/dlpreopen +dlopen='$dlfiles' +dlpreopen='$dlprefiles' + +# Directory that this library needs to be installed in: +libdir='$install_libdir'" + if test "$installed" = no && test "$need_relink" = yes; then + $ECHO >> $output "\ +relink_command=\"$relink_command\"" + fi + done + } + + # Do a symbolic link so that the libtool archive can be found in + # LD_LIBRARY_PATH before the program is installed. + func_show_eval '( cd "$output_objdir" && $RM "$outputname" && $LN_S "../$outputname" "$outputname" )' 'exit $?' + ;; + esac + exit $EXIT_SUCCESS +} + +{ test "$mode" = link || test "$mode" = relink; } && + func_mode_link ${1+"$@"} + + +# func_mode_uninstall arg... +func_mode_uninstall () +{ + $opt_debug + RM="$nonopt" + files= + rmforce= + exit_status=0 + + # This variable tells wrapper scripts just to set variables rather + # than running their programs. + libtool_install_magic="$magic" + + for arg + do + case $arg in + -f) RM="$RM $arg"; rmforce=yes ;; + -*) RM="$RM $arg" ;; + *) files="$files $arg" ;; + esac + done + + test -z "$RM" && \ + func_fatal_help "you must specify an RM program" + + rmdirs= + + origobjdir="$objdir" + for file in $files; do + func_dirname "$file" "" "." + dir="$func_dirname_result" + if test "X$dir" = X.; then + objdir="$origobjdir" + else + objdir="$dir/$origobjdir" + fi + func_basename "$file" + name="$func_basename_result" + test "$mode" = uninstall && objdir="$dir" + + # Remember objdir for removal later, being careful to avoid duplicates + if test "$mode" = clean; then + case " $rmdirs " in + *" $objdir "*) ;; + *) rmdirs="$rmdirs $objdir" ;; + esac + fi + + # Don't error if the file doesn't exist and rm -f was used. + if { test -L "$file"; } >/dev/null 2>&1 || + { test -h "$file"; } >/dev/null 2>&1 || + test -f "$file"; then + : + elif test -d "$file"; then + exit_status=1 + continue + elif test "$rmforce" = yes; then + continue + fi + + rmfiles="$file" + + case $name in + *.la) + # Possibly a libtool archive, so verify it. + if func_lalib_p "$file"; then + func_source $dir/$name + + # Delete the libtool libraries and symlinks. + for n in $library_names; do + rmfiles="$rmfiles $objdir/$n" + done + test -n "$old_library" && rmfiles="$rmfiles $objdir/$old_library" + + case "$mode" in + clean) + case " $library_names " in + # " " in the beginning catches empty $dlname + *" $dlname "*) ;; + *) rmfiles="$rmfiles $objdir/$dlname" ;; + esac + test -n "$libdir" && rmfiles="$rmfiles $objdir/$name $objdir/${name}i" + ;; + uninstall) + if test -n "$library_names"; then + # Do each command in the postuninstall commands. + func_execute_cmds "$postuninstall_cmds" 'test "$rmforce" = yes || exit_status=1' + fi + + if test -n "$old_library"; then + # Do each command in the old_postuninstall commands. + func_execute_cmds "$old_postuninstall_cmds" 'test "$rmforce" = yes || exit_status=1' + fi + # FIXME: should reinstall the best remaining shared library. + ;; + esac + fi + ;; + + *.lo) + # Possibly a libtool object, so verify it. + if func_lalib_p "$file"; then + + # Read the .lo file + func_source $dir/$name + + # Add PIC object to the list of files to remove. + if test -n "$pic_object" && + test "$pic_object" != none; then + rmfiles="$rmfiles $dir/$pic_object" + fi + + # Add non-PIC object to the list of files to remove. + if test -n "$non_pic_object" && + test "$non_pic_object" != none; then + rmfiles="$rmfiles $dir/$non_pic_object" + fi + fi + ;; + + *) + if test "$mode" = clean ; then + noexename=$name + case $file in + *.exe) + func_stripname '' '.exe' "$file" + file=$func_stripname_result + func_stripname '' '.exe' "$name" + noexename=$func_stripname_result + # $file with .exe has already been added to rmfiles, + # add $file without .exe + rmfiles="$rmfiles $file" + ;; + esac + # Do a test to see if this is a libtool program. + if func_ltwrapper_p "$file"; then + if func_ltwrapper_executable_p "$file"; then + func_ltwrapper_scriptname "$file" + relink_command= + func_source $func_ltwrapper_scriptname_result + rmfiles="$rmfiles $func_ltwrapper_scriptname_result" + else + relink_command= + func_source $dir/$noexename + fi + + # note $name still contains .exe if it was in $file originally + # as does the version of $file that was added into $rmfiles + rmfiles="$rmfiles $objdir/$name $objdir/${name}S.${objext}" + if test "$fast_install" = yes && test -n "$relink_command"; then + rmfiles="$rmfiles $objdir/lt-$name" + fi + if test "X$noexename" != "X$name" ; then + rmfiles="$rmfiles $objdir/lt-${noexename}.c" + fi + fi + fi + ;; + esac + func_show_eval "$RM $rmfiles" 'exit_status=1' + done + objdir="$origobjdir" + + # Try to remove the ${objdir}s in the directories where we deleted files + for dir in $rmdirs; do + if test -d "$dir"; then + func_show_eval "rmdir $dir >/dev/null 2>&1" + fi + done + + exit $exit_status +} + +{ test "$mode" = uninstall || test "$mode" = clean; } && + func_mode_uninstall ${1+"$@"} + +test -z "$mode" && { + help="$generic_help" + func_fatal_help "you must specify a MODE" +} + +test -z "$exec_cmd" && \ + func_fatal_help "invalid operation mode \`$mode'" + +if test -n "$exec_cmd"; then + eval exec "$exec_cmd" + exit $EXIT_FAILURE +fi + +exit $exit_status + + +# The TAGs below are defined such that we never get into a situation +# in which we disable both kinds of libraries. Given conflicting +# choices, we go for a static library, that is the most portable, +# since we can't tell whether shared libraries were disabled because +# the user asked for that or because the platform doesn't support +# them. This is particularly important on AIX, because we don't +# support having both static and shared libraries enabled at the same +# time on that platform, so we default to a shared-only configuration. +# If a disable-shared tag is given, we'll fallback to a static-only +# configuration. But we'll never go from static-only to shared-only. + +# ### BEGIN LIBTOOL TAG CONFIG: disable-shared +build_libtool_libs=no +build_old_libs=yes +# ### END LIBTOOL TAG CONFIG: disable-shared + +# ### BEGIN LIBTOOL TAG CONFIG: disable-static +build_old_libs=`case $build_libtool_libs in yes) echo no;; *) echo yes;; esac` +# ### END LIBTOOL TAG CONFIG: disable-static + +# Local Variables: +# mode:shell-script +# sh-indentation:2 +# End: +# vi:sw=2 + diff --git a/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/missing b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/missing new file mode 100755 index 0000000000..28055d2ae6 --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/missing @@ -0,0 +1,376 @@ +#! /bin/sh +# Common stub for a few missing GNU programs while installing. + +scriptversion=2009-04-28.21; # UTC + +# Copyright (C) 1996, 1997, 1999, 2000, 2002, 2003, 2004, 2005, 2006, +# 2008, 2009 Free Software Foundation, Inc. +# Originally by Fran,cois Pinard , 1996. + +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2, or (at your option) +# any later version. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. + +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program that contains a +# configuration script generated by Autoconf, you may include it under +# the same distribution terms that you use for the rest of that program. + +if test $# -eq 0; then + echo 1>&2 "Try \`$0 --help' for more information" + exit 1 +fi + +run=: +sed_output='s/.* --output[ =]\([^ ]*\).*/\1/p' +sed_minuso='s/.* -o \([^ ]*\).*/\1/p' + +# In the cases where this matters, `missing' is being run in the +# srcdir already. +if test -f configure.ac; then + configure_ac=configure.ac +else + configure_ac=configure.in +fi + +msg="missing on your system" + +case $1 in +--run) + # Try to run requested program, and just exit if it succeeds. + run= + shift + "$@" && exit 0 + # Exit code 63 means version mismatch. This often happens + # when the user try to use an ancient version of a tool on + # a file that requires a minimum version. In this case we + # we should proceed has if the program had been absent, or + # if --run hadn't been passed. + if test $? = 63; then + run=: + msg="probably too old" + fi + ;; + + -h|--h|--he|--hel|--help) + echo "\ +$0 [OPTION]... PROGRAM [ARGUMENT]... + +Handle \`PROGRAM [ARGUMENT]...' for when PROGRAM is missing, or return an +error status if there is no known handling for PROGRAM. + +Options: + -h, --help display this help and exit + -v, --version output version information and exit + --run try to run the given command, and emulate it if it fails + +Supported PROGRAM values: + aclocal touch file \`aclocal.m4' + autoconf touch file \`configure' + autoheader touch file \`config.h.in' + autom4te touch the output file, or create a stub one + automake touch all \`Makefile.in' files + bison create \`y.tab.[ch]', if possible, from existing .[ch] + flex create \`lex.yy.c', if possible, from existing .c + help2man touch the output file + lex create \`lex.yy.c', if possible, from existing .c + makeinfo touch the output file + tar try tar, gnutar, gtar, then tar without non-portable flags + yacc create \`y.tab.[ch]', if possible, from existing .[ch] + +Version suffixes to PROGRAM as well as the prefixes \`gnu-', \`gnu', and +\`g' are ignored when checking the name. + +Send bug reports to ." + exit $? + ;; + + -v|--v|--ve|--ver|--vers|--versi|--versio|--version) + echo "missing $scriptversion (GNU Automake)" + exit $? + ;; + + -*) + echo 1>&2 "$0: Unknown \`$1' option" + echo 1>&2 "Try \`$0 --help' for more information" + exit 1 + ;; + +esac + +# normalize program name to check for. +program=`echo "$1" | sed ' + s/^gnu-//; t + s/^gnu//; t + s/^g//; t'` + +# Now exit if we have it, but it failed. Also exit now if we +# don't have it and --version was passed (most likely to detect +# the program). This is about non-GNU programs, so use $1 not +# $program. +case $1 in + lex*|yacc*) + # Not GNU programs, they don't have --version. + ;; + + tar*) + if test -n "$run"; then + echo 1>&2 "ERROR: \`tar' requires --run" + exit 1 + elif test "x$2" = "x--version" || test "x$2" = "x--help"; then + exit 1 + fi + ;; + + *) + if test -z "$run" && ($1 --version) > /dev/null 2>&1; then + # We have it, but it failed. + exit 1 + elif test "x$2" = "x--version" || test "x$2" = "x--help"; then + # Could not run --version or --help. This is probably someone + # running `$TOOL --version' or `$TOOL --help' to check whether + # $TOOL exists and not knowing $TOOL uses missing. + exit 1 + fi + ;; +esac + +# If it does not exist, or fails to run (possibly an outdated version), +# try to emulate it. +case $program in + aclocal*) + echo 1>&2 "\ +WARNING: \`$1' is $msg. You should only need it if + you modified \`acinclude.m4' or \`${configure_ac}'. You might want + to install the \`Automake' and \`Perl' packages. Grab them from + any GNU archive site." + touch aclocal.m4 + ;; + + autoconf*) + echo 1>&2 "\ +WARNING: \`$1' is $msg. You should only need it if + you modified \`${configure_ac}'. You might want to install the + \`Autoconf' and \`GNU m4' packages. Grab them from any GNU + archive site." + touch configure + ;; + + autoheader*) + echo 1>&2 "\ +WARNING: \`$1' is $msg. You should only need it if + you modified \`acconfig.h' or \`${configure_ac}'. You might want + to install the \`Autoconf' and \`GNU m4' packages. Grab them + from any GNU archive site." + files=`sed -n 's/^[ ]*A[CM]_CONFIG_HEADER(\([^)]*\)).*/\1/p' ${configure_ac}` + test -z "$files" && files="config.h" + touch_files= + for f in $files; do + case $f in + *:*) touch_files="$touch_files "`echo "$f" | + sed -e 's/^[^:]*://' -e 's/:.*//'`;; + *) touch_files="$touch_files $f.in";; + esac + done + touch $touch_files + ;; + + automake*) + echo 1>&2 "\ +WARNING: \`$1' is $msg. You should only need it if + you modified \`Makefile.am', \`acinclude.m4' or \`${configure_ac}'. + You might want to install the \`Automake' and \`Perl' packages. + Grab them from any GNU archive site." + find . -type f -name Makefile.am -print | + sed 's/\.am$/.in/' | + while read f; do touch "$f"; done + ;; + + autom4te*) + echo 1>&2 "\ +WARNING: \`$1' is needed, but is $msg. + You might have modified some files without having the + proper tools for further handling them. + You can get \`$1' as part of \`Autoconf' from any GNU + archive site." + + file=`echo "$*" | sed -n "$sed_output"` + test -z "$file" && file=`echo "$*" | sed -n "$sed_minuso"` + if test -f "$file"; then + touch $file + else + test -z "$file" || exec >$file + echo "#! /bin/sh" + echo "# Created by GNU Automake missing as a replacement of" + echo "# $ $@" + echo "exit 0" + chmod +x $file + exit 1 + fi + ;; + + bison*|yacc*) + echo 1>&2 "\ +WARNING: \`$1' $msg. You should only need it if + you modified a \`.y' file. You may need the \`Bison' package + in order for those modifications to take effect. You can get + \`Bison' from any GNU archive site." + rm -f y.tab.c y.tab.h + if test $# -ne 1; then + eval LASTARG="\${$#}" + case $LASTARG in + *.y) + SRCFILE=`echo "$LASTARG" | sed 's/y$/c/'` + if test -f "$SRCFILE"; then + cp "$SRCFILE" y.tab.c + fi + SRCFILE=`echo "$LASTARG" | sed 's/y$/h/'` + if test -f "$SRCFILE"; then + cp "$SRCFILE" y.tab.h + fi + ;; + esac + fi + if test ! -f y.tab.h; then + echo >y.tab.h + fi + if test ! -f y.tab.c; then + echo 'main() { return 0; }' >y.tab.c + fi + ;; + + lex*|flex*) + echo 1>&2 "\ +WARNING: \`$1' is $msg. You should only need it if + you modified a \`.l' file. You may need the \`Flex' package + in order for those modifications to take effect. You can get + \`Flex' from any GNU archive site." + rm -f lex.yy.c + if test $# -ne 1; then + eval LASTARG="\${$#}" + case $LASTARG in + *.l) + SRCFILE=`echo "$LASTARG" | sed 's/l$/c/'` + if test -f "$SRCFILE"; then + cp "$SRCFILE" lex.yy.c + fi + ;; + esac + fi + if test ! -f lex.yy.c; then + echo 'main() { return 0; }' >lex.yy.c + fi + ;; + + help2man*) + echo 1>&2 "\ +WARNING: \`$1' is $msg. You should only need it if + you modified a dependency of a manual page. You may need the + \`Help2man' package in order for those modifications to take + effect. You can get \`Help2man' from any GNU archive site." + + file=`echo "$*" | sed -n "$sed_output"` + test -z "$file" && file=`echo "$*" | sed -n "$sed_minuso"` + if test -f "$file"; then + touch $file + else + test -z "$file" || exec >$file + echo ".ab help2man is required to generate this page" + exit $? + fi + ;; + + makeinfo*) + echo 1>&2 "\ +WARNING: \`$1' is $msg. You should only need it if + you modified a \`.texi' or \`.texinfo' file, or any other file + indirectly affecting the aspect of the manual. The spurious + call might also be the consequence of using a buggy \`make' (AIX, + DU, IRIX). You might want to install the \`Texinfo' package or + the \`GNU make' package. Grab either from any GNU archive site." + # The file to touch is that specified with -o ... + file=`echo "$*" | sed -n "$sed_output"` + test -z "$file" && file=`echo "$*" | sed -n "$sed_minuso"` + if test -z "$file"; then + # ... or it is the one specified with @setfilename ... + infile=`echo "$*" | sed 's/.* \([^ ]*\) *$/\1/'` + file=`sed -n ' + /^@setfilename/{ + s/.* \([^ ]*\) *$/\1/ + p + q + }' $infile` + # ... or it is derived from the source name (dir/f.texi becomes f.info) + test -z "$file" && file=`echo "$infile" | sed 's,.*/,,;s,.[^.]*$,,'`.info + fi + # If the file does not exist, the user really needs makeinfo; + # let's fail without touching anything. + test -f $file || exit 1 + touch $file + ;; + + tar*) + shift + + # We have already tried tar in the generic part. + # Look for gnutar/gtar before invocation to avoid ugly error + # messages. + if (gnutar --version > /dev/null 2>&1); then + gnutar "$@" && exit 0 + fi + if (gtar --version > /dev/null 2>&1); then + gtar "$@" && exit 0 + fi + firstarg="$1" + if shift; then + case $firstarg in + *o*) + firstarg=`echo "$firstarg" | sed s/o//` + tar "$firstarg" "$@" && exit 0 + ;; + esac + case $firstarg in + *h*) + firstarg=`echo "$firstarg" | sed s/h//` + tar "$firstarg" "$@" && exit 0 + ;; + esac + fi + + echo 1>&2 "\ +WARNING: I can't seem to be able to run \`tar' with the given arguments. + You may want to install GNU tar or Free paxutils, or check the + command line arguments." + exit 1 + ;; + + *) + echo 1>&2 "\ +WARNING: \`$1' is needed, and is $msg. + You might have modified some files without having the + proper tools for further handling them. Check the \`README' file, + it often tells you about the needed prerequisites for installing + this package. You may also peek at any GNU archive site, in case + some other package would contain this missing \`$1' program." + exit 1 + ;; +esac + +exit 0 + +# Local variables: +# eval: (add-hook 'write-file-hooks 'time-stamp) +# time-stamp-start: "scriptversion=" +# time-stamp-format: "%:y-%02m-%02d.%02H" +# time-stamp-time-zone: "UTC" +# time-stamp-end: "; # UTC" +# End: diff --git a/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/ylwrap b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/ylwrap new file mode 100755 index 0000000000..84d563405e --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/.autostuff/scripts/ylwrap @@ -0,0 +1,222 @@ +#! /bin/sh +# ylwrap - wrapper for lex/yacc invocations. + +scriptversion=2009-04-28.21; # UTC + +# Copyright (C) 1996, 1997, 1998, 1999, 2001, 2002, 2003, 2004, 2005, +# 2007, 2009 Free Software Foundation, Inc. +# +# Written by Tom Tromey . +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2, or (at your option) +# any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program that contains a +# configuration script generated by Autoconf, you may include it under +# the same distribution terms that you use for the rest of that program. + +# This file is maintained in Automake, please report +# bugs to or send patches to +# . + +case "$1" in + '') + echo "$0: No files given. Try \`$0 --help' for more information." 1>&2 + exit 1 + ;; + --basedir) + basedir=$2 + shift 2 + ;; + -h|--h*) + cat <<\EOF +Usage: ylwrap [--help|--version] INPUT [OUTPUT DESIRED]... -- PROGRAM [ARGS]... + +Wrapper for lex/yacc invocations, renaming files as desired. + + INPUT is the input file + OUTPUT is one file PROG generates + DESIRED is the file we actually want instead of OUTPUT + PROGRAM is program to run + ARGS are passed to PROG + +Any number of OUTPUT,DESIRED pairs may be used. + +Report bugs to . +EOF + exit $? + ;; + -v|--v*) + echo "ylwrap $scriptversion" + exit $? + ;; +esac + + +# The input. +input="$1" +shift +case "$input" in + [\\/]* | ?:[\\/]*) + # Absolute path; do nothing. + ;; + *) + # Relative path. Make it absolute. + input="`pwd`/$input" + ;; +esac + +pairlist= +while test "$#" -ne 0; do + if test "$1" = "--"; then + shift + break + fi + pairlist="$pairlist $1" + shift +done + +# The program to run. +prog="$1" +shift +# Make any relative path in $prog absolute. +case "$prog" in + [\\/]* | ?:[\\/]*) ;; + *[\\/]*) prog="`pwd`/$prog" ;; +esac + +# FIXME: add hostname here for parallel makes that run commands on +# other machines. But that might take us over the 14-char limit. +dirname=ylwrap$$ +trap "cd '`pwd`'; rm -rf $dirname > /dev/null 2>&1" 1 2 3 15 +mkdir $dirname || exit 1 + +cd $dirname + +case $# in + 0) "$prog" "$input" ;; + *) "$prog" "$@" "$input" ;; +esac +ret=$? + +if test $ret -eq 0; then + set X $pairlist + shift + first=yes + # Since DOS filename conventions don't allow two dots, + # the DOS version of Bison writes out y_tab.c instead of y.tab.c + # and y_tab.h instead of y.tab.h. Test to see if this is the case. + y_tab_nodot="no" + if test -f y_tab.c || test -f y_tab.h; then + y_tab_nodot="yes" + fi + + # The directory holding the input. + input_dir=`echo "$input" | sed -e 's,\([\\/]\)[^\\/]*$,\1,'` + # Quote $INPUT_DIR so we can use it in a regexp. + # FIXME: really we should care about more than `.' and `\'. + input_rx=`echo "$input_dir" | sed 's,\\\\,\\\\\\\\,g;s,\\.,\\\\.,g'` + + while test "$#" -ne 0; do + from="$1" + # Handle y_tab.c and y_tab.h output by DOS + if test $y_tab_nodot = "yes"; then + if test $from = "y.tab.c"; then + from="y_tab.c" + else + if test $from = "y.tab.h"; then + from="y_tab.h" + fi + fi + fi + if test -f "$from"; then + # If $2 is an absolute path name, then just use that, + # otherwise prepend `../'. + case "$2" in + [\\/]* | ?:[\\/]*) target="$2";; + *) target="../$2";; + esac + + # We do not want to overwrite a header file if it hasn't + # changed. This avoid useless recompilations. However the + # parser itself (the first file) should always be updated, + # because it is the destination of the .y.c rule in the + # Makefile. Divert the output of all other files to a temporary + # file so we can compare them to existing versions. + if test $first = no; then + realtarget="$target" + target="tmp-`echo $target | sed s/.*[\\/]//g`" + fi + # Edit out `#line' or `#' directives. + # + # We don't want the resulting debug information to point at + # an absolute srcdir; it is better for it to just mention the + # .y file with no path. + # + # We want to use the real output file name, not yy.lex.c for + # instance. + # + # We want the include guards to be adjusted too. + FROM=`echo "$from" | sed \ + -e 'y/abcdefghijklmnopqrstuvwxyz/ABCDEFGHIJKLMNOPQRSTUVWXYZ/'\ + -e 's/[^ABCDEFGHIJKLMNOPQRSTUVWXYZ]/_/g'` + TARGET=`echo "$2" | sed \ + -e 'y/abcdefghijklmnopqrstuvwxyz/ABCDEFGHIJKLMNOPQRSTUVWXYZ/'\ + -e 's/[^ABCDEFGHIJKLMNOPQRSTUVWXYZ]/_/g'` + + sed -e "/^#/!b" -e "s,$input_rx,," -e "s,$from,$2," \ + -e "s,$FROM,$TARGET," "$from" >"$target" || ret=$? + + # Check whether header files must be updated. + if test $first = no; then + if test -f "$realtarget" && cmp -s "$realtarget" "$target"; then + echo "$2" is unchanged + rm -f "$target" + else + echo updating "$2" + mv -f "$target" "$realtarget" + fi + fi + else + # A missing file is only an error for the first file. This + # is a blatant hack to let us support using "yacc -d". If -d + # is not specified, we don't want an error when the header + # file is "missing". + if test $first = yes; then + ret=1 + fi + fi + shift + shift + first=no + done +else + ret=$? +fi + +# Remove the directory. +cd .. +rm -rf $dirname + +exit $ret + +# Local Variables: +# mode: shell-script +# sh-indentation: 2 +# eval: (add-hook 'write-file-hooks 'time-stamp) +# time-stamp-start: "scriptversion=" +# time-stamp-format: "%:y-%02m-%02d.%02H" +# time-stamp-time-zone: "UTC" +# time-stamp-end: "; # UTC" +# End: diff --git a/misc/tools/kconfig-frontends/scripts/Makefile.am b/misc/tools/kconfig-frontends/scripts/Makefile.am new file mode 100644 index 0000000000..2df640c4c4 --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/Makefile.am @@ -0,0 +1 @@ +EXTRA_DIST = ksync.sh ksync.list version.sh diff --git a/misc/tools/kconfig-frontends/scripts/Makefile.in b/misc/tools/kconfig-frontends/scripts/Makefile.in new file mode 100644 index 0000000000..f27aae48f0 --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/Makefile.in @@ -0,0 +1,403 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +subdir = scripts +DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +SOURCES = +DIST_SOURCES = +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +EXTRA_DIST = ksync.sh ksync.list version.sh +all: all-am + +.SUFFIXES: +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign scripts/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign scripts/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs +tags: TAGS +TAGS: + +ctags: CTAGS +CTAGS: + + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-am +all-am: Makefile +installdirs: +install: install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-am + +clean-am: clean-generic clean-libtool mostlyclean-am + +distclean: distclean-am + -rm -f Makefile +distclean-am: clean-am distclean-generic + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-generic mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: + +.MAKE: install-am install-strip + +.PHONY: all all-am check check-am clean clean-generic clean-libtool \ + distclean distclean-generic distclean-libtool distdir dvi \ + dvi-am html html-am info info-am install install-am \ + install-data install-data-am install-dvi install-dvi-am \ + install-exec install-exec-am install-html install-html-am \ + install-info install-info-am install-man install-pdf \ + install-pdf-am install-ps install-ps-am install-strip \ + installcheck installcheck-am installdirs maintainer-clean \ + maintainer-clean-generic mostlyclean mostlyclean-generic \ + mostlyclean-libtool pdf pdf-am ps ps-am uninstall uninstall-am + + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/scripts/ksync.list b/misc/tools/kconfig-frontends/scripts/ksync.list new file mode 100644 index 0000000000..9766b7a050 --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/ksync.list @@ -0,0 +1,35 @@ +scripts/kconfig/conf.c --> frontends/conf/conf.c +scripts/kconfig/gconf.c --> frontends/gconf/gconf.c +scripts/kconfig/gconf.glade --> frontends/gconf/gconf.glade +scripts/kconfig/mconf.c --> frontends/mconf/mconf.c +scripts/kconfig/nconf.c --> frontends/nconf/nconf.c +scripts/kconfig/nconf.gui.c --> frontends/nconf/nconf.gui.c +scripts/kconfig/nconf.h --> frontends/nconf/nconf.h +scripts/kconfig/qconf.cc --> frontends/qconf/qconf.cc +scripts/kconfig/qconf.h --> frontends/qconf/qconf.h +scripts/kconfig/images.c --> libs/images/images.c_orig +scripts/kconfig/lxdialog/BIG.FAT.WARNING --> libs/lxdialog/BIG.FAT.WARNING +scripts/kconfig/lxdialog/checklist.c --> libs/lxdialog/checklist.c +scripts/kconfig/lxdialog/dialog.h --> libs/lxdialog/dialog.h +scripts/kconfig/lxdialog/inputbox.c --> libs/lxdialog/inputbox.c +scripts/kconfig/lxdialog/menubox.c --> libs/lxdialog/menubox.c +scripts/kconfig/lxdialog/textbox.c --> libs/lxdialog/textbox.c +scripts/kconfig/lxdialog/util.c --> libs/lxdialog/util.c +scripts/kconfig/lxdialog/yesno.c --> libs/lxdialog/yesno.c +scripts/kconfig/confdata.c --> libs/parser/confdata.c +scripts/kconfig/expr.c --> libs/parser/expr.c +scripts/kconfig/expr.h --> libs/parser/expr.h +scripts/kconfig/zconf.gperf --> libs/parser/hconf.gperf +scripts/kconfig/zconf.l --> libs/parser/lconf.l +scripts/kconfig/lkc.h --> libs/parser/lkc.h +scripts/kconfig/lkc_proto.h --> libs/parser/lkc_proto.h +scripts/kconfig/menu.c --> libs/parser/menu.c +scripts/kconfig/symbol.c --> libs/parser/symbol.c +scripts/kconfig/util.c --> libs/parser/util.c +scripts/kconfig/zconf.y --> libs/parser/yconf.y +scripts/config --> utils/tweak.in +scripts/diffconfig --> utils/diff +scripts/kconfig/merge_config.sh --> utils/merge +scripts/kconfig/kxgettext.c --> utils/gettext.c +Documentation/kbuild/kconfig-language.txt --> docs/kconfig-language.txt +Documentation/kbuild/kconfig.txt --> docs/kconfig.txt diff --git a/misc/tools/kconfig-frontends/scripts/ksync.sh b/misc/tools/kconfig-frontends/scripts/ksync.sh new file mode 100755 index 0000000000..97fb3fe4df --- /dev/null +++ b/misc/tools/kconfig-frontends/scripts/ksync.sh @@ -0,0 +1,61 @@ +#!/bin/sh + +my_name="${0##*/}" + +# If an argument is given, it's the location +# of the Linux kernel source tree +k_dir="${1}" +if [ ! \( -n "${k_dir}" -a -d "${k_dir}/kernel" \) ]; then + if [ -n "${k_dir}" ]; then + printf "%s: \`%s': not a Linux kernel source tree\n" \ + "${my_name}" "${k_dir}" + else + printf "Usage: %s /path/to/kernel/dir\n" "${my_name}" + fi + exit 1 +fi + +# Save current version +k_cset_old=$( head -n 1 .version |awk '{ print $(2); }' ) + +# Get the kernel version +eval $( head -n 5 "${k_dir}/Makefile" \ + |sed -r -e 's/^/K_/; s/"//g; s/ = ?/="/; s/$/"/;' \ + ) +k_cset="$( cd "${k_dir}"; \ + git log -n 1 --pretty='format:%H' \ + )" +printf "Found Linux kernel %d.%d.%d%s '%s' (%7.7s)\n" \ + "${K_VERSION}" "${K_PATCHLEVEL}" "${K_SUBLEVEL}" \ + "${K_EXTRAVERSION}" "${K_NAME}" "${k_cset}" + +# Get the kconfig-frontends version +kf_version="$( tail -n 1 .version )" + +# Store the new version +printf "%d.%d.%d%s %s %s\n%s\n" \ + "${K_VERSION}" "${K_PATCHLEVEL}" \ + "${K_SUBLEVEL}" "${K_EXTRAVERSION}" \ + "${k_cset}" "${K_NAME}" \ + "${kf_version}" \ + >.version + +# Sync-up the files +k_files="" +while read k_file trash kf_file; do + k_files="${k_files} ${k_file}" + mkdir -p "${kf_file%/*}" + cp -v "${k_dir}/${k_file}" "${kf_file}" + if [ -f "${kf_file}.patch" ]; then + patch --no-backup-if-mismatch -g0 -F1 -p1 -f <"${kf_file}.patch" + fi +done &2; exit 1;; +esac +if [ ${plain} -ne 0 -a ${internal} -ne 0 ]; then + printf "Can't print both plain and internal" >&2 + printf " versions at the same time\n" >&2 + exit 1 +fi + +ver_file="${0%/*}/../.version" +k_ver="$( head -n 1 "${ver_file}" |cut -d ' ' -f 1 )" +k_cset="$( head -n 1 "${ver_file}" |cut -d ' ' -f 2 )" +k_name="$( head -n 1 "${ver_file}" |cut -d ' ' -f 3- )" +kf_ver="$( tail -n 1 "${ver_file}" )" + +if [ ${internal} -ne 0 ]; then + printf "%s\n" "${kf_ver}" + exit 0 +fi + +k_ver_plain="$( printf "%s" "${k_ver}" \ + |sed -r -e 's/-rc.*//;' )" + +case "${kf_ver}" in + hg) kf_ver="hg_$( hg id -i -r . )" + k_ver_extra="$( printf "_%-7.7s" "${k_cset}" )" + ;; + *) k_ver_extra="";; +esac + +if [ "${plain}" -eq 1 ]; then + echo "${k_ver_plain}" +else + echo "${k_ver}${k_ver_extra}-${kf_ver}" +fi + diff --git a/misc/tools/kconfig-frontends/utils/Makefile.am b/misc/tools/kconfig-frontends/utils/Makefile.am new file mode 100644 index 0000000000..57ff28896e --- /dev/null +++ b/misc/tools/kconfig-frontends/utils/Makefile.am @@ -0,0 +1,21 @@ +bin_SCRIPTS = tweak +dist_bin_SCRIPTS = diff merge + +if COND_utils_gettext + MAYBE_utils_gettext = gettext +endif +bin_PROGRAMS = $(MAYBE_utils_gettext) + +gettext_SOURCES = gettext.c +gettext_CPPFLAGS = $(AM_CPPFLAGS) \ + -I$(top_srcdir)/libs/parser +gettext_CFLAGS = $(AM_CFLAGS) $(kf_CFLAGS) +gettext_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(intl_LIBS) +CLEANFILES = tweak +EXTRA_DIST = tweak.in tweak.in.patch + +tweak: tweak.in + $(AM_V_GEN)$(SED) -r -e "s/@CONFIG_@/$(config_prefix)/g" \ + $< >$@ + @chmod +x $@ diff --git a/misc/tools/kconfig-frontends/utils/Makefile.in b/misc/tools/kconfig-frontends/utils/Makefile.in new file mode 100644 index 0000000000..0ee4a2a894 --- /dev/null +++ b/misc/tools/kconfig-frontends/utils/Makefile.in @@ -0,0 +1,708 @@ +# Makefile.in generated by automake 1.11.1 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, +# 2003, 2004, 2005, 2006, 2007, 2008, 2009 Free Software Foundation, +# Inc. +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ + + +VPATH = @srcdir@ +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +bin_PROGRAMS = $(am__EXEEXT_1) +subdir = utils +DIST_COMMON = $(dist_bin_SCRIPTS) $(srcdir)/Makefile.am \ + $(srcdir)/Makefile.in +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/scripts/.autostuff/config.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +@COND_utils_gettext_TRUE@am__EXEEXT_1 = gettext$(EXEEXT) +am__installdirs = "$(DESTDIR)$(bindir)" "$(DESTDIR)$(bindir)" \ + "$(DESTDIR)$(bindir)" +PROGRAMS = $(bin_PROGRAMS) +am_gettext_OBJECTS = gettext-gettext.$(OBJEXT) +gettext_OBJECTS = $(am_gettext_OBJECTS) +am__DEPENDENCIES_1 = +gettext_DEPENDENCIES = \ + $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(am__DEPENDENCIES_1) +AM_V_lt = $(am__v_lt_$(V)) +am__v_lt_ = $(am__v_lt_$(AM_DEFAULT_VERBOSITY)) +am__v_lt_0 = --silent +gettext_LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(gettext_CFLAGS) \ + $(CFLAGS) $(AM_LDFLAGS) $(LDFLAGS) -o $@ +am__vpath_adj_setup = srcdirstrip=`echo "$(srcdir)" | sed 's|.|.|g'`; +am__vpath_adj = case $$p in \ + $(srcdir)/*) f=`echo "$$p" | sed "s|^$$srcdirstrip/||"`;; \ + *) f=$$p;; \ + esac; +am__strip_dir = f=`echo $$p | sed -e 's|^.*/||'`; +am__install_max = 40 +am__nobase_strip_setup = \ + srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*|]/\\\\&/g'` +am__nobase_strip = \ + for p in $$list; do echo "$$p"; done | sed -e "s|$$srcdirstrip/||" +am__nobase_list = $(am__nobase_strip_setup); \ + for p in $$list; do echo "$$p $$p"; done | \ + sed "s| $$srcdirstrip/| |;"' / .*\//!s/ .*/ ./; s,\( .*\)/[^/]*$$,\1,' | \ + $(AWK) 'BEGIN { files["."] = "" } { files[$$2] = files[$$2] " " $$1; \ + if (++n[$$2] == $(am__install_max)) \ + { print $$2, files[$$2]; n[$$2] = 0; files[$$2] = "" } } \ + END { for (dir in files) print dir, files[dir] }' +am__base_list = \ + sed '$$!N;$$!N;$$!N;$$!N;$$!N;$$!N;$$!N;s/\n/ /g' | \ + sed '$$!N;$$!N;$$!N;$$!N;s/\n/ /g' +SCRIPTS = $(bin_SCRIPTS) $(dist_bin_SCRIPTS) +DEFAULT_INCLUDES = -I.@am__isrc@ -I$(top_builddir)/scripts/.autostuff +depcomp = $(SHELL) $(top_srcdir)/scripts/.autostuff/scripts/depcomp +am__depfiles_maybe = depfiles +am__mv = mv -f +COMPILE = $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) \ + $(CPPFLAGS) $(AM_CFLAGS) $(CFLAGS) +LTCOMPILE = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=compile $(CC) $(DEFS) \ + $(DEFAULT_INCLUDES) $(INCLUDES) $(AM_CPPFLAGS) $(CPPFLAGS) \ + $(AM_CFLAGS) $(CFLAGS) +AM_V_CC = $(am__v_CC_$(V)) +am__v_CC_ = $(am__v_CC_$(AM_DEFAULT_VERBOSITY)) +am__v_CC_0 = @echo " CC " $@; +AM_V_at = $(am__v_at_$(V)) +am__v_at_ = $(am__v_at_$(AM_DEFAULT_VERBOSITY)) +am__v_at_0 = @ +CCLD = $(CC) +LINK = $(LIBTOOL) $(AM_V_lt) --tag=CC $(AM_LIBTOOLFLAGS) \ + $(LIBTOOLFLAGS) --mode=link $(CCLD) $(AM_CFLAGS) $(CFLAGS) \ + $(AM_LDFLAGS) $(LDFLAGS) -o $@ +AM_V_CCLD = $(am__v_CCLD_$(V)) +am__v_CCLD_ = $(am__v_CCLD_$(AM_DEFAULT_VERBOSITY)) +am__v_CCLD_0 = @echo " CCLD " $@; +AM_V_GEN = $(am__v_GEN_$(V)) +am__v_GEN_ = $(am__v_GEN_$(AM_DEFAULT_VERBOSITY)) +am__v_GEN_0 = @echo " GEN " $@; +SOURCES = $(gettext_SOURCES) +DIST_SOURCES = $(gettext_SOURCES) +ETAGS = etags +CTAGS = ctags +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +ALLOCA = @ALLOCA@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AM_LFLAGS = @AM_LFLAGS@ +AM_YFLAGS = @AM_YFLAGS@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CURSES_LOC = @CURSES_LOC@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GPERF = @GPERF@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +KCONFIGPARSER_LIB_VERSION = @KCONFIGPARSER_LIB_VERSION@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LEX = @LEX@ +LEXLIB = @LEXLIB@ +LEX_OUTPUT_ROOT = @LEX_OUTPUT_ROOT@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +MAKEINFO = @MAKEINFO@ +MKDIR_P = @MKDIR_P@ +MOC = @MOC@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +SILENT_MAKEFLAGS = @SILENT_MAKEFLAGS@ +STRIP = @STRIP@ +VERSION = @VERSION@ +YACC = @YACC@ +YFLAGS = @YFLAGS@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +conf_EXTRA_LIBS = @conf_EXTRA_LIBS@ +config_prefix = @config_prefix@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +enable_L10n = @enable_L10n@ +enable_conf = @enable_conf@ +enable_frontends = @enable_frontends@ +enable_gconf = @enable_gconf@ +enable_mconf = @enable_mconf@ +enable_nconf = @enable_nconf@ +enable_qconf = @enable_qconf@ +enable_utils = @enable_utils@ +exec_prefix = @exec_prefix@ +gconf_EXTRA_LIBS = @gconf_EXTRA_LIBS@ +gtk_CFLAGS = @gtk_CFLAGS@ +gtk_LIBS = @gtk_LIBS@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +intl_CPPFLAGS = @intl_CPPFLAGS@ +intl_LIBS = @intl_LIBS@ +kf_CFLAGS = @kf_CFLAGS@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +lt_ECHO = @lt_ECHO@ +mandir = @mandir@ +mconf_EXTRA_LIBS = @mconf_EXTRA_LIBS@ +mkdir_p = @mkdir_p@ +nconf_EXTRA_LIBS = @nconf_EXTRA_LIBS@ +ncurses_LIBS = @ncurses_LIBS@ +ncurses_extra_CPPFLAGS = @ncurses_extra_CPPFLAGS@ +ncurses_extra_LIBS = @ncurses_extra_LIBS@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +qconf_EXTRA_LIBS = @qconf_EXTRA_LIBS@ +qt4_CFLAGS = @qt4_CFLAGS@ +qt4_LIBS = @qt4_LIBS@ +root_menu = @root_menu@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target_alias = @target_alias@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +wall_CFLAGS = @wall_CFLAGS@ +werror_CFLAGS = @werror_CFLAGS@ +bin_SCRIPTS = tweak +dist_bin_SCRIPTS = diff merge +@COND_utils_gettext_TRUE@MAYBE_utils_gettext = gettext +gettext_SOURCES = gettext.c +gettext_CPPFLAGS = $(AM_CPPFLAGS) \ + -I$(top_srcdir)/libs/parser + +gettext_CFLAGS = $(AM_CFLAGS) $(kf_CFLAGS) +gettext_LDADD = $(top_builddir)/libs/parser/libkconfig-parser.la \ + $(intl_LIBS) + +CLEANFILES = tweak +EXTRA_DIST = tweak.in tweak.in.patch +all: all-am + +.SUFFIXES: +.SUFFIXES: .c .lo .o .obj +$(srcdir)/Makefile.in: $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign utils/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --foreign utils/Makefile +.PRECIOUS: Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): +install-binPROGRAMS: $(bin_PROGRAMS) + @$(NORMAL_INSTALL) + test -z "$(bindir)" || $(MKDIR_P) "$(DESTDIR)$(bindir)" + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + for p in $$list; do echo "$$p $$p"; done | \ + sed 's/$(EXEEXT)$$//' | \ + while read p p1; do if test -f $$p || test -f $$p1; \ + then echo "$$p"; echo "$$p"; else :; fi; \ + done | \ + sed -e 'p;s,.*/,,;n;h' -e 's|.*|.|' \ + -e 'p;x;s,.*/,,;s/$(EXEEXT)$$//;$(transform);s/$$/$(EXEEXT)/' | \ + sed 'N;N;N;s,\n, ,g' | \ + $(AWK) 'BEGIN { files["."] = ""; dirs["."] = 1 } \ + { d=$$3; if (dirs[d] != 1) { print "d", d; dirs[d] = 1 } \ + if ($$2 == $$4) files[d] = files[d] " " $$1; \ + else { print "f", $$3 "/" $$4, $$1; } } \ + END { for (d in files) print "f", d, files[d] }' | \ + while read type dir files; do \ + if test "$$dir" = .; then dir=; else dir=/$$dir; fi; \ + test -z "$$files" || { \ + echo " $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files '$(DESTDIR)$(bindir)$$dir'"; \ + $(INSTALL_PROGRAM_ENV) $(LIBTOOL) $(AM_LIBTOOLFLAGS) $(LIBTOOLFLAGS) --mode=install $(INSTALL_PROGRAM) $$files "$(DESTDIR)$(bindir)$$dir" || exit $$?; \ + } \ + ; done + +uninstall-binPROGRAMS: + @$(NORMAL_UNINSTALL) + @list='$(bin_PROGRAMS)'; test -n "$(bindir)" || list=; \ + files=`for p in $$list; do echo "$$p"; done | \ + sed -e 'h;s,^.*/,,;s/$(EXEEXT)$$//;$(transform)' \ + -e 's/$$/$(EXEEXT)/' `; \ + test -n "$$list" || exit 0; \ + echo " ( cd '$(DESTDIR)$(bindir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(bindir)" && rm -f $$files + +clean-binPROGRAMS: + @list='$(bin_PROGRAMS)'; test -n "$$list" || exit 0; \ + echo " rm -f" $$list; \ + rm -f $$list || exit $$?; \ + test -n "$(EXEEXT)" || exit 0; \ + list=`for p in $$list; do echo "$$p"; done | sed 's/$(EXEEXT)$$//'`; \ + echo " rm -f" $$list; \ + rm -f $$list +gettext$(EXEEXT): $(gettext_OBJECTS) $(gettext_DEPENDENCIES) + @rm -f gettext$(EXEEXT) + $(AM_V_CCLD)$(gettext_LINK) $(gettext_OBJECTS) $(gettext_LDADD) $(LIBS) +install-binSCRIPTS: $(bin_SCRIPTS) + @$(NORMAL_INSTALL) + test -z "$(bindir)" || $(MKDIR_P) "$(DESTDIR)$(bindir)" + @list='$(bin_SCRIPTS)'; test -n "$(bindir)" || list=; \ + for p in $$list; do \ + if test -f "$$p"; then d=; else d="$(srcdir)/"; fi; \ + if test -f "$$d$$p"; then echo "$$d$$p"; echo "$$p"; else :; fi; \ + done | \ + sed -e 'p;s,.*/,,;n' \ + -e 'h;s|.*|.|' \ + -e 'p;x;s,.*/,,;$(transform)' | sed 'N;N;N;s,\n, ,g' | \ + $(AWK) 'BEGIN { files["."] = ""; dirs["."] = 1; } \ + { d=$$3; if (dirs[d] != 1) { print "d", d; dirs[d] = 1 } \ + if ($$2 == $$4) { files[d] = files[d] " " $$1; \ + if (++n[d] == $(am__install_max)) { \ + print "f", d, files[d]; n[d] = 0; files[d] = "" } } \ + else { print "f", d "/" $$4, $$1 } } \ + END { for (d in files) print "f", d, files[d] }' | \ + while read type dir files; do \ + if test "$$dir" = .; then dir=; else dir=/$$dir; fi; \ + test -z "$$files" || { \ + echo " $(INSTALL_SCRIPT) $$files '$(DESTDIR)$(bindir)$$dir'"; \ + $(INSTALL_SCRIPT) $$files "$(DESTDIR)$(bindir)$$dir" || exit $$?; \ + } \ + ; done + +uninstall-binSCRIPTS: + @$(NORMAL_UNINSTALL) + @list='$(bin_SCRIPTS)'; test -n "$(bindir)" || exit 0; \ + files=`for p in $$list; do echo "$$p"; done | \ + sed -e 's,.*/,,;$(transform)'`; \ + test -n "$$list" || exit 0; \ + echo " ( cd '$(DESTDIR)$(bindir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(bindir)" && rm -f $$files +install-dist_binSCRIPTS: $(dist_bin_SCRIPTS) + @$(NORMAL_INSTALL) + test -z "$(bindir)" || $(MKDIR_P) "$(DESTDIR)$(bindir)" + @list='$(dist_bin_SCRIPTS)'; test -n "$(bindir)" || list=; \ + for p in $$list; do \ + if test -f "$$p"; then d=; else d="$(srcdir)/"; fi; \ + if test -f "$$d$$p"; then echo "$$d$$p"; echo "$$p"; else :; fi; \ + done | \ + sed -e 'p;s,.*/,,;n' \ + -e 'h;s|.*|.|' \ + -e 'p;x;s,.*/,,;$(transform)' | sed 'N;N;N;s,\n, ,g' | \ + $(AWK) 'BEGIN { files["."] = ""; dirs["."] = 1; } \ + { d=$$3; if (dirs[d] != 1) { print "d", d; dirs[d] = 1 } \ + if ($$2 == $$4) { files[d] = files[d] " " $$1; \ + if (++n[d] == $(am__install_max)) { \ + print "f", d, files[d]; n[d] = 0; files[d] = "" } } \ + else { print "f", d "/" $$4, $$1 } } \ + END { for (d in files) print "f", d, files[d] }' | \ + while read type dir files; do \ + if test "$$dir" = .; then dir=; else dir=/$$dir; fi; \ + test -z "$$files" || { \ + echo " $(INSTALL_SCRIPT) $$files '$(DESTDIR)$(bindir)$$dir'"; \ + $(INSTALL_SCRIPT) $$files "$(DESTDIR)$(bindir)$$dir" || exit $$?; \ + } \ + ; done + +uninstall-dist_binSCRIPTS: + @$(NORMAL_UNINSTALL) + @list='$(dist_bin_SCRIPTS)'; test -n "$(bindir)" || exit 0; \ + files=`for p in $$list; do echo "$$p"; done | \ + sed -e 's,.*/,,;$(transform)'`; \ + test -n "$$list" || exit 0; \ + echo " ( cd '$(DESTDIR)$(bindir)' && rm -f" $$files ")"; \ + cd "$(DESTDIR)$(bindir)" && rm -f $$files + +mostlyclean-compile: + -rm -f *.$(OBJEXT) + +distclean-compile: + -rm -f *.tab.c + +@AMDEP_TRUE@@am__include@ @am__quote@./$(DEPDIR)/gettext-gettext.Po@am__quote@ + +.c.o: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c $< + +.c.obj: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(COMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ `$(CYGPATH_W) '$<'` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(COMPILE) -c `$(CYGPATH_W) '$<'` + +.c.lo: +@am__fastdepCC_TRUE@ $(AM_V_CC)$(LTCOMPILE) -MT $@ -MD -MP -MF $(DEPDIR)/$*.Tpo -c -o $@ $< +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/$*.Tpo $(DEPDIR)/$*.Plo +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='$<' object='$@' libtool=yes @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(LTCOMPILE) -c -o $@ $< + +gettext-gettext.o: gettext.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(gettext_CPPFLAGS) $(CPPFLAGS) $(gettext_CFLAGS) $(CFLAGS) -MT gettext-gettext.o -MD -MP -MF $(DEPDIR)/gettext-gettext.Tpo -c -o gettext-gettext.o `test -f 'gettext.c' || echo '$(srcdir)/'`gettext.c +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/gettext-gettext.Tpo $(DEPDIR)/gettext-gettext.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='gettext.c' object='gettext-gettext.o' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(gettext_CPPFLAGS) $(CPPFLAGS) $(gettext_CFLAGS) $(CFLAGS) -c -o gettext-gettext.o `test -f 'gettext.c' || echo '$(srcdir)/'`gettext.c + +gettext-gettext.obj: gettext.c +@am__fastdepCC_TRUE@ $(AM_V_CC)$(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(gettext_CPPFLAGS) $(CPPFLAGS) $(gettext_CFLAGS) $(CFLAGS) -MT gettext-gettext.obj -MD -MP -MF $(DEPDIR)/gettext-gettext.Tpo -c -o gettext-gettext.obj `if test -f 'gettext.c'; then $(CYGPATH_W) 'gettext.c'; else $(CYGPATH_W) '$(srcdir)/gettext.c'; fi` +@am__fastdepCC_TRUE@ $(AM_V_at)$(am__mv) $(DEPDIR)/gettext-gettext.Tpo $(DEPDIR)/gettext-gettext.Po +@am__fastdepCC_FALSE@ $(AM_V_CC) @AM_BACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ source='gettext.c' object='gettext-gettext.obj' libtool=no @AMDEPBACKSLASH@ +@AMDEP_TRUE@@am__fastdepCC_FALSE@ DEPDIR=$(DEPDIR) $(CCDEPMODE) $(depcomp) @AMDEPBACKSLASH@ +@am__fastdepCC_FALSE@ $(CC) $(DEFS) $(DEFAULT_INCLUDES) $(INCLUDES) $(gettext_CPPFLAGS) $(CPPFLAGS) $(gettext_CFLAGS) $(CFLAGS) -c -o gettext-gettext.obj `if test -f 'gettext.c'; then $(CYGPATH_W) 'gettext.c'; else $(CYGPATH_W) '$(srcdir)/gettext.c'; fi` + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs + +ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + mkid -fID $$unique +tags: TAGS + +TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + set x; \ + here=`pwd`; \ + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + shift; \ + if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ + test -n "$$unique" || unique=$$empty_fix; \ + if test $$# -gt 0; then \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + "$$@" $$unique; \ + else \ + $(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \ + $$unique; \ + fi; \ + fi +ctags: CTAGS +CTAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ + $(TAGS_FILES) $(LISP) + list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | \ + $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in files) print i; }; }'`; \ + test -z "$(CTAGS_ARGS)$$unique" \ + || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ + $$unique + +GTAGS: + here=`$(am__cd) $(top_builddir) && pwd` \ + && $(am__cd) $(top_srcdir) \ + && gtags -i $(GTAGS_ARGS) "$$here" + +distclean-tags: + -rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-am +all-am: Makefile $(PROGRAMS) $(SCRIPTS) +installdirs: + for dir in "$(DESTDIR)$(bindir)" "$(DESTDIR)$(bindir)" "$(DESTDIR)$(bindir)"; do \ + test -z "$$dir" || $(MKDIR_P) "$$dir"; \ + done +install: install-am +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + `test -z '$(STRIP)' || \ + echo "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'"` install +mostlyclean-generic: + +clean-generic: + -test -z "$(CLEANFILES)" || rm -f $(CLEANFILES) + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-am + +clean-am: clean-binPROGRAMS clean-generic clean-libtool mostlyclean-am + +distclean: distclean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +distclean-am: clean-am distclean-compile distclean-generic \ + distclean-tags + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: install-binPROGRAMS install-binSCRIPTS \ + install-dist_binSCRIPTS + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -rf ./$(DEPDIR) + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-compile mostlyclean-generic \ + mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: uninstall-binPROGRAMS uninstall-binSCRIPTS \ + uninstall-dist_binSCRIPTS + +.MAKE: install-am install-strip + +.PHONY: CTAGS GTAGS all all-am check check-am clean clean-binPROGRAMS \ + clean-generic clean-libtool ctags distclean distclean-compile \ + distclean-generic distclean-libtool distclean-tags distdir dvi \ + dvi-am html html-am info info-am install install-am \ + install-binPROGRAMS install-binSCRIPTS install-data \ + install-data-am install-dist_binSCRIPTS install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-compile mostlyclean-generic mostlyclean-libtool \ + pdf pdf-am ps ps-am tags uninstall uninstall-am \ + uninstall-binPROGRAMS uninstall-binSCRIPTS \ + uninstall-dist_binSCRIPTS + + +tweak: tweak.in + $(AM_V_GEN)$(SED) -r -e "s/@CONFIG_@/$(config_prefix)/g" \ + $< >$@ + @chmod +x $@ + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/misc/tools/kconfig-frontends/utils/diff b/misc/tools/kconfig-frontends/utils/diff new file mode 100755 index 0000000000..b91f3e34d4 --- /dev/null +++ b/misc/tools/kconfig-frontends/utils/diff @@ -0,0 +1,129 @@ +#!/usr/bin/python +# +# diffconfig - a tool to compare .config files. +# +# originally written in 2006 by Matt Mackall +# (at least, this was in his bloatwatch source code) +# last worked on 2008 by Tim Bird +# + +import sys, os + +def usage(): + print """Usage: diffconfig [-h] [-m] [ ] + +Diffconfig is a simple utility for comparing two .config files. +Using standard diff to compare .config files often includes extraneous and +distracting information. This utility produces sorted output with only the +changes in configuration values between the two files. + +Added and removed items are shown with a leading plus or minus, respectively. +Changed items show the old and new values on a single line. + +If -m is specified, then output will be in "merge" style, which has the +changed and new values in kernel config option format. + +If no config files are specified, .config and .config.old are used. + +Example usage: + $ diffconfig .config config-with-some-changes +-EXT2_FS_XATTR n +-EXT2_FS_XIP n + CRAMFS n -> y + EXT2_FS y -> n + LOG_BUF_SHIFT 14 -> 16 + PRINTK_TIME n -> y +""" + sys.exit(0) + +# returns a dictionary of name/value pairs for config items in the file +def readconfig(config_file): + d = {} + for line in config_file: + line = line[:-1] + if line[:7] == "CONFIG_": + name, val = line[7:].split("=", 1) + d[name] = val + if line[-11:] == " is not set": + d[line[9:-11]] = "n" + return d + +def print_config(op, config, value, new_value): + global merge_style + + if merge_style: + if new_value: + if new_value=="n": + print "# CONFIG_%s is not set" % config + else: + print "CONFIG_%s=%s" % (config, new_value) + else: + if op=="-": + print "-%s %s" % (config, value) + elif op=="+": + print "+%s %s" % (config, new_value) + else: + print " %s %s -> %s" % (config, value, new_value) + +def main(): + global merge_style + + # parse command line args + if ("-h" in sys.argv or "--help" in sys.argv): + usage() + + merge_style = 0 + if "-m" in sys.argv: + merge_style = 1 + sys.argv.remove("-m") + + argc = len(sys.argv) + if not (argc==1 or argc == 3): + print "Error: incorrect number of arguments or unrecognized option" + usage() + + if argc == 1: + # if no filenames given, assume .config and .config.old + build_dir="" + if os.environ.has_key("KBUILD_OUTPUT"): + build_dir = os.environ["KBUILD_OUTPUT"]+"/" + + configa_filename = build_dir + ".config.old" + configb_filename = build_dir + ".config" + else: + configa_filename = sys.argv[1] + configb_filename = sys.argv[2] + + a = readconfig(file(configa_filename)) + b = readconfig(file(configb_filename)) + + # print items in a but not b (accumulate, sort and print) + old = [] + for config in a: + if config not in b: + old.append(config) + old.sort() + for config in old: + print_config("-", config, a[config], None) + del a[config] + + # print items that changed (accumulate, sort, and print) + changed = [] + for config in a: + if a[config] != b[config]: + changed.append(config) + else: + del b[config] + changed.sort() + for config in changed: + print_config("->", config, a[config], b[config]) + del b[config] + + # now print items in b but not in a + # (items from b that were in a were removed above) + new = b.keys() + new.sort() + for config in new: + print_config("+", config, None, b[config]) + +main() diff --git a/misc/tools/kconfig-frontends/utils/gettext.c b/misc/tools/kconfig-frontends/utils/gettext.c new file mode 100644 index 0000000000..2858738b22 --- /dev/null +++ b/misc/tools/kconfig-frontends/utils/gettext.c @@ -0,0 +1,235 @@ +/* + * Arnaldo Carvalho de Melo , 2005 + * + * Released under the terms of the GNU GPL v2.0 + */ + +#include +#include + +#include "lkc.h" + +static char *escape(const char* text, char *bf, int len) +{ + char *bfp = bf; + int multiline = strchr(text, '\n') != NULL; + int eol = 0; + int textlen = strlen(text); + + if ((textlen > 0) && (text[textlen-1] == '\n')) + eol = 1; + + *bfp++ = '"'; + --len; + + if (multiline) { + *bfp++ = '"'; + *bfp++ = '\n'; + *bfp++ = '"'; + len -= 3; + } + + while (*text != '\0' && len > 1) { + if (*text == '"') + *bfp++ = '\\'; + else if (*text == '\n') { + *bfp++ = '\\'; + *bfp++ = 'n'; + *bfp++ = '"'; + *bfp++ = '\n'; + *bfp++ = '"'; + len -= 5; + ++text; + goto next; + } + else if (*text == '\\') { + *bfp++ = '\\'; + len--; + } + *bfp++ = *text++; +next: + --len; + } + + if (multiline && eol) + bfp -= 3; + + *bfp++ = '"'; + *bfp = '\0'; + + return bf; +} + +struct file_line { + struct file_line *next; + const char *file; + int lineno; +}; + +static struct file_line *file_line__new(const char *file, int lineno) +{ + struct file_line *self = malloc(sizeof(*self)); + + if (self == NULL) + goto out; + + self->file = file; + self->lineno = lineno; + self->next = NULL; +out: + return self; +} + +struct message { + const char *msg; + const char *option; + struct message *next; + struct file_line *files; +}; + +static struct message *message__list; + +static struct message *message__new(const char *msg, char *option, + const char *file, int lineno) +{ + struct message *self = malloc(sizeof(*self)); + + if (self == NULL) + goto out; + + self->files = file_line__new(file, lineno); + if (self->files == NULL) + goto out_fail; + + self->msg = strdup(msg); + if (self->msg == NULL) + goto out_fail_msg; + + self->option = option; + self->next = NULL; +out: + return self; +out_fail_msg: + free(self->files); +out_fail: + free(self); + self = NULL; + goto out; +} + +static struct message *mesage__find(const char *msg) +{ + struct message *m = message__list; + + while (m != NULL) { + if (strcmp(m->msg, msg) == 0) + break; + m = m->next; + } + + return m; +} + +static int message__add_file_line(struct message *self, const char *file, + int lineno) +{ + int rc = -1; + struct file_line *fl = file_line__new(file, lineno); + + if (fl == NULL) + goto out; + + fl->next = self->files; + self->files = fl; + rc = 0; +out: + return rc; +} + +static int message__add(const char *msg, char *option, const char *file, + int lineno) +{ + int rc = 0; + char bf[16384]; + char *escaped = escape(msg, bf, sizeof(bf)); + struct message *m = mesage__find(escaped); + + if (m != NULL) + rc = message__add_file_line(m, file, lineno); + else { + m = message__new(escaped, option, file, lineno); + + if (m != NULL) { + m->next = message__list; + message__list = m; + } else + rc = -1; + } + return rc; +} + +static void menu_build_message_list(struct menu *menu) +{ + struct menu *child; + + message__add(menu_get_prompt(menu), NULL, + menu->file == NULL ? "Root Menu" : menu->file->name, + menu->lineno); + + if (menu->sym != NULL && menu_has_help(menu)) + message__add(menu_get_help(menu), menu->sym->name, + menu->file == NULL ? "Root Menu" : menu->file->name, + menu->lineno); + + for (child = menu->list; child != NULL; child = child->next) + if (child->prompt != NULL) + menu_build_message_list(child); +} + +static void message__print_file_lineno(struct message *self) +{ + struct file_line *fl = self->files; + + putchar('\n'); + if (self->option != NULL) + printf("# %s:00000\n", self->option); + + printf("#: %s:%d", fl->file, fl->lineno); + fl = fl->next; + + while (fl != NULL) { + printf(", %s:%d", fl->file, fl->lineno); + fl = fl->next; + } + + putchar('\n'); +} + +static void message__print_gettext_msgid_msgstr(struct message *self) +{ + message__print_file_lineno(self); + + printf("msgid %s\n" + "msgstr \"\"\n", self->msg); +} + +static void menu__xgettext(void) +{ + struct message *m = message__list; + + while (m != NULL) { + /* skip empty lines ("") */ + if (strlen(m->msg) > sizeof("\"\"")) + message__print_gettext_msgid_msgstr(m); + m = m->next; + } +} + +int main(int ac, char **av) +{ + conf_parse(av[1]); + + menu_build_message_list(menu_get_root_menu(NULL)); + menu__xgettext(); + return 0; +} diff --git a/misc/tools/kconfig-frontends/utils/merge b/misc/tools/kconfig-frontends/utils/merge new file mode 100755 index 0000000000..974d5cb7e3 --- /dev/null +++ b/misc/tools/kconfig-frontends/utils/merge @@ -0,0 +1,130 @@ +#!/bin/sh +# merge_config.sh - Takes a list of config fragment values, and merges +# them one by one. Provides warnings on overridden values, and specified +# values that did not make it to the resulting .config file (due to missed +# dependencies or config symbol removal). +# +# Portions reused from kconf_check and generate_cfg: +# http://git.yoctoproject.org/cgit/cgit.cgi/yocto-kernel-tools/tree/tools/kconf_check +# http://git.yoctoproject.org/cgit/cgit.cgi/yocto-kernel-tools/tree/tools/generate_cfg +# +# Copyright (c) 2009-2010 Wind River Systems, Inc. +# Copyright 2011 Linaro +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License version 2 as +# published by the Free Software Foundation. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the GNU General Public License for more details. + +clean_up() { + rm -f $TMP_FILE + exit +} +trap clean_up HUP INT TERM + +usage() { + echo "Usage: $0 [OPTIONS] [CONFIG [...]]" + echo " -h display this help text" + echo " -m only merge the fragments, do not execute the make command" + echo " -n use allnoconfig instead of alldefconfig" + echo " -r list redundant entries when merging fragments" +} + +MAKE=true +ALLTARGET=alldefconfig +WARNREDUN=false + +while true; do + case $1 in + "-n") + ALLTARGET=allnoconfig + shift + continue + ;; + "-m") + MAKE=false + shift + continue + ;; + "-h") + usage + exit + ;; + "-r") + WARNREDUN=true + shift + continue + ;; + *) + break + ;; + esac +done + +INITFILE=$1 +shift; + +MERGE_LIST=$* +SED_CONFIG_EXP="s/^\(# \)\{0,1\}\(CONFIG_[a-zA-Z0-9_]*\)[= ].*/\2/p" +TMP_FILE=$(mktemp ./.tmp.config.XXXXXXXXXX) + +echo "Using $INITFILE as base" +cat $INITFILE > $TMP_FILE + +# Merge files, printing warnings on overrided values +for MERGE_FILE in $MERGE_LIST ; do + echo "Merging $MERGE_FILE" + CFG_LIST=$(sed -n "$SED_CONFIG_EXP" $MERGE_FILE) + + for CFG in $CFG_LIST ; do + grep -q -w $CFG $TMP_FILE + if [ $? -eq 0 ] ; then + PREV_VAL=$(grep -w $CFG $TMP_FILE) + NEW_VAL=$(grep -w $CFG $MERGE_FILE) + if [ "x$PREV_VAL" != "x$NEW_VAL" ] ; then + echo Value of $CFG is redefined by fragment $MERGE_FILE: + echo Previous value: $PREV_VAL + echo New value: $NEW_VAL + echo + elif [ "$WARNREDUN" = "true" ]; then + echo Value of $CFG is redundant by fragment $MERGE_FILE: + fi + sed -i "/$CFG[ =]/d" $TMP_FILE + fi + done + cat $MERGE_FILE >> $TMP_FILE +done + +if [ "$MAKE" = "false" ]; then + cp $TMP_FILE .config + echo "#" + echo "# merged configuration written to .config (needs make)" + echo "#" + clean_up + exit +fi + +# Use the merged file as the starting point for: +# alldefconfig: Fills in any missing symbols with Kconfig default +# allnoconfig: Fills in any missing symbols with # CONFIG_* is not set +make KCONFIG_ALLCONFIG=$TMP_FILE $ALLTARGET + + +# Check all specified config values took (might have missed-dependency issues) +for CFG in $(sed -n "$SED_CONFIG_EXP" $TMP_FILE); do + + REQUESTED_VAL=$(grep -w -e "$CFG" $TMP_FILE) + ACTUAL_VAL=$(grep -w -e "$CFG" .config) + if [ "x$REQUESTED_VAL" != "x$ACTUAL_VAL" ] ; then + echo "Value requested for $CFG not in final .config" + echo "Requested value: $REQUESTED_VAL" + echo "Actual value: $ACTUAL_VAL" + echo "" + fi +done + +clean_up diff --git a/misc/tools/kconfig-frontends/utils/tweak.in b/misc/tools/kconfig-frontends/utils/tweak.in new file mode 100644 index 0000000000..743dc54ca2 --- /dev/null +++ b/misc/tools/kconfig-frontends/utils/tweak.in @@ -0,0 +1,187 @@ +#!/bin/bash +# Manipulate options in a .config file from the command line + +# If no prefix forced, use the default @CONFIG_@ +CONFIG_="${CONFIG_-@CONFIG_@}" + +usage() { + cat >&2 <>"$FN" + fi +} + +undef_var() { + local name=$1 + + sed -ri "/^($name=|# $name is not set)/d" "$FN" +} + +if [ "$1" = "--file" ]; then + FN="$2" + if [ "$FN" = "" ] ; then + usage + fi + shift 2 +else + FN=.config +fi + +if [ "$1" = "" ] ; then + usage +fi + +MUNGE_CASE=yes +while [ "$1" != "" ] ; do + CMD="$1" + shift + case "$CMD" in + --keep-case|-k) + MUNGE_CASE=no + shift + continue + ;; + --refresh) + ;; + --*-after) + checkarg "$1" + A=$ARG + checkarg "$2" + B=$ARG + shift 2 + ;; + -*) + checkarg "$1" + shift + ;; + esac + case "$CMD" in + --enable|-e) + set_var "${CONFIG_}$ARG" "${CONFIG_}$ARG=y" + ;; + + --disable|-d) + set_var "${CONFIG_}$ARG" "# ${CONFIG_}$ARG is not set" + ;; + + --module|-m) + set_var "${CONFIG_}$ARG" "${CONFIG_}$ARG=m" + ;; + + --set-str) + # sed swallows one level of escaping, so we need double-escaping + set_var "${CONFIG_}$ARG" "${CONFIG_}$ARG=\"${1//\"/\\\\\"}\"" + shift + ;; + + --set-val) + set_var "${CONFIG_}$ARG" "${CONFIG_}$ARG=$1" + shift + ;; + --undefine|-u) + undef_var "${CONFIG_}$ARG" + ;; + + --state|-s) + if grep -q "# ${CONFIG_}$ARG is not set" $FN ; then + echo n + else + V="$(grep "^${CONFIG_}$ARG=" $FN)" + if [ $? != 0 ] ; then + echo undef + else + V="${V/#${CONFIG_}$ARG=/}" + V="${V/#\"/}" + V="${V/%\"/}" + V="${V//\\\"/\"}" + echo "${V}" + fi + fi + ;; + + --enable-after|-E) + set_var "${CONFIG_}$B" "${CONFIG_}$B=y" "${CONFIG_}$A" + ;; + + --disable-after|-D) + set_var "${CONFIG_}$B" "# ${CONFIG_}$B is not set" "${CONFIG_}$A" + ;; + + --module-after|-M) + set_var "${CONFIG_}$B" "${CONFIG_}$B=m" "${CONFIG_}$A" + ;; + + # undocumented because it ignores --file (fixme) + --refresh) + yes "" | make oldconfig + ;; + + *) + usage + ;; + esac +done + diff --git a/misc/tools/kconfig-frontends/utils/tweak.in.patch b/misc/tools/kconfig-frontends/utils/tweak.in.patch new file mode 100644 index 0000000000..db365143f2 --- /dev/null +++ b/misc/tools/kconfig-frontends/utils/tweak.in.patch @@ -0,0 +1,23 @@ +diff --git a/utils/tweak.in b/utils/tweak.in +--- a/utils/tweak.in ++++ b/utils/tweak.in +@@ -1,8 +1,8 @@ + #!/bin/bash + # Manipulate options in a .config file from the command line + +-# If no prefix forced, use the default CONFIG_ +-CONFIG_="${CONFIG_-CONFIG_}" ++# If no prefix forced, use the default @CONFIG_@ ++CONFIG_="${CONFIG_-@CONFIG_@}" + + usage() { + cat >&2 < Date: Sat, 10 Nov 2012 15:47:45 +0000 Subject: [PATCH 097/206] move lib/ to libc/ to make room for a true lib/ directory. Rename libraries to match git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5328 42af7a65-404d-4744-a932-0658087f49c3 --- misc/tools/README.txt | 56 +- nuttx/COPYING | 10 +- nuttx/ChangeLog | 4 + nuttx/Documentation/NuttXNxFlat.html | 4 +- nuttx/Documentation/NuttxPortingGuide.html | 14 +- nuttx/Documentation/README.html | 4 +- nuttx/Kconfig | 2 +- nuttx/Makefile | 34 +- nuttx/README.txt | 2 +- nuttx/TODO | 14 +- .../configs/stm32f4discovery/ostest/defconfig | 300 +-- nuttx/lib/Kconfig | 275 --- nuttx/lib/Makefile | 136 -- nuttx/lib/README.txt | 85 - nuttx/lib/dirent/Make.defs | 48 - nuttx/lib/dirent/lib_readdirr.c | 122 -- nuttx/lib/dirent/lib_telldir.c | 91 - nuttx/lib/fixedmath/Make.defs | 43 - nuttx/lib/fixedmath/lib_b16atan2.c | 108 -- nuttx/lib/fixedmath/lib_b16cos.c | 64 - nuttx/lib/fixedmath/lib_b16sin.c | 110 -- nuttx/lib/fixedmath/lib_fixedmath.c | 272 --- nuttx/lib/fixedmath/lib_rint.c | 135 -- nuttx/lib/lib.csv | 171 -- nuttx/lib/lib_internal.h | 211 --- nuttx/lib/libgen/Make.defs | 43 - nuttx/lib/libgen/lib_basename.c | 131 -- nuttx/lib/libgen/lib_dirname.c | 144 -- nuttx/lib/math/Kconfig | 26 - nuttx/lib/math/Make.defs | 62 - nuttx/lib/math/lib_acos.c | 46 - nuttx/lib/math/lib_acosf.c | 41 - nuttx/lib/math/lib_acosl.c | 46 - nuttx/lib/math/lib_asin.c | 69 - nuttx/lib/math/lib_asinf.c | 65 - nuttx/lib/math/lib_asinl.c | 69 - nuttx/lib/math/lib_atan.c | 48 - nuttx/lib/math/lib_atan2.c | 86 - nuttx/lib/math/lib_atan2f.c | 81 - nuttx/lib/math/lib_atan2l.c | 87 - nuttx/lib/math/lib_atanf.c | 43 - nuttx/lib/math/lib_atanl.c | 48 - nuttx/lib/math/lib_ceil.c | 52 - nuttx/lib/math/lib_ceilf.c | 47 - nuttx/lib/math/lib_ceill.c | 52 - nuttx/lib/math/lib_cos.c | 46 - nuttx/lib/math/lib_cosf.c | 41 - nuttx/lib/math/lib_cosh.c | 47 - nuttx/lib/math/lib_coshf.c | 42 - nuttx/lib/math/lib_coshl.c | 47 - nuttx/lib/math/lib_cosl.c | 46 - nuttx/lib/math/lib_exp.c | 126 -- nuttx/lib/math/lib_expf.c | 112 -- nuttx/lib/math/lib_expl.c | 126 -- nuttx/lib/math/lib_fabs.c | 46 - nuttx/lib/math/lib_fabsf.c | 41 - nuttx/lib/math/lib_fabsl.c | 46 - nuttx/lib/math/lib_floor.c | 52 - nuttx/lib/math/lib_floorf.c | 47 - nuttx/lib/math/lib_floorl.c | 52 - nuttx/lib/math/lib_fmod.c | 52 - nuttx/lib/math/lib_fmodf.c | 47 - nuttx/lib/math/lib_fmodl.c | 52 - nuttx/lib/math/lib_frexp.c | 47 - nuttx/lib/math/lib_frexpf.c | 42 - nuttx/lib/math/lib_frexpl.c | 47 - nuttx/lib/math/lib_ldexp.c | 46 - nuttx/lib/math/lib_ldexpf.c | 41 - nuttx/lib/math/lib_ldexpl.c | 46 - nuttx/lib/math/lib_libexpi.c | 103 -- nuttx/lib/math/lib_libsqrtapprox.c | 50 - nuttx/lib/math/lib_log.c | 82 - nuttx/lib/math/lib_log10.c | 46 - nuttx/lib/math/lib_log10f.c | 41 - nuttx/lib/math/lib_log10l.c | 46 - nuttx/lib/math/lib_log2.c | 46 - nuttx/lib/math/lib_log2f.c | 41 - nuttx/lib/math/lib_log2l.c | 46 - nuttx/lib/math/lib_logf.c | 77 - nuttx/lib/math/lib_logl.c | 80 - nuttx/lib/math/lib_modf.c | 58 - nuttx/lib/math/lib_modff.c | 55 - nuttx/lib/math/lib_modfl.c | 61 - nuttx/lib/math/lib_pow.c | 46 - nuttx/lib/math/lib_powf.c | 41 - nuttx/lib/math/lib_powl.c | 46 - nuttx/lib/math/lib_sin.c | 114 -- nuttx/lib/math/lib_sinf.c | 104 -- nuttx/lib/math/lib_sinh.c | 47 - nuttx/lib/math/lib_sinhf.c | 42 - nuttx/lib/math/lib_sinhl.c | 47 - nuttx/lib/math/lib_sinl.c | 114 -- nuttx/lib/math/lib_sqrt.c | 99 - nuttx/lib/math/lib_sqrtf.c | 84 - nuttx/lib/math/lib_sqrtl.c | 101 - nuttx/lib/math/lib_tan.c | 46 - nuttx/lib/math/lib_tanf.c | 41 - nuttx/lib/math/lib_tanh.c | 49 - nuttx/lib/math/lib_tanhf.c | 44 - nuttx/lib/math/lib_tanhl.c | 49 - nuttx/lib/math/lib_tanl.c | 46 - nuttx/lib/misc/Make.defs | 69 - nuttx/lib/misc/lib_crc32.c | 123 -- nuttx/lib/misc/lib_dbg.c | 165 -- nuttx/lib/misc/lib_dumpbuffer.c | 129 -- nuttx/lib/misc/lib_filesem.c | 145 -- nuttx/lib/misc/lib_init.c | 207 --- nuttx/lib/misc/lib_match.c | 148 -- nuttx/lib/misc/lib_sendfile.c | 297 --- nuttx/lib/misc/lib_streamsem.c | 90 - nuttx/lib/mqueue/Make.defs | 48 - nuttx/lib/mqueue/mq_getattr.c | 104 -- nuttx/lib/mqueue/mq_setattr.c | 118 -- nuttx/lib/net/Make.defs | 44 - nuttx/lib/net/lib_etherntoa.c | 69 - nuttx/lib/net/lib_htonl.c | 68 - nuttx/lib/net/lib_htons.c | 65 - nuttx/lib/net/lib_inetaddr.c | 74 - nuttx/lib/net/lib_inetntoa.c | 79 - nuttx/lib/net/lib_inetntop.c | 202 -- nuttx/lib/net/lib_inetpton.c | 338 ---- nuttx/lib/pthread/Make.defs | 56 - nuttx/lib/pthread/pthread_attrdestroy.c | 108 -- .../lib/pthread/pthread_attrgetinheritsched.c | 111 -- nuttx/lib/pthread/pthread_attrgetschedparam.c | 110 -- .../lib/pthread/pthread_attrgetschedpolicy.c | 105 -- nuttx/lib/pthread/pthread_attrgetstacksize.c | 106 -- nuttx/lib/pthread/pthread_attrinit.c | 123 -- .../lib/pthread/pthread_attrsetinheritsched.c | 113 -- nuttx/lib/pthread/pthread_attrsetschedparam.c | 108 -- .../lib/pthread/pthread_attrsetschedpolicy.c | 111 -- nuttx/lib/pthread/pthread_attrsetstacksize.c | 106 -- .../lib/pthread/pthread_barrierattrdestroy.c | 102 - .../pthread/pthread_barrierattrgetpshared.c | 101 - nuttx/lib/pthread/pthread_barrierattrinit.c | 101 - .../pthread/pthread_barrierattrsetpshared.c | 111 -- nuttx/lib/pthread/pthread_condattrdestroy.c | 82 - nuttx/lib/pthread/pthread_condattrinit.c | 85 - nuttx/lib/pthread/pthread_mutexattrdestroy.c | 104 -- .../lib/pthread/pthread_mutexattrgetpshared.c | 104 -- nuttx/lib/pthread/pthread_mutexattrgettype.c | 98 - nuttx/lib/pthread/pthread_mutexattrinit.c | 106 -- .../lib/pthread/pthread_mutexattrsetpshared.c | 104 -- nuttx/lib/pthread/pthread_mutexattrsettype.c | 98 - nuttx/lib/queue/Make.defs | 47 - nuttx/lib/queue/dq_addafter.c | 74 - nuttx/lib/queue/dq_addbefore.c | 69 - nuttx/lib/queue/dq_addfirst.c | 74 - nuttx/lib/queue/dq_addlast.c | 74 - nuttx/lib/queue/dq_rem.c | 84 - nuttx/lib/queue/dq_remfirst.c | 82 - nuttx/lib/queue/dq_remlast.c | 78 - nuttx/lib/queue/sq_addafter.c | 71 - nuttx/lib/queue/sq_addfirst.c | 67 - nuttx/lib/queue/sq_addlast.c | 72 - nuttx/lib/queue/sq_rem.c | 83 - nuttx/lib/queue/sq_remafter.c | 79 - nuttx/lib/queue/sq_remfirst.c | 76 - nuttx/lib/queue/sq_remlast.c | 87 - nuttx/lib/sched/Make.defs | 43 - nuttx/lib/sched/sched_getprioritymax.c | 100 - nuttx/lib/sched/sched_getprioritymin.c | 100 - nuttx/lib/semaphore/Make.defs | 43 - nuttx/lib/semaphore/sem_getvalue.c | 108 -- nuttx/lib/semaphore/sem_init.c | 125 -- nuttx/lib/signal/Make.defs | 47 - nuttx/lib/signal/sig_addset.c | 100 - nuttx/lib/signal/sig_delset.c | 100 - nuttx/lib/signal/sig_emptyset.c | 88 - nuttx/lib/signal/sig_fillset.c | 88 - nuttx/lib/signal/sig_ismember.c | 101 - nuttx/lib/stdio/Make.defs | 85 - nuttx/lib/stdio/lib_asprintf.c | 105 -- nuttx/lib/stdio/lib_avsprintf.c | 146 -- nuttx/lib/stdio/lib_clearerr.c | 69 - nuttx/lib/stdio/lib_dtoa.c | 1641 ----------------- nuttx/lib/stdio/lib_fclose.c | 154 -- nuttx/lib/stdio/lib_feof.c | 77 - nuttx/lib/stdio/lib_ferror.c | 90 - nuttx/lib/stdio/lib_fflush.c | 132 -- nuttx/lib/stdio/lib_fgetc.c | 101 - nuttx/lib/stdio/lib_fgetpos.c | 123 -- nuttx/lib/stdio/lib_fgets.c | 207 --- nuttx/lib/stdio/lib_fileno.c | 70 - nuttx/lib/stdio/lib_fopen.c | 299 --- nuttx/lib/stdio/lib_fprintf.c | 93 - nuttx/lib/stdio/lib_fputc.c | 113 -- nuttx/lib/stdio/lib_fputs.c | 220 --- nuttx/lib/stdio/lib_fread.c | 101 - nuttx/lib/stdio/lib_fseek.c | 138 -- nuttx/lib/stdio/lib_fsetpos.c | 116 -- nuttx/lib/stdio/lib_ftell.c | 129 -- nuttx/lib/stdio/lib_fwrite.c | 99 - nuttx/lib/stdio/lib_gets.c | 120 -- nuttx/lib/stdio/lib_libdtoa.c | 304 --- nuttx/lib/stdio/lib_libfflush.c | 202 -- nuttx/lib/stdio/lib_libflushall.c | 137 -- nuttx/lib/stdio/lib_libfread.c | 315 ---- nuttx/lib/stdio/lib_libfwrite.c | 179 -- nuttx/lib/stdio/lib_libnoflush.c | 103 -- nuttx/lib/stdio/lib_libsprintf.c | 90 - nuttx/lib/stdio/lib_libvsprintf.c | 1620 ---------------- nuttx/lib/stdio/lib_lowinstream.c | 102 - nuttx/lib/stdio/lib_lowoutstream.c | 97 - nuttx/lib/stdio/lib_lowprintf.c | 128 -- nuttx/lib/stdio/lib_meminstream.c | 104 -- nuttx/lib/stdio/lib_memoutstream.c | 105 -- nuttx/lib/stdio/lib_nullinstream.c | 79 - nuttx/lib/stdio/lib_nulloutstream.c | 84 - nuttx/lib/stdio/lib_perror.c | 99 - nuttx/lib/stdio/lib_printf.c | 109 -- nuttx/lib/stdio/lib_puts.c | 130 -- nuttx/lib/stdio/lib_rawinstream.c | 107 -- nuttx/lib/stdio/lib_rawoutstream.c | 115 -- nuttx/lib/stdio/lib_rawprintf.c | 151 -- nuttx/lib/stdio/lib_rdflush.c | 144 -- nuttx/lib/stdio/lib_snprintf.c | 99 - nuttx/lib/stdio/lib_sprintf.c | 95 - nuttx/lib/stdio/lib_sscanf.c | 507 ----- nuttx/lib/stdio/lib_stdinstream.c | 99 - nuttx/lib/stdio/lib_stdoutstream.c | 147 -- nuttx/lib/stdio/lib_syslogstream.c | 122 -- nuttx/lib/stdio/lib_ungetc.c | 121 -- nuttx/lib/stdio/lib_vfprintf.c | 102 - nuttx/lib/stdio/lib_vprintf.c | 92 - nuttx/lib/stdio/lib_vsnprintf.c | 96 - nuttx/lib/stdio/lib_vsprintf.c | 92 - nuttx/lib/stdio/lib_wrflush.c | 134 -- nuttx/lib/stdio/lib_zeroinstream.c | 79 - nuttx/lib/stdlib/Make.defs | 44 - nuttx/lib/stdlib/lib_abort.c | 121 -- nuttx/lib/stdlib/lib_abs.c | 54 - nuttx/lib/stdlib/lib_imaxabs.c | 54 - nuttx/lib/stdlib/lib_labs.c | 54 - nuttx/lib/stdlib/lib_llabs.c | 57 - nuttx/lib/stdlib/lib_qsort.c | 238 --- nuttx/lib/stdlib/lib_rand.c | 220 --- nuttx/lib/string/Make.defs | 58 - nuttx/lib/string/lib_checkbase.c | 115 -- nuttx/lib/string/lib_isbasedigit.c | 105 -- nuttx/lib/string/lib_memccpy.c | 99 - nuttx/lib/string/lib_memchr.c | 80 - nuttx/lib/string/lib_memcmp.c | 74 - nuttx/lib/string/lib_memcpy.c | 64 - nuttx/lib/string/lib_memmove.c | 77 - nuttx/lib/string/lib_memset.c | 188 -- nuttx/lib/string/lib_skipspace.c | 69 - nuttx/lib/string/lib_strcasecmp.c | 65 - nuttx/lib/string/lib_strcasestr.c | 134 -- nuttx/lib/string/lib_strcat.c | 62 - nuttx/lib/string/lib_strchr.c | 78 - nuttx/lib/string/lib_strcmp.c | 59 - nuttx/lib/string/lib_strcpy.c | 55 - nuttx/lib/string/lib_strcspn.c | 67 - nuttx/lib/string/lib_strdup.c | 62 - nuttx/lib/string/lib_strerror.c | 375 ---- nuttx/lib/string/lib_strlen.c | 55 - nuttx/lib/string/lib_strncasecmp.c | 70 - nuttx/lib/string/lib_strncat.c | 62 - nuttx/lib/string/lib_strncmp.c | 65 - nuttx/lib/string/lib_strncpy.c | 57 - nuttx/lib/string/lib_strndup.c | 93 - nuttx/lib/string/lib_strnlen.c | 62 - nuttx/lib/string/lib_strpbrk.c | 85 - nuttx/lib/string/lib_strrchr.c | 68 - nuttx/lib/string/lib_strspn.c | 66 - nuttx/lib/string/lib_strstr.c | 104 -- nuttx/lib/string/lib_strtod.c | 241 --- nuttx/lib/string/lib_strtok.c | 87 - nuttx/lib/string/lib_strtokr.c | 157 -- nuttx/lib/string/lib_strtol.c | 103 -- nuttx/lib/string/lib_strtoll.c | 107 -- nuttx/lib/string/lib_strtoul.c | 98 - nuttx/lib/string/lib_strtoull.c | 100 - nuttx/lib/string/lib_vikmemcpy.c | 348 ---- nuttx/lib/termios/Make.defs | 54 - nuttx/lib/termios/lib_cfgetspeed.c | 93 - nuttx/lib/termios/lib_cfsetspeed.c | 116 -- nuttx/lib/termios/lib_tcflush.c | 88 - nuttx/lib/termios/lib_tcgetattr.c | 93 - nuttx/lib/termios/lib_tcsetattr.c | 122 -- nuttx/lib/time/Make.defs | 44 - nuttx/lib/time/lib_calendar2utc.c | 209 --- nuttx/lib/time/lib_daysbeforemonth.c | 102 - nuttx/lib/time/lib_gmtime.c | 93 - nuttx/lib/time/lib_gmtimer.c | 355 ---- nuttx/lib/time/lib_isleapyear.c | 88 - nuttx/lib/time/lib_mktime.c | 141 -- nuttx/lib/time/lib_strftime.c | 398 ---- nuttx/lib/time/lib_time.c | 110 -- nuttx/lib/unistd/Make.defs | 49 - nuttx/lib/unistd/lib_chdir.c | 179 -- nuttx/lib/unistd/lib_getcwd.c | 132 -- nuttx/lib/unistd/lib_getopt.c | 269 --- nuttx/lib/unistd/lib_getoptargp.c | 73 - nuttx/lib/unistd/lib_getoptindp.c | 73 - nuttx/lib/unistd/lib_getoptoptp.c | 73 - nuttx/libxx/Makefile | 2 +- 298 files changed, 133 insertions(+), 32321 deletions(-) delete mode 100644 nuttx/lib/Kconfig delete mode 100644 nuttx/lib/Makefile delete mode 100644 nuttx/lib/README.txt delete mode 100644 nuttx/lib/dirent/Make.defs delete mode 100644 nuttx/lib/dirent/lib_readdirr.c delete mode 100644 nuttx/lib/dirent/lib_telldir.c delete mode 100644 nuttx/lib/fixedmath/Make.defs delete mode 100644 nuttx/lib/fixedmath/lib_b16atan2.c delete mode 100644 nuttx/lib/fixedmath/lib_b16cos.c delete mode 100644 nuttx/lib/fixedmath/lib_b16sin.c delete mode 100644 nuttx/lib/fixedmath/lib_fixedmath.c delete mode 100644 nuttx/lib/fixedmath/lib_rint.c delete mode 100644 nuttx/lib/lib.csv delete mode 100644 nuttx/lib/lib_internal.h delete mode 100644 nuttx/lib/libgen/Make.defs delete mode 100644 nuttx/lib/libgen/lib_basename.c delete mode 100644 nuttx/lib/libgen/lib_dirname.c delete mode 100644 nuttx/lib/math/Kconfig delete mode 100644 nuttx/lib/math/Make.defs delete mode 100644 nuttx/lib/math/lib_acos.c delete mode 100644 nuttx/lib/math/lib_acosf.c delete mode 100644 nuttx/lib/math/lib_acosl.c delete mode 100644 nuttx/lib/math/lib_asin.c delete mode 100644 nuttx/lib/math/lib_asinf.c delete mode 100644 nuttx/lib/math/lib_asinl.c delete mode 100644 nuttx/lib/math/lib_atan.c delete mode 100644 nuttx/lib/math/lib_atan2.c delete mode 100644 nuttx/lib/math/lib_atan2f.c delete mode 100644 nuttx/lib/math/lib_atan2l.c delete mode 100644 nuttx/lib/math/lib_atanf.c delete mode 100644 nuttx/lib/math/lib_atanl.c delete mode 100644 nuttx/lib/math/lib_ceil.c delete mode 100644 nuttx/lib/math/lib_ceilf.c delete mode 100644 nuttx/lib/math/lib_ceill.c delete mode 100644 nuttx/lib/math/lib_cos.c delete mode 100644 nuttx/lib/math/lib_cosf.c delete mode 100644 nuttx/lib/math/lib_cosh.c delete mode 100644 nuttx/lib/math/lib_coshf.c delete mode 100644 nuttx/lib/math/lib_coshl.c delete mode 100644 nuttx/lib/math/lib_cosl.c delete mode 100644 nuttx/lib/math/lib_exp.c delete mode 100644 nuttx/lib/math/lib_expf.c delete mode 100644 nuttx/lib/math/lib_expl.c delete mode 100644 nuttx/lib/math/lib_fabs.c delete mode 100644 nuttx/lib/math/lib_fabsf.c delete mode 100644 nuttx/lib/math/lib_fabsl.c delete mode 100644 nuttx/lib/math/lib_floor.c delete mode 100644 nuttx/lib/math/lib_floorf.c delete mode 100644 nuttx/lib/math/lib_floorl.c delete mode 100644 nuttx/lib/math/lib_fmod.c delete mode 100644 nuttx/lib/math/lib_fmodf.c delete mode 100644 nuttx/lib/math/lib_fmodl.c delete mode 100644 nuttx/lib/math/lib_frexp.c delete mode 100644 nuttx/lib/math/lib_frexpf.c delete mode 100644 nuttx/lib/math/lib_frexpl.c delete mode 100644 nuttx/lib/math/lib_ldexp.c delete mode 100644 nuttx/lib/math/lib_ldexpf.c delete mode 100644 nuttx/lib/math/lib_ldexpl.c delete mode 100644 nuttx/lib/math/lib_libexpi.c delete mode 100644 nuttx/lib/math/lib_libsqrtapprox.c delete mode 100644 nuttx/lib/math/lib_log.c delete mode 100644 nuttx/lib/math/lib_log10.c delete mode 100644 nuttx/lib/math/lib_log10f.c delete mode 100644 nuttx/lib/math/lib_log10l.c delete mode 100644 nuttx/lib/math/lib_log2.c delete mode 100644 nuttx/lib/math/lib_log2f.c delete mode 100644 nuttx/lib/math/lib_log2l.c delete mode 100644 nuttx/lib/math/lib_logf.c delete mode 100644 nuttx/lib/math/lib_logl.c delete mode 100644 nuttx/lib/math/lib_modf.c delete mode 100644 nuttx/lib/math/lib_modff.c delete mode 100644 nuttx/lib/math/lib_modfl.c delete mode 100644 nuttx/lib/math/lib_pow.c delete mode 100644 nuttx/lib/math/lib_powf.c delete mode 100644 nuttx/lib/math/lib_powl.c delete mode 100644 nuttx/lib/math/lib_sin.c delete mode 100644 nuttx/lib/math/lib_sinf.c delete mode 100644 nuttx/lib/math/lib_sinh.c delete mode 100644 nuttx/lib/math/lib_sinhf.c delete mode 100644 nuttx/lib/math/lib_sinhl.c delete mode 100644 nuttx/lib/math/lib_sinl.c delete mode 100644 nuttx/lib/math/lib_sqrt.c delete mode 100644 nuttx/lib/math/lib_sqrtf.c delete mode 100644 nuttx/lib/math/lib_sqrtl.c delete mode 100644 nuttx/lib/math/lib_tan.c delete mode 100644 nuttx/lib/math/lib_tanf.c delete mode 100644 nuttx/lib/math/lib_tanh.c delete mode 100644 nuttx/lib/math/lib_tanhf.c delete mode 100644 nuttx/lib/math/lib_tanhl.c delete mode 100644 nuttx/lib/math/lib_tanl.c delete mode 100644 nuttx/lib/misc/Make.defs delete mode 100644 nuttx/lib/misc/lib_crc32.c delete mode 100644 nuttx/lib/misc/lib_dbg.c delete mode 100644 nuttx/lib/misc/lib_dumpbuffer.c delete mode 100644 nuttx/lib/misc/lib_filesem.c delete mode 100644 nuttx/lib/misc/lib_init.c delete mode 100644 nuttx/lib/misc/lib_match.c delete mode 100644 nuttx/lib/misc/lib_sendfile.c delete mode 100644 nuttx/lib/misc/lib_streamsem.c delete mode 100644 nuttx/lib/mqueue/Make.defs delete mode 100644 nuttx/lib/mqueue/mq_getattr.c delete mode 100644 nuttx/lib/mqueue/mq_setattr.c delete mode 100644 nuttx/lib/net/Make.defs delete mode 100644 nuttx/lib/net/lib_etherntoa.c delete mode 100644 nuttx/lib/net/lib_htonl.c delete mode 100644 nuttx/lib/net/lib_htons.c delete mode 100644 nuttx/lib/net/lib_inetaddr.c delete mode 100644 nuttx/lib/net/lib_inetntoa.c delete mode 100644 nuttx/lib/net/lib_inetntop.c delete mode 100644 nuttx/lib/net/lib_inetpton.c delete mode 100644 nuttx/lib/pthread/Make.defs delete mode 100644 nuttx/lib/pthread/pthread_attrdestroy.c delete mode 100644 nuttx/lib/pthread/pthread_attrgetinheritsched.c delete mode 100644 nuttx/lib/pthread/pthread_attrgetschedparam.c delete mode 100644 nuttx/lib/pthread/pthread_attrgetschedpolicy.c delete mode 100644 nuttx/lib/pthread/pthread_attrgetstacksize.c delete mode 100644 nuttx/lib/pthread/pthread_attrinit.c delete mode 100644 nuttx/lib/pthread/pthread_attrsetinheritsched.c delete mode 100644 nuttx/lib/pthread/pthread_attrsetschedparam.c delete mode 100644 nuttx/lib/pthread/pthread_attrsetschedpolicy.c delete mode 100644 nuttx/lib/pthread/pthread_attrsetstacksize.c delete mode 100644 nuttx/lib/pthread/pthread_barrierattrdestroy.c delete mode 100644 nuttx/lib/pthread/pthread_barrierattrgetpshared.c delete mode 100644 nuttx/lib/pthread/pthread_barrierattrinit.c delete mode 100644 nuttx/lib/pthread/pthread_barrierattrsetpshared.c delete mode 100644 nuttx/lib/pthread/pthread_condattrdestroy.c delete mode 100644 nuttx/lib/pthread/pthread_condattrinit.c delete mode 100644 nuttx/lib/pthread/pthread_mutexattrdestroy.c delete mode 100644 nuttx/lib/pthread/pthread_mutexattrgetpshared.c delete mode 100644 nuttx/lib/pthread/pthread_mutexattrgettype.c delete mode 100644 nuttx/lib/pthread/pthread_mutexattrinit.c delete mode 100644 nuttx/lib/pthread/pthread_mutexattrsetpshared.c delete mode 100644 nuttx/lib/pthread/pthread_mutexattrsettype.c delete mode 100644 nuttx/lib/queue/Make.defs delete mode 100644 nuttx/lib/queue/dq_addafter.c delete mode 100644 nuttx/lib/queue/dq_addbefore.c delete mode 100644 nuttx/lib/queue/dq_addfirst.c delete mode 100644 nuttx/lib/queue/dq_addlast.c delete mode 100644 nuttx/lib/queue/dq_rem.c delete mode 100644 nuttx/lib/queue/dq_remfirst.c delete mode 100644 nuttx/lib/queue/dq_remlast.c delete mode 100644 nuttx/lib/queue/sq_addafter.c delete mode 100644 nuttx/lib/queue/sq_addfirst.c delete mode 100644 nuttx/lib/queue/sq_addlast.c delete mode 100644 nuttx/lib/queue/sq_rem.c delete mode 100644 nuttx/lib/queue/sq_remafter.c delete mode 100644 nuttx/lib/queue/sq_remfirst.c delete mode 100644 nuttx/lib/queue/sq_remlast.c delete mode 100644 nuttx/lib/sched/Make.defs delete mode 100644 nuttx/lib/sched/sched_getprioritymax.c delete mode 100644 nuttx/lib/sched/sched_getprioritymin.c delete mode 100644 nuttx/lib/semaphore/Make.defs delete mode 100644 nuttx/lib/semaphore/sem_getvalue.c delete mode 100644 nuttx/lib/semaphore/sem_init.c delete mode 100644 nuttx/lib/signal/Make.defs delete mode 100644 nuttx/lib/signal/sig_addset.c delete mode 100644 nuttx/lib/signal/sig_delset.c delete mode 100644 nuttx/lib/signal/sig_emptyset.c delete mode 100644 nuttx/lib/signal/sig_fillset.c delete mode 100644 nuttx/lib/signal/sig_ismember.c delete mode 100644 nuttx/lib/stdio/Make.defs delete mode 100644 nuttx/lib/stdio/lib_asprintf.c delete mode 100644 nuttx/lib/stdio/lib_avsprintf.c delete mode 100644 nuttx/lib/stdio/lib_clearerr.c delete mode 100644 nuttx/lib/stdio/lib_dtoa.c delete mode 100644 nuttx/lib/stdio/lib_fclose.c delete mode 100644 nuttx/lib/stdio/lib_feof.c delete mode 100644 nuttx/lib/stdio/lib_ferror.c delete mode 100644 nuttx/lib/stdio/lib_fflush.c delete mode 100644 nuttx/lib/stdio/lib_fgetc.c delete mode 100644 nuttx/lib/stdio/lib_fgetpos.c delete mode 100644 nuttx/lib/stdio/lib_fgets.c delete mode 100644 nuttx/lib/stdio/lib_fileno.c delete mode 100644 nuttx/lib/stdio/lib_fopen.c delete mode 100644 nuttx/lib/stdio/lib_fprintf.c delete mode 100644 nuttx/lib/stdio/lib_fputc.c delete mode 100644 nuttx/lib/stdio/lib_fputs.c delete mode 100644 nuttx/lib/stdio/lib_fread.c delete mode 100644 nuttx/lib/stdio/lib_fseek.c delete mode 100644 nuttx/lib/stdio/lib_fsetpos.c delete mode 100644 nuttx/lib/stdio/lib_ftell.c delete mode 100644 nuttx/lib/stdio/lib_fwrite.c delete mode 100644 nuttx/lib/stdio/lib_gets.c delete mode 100644 nuttx/lib/stdio/lib_libdtoa.c delete mode 100644 nuttx/lib/stdio/lib_libfflush.c delete mode 100644 nuttx/lib/stdio/lib_libflushall.c delete mode 100644 nuttx/lib/stdio/lib_libfread.c delete mode 100644 nuttx/lib/stdio/lib_libfwrite.c delete mode 100644 nuttx/lib/stdio/lib_libnoflush.c delete mode 100644 nuttx/lib/stdio/lib_libsprintf.c delete mode 100644 nuttx/lib/stdio/lib_libvsprintf.c delete mode 100644 nuttx/lib/stdio/lib_lowinstream.c delete mode 100644 nuttx/lib/stdio/lib_lowoutstream.c delete mode 100644 nuttx/lib/stdio/lib_lowprintf.c delete mode 100644 nuttx/lib/stdio/lib_meminstream.c delete mode 100644 nuttx/lib/stdio/lib_memoutstream.c delete mode 100644 nuttx/lib/stdio/lib_nullinstream.c delete mode 100644 nuttx/lib/stdio/lib_nulloutstream.c delete mode 100644 nuttx/lib/stdio/lib_perror.c delete mode 100644 nuttx/lib/stdio/lib_printf.c delete mode 100644 nuttx/lib/stdio/lib_puts.c delete mode 100644 nuttx/lib/stdio/lib_rawinstream.c delete mode 100644 nuttx/lib/stdio/lib_rawoutstream.c delete mode 100644 nuttx/lib/stdio/lib_rawprintf.c delete mode 100644 nuttx/lib/stdio/lib_rdflush.c delete mode 100644 nuttx/lib/stdio/lib_snprintf.c delete mode 100644 nuttx/lib/stdio/lib_sprintf.c delete mode 100644 nuttx/lib/stdio/lib_sscanf.c delete mode 100644 nuttx/lib/stdio/lib_stdinstream.c delete mode 100644 nuttx/lib/stdio/lib_stdoutstream.c delete mode 100644 nuttx/lib/stdio/lib_syslogstream.c delete mode 100644 nuttx/lib/stdio/lib_ungetc.c delete mode 100644 nuttx/lib/stdio/lib_vfprintf.c delete mode 100644 nuttx/lib/stdio/lib_vprintf.c delete mode 100644 nuttx/lib/stdio/lib_vsnprintf.c delete mode 100644 nuttx/lib/stdio/lib_vsprintf.c delete mode 100644 nuttx/lib/stdio/lib_wrflush.c delete mode 100644 nuttx/lib/stdio/lib_zeroinstream.c delete mode 100644 nuttx/lib/stdlib/Make.defs delete mode 100644 nuttx/lib/stdlib/lib_abort.c delete mode 100644 nuttx/lib/stdlib/lib_abs.c delete mode 100644 nuttx/lib/stdlib/lib_imaxabs.c delete mode 100644 nuttx/lib/stdlib/lib_labs.c delete mode 100644 nuttx/lib/stdlib/lib_llabs.c delete mode 100644 nuttx/lib/stdlib/lib_qsort.c delete mode 100644 nuttx/lib/stdlib/lib_rand.c delete mode 100644 nuttx/lib/string/Make.defs delete mode 100644 nuttx/lib/string/lib_checkbase.c delete mode 100644 nuttx/lib/string/lib_isbasedigit.c delete mode 100644 nuttx/lib/string/lib_memccpy.c delete mode 100644 nuttx/lib/string/lib_memchr.c delete mode 100644 nuttx/lib/string/lib_memcmp.c delete mode 100644 nuttx/lib/string/lib_memcpy.c delete mode 100644 nuttx/lib/string/lib_memmove.c delete mode 100644 nuttx/lib/string/lib_memset.c delete mode 100644 nuttx/lib/string/lib_skipspace.c delete mode 100644 nuttx/lib/string/lib_strcasecmp.c delete mode 100644 nuttx/lib/string/lib_strcasestr.c delete mode 100644 nuttx/lib/string/lib_strcat.c delete mode 100644 nuttx/lib/string/lib_strchr.c delete mode 100644 nuttx/lib/string/lib_strcmp.c delete mode 100644 nuttx/lib/string/lib_strcpy.c delete mode 100644 nuttx/lib/string/lib_strcspn.c delete mode 100644 nuttx/lib/string/lib_strdup.c delete mode 100644 nuttx/lib/string/lib_strerror.c delete mode 100644 nuttx/lib/string/lib_strlen.c delete mode 100644 nuttx/lib/string/lib_strncasecmp.c delete mode 100644 nuttx/lib/string/lib_strncat.c delete mode 100644 nuttx/lib/string/lib_strncmp.c delete mode 100644 nuttx/lib/string/lib_strncpy.c delete mode 100644 nuttx/lib/string/lib_strndup.c delete mode 100644 nuttx/lib/string/lib_strnlen.c delete mode 100644 nuttx/lib/string/lib_strpbrk.c delete mode 100644 nuttx/lib/string/lib_strrchr.c delete mode 100644 nuttx/lib/string/lib_strspn.c delete mode 100644 nuttx/lib/string/lib_strstr.c delete mode 100644 nuttx/lib/string/lib_strtod.c delete mode 100644 nuttx/lib/string/lib_strtok.c delete mode 100644 nuttx/lib/string/lib_strtokr.c delete mode 100644 nuttx/lib/string/lib_strtol.c delete mode 100644 nuttx/lib/string/lib_strtoll.c delete mode 100644 nuttx/lib/string/lib_strtoul.c delete mode 100644 nuttx/lib/string/lib_strtoull.c delete mode 100644 nuttx/lib/string/lib_vikmemcpy.c delete mode 100644 nuttx/lib/termios/Make.defs delete mode 100644 nuttx/lib/termios/lib_cfgetspeed.c delete mode 100644 nuttx/lib/termios/lib_cfsetspeed.c delete mode 100644 nuttx/lib/termios/lib_tcflush.c delete mode 100644 nuttx/lib/termios/lib_tcgetattr.c delete mode 100644 nuttx/lib/termios/lib_tcsetattr.c delete mode 100644 nuttx/lib/time/Make.defs delete mode 100644 nuttx/lib/time/lib_calendar2utc.c delete mode 100644 nuttx/lib/time/lib_daysbeforemonth.c delete mode 100644 nuttx/lib/time/lib_gmtime.c delete mode 100644 nuttx/lib/time/lib_gmtimer.c delete mode 100644 nuttx/lib/time/lib_isleapyear.c delete mode 100644 nuttx/lib/time/lib_mktime.c delete mode 100644 nuttx/lib/time/lib_strftime.c delete mode 100644 nuttx/lib/time/lib_time.c delete mode 100644 nuttx/lib/unistd/Make.defs delete mode 100644 nuttx/lib/unistd/lib_chdir.c delete mode 100644 nuttx/lib/unistd/lib_getcwd.c delete mode 100644 nuttx/lib/unistd/lib_getopt.c delete mode 100644 nuttx/lib/unistd/lib_getoptargp.c delete mode 100644 nuttx/lib/unistd/lib_getoptindp.c delete mode 100644 nuttx/lib/unistd/lib_getoptoptp.c diff --git a/misc/tools/README.txt b/misc/tools/README.txt index 9faba836db..fff94cd3f5 100644 --- a/misc/tools/README.txt +++ b/misc/tools/README.txt @@ -2,6 +2,7 @@ misc/tools/README.txt ===================== genromfs-0.5.2.tar.gz +--------------------- This is a snapshot of the genromfs tarball taken from http://sourceforge.net/projects/romfs/. This snapshot is provided to @@ -11,6 +12,7 @@ genromfs-0.5.2.tar.gz from the buildroot. kconfig-frontends +----------------- This is a snapshot of the kconfig-frontends version 3.6.0 tarball taken from http://ymorin.is-a-geek.org/projects/kconfig-frontends. @@ -29,9 +31,10 @@ kconfig-frontends make install kconfig-frontends-3.3.0-1-libintl.patch +--------------------------------------- The above build instructions did not work for me under my Cygwin - installation with kconfig-frontends-4.4.0. This patch is a awful hack + installation with kconfig-frontends-3.3.0. This patch is a awful hack but will successfully build 'mconf' under Cygwin. cat kconfig-frontends-3.3.0-1-libintl.patch | patch -p0 @@ -48,5 +51,56 @@ kconfig-frontends-3.3.0-1-libintl.patch http://ymorin.is-a-geek.org/download/kconfig-frontends/ kconfig-macos.path +------------------ This is a patch to make the kconfig-frontends-3.3.0 build on Mac OS X. + +kconfig-frontends for Windows +============================= + +From http://tech.groups.yahoo.com/group/nuttx/message/2900: + +"The build was quite simple: + +I used mingw installer and I had to install two packages that the +automated mingw setup does not bring by default: + + * mingw-get update + * mingw-get install mingw32-pdcurses mingw32-libpdcurses + * mingw-get install msys-regex msys-libregex + +(grep the output of mingw-get list if I got the names wrong) + +Then I had to change some things in mconf code, it was quite simple to +understand the make errors. + + * The first of them is to disable any use of uname() in symbol.c and + replace the uname output by a constant string value (I used MINGW32-MSYS), + + * The second one is related to the second parameter to mkdir() that has + to disappear for windows (we don't care about folder rights) in confdata.c; + + * And the last one of them involves #undef bool in dialog.h before including + curses.h (CURSES_LOC), around line 30. + +I wrapped all of my changes in #if(n)def __MINGW32__, but that is not +sufficient to make that work everywhere, I think. + +So mconf itself has some portability issues that shall be managed in a +cleaner way, what I did was just hacks, I don't think they are +acceptable by mconf upstream maintainers. + +Here is the magic incantation to get the whole thing working. It seems +that the configure script is not so good and does not bring the required +bits to link libregex. + + CFLAGS="-I/mingw/include -I/usr/include" LDFLAGS="-Bstatic -L/mingw/lib + -L/usr/lib -lregex" ./configure --enable-frontends=mconf --enable-static + --disable-shared + +So the message I want to pass is that native "make menuconfig" in +windows IS POSSIBLE, I have done it in a few minutes." + +"Oops, forgot something, I had to bring a gperf binary from the gnuwin32 project." + +- Sebastien Lorquet diff --git a/nuttx/COPYING b/nuttx/COPYING index 4cf66a5965..b3655265d6 100644 --- a/nuttx/COPYING +++ b/nuttx/COPYING @@ -163,8 +163,8 @@ dtoa(): "This product includes software developed by the University of California, Berkeley and its contributors." -lib/string/lib_vikmemcpy.c -^^^^^^^^^^^^^^^^^^^^^^^^^^ +libc/string/lib_vikmemcpy.c +^^^^^^^^^^^^^^^^^^^^^^^^^^^ If you enable CONFIG_MEMCPY_VIK, then you will build with the optimized version of memcpy from Daniel Vik. Licensing information for that version @@ -192,10 +192,10 @@ lib/string/lib_vikmemcpy.c 3. This notice may not be removed or altered from any source distribution. -lib/math -^^^^^^^^ +libc/math +^^^^^^^^^ - If you enable CONFIG_LIB, you will build the math library at lib/math. + If you enable CONFIG_LIB, you will build the math library at libc/math. This library was taken from the math library developed for the Rhombus OS by Nick Johnson (https://github.com/nickbjohnson4224/rhombus). This port was contributed by Darcy Gong. The Rhombus math library has this diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 247704b7a0..c63dbe62b2 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3591,3 +3591,7 @@ are also more subject to the "fat, flat line bug" that I need to fix someday. See http://www.nuttx.org/doku.php?id=wiki:graphics:nxgraphics for a description of the fat, flat line bug. + * libc: Renamed nuttx/lib to nuttx/libc to make space for a true lib/ + directory that will be forthcoming. Also rename libraries: liblib.a -> libc.a, + libulib.a -> libuc.a, libklib.a -> libkc.a, liblibxx.a ->libcxx.a. + (I will probably, eventually rename libxx to libcxx for consistency) diff --git a/nuttx/Documentation/NuttXNxFlat.html b/nuttx/Documentation/NuttXNxFlat.html index 2e6d2f59a8..3a2ed80460 100644 --- a/nuttx/Documentation/NuttXNxFlat.html +++ b/nuttx/Documentation/NuttXNxFlat.html @@ -407,7 +407,7 @@ any following arguments. nuttx/syscall/syscall.csv that describes the NuttX RTOS interface, and
  • - nuttx/lib/lib/csv that describes the NuttX C library interface. + nuttx/libc/lib.csv that describes the NuttX C library interface.
    • @@ -424,7 +424,7 @@ Where:
       

         cd nuttx/tools
        -cat ../syscall/syscall.csv ../lib/lib.csv | sort >tmp.csv
        +cat ../syscall/syscall.csv ../libc/lib.csv | sort >tmp.csv
         ./mksymtab.exe tmp.csv tmp.c
         
      diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index a2c58b41f8..e602d2cd37 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -52,7 +52,7 @@ 2.6 nuttx/fs/
      2.7 nuttx/graphics/
      2.8 nuttx/include/
      - 2.9 nuttx/lib/
      + 2.9 nuttx/libc/
      2.10 nuttx/libxx/
      2.11 nuttx/mm/
      2.12 nuttx/net
      @@ -230,9 +230,9 @@ | | | `-- (more standard header files) | | |-- (non-standard include sub-directories) | | `-- (non-standard header files) -| |-- lib/ +| |-- libc/ | | |-- Makefile -| | `-- (lib source files) +| | `-- (libc source files) | |-- libxx/ | | |-- Makefile | | `-- (libxx management source files) @@ -1160,15 +1160,15 @@ include/ `-- (More standard header files)
    -

    2.9 nuttx/lib

    +

    2.9 nuttx/libc

    This directory holds a collection of standard libc-like functions with custom interfaces into NuttX.

    - Normally the logic in this file builds to a single library (liblib.a). + Normally the logic in this file builds to a single library (libc.a). However, if NuttX is built as a separately compiled kernel (with CONFIG_NUTTX_KERNEL=y), then the contents of this directory are built as two libraries: - One for use by user programs (libulib.a) and one for use only within the <kernel> space (libklib.a). + One for use by user programs (libuc.a) and one for use only within the <kernel> space (libkc.a).

    These user/kernel space libraries (along with the sycalls of nuttx/syscall) are needed to support the two differing protection domains. @@ -1177,7 +1177,7 @@ include/ Directory structure:

      -lib/
      +libc/
       |-- libgen/
       |   `-- (Implementation of functions from libgen.h)
       |-- math/
      diff --git a/nuttx/Documentation/README.html b/nuttx/Documentation/README.html
      index 61d5c43af1..0a4cc93b0c 100644
      --- a/nuttx/Documentation/README.html
      +++ b/nuttx/Documentation/README.html
      @@ -236,8 +236,8 @@
        |   |       `- README.txt
        |   |- graphics/
        |   |   `- README.txt
      - |   |- lib/
      - |   |   `- README.txt
      + |   |- libc/
      + |   |   `- README.txt
        |   |- libxx/
        |   |   `- README.txt
        |   |- mm/
      diff --git a/nuttx/Kconfig b/nuttx/Kconfig
      index 90fe74f257..13e92ebf2c 100644
      --- a/nuttx/Kconfig
      +++ b/nuttx/Kconfig
      @@ -467,7 +467,7 @@ source binfmt/Kconfig
       endmenu
       
       menu "Library Routines"
      -source lib/Kconfig
      +source libc/Kconfig
       source libxx/Kconfig
       endmenu
       
      diff --git a/nuttx/Makefile b/nuttx/Makefile
      index 8235854fd1..c1060c34f7 100644
      --- a/nuttx/Makefile
      +++ b/nuttx/Makefile
      @@ -115,14 +115,14 @@ ifeq ($(CONFIG_NUTTX_KERNEL),y)
       
       NONFSDIRS += syscall
       CONTEXTDIRS += syscall
      -USERDIRS += syscall lib mm $(USER_ADDONS)
      +USERDIRS += syscall libc mm $(USER_ADDONS)
       ifeq ($(CONFIG_HAVE_CXX),y)
       USERDIRS += libxx
       endif
       
       else
       
      -NONFSDIRS += lib mm
      +NONFSDIRS += libc mm
       OTHERDIRS += syscall $(USER_ADDONS)
       ifeq ($(CONFIG_HAVE_CXX),y)
       NONFSDIRS += libxx
      @@ -197,10 +197,10 @@ USERLIBS =
       # is placed in user space (only).
       
       ifeq ($(CONFIG_NUTTX_KERNEL),y)
      -NUTTXLIBS += syscall/libstubs$(LIBEXT) lib/libklib$(LIBEXT)
      -USERLIBS += syscall/libproxies$(LIBEXT) lib/libulib$(LIBEXT) mm/libmm$(LIBEXT)
      +NUTTXLIBS += syscall/libstubs$(LIBEXT) libc/libkc$(LIBEXT)
      +USERLIBS += syscall/libproxies$(LIBEXT) libc/libuc$(LIBEXT) mm/libmm$(LIBEXT)
       else
      -NUTTXLIBS += mm/libmm$(LIBEXT) lib/liblib$(LIBEXT)
      +NUTTXLIBS += mm/libmm$(LIBEXT) libc/libc$(LIBEXT)
       endif
       
       # Add libraries for C++ support.  CXX, CXXFLAGS, and COMPILEXX must
      @@ -208,9 +208,9 @@ endif
       
       ifeq ($(CONFIG_HAVE_CXX),y)
       ifeq ($(CONFIG_NUTTX_KERNEL),y)
      -USERLIBS += libxx/liblibxx$(LIBEXT)
      +USERLIBS += libxx/libcxx$(LIBEXT)
       else
      -NUTTXLIBS += libxx/liblibxx$(LIBEXT)
      +NUTTXLIBS += libxx/libcxx$(LIBEXT)
       endif
       endif
       
      @@ -267,7 +267,7 @@ all: $(BIN)
       # include/nuttx/math.h will hand the redirection to the architecture-
       # specific math.h header file.
       #
      -# If the CONFIG_LIBM is defined, the Rhombus libm will be built at lib/math.
      +# If the CONFIG_LIBM is defined, the Rhombus libm will be built at libc/math.
       # Definitions and prototypes for the Rhombus libm are also contained in
       # include/nuttx/math.h and so the file must also be copied in that case.
       #
      @@ -445,8 +445,8 @@ check_context:
       #
       # Possible kernel-mode builds
       
      -lib/libklib$(LIBEXT): context
      -	$(Q) $(MAKE) -C lib TOPDIR="$(TOPDIR)" libklib$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +libc/libkc$(LIBEXT): context
      +	$(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libkc$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
       sched/libsched$(LIBEXT): context
       	$(Q) $(MAKE) -C sched TOPDIR="$(TOPDIR)" libsched$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      @@ -474,11 +474,11 @@ syscall/libstubs$(LIBEXT): context
       
       # Possible user-mode builds
       
      -lib/libulib$(LIBEXT): context
      -	$(Q) $(MAKE) -C lib TOPDIR="$(TOPDIR)" libulib$(LIBEXT)
      +libc/libuc$(LIBEXT): context
      +	$(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libuc$(LIBEXT)
       
      -libxx/liblibxx$(LIBEXT): context
      -	$(Q) $(MAKE) -C libxx TOPDIR="$(TOPDIR)" liblibxx$(LIBEXT)
      +libxx/libcxx$(LIBEXT): context
      +	$(Q) $(MAKE) -C libxx TOPDIR="$(TOPDIR)" libcxx$(LIBEXT)
       
       mm/libmm$(LIBEXT): context
       	$(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      @@ -491,8 +491,8 @@ syscall/libproxies$(LIBEXT): context
       
       # Possible non-kernel builds
       
      -lib/liblib$(LIBEXT): context
      -	$(Q) $(MAKE) -C lib TOPDIR="$(TOPDIR)" liblib$(LIBEXT)
      +libc/libc$(LIBEXT): context
      +	$(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libc$(LIBEXT)
       
       # pass1 and pass2
       #
      @@ -649,7 +649,7 @@ distclean: clean subdir_distclean clean_context
       ifeq ($(CONFIG_BUILD_2PASS),y)
       	$(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean
       endif
      -	$(Q) rm -f Make.defs setenv.sh .config .config.old
      +	$(Q) rm -f Make.defs setenv.sh setenv.bat .config .config.old
       
       # Application housekeeping targets.  The APPDIR variable refers to the user
       # application directory.  A sample apps/ directory is included with NuttX,
      diff --git a/nuttx/README.txt b/nuttx/README.txt
      index 85bb7f3814..c6138d1fdd 100644
      --- a/nuttx/README.txt
      +++ b/nuttx/README.txt
      @@ -842,7 +842,7 @@ nuttx
        |       `- README.txt
        |- graphics/
        |   `- README.txt
      - |- lib/
      + |- libc/
        |   `- README.txt
        |- libxx/
        |   `- README.txt
      diff --git a/nuttx/TODO b/nuttx/TODO
      index e98aced905..343212a313 100644
      --- a/nuttx/TODO
      +++ b/nuttx/TODO
      @@ -15,7 +15,7 @@ nuttx/
         (6)  Binary loaders (binfmt/)
        (17)  Network (net/, drivers/net)
         (4)  USB (drivers/usbdev, drivers/usbhost)
      - (11)  Libraries (lib/)
      + (11)  Libraries (libc/, )
         (9)  File system/Generic drivers (fs/, drivers/)
         (5)  Graphics subystem (graphics/)
         (1)  Pascal add-on (pcode/)
      @@ -634,8 +634,8 @@ o USB (drivers/usbdev, drivers/usbhost)
         Status:      Open
         Priority:    Low/Unknown.  This is a feature enhancement.
       
      -o Libraries (lib/)
      -  ^^^^^^^^^^^^^^^^
      +o Libraries (libc/)
      +  ^^^^^^^^^^^^^^^^^
       
         Title:       ENVIRON
         Description: The definition of environ in stdlib.h is bogus and will not
      @@ -648,7 +648,7 @@ o Libraries (lib/)
         Description: Need some minimal termios support... at a minimum, enough to
                      switch between raw and "normal" modes to support behavior like
                      that needed for readline().
      -               UPDATE:  There is growing functionality in lib/termios/ and in the
      +               UPDATE:  There is growing functionality in libc/termios/ and in the
                      ioctl methods of several MCU serial drivers (stm32, lpc43, lpc17,
                      pic32).  However, as phrased, this bug cannot yet be closed since
                      this "growing functionality" does not address all termios.h
      @@ -713,7 +713,7 @@ o Libraries (lib/)
         Priority:     
       
         Title:       OLD dtoa NEEDS TO BE UPDATED
      -  Description: This implementation of dtoa in lib/stdio is old and will not
      +  Description: This implementation of dtoa in libc/stdio is old and will not
                      work with some newer compilers.  See 
                      http://patrakov.blogspot.com/2009/03/dont-use-old-dtoac.html
         Status:      Open
      @@ -721,7 +721,7 @@ o Libraries (lib/)
       
         Title:       SYSLOG INTEGRATION
         Description: There are the beginnings of some system logging capabilities (see
      -               drivers/syslog, fs/fs_syslog.c, and lib/stdio/lib_librawprintf.c and
      +               drivers/syslog, fs/fs_syslog.c, and libc/stdio/lib_librawprintf.c and
                      lib_liblowprintf.c.  For NuttX, SYSLOG is a concept and includes,
                      extends, and replaces the legacy NuttX debug ouput.  Some additional
                      integration is required to formalized this.  For example:
      @@ -958,7 +958,7 @@ o Build system
                      built configuration, only the multiple user mode can be supported
                      with the NX server residing inside of the kernel space.  In
                      this case, most of the user end functions in graphics/nxmu
      -               must be moved to lib/nx and those functions must be built into
      +               must be moved to libc/nx and those functions must be built into
                      libuser.a to be linked with the user-space code.
                      A similar issue exists in NSH that uses some internal OS
                      interfaces that would not be available in a kernel build
      diff --git a/nuttx/configs/stm32f4discovery/ostest/defconfig b/nuttx/configs/stm32f4discovery/ostest/defconfig
      index a644b42eca..da7c8d200a 100644
      --- a/nuttx/configs/stm32f4discovery/ostest/defconfig
      +++ b/nuttx/configs/stm32f4discovery/ostest/defconfig
      @@ -8,6 +8,15 @@ CONFIG_NUTTX_NEWCONFIG=y
       # Build Setup
       #
       # CONFIG_EXPERIMENTAL is not set
      +# CONFIG_HOST_LINUX is not set
      +# CONFIG_HOST_OSX is not set
      +CONFIG_HOST_WINDOWS=y
      +# CONFIG_HOST_OTHER is not set
      +# CONFIG_WINDOWS_NATIVE is not set
      +CONFIG_WINDOWS_CYGWIN=y
      +# CONFIG_WINDOWS_MSYS is not set
      +# CONFIG_WINDOWS_OTHER is not set
      +# CONFIG_WINDOWS_MKLINK is not set
       
       #
       # Build Configuration
      @@ -28,6 +37,7 @@ CONFIG_RAW_BINARY=y
       #
       # CONFIG_ARCH_STDBOOL_H is not set
       # CONFIG_ARCH_MATH_H is not set
      +# CONFIG_ARCH_FLOAT_H is not set
       # CONFIG_ARCH_STDARG_H is not set
       
       #
      @@ -72,6 +82,8 @@ CONFIG_ARCH_CHIP_STM32=y
       CONFIG_ARCH_CORTEXM4=y
       CONFIG_ARCH_FAMILY="armv7-m"
       CONFIG_ARCH_CHIP="stm32"
      +CONFIG_ARCH_HAVE_CMNVECTOR=y
      +# CONFIG_ARMV7M_CMNVECTOR is not set
       # CONFIG_ARCH_FPU is not set
       CONFIG_ARCH_HAVE_MPU=y
       # CONFIG_ARMV7M_MPU is not set
      @@ -87,8 +99,14 @@ CONFIG_BOARD_LOOPSPERMSEC=16717
       # CONFIG_ARCH_CHIP_STM32F100CB is not set
       # CONFIG_ARCH_CHIP_STM32F100R8 is not set
       # CONFIG_ARCH_CHIP_STM32F100RB is not set
      +# CONFIG_ARCH_CHIP_STM32F100RC is not set
      +# CONFIG_ARCH_CHIP_STM32F100RD is not set
      +# CONFIG_ARCH_CHIP_STM32F100RE is not set
       # CONFIG_ARCH_CHIP_STM32F100V8 is not set
       # CONFIG_ARCH_CHIP_STM32F100VB is not set
      +# CONFIG_ARCH_CHIP_STM32F100VC is not set
      +# CONFIG_ARCH_CHIP_STM32F100VD is not set
      +# CONFIG_ARCH_CHIP_STM32F100VE is not set
       # CONFIG_ARCH_CHIP_STM32F103RET6 is not set
       # CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
       # CONFIG_ARCH_CHIP_STM32F103VET6 is not set
      @@ -121,14 +139,14 @@ CONFIG_STM32_CODESOURCERYL=y
       # CONFIG_STM32_ADC1 is not set
       # CONFIG_STM32_ADC2 is not set
       # CONFIG_STM32_ADC3 is not set
      -# CONFIG_STM32_CRC is not set
      -# CONFIG_STM32_DMA1 is not set
      -# CONFIG_STM32_DMA2 is not set
       # CONFIG_STM32_BKPSRAM is not set
       # CONFIG_STM32_CAN1 is not set
       # CONFIG_STM32_CAN2 is not set
       # CONFIG_STM32_CCMDATARAM is not set
      +# CONFIG_STM32_CRC is not set
       # CONFIG_STM32_CRYP is not set
      +# CONFIG_STM32_DMA1 is not set
      +# CONFIG_STM32_DMA2 is not set
       # CONFIG_STM32_DAC1 is not set
       # CONFIG_STM32_DAC2 is not set
       # CONFIG_STM32_DCMI is not set
      @@ -387,6 +405,7 @@ CONFIG_SYMTAB_ORDEREDBYNAME=y
       CONFIG_STDIO_BUFFER_SIZE=256
       CONFIG_STDIO_LINEBUFFER=y
       CONFIG_NUNGET_CHARS=2
      +# CONFIG_LIBM is not set
       # CONFIG_NOPRINTF_FIELDWIDTH is not set
       # CONFIG_LIBC_FLOATINGPOINT is not set
       # CONFIG_EOL_IS_CR is not set
      @@ -399,9 +418,11 @@ CONFIG_ARCH_LOWPUTC=y
       CONFIG_LIB_SENDFILE_BUFSIZE=512
       # CONFIG_ARCH_ROMGETC is not set
       # CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
      +
      +#
      +# Basic CXX Support
      +#
       # CONFIG_HAVE_CXX is not set
      -# CONFIG_HAVE_CXXINITIALIZE is not set
      -# CONFIG_CXX_NEWLONG is not set
       
       #
       # Application Configuration
      @@ -415,266 +436,61 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
       #
       # Examples
       #
      -
      -#
      -# ADC Example
      -#
      -
      -#
      -# Buttons Example
      -#
       # CONFIG_EXAMPLES_BUTTONS is not set
      -
      -#
      -# CAN Example
      -#
       # CONFIG_EXAMPLES_CAN is not set
      -
      -#
      -# USB CDC/ACM Class Driver Example
      -#
       # CONFIG_EXAMPLES_CDCACM is not set
      -
      -#
      -# USB composite Class Driver Example
      -#
       # CONFIG_EXAMPLES_COMPOSITE is not set
      -
      -#
      -# DHCP Server Example
      -#
       # CONFIG_EXAMPLES_DHCPD is not set
      -
      -#
      -# ELF Loader Example
      -#
       # CONFIG_EXAMPLES_ELF is not set
      -
      -#
      -# FTP Client Example
      -#
       # CONFIG_EXAMPLES_FTPC is not set
      -
      -#
      -# FTP Server Example
      -#
       # CONFIG_EXAMPLES_FTPD is not set
      -
      -#
      -# "Hello, World!" Example
      -#
       # CONFIG_EXAMPLES_HELLO is not set
      -
      -#
      -# "Hello, World!" C++ Example
      -#
       # CONFIG_EXAMPLES_HELLOXX is not set
      -
      -#
      -# USB HID Keyboard Example
      -#
      +# CONFIG_EXAMPLES_JSON is not set
       # CONFIG_EXAMPLES_HIDKBD is not set
      -
      -#
      -# IGMP Example
      -#
       # CONFIG_EXAMPLES_IGMP is not set
      -
      -#
      -# LCD Read/Write Example
      -#
       # CONFIG_EXAMPLES_LCDRW is not set
      -
      -#
      -# Memory Management Example
      -#
       # CONFIG_EXAMPLES_MM is not set
      -
      -#
      -# File System Mount Example
      -#
       # CONFIG_EXAMPLES_MOUNT is not set
      -
      -#
      -# FreeModBus Example
      -#
       # CONFIG_EXAMPLES_MODBUS is not set
      -
      -#
      -# Network Test Example
      -#
       # CONFIG_EXAMPLES_NETTEST is not set
      -
      -#
      -# NuttShell (NSH) Example
      -#
       # CONFIG_EXAMPLES_NSH is not set
      -
      -#
      -# NULL Example
      -#
       # CONFIG_EXAMPLES_NULL is not set
      -
      -#
      -# NX Graphics Example
      -#
       # CONFIG_EXAMPLES_NX is not set
      -
      -#
      -# NxConsole Example
      -#
       # CONFIG_EXAMPLES_NXCONSOLE is not set
      -
      -#
      -# NXFFS File System Example
      -#
       # CONFIG_EXAMPLES_NXFFS is not set
      -
      -#
      -# NXFLAT Example
      -#
       # CONFIG_EXAMPLES_NXFLAT is not set
      -
      -#
      -# NX Graphics "Hello, World!" Example
      -#
       # CONFIG_EXAMPLES_NXHELLO is not set
      -
      -#
      -# NX Graphics image Example
      -#
       # CONFIG_EXAMPLES_NXIMAGE is not set
      -
      -#
      -# NX Graphics lines Example
      -#
       # CONFIG_EXAMPLES_NXLINES is not set
      -
      -#
      -# NX Graphics Text Example
      -#
       # CONFIG_EXAMPLES_NXTEXT is not set
      -
      -#
      -# OS Test Example
      -#
       CONFIG_EXAMPLES_OSTEST=y
       # CONFIG_EXAMPLES_OSTEST_BUILTIN is not set
       CONFIG_EXAMPLES_OSTEST_LOOPS=1
       CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048
       CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3
      -
      -#
      -# Pascal "Hello, World!"example
      -#
      +CONFIG_EXAMPLES_OSTEST_RR_RANGE=10000
      +CONFIG_EXAMPLES_OSTEST_RR_RUNS=10
       # CONFIG_EXAMPLES_PASHELLO is not set
      -
      -#
      -# Pipe Example
      -#
       # CONFIG_EXAMPLES_PIPE is not set
      -
      -#
      -# Poll Example
      -#
       # CONFIG_EXAMPLES_POLL is not set
      -
      -#
      -# Pulse Width Modulation (PWM) Example
      -#
      -
      -#
      -# Quadrature Encoder Example
      -#
       # CONFIG_EXAMPLES_QENCODER is not set
      -
      -#
      -# RGMP Example
      -#
       # CONFIG_EXAMPLES_RGMP is not set
      -
      -#
      -# ROMFS Example
      -#
       # CONFIG_EXAMPLES_ROMFS is not set
      -
      -#
      -# sendmail Example
      -#
       # CONFIG_EXAMPLES_SENDMAIL is not set
      -
      -#
      -# Serial Loopback Example
      -#
       # CONFIG_EXAMPLES_SERLOOP is not set
      -
      -#
      -# Telnet Daemon Example
      -#
       # CONFIG_EXAMPLES_TELNETD is not set
      -
      -#
      -# THTTPD Web Server Example
      -#
       # CONFIG_EXAMPLES_THTTPD is not set
      -
      -#
      -# TIFF Generation Example
      -#
       # CONFIG_EXAMPLES_TIFF is not set
      -
      -#
      -# Touchscreen Example
      -#
       # CONFIG_EXAMPLES_TOUCHSCREEN is not set
      -
      -#
      -# UDP Example
      -#
       # CONFIG_EXAMPLES_UDP is not set
      -
      -#
      -# UDP Discovery Daemon Example
      -#
      -
      -#
      -# uIP Web Server Example
      -#
       # CONFIG_EXAMPLES_UIP is not set
      -
      -#
      -# USB Serial Test Example
      -#
       # CONFIG_EXAMPLES_USBSERIAL is not set
      -
      -#
      -# USB Mass Storage Class Example
      -#
       # CONFIG_EXAMPLES_USBMSC is not set
      -
      -#
      -# USB Serial Terminal Example
      -#
       # CONFIG_EXAMPLES_USBTERM is not set
      -
      -#
      -# Watchdog timer Example
      -#
       # CONFIG_EXAMPLES_WATCHDOG is not set
      -
      -#
      -# wget Example
      -#
      -
      -#
      -# WLAN Example
      -#
       # CONFIG_EXAMPLES_WLAN is not set
       
      -#
      -# XML RPC Example
      -#
      -
       #
       # Interpreters
       #
      @@ -692,74 +508,20 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3
       #
       # Networking Utilities
       #
      -
      -#
      -# DHCP client
      -#
      +# CONFIG_NETUTILS_CODECS is not set
       # CONFIG_NETUTILS_DHCPC is not set
      -
      -#
      -# DHCP server
      -#
       # CONFIG_NETUTILS_DHCPD is not set
      -
      -#
      -# FTP client
      -#
       # CONFIG_NETUTILS_FTPC is not set
      -
      -#
      -# FTP server
      -#
       # CONFIG_NETUTILS_FTPD is not set
      -
      -#
      -# Name resolution
      -#
      +# CONFIG_NETUTILS_JSON is not set
       # CONFIG_NETUTILS_RESOLV is not set
      -
      -#
      -# SMTP
      -#
       # CONFIG_NETUTILS_SMTP is not set
      -
      -#
      -# TFTP client
      -#
       # CONFIG_NETUTILS_TELNETD is not set
      -
      -#
      -# TFTP client
      -#
       # CONFIG_NETUTILS_TFTPC is not set
      -
      -#
      -# THTTPD web server
      -#
       # CONFIG_NETUTILS_THTTPD is not set
      -
      -#
      -# uIP support library
      -#
       # CONFIG_NETUTILS_UIPLIB is not set
      -
      -#
      -# uIP web client
      -#
       # CONFIG_NETUTILS_WEBCLIENT is not set
       
      -#
      -# uIP web server
      -#
      -
      -#
      -# UDP Discovery Utility
      -#
      -
      -#
      -# XML-RPC library
      -#
      -
       #
       # ModBus
       #
      diff --git a/nuttx/lib/Kconfig b/nuttx/lib/Kconfig
      deleted file mode 100644
      index 1c93bb0475..0000000000
      --- a/nuttx/lib/Kconfig
      +++ /dev/null
      @@ -1,275 +0,0 @@
      -#
      -# For a description of the syntax of this configuration file,
      -# see misc/tools/kconfig-language.txt.
      -#
      -
      -config STDIO_BUFFER_SIZE
      -	int "C STDIO buffer size"
      -	default 64
      -	---help---
      -		Size of buffers using within the C buffered I/O interfaces.
      -		(printf, putchar, fwrite, etc.).
      -
      -config STDIO_LINEBUFFER
      -	bool "STDIO line buffering"
      -	default y
      -	---help---
      -		Flush buffer I/O whenever a newline character is found in
      -		the output data stream.
      -
      -config NUNGET_CHARS
      -	int "Number unget() characters"
      -	default 2
      -	---help---
      -		Number of characters that can be buffered by ungetc() (Only if NFILE_STREAMS > 0)
      -
      -config LIB_HOMEDIR
      -	string "Home directory"
      -	default "/"
      -	depends on !DISABLE_ENVIRON
      -	---help---
      -		The home directory to use with operations like such as 'cd ~'
      -
      -source lib/math/Kconfig
      -
      -config NOPRINTF_FIELDWIDTH
      -	bool "Disable sprintf support fieldwidth"
      -	default n
      -	---help---
      -	sprintf-related logic is a
      -	little smaller if we do not support fieldwidthes
      -
      -config LIBC_FLOATINGPOINT
      -	bool "Enable floating point in printf"
      -	default n
      -	---help---
      -		By default, floating point
      -		support in printf, sscanf, etc. is disabled.
      -
      -choice
      -	prompt "Newline Options"
      -	default EOL_IS_EITHER_CRLF
      -	---help---
      -		This selection determines the line terminating character that is used.
      -		Some environments may return CR as end-of-line, others LF, and others
      -		both.  If not specified, the default is either CR or LF (but not both)
      -		as the line terminating charactor.
      -
      -config EOL_IS_CR
      -	bool "EOL is CR"
      -
      -config EOL_IS_LF
      -	bool "EOL is LF"
      -
      -config EOL_IS_BOTH_CRLF
      -	bool "EOL is CR and LF"
      -
      -config EOL_IS_EITHER_CRLF
      -	bool "EOL is CR or LF"
      -
      -endchoice
      -
      -config LIBC_STRERROR
      -	bool "Enable strerror"
      -	default n
      -	---help---
      -		strerror() is useful because it decodes 'errno' values into a human readable
      -		strings.  But it can also require a lot of memory.  If this option is selected,
      -		strerror() will still exist in the build but it will not decode error values.
      -		This option should be used by other logic to decide if it should use strerror()
      -		or not.  For example, the NSH application will not use strerror() if this
      -		option is not selected; perror() will not use strerror() is this option is not
      -		selected (see also NSH_STRERROR).
      -
      -config LIBC_STRERROR_SHORT
      -	bool "Use short error descriptions in strerror()"
      -	default n
      -	depends on LIBC_STRERROR
      -	---help---
      -		If this option is selected, then strerror() will use a shortened string when
      -		it decodes the error.  Specifically, strerror() is simply use the string that
      -		is the common name for the error.  For example, the 'errno' value of 2 will
      -		produce the string "No such file or directory" is LIBC_STRERROR_SHORT
      -		is not defined but the string "ENOENT" is LIBC_STRERROR_SHORT is defined.
      -
      -config LIBC_PERROR_STDOUT
      -	bool "perror() to stdout"
      -	default n
      -	---help---
      -		POSIX requires that perror() provide its output on stderr.  This option may
      -		be defined, however, to provide perror() output that is serialized with
      -		other stdout messages.
      -
      -config ARCH_LOWPUTC
      -	bool "Low-level console output"
      -	default "y"
      -	---help---
      -		architecture supports low-level, boot time console output
      -
      -config LIB_SENDFILE_BUFSIZE
      -	int "sendfile() buffer size"
      -	default 512
      -	---help---
      -		Size of the I/O buffer to allocate in sendfile().  Default: 512b
      -
      -config ARCH_ROMGETC
      -	bool "Support for ROM string access"
      -	default n
      -	---help---
      -		In Harvard architectures, data accesses and instruction accesses
      -		occur on different busses, perhaps concurrently.  All data accesses
      -		are performed on the data bus unless special machine instructions
      -		are used to read data from the instruction address space.  Also, in
      -		the typical MCU, the available SRAM data memory is much smaller that
      -		the non-volatile FLASH instruction memory.  So if the application
      -		requires many constant strings, the only practical solution may be
      -		to store those constant strings in FLASH memory where they can only
      -		be accessed using architecture-specific machine instructions.
      -
      -		If ARCH_ROMGETC is defined, then the architecture logic must export
      -		the function up_romgetc().  up_romgetc() will simply read one byte
      -		of data from the instruction space.
      -
      -		If ARCH_ROMGETC, certain C stdio functions are effected: (1) All
      -		format strings in printf, fprintf, sprintf, etc. are assumed to lie
      -		in FLASH (string arguments for %s are still assumed to reside in SRAM).
      -		And (2), the string argument to puts and fputs is assumed to reside
      -		in FLASH.  Clearly, these assumptions may have to modified for the
      -		particular needs of your environment.  There is no "one-size-fits-all"
      -		solution for this problem.
      -
      -config ARCH_OPTIMIZED_FUNCTIONS
      -	bool "Enable arch optimized functions"
      -	default n
      -	---help---
      -		Allow for architecture optimized implementations of certain library
      -		functions.  Architecture-specific implementations can improve overall
      -		system performance.
      -
      -if ARCH_OPTIMIZED_FUNCTIONS
      -config ARCH_MEMCPY
      -	bool "memcpy()"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of memcpy().
      -
      -config MEMCPY_VIK
      -	bool "Vik memcpy()"
      -	default n
      -	depends on !ARCH_MEMCPY
      -	---help---
      -		Select this option to use the optimized memcpy() function by Daniel Vik.
      -		Select this option for improved performance at the expense of increased
      -		size. See licensing information in the top-level COPYING file.
      -
      -if MEMCPY_VIK
      -config MEMCPY_PRE_INC_PTRS
      -	bool "Pre-increment pointers"
      -	default n
      -	---help---
      -		Use pre-increment of pointers. Default is post increment of pointers.
      -
      -config MEMCPY_INDEXED_COPY
      -	bool "Array indexing"
      -	default y
      -	---help---
      -		Copying data using array indexing. Using this option, disables the
      -		MEMCPY_PRE_INC_PTRS option.
      -
      -config MEMCPY_64BIT
      -	bool "64-bit memcpy()"
      -	default n
      -	---help---
      -		Compiles memcpy() for architectures that suppport 64-bit operations
      -		efficiently.
      -
      -endif
      -
      -config ARCH_MEMCMP
      -	bool "memcmp()"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of memcmp().
      -
      -config ARCH_MEMMOVE
      -	bool "memmove()"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of memmove().
      -
      -config ARCH_MEMSET
      -	bool "memset()"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of memset().
      -
      -config MEMSET_OPTSPEED
      -	bool "Optimize memset() for speed"
      -	default n
      -	depends on !ARCH_MEMSET
      -	---help---
      -		Select this option to use a version of memcpy() optimized for speed.
      -		Default: memcpy() is optimized for size.
      -
      -config MEMSET_64BIT
      -	bool "64-bit memset()"
      -	default n
      -	depends on MEMSET_OPTSPEED
      -	---help---
      -		Compiles memset() for architectures that suppport 64-bit operations
      -		efficiently.
      -
      -config ARCH_STRCHR
      -	bool "strchr()"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of strchr().
      -
      -config ARCH_STRCMP
      -	bool "strcmp()"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of strcmp().
      -
      -config ARCH_STRCPY
      -	bool "strcpy()"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of strcpy().
      -
      -config ARCH_STRNCPY
      -	bool "strncpy()"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of strncpy().
      -
      -config ARCH_STRLEN
      -	bool "strlen"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of strlen().
      -
      -config ARCH_STRNLEN
      -	bool "strlen()"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of strnlen().
      -
      -config ARCH_BZERO
      -	bool "bzero()"
      -	default n
      -	---help---
      -		Select this option if the architecture provides an optimized version
      -		of bzero().
      -
      -endif
      diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile
      deleted file mode 100644
      index 406c2276ef..0000000000
      --- a/nuttx/lib/Makefile
      +++ /dev/null
      @@ -1,136 +0,0 @@
      -############################################################################
      -# lib/Makefile
      -#
      -#   Copyright (C) 2007-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)/Make.defs
      -
      -ASRCS =
      -CSRCS =
      -
      -DEPPATH := --dep-path .
      -VPATH := .
      -
      -include stdio/Make.defs
      -include stdlib/Make.defs
      -include unistd/Make.defs
      -include sched/Make.defs
      -include string/Make.defs
      -include pthread/Make.defs
      -include semaphore/Make.defs
      -include signal/Make.defs
      -include mqueue/Make.defs
      -include math/Make.defs
      -include fixedmath/Make.defs
      -include net/Make.defs
      -include time/Make.defs
      -include libgen/Make.defs
      -include dirent/Make.defs
      -include termios/Make.defs
      -include queue/Make.defs
      -include misc/Make.defs
      -
      -AOBJS = $(ASRCS:.S=$(OBJEXT))
      -COBJS = $(CSRCS:.c=$(OBJEXT))
      -
      -SRCS = $(ASRCS) $(CSRCS)
      -OBJS = $(AOBJS) $(COBJS)
      -
      -UBIN = libulib$(LIBEXT)
      -KBIN = libklib$(LIBEXT)
      -BIN  = liblib$(LIBEXT)
      -
      -all: $(BIN)
      -
      -$(AOBJS): %$(OBJEXT): %.S
      -	$(call ASSEMBLE, $<, $@)
      -
      -$(COBJS): %$(OBJEXT): %.c
      -	$(call COMPILE, $<, $@)
      -
      -$(BIN):	$(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      -
      -ifneq ($(BIN),$(UBIN))
      -.userlib:
      -	@$(MAKE) $(UBIN) BIN=$(UBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      -	@touch .userlib
      -
      -$(UBIN): kclean .userlib
      -endif
      -
      -ifneq ($(BIN),$(KBIN))
      -.kernlib:
      -	@$(MAKE) $(KBIN) BIN=$(KBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      -	@touch .kernlib
      -
      -$(KBIN): uclean .kernlib
      -endif
      -
      -.depend: Makefile $(SRCS)
      -	@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      -
      -depend: .depend
      -
      -# Clean Targets:
      -# Clean user-mode temporary files (retaining the UBIN binary)
      -
      -uclean:
      -ifneq ($(OBJEXT),)
      -	@( if [ -f .userlib ]; then rm -f *$(OBJEXT); fi )
      -endif
      -	@rm -f .userlib *~ .*.swp
      -
      -# Clean kernel-mode temporary files (retaining the KBIN binary)
      -
      -kclean:
      -ifneq ($(OBJEXT),)
      -	@( if [ -f .kernlib ]; then rm -f *$(OBJEXT); fi )
      -endif
      -	@rm -f .kernlib *~ .*.swp
      -
      -# Really clean everything
      -
      -clean: uclean kclean
      -	@rm -f $(BIN) $(UBIN) $(KBIN) *~ .*.swp
      -	$(call CLEAN)
      -
      -# Deep clean -- removes all traces of the configuration
      -
      -distclean: clean
      -	@rm -f Make.dep .depend
      -
      --include Make.dep
      diff --git a/nuttx/lib/README.txt b/nuttx/lib/README.txt
      deleted file mode 100644
      index e99304841b..0000000000
      --- a/nuttx/lib/README.txt
      +++ /dev/null
      @@ -1,85 +0,0 @@
      -lib
      -===
      -
      -This directory contains numerous, small functions typically associated with
      -what you would expect to find in a standard C library.  The sub-directories
      -in this directory contain standard interface that can be executed by user-
      -mode programs.
      -
      -Normally, NuttX is built with no protection and all threads running in kerne-
      -mode.  In that model, there is no real architectural distinction between
      -what is a kernel-mode program and what is a user-mode program; the system is
      -more like on multi-threaded program that all runs in kernel-mode.
      -
      -But if the CONFIG_NUTTX_KERNEL option is selected, NuttX will be built into
      -distinct user-mode and kernel-mode sections.  In that case, most of the
      -code in the nuttx/ directory will run in kernel-mode with with exceptions
      -of (1) the user-mode "proxies" found in syscall/proxies, and (2) the
      -standard C library functions found in this directory.  In this build model,
      -it is critical to separate the user-mode OS interfaces in this way.
      -
      -Sub-Directories
      -===============
      -
      -The files in the lib/ directory are organized (mostly) according which file
      -in the include/ directory provides the prototype for library functions.  So
      -we have:
      -
      -  libgen    - libgen.h
      -  fixedmath - fixedmath.h
      -  math      - math.h
      -  mqueue    - pthread.h
      -  net       - Various network-related header files: netinet/ether.h, arpa/inet.h
      -  pthread   - pthread.h
      -  queue     - queue.h
      -  sched     - sched.h
      -  semaphore - semaphore.h
      -  stdio     - stdio.h
      -  stdlib    - stdlib.h
      -  string    - string.h
      -  time      - time.h
      -  unistd    - unistd.h
      -
      -There is also a misc/ subdirectory that contains various internal functions
      -and interfaces from header files that are too few to warrant their own sub-
      -directory:
      -
      - misc       - Nonstandard "glue" logic, debug.h, crc32.h, dirent.h
      -
      -Library Database
      -================
      -
      -Information about functions available in the NuttX C library information is
      -maintained in a database.  That "database" is implemented as a simple comma-
      -separated-value file, lib.csv.  Most spreadsheets programs will accept this
      -format and can be used to maintain the library database.
      -
      -This library database will (eventually) be used to generate symbol library
      -symbol table information that can be exported to external applications.
      -
      -The format of the CSV file for each line is:
      -
      -  Field 1: Function name
      -  Field 2: The header file that contains the function prototype
      -  Field 3: Condition for compilation
      -  Field 4: The type of function return value.
      -  Field 5 - N+5: The type of each of the N formal parameters of the function
      -
      -Each type field has a format as follows:
      -
      -  type name:
      -        For all simpler types
      -  formal type | actual type: 
      -        For array types where the form of the formal (eg. int parm[2])
      -        differs from the type of actual passed parameter (eg. int*).  This
      -        is necessary because you cannot do simple casts to array types.
      -  formal type | union member actual type | union member fieldname:
      -        A similar situation exists for unions.  For example, the formal
      -        parameter type union sigval -- You cannot cast a uintptr_t to
      -        a union sigval, but you can cast to the type of one of the union
      -        member types when passing the actual paramter.  Similarly, we
      -        cannot cast a union sigval to a uinptr_t either.  Rather, we need
      -        to cast a specific union member fieldname to uintptr_t.
      -
      -NOTE: The tool mksymtab can be used to generate a symbol table from this CSV
      -file.  See nuttx/tools/README.txt for further details about the use of mksymtab.
      diff --git a/nuttx/lib/dirent/Make.defs b/nuttx/lib/dirent/Make.defs
      deleted file mode 100644
      index cc1d6b7839..0000000000
      --- a/nuttx/lib/dirent/Make.defs
      +++ /dev/null
      @@ -1,48 +0,0 @@
      -############################################################################
      -# lib/dirent/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
      -
      -# Add the dirent C files to the build
      -
      -CSRCS += lib_readdirr.c lib_telldir.c
      -
      -# Add the dirent directory to the build
      -
      -DEPPATH += --dep-path dirent
      -VPATH += :dirent
      -
      -endif
      -
      diff --git a/nuttx/lib/dirent/lib_readdirr.c b/nuttx/lib/dirent/lib_readdirr.c
      deleted file mode 100644
      index 47c5b9a7bd..0000000000
      --- a/nuttx/lib/dirent/lib_readdirr.c
      +++ /dev/null
      @@ -1,122 +0,0 @@
      -/****************************************************************************
      - * lib/dirent/lib_readdirr.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: readdir_r
      - *
      - * Description:
      - *   The readdir() function returns a pointer to a dirent
      - *   structure representing the next directory entry in the
      - *   directory stream pointed to by dir.  It returns NULL on
      - *   reaching the end-of-file or if an error occurred.
      - *
      - * Inputs:
      - *   dirp -- An instance of type DIR created by a previous
      - *     call to opendir();
      - *   entry -- The  storage  pointed to by entry must be large
      - *     enough for a dirent with an array of char d_name
      - *     members containing at least {NAME_MAX}+1 elements.
      - *   result -- Upon successful return, the pointer returned
      - *     at *result shall have the  same  value  as  the 
      - *     argument entry. Upon reaching the end of the directory
      - *     stream, this pointer shall have the value NULL.
      - *
      - * Return:
      - *   If successful, the readdir_r() function return s zero;
      - *   otherwise, an error number is returned to indicate the
      - *   error.
      - *
      - *   EBADF   - Invalid directory stream descriptor dir
      - *
      - ****************************************************************************/
      -
      -int readdir_r(FAR DIR *dirp, FAR struct dirent *entry,
      -              FAR struct dirent **result)
      -{
      -  struct dirent *tmp;
      -
      -  /* NOTE: The following use or errno is *not* thread-safe */
      -
      -  set_errno(0);
      -  tmp = readdir(dirp);
      -  if (!tmp)
      -    {
      -       int error = get_errno();
      -       if (!error)
      -          {
      -            if (result)
      -              {
      -                *result = NULL;
      -              }
      -            return 0;
      -          }
      -       else
      -          {
      -            return error;
      -          }
      -    }
      -
      -  if (entry)
      -    {
      -      memcpy(entry, tmp, sizeof(struct dirent));
      -    }
      -
      -  if (result)
      -    {
      -      *result = entry;
      -    }
      -  return 0;
      -}
      -
      diff --git a/nuttx/lib/dirent/lib_telldir.c b/nuttx/lib/dirent/lib_telldir.c
      deleted file mode 100644
      index 3753b326e9..0000000000
      --- a/nuttx/lib/dirent/lib_telldir.c
      +++ /dev/null
      @@ -1,91 +0,0 @@
      -/****************************************************************************
      - * lib/dirent/fs_telldir.c
      - *
      - *   Copyright (C) 2007-2008, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: telldir
      - *
      - * Description:
      - *   The telldir() function returns the current location
      - *   associated with the directory stream dirp.
      - *
      - * Inputs:
      - *   dirp -- An instance of type DIR created by a previous
      - *     call to opendir();
      - *
      - * Return:
      - *   On success, the telldir() function returns the current
      - *   location in the directory stream.  On error, -1 is
      - *   returned, and errno is set appropriately.
      - *
      - *   EBADF - Invalid directory stream descriptor dir
      - *
      - ****************************************************************************/
      -
      -off_t telldir(FAR DIR *dirp)
      -{
      -  struct fs_dirent_s *idir = (struct fs_dirent_s *)dirp;
      -
      -  if (!idir || !idir->fd_root)
      -    {
      -      set_errno(EBADF);
      -      return (off_t)-1;
      -    }
      -
      -  /* Just return the current position */
      -
      -  return idir->fd_position;
      -}
      -
      diff --git a/nuttx/lib/fixedmath/Make.defs b/nuttx/lib/fixedmath/Make.defs
      deleted file mode 100644
      index 578e330153..0000000000
      --- a/nuttx/lib/fixedmath/Make.defs
      +++ /dev/null
      @@ -1,43 +0,0 @@
      -############################################################################
      -# lib/fixedmath/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the fixed precision math C files to the build
      -
      -CSRCS += lib_rint.c lib_fixedmath.c lib_b16sin.c lib_b16cos.c lib_b16atan2.c
      -
      -# Add the fixed precision math directory to the build
      -
      -DEPPATH += --dep-path fixedmath
      -VPATH += :fixedmath
      diff --git a/nuttx/lib/fixedmath/lib_b16atan2.c b/nuttx/lib/fixedmath/lib_b16atan2.c
      deleted file mode 100644
      index 69d132f80f..0000000000
      --- a/nuttx/lib/fixedmath/lib_b16atan2.c
      +++ /dev/null
      @@ -1,108 +0,0 @@
      -/****************************************************************************
      - * lib/fixedmath/lib_b16atan2.c
      - *
      - *   Copyright (C) 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -#define B16_C1     0x00000373 /* 0.013480470 */
      -#define B16_C2     0x00000eb7 /* 0.057477314 */
      -#define B16_C3     0x00001f0a /* 0.121239071 */
      -#define B16_C4     0x00003215 /* 0.195635925 */
      -#define B16_C5     0x0000553f /* 0.332994597 */
      -#define B16_C6     0x00010000 /* 0.999995630 */
      -#define B16_HALFPI 0x00019220 /* 1.570796327 */
      -#define B16_PI     0x00032440 /* 3.141592654 */
      -
      -#ifndef MAX
      -#  define MAX(a,b) (a > b ? a : b)
      -#endif
      -
      -#ifndef MIN
      -#  define MIN(a,b) (a < b ? a : b)
      -#endif
      -
      -#ifndef ABS
      -#  define ABS(a)   (a < 0 ? -a : a)
      -#endif
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: b16atan2
      - *
      - * Description:
      - *   atan2 calculates the arctangent of y/x.  (Based on a algorithm I saw
      - *   posted on the internet... now I have lost the link -- sorry).
      - *
      - ****************************************************************************/
      -
      -b16_t b16atan2(b16_t y, b16_t x)
      -{
      -  b16_t t0;
      -  b16_t t1;
      -  b16_t t2;
      -  b16_t t3;
      -
      -  t2 = ABS(x);
      -  t1 = ABS(y);
      -  t0 = MAX(t2, t1);
      -  t1 = MIN(t2, t1);
      -  t2 = ub16inv(t0);
      -  t2 = b16mulb16(t1, t2);
      -
      -  t3 = b16mulb16(t2, t2); 
      -  t0 =                   - B16_C1;
      -  t0 = b16mulb16(t0, t3) + B16_C2;
      -  t0 = b16mulb16(t0, t3) - B16_C3;
      -  t0 = b16mulb16(t0, t3) + B16_C4;
      -  t0 = b16mulb16(t0, t3) - B16_C5;
      -  t0 = b16mulb16(t0, t3) + B16_C6;
      -  t2 = b16mulb16(t0, t2);
      -
      -  t2 = (ABS(y) > ABS(x)) ? B16_HALFPI - t2 : t2;
      -  t2 = (x < 0) ?  B16_PI - t2 : t2;
      -  t2 = (y < 0) ? -t2 : t2;
      -
      -  return t2;
      -}
      diff --git a/nuttx/lib/fixedmath/lib_b16cos.c b/nuttx/lib/fixedmath/lib_b16cos.c
      deleted file mode 100644
      index 3e9229029e..0000000000
      --- a/nuttx/lib/fixedmath/lib_b16cos.c
      +++ /dev/null
      @@ -1,64 +0,0 @@
      -/****************************************************************************
      - * lib/fixedmath/lib_b16cos.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: b16cos
      - ****************************************************************************/
      -
      -b16_t b16cos(b16_t rad)
      -{
      -  /* Compute cosine: sin(rad + PI/2) = cos(rad) */
      -
      -  rad += b16HALFPI;
      -  if (rad > b16PI)
      -    {
      -      rad -= b16TWOPI;
      -    }
      -  return b16sin(rad);
      -}
      diff --git a/nuttx/lib/fixedmath/lib_b16sin.c b/nuttx/lib/fixedmath/lib_b16sin.c
      deleted file mode 100644
      index 491b0ec782..0000000000
      --- a/nuttx/lib/fixedmath/lib_b16sin.c
      +++ /dev/null
      @@ -1,110 +0,0 @@
      -/****************************************************************************
      - * lib/fixedmath/lib_b16sin.c
      - *
      - *   Copyright (C) 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -#define b16_P225       0x0000399a
      -#define b16_P405284735 0x000067c1
      -#define b16_1P27323954 0x000145f3
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: b16sin
      - * Ref: http://lab.polygonal.de/2007/07/18/fast-and-accurate-sinecosine-approximation/
      - ****************************************************************************/
      -
      -b16_t b16sin(b16_t rad)
      -{
      -  b16_t tmp1;
      -  b16_t tmp2;
      -  b16_t tmp3;
      -
      -  /* Force angle into the good range */
      -
      -  if (rad < -b16PI)
      -    {
      -      rad += b16TWOPI;
      -    }
      -  else if (rad > b16PI)
      -   {
      -      rad -= b16TWOPI;
      -   }
      -
      -  /* tmp1 = 1.27323954 * rad
      -   * tmp2 = .405284735 * rad * rad
      -   */
      -
      -
      -  tmp1 = b16mulb16(b16_1P27323954, rad);
      -  tmp2 = b16mulb16(b16_P405284735, b16sqr(rad));
      -
      -  if (rad < 0)
      -    {
      -       /* tmp3 = 1.27323954 * rad + .405284735 * rad * rad */
      -
      -       tmp3 = tmp1 + tmp2;
      -    }
      -  else
      -    {
      -       /* tmp3 = 1.27323954 * rad - 0.405284735 * rad * rad */
      -
      -       tmp3 = tmp1 - tmp2;
      -    }
      -
      -  /* tmp1 = tmp3*tmp3 */
      -
      -  tmp1 = b16sqr(tmp3);
      -  if (tmp3 < 0)
      -    {
      -      /* tmp1 = tmp3 * -tmp3 */
      -
      -      tmp1 = -tmp1;
      -    }
      -
      -  /* Return sin = .225 * (tmp3 * (+/-tmp3) - tmp3) + tmp3 */
      -
      -  return b16mulb16(b16_P225, (tmp1 - tmp3)) + tmp3;
      -}
      diff --git a/nuttx/lib/fixedmath/lib_fixedmath.c b/nuttx/lib/fixedmath/lib_fixedmath.c
      deleted file mode 100644
      index c1a710e739..0000000000
      --- a/nuttx/lib/fixedmath/lib_fixedmath.c
      +++ /dev/null
      @@ -1,272 +0,0 @@
      -/****************************************************************************
      - * lib/math/lib_fixedmath.c
      - *
      - *   Copyright (C) 2008-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#ifndef CONFIG_HAVE_LONG_LONG
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fixsign
      - ****************************************************************************/
      -
      -static void fixsign(b16_t *parg1, b16_t *parg2, bool *pnegate)
      -{
      -  bool negate = false;
      -  b16_t arg;
      -
      -  arg = *parg1;
      -  if (arg < 0)
      -    {
      -      *parg1 = -arg;
      -      negate = true;
      -    }
      -
      -  arg = *parg2;
      -  if (arg < 0)
      -    {
      -      *parg2 = -arg;
      -      negate ^= true;
      -    }
      -
      -  *pnegate = negate;
      -}
      -
      -/****************************************************************************
      - * Name: adjustsign
      - ****************************************************************************/
      -
      -static b16_t adjustsign(b16_t result, bool negate)
      -{
      -  /* If the product is negative, then we overflowed */
      -
      -  if (result < 0)
      -    {
      -      if (result)
      -        {
      -          return b16MIN;
      -        }
      -      else
      -        {
      -          return b16MAX;
      -        }
      -    }
      -
      -  /* correct the sign of the result */
      -
      -  if (negate)
      -    {
      -      return -result;
      -    }
      -  return result;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: b16mulb16
      - ****************************************************************************/
      -
      -b16_t b16mulb16(b16_t m1, b16_t m2)
      -{
      -  bool negate;
      -  b16_t product;
      -
      -  fixsign(&m1, &m2, &negate);
      -  product = (b16_t)ub16mulub16((ub16_t)m1, (ub16_t)m2);
      -  return adjustsign(product, negate);
      -}
      -
      -/****************************************************************************
      - * Name: ub16mulub16
      - **************************************************************************/
      -
      -ub16_t ub16mulub16(ub16_t m1, ub16_t m2)
      -{
      - /* Let:
      - *
      -  *   m1 = m1i*2**16 + m1f                                            (b16)
      -  *   m2 = m2i*2**16 + m2f                                            (b16)
      -  *
      -  * Then:
      -  *
      -  *  m1*m2 = (m1i*m2i)*2**32 + (m1i*m2f + m2i*m1f)*2**16 + m1f*m2f     (b32)
      -  *        = (m1i*m2i)*2**16 + (m1i*m2f + m2i*m1f) + m1f*m2f*2**-16    (b16)
      -  *        = a*2**16 + b + c*2**-16
      -  */
      -
      -  uint32_t m1i = ((uint32_t)m1 >> 16);
      -  uint32_t m2i = ((uint32_t)m1 >> 16);
      -  uint32_t m1f = ((uint32_t)m1 & 0x0000ffff);
      -  uint32_t m2f = ((uint32_t)m2 & 0x0000ffff);
      -
      -  return (m1i*m2i << 16) + m1i*m2f + m2i*m1f + (((m1f*m2f) + b16HALF) >> 16);
      -}
      -
      -/****************************************************************************
      - * Name: b16sqr
      - **************************************************************************/
      -
      -b16_t b16sqr(b16_t a)
      -{
      -  b16_t sq;
      -
      -  /* The result is always positive.  Just take the absolute value */
      -
      -  if (a < 0)
      -    {
      -      a = -a;
      -    }
      -
      -  /* Overflow occurred if the result is negative */
      -
      -  sq = (b16_t)ub16sqr(a);
      -  if (sq < 0)
      -    {
      -      sq = b16MAX;
      -    }
      -  return sq;
      -}
      -
      -/****************************************************************************
      - * Name: b16divb16
      - **************************************************************************/
      -
      -ub16_t ub16sqr(ub16_t a)
      -{
      - /* Let:
      - *
      -  *   m = mi*2**16 + mf                                               (b16)
      -  *
      -  * Then:
      -  *
      -  *  m*m = (mi*mi)*2**32 + 2*(m1*m2)*2**16 + mf*mf                    (b32)
      -  *      = (mi*mi)*2**16 + 2*(mi*mf)       + mf*mf*2**-16             (b16)
      -  */
      -
      -  uint32_t mi = ((uint32_t)a >> 16);
      -  uint32_t mf = ((uint32_t)a & 0x0000ffff);
      -
      -  return (mi*mi << 16) + (mi*mf << 1) + ((mf*mf + b16HALF) >> 16);
      -}
      -
      -/****************************************************************************
      - * Name: b16divb16
      - **************************************************************************/
      -
      -b16_t b16divb16(b16_t num, b16_t denom)
      -{
      -  bool  negate;
      -  b16_t quotient;
      -
      -  fixsign(&num, &denom, &negate);
      -  quotient = (b16_t)ub16divub16((ub16_t)num, (ub16_t)denom);
      -  return adjustsign(quotient, negate);
      -}
      -
      -/****************************************************************************
      - * Name: ub16divub16
      - **************************************************************************/
      -
      -ub16_t ub16divub16(ub16_t num, ub16_t denom)
      -{
      -  uint32_t term1;
      -  uint32_t numf;
      -  uint32_t product;
      -
      - /* Let:
      -  *
      -  *   num = numi*2**16 + numf                                         (b16)
      -  *   den = deni*2**16 + denf                                         (b16)
      -  *
      -  * Then:
      -  *
      -  *  num/den = numi*2**16 / den + numf / den                          (b0)
      -  *          = numi*2**32 / den + numf*2**16 /den                     (b16)
      -  */
      -
      -  /* Check for overflow in the first part of the quotient */
      -
      -  term1 = ((uint32_t)num & 0xffff0000) / denom;
      -  if (term1 >= 0x00010000)
      -    {
      -        return ub16MAX; /* Will overflow */
      -    }
      -
      -  /* Finish the division */
      -
      -  numf    = num - term1 * denom;
      -  term1 <<= 16;
      -  product = term1 + (numf + (denom >> 1)) / denom;
      -
      -  /* Check for overflow */
      -
      -  if (product < term1)
      -    {
      -        return ub16MAX; /* Overflowed */
      -    }
      -  return product;
      -}
      -
      -#endif
      diff --git a/nuttx/lib/fixedmath/lib_rint.c b/nuttx/lib/fixedmath/lib_rint.c
      deleted file mode 100644
      index 3a6407b8c0..0000000000
      --- a/nuttx/lib/fixedmath/lib_rint.c
      +++ /dev/null
      @@ -1,135 +0,0 @@
      -/************************************************************
      - * lib/fixedmath/lib_rint.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************
      - * Definitions
      - ************************************************************/
      -
      -/************************************************************
      - * Private Type Declarations
      - ************************************************************/
      -
      -/************************************************************
      - * Private Function Prototypes
      - ************************************************************/
      -
      -/**********************************************************
      - * Global Constant Data
      - **********************************************************/
      -
      -/************************************************************
      - * Global Variables
      - ************************************************************/
      -
      -/**********************************************************
      - * Private Constant Data
      - **********************************************************/
      -
      -/************************************************************
      - * Private Variables
      - ************************************************************/
      -
      -double_t rint(double_t x)
      -{
      -  double_t ret;
      -
      -  /* If the current rounding mode rounds toward negative
      -   * infinity, rint() is identical to floor().  If the current
      -   * rounding mode rounds toward positive infinity, rint() is
      -   * identical to ceil().
      -   */
      -
      -#if defined(CONFIG_FP_ROUND_POSITIVE) && CONFIG_FP_ROUNDING_POSITIVE != 0
      -
      -  ret = ceil(x);
      -
      -#elif defined(CONFIG_FP_ROUND_NEGATIVE) && CONFIG_FP_ROUNDING_NEGATIVE != 0
      -
      -  ret = floor(x);
      -
      -#else
      -
      -  /* In the default rounding mode (round to nearest), rint(x) is the
      -   * integer nearest x with the additional stipulation that if
      -   * |rint(x)-x|=1/2, then rint(x) is even.
      -   */
      -
      -  long     dwinteger  = (long)x;
      -  double_t fremainder = x - (double_t)dwinteger;
      -
      -  if (x < 0.0)
      -    {
      -      /* fremainder should be in range 0 .. -1 */
      -
      -      if (fremainder == -0.5)
      -        {
      -          dwinteger = ((dwinteger+1)&~1);
      -        }
      -      else if (fremainder < -0.5)
      -        {
      -          dwinteger--;
      -        }
      -    }
      -  else
      -    {
      -      /* fremainder should be in range 0 .. 1 */
      -
      -      if (fremainder == 0.5)
      -        {
      -          dwinteger = ((dwinteger+1)&~1);
      -        }
      -      else if (fremainder > 0.5)
      -        {
      -          dwinteger++;
      -        }
      -    }
      -
      -  ret = (double_t)dwinteger;
      -#endif
      -
      -  return ret;
      -}
      diff --git a/nuttx/lib/lib.csv b/nuttx/lib/lib.csv
      deleted file mode 100644
      index 171f64e9b7..0000000000
      --- a/nuttx/lib/lib.csv
      +++ /dev/null
      @@ -1,171 +0,0 @@
      -"_inet_ntoa","arpa/inet.h","!defined(CONFIG_NET_IPv6) && !defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","in_addr_t"
      -"abort","stdlib.h","","void"
      -"abs","stdlib.h","","int","int"
      -"asprintf","stdio.h","","int","FAR char **","const char *","..."
      -"avsprintf","stdio.h","","int","FAR char **","const char *","va_list"
      -"b16atan2","fixedmath.h","","b16_t","b16_t","b16_t"
      -"b16cos","fixedmath.h","","b16_t","b16_t"
      -"b16divb16","fixedmath.h","","b16_t","b16_t","b16_t"
      -"b16mulb16","fixedmath.h","","b16_t","b16_t","b16_t"
      -"b16sin","fixedmath.h","","b16_t","b16_t"
      -"b16sqr","fixedmath.h","","b16_t","b16_t"
      -"basename","libgen.h","","FAR char","FAR char *"
      -"cfgetspeed","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","speed_t","FAR const struct termios *"
      -"cfsetspeed","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","FAR struct termios *","speed_t"
      -"chdir","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)","int","FAR const char *"
      -"crc32","crc32.h","","uint32_t","FAR const uint8_t *","size_t"
      -"crc32part","crc32.h","","uint32_t","FAR const uint8_t *","size_t","uint32_t"
      -"dbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG)","int","const char *","..."
      -"dbg_enable","debug.h","defined(CONFIG_DEBUG_ENABLE)","void","bool"
      -"dirname","libgen.h","","FAR char","FAR char *"
      -"dq_addafter","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *"
      -"dq_addbefore","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *"
      -"dq_addfirst","queue.h","","void","FAR dq_entry_t *","dq_queue_t *"
      -"dq_addlast","queue.h","","void","FAR dq_entry_t *","dq_queue_t *"
      -"dq_rem","queue.h","","void","FAR dq_entry_t *","dq_queue_t *"
      -"dq_remfirst","queue.h","","FAR dq_entry_t","dq_queue_t *"
      -"dq_remlast","queue.h","","FAR dq_entry_t","dq_queue_t *"
      -"ether_ntoa","netinet/ether.h","","FAR char","FAR const struct ether_addr *"
      -"fclose","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *"
      -"fdopen","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR FILE","int","FAR const char *"
      -"fflush","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *"
      -"fgetc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *"
      -"fgetpos","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR fpos_t *"
      -"fgets","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR char","FAR char *","int","FAR FILE *"
      -"fileno","stdio.h","","int","FAR FILE *"
      -"fopen","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR FILE","FAR const char *","FAR const char *"
      -"fprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR const char *","..."
      -"fputc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","int c","FAR FILE *"
      -"fputs","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *","FAR FILE *"
      -"fread","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","size_t","FAR void *","size_t","size_t","FAR FILE *"
      -"fseek","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","long int","int"
      -"fsetpos","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR fpos_t *"
      -"ftell","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","long","FAR FILE *"
      -"fwrite","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","size_t","FAR const void *","size_t","size_t","FAR FILE *"
      -"getcwd","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)","FAR char","FAR char *","size_t"
      -"getopt","unistd.h","","int","int","FAR char *const[]","FAR const char *"
      -"getoptargp","unistd.h","","FAR char *"
      -"getoptindp","unistd.h","","int"
      -"getoptoptp","unistd.h","","int"
      -"gets","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR char","FAR char *"
      -"gmtime","time.h","","struct tm","const time_t *"
      -"gmtime_r","time.h","","FAR struct tm","FAR const time_t *","FAR struct tm *"
      -"htonl","arpa/inet.h","","uint32_t","uint32_t"
      -"htons","arpa/inet.h","","uint16_t","uint16_t"
      -"imaxabs","stdlib.h","","intmax_t","intmax_t"
      -"inet_addr","arpa/inet.h","","in_addr_t","FAR const char "
      -"inet_ntoa","arpa/inet.h","!defined(CONFIG_NET_IPv6) && defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","struct in_addr"
      -"inet_ntop","arpa/inet.h","","FAR const char","int","FAR const void *","FAR char *","socklen_t"
      -"inet_pton","arpa/inet.h","","int","int","FAR const char *","FAR void *"
      -"labs","stdlib.h","","long int","long int"
      -"lib_dumpbuffer","debug.h","","void","FAR const char *","FAR const uint8_t *","unsigned int"
      -"lib_lowprintf","debug.h","","int","FAR const char *","..."
      -"lib_rawprintf","debug.h","","int","FAR const char *","..."
      -"llabs","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long int","long long int"
      -"lldbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..."
      -"llvdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..."
      -"match","","","int","const char *","const char *"
      -"memccpy","string.h","","FAR void","FAR void *","FAR const void *","int c","size_t"
      -"memchr","string.h","","FAR void","FAR const void *","int c","size_t"
      -"memcmp","string.h","","int","FAR const void *","FAR const void *","size_t"
      -"memcpy","string.h","","FAR void","FAR void *","FAR const void *","size_t"
      -"memmove","string.h","","FAR void","FAR void *","FAR const void *","size_t"
      -"memset","string.h","","FAR void","FAR void *","int c","size_t"
      -"mktime","time.h","","time_t","const struct tm *"
      -"mq_getattr","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","struct mq_attr *"
      -"mq_setattr","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","const struct mq_attr *","struct mq_attr *"
      -"ntohl","arpa/inet.h","","uint32_t","uint32_t"
      -"ntohs","arpa/inet.h","","uint16_t","uint16_t"
      -"perror","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","void","FAR const char *"
      -"printf","stdio.h","","int","const char *","..."
      -"pthread_attr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *"
      -"pthread_attr_getinheritsched","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_attr_t *","FAR int *"
      -"pthread_attr_getschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR struct sched_param *"
      -"pthread_attr_getschedpolicy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int *"
      -"pthread_attr_getstacksize","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR long *"
      -"pthread_attr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *"
      -"pthread_attr_setinheritsched","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int"
      -"pthread_attr_setschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR const struct sched_param *"
      -"pthread_attr_setschedpolicy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int"
      -"pthread_attr_setstacksize","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","long"
      -"pthread_barrierattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *"
      -"pthread_barrierattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_barrierattr_t *","FAR int *"
      -"pthread_barrierattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *"
      -"pthread_barrierattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *","int"
      -"pthread_condattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *"
      -"pthread_condattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *"
      -"pthread_mutexattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *"
      -"pthread_mutexattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","FAR int *"
      -"pthread_mutexattr_gettype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","const pthread_mutexattr_t *","int *"
      -"pthread_mutexattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *"
      -"pthread_mutexattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","int "
      -"pthread_mutexattr_settype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","pthread_mutexattr_t *","int"
      -"puts","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *"
      -"qsort","stdlib.h","","void","void *","size_t","size_t","int(*)(const void *","const void *)"
      -"rand","stdlib.h","","int"
      -"readdir_r","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","int","FAR DIR *","FAR struct dirent *","FAR struct dirent **"
      -"rint","","","double_t","double_t"
      -"sched_get_priority_max","sched.h","","int","int"
      -"sched_get_priority_min","sched.h","","int","int"
      -"sem_getvalue","semaphore.h","","int","FAR sem_t *","FAR int *"
      -"sem_init","semaphore.h","","int","FAR sem_t *","int","unsigned int"
      -"sendfile","sys/sendfile.h","CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0","ssize_t","int","int","off_t","size_t"
      -"sigaddset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *","int"
      -"sigdelset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *","int"
      -"sigemptyset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *"
      -"sigfillset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *"
      -"sigismember","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR const sigset_t *","int"
      -"snprintf","stdio.h","","int","FAR char *","size_t","const char *","..."
      -"sprintf","stdio.h","","int","FAR char *","const char *","..."
      -"sq_addafter","queue.h","","void","FAR sq_entry_t *","FAR sq_entry_t *","FAR sq_queue_t *"
      -"sq_addfirst","queue.h","","void","FAR sq_entry_t *","sq_queue_t *"
      -"sq_addlast","queue.h","","void","FAR sq_entry_t *","sq_queue_t *"
      -"sq_rem","queue.h","","void","FAR sq_entry_t *","sq_queue_t *"
      -"sq_remafter","queue.h","","FAR sq_entry_t","FAR sq_entry_t *","sq_queue_t *"
      -"sq_remfirst","queue.h","","FAR sq_entry_t","sq_queue_t *"
      -"sq_remlast","queue.h","","FAR sq_entry_t","sq_queue_t *"
      -"srand","stdlib.h","","void","unsigned int"
      -"sscanf","stdio.h","","int","const char *","const char *","..."
      -"strcasecmp","string.h","","int","FAR const char *","FAR const char *"
      -"strcasestr","string.h","","FAR char","FAR const char *","FAR const char *"
      -"strcat","string.h","","FAR char","FAR char *","FAR const char *"
      -"strchr","string.h","","FAR char","FAR const char *","int"
      -"strcmp","string.h","","int","FAR const char *","FAR const char *"
      -"strcpy","string.h","","FAR char","char *","FAR const char *"
      -"strcspn","string.h","","size_t","FAR const char *","FAR const char *"
      -"strdup","string.h","","FAR char","FAR const char *"
      -"strerror","string.h","","FAR const char","int"
      -"strftime","time.h","","size_t","char *","size_t","const char *","const struct tm *"
      -"strlen","string.h","","size_t","FAR const char *"
      -"strncasecmp","string.h","","int","FAR const char *","FAR const char *","size_t"
      -"strncat","string.h","","FAR char","FAR char *","FAR const char *","size_t"
      -"strncmp","string.h","","int","FAR const char *","FAR const char *","size_t"
      -"strncpy","string.h","","FAR char","char *","FAR const char *","size_t"
      -"strndup","string.h","","FAR char","FAR const char *","size_t"
      -"strnlen","string.h","","size_t","FAR const char *","size_t"
      -"strpbrk","string.h","","FAR char","FAR const char *","FAR const char *"
      -"strrchr","string.h","","FAR char","FAR const char *","int"
      -"strspn","string.h","","size_t","FAR const char *","FAR const char *"
      -"strstr","string.h","","FAR char","FAR const char *","FAR const char *"
      -"strtod","stdlib.h","","double_t","const char *str","char **endptr"
      -"strtok","string.h","","FAR char","FAR char *","FAR const char *"
      -"strtok_r","string.h","","FAR char","FAR char *","FAR const char *","FAR char **"
      -"strtol","string.h","","long","const char *","char **","int"
      -"strtoll","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long","const char *nptr","char **endptr","int base"
      -"strtoul","stdlib.h","","unsigned long","const char *","char **","int"
      -"strtoull","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","unsigned long long","const char *","char **","int"
      -"tcflush","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int"
      -"tcgetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","FAR struct termios *"
      -"tcsetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int","FAR const struct termios *"
      -"telldir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","off_t","FAR DIR *"
      -"time","time.h","","time_t","time_t *"
      -"ub16divub16","fixedmath.h","","ub16_t","ub16_t","ub16_t"
      -"ub16mulub16","fixedmath.h","","ub16_t","ub16_t","ub16_t"
      -"ub16sqr","fixedmath.h","","ub16_t","ub16_t"
      -"ungetc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","int","FAR FILE *"
      -"vdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE)","int","const char *","..."
      -"vfprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","const char *","va_list"
      -"vprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *","va_list"
      -"vsnprintf","stdio.h","","int","FAR char *","size_t","const char *","va_list"
      -"vsprintf","stdio.h","","int","FAR char *","const char *","va_list"
      -"vsscanf","stdio.h","","int","char *","const char *","va_list"
      diff --git a/nuttx/lib/lib_internal.h b/nuttx/lib/lib_internal.h
      deleted file mode 100644
      index 5da0ac9249..0000000000
      --- a/nuttx/lib/lib_internal.h
      +++ /dev/null
      @@ -1,211 +0,0 @@
      -/****************************************************************************
      - * lib/lib_internal.h
      - *
      - *   Copyright (C) 2007-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.
      - *
      - ****************************************************************************/
      -
      -#ifndef __LIB_LIB_INTERNAL_H
      -#define __LIB_LIB_INTERNAL_H
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -/* This configuration directory is used in environment variable processing
      - * when we need to reference the user's home directory.  There are no user
      - * directories in NuttX so, by default, this always refers to the root
      - * directory.
      - */
      -
      -#ifndef CONFIG_LIB_HOMEDIR
      -# define CONFIG_LIB_HOMEDIR "/"
      -#endif
      -
      -/* If C std I/O buffering is not supported, then we don't need its semaphore
      - * protection.
      - */
      -
      -#if CONFIG_STDIO_BUFFER_SIZE <= 0
      -#  define lib_sem_initialize(s)
      -#  define lib_take_semaphore(s)
      -#  define lib_give_semaphore(s)
      -#endif
      -
      -/* The NuttX C library an be build in two modes: (1) as a standard, C-libary
      - * that can be used by normal, user-space applications, or (2) as a special,
      - * kernel-mode C-library only used within the OS.  If NuttX is not being
      - * built as separated kernel- and user-space modules, then only the first
      - * mode is supported.
      - */
      -
      -#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
      -#  include 
      -#  define lib_malloc(s)    kmalloc(s)
      -#  define lib_zalloc(s)    kzalloc(s)
      -#  define lib_realloc(p,s) krealloc(p,s)
      -#  define lib_free(p)      kfree(p)
      -#else
      -#  include 
      -#  define lib_malloc(s)    malloc(s)
      -#  define lib_zalloc(s)    zalloc(s)
      -#  define lib_realloc(p,s) realloc(p,s)
      -#  define lib_free(p)      free(p)
      -#endif
      -
      -#define LIB_BUFLEN_UNKNOWN INT_MAX
      -
      -/****************************************************************************
      - * Public Types
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/* Debug output is initially disabled */
      -
      -#ifdef CONFIG_DEBUG_ENABLE
      -extern bool g_dbgenable;
      -#endif
      -
      -/****************************************************************************
      - * Public Function Prototypes
      - ****************************************************************************/
      -
      -/* Defined in lib_streamsem.c */
      -
      -#if CONFIG_NFILE_STREAMS > 0
      -void  stream_semtake(FAR struct streamlist *list);
      -void  stream_semgive(FAR struct streamlist *list);
      -#endif
      -
      -/* Defined in lib_libnoflush.c */
      -
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -int lib_noflush(FAR struct lib_outstream_s *this);
      -#endif
      -
      -/* Defined in lib_libsprintf.c */
      -
      -int lib_sprintf(FAR struct lib_outstream_s *obj,
      -                       const char *fmt, ...);
      -
      -/* Defined lib_libvsprintf.c */
      -
      -int lib_vsprintf(FAR struct lib_outstream_s *obj,
      -                 FAR const char *src, va_list ap);
      -
      -/* Defined lib_rawprintf.c */
      -
      -int lib_rawvprintf(const char *src, va_list ap);
      -
      -/* Defined lib_lowprintf.c */
      -
      -int lib_lowvprintf(const char *src, va_list ap);
      -
      -/* Defined in lib_dtoa.c */
      -
      -#ifdef CONFIG_LIBC_FLOATINGPOINT
      -char *__dtoa(double d, int mode, int ndigits, int *decpt, int *sign,
      -             char **rve);
      -#endif
      -
      -/* Defined in lib_libwrite.c */
      -
      -ssize_t lib_fwrite(FAR const void *ptr, size_t count, FAR FILE *stream);
      -
      -/* Defined in lib_libfread.c */
      -
      -ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream);
      -
      -/* Defined in lib_libfflush.c */
      -
      -ssize_t lib_fflush(FAR FILE *stream, bool bforce);
      -
      -/* Defined in lib_rdflush.c */
      -
      -int lib_rdflush(FAR FILE *stream);
      -
      -/* Defined in lib_wrflush.c */
      -
      -int lib_wrflush(FAR FILE *stream);
      -
      -/* Defined in lib_sem.c */
      -
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -void lib_sem_initialize(FAR struct file_struct *stream);
      -void lib_take_semaphore(FAR struct file_struct *stream);
      -void lib_give_semaphore(FAR struct file_struct *stream);
      -#endif
      -
      -/* Defined in lib_libgetbase.c */
      -
      -int lib_getbase(const char *nptr, const char **endptr);
      -
      -/* Defined in lib_skipspace.c */
      -
      -void lib_skipspace(const char **pptr);
      -
      -/* Defined in lib_isbasedigit.c */
      -
      -bool lib_isbasedigit(int ch, int base, int *value);
      -
      -/* Defined in lib_checkbase.c */
      -
      -int lib_checkbase(int base, const char **pptr);
      -
      -/* Defined in lib_expi.c */
      -
      -#ifdef CONFIG_LIBM
      -double lib_expi(size_t n);
      -#endif
      -
      -/* Defined in lib_libsqrtapprox.c */
      -
      -#ifdef CONFIG_LIBM
      -float lib_sqrtapprox(float x);
      -#endif
      -
      -#endif /* __LIB_LIB_INTERNAL_H */
      diff --git a/nuttx/lib/libgen/Make.defs b/nuttx/lib/libgen/Make.defs
      deleted file mode 100644
      index f126455124..0000000000
      --- a/nuttx/lib/libgen/Make.defs
      +++ /dev/null
      @@ -1,43 +0,0 @@
      -############################################################################
      -# lib/libgen/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the libgen C files to the build
      -
      -CSRCS += lib_basename.c lib_dirname.c
      -
      -# Add the libgen directory to the build
      -
      -DEPPATH += --dep-path libgen
      -VPATH += :libgen
      diff --git a/nuttx/lib/libgen/lib_basename.c b/nuttx/lib/libgen/lib_basename.c
      deleted file mode 100644
      index 986c6b8520..0000000000
      --- a/nuttx/lib/libgen/lib_basename.c
      +++ /dev/null
      @@ -1,131 +0,0 @@
      -/****************************************************************************
      - * lib/libgen/lib_basename.c
      - *
      - *   Copyright (C) 2007, 2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Private Data
      - ****************************************************************************/
      -
      -static char g_retchar[2];
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function: basename
      - *
      - * Description:
      - *   basename() extracts the filename component from a null-terminated
      - *   pathname string. In the usual case, basename() returns the component
      - *   following the final '/'. Trailing '/' characters are not counted as
      - *   part of the pathname.
      - *
      - *   If path does not contain a slash, basename() returns a copy of path.
      - *   If path is the string "/", then basename() returns the string "/". If
      - *   path is a NULL pointer or points to an empty string, then basename()
      - *   return the string ".".
      - *
      - *   basename() may modify the contents of path, so copies should be passed.
      - *   basename() may return pointers to statically allocated memory which may
      - *   be overwritten by subsequent calls.
      - *
      - * Parameter:
      - *   path The null-terminated string referring to the path to be decomposed
      - *
      - * Return:
      - *   On success the filename component of the path is returned.
      - *
      - ****************************************************************************/
      -
      -FAR char *basename(FAR char *path)
      -{
      -  char *p;
      -  int   len;
      -  int   ch;
      -
      -  /* Handle some corner cases */
      -
      -  if (!path || *path == '\0')
      -    {
      -      ch = '.';
      -      goto out_retchar;
      -    }
      -
      -  /* Check for trailing slash characters */
      -
      -  len = strlen(path);
      -  while (path[len-1] == '/')
      -    {
      -      /* Remove trailing '/' UNLESS this would make a zero length string */
      -      if (len > 1)
      -        {
      -          path[len-1] = '\0';
      -          len--;
      -        }
      -      else
      -        {
      -          ch = '/';
      -          goto out_retchar;
      -        }
      -    }
      -
      -  /* Get the address of the last '/' which is not at the end of the path and,
      -   * therefor, must be just before the beginning of the filename component.
      -   */
      -
      -  p = strrchr(path, '/');
      -  if (p)
      -    {
      -      return p + 1;
      -    }
      -
      -  /* There is no '/' in the path */
      -
      -  return path;
      -
      -out_retchar:
      -  g_retchar[0] = ch;
      -  g_retchar[1] = '\0';
      -  return g_retchar;
      -}
      diff --git a/nuttx/lib/libgen/lib_dirname.c b/nuttx/lib/libgen/lib_dirname.c
      deleted file mode 100644
      index 248293a605..0000000000
      --- a/nuttx/lib/libgen/lib_dirname.c
      +++ /dev/null
      @@ -1,144 +0,0 @@
      -/****************************************************************************
      - * lib/libgen/lib_dirname.c
      - *
      - *   Copyright (C) 2007, 2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Private Data
      - ****************************************************************************/
      -
      -static char g_retchar[2];
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function: dirname
      - *
      - * Description:
      - *   dirname() extracts the directory component from a null-terminated
      - *   pathname string. In the usual case, dirname() returns the string up
      - *   to, but not including, the final '/'. Trailing '/' characters are not
      - *   counted as part of the pathname.
      - *
      - *   If path does not contain a slash, dirname() returns the string ".". If
      - *   path is the string "/", then dirname() returns the string "/". If path
      - *   is a NULL pointer or points to an empty string, then dirname() returns
      - *   the string ".".
      - *
      - *   dirname() may modify the contents of path, so copies should be passed.
      - *   dirname() may return pointers to statically allocated memory which may
      - *   be overwritten by subsequent calls.
      - *
      - * Parameter:
      - *   path The null-terminated string referring to the path to be decomposed
      - *
      - * Return:
      - *   On success the directory component of the path is returned.
      - *
      - ****************************************************************************/
      -
      -FAR char *dirname(FAR char *path)
      -{
      -  char *p;
      -  int   len;
      -  int   ch;
      -
      -  /* Handle some corner cases */
      -
      -  if (!path || *path == '\0')
      -    {
      -      ch = '.';
      -      goto out_retchar;
      -    }
      -
      -  /* Check for trailing slash characters */
      -
      -  len = strlen(path);
      -  while (path[len-1] == '/')
      -    {
      -      /* Remove trailing '/' UNLESS this would make a zero length string */
      -      if (len > 1)
      -        {
      -          path[len-1] = '\0';
      -          len--;
      -        }
      -      else
      -        {
      -          ch = '/';
      -          goto out_retchar;
      -        }
      -    }
      -
      -  /* Get the address of the last '/' which is not at the end of the path and,
      -   * therefor, must be the end of the directory component.
      -   */
      -
      -  p = strrchr(path, '/');
      -  if (p)
      -    {
      -      /* Handle the case where the only '/' in the string is the at the beginning
      -       * of the path.
      -       */
      -
      -      if (p == path)
      -        {
      -          ch = '/';
      -          goto out_retchar;
      -        }
      -
      -      /* No, the directory component is the substring before the '/'. */
      -
      -      *p = '\0';
      -      return path;
      -    }
      -
      -  /* There is no '/' in the path */
      -
      -  ch = '.';
      -
      -out_retchar:
      -  g_retchar[0] = ch;
      -  g_retchar[1] = '\0';
      -  return g_retchar;
      -}
      diff --git a/nuttx/lib/math/Kconfig b/nuttx/lib/math/Kconfig
      deleted file mode 100644
      index c24bfd53f3..0000000000
      --- a/nuttx/lib/math/Kconfig
      +++ /dev/null
      @@ -1,26 +0,0 @@
      -#
      -# For a description of the syntax of this configuration file,
      -# see misc/tools/kconfig-language.txt.
      -#
      -
      -config LIBM
      -	bool "Math library"
      -	default n
      -	depends on !ARCH_MATH_H
      -	---help---
      -		By default, no math library will be provided by NuttX.  In this this case, it
      -		is assumed that (1) no math library is required, or (2) you will be using the
      -		math.h header file and the libm library provided by your toolchain.
      -
      -		This is may be a very good choice is possible because your toolchain may have
      -		have a highly optimized version of libm.
      -
      -		Another possibility is that you have a custom, architecture-specific math
      -		libary and that the corresponding math.h file resides at arch//include/math.h.
      -		The option is selected via ARCH_MATH_H.  If ARCH_MATH_H is selected,then the include/nuttx/math.h
      - 		header file will be copied to include/math.h where it can be used by your applications.
      -
      -		If ARCH_MATH_H is not defined, then this option can be selected to build a generic,
      -		math library built into NuttX.  This math library comes from the Rhombus OS and
      -		was written by Nick Johnson.  The Rhombus OS math library port was contributed by
      -		Darcy Gong.
      diff --git a/nuttx/lib/math/Make.defs b/nuttx/lib/math/Make.defs
      deleted file mode 100644
      index 73d0be6f3b..0000000000
      --- a/nuttx/lib/math/Make.defs
      +++ /dev/null
      @@ -1,62 +0,0 @@
      -############################################################################
      -# lib/math/Make.defs
      -#
      -#   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_LIBM),y)
      -
      -# Add the floating point math C files to the build
      -
      -CSRCS += lib_acosf.c lib_asinf.c lib_atan2f.c lib_atanf.c lib_ceilf.c lib_cosf.c
      -CSRCS += lib_coshf.c  lib_expf.c lib_fabsf.c lib_floorf.c lib_fmodf.c lib_frexpf.c
      -CSRCS += lib_ldexpf.c lib_logf.c lib_log10f.c lib_log2f.c lib_modff.c lib_powf.c
      -CSRCS += lib_sinf.c lib_sinhf.c lib_sqrtf.c lib_tanf.c lib_tanhf.c
      -
      -CSRCS += lib_acos.c lib_asin.c lib_atan.c lib_atan2.c lib_ceil.c lib_cos.c
      -CSRCS += lib_cosh.c lib_exp.c lib_fabs.c lib_floor.c lib_fmod.c lib_frexp.c
      -CSRCS += lib_ldexp.c lib_log.c lib_log10.c lib_log2.c lib_modf.c lib_pow.c
      -CSRCS += lib_sin.c lib_sinh.c lib_sqrt.c lib_tan.c lib_tanh.c
      -
      -CSRCS += lib_acosl.c lib_asinl.c lib_atan2l.c lib_atanl.c lib_ceill.c lib_cosl.c
      -CSRCS += lib_coshl.c lib_expl.c lib_fabsl.c lib_floorl.c lib_fmodl.c lib_frexpl.c
      -CSRCS += lib_ldexpl.c lib_logl.c lib_log10l.c lib_log2l.c lib_modfl.c lib_powl.c
      -CSRCS += lib_sinl.c lib_sinhl.c lib_sqrtl.c lib_tanl.c lib_tanhl.c
      -
      -CSRCS += lib_libexpi.c lib_libsqrtapprox.c
      -
      -# Add the floating point math directory to the build
      -
      -DEPPATH += --dep-path math
      -VPATH += :math
      -
      -endif
      diff --git a/nuttx/lib/math/lib_acos.c b/nuttx/lib/math/lib_acos.c
      deleted file mode 100644
      index d5ec36b9ff..0000000000
      --- a/nuttx/lib/math/lib_acos.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_acos.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double acos(double x)
      -{
      -  return (M_PI_2 - asin(x));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_acosf.c b/nuttx/lib/math/lib_acosf.c
      deleted file mode 100644
      index e14a73a6ea..0000000000
      --- a/nuttx/lib/math/lib_acosf.c
      +++ /dev/null
      @@ -1,41 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_acosf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float acosf(float x)
      -{
      -  return (M_PI_2 - asinf(x));
      -}
      diff --git a/nuttx/lib/math/lib_acosl.c b/nuttx/lib/math/lib_acosl.c
      deleted file mode 100644
      index 9113305776..0000000000
      --- a/nuttx/lib/math/lib_acosl.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_acos.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double acosl(long double x)
      -{
      -  return (M_PI_2 - asinl(x));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_asin.c b/nuttx/lib/math/lib_asin.c
      deleted file mode 100644
      index 61b9535310..0000000000
      --- a/nuttx/lib/math/lib_asin.c
      +++ /dev/null
      @@ -1,69 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sin.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double asin(double x)
      -{
      -  long double y, y_sin, y_cos;
      -
      -  y = 0;
      -
      -  while (1)
      -    {
      -      y_sin = sin(y);
      -      y_cos = cos(y);
      -
      -      if (y > M_PI_2 || y < -M_PI_2)
      -        {
      -          y = fmod(y, M_PI);
      -        }
      -
      -      if (y_sin + DBL_EPSILON >= x && y_sin - DBL_EPSILON <= x)
      -        {
      -          break;
      -        }
      -
      -      y = y - (y_sin - x) / y_cos;
      -    }
      -
      -  return y;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_asinf.c b/nuttx/lib/math/lib_asinf.c
      deleted file mode 100644
      index 17669a9346..0000000000
      --- a/nuttx/lib/math/lib_asinf.c
      +++ /dev/null
      @@ -1,65 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sinf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float asinf(float x)
      -{
      -  long double y, y_sin, y_cos;
      -
      -  y = 0;
      -
      -  while (1)
      -    {
      -      y_sin = sinf(y);
      -      y_cos = cosf(y);
      -
      -      if (y > M_PI_2 || y < -M_PI_2)
      -        {
      -          y = fmodf(y, M_PI);
      -        }
      -
      -      if (y_sin + FLT_EPSILON >= x && y_sin - FLT_EPSILON <= x)
      -        {
      -          break;
      -        }
      -
      -      y = y - (y_sin - x) / y_cos;
      -    }
      -
      -  return y;
      -}
      -
      diff --git a/nuttx/lib/math/lib_asinl.c b/nuttx/lib/math/lib_asinl.c
      deleted file mode 100644
      index dbb2bc3a2e..0000000000
      --- a/nuttx/lib/math/lib_asinl.c
      +++ /dev/null
      @@ -1,69 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sinl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double asinl(long double x)
      -{
      -  long double y, y_sin, y_cos;
      -
      -  y = 0;
      -
      -  while (1)
      -    {
      -      y_sin = sinl(y);
      -      y_cos = cosl(y);
      -
      -      if (y > M_PI_2 || y < -M_PI_2)
      -        {
      -          y = fmodl(y, M_PI);
      -        }
      -
      -      if (y_sin + LDBL_EPSILON >= x && y_sin - LDBL_EPSILON <= x)
      -        {
      -          break;
      -        }
      -
      -      y = y - (y_sin - x) / y_cos;
      -    }
      -
      -  return y;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_atan.c b/nuttx/lib/math/lib_atan.c
      deleted file mode 100644
      index b4db8fb313..0000000000
      --- a/nuttx/lib/math/lib_atan.c
      +++ /dev/null
      @@ -1,48 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_atan.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double atan(double x)
      -{
      -  return asin(x / sqrt(x * x + 1));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_atan2.c b/nuttx/lib/math/lib_atan2.c
      deleted file mode 100644
      index 82d1f47ec3..0000000000
      --- a/nuttx/lib/math/lib_atan2.c
      +++ /dev/null
      @@ -1,86 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_atan2.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double atan2(double y, double x)
      -{
      -  if (y == 0.0)
      -    {
      -      if (x >= 0.0)
      -        {
      -          return 0.0;
      -        }
      -      else
      -        {
      -          return M_PI;
      -        }
      -    }
      -  else if (y > 0.0)
      -    {
      -      if (x == 0.0)
      -        {
      -          return M_PI_2;
      -        }
      -      else if (x > 0.0)
      -        {
      -          return atan(y / x);
      -        }
      -      else
      -        {
      -          return M_PI - atan(y / x);
      -        }
      -    }
      -  else
      -    {
      -      if (x == 0.0)
      -        {
      -          return M_PI + M_PI_2;
      -        }
      -      else if (x > 0.0)
      -        {
      -          return 2 * M_PI - atan(y / x);
      -        }
      -      else
      -        {
      -          return M_PI + atan(y / x);
      -        }
      -    }
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_atan2f.c b/nuttx/lib/math/lib_atan2f.c
      deleted file mode 100644
      index a60d32c655..0000000000
      --- a/nuttx/lib/math/lib_atan2f.c
      +++ /dev/null
      @@ -1,81 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_atan2f.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float atan2f(float y, float x)
      -{
      -  if (y == 0.0)
      -    {
      -      if (x >= 0.0)
      -        {
      -          return 0.0;
      -        }
      -      else
      -        {
      -          return M_PI;
      -        }
      -    }
      -  else if (y > 0.0)
      -    {
      -      if (x == 0.0)
      -        {
      -          return M_PI_2;
      -        }
      -      else if (x > 0.0)
      -        {
      -          return atanf(y / x);
      -        }
      -      else
      -        {
      -          return M_PI - atanf(y / x);
      -        }
      -    }
      -  else
      -    {
      -      if (x == 0.0)
      -        {
      -          return M_PI + M_PI_2;
      -        }
      -      else if (x > 0.0)
      -        {
      -          return 2 * M_PI - atanf(y / x);
      -        }
      -      else
      -        {
      -          return M_PI + atanf(y / x);
      -        }
      -    }
      -}
      diff --git a/nuttx/lib/math/lib_atan2l.c b/nuttx/lib/math/lib_atan2l.c
      deleted file mode 100644
      index 07fcd9669b..0000000000
      --- a/nuttx/lib/math/lib_atan2l.c
      +++ /dev/null
      @@ -1,87 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_atan2l.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double atan2l(long double y, long double x)
      -{
      -
      -  if (y == 0.0)
      -    {
      -      if (x >= 0.0)
      -        {
      -          return 0.0;
      -        }
      -      else
      -        {
      -          return M_PI;
      -        }
      -    }
      -  else if (y > 0.0)
      -    {
      -      if (x == 0.0)
      -        {
      -          return M_PI_2;
      -        }
      -      else if (x > 0.0)
      -        {
      -          return atanl(y / x);
      -        }
      -      else
      -        {
      -          return M_PI - atanl(y / x);
      -        }
      -    }
      -  else
      -    {
      -      if (x == 0.0)
      -        {
      -          return M_PI + M_PI_2;
      -        }
      -      else if (x > 0.0)
      -        {
      -          return 2 * M_PI - atanl(y / x);
      -        }
      -      else
      -        {
      -          return M_PI + atanl(y / x);
      -        }
      -    }
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_atanf.c b/nuttx/lib/math/lib_atanf.c
      deleted file mode 100644
      index 7c540dd163..0000000000
      --- a/nuttx/lib/math/lib_atanf.c
      +++ /dev/null
      @@ -1,43 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_atanf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float atanf(float x)
      -{
      -  return asinf(x / sqrtf(x * x + 1));
      -}
      diff --git a/nuttx/lib/math/lib_atanl.c b/nuttx/lib/math/lib_atanl.c
      deleted file mode 100644
      index 0fa2030988..0000000000
      --- a/nuttx/lib/math/lib_atanl.c
      +++ /dev/null
      @@ -1,48 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_atanl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double atanl(long double x)
      -{
      -  return asinl(x / sqrtl(x * x + 1));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_ceil.c b/nuttx/lib/math/lib_ceil.c
      deleted file mode 100644
      index 0e76029967..0000000000
      --- a/nuttx/lib/math/lib_ceil.c
      +++ /dev/null
      @@ -1,52 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_ceil.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double ceil(double x)
      -{
      -  modf(x, &x);
      -  if (x > 0.0)
      -    {
      -      x += 1.0;
      -    }
      -
      -  return x;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_ceilf.c b/nuttx/lib/math/lib_ceilf.c
      deleted file mode 100644
      index 0721ffc22a..0000000000
      --- a/nuttx/lib/math/lib_ceilf.c
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_ceilf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float ceilf(float x)
      -{
      -  modff(x, &x);
      -  if (x > 0.0)
      -    {
      -      x += 1.0;
      -    }
      -
      -  return x;
      -}
      diff --git a/nuttx/lib/math/lib_ceill.c b/nuttx/lib/math/lib_ceill.c
      deleted file mode 100644
      index a24b56f683..0000000000
      --- a/nuttx/lib/math/lib_ceill.c
      +++ /dev/null
      @@ -1,52 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_ceil;.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double ceill(long double x)
      -{
      -  modfl(x, &x);
      -  if (x > 0.0)
      -    {
      -      x += 1.0;
      -    }
      -
      -  return x;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_cos.c b/nuttx/lib/math/lib_cos.c
      deleted file mode 100644
      index aa672b8559..0000000000
      --- a/nuttx/lib/math/lib_cos.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_cos.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double cos(double x)
      -{
      -  return sin(x + M_PI_2);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_cosf.c b/nuttx/lib/math/lib_cosf.c
      deleted file mode 100644
      index 093a8a0024..0000000000
      --- a/nuttx/lib/math/lib_cosf.c
      +++ /dev/null
      @@ -1,41 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_cosf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float cosf(float x)
      -{
      -  return sinf(x + M_PI_2);
      -}
      diff --git a/nuttx/lib/math/lib_cosh.c b/nuttx/lib/math/lib_cosh.c
      deleted file mode 100644
      index 1be44d2933..0000000000
      --- a/nuttx/lib/math/lib_cosh.c
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_cosh.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double cosh(double x)
      -{
      -  x = exp(x);
      -  return ((x + (1.0 / x)) / 2.0);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_coshf.c b/nuttx/lib/math/lib_coshf.c
      deleted file mode 100644
      index d5e5ea14de..0000000000
      --- a/nuttx/lib/math/lib_coshf.c
      +++ /dev/null
      @@ -1,42 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_coshf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float coshf(float x)
      -{
      -  x = expf(x);
      -  return ((x + (1.0 / x)) / 2.0);
      -}
      diff --git a/nuttx/lib/math/lib_coshl.c b/nuttx/lib/math/lib_coshl.c
      deleted file mode 100644
      index 4576b88769..0000000000
      --- a/nuttx/lib/math/lib_coshl.c
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_coshl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double coshl(long double x)
      -{
      -  x = expl(x);
      -  return ((x + (1.0 / x)) / 2.0);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_cosl.c b/nuttx/lib/math/lib_cosl.c
      deleted file mode 100644
      index 25dd861393..0000000000
      --- a/nuttx/lib/math/lib_cosl.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_cosl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double cosl(long double x)
      -{
      -  return sinl(x + M_PI_2);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_exp.c b/nuttx/lib/math/lib_exp.c
      deleted file mode 100644
      index 1e3120453d..0000000000
      --- a/nuttx/lib/math/lib_exp.c
      +++ /dev/null
      @@ -1,126 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_exp.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -
      -/************************************************************************
      - * Private Data
      - ************************************************************************/
      -
      -static double _dbl_inv_fact[] =
      -{
      -  1.0 / 1.0,                    // 1 / 0!
      -  1.0 / 1.0,                    // 1 / 1!
      -  1.0 / 2.0,                    // 1 / 2!
      -  1.0 / 6.0,                    // 1 / 3!
      -  1.0 / 24.0,                   // 1 / 4!
      -  1.0 / 120.0,                  // 1 / 5!
      -  1.0 / 720.0,                  // 1 / 6!
      -  1.0 / 5040.0,                 // 1 / 7!
      -  1.0 / 40320.0,                // 1 / 8!
      -  1.0 / 362880.0,               // 1 / 9!
      -  1.0 / 3628800.0,              // 1 / 10!
      -  1.0 / 39916800.0,             // 1 / 11!
      -  1.0 / 479001600.0,            // 1 / 12!
      -  1.0 / 6227020800.0,           // 1 / 13!
      -  1.0 / 87178291200.0,          // 1 / 14!
      -  1.0 / 1307674368000.0,        // 1 / 15!
      -  1.0 / 20922789888000.0,       // 1 / 16!
      -  1.0 / 355687428096000.0,      // 1 / 17!
      -  1.0 / 6402373705728000.0,     // 1 / 18!
      -};
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -double exp(double x)
      -{
      -  size_t int_part;
      -  bool invert;
      -  double value;
      -  double x0;
      -  size_t i;
      -
      -  if (x == 0)
      -    {
      -      return 1;
      -    }
      -  else if (x < 0)
      -    {
      -      invert = true;
      -      x = -x;
      -    }
      -  else
      -    {
      -      invert = false;
      -    }
      -
      -  /* Extract integer component */
      -
      -  int_part = (size_t) x;
      -
      -  /* Set x to fractional component */
      -
      -  x -= (double)int_part;
      -
      -  /* Perform Taylor series approximation with nineteen terms */
      -
      -  value = 0.0;
      -  x0 = 1.0;
      -  for (i = 0; i < 19; i++)
      -    {
      -      value += x0 * _dbl_inv_fact[i];
      -      x0 *= x;
      -    }
      -
      -  /* Multiply by exp of the integer component */
      -
      -  value *= lib_expi(int_part);
      -
      -  if (invert)
      -    {
      -      return (1.0 / value);
      -    }
      -  else
      -    {
      -      return value;
      -    }
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_expf.c b/nuttx/lib/math/lib_expf.c
      deleted file mode 100644
      index eac4641c67..0000000000
      --- a/nuttx/lib/math/lib_expf.c
      +++ /dev/null
      @@ -1,112 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_expf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/************************************************************************
      - * Private Data
      - ************************************************************************/
      -
      -static float _flt_inv_fact[] =
      -{
      -  1.0 / 1.0,                    // 1/0!
      -  1.0 / 1.0,                    // 1/1!
      -  1.0 / 2.0,                    // 1/2!
      -  1.0 / 6.0,                    // 1/3!
      -  1.0 / 24.0,                   // 1/4!
      -  1.0 / 120.0,                  // 1/5!
      -  1.0 / 720.0,                  // 1/6!
      -  1.0 / 5040.0,                 // 1/7!
      -  1.0 / 40320.0,                // 1/8!
      -  1.0 / 362880.0,               // 1/9!
      -  1.0 / 3628800.0,              // 1/10!
      -};
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float expf(float x)
      -{
      -  size_t int_part;
      -  bool invert;
      -  float value;
      -  float x0;
      -  size_t i;
      -
      -  if (x == 0)
      -    {
      -      return 1;
      -    }
      -  else if (x < 0)
      -    {
      -      invert = true;
      -      x = -x;
      -    }
      -  else
      -    {
      -      invert = false;
      -    }
      -
      -  /* Extract integer component */
      -
      -  int_part = (size_t) x;
      -
      -  /* set x to fractional component */
      -
      -  x -= (float)int_part;
      -
      -  /* Perform Taylor series approximation with eleven terms */
      -
      -  value = 0.0;
      -  x0 = 1.0;
      -  for (i = 0; i < 10; i++)
      -    {
      -      value += x0 * _flt_inv_fact[i];
      -      x0 *= x;
      -    }
      -
      -  /* Multiply by exp of the integer component */
      -
      -  value *= lib_expi(int_part);
      -
      -  if (invert)
      -    {
      -      return (1.0 / value);
      -    }
      -  else
      -    {
      -      return value;
      -    }
      -}
      diff --git a/nuttx/lib/math/lib_expl.c b/nuttx/lib/math/lib_expl.c
      deleted file mode 100644
      index 053103c9bb..0000000000
      --- a/nuttx/lib/math/lib_expl.c
      +++ /dev/null
      @@ -1,126 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_expl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -
      -/************************************************************************
      - * Private Data
      - ************************************************************************/
      -
      -static long double _ldbl_inv_fact[] =
      -{
      -  1.0 / 1.0,                    // 1 / 0!
      -  1.0 / 1.0,                    // 1 / 1!
      -  1.0 / 2.0,                    // 1 / 2!
      -  1.0 / 6.0,                    // 1 / 3!
      -  1.0 / 24.0,                   // 1 / 4!
      -  1.0 / 120.0,                  // 1 / 5!
      -  1.0 / 720.0,                  // 1 / 6!
      -  1.0 / 5040.0,                 // 1 / 7!
      -  1.0 / 40320.0,                // 1 / 8!
      -  1.0 / 362880.0,               // 1 / 9!
      -  1.0 / 3628800.0,              // 1 / 10!
      -  1.0 / 39916800.0,             // 1 / 11!
      -  1.0 / 479001600.0,            // 1 / 12!
      -  1.0 / 6227020800.0,           // 1 / 13!
      -  1.0 / 87178291200.0,          // 1 / 14!
      -  1.0 / 1307674368000.0,        // 1 / 15!
      -  1.0 / 20922789888000.0,       // 1 / 16!
      -  1.0 / 355687428096000.0,      // 1 / 17!
      -  1.0 / 6402373705728000.0,     // 1 / 18!
      -};
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -long double expl(long double x)
      -{
      -  size_t int_part;
      -  bool invert;
      -  long double value;
      -  long double x0;
      -  size_t i;
      -
      -  if (x == 0)
      -    {
      -      return 1;
      -    }
      -  else if (x < 0)
      -    {
      -      invert = true;
      -      x = -x;
      -    }
      -  else
      -    {
      -      invert = false;
      -    }
      -
      -  /* Extract integer component */
      -
      -  int_part = (size_t) x;
      -
      -  /* Set x to fractional component */
      -
      -  x -= (long double)int_part;
      -
      -  /* Perform Taylor series approximation with nineteen terms */
      -
      -  value = 0.0;
      -  x0 = 1.0;
      -  for (i = 0; i < 19; i++)
      -    {
      -      value += x0 * _ldbl_inv_fact[i];
      -      x0 *= x;
      -    }
      -
      -  /* Multiply by exp of the integer component */
      -
      -  value *= lib_expi(int_part);
      -
      -  if (invert)
      -    {
      -      return (1.0 / value);
      -    }
      -  else
      -    {
      -      return value;
      -    }
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_fabs.c b/nuttx/lib/math/lib_fabs.c
      deleted file mode 100644
      index ff99ceb642..0000000000
      --- a/nuttx/lib/math/lib_fabs.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_fabs.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double fabs(double x)
      -{
      -  return ((x < 0) ? -x : x);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_fabsf.c b/nuttx/lib/math/lib_fabsf.c
      deleted file mode 100644
      index 0ea186ca03..0000000000
      --- a/nuttx/lib/math/lib_fabsf.c
      +++ /dev/null
      @@ -1,41 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_fabsf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float fabsf(float x)
      -{
      -  return ((x < 0) ? -x : x);
      -}
      diff --git a/nuttx/lib/math/lib_fabsl.c b/nuttx/lib/math/lib_fabsl.c
      deleted file mode 100644
      index 5313d897da..0000000000
      --- a/nuttx/lib/math/lib_fabsl.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_fabsl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double fabsl(long double x)
      -{
      -  return ((x < 0) ? -x : x);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_floor.c b/nuttx/lib/math/lib_floor.c
      deleted file mode 100644
      index f0c4477a04..0000000000
      --- a/nuttx/lib/math/lib_floor.c
      +++ /dev/null
      @@ -1,52 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_floor.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double floor(double x)
      -{
      -  modf(x, &x);
      -  if (x < 0.0)
      -    {
      -      x -= 1.0;
      -    }
      -
      -  return x;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_floorf.c b/nuttx/lib/math/lib_floorf.c
      deleted file mode 100644
      index 2becb5fac9..0000000000
      --- a/nuttx/lib/math/lib_floorf.c
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_floorf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float floorf(float x)
      -{
      -  modff(x, &x);
      -  if (x < 0.0)
      -    {
      -      x -= 1.0;
      -    }
      -
      -  return x;
      -}
      diff --git a/nuttx/lib/math/lib_floorl.c b/nuttx/lib/math/lib_floorl.c
      deleted file mode 100644
      index e38ce80ed3..0000000000
      --- a/nuttx/lib/math/lib_floorl.c
      +++ /dev/null
      @@ -1,52 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_floorl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double floorl(long double x)
      -{
      -  modfl(x, &x);
      -  if (x < 0.0)
      -    {
      -      x -= 1.0;
      -    }
      -
      -  return x;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_fmod.c b/nuttx/lib/math/lib_fmod.c
      deleted file mode 100644
      index 939e7e18ad..0000000000
      --- a/nuttx/lib/math/lib_fmod.c
      +++ /dev/null
      @@ -1,52 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_fmod.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double fmod(double x, double div)
      -{
      -  double n0;
      -
      -  x /= div;
      -  x = modf(x, &n0);
      -  x *= div;
      -
      -  return x;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_fmodf.c b/nuttx/lib/math/lib_fmodf.c
      deleted file mode 100644
      index 085786f172..0000000000
      --- a/nuttx/lib/math/lib_fmodf.c
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_fmodf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float fmodf(float x, float div)
      -{
      -  float n0;
      -
      -  x /= div;
      -  x = modff(x, &n0);
      -  x *= div;
      -
      -  return x;
      -}
      diff --git a/nuttx/lib/math/lib_fmodl.c b/nuttx/lib/math/lib_fmodl.c
      deleted file mode 100644
      index 51c5e95ec8..0000000000
      --- a/nuttx/lib/math/lib_fmodl.c
      +++ /dev/null
      @@ -1,52 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_fmodl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double fmodl(long double x, long double div)
      -{
      -  long double n0;
      -
      -  x /= div;
      -  x = modfl(x, &n0);
      -  x *= div;
      -
      -  return x;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_frexp.c b/nuttx/lib/math/lib_frexp.c
      deleted file mode 100644
      index 56feee8639..0000000000
      --- a/nuttx/lib/math/lib_frexp.c
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_frexp.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double frexp(double x, int *exponent)
      -{
      -  *exponent = (int)ceil(log2(x));
      -  return x / ldexp(1.0, *exponent);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_frexpf.c b/nuttx/lib/math/lib_frexpf.c
      deleted file mode 100644
      index 1fb0df3d89..0000000000
      --- a/nuttx/lib/math/lib_frexpf.c
      +++ /dev/null
      @@ -1,42 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_frexpf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float frexpf(float x, int *exponent)
      -{
      -  *exponent = (int)ceilf(log2f(x));
      -  return x / ldexpf(1.0, *exponent);
      -}
      diff --git a/nuttx/lib/math/lib_frexpl.c b/nuttx/lib/math/lib_frexpl.c
      deleted file mode 100644
      index 87708ad86c..0000000000
      --- a/nuttx/lib/math/lib_frexpl.c
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_frexpl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double frexpl(long double x, int *exponent)
      -{
      -  *exponent = (int)ceill(log2(x));
      -  return x / ldexpl(1.0, *exponent);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_ldexp.c b/nuttx/lib/math/lib_ldexp.c
      deleted file mode 100644
      index 4c7b2b721b..0000000000
      --- a/nuttx/lib/math/lib_ldexp.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_ldexp.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double ldexp(double x, int n)
      -{
      -  return (x * pow(2.0, (double)n));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_ldexpf.c b/nuttx/lib/math/lib_ldexpf.c
      deleted file mode 100644
      index c61d633d5c..0000000000
      --- a/nuttx/lib/math/lib_ldexpf.c
      +++ /dev/null
      @@ -1,41 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_ldexpf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float ldexpf(float x, int n)
      -{
      -  return (x * powf(2.0, (float)n));
      -}
      diff --git a/nuttx/lib/math/lib_ldexpl.c b/nuttx/lib/math/lib_ldexpl.c
      deleted file mode 100644
      index b9a0f4a865..0000000000
      --- a/nuttx/lib/math/lib_ldexpl.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_ldexpl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double ldexpl(long double x, int n)
      -{
      -  return (x * powl(2.0, (long double)n));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_libexpi.c b/nuttx/lib/math/lib_libexpi.c
      deleted file mode 100644
      index 1ec947a71a..0000000000
      --- a/nuttx/lib/math/lib_libexpi.c
      +++ /dev/null
      @@ -1,103 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_libexpi.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Pre-processor Definitions
      - ************************************************************************/
      -
      -#define M_E2    (M_E * M_E)
      -#define M_E4    (M_E2 * M_E2)
      -#define M_E8    (M_E4 * M_E4)
      -#define M_E16   (M_E8 * M_E8)
      -#define M_E32   (M_E16 * M_E16)
      -#define M_E64   (M_E32 * M_E32)
      -#define M_E128  (M_E64 * M_E64)
      -#define M_E256  (M_E128 * M_E128)
      -#define M_E512  (M_E256 * M_E256)
      -#define M_E1024 (M_E512 * M_E512)
      -
      -/************************************************************************
      - * Private Data
      - ************************************************************************/
      -
      -static double _expi_square_tbl[11] =
      -{
      -  M_E,                          // e^1
      -  M_E2,                         // e^2
      -  M_E4,                         // e^4
      -  M_E8,                         // e^8
      -  M_E16,                        // e^16
      -  M_E32,                        // e^32
      -  M_E64,                        // e^64
      -  M_E128,                       // e^128
      -  M_E256,                       // e^256
      -  M_E512,                       // e^512
      -  M_E1024,                      // e^1024
      -};
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -double lib_expi(size_t n)
      -{
      -  size_t i;
      -  double val;
      -
      -  if (n > 1024)
      -    {
      -      return INFINITY;
      -    }
      -
      -  val = 1.0;
      -
      -  for (i = 0; n; i++)
      -    {
      -      if (n & (1 << i))
      -        {
      -          n   &= ~(1 << i);
      -          val *= _expi_square_tbl[i];
      -        }
      -    }
      -
      -  return val;
      -}
      -
      diff --git a/nuttx/lib/math/lib_libsqrtapprox.c b/nuttx/lib/math/lib_libsqrtapprox.c
      deleted file mode 100644
      index 5c556c3a0e..0000000000
      --- a/nuttx/lib/math/lib_libsqrtapprox.c
      +++ /dev/null
      @@ -1,50 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_libsqrtapprox.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float lib_sqrtapprox(float x)
      -{
      -  int32_t i;
      -
      -  /* Floats + bit manipulation = +inf fun! */
      -
      -  i = *((int32_t *) & x);
      -  i = 0x1fc00000 + (i >> 1);
      -  x = *((float *)&i);
      -
      -  return x;
      -}
      diff --git a/nuttx/lib/math/lib_log.c b/nuttx/lib/math/lib_log.c
      deleted file mode 100644
      index 1350ba4fea..0000000000
      --- a/nuttx/lib/math/lib_log.c
      +++ /dev/null
      @@ -1,82 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_log.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double log(double x)
      -{
      -  double y, y_old, ey, epsilon;
      -
      -  y = 0.0;
      -  y_old = 1.0;
      -  epsilon = DBL_EPSILON;
      -
      -  while (y > y_old + epsilon || y < y_old - epsilon)
      -    {
      -      y_old = y;
      -      ey = exp(y);
      -      y -= (ey - x) / ey;
      -
      -      if (y > 700.0)
      -        {
      -          y = 700.0;
      -        }
      -
      -      if (y < -700.0)
      -        {
      -          y = -700.0;
      -        }
      -
      -      epsilon = (fabs(y) > 1.0) ? fabs(y) * DBL_EPSILON : DBL_EPSILON;
      -    }
      -
      -  if (y == 700.0)
      -    {
      -      return INFINITY;
      -    }
      -
      -  if (y == -700.0)
      -    {
      -      return INFINITY;
      -    }
      -
      -  return y;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_log10.c b/nuttx/lib/math/lib_log10.c
      deleted file mode 100644
      index 47854fca44..0000000000
      --- a/nuttx/lib/math/lib_log10.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_log10.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double log10(double x)
      -{
      -  return (log(x) / M_LN10);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_log10f.c b/nuttx/lib/math/lib_log10f.c
      deleted file mode 100644
      index 651071920f..0000000000
      --- a/nuttx/lib/math/lib_log10f.c
      +++ /dev/null
      @@ -1,41 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_log10f.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float log10f(float x)
      -{
      -  return (logf(x) / M_LN10);
      -}
      diff --git a/nuttx/lib/math/lib_log10l.c b/nuttx/lib/math/lib_log10l.c
      deleted file mode 100644
      index 65892262a8..0000000000
      --- a/nuttx/lib/math/lib_log10l.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_log10l.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double log10l(long double x)
      -{
      -  return (logl(x) / M_LN10);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_log2.c b/nuttx/lib/math/lib_log2.c
      deleted file mode 100644
      index 0aa1e80101..0000000000
      --- a/nuttx/lib/math/lib_log2.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_log2.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double log2(double x)
      -{
      -  return (log(x) / M_LN2);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_log2f.c b/nuttx/lib/math/lib_log2f.c
      deleted file mode 100644
      index e160ca59e3..0000000000
      --- a/nuttx/lib/math/lib_log2f.c
      +++ /dev/null
      @@ -1,41 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_log2f.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float log2f(float x)
      -{
      -  return (logf(x) / M_LN2);
      -}
      diff --git a/nuttx/lib/math/lib_log2l.c b/nuttx/lib/math/lib_log2l.c
      deleted file mode 100644
      index 21d26d4d7b..0000000000
      --- a/nuttx/lib/math/lib_log2l.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_log2l.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double log2l(long double x)
      -{
      -  return (logl(x) / M_LN2);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_logf.c b/nuttx/lib/math/lib_logf.c
      deleted file mode 100644
      index 1d31aa0c0b..0000000000
      --- a/nuttx/lib/math/lib_logf.c
      +++ /dev/null
      @@ -1,77 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_logf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float logf(float x)
      -{
      -  float y, y_old, ey, epsilon;
      -
      -  y = 0.0;
      -  y_old = 1.0;
      -  epsilon = FLT_EPSILON;
      -
      -  while (y > y_old + epsilon || y < y_old - epsilon)
      -    {
      -      y_old = y;
      -      ey = exp(y);
      -      y -= (ey - x) / ey;
      -
      -      if (y > 700.0)
      -        {
      -          y = 700.0;
      -        }
      -
      -      if (y < -700.0)
      -        {
      -          y = -700.0;
      -        }
      -
      -      epsilon = (fabs(y) > 1.0) ? fabs(y) * FLT_EPSILON : FLT_EPSILON;
      -    }
      -
      -  if (y == 700.0)
      -    {
      -      return INFINITY;
      -    }
      -
      -  if (y == -700.0)
      -    {
      -      return INFINITY;
      -    }
      -
      -  return y;
      -}
      diff --git a/nuttx/lib/math/lib_logl.c b/nuttx/lib/math/lib_logl.c
      deleted file mode 100644
      index 577f9cee2e..0000000000
      --- a/nuttx/lib/math/lib_logl.c
      +++ /dev/null
      @@ -1,80 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_lol.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double logl(long double x)
      -{
      -  long double y, y_old, ey, epsilon;
      -
      -  y = 0.0;
      -  y_old = 1.0;
      -  epsilon = LDBL_EPSILON;
      -
      -  while (y > y_old + epsilon || y < y_old - epsilon)
      -    {
      -      y_old = y;
      -      ey = expl(y);
      -      y -= (ey - x) / ey;
      -
      -      if (y > 700.0)
      -        {
      -          y = 700.0;
      -        }
      -
      -      if (y < -700.0)
      -        {
      -          y = -700.0;
      -        }
      -    }
      -
      -  if (y == 700.0)
      -    {
      -      return INFINITY;
      -    }
      -
      -  if (y == -700.0)
      -    {
      -      return INFINITY;
      -    }
      -
      -  return y;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_modf.c b/nuttx/lib/math/lib_modf.c
      deleted file mode 100644
      index 9dc6284c20..0000000000
      --- a/nuttx/lib/math/lib_modf.c
      +++ /dev/null
      @@ -1,58 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_modf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double modf(double x, double *iptr)
      -{
      -  if (fabs(x) >= 4503599627370496.0)
      -    {
      -      *iptr = x;
      -      return 0.0;
      -    }
      -  else if (fabs(x) < 1.0)
      -    {
      -      *iptr = 0.0;
      -      return x;
      -    }
      -  else
      -    {
      -      *iptr = (double)(int64_t) x;
      -      return (x - *iptr);
      -    }
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_modff.c b/nuttx/lib/math/lib_modff.c
      deleted file mode 100644
      index 4eec2ae17f..0000000000
      --- a/nuttx/lib/math/lib_modff.c
      +++ /dev/null
      @@ -1,55 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_modff.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float modff(float x, float *iptr)
      -{
      -  if (fabsf(x) >= 8388608.0)
      -    {
      -      *iptr = x;
      -      return 0.0;
      -    }
      -  else if (fabs(x) < 1.0)
      -    {
      -      *iptr = 0.0;
      -      return x;
      -    }
      -  else
      -    {
      -      *iptr = (float)(int)x;
      -      return (x - *iptr);
      -    }
      -}
      diff --git a/nuttx/lib/math/lib_modfl.c b/nuttx/lib/math/lib_modfl.c
      deleted file mode 100644
      index 3b04571f3a..0000000000
      --- a/nuttx/lib/math/lib_modfl.c
      +++ /dev/null
      @@ -1,61 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_modfl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double modfl(long double x, long double *iptr)
      -{
      -  if (fabs(x) >= 4503599627370496.0)
      -    {
      -      *iptr = x;
      -      return 0.0;
      -    }
      -  else if (fabs(x) < 1.0)
      -    {
      -      *iptr = 0.0;
      -      return x;
      -    }
      -  else
      -    {
      -      *iptr = (long double)(int64_t) x;
      -      return (x - *iptr);
      -    }
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_pow.c b/nuttx/lib/math/lib_pow.c
      deleted file mode 100644
      index af0a55d32f..0000000000
      --- a/nuttx/lib/math/lib_pow.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_pow.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double pow(double b, double e)
      -{
      -  return exp(e * log(b));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_powf.c b/nuttx/lib/math/lib_powf.c
      deleted file mode 100644
      index a43f9cf82a..0000000000
      --- a/nuttx/lib/math/lib_powf.c
      +++ /dev/null
      @@ -1,41 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_powf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float powf(float b, float e)
      -{
      -  return expf(e * logf(b));
      -}
      diff --git a/nuttx/lib/math/lib_powl.c b/nuttx/lib/math/lib_powl.c
      deleted file mode 100644
      index f5fbf042e9..0000000000
      --- a/nuttx/lib/math/lib_powl.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_powl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double powl(long double b, long double e)
      -{
      -  return expl(e * logl(b));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_sin.c b/nuttx/lib/math/lib_sin.c
      deleted file mode 100644
      index c04d6b88b9..0000000000
      --- a/nuttx/lib/math/lib_sin.c
      +++ /dev/null
      @@ -1,114 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sin.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -
      -/************************************************************************
      - * Private Data
      - ************************************************************************/
      -
      -static double _dbl_inv_fact[] =
      -{
      -  1.0 / 1.0,                    // 1 / 1!
      -  1.0 / 6.0,                    // 1 / 3!
      -  1.0 / 120.0,                  // 1 / 5!
      -  1.0 / 5040.0,                 // 1 / 7!
      -  1.0 / 362880.0,               // 1 / 9!
      -  1.0 / 39916800.0,             // 1 / 11!
      -  1.0 / 6227020800.0,           // 1 / 13!
      -  1.0 / 1307674368000.0,        // 1 / 15!
      -  1.0 / 355687428096000.0,      // 1 / 17!
      -  1.0 / 121645100408832000.0,   // 1 / 19!
      -};
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -double sin(double x)
      -{
      -  double x_squared;
      -  double sin_x;
      -  size_t i;
      -
      -  /* Move x to [-pi, pi) */
      -
      -  x = fmod(x, 2 * M_PI);
      -  if (x >= M_PI)
      -    {
      -      x -= 2 * M_PI;
      -    }
      -
      -  if (x < -M_PI)
      -    {
      -      x += 2 * M_PI;
      -    }
      -
      -  /* Move x to [-pi/2, pi/2) */
      -
      -  if (x >= M_PI_2)
      -    {
      -      x = M_PI - x;
      -    }
      -
      -  if (x < -M_PI_2)
      -    {
      -      x = -M_PI - x;
      -    }
      -
      -  x_squared = x * x;
      -  sin_x = 0.0;
      -
      -  /* Perform Taylor series approximation for sin(x) with ten terms */
      -
      -  for (i = 0; i < 10; i++)
      -    {
      -      if (i % 2 == 0)
      -        {
      -          sin_x += x * _dbl_inv_fact[i];
      -        }
      -      else
      -        {
      -          sin_x -= x * _dbl_inv_fact[i];
      -        }
      -
      -      x *= x_squared;
      -    }
      -
      -  return sin_x;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_sinf.c b/nuttx/lib/math/lib_sinf.c
      deleted file mode 100644
      index e298bbba49..0000000000
      --- a/nuttx/lib/math/lib_sinf.c
      +++ /dev/null
      @@ -1,104 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sinf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Private Data
      - ************************************************************************/
      -
      -static float _flt_inv_fact[] =
      -{
      -  1.0 / 1.0,                    // 1 / 1!
      -  1.0 / 6.0,                    // 1 / 3!
      -  1.0 / 120.0,                  // 1 / 5!
      -  1.0 / 5040.0,                 // 1 / 7!
      -  1.0 / 362880.0,               // 1 / 9!
      -  1.0 / 39916800.0,             // 1 / 11!
      -};
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float sinf(float x)
      -{
      -  float x_squared;
      -  float sin_x;
      -  size_t i;
      -
      -  /* Move x to [-pi, pi) */
      -
      -  x = fmodf(x, 2 * M_PI);
      -  if (x >= M_PI)
      -    {
      -      x -= 2 * M_PI;
      -    }
      -
      -  if (x < -M_PI)
      -    {
      -      x += 2 * M_PI;
      -    }
      -
      -  /* Move x to [-pi/2, pi/2) */
      -
      -  if (x >= M_PI_2)
      -    {
      -      x = M_PI - x;
      -    }
      -
      -  if (x < -M_PI_2)
      -    {
      -      x = -M_PI - x;
      -    }
      -
      -  x_squared = x * x;
      -  sin_x = 0.0;
      -
      -  /* Perform Taylor series approximation for sin(x) with six terms */
      -
      -  for (i = 0; i < 6; i++)
      -    {
      -      if (i % 2 == 0)
      -        {
      -          sin_x += x * _flt_inv_fact[i];
      -        }
      -      else
      -        {
      -          sin_x -= x * _flt_inv_fact[i];
      -        }
      -
      -      x *= x_squared;
      -    }
      -
      -  return sin_x;
      -}
      diff --git a/nuttx/lib/math/lib_sinh.c b/nuttx/lib/math/lib_sinh.c
      deleted file mode 100644
      index f33852433b..0000000000
      --- a/nuttx/lib/math/lib_sinh.c
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sinh.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double sinh(double x)
      -{
      -  x = exp(x);
      -  return ((x - (1.0 / x)) / 2.0);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_sinhf.c b/nuttx/lib/math/lib_sinhf.c
      deleted file mode 100644
      index e15cb14dc4..0000000000
      --- a/nuttx/lib/math/lib_sinhf.c
      +++ /dev/null
      @@ -1,42 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sinhf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float sinhf(float x)
      -{
      -  x = expf(x);
      -  return ((x - (1.0 / x)) / 2.0);
      -}
      diff --git a/nuttx/lib/math/lib_sinhl.c b/nuttx/lib/math/lib_sinhl.c
      deleted file mode 100644
      index b0fea29149..0000000000
      --- a/nuttx/lib/math/lib_sinhl.c
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sinhl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double sinhl(long double x)
      -{
      -  x = expl(x);
      -  return ((x - (1.0 / x)) / 2.0);
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_sinl.c b/nuttx/lib/math/lib_sinl.c
      deleted file mode 100644
      index a69b548cb3..0000000000
      --- a/nuttx/lib/math/lib_sinl.c
      +++ /dev/null
      @@ -1,114 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sinl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -
      -/************************************************************************
      - * Private Data
      - ************************************************************************/
      -
      -static long double _ldbl_inv_fact[] =
      -{
      -  1.0 / 1.0,                    // 1 / 1!
      -  1.0 / 6.0,                    // 1 / 3!
      -  1.0 / 120.0,                  // 1 / 5!
      -  1.0 / 5040.0,                 // 1 / 7!
      -  1.0 / 362880.0,               // 1 / 9!
      -  1.0 / 39916800.0,             // 1 / 11!
      -  1.0 / 6227020800.0,           // 1 / 13!
      -  1.0 / 1307674368000.0,        // 1 / 15!
      -  1.0 / 355687428096000.0,      // 1 / 17!
      -  1.0 / 121645100408832000.0,   // 1 / 19!
      -};
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -long double sinl(long double x)
      -{
      -  long double x_squared;
      -  long double sin_x;
      -  size_t i;
      -
      -  /* Move x to [-pi, pi) */
      -
      -  x = fmodl(x, 2 * M_PI);
      -  if (x >= M_PI)
      -    {
      -      x -= 2 * M_PI;
      -    }
      -
      -  if (x < -M_PI)
      -    {
      -      x += 2 * M_PI;
      -    }
      -
      -  /* Move x to [-pi/2, pi/2) */
      -
      -  if (x >= M_PI_2)
      -    {
      -      x = M_PI - x;
      -    }
      -
      -  if (x < -M_PI_2)
      -    {
      -      x = -M_PI - x;
      -    }
      -
      -  x_squared = x * x;
      -  sin_x = 0.0;
      -
      -  /* Perform Taylor series approximation for sin(x) with ten terms */
      -
      -  for (i = 0; i < 10; i++)
      -    {
      -      if (i % 2 == 0)
      -        {
      -          sin_x += x * _ldbl_inv_fact[i];
      -        }
      -      else
      -        {
      -          sin_x -= x * _ldbl_inv_fact[i];
      -        }
      -
      -      x *= x_squared;
      -    }
      -
      -  return sin_x;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_sqrt.c b/nuttx/lib/math/lib_sqrt.c
      deleted file mode 100644
      index d77997f7cd..0000000000
      --- a/nuttx/lib/math/lib_sqrt.c
      +++ /dev/null
      @@ -1,99 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sqrt.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double sqrt(double x)
      -{
      -  long double y, y1;
      -
      -  if (x < 0.0)
      -    {
      -      errno = EDOM;
      -      return NAN;
      -    }
      -
      -  if (isnan(x))
      -    {
      -      return NAN;
      -    }
      -
      -  if (isinf(x))
      -    {
      -      return INFINITY;
      -    }
      -
      -  if (x == 0.0)
      -    {
      -      return 0.0;
      -    }
      -
      -  /* Guess square root (using bit manipulation) */
      -
      -  y = lib_sqrtapprox(x);
      -
      -  /* Perform four iterations of approximation.  This number (4) is
      -   * definitely optimal
      -   */
      -
      -  y = 0.5 * (y + x / y);
      -  y = 0.5 * (y + x / y);
      -  y = 0.5 * (y + x / y);
      -  y = 0.5 * (y + x / y);
      -
      -  /* If guess was terribe (out of range of float).  Repeat approximation
      -   * until convergence.
      -   */
      -
      -  if (y * y < x - 1.0 || y * y > x + 1.0)
      -    {
      -      y1 = -1.0;
      -      while (y != y1)
      -        {
      -          y1 = y;
      -          y = 0.5 * (y + x / y);
      -        }
      -    }
      -
      -  return y;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_sqrtf.c b/nuttx/lib/math/lib_sqrtf.c
      deleted file mode 100644
      index 81817a0406..0000000000
      --- a/nuttx/lib/math/lib_sqrtf.c
      +++ /dev/null
      @@ -1,84 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sqrtf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float sqrtf(float x)
      -{
      -  float y;
      -
      -  /* Filter out invalid/trivial inputs */
      -
      -  if (x < 0.0)
      -    {
      -      errno = EDOM;
      -      return NAN;
      -    }
      -
      -  if (isnan(x))
      -    {
      -      return NAN;
      -    }
      -
      -  if (isinf(x))
      -    {
      -      return INFINITY;
      -    }
      -
      -  if (x == 0.0)
      -    {
      -      return 0.0;
      -    }
      -
      -  /* Guess square root (using bit manipulation) */
      -
      -  y = lib_sqrtapprox(x);
      -
      -  /* Perform three iterations of approximation. This number (3) is
      -   * definitely optimal
      -   */
      -
      -  y = 0.5 * (y + x / y);
      -  y = 0.5 * (y + x / y);
      -  y = 0.5 * (y + x / y);
      -
      -  return y;
      -}
      diff --git a/nuttx/lib/math/lib_sqrtl.c b/nuttx/lib/math/lib_sqrtl.c
      deleted file mode 100644
      index 6674fe50f8..0000000000
      --- a/nuttx/lib/math/lib_sqrtl.c
      +++ /dev/null
      @@ -1,101 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_sqrtl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009-2011 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double sqrtl(long double x)
      -{
      -  long double y, y1;
      -
      -  /* Filter out invalid/trivial inputs */
      -
      -  if (x < 0.0)
      -    {
      -      errno = EDOM;
      -      return NAN;
      -    }
      -
      -  if (isnan(x))
      -    {
      -    return NAN;
      -    }
      -
      -  if (isinf(x))
      -    {
      -    return INFINITY;
      -    }
      -
      -  if (x == 0.0)
      -    {
      -    return 0.0;
      -    }
      -
      -  /* Guess square root (using bit manipulation) */
      -
      -  y = lib_sqrtapprox(x);
      -
      -  /* Perform four iterations of approximation.  This number (4) is
      -   * definitely optimal
      -   */
      -
      -  y = 0.5 * (y + x / y);
      -  y = 0.5 * (y + x / y);
      -  y = 0.5 * (y + x / y);
      -  y = 0.5 * (y + x / y);
      -
      -  /* If guess was terribe (out of range of float).  Repeat approximation
      -   * until convergence
      -   */
      -
      -  if (y * y < x - 1.0 || y * y > x + 1.0)
      -    {
      -      y1 = -1.0;
      -      while (y != y1)
      -        {
      -          y1 = y;
      -          y = 0.5 * (y + x / y);
      -        }
      -    }
      -
      -  return y;
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_tan.c b/nuttx/lib/math/lib_tan.c
      deleted file mode 100644
      index bce14b3270..0000000000
      --- a/nuttx/lib/math/lib_tan.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_tan.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double tan(double x)
      -{
      -  return (sin(x) / cos(x));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_tanf.c b/nuttx/lib/math/lib_tanf.c
      deleted file mode 100644
      index 3db3bda265..0000000000
      --- a/nuttx/lib/math/lib_tanf.c
      +++ /dev/null
      @@ -1,41 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_tanf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float tanf(float x)
      -{
      -  return (sinf(x) / cosf(x));
      -}
      diff --git a/nuttx/lib/math/lib_tanh.c b/nuttx/lib/math/lib_tanh.c
      deleted file mode 100644
      index 46fddd06df..0000000000
      --- a/nuttx/lib/math/lib_tanh.c
      +++ /dev/null
      @@ -1,49 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_tanh.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -double tanh(double x)
      -{
      -  double x0 = exp(x);
      -  double x1 = 1.0 / x0;
      -
      -  return ((x0 + x1) / (x0 - x1));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_tanhf.c b/nuttx/lib/math/lib_tanhf.c
      deleted file mode 100644
      index 94d15cc60d..0000000000
      --- a/nuttx/lib/math/lib_tanhf.c
      +++ /dev/null
      @@ -1,44 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_tanhf.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -float tanhf(float x)
      -{
      -  float x0 = expf(x);
      -  float x1 = 1.0 / x0;
      -
      -  return ((x0 + x1) / (x0 - x1));
      -}
      diff --git a/nuttx/lib/math/lib_tanhl.c b/nuttx/lib/math/lib_tanhl.c
      deleted file mode 100644
      index 23c11d6672..0000000000
      --- a/nuttx/lib/math/lib_tanhl.c
      +++ /dev/null
      @@ -1,49 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_tanhl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double tanhl(long double x)
      -{
      -  long double x0 = exp(x);
      -  long double x1 = 1.0 / x0;
      -
      -  return ((x0 + x1) / (x0 - x1));
      -}
      -#endif
      diff --git a/nuttx/lib/math/lib_tanl.c b/nuttx/lib/math/lib_tanl.c
      deleted file mode 100644
      index 4973aa073c..0000000000
      --- a/nuttx/lib/math/lib_tanl.c
      +++ /dev/null
      @@ -1,46 +0,0 @@
      -/************************************************************************
      - * lib/math/lib_tanl.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Ported by: Darcy Gong
      - *
      - * It derives from the Rhombs OS math library by Nick Johnson which has
      - * a compatibile, MIT-style license:
      - *
      - * Copyright (C) 2009, 2010 Nick Johnson 
      - * 
      - * Permission to use, copy, modify, and distribute this software for any
      - * purpose with or without fee is hereby granted, provided that the above
      - * copyright notice and this permission notice appear in all copies.
      - * 
      - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_DOUBLE
      -long double tanl(long double x)
      -{
      -  return (sinl(x) / cosl(x));
      -}
      -#endif
      diff --git a/nuttx/lib/misc/Make.defs b/nuttx/lib/misc/Make.defs
      deleted file mode 100644
      index c12533f754..0000000000
      --- a/nuttx/lib/misc/Make.defs
      +++ /dev/null
      @@ -1,69 +0,0 @@
      -############################################################################
      -# lib/misc/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the internal C files to the build
      -
      -CSRCS += lib_init.c lib_filesem.c
      -
      -# Add C files that depend on file OR socket descriptors
      -
      -ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
      -
      -CSRCS += lib_sendfile.c
      -ifneq ($(CONFIG_NFILE_STREAMS),0)
      -CSRCS += lib_streamsem.c
      -endif
      -
      -else
      -ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0)
      -
      -CSRCS += lib_sendfile.c
      -ifneq ($(CONFIG_NFILE_STREAMS),0)
      -CSRCS += lib_streamsem.c
      -endif
      -
      -endif
      -endif
      -
      -# Add the miscellaneous C files to the build
      -
      -CSRCS += lib_match.c
      -CSRCS += lib_crc32.c
      -CSRCS += lib_dbg.c lib_dumpbuffer.c
      -
      -# Add the misc directory to the build
      -
      -DEPPATH += --dep-path misc
      -VPATH += :misc
      diff --git a/nuttx/lib/misc/lib_crc32.c b/nuttx/lib/misc/lib_crc32.c
      deleted file mode 100644
      index f851598e01..0000000000
      --- a/nuttx/lib/misc/lib_crc32.c
      +++ /dev/null
      @@ -1,123 +0,0 @@
      -/************************************************************************************************
      - * lib/misc/lib_crc32.c
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
      - *
      - * The logic in this file was developed by Gary S. Brown:
      - *
      - *   COPYRIGHT (C) 1986 Gary S. Brown.  You may use this program, or code or tables
      - *   extracted from it, as desired without restriction.
      - *
      - * First, the polynomial itself and its table of feedback terms.  The polynomial is:
      - *
      - *    X^32+X^26+X^23+X^22+X^16+X^12+X^11+X^10+X^8+X^7+X^5+X^4+X^2+X^1+X^0
      - *
      - * Note that we take it "backwards" and put the highest-order term in the lowest-order bit.
      - * The X^32 term is "implied"; the LSB is the X^31 term, etc.  The X^0 term (usually shown
      - * as "+1") results in the MSB being 1
      - *
      - * Note that the usual hardware shift register implementation, which is what we're using
      - * (we're merely optimizing it by doing eight-bit chunks at a time) shifts bits into the
      - * lowest-order term.  In our implementation, that means shifting towards the right.  Why
      - * do we do it this way?  Because the calculated CRC must be transmitted in order from
      - * highest-order term to lowest-order term.  UARTs transmit characters in order from LSB
      - * to MSB.  By storing the CRC this way we hand it to the UART in the order low-byte to
      - * high-byte; the UART sends each low-bit to hight-bit; and the result is transmission bit
      - * by bit from highest- to lowest-order term without requiring any bit shuffling on our
      - * part.  Reception works similarly
      - *
      - * The feedback terms table consists of 256, 32-bit entries.  Notes
      - *
      - * - The table can be generated at runtime if desired; code to do so is shown later.  It
      - *   might not be obvious, but the feedback terms simply represent the results of eight
      - *   shift/xor operations for all combinations of data and CRC register values
      - *
      - * - The values must be right-shifted by eight bits by the updcrc logic; the shift must
      - *   be u_(bring in zeroes).  On some hardware you could probably optimize the shift in
      - *   assembler by using byte-swap instructions polynomial $edb88320
      -  ************************************************************************************************/
      -
      -/************************************************************************************************
      - * Included Files
      - ************************************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************************************************
      - * Private Data
      - ************************************************************************************************/
      - 
      -static const uint32_t crc32_tab[] =
      -{
      -  0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
      -  0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
      -  0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
      -  0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
      -  0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
      -  0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
      -  0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
      -  0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
      -  0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
      -  0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
      -  0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
      -  0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
      -  0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
      -  0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
      -  0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
      -  0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
      -  0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
      -  0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
      -  0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
      -  0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
      -  0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
      -  0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
      -  0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
      -  0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
      -  0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
      -  0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
      -  0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
      -  0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
      -  0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
      -  0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
      -  0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
      -  0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
      -};
      -
      -/************************************************************************************************
      - * Public Functions
      - ************************************************************************************************/
      -/************************************************************************************************
      - * Name: crc32part
      - *
      - * Description:
      - *   Continue CRC calculation on a part of the buffer.
      - *
      - ************************************************************************************************/
      -
      -uint32_t crc32part(FAR const uint8_t *src, size_t len, uint32_t crc32val)
      -{
      -  size_t i;
      -
      -  for (i = 0;  i < len;  i++)
      -    {
      -      crc32val = crc32_tab[(crc32val ^ src[i]) & 0xff] ^ (crc32val >> 8);
      -    }
      -  return crc32val;
      -}
      -
      -/************************************************************************************************
      - * Name: crc32
      - *
      - * Description:
      - *   Return a 32-bit CRC of the contents of the 'src' buffer, length 'len'
      - *
      - ************************************************************************************************/
      -
      -uint32_t crc32(FAR const uint8_t *src, size_t len)
      -{
      -  return crc32part(src, len, 0);
      -}
      diff --git a/nuttx/lib/misc/lib_dbg.c b/nuttx/lib/misc/lib_dbg.c
      deleted file mode 100644
      index aacdaa30a9..0000000000
      --- a/nuttx/lib/misc/lib_dbg.c
      +++ /dev/null
      @@ -1,165 +0,0 @@
      -/****************************************************************************
      - * lib/misc/lib_dbg.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/* Debug output is initially disabled */
      -
      -#ifdef CONFIG_DEBUG_ENABLE
      -bool g_dbgenable;
      -#endif
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: dbg_enable
      - *
      - * Description:
      - *  Enable or disable debug output.
      - *
      - ****************************************************************************/
      -
      -#ifdef CONFIG_DEBUG_ENABLE
      -void dbg_enable(bool enable)
      -{
      -  g_dbgenable = enable;
      -}
      -#endif
      -
      -/****************************************************************************
      - * Name: dbg, lldbg, vdbg
      - *
      - * Description:
      - *  If the cross-compiler's pre-processor does not support variable
      - * length arguments, then these additional APIs will be built.
      - *
      - ****************************************************************************/
      -
      -#ifndef CONFIG_CPP_HAVE_VARARGS
      -#ifdef CONFIG_DEBUG
      -int dbg(const char *format, ...)
      -{
      -  va_list ap;
      -  int     ret;
      -
      -#ifdef CONFIG_DEBUG_ENABLE
      -  ret = 0;
      -  if (g_dbgenable)
      -#endif
      -    {
      -      va_start(ap, format);
      -      ret = lib_rawvprintf(format, ap);
      -      va_end(ap);
      -    }
      -
      -  return ret;
      -}
      -
      -#ifdef CONFIG_ARCH_LOWPUTC
      -int lldbg(const char *format, ...)
      -{
      -  va_list ap;
      -  int     ret;
      -
      -#ifdef CONFIG_DEBUG_ENABLE
      -  ret = 0;
      -  if (g_dbgenable)
      -#endif
      -    {
      -      va_start(ap, format);
      -      ret = lib_lowvprintf(format, ap);
      -      va_end(ap);
      -    }
      -
      -  return ret;
      -}
      -#endif
      -
      -#ifdef CONFIG_DEBUG_VERBOSE
      -int vdbg(const char *format, ...)
      -{
      -  va_list ap;
      -  int     ret;
      -
      -#ifdef CONFIG_DEBUG_ENABLE
      -  ret = 0;
      -  if (g_dbgenable)
      -#endif
      -    {
      -      va_start(ap, format);
      -      ret = lib_rawvprintf(format, ap);
      -      va_end(ap);
      -    }
      -
      -  return ret;
      -}
      -
      -#ifdef CONFIG_ARCH_LOWPUTC
      -int llvdbg(const char *format, ...)
      -{
      -  va_list ap;
      -  int     ret;
      -
      -#ifdef CONFIG_DEBUG_ENABLE
      -  ret = 0;
      -  if (g_dbgenable)
      -#endif
      -    {
      -      va_start(ap, format);
      -      ret = lib_lowvprintf(format, ap);
      -      va_end(ap);
      -    }
      -
      -  return ret;
      -}
      -#endif /* CONFIG_ARCH_LOWPUTC */
      -#endif /* CONFIG_DEBUG_VERBOSE */
      -#endif /* CONFIG_DEBUG */
      -#endif /* CONFIG_CPP_HAVE_VARARGS */
      diff --git a/nuttx/lib/misc/lib_dumpbuffer.c b/nuttx/lib/misc/lib_dumpbuffer.c
      deleted file mode 100644
      index 155468ca12..0000000000
      --- a/nuttx/lib/misc/lib_dumpbuffer.c
      +++ /dev/null
      @@ -1,129 +0,0 @@
      -/****************************************************************************
      - * lib/misc/lib_dumpbuffer.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor definitions
      - ****************************************************************************/
      -
      -/* Select the lowest level debug interface available */
      -
      -#ifdef CONFIG_CPP_HAVE_VARARGS
      -#  ifdef CONFIG_ARCH_LOWPUTC
      -#    define message(format, arg...) lib_lowprintf(format, ##arg)
      -#  else
      -#    define message(format, arg...) lib_rawprintf(format, ##arg)
      -#  endif
      -#else
      -#  ifdef CONFIG_ARCH_LOWPUTC
      -#    define message lib_lowprintf
      -#  else
      -#    define message lib_rawprintf
      -#  endif
      -#endif
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_dumpbuffer
      - *
      - * Description:
      - *  Do a pretty buffer dump
      - *
      - ****************************************************************************/
      -
      -void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer, unsigned int buflen)
      -{
      -  int i, j, k;
      -
      -  message("%s (%p):\n", msg, buffer);
      -  for (i = 0; i < buflen; i += 32)
      -    {
      -      message("%04x: ", i);
      -      for (j = 0; j < 32; j++)
      -        {
      -          k = i + j;
      -
      -          if (j == 16)
      -            {
      -              message(" ");
      -            }
      -
      -          if (k < buflen)
      -            {
      -              message("%02x", buffer[k]);
      -            }
      -          else
      -            {
      -              message("  ");
      -            }
      -        }
      -
      -      message(" ");
      -      for (j = 0; j < 32; j++)
      -        {
      -         k = i + j;
      -
      -          if (j == 16)
      -            {
      -              message(" ");
      -            }
      -
      -          if (k < buflen)
      -            {
      -              if (buffer[k] >= 0x20 && buffer[k] < 0x7f)
      -                {
      -                  message("%c", buffer[k]);
      -                }
      -              else
      -                {
      -                  message(".");
      -                }
      -            }
      -        }
      -      message("\n");
      -   }
      -}
      diff --git a/nuttx/lib/misc/lib_filesem.c b/nuttx/lib/misc/lib_filesem.c
      deleted file mode 100644
      index 1d1f25c2fd..0000000000
      --- a/nuttx/lib/misc/lib_filesem.c
      +++ /dev/null
      @@ -1,145 +0,0 @@
      -/************************************************************************
      - * lib/misc/lib_filesem.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -
      -/************************************************************************
      - * Pre-processor Definitions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Data
      - ************************************************************************/
      -
      -/************************************************************************
      - * Global Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * lib_sem_initialize
      - ************************************************************************/
      -
      -void lib_sem_initialize(FAR struct file_struct *stream)
      -{
      -  /* Initialize the LIB semaphore to one (to support one-at-
      -   * a-time access to private data sets.
      -   */
      -
      -  (void)sem_init(&stream->fs_sem, 0, 1);
      -
      -  stream->fs_holder = -1;
      -  stream->fs_counts = 0;
      -}
      -
      -/************************************************************************
      - * lib_take_semaphore
      - ************************************************************************/
      -
      -void lib_take_semaphore(FAR struct file_struct *stream)
      -{
      -  pid_t my_pid = getpid();
      -
      -  /* Do I already have the semaphore? */
      -
      -  if (stream->fs_holder == my_pid)
      -    {
      -      /* Yes, just increment the number of references that I have */
      -
      -      stream->fs_counts++;
      -    }
      -  else
      -    {
      -      /* Take the semaphore (perhaps waiting) */
      -
      -      while (sem_wait(&stream->fs_sem) != 0)
      -	{
      -	  /* The only case that an error should occr here is if
      -	   * the wait was awakened by a signal.
      -	   */
      -
      -	  ASSERT(get_errno() == EINTR);
      -	}
      -
      -      /* We have it.  Claim the stak and return */
      -
      -      stream->fs_holder = my_pid;
      -      stream->fs_counts = 1;
      -    }
      -}
      -
      -/************************************************************************
      - * lib_give_semaphore
      - ************************************************************************/
      -
      -void lib_give_semaphore(FAR struct file_struct *stream)
      -{
      -  pid_t my_pid = getpid();
      -
      -  /* I better be holding at least one reference to the semaphore */
      -
      -  ASSERT(stream->fs_holder == my_pid);
      -
      -  /* Do I hold multiple references to the semphore */
      -
      -  if (stream->fs_counts > 1)
      -    {
      -      /* Yes, just release one count and return */
      -
      -      stream->fs_counts--;
      -    }
      -  else
      -    {
      -      /* Nope, this is the last reference I have */
      -
      -      stream->fs_holder = -1;
      -      stream->fs_counts = 0;
      -      ASSERT(sem_post(&stream->fs_sem) == 0);
      -    }
      -}
      -#endif /* CONFIG_STDIO_BUFFER_SIZE */
      diff --git a/nuttx/lib/misc/lib_init.c b/nuttx/lib/misc/lib_init.c
      deleted file mode 100644
      index 3403a837b9..0000000000
      --- a/nuttx/lib/misc/lib_init.c
      +++ /dev/null
      @@ -1,207 +0,0 @@
      -/************************************************************
      - * lib/misc/lib_init.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/************************************************************
      - * Definitions
      - ************************************************************/
      -
      -/************************************************************
      - * Private Variables
      - ************************************************************/
      -
      -/************************************************************
      - * Private Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * lib_initialize
      - ************************************************************/
      -
      -/* General library initialization hook */
      -
      -void weak_const_function lib_initialize(void)
      -{
      -}
      -
      -#if CONFIG_NFILE_STREAMS > 0
      -/* The following function is called when a new TCB is allocated.  It
      - * creates the streamlist instance that is stored in the TCB.
      - */
      -
      -FAR struct streamlist *lib_alloclist(void)
      -{
      -  FAR struct streamlist *list;
      -  list = (FAR struct streamlist*)lib_zalloc(sizeof(struct streamlist));
      -  if (list)
      -    {
      -      int i;
      -
      -      /* Start with a reference count of one */
      -
      -      list->sl_crefs = 1;
      -
      -      /* Initialize the list access mutex */
      -
      -      (void)sem_init(&list->sl_sem, 0, 1);
      -
      -      /* Initialize each FILE structure */
      -
      -      for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
      -       {
      -         /* Clear the IOB */
      -
      -          memset(&list->sl_streams[i], 0, sizeof(FILE));
      -
      -          /* Indicate not opened */
      -
      -          list->sl_streams[i].fs_filedes = -1;
      -
      -          /* Initialize the stream semaphore to one to support one-at-
      -           * a-time access to private data sets.
      -           */
      -
      -          lib_sem_initialize(&list->sl_streams[i]);
      -        }
      -    }
      -  return list;
      -
      -}
      -
      -/* This function is called when a TCB is closed (such as with
      - * pthread_create().  It increases the reference count on the stream
      - * list.
      - */
      -
      -void lib_addreflist(FAR struct streamlist *list)
      -{
      -  if (list)
      -    {
      -       /* Increment the reference count on the list.
      -        * NOTE: that we disable interrupts to do this
      -        * (vs. taking the list semaphore).  We do this
      -        * because file cleanup operations often must be
      -        * done from the IDLE task which cannot wait
      -        * on semaphores.
      -        */
      -
      -       register irqstate_t flags = irqsave();
      -       list->sl_crefs++;
      -       irqrestore(flags);
      -    }
      -}
      -
      -/* this function is called when a TCB is destroyed.  Note that is
      - * does not close the file by release this inode.  This happens
      - * separately when the file descriptor list is freed.
      - */
      -
      -void lib_releaselist(FAR struct streamlist *list)
      -{
      -  int crefs;
      -  if (list)
      -    {
      -       /* Decrement the reference count on the list.
      -        * NOTE: that we disable interrupts to do this
      -        * (vs. taking the list semaphore).  We do this
      -        * because file cleanup operations often must be
      -        * done from the IDLE task which cannot wait
      -        * on semaphores.
      -        */
      -
      -       register irqstate_t flags = irqsave();
      -       crefs = --(list->sl_crefs);
      -       irqrestore(flags);
      -
      -       /* If the count decrements to zero, then there is no reference
      -        * to the structure and it should be deallocated.  Since there
      -        * are references, it would be an error if any task still held
      -        * a reference to the list's semaphore.
      -        */
      -
      -       if (crefs <= 0)
      -          {
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -            int i;
      -#endif
      -            /* Destroy the semaphore and release the filelist */
      -
      -            (void)sem_destroy(&list->sl_sem);
      -
      -            /* Release each stream in the list */
      -
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -            for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
      -             {
      -               /* Destroy the semaphore that protects the IO buffer */
      -
      -               (void)sem_destroy(&list->sl_streams[i].fs_sem);
      -
      -               /* Release the IO buffer */
      -               if (list->sl_streams[i].fs_bufstart)
      -                 {
      -                   sched_free(list->sl_streams[i].fs_bufstart);
      -                 }
      -             }
      -#endif
      -           /* Finally, release the list itself */
      -
      -            sched_free(list);
      -         }
      -     }
      -}
      -
      -#endif /* CONFIG_NFILE_STREAMS */
      -
      -
      diff --git a/nuttx/lib/misc/lib_match.c b/nuttx/lib/misc/lib_match.c
      deleted file mode 100644
      index 18e0632ec6..0000000000
      --- a/nuttx/lib/misc/lib_match.c
      +++ /dev/null
      @@ -1,148 +0,0 @@
      -/****************************************************************************
      - * lib/misc/lib_match.c - simple shell-style filename matcher
      - *
      - * Simple shell-style filename pattern matcher written by Jef Poskanzer
      - * This pattern matcher only handles '?', '*' and '**', and  multiple
      - * patterns separated by '|'.
      - *
      - *   Copyright © 1995,2000 by Jef Poskanzer .
      - *   All rights reserved.
      - *
      - * 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.
      - *
      - * THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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 
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: match_one
      - *
      - * Description:
      - *   Does all of the work for one '|' delimited pattern
      - *
      - * Returned Value:
      - *   Returns 1 (match) or 0 (no-match).
      - *
      - ****************************************************************************/
      -
      -static int match_one(const char *pattern, int patlen, const char *string)
      -{
      -  const char *p;
      -  int pl;
      -  int i;
      -
      -  for (p = pattern; p - pattern < patlen; p++, string++)
      -    {
      -      if (*p == '?' && *string != '\0')
      -        {
      -          continue;
      -        }
      -
      -      if (*p == '*')
      -        {
      -          p++;
      -          if (*p == '*')
      -            {
      -              /* Double-wildcard matches anything. */
      -
      -              p++;
      -              i = strlen(string);
      -            }
      -          else
      -            {
      -              /* Single-wildcard matches anything but slash. */
      -
      -              i = strcspn(string, "/");
      -            }
      -
      -          pl = patlen - (p - pattern);
      -          for (; i >= 0; i--)
      -            {
      -              if (match_one(p, pl, &(string[i])))
      -                {
      -                  return 1;
      -                }
      -            }
      -          return 0;
      -        }
      -
      -      if (*p != *string)
      -        {
      -          return 0;
      -        }
      -    }
      -
      -  if (*string == '\0')
      -    {
      -      return 1;
      -    }
      -  return 0;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: match
      - *
      - * Description:
      - *   Simple shell-style filename pattern matcher written by Jef Poskanzer
      - *   This pattern matcher only handles '?', '*' and '**', and  multiple
      - *   patterns separated by '|'.
      - *
      - * Returned Value:
      - *   Returns 1 (match) or 0 (no-match).
      - *
      - ****************************************************************************/
      -
      -int match(const char *pattern, const char *string)
      -{
      -  const char *or;
      -
      -  for (;;)
      -    {
      -      or = strchr(pattern, '|');
      -      if (or == (char *)0)
      -        {
      -          return match_one(pattern, strlen(pattern), string);
      -        }
      -
      -      if (match_one(pattern, or - pattern, string))
      -        {
      -          return 1;
      -        }
      -
      -      pattern = or + 1;
      -    }
      -}
      -
      diff --git a/nuttx/lib/misc/lib_sendfile.c b/nuttx/lib/misc/lib_sendfile.c
      deleted file mode 100644
      index a82eb325e7..0000000000
      --- a/nuttx/lib/misc/lib_sendfile.c
      +++ /dev/null
      @@ -1,297 +0,0 @@
      -/************************************************************************
      - * lib/misc/lib_streamsem.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#if CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0
      -
      -/************************************************************************
      - * Private types
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Public Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Name: sendfile
      - *
      - * Description:
      - *   sendfile() copies data between one file descriptor and another.
      - *   sendfile() basically just wraps a sequence of reads() and writes()
      - *   to perform a copy.  It serves a purpose in systems where there is
      - *   a penalty for copies to between user and kernal space, but really
      - *   nothing in NuttX but provide some Linux compatible (and adding
      - *   another 'almost standard' interface). 
      - *
      - *   NOTE: This interface is *not* specified in POSIX.1-2001, or other
      - *   standards.  The implementation here is very similar to the Linux
      - *   sendfile interface.  Other UNIX systems implement sendfile() with
      - *   different semantics and prototypes.  sendfile() should not be used
      - *   in portable programs.
      - *
      - * Input Parmeters:
      - *   infd   - A file (or socket) descriptor opened for reading
      - *   outfd  - A descriptor opened for writing.
      - *   offset - If 'offset' is not NULL, then it points to a variable
      - *            holding the file offset from which sendfile() will start
      - *            reading data from 'infd'.  When sendfile() returns, this
      - *            variable will be set to the offset of the byte following
      - *            the last byte that was read.  If 'offset' is not NULL,
      - *            then sendfile() does not modify the current file offset of
      - *            'infd'; otherwise the current file offset is adjusted to
      - *            reflect the number of bytes read from 'infd.'
      - *
      - *            If 'offset' is NULL, then data will be read from 'infd'
      - *            starting at the current file offset, and the file offset
      - *            will be updated by the call.
      - *   count -  The number of bytes to copy between the file descriptors.
      - *
      - * Returned Value:
      - *   If the transfer was successful, the number of bytes written to outfd is
      - *   returned.  On error, -1 is returned, and errno is set appropriately.
      - *   There error values are those returned by read() or write() plus:
      - *
      - *   EINVAL - Bad input parameters.
      - *   ENOMEM - Could not allocated an I/O buffer
      - *
      - ************************************************************************/
      -
      -ssize_t sendfile(int outfd, int infd, off_t *offset, size_t count)
      -{
      -  FAR uint8_t *iobuffer;
      -  FAR uint8_t *wrbuffer;
      -  off_t startpos = 0;
      -  ssize_t nbytesread;
      -  ssize_t nbyteswritten;
      -  size_t  ntransferred;
      -  bool endxfr;
      -
      -  /* Get the current file position. */
      -
      -  if (offset)
      -    {
      -      /* Use lseek to get the current file position */
      -
      -      startpos = lseek(infd, 0, SEEK_CUR);
      -      if (startpos == (off_t)-1)
      -        {
      -          return ERROR;
      -        }
      -
      -      /* Use lseek again to set the new file position */
      -
      -      if (lseek(infd, *offset, SEEK_SET) == (off_t)-1)
      -        {
      -          return ERROR;
      -        }
      -    }
      -
      -  /* Allocate an I/O buffer */
      -
      -  iobuffer = (FAR void *)malloc(CONFIG_LIB_SENDFILE_BUFSIZE);
      -  if (!iobuffer)
      -    {
      -      set_errno(ENOMEM);
      -      return ERROR;
      -    }
      -
      -  /* Now transfer 'count' bytes from the infd to the outfd */
      -
      -  for (ntransferred = 0, endxfr = false; ntransferred < count && !endxfr; )
      -    {
      -      /* Loop until the read side of the transfer comes to some conclusion */
      -
      -      do
      -        {
      -          /* Read a buffer of data from the infd */
      -
      -          nbytesread = read(infd, iobuffer, CONFIG_LIB_SENDFILE_BUFSIZE);
      -
      -          /* Check for end of file */
      -
      -          if (nbytesread == 0)
      -            {
      -              /* End of file.  Break out and return current number of bytes
      -               * transferred.
      -               */
      -
      -              endxfr = true;
      -              break;
      -            }
      -
      -          /* Check for a read ERROR.  EINTR is a special case.  This function
      -           * should break out and return an error if EINTR is returned and
      -           * no data has been transferred.  But what should it do if some
      -           * data has been transferred?  I suppose just continue?
      -           */
      -
      -          else if (nbytesread < 0)
      -            {
      -              /* EINTR is not an error (but will still stop the copy) */
      -
      -#ifndef CONFIG_DISABLE_SIGNALS
      -              if (errno != EINTR || ntransferred == 0)
      -#endif
      -                {
      -                  /* Read error.  Break out and return the error condition. */
      -
      -                  ntransferred = ERROR;
      -                  endxfr       = true;
      -                  break;
      -                }
      -            }
      -        }
      -      while (nbytesread < 0);
      -
      -      /* Was anything read? */
      -
      -      if (!endxfr)
      -        {
      -          /* Yes.. Loop until the read side of the transfer comes to some
      -           * conclusion.
      -           */
      -
      -          wrbuffer = iobuffer;
      -          do
      -            {
      -              /* Write the buffer of data to the outfd */
      -
      -              nbyteswritten = write(outfd, wrbuffer, nbytesread);
      -
      -              /* Check for a complete (or parial) write.  write() should not
      -               * return zero.
      -               */
      -
      -              if (nbyteswritten >= 0)
      -                {
      -                  /* Advance the buffer pointer and decrement the number of bytes
      -                   * remaining in the iobuffer.  Typically, nbytesread will now
      -                   * be zero.
      -                   */
      -
      -                  wrbuffer     += nbyteswritten;
      -                  nbytesread   -= nbyteswritten;
      -
      -                  /* Increment the total number of bytes successfully transferred. */
      -
      -                  ntransferred += nbyteswritten;
      -                }
      -
      -              /* Otherwise an error occurred */
      -
      -              else
      -                {
      -                  /* Check for a read ERROR.  EINTR is a special case.  This
      -                   * function should break out and return an error if EINTR
      -                   * is returned and no data has been transferred.  But what
      -                   * should it do if some data has been transferred?  I
      -                   * suppose just continue?
      -                   */
      -
      -#ifndef CONFIG_DISABLE_SIGNALS
      -                  if (errno != EINTR || ntransferred == 0)
      -#endif
      -                    {
      -                      /* Write error.  Break out and return the error condition */
      -
      -                      ntransferred = ERROR;
      -                      endxfr       = true;
      -                      break;
      -                    }
      -                }
      -            }
      -          while (nbytesread > 0);
      -        }
      -    }
      -
      -  /* Release the I/O buffer */
      -
      -  free(iobuffer);
      -
      -  /* Return the current file position */
      -
      -  if (offset)
      -    {
      -      /* Use lseek to get the current file position */
      -
      -      off_t curpos = lseek(infd, 0, SEEK_CUR);
      -      if (curpos == (off_t)-1)
      -        {
      -          return ERROR;
      -        }
      -
      -      /* Return the current file position */
      -
      -      *offset = curpos;
      -
      -      /* Use lseek again to restore the original file position */
      -
      -      if (lseek(infd, startpos, SEEK_SET) == (off_t)-1)
      -        {
      -          return ERROR;
      -        }
      -    }
      -
      -  /* Finally return the number of bytes actually transferred (or ERROR
      -   * if any failure occurred).
      -   */
      -
      -  return ntransferred;
      -}
      -
      -#endif /* CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0 */
      diff --git a/nuttx/lib/misc/lib_streamsem.c b/nuttx/lib/misc/lib_streamsem.c
      deleted file mode 100644
      index fdf494e751..0000000000
      --- a/nuttx/lib/misc/lib_streamsem.c
      +++ /dev/null
      @@ -1,90 +0,0 @@
      -/************************************************************************
      - * lib/misc/lib_streamsem.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/************************************************************************
      - * Private types
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Public Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -void stream_semtake(FAR struct streamlist *list)
      -{
      -  /* Take the semaphore (perhaps waiting) */
      -
      -  while (sem_wait(&list->sl_sem) != 0)
      -    {
      -      /* The only case that an error should occr here is if
      -       * the wait was awakened by a signal.
      -       */
      -
      -      ASSERT(get_errno() == EINTR);
      -    }
      -}
      -
      -void stream_semgive(FAR struct streamlist *list)
      -{
      -  sem_post(&list->sl_sem);
      -}
      -
      -
      diff --git a/nuttx/lib/mqueue/Make.defs b/nuttx/lib/mqueue/Make.defs
      deleted file mode 100644
      index 40dc6c13e6..0000000000
      --- a/nuttx/lib/mqueue/Make.defs
      +++ /dev/null
      @@ -1,48 +0,0 @@
      -############################################################################
      -# lib/mqueue/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -ifneq ($(CONFIG_DISABLE_MQUEUE),y)
      -
      -# Add the mqueue C files to the build
      -
      -CSRCS += mq_setattr.c mq_getattr.c
      -
      -# Add the mqueue directory to the build
      -
      -DEPPATH += --dep-path mqueue
      -VPATH += :mqueue
      -
      -endif
      -
      diff --git a/nuttx/lib/mqueue/mq_getattr.c b/nuttx/lib/mqueue/mq_getattr.c
      deleted file mode 100644
      index 9c9f47fdce..0000000000
      --- a/nuttx/lib/mqueue/mq_getattr.c
      +++ /dev/null
      @@ -1,104 +0,0 @@
      -/************************************************************************
      - * lib/mqueue/mq_getattr.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Definitions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Type Declarations
      - ************************************************************************/
      -
      -/************************************************************************
      - * Global Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Function:  mq_getattr
      - *
      - * Description:
      - *   This functions gets status information and attributes
      - *   associated with the specified message queue.
      - *
      - * Parameters:
      - *   mqdes - Message queue descriptor
      - *   mq_stat - Buffer in which to return attributes
      - *
      - * Return Value:
      - *   0 (OK) if attributes provided, -1 (ERROR) otherwise.
      - *
      - * Assumptions:
      - *
      - ************************************************************************/
      -
      -int mq_getattr(mqd_t mqdes, struct mq_attr *mq_stat)
      -{
      -  int ret = ERROR;
      -
      -  if (mqdes && mq_stat)
      -    {
      -      /* Return the attributes */
      -
      -      mq_stat->mq_maxmsg  = mqdes->msgq->maxmsgs;
      -      mq_stat->mq_msgsize = mqdes->msgq->maxmsgsize;
      -      mq_stat->mq_flags   = mqdes->oflags;
      -      mq_stat->mq_curmsgs = mqdes->msgq->nmsgs;
      -
      -      ret = OK;
      -    }
      -
      -  return ret;
      -}
      diff --git a/nuttx/lib/mqueue/mq_setattr.c b/nuttx/lib/mqueue/mq_setattr.c
      deleted file mode 100644
      index 1276d64e8a..0000000000
      --- a/nuttx/lib/mqueue/mq_setattr.c
      +++ /dev/null
      @@ -1,118 +0,0 @@
      -/************************************************************************
      - * lib/mqueue/mq_setattr.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include           /* O_NONBLOCK */
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Definitions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Type Declarations
      - ************************************************************************/
      -
      -/************************************************************************
      - * Global Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Function:  mq_setattr
      - *
      - * Description:
      - *   This function sets the attributes associated with the
      - *   specified message queue "mqdes."  Only the "O_NONBLOCK"
      - *   bit of the "mq_flags" can be changed.
      - *
      - *   If "oldstat" is non-null, mq_setattr() will store the
      - *   previous message queue attributes at that location (just
      - *   as would have been returned by mq_getattr()).
      - *
      - * Parameters:
      - *   mqdes - Message queue descriptor
      - *   mq_stat - New attributes
      - *   oldstate - Old attributes
      - *
      - * Return Value:
      - *   0 (OK) if attributes are set successfully, otherwise
      - *   -1 (ERROR).
      - *
      - * Assumptions:
      - *
      - ************************************************************************/
      -
      -int mq_setattr(mqd_t mqdes, const struct mq_attr *mq_stat,
      -               struct mq_attr *oldstat)
      -{
      -  int ret = ERROR;
      -
      -  if (mqdes && mq_stat)
      -    {
      -      /* Return the attributes if so requested */
      -
      -      if (oldstat)
      -        {
      -          (void)mq_getattr(mqdes, oldstat);
      -        }
      -
      -      /* Set the new value of the O_NONBLOCK flag. */
      -
      -      mqdes->oflags = ((mq_stat->mq_flags & O_NONBLOCK) |
      -                       (mqdes->oflags & (~O_NONBLOCK)));
      -      ret = OK;
      -    }
      -
      -  return ret;
      -}
      diff --git a/nuttx/lib/net/Make.defs b/nuttx/lib/net/Make.defs
      deleted file mode 100644
      index ae041bd2c5..0000000000
      --- a/nuttx/lib/net/Make.defs
      +++ /dev/null
      @@ -1,44 +0,0 @@
      -############################################################################
      -# lib/net/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the networking C files to the build
      -
      -CSRCS += lib_etherntoa.c lib_htons.c lib_htonl.c lib_inetaddr.c
      -CSRCS += lib_inetntoa.c lib_inetntop.c lib_inetpton.c
      -
      -# Add the net directory to the build
      -
      -DEPPATH += --dep-path net
      -VPATH += :net
      diff --git a/nuttx/lib/net/lib_etherntoa.c b/nuttx/lib/net/lib_etherntoa.c
      deleted file mode 100644
      index f89f205a2e..0000000000
      --- a/nuttx/lib/net/lib_etherntoa.c
      +++ /dev/null
      @@ -1,69 +0,0 @@
      -/****************************************************************************
      - * lib/net/lib_etherntoa.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: ether_ntoa
      - *
      - * Description:
      - *   The ether_ntoa() function converts the Ethernet host address addr given
      - *   in network byte order to a string in standard hex-digits-and-colons
      - *   notation. The string is returned in a statically allocated buffer, which
      - *   subsequent calls will overwrite.
      - *
      - ****************************************************************************/
      -
      -FAR char *ether_ntoa(FAR const struct ether_addr *addr)
      -{
      -  static char buffer[20];
      -  sprintf(buffer, "%02x:%02x:%02x:%02x:%02x:%02x",
      -          addr->ether_addr_octet[0], addr->ether_addr_octet[1],
      -          addr->ether_addr_octet[2], addr->ether_addr_octet[3],
      -          addr->ether_addr_octet[4], addr->ether_addr_octet[5]);
      -  return buffer;
      -}
      diff --git a/nuttx/lib/net/lib_htonl.c b/nuttx/lib/net/lib_htonl.c
      deleted file mode 100644
      index e4c3e53838..0000000000
      --- a/nuttx/lib/net/lib_htonl.c
      +++ /dev/null
      @@ -1,68 +0,0 @@
      -/************************************************************
      - * lib/net/lib_ntohl.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -/************************************************************
      - * Global Functions
      - ************************************************************/
      -
      -uint32_t htonl(uint32_t hl)
      -{
      -#ifdef CONFIG_ENDIAN_BIG
      -  return hl;
      -#else
      -  return (( (hl) >> 24) |
      -          (((hl) >>  8) & 0x0000ff00) |
      -          (((hl) <<  8) & 0x00ff0000) |
      -	  ( (hl) << 24));
      -#endif
      -}
      -
      -uint32_t ntohl(uint32_t nl)
      -{
      -#ifdef CONFIG_ENDIAN_BIG
      -  return nl;
      -#else
      -  return htonl(nl);
      -#endif
      -}
      diff --git a/nuttx/lib/net/lib_htons.c b/nuttx/lib/net/lib_htons.c
      deleted file mode 100644
      index b4117e1dc2..0000000000
      --- a/nuttx/lib/net/lib_htons.c
      +++ /dev/null
      @@ -1,65 +0,0 @@
      -/***************************************************************************
      - * lib/net/lib_htons.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ***************************************************************************/
      -
      -/***************************************************************************
      - * Compilation Switches
      - ***************************************************************************/
      -
      -/***************************************************************************
      - * Included Files
      - ***************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -/***************************************************************************
      - * Global Functions
      - ***************************************************************************/
      -
      -uint16_t htons(uint16_t hs)
      -{
      -  return HTONS(hs);
      -}
      -
      -uint16_t ntohs(uint16_t ns)
      -{
      -#ifdef CONFIG_ENDIAN_BIG
      -  return ns;
      -#else
      -  return htons(ns);
      -#endif
      -}
      diff --git a/nuttx/lib/net/lib_inetaddr.c b/nuttx/lib/net/lib_inetaddr.c
      deleted file mode 100644
      index 48b01d682f..0000000000
      --- a/nuttx/lib/net/lib_inetaddr.c
      +++ /dev/null
      @@ -1,74 +0,0 @@
      -/****************************************************************************
      - * lib/net/lib_inetaddr.c
      - *
      - *   Copyright (C) 2011 Yu Qiang. All rights reserved.
      - *   Author: Yu Qiang 
      - *
      - * This file is a part of NuttX:
      - *
      - *   Copyright (C) 2011 Gregory Nutt. All rights reserved.
      - *
      - * 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 
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * name inet_addr
      - *
      - * Description:
      - *   The inet_addr() function converts the string pointed to by cp, in the
      - *   standard IPv4 dotted decimal notation, to an integer value suitable for
      - *   use as an Internet address.
      - 
      - ****************************************************************************/
      -
      -in_addr_t inet_addr(FAR const char *cp)
      -{
      -  unsigned int a, b, c, d;
      -  uint32_t result;
      -
      -  sscanf(cp, "%u.%u.%u.%u", &a, &b, &c, &d);
      -  result   = a << 8;
      -  result  |= b;
      -  result <<= 8;
      -  result  |= c;
      -  result <<= 8;
      -  result  |= d;
      -  return HTONL(result);
      -}
      diff --git a/nuttx/lib/net/lib_inetntoa.c b/nuttx/lib/net/lib_inetntoa.c
      deleted file mode 100644
      index 0f4fb61df6..0000000000
      --- a/nuttx/lib/net/lib_inetntoa.c
      +++ /dev/null
      @@ -1,79 +0,0 @@
      -/****************************************************************************
      - * lib/net/lib_inetntoa.c
      - *
      - *   Copyright (C) 2007-2008, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -#ifndef CONFIG_NET_IPv6
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: inet_ntoa
      - *
      - * Description:
      - *   The inet_ntoa() function converts the Internet host address in given in
      - *   network byte order to a string in standard numbers-and-dots notation.
      - *   The string is returned in a statically allocated buffer, which subsequent
      - *   calls will overwrite.
      - *
      - ****************************************************************************/
      -
      -#ifdef CONFIG_CAN_PASS_STRUCTS
      -FAR char *inet_ntoa(struct in_addr in)
      -{
      -  static char buffer[INET_ADDRSTRLEN+2];
      -  FAR char *ptr = (FAR char*)&in.s_addr;
      -  sprintf(buffer, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]);
      -  return buffer;
      -}
      -#else
      -FAR char *_inet_ntoa(in_addr_t in)
      -{
      -  static char buffer[INET_ADDRSTRLEN+2];
      -  FAR char *ptr = (FAR char*)∈
      -  sprintf(buffer, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]);
      -  return buffer;
      -}
      -#endif
      -#endif /* !CONFIG_NET_IPv6 */
      -
      diff --git a/nuttx/lib/net/lib_inetntop.c b/nuttx/lib/net/lib_inetntop.c
      deleted file mode 100644
      index dc6a2d0d79..0000000000
      --- a/nuttx/lib/net/lib_inetntop.c
      +++ /dev/null
      @@ -1,202 +0,0 @@
      -/****************************************************************************
      - * lib/net/lib_inetntop.c
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Author: Gregory Nutt 
      - *
      - * Includes some logic extracted from hwport_ftpd, written by Jaehyuk Cho
      - *  which was released under the BSD license.
      - *
      - *   Copyright (C) HWPORT.COM. All rights reserved.
      - *   Author: JAEHYUK CHO 
      - *
      - * 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 
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: inet_ntop
      - *
      - * Description:
      - *  The inet_ntop() function converts a numeric address into a text string
      - *  suitable for presentation.
      - *
      - * Input Parameters:
      - *   af   - The af argument specifies the family of the address. This can be
      - *          AF_INET or AF_INET6.
      - *   src  - The src argument points to a buffer holding an address of the
      - *          specified type.  The address must be in network byte order.
      - *   dst  - The dst argument points to a buffer where the function stores
      - *          the resulting text string; it shall not be NULL.
      - *   size - The size argument specifies the size of this buffer, which must
      - *          be large enough to hold the text string (INET_ADDRSTRLEN
      - *          characters for IPv4, INET6_ADDRSTRLEN characters for IPv6).
      - *
      - * Returned Value:
      - *   inet_ntop() returns a pointer to the buffer containing the text string
      - *   if the conversion succeeds.  Otherwise, NULL is returned and the errno
      - *   is set to indicate the error.  There follow errno values may be set:
      - *
      - *   EAFNOSUPPORT - The af argument is invalid.
      - *   ENOSPC - The size of the inet_ntop() result buffer is inadequate
      - *
      - ****************************************************************************/
      -
      -FAR const char *inet_ntop(int af, FAR const void *src, FAR char *dst, socklen_t size)
      -{
      -  int errval;
      -#ifndef CONFIG_NET_IPv6
      -  FAR char *ptr;
      -
      -  DEBUGASSERT(src && dst);
      -
      -  if (af != AF_INET)
      -    {
      -      errval = EAFNOSUPPORT;
      -      goto errout;
      -    }
      -
      -  if (size < INET_ADDRSTRLEN)
      -    {
      -      errval = ENOSPC;
      -      goto errout;
      -    }
      -
      -  ptr = (FAR char*)src;
      -  sprintf(dst, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]);
      -  return dst;
      -#else
      -  FAR const struct in6_addr *in6_addr;
      -  uint16_t warray[8];
      -  int offset;
      -  int entry;
      -  int count;
      -  int maxentry;
      -  int maxcount;
      - 
      -  DEBUGASSERT(src && dst);
      -
      -  if (af != AF_INET6)
      -    {
      -      errval = EAFNOSUPPORT;
      -      goto errout;
      -    }
      -
      -  if (size < INET6_ADDRSTRLEN)
      -    {
      -      errval = ENOSPC;
      -      goto errout;
      -    }
      -
      -  in6_addr = (FAR const struct in6_addr *)src;
      -  entry    = -1;
      -  maxentry = -1;
      -  maxcount = 0;
      -  offset   = 0;
      -
      -  while (offset < 8)
      -    {
      -      warray[offset] = ntohs(in6_addr->s6_addr16[offset]);
      -      if (warray[offset] == 0)
      -        {
      -          entry = offset;
      -          count = 1;
      -          offset++;
      -
      -          while (offset < 8)
      -            {
      -              warray[offset] = ntohs(in6_addr->s6_addr16[offset]);
      -              if (warray[offset] != 0)
      -                {
      -                  break;
      -                }
      -              offset++;
      -              count++;
      -            }
      -
      -          if (count > maxcount)
      -            {
      -              maxentry = entry;
      -              maxcount = count;
      -            }
      -        }
      -      offset++;
      -    }
      -
      -  offset = 0;
      -  dst[0] = '\0';
      -
      -  while (offset < 8)
      -    {
      -      if (offset == maxentry)
      -        {
      -          size   -= snprintf(&dst[strlen(dst)], size, ":");
      -          offset += maxcount;
      -          if (offset >= 8)
      -            {
      -              size -= snprintf(&dst[strlen(dst)], size, ":");
      -            }
      -        }
      -      else
      -        {
      -          if (offset > 0)
      -            {
      -              size -= snprintf(&dst[strlen(dst)], size, ":");
      -            }
      -
      -          size -= snprintf(&dst[strlen(dst)], size, "%x", warray[offset]);
      -          offset++;
      -        }
      -    }
      -
      -    return dst;
      -#endif
      -
      -errout:
      -    set_errno(errval);
      -    memset(dst, 0, size);
      -    return NULL;
      -}
      diff --git a/nuttx/lib/net/lib_inetpton.c b/nuttx/lib/net/lib_inetpton.c
      deleted file mode 100644
      index 5371cd3f21..0000000000
      --- a/nuttx/lib/net/lib_inetpton.c
      +++ /dev/null
      @@ -1,338 +0,0 @@
      -/****************************************************************************
      - * lib/net/lib_inetpton.c
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Author: Gregory Nutt 
      - *
      - * Includes some logic extracted from hwport_ftpd, written by Jaehyuk Cho
      - *  which was released under the BSD license.
      - *
      - *   Copyright (C) HWPORT.COM. All rights reserved.
      - *   Author: JAEHYUK CHO 
      - *
      - * 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 
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: inet_pton
      - *
      - * Description:
      - *  The inet_pton() function converts an address in its standard text
      - *  presentation form into its numeric binary form.
      - *
      - *  If the af argument of inet_pton() is AF_INET, the src string will be
      - *  in the standard IPv4 dotted-decimal form:
      - *
      - *    ddd.ddd.ddd.ddd
      - *
      - *  where "ddd" is a one to three digit decimal number between 0 and 255.
      - *
      - *  If the af argument of inet_pton() is AF_INET6, the src string will be in
      - *  one of the following standard IPv6 text forms:
      - *
      - *  1. The preferred form is "x:x:x:x:x:x:x:x", where the 'x' s are the
      - *     hexadecimal values of the eight 16-bit pieces of the address. Leading
      - *     zeros in individual fields can be omitted, but there must be at least
      - *     one numeral in every field.
      - *
      - *  2. A string of contiguous zero fields in the preferred form can be shown
      - *     as "::". The "::" can only appear once in an address. Unspecified
      - *     addresses ( "0:0:0:0:0:0:0:0" ) may be represented simply as "::".
      - *
      - *  3. A third form that is sometimes more convenient when dealing with a
      - *     mixed environment of IPv4 and IPv6 nodes is "x:x:x:x:x:x:d.d.d.d",
      - *     where the 'x' s are the hexadecimal values of the six high-order
      - *     16-bit pieces of the address, and the 'd' s are the decimal values
      - *     of the four low-order 8-bit pieces of the address (standard IPv4
      - *     representation).
      - *
      - * Input Parameters:
      - *   af   - The af argument specifies the family of the address. This can be
      - *          AF_INET or AF_INET6.
      - *   src  - The src argument points to the string being passed in.
      - *   dst  - The dst argument points to a numstr into which the function stores
      - *          the numeric address; this must be large enough to hold the numeric
      - *          address (32 bits for AF_INET, 128 bits for AF_INET6).
      - *
      - * Returned Value:
      - *   The inet_pton() function returns 1 if the conversion succeeds, with the
      - *   address pointed to by dst in network byte order. It will return 0 if the
      - *   input is not a valid IPv4 dotted-decimal string or a valid IPv6 address
      - *   string, or -1 with errno set to EAFNOSUPPOR] if the af argument is unknown.
      - *
      - ****************************************************************************/
      -
      -int inet_pton(int af, FAR const char *src, FAR void *dst)
      -{
      -#ifndef CONFIG_NET_IPv6
      -  size_t srcoffset;
      -  size_t numoffset;
      -  int value;
      -  int ndots;
      -  uint8_t ch;
      -  char numstr[4];
      -  uint8_t *ip;
      -
      -  DEBUGASSERT(src && dst);
      -
      -  if (af != AF_INET)
      -    {
      -      set_errno(EAFNOSUPPORT);
      -      return -1;
      -    }
      -
      -  (void)memset(dst, 0, sizeof(struct in_addr));
      -
      -  ip        = (uint8_t *)dst;
      -  srcoffset = 0;
      -  numoffset = 0;
      -  ndots     = 0;
      -
      -  for(;;)
      -    {
      -      ch = (uint8_t)src[srcoffset++];
      -
      -      if (ch == '.' || ch == '\0')
      -        {
      -          if (ch == '.' && ndots >= 4)
      -            {
      -              /* Too many dots */
      -
      -              break;
      -            }
      -
      -          if (numoffset <= 0)
      -            {
      -              /* Empty numeric string */
      -
      -              break;
      -            }
      -
      -          numstr[numoffset] = '\0';
      -          numoffset = 0;
      -
      -          value = atoi(numstr);
      -          if (value < 0 || value > 255)
      -            {
      -              /* Out of range value */
      -
      -              break;
      -            }
      -
      -          ip[ndots] = (uint8_t)value;
      -
      -          if (ch == '\0')
      -            {
      -              if (ndots != 3)
      -                {
      -                  /* Not enough dots */
      -
      -                  break;
      -                }
      -
      -              /* Return 1 if the conversion succeeds */
      -
      -              return 1;
      -            }
      -
      -          ndots++;
      -        }
      -      else if (ch >= '0' && ch <= '9')
      -        {
      -          numstr[numoffset++] = ch;
      -          if (numoffset >= 4)
      -            {
      -              /* Number is too long */
      -
      -              break;
      -            }
      -        }
      -      else
      -        {
      -          /* Illegal character */
      -
      -          break;
      -        }
      -    }
      -
      -  /* Return zero if there is any problem parsing the input */
      -
      -  return 0;
      -#else
      -  size_t srcoffset;
      -  size_t numoffset;
      -  long value;
      -  int nsep;
      -  int nrsep;
      -  uint8_t ch;
      -  char numstr[5];
      -  uint8_t ip[sizeof(struct in6_addr)];
      -  uint8_t rip[sizeof(struct in6_addr)];
      -  bool rtime;
      -
      -  DEBUGASSERT(src && dst);
      -
      -  if (af != AF_INET6)
      -    {
      -      set_errno(EAFNOSUPPORT);
      -      return -1;
      -    }
      -
      -  (void)memset(dst, 0, sizeof(struct in6_addr));
      -
      -  srcoffset = 0;
      -  numoffset = 0;
      -  nsep      = 0;
      -  nrsep     = 0;
      -  rtime     = false;
      -
      -  for(;;)
      -    {
      -      ch = (uint8_t)src[srcoffset++];
      -
      -      if (ch == ':' || ch == '\0')
      -        {
      -          if (ch == ':' && (nsep + nrsep) >= 8)
      -            {
      -              /* Too many separators */
      -
      -              break;
      -            }
      -
      -          if (ch != '\0' && numoffset <= 0)
      -            {
      -              /* Empty numeric string */
      -
      -              if (rtime && nrsep > 1)
      -                {
      -                  /* dup simple */
      -
      -                  break;
      -                }
      -
      -              numoffset = 0;
      -              rtime = true;
      -              continue;
      -            }
      -
      -          numstr[numoffset] = '\0';
      -          numoffset = 0;
      -
      -          value = strtol(numstr, NULL, 16);
      -          if (value < 0 || value > 0xffff)
      -            {
      -              /* Out of range value */
      -
      -              break;
      -            }
      -
      -          if (!rtime)
      -            {
      -              ip[(nsep << 1) + 0] = (uint8_t)((value >> 8) & 0xff);
      -              ip[(nsep << 1) + 1] = (uint8_t)((value >> 0) & 0xff);
      -              nsep++;
      -            }
      -          else
      -            {
      -              rip[(nrsep << 1) + 0] = (uint8_t)((value >> 8) & 0xff);
      -              rip[(nrsep << 1) + 1] = (uint8_t)((value >> 0) & 0xff);
      -              nrsep++;
      -            }
      -
      -          if (ch == '\0' /* || ch == '/' */)
      -            {
      -              if ((nsep <= 1 && nrsep <= 0) ||
      -                  (nsep + nrsep) < 1 ||
      -                  (nsep + nrsep) > 8)
      -                {
      -                  /* Separator count problem */
      -
      -                  break;
      -                }
      -
      -              if (nsep > 0)
      -                {
      -                  memcpy(dst, &ip[0], nsep << 1);
      -                }
      -
      -              if (nrsep > 0)
      -                {
      -                  memcpy(dst + (16 - (nrsep << 1)), &rip[0], nrsep << 1);
      -                }
      -
      -              /* Return 1 if the conversion succeeds */
      -
      -              return 1;
      -            }
      -        }
      -      else if ((ch >= '0' && ch <= '9') ||
      -               (ch >= 'a' && ch <= 'f') ||
      -               (ch >= 'A' && ch <= 'F'))
      -        {
      -          numstr[numoffset++] = ch;
      -          if (numoffset >= 5)
      -            {
      -              /* Numeric string is too long */
      -
      -              break;
      -            }
      -        }
      -      else
      -        {
      -          /* Illegal character */
      -
      -          break;
      -        }
      -    }
      -
      -
      -  /* Return zero if there is any problem parsing the input */
      -
      -  return 0;
      -#endif
      -}
      diff --git a/nuttx/lib/pthread/Make.defs b/nuttx/lib/pthread/Make.defs
      deleted file mode 100644
      index a1eba7bb0a..0000000000
      --- a/nuttx/lib/pthread/Make.defs
      +++ /dev/null
      @@ -1,56 +0,0 @@
      -############################################################################
      -# lib/pthread/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the pthread C files to the build
      -
      -CSRCS += pthread_attrinit.c pthread_attrdestroy.c \
      -		  pthread_attrsetschedpolicy.c pthread_attrgetschedpolicy.c \
      -		  pthread_attrsetinheritsched.c pthread_attrgetinheritsched.c \
      -		  pthread_attrsetstacksize.c pthread_attrgetstacksize.c \
      -		  pthread_attrsetschedparam.c pthread_attrgetschedparam.c \
      -		  pthread_barrierattrinit.c pthread_barrierattrdestroy.c \
      -		  pthread_barrierattrgetpshared.c pthread_barrierattrsetpshared.c \
      -		  pthread_condattrinit.c pthread_condattrdestroy.c \
      -		  pthread_mutexattrinit.c pthread_mutexattrdestroy.c \
      -		  pthread_mutexattrgetpshared.c pthread_mutexattrsetpshared.c
      -
      -ifeq ($(CONFIG_MUTEX_TYPES),y)
      -CSRCS += pthread_mutexattrsettype.c pthread_mutexattrgettype.c
      -endif
      -
      -# Add the pthread directory to the build
      -
      -DEPPATH += --dep-path pthread
      -VPATH += :pthread
      diff --git a/nuttx/lib/pthread/pthread_attrdestroy.c b/nuttx/lib/pthread/pthread_attrdestroy.c
      deleted file mode 100644
      index 103528c7e1..0000000000
      --- a/nuttx/lib/pthread/pthread_attrdestroy.c
      +++ /dev/null
      @@ -1,108 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_attrdestroy.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_attr_destroy
      - *
      - * Description:
      - *    An attributes object can be deleted when it is no longer
      - *     needed.
      - *
      - * Parameters:
      - *   attr
      - *
      - * Return Value:
      - *   0 meaning success
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_attr_destroy(FAR pthread_attr_t *attr)
      -{
      -  int ret;
      -
      -  sdbg("attr=0x%p\n", attr);
      -
      -  if (!attr)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      memset(attr, 0, sizeof(pthread_attr_t));
      -      ret = OK;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      -
      -
      diff --git a/nuttx/lib/pthread/pthread_attrgetinheritsched.c b/nuttx/lib/pthread/pthread_attrgetinheritsched.c
      deleted file mode 100644
      index 02d6e0b7c0..0000000000
      --- a/nuttx/lib/pthread/pthread_attrgetinheritsched.c
      +++ /dev/null
      @@ -1,111 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_attrgetinheritsched.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_attr_getinheritsched
      - *
      - * Description:
      - *   Report whether the scheduling info in the pthread
      - *   attributes will be used or if the thread will
      - *   inherit the properties of the parent.
      - *
      - * Parameters:
      - *   attr
      - *   inheritsched
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_attr_getinheritsched(FAR const pthread_attr_t *attr,
      -                                 FAR int *inheritsched)
      -{
      -  int ret;
      -
      -  sdbg("attr=0x%p inheritsched=0x%p\n", attr, inheritsched);
      -
      -  if (!attr || !inheritsched)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      *inheritsched = (int)attr->inheritsched;
      -      ret = OK;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      -
      -
      diff --git a/nuttx/lib/pthread/pthread_attrgetschedparam.c b/nuttx/lib/pthread/pthread_attrgetschedparam.c
      deleted file mode 100644
      index c6bf55dea8..0000000000
      --- a/nuttx/lib/pthread/pthread_attrgetschedparam.c
      +++ /dev/null
      @@ -1,110 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_attrgetschedparam.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_attr_getschedparam
      - *
      - * Description:
      - *
      - * Parameters:
      - *   attr
      - *   param
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_attr_getschedparam(FAR pthread_attr_t *attr,
      -                               FAR struct sched_param *param)
      -{
      -  int ret;
      -
      -  sdbg("attr=0x%p param=0x%p\n", attr, param);
      -
      -  if (!attr || !param)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      param->sched_priority = attr->priority;
      -      ret = OK;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      -
      -
      -
      diff --git a/nuttx/lib/pthread/pthread_attrgetschedpolicy.c b/nuttx/lib/pthread/pthread_attrgetschedpolicy.c
      deleted file mode 100644
      index c42b828c96..0000000000
      --- a/nuttx/lib/pthread/pthread_attrgetschedpolicy.c
      +++ /dev/null
      @@ -1,105 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_attrgetschedpolicy.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_attr_getschedpolicy
      - *
      - * Description:
      - *   Obtain the scheduling algorithm attribute.
      - *
      - * Parameters:
      - *   attr
      - *   policy
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_attr_getschedpolicy(FAR pthread_attr_t *attr, int *policy)
      -{
      -  int ret;
      -
      -  sdbg("attr=0x%p policy=0x%p\n", attr, policy);
      -
      -  if (!attr || !policy)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      *policy = attr->policy;
      -      ret = OK;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      diff --git a/nuttx/lib/pthread/pthread_attrgetstacksize.c b/nuttx/lib/pthread/pthread_attrgetstacksize.c
      deleted file mode 100644
      index 2faa586ba8..0000000000
      --- a/nuttx/lib/pthread/pthread_attrgetstacksize.c
      +++ /dev/null
      @@ -1,106 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_attrgetstacksize.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_attr_getstacksize
      - *
      - * Description:
      - *
      - * Parameters:
      - *   attr
      - *   stacksize
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_attr_getstacksize(FAR pthread_attr_t *attr, FAR long *stacksize)
      -{
      -  int ret;
      -
      -  sdbg("attr=0x%p stacksize=0x%p\n", attr, stacksize);
      -
      -  if (!stacksize)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      *stacksize = attr->stacksize;
      -      ret = OK;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      -
      -
      diff --git a/nuttx/lib/pthread/pthread_attrinit.c b/nuttx/lib/pthread/pthread_attrinit.c
      deleted file mode 100644
      index d06a535d78..0000000000
      --- a/nuttx/lib/pthread/pthread_attrinit.c
      +++ /dev/null
      @@ -1,123 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_attrinit.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/* Default pthread attributes (see included/nuttx/pthread.h).  When configured
      - * to build separate kernel- and user-address spaces, this global is
      - * duplicated in each address spaced.  This copy can only be shared within
      - * the user address space. 
      - */
      -
      -#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__)
      -pthread_attr_t g_default_pthread_attr = PTHREAD_ATTR_INITIALIZER;
      -#endif
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_attr_init
      - *
      - * Description:
      - *   Initializes a thread attributes object (attr) with
      - *   default values for all of the individual attributes
      - *   used by a given implementation.
      - *
      - * Parameters:
      - *   attr
      - *
      - * Return Value:
      - *   0 on success, otherwise an error number
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_attr_init(FAR pthread_attr_t *attr)
      -{
      -  int ret = OK;
      -
      -  sdbg("attr=0x%p\n", attr);
      -  if (!attr)
      -    {
      -      ret = ENOMEM;
      -    }
      -  else
      -    {
      -      /* Set the child thread priority to be the default
      -       * priority. Set the child stack size to some arbitrary
      -       * default value.
      -       */
      -
      -      memcpy(attr, &g_default_pthread_attr, sizeof(pthread_attr_t));
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/pthread/pthread_attrsetinheritsched.c b/nuttx/lib/pthread/pthread_attrsetinheritsched.c
      deleted file mode 100644
      index df2c2fba33..0000000000
      --- a/nuttx/lib/pthread/pthread_attrsetinheritsched.c
      +++ /dev/null
      @@ -1,113 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_attrsetinheritsched.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_attr_setinheritsched
      - *
      - * Description:
      - *   Indicate whether the scheduling info in the pthread
      - *   attributes will be used or if the thread will
      - *   inherit the properties of the parent.
      - *
      - * Parameters:
      - *   attr
      - *   policy
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_attr_setinheritsched(FAR pthread_attr_t *attr,
      -                                 int inheritsched)
      -{
      -  int ret;
      -
      -  sdbg("inheritsched=%d\n", inheritsched);
      -
      -  if (!attr ||
      -      (inheritsched != PTHREAD_INHERIT_SCHED &&
      -       inheritsched != PTHREAD_EXPLICIT_SCHED))
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      attr->inheritsched = (uint8_t)inheritsched;
      -      ret = OK;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/pthread/pthread_attrsetschedparam.c b/nuttx/lib/pthread/pthread_attrsetschedparam.c
      deleted file mode 100644
      index c2ab4d1c41..0000000000
      --- a/nuttx/lib/pthread/pthread_attrsetschedparam.c
      +++ /dev/null
      @@ -1,108 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_attrsetschedparam.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_attr_setschedparam
      - *
      - * Description:
      - *
      - * Parameters:
      - *   attr
      - *   param
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_attr_setschedparam(FAR pthread_attr_t *attr,
      -			       FAR const struct sched_param *param)
      -{
      -  int ret;
      -
      -  sdbg("attr=0x%p param=0x%p\n", attr, param);
      -
      -  if (!attr || !param)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      attr->priority = (short)param->sched_priority;
      -      ret = OK;
      -    }
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      -
      -
      diff --git a/nuttx/lib/pthread/pthread_attrsetschedpolicy.c b/nuttx/lib/pthread/pthread_attrsetschedpolicy.c
      deleted file mode 100644
      index 4e43e635de..0000000000
      --- a/nuttx/lib/pthread/pthread_attrsetschedpolicy.c
      +++ /dev/null
      @@ -1,111 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_attrsetschedpolicy.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_attr_setschedpolicy
      - *
      - * Description:
      - *   Set the scheduling algorithm attribute.
      - *
      - * Parameters:
      - *   attr
      - *   policy
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_attr_setschedpolicy(FAR pthread_attr_t *attr, int policy)
      -{
      -  int ret;
      -
      -  sdbg("attr=0x%p policy=%d\n", attr, policy);
      -
      -#if CONFIG_RR_INTERVAL > 0
      -  if (!attr || (policy != SCHED_FIFO && policy != SCHED_RR))
      -#else
      -  if (!attr || policy != SCHED_FIFO )
      -#endif
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      attr->policy = policy;
      -      ret = OK;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      diff --git a/nuttx/lib/pthread/pthread_attrsetstacksize.c b/nuttx/lib/pthread/pthread_attrsetstacksize.c
      deleted file mode 100644
      index 8a826dd3ac..0000000000
      --- a/nuttx/lib/pthread/pthread_attrsetstacksize.c
      +++ /dev/null
      @@ -1,106 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_attrsetstacksize.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_attr_setstacksize
      - *
      - * Description:
      - *
      - * Parameters:
      - *   attr
      - *   stacksize
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_attr_setstacksize(FAR pthread_attr_t *attr, long stacksize)
      -{
      -  int ret;
      -
      -  sdbg("attr=0x%p stacksize=%ld\n", attr, stacksize);
      -
      -  if (!attr || stacksize < PTHREAD_STACK_MIN)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      attr->stacksize = stacksize;
      -      ret = OK;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/pthread/pthread_barrierattrdestroy.c b/nuttx/lib/pthread/pthread_barrierattrdestroy.c
      deleted file mode 100644
      index 6d16b9cff8..0000000000
      --- a/nuttx/lib/pthread/pthread_barrierattrdestroy.c
      +++ /dev/null
      @@ -1,102 +0,0 @@
      -/********************************************************************************
      - * lib/pthread/pthread_barrierattrdestroy.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Included Files
      - ********************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/********************************************************************************
      - * Definitions
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Type Declarations
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Global Variables
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Variables
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Function Prototypes
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Public Functions
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Function: pthread_barrierattr_destroy
      - *
      - * Description:
      - *   The pthread_barrierattr_destroy() function will destroy a barrier attributes
      - *   object.  A destroyed attr attributes object can be reinitialized using
      - *   pthread_barrierattr_init(); the results of otherwise referencing the object
      - *   after it has been destroyed are undefined.
      - *
      - * Parameters:
      - *   attr - barrier attributes to be destroyed.
      - *
      - * Return Value:
      - *   0 (OK) on success or EINVAL if attr is invalid.
      - *
      - * Assumptions:
      - *
      - ********************************************************************************/
      -
      -int pthread_barrierattr_destroy(FAR pthread_barrierattr_t *attr)
      -{
      -  int ret = OK;
      -
      -  if (!attr)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      attr->pshared = PTHREAD_PROCESS_PRIVATE;
      -    }
      -  return ret;
      -}
      diff --git a/nuttx/lib/pthread/pthread_barrierattrgetpshared.c b/nuttx/lib/pthread/pthread_barrierattrgetpshared.c
      deleted file mode 100644
      index d29bc6dfc8..0000000000
      --- a/nuttx/lib/pthread/pthread_barrierattrgetpshared.c
      +++ /dev/null
      @@ -1,101 +0,0 @@
      -/********************************************************************************
      - * lib/pthread/pthread_barrierattrgetpshared.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Included Files
      - ********************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/********************************************************************************
      - * Definitions
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Type Declarations
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Global Variables
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Variables
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Function Prototypes
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Public Functions
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Function: pthread_barrierattr_getpshared
      - *
      - * Description:
      - *   The pthread_barrierattr_getpshared() function will obtain the value of the
      - *   process-shared attribute from the attributes object referenced by attr.
      - *
      - * Parameters:
      - *   attr - barrier attributes to be queried.
      - *   pshared - the location to stored the current value of the pshared attribute.
      - *
      - * Return Value:
      - *   0 (OK) on success or EINVAL if either attr or pshared is invalid.
      - *
      - * Assumptions:
      - *
      - ********************************************************************************/
      -
      -int pthread_barrierattr_getpshared(FAR const pthread_barrierattr_t *attr, FAR int *pshared)
      -{
      -  int ret = OK;
      -
      -  if (!attr || !pshared)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      *pshared = attr->pshared;
      -    }
      -  return ret;
      -}
      diff --git a/nuttx/lib/pthread/pthread_barrierattrinit.c b/nuttx/lib/pthread/pthread_barrierattrinit.c
      deleted file mode 100644
      index b5f35ca917..0000000000
      --- a/nuttx/lib/pthread/pthread_barrierattrinit.c
      +++ /dev/null
      @@ -1,101 +0,0 @@
      -/********************************************************************************
      - * lib/pthread/pthread_barrierattrinit.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Included Files
      - ********************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/********************************************************************************
      - * Definitions
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Type Declarations
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Global Variables
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Variables
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Function Prototypes
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Public Functions
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Function: pthread_barrierattr_init
      - *
      - * Description:
      - *   The pthread_barrierattr_init() function will initialize a barrier attribute
      - *   object attr with the default value for all of the attributes defined by the
      - *   implementation.
      - *
      - * Parameters:
      - *   attr - barrier attributes to be initialized.
      - *
      - * Return Value:
      - *   0 (OK) on success or EINVAL if attr is invalid.
      - *
      - * Assumptions:
      - *
      - ********************************************************************************/
      -
      -int pthread_barrierattr_init(FAR pthread_barrierattr_t *attr)
      -{
      -  int ret = OK;
      -
      -  if (!attr)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      attr->pshared = PTHREAD_PROCESS_PRIVATE;
      -    }
      -  return ret;
      -}
      diff --git a/nuttx/lib/pthread/pthread_barrierattrsetpshared.c b/nuttx/lib/pthread/pthread_barrierattrsetpshared.c
      deleted file mode 100644
      index d0eecbf5a4..0000000000
      --- a/nuttx/lib/pthread/pthread_barrierattrsetpshared.c
      +++ /dev/null
      @@ -1,111 +0,0 @@
      -/********************************************************************************
      - * lib/pthread/pthread_barrierattrsetpshared.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Included Files
      - ********************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/********************************************************************************
      - * Definitions
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Type Declarations
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Global Variables
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Variables
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Private Function Prototypes
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Public Functions
      - ********************************************************************************/
      -
      -/********************************************************************************
      - * Function: pthread_barrierattr_setpshared
      - *
      - * Description:
      - *   The process-shared attribute is set to PTHREAD_PROCESS_SHARED to permit a
      - *   barrier to be operated upon by any thread that has access to the memory where
      - *   the barrier is allocated. If the process-shared attribute is
      - *   PTHREAD_PROCESS_PRIVATE, the barrier can only be operated upon by threads
      - *   created within the same process as the thread that initialized the barrier.
      - *   If threads of different processes attempt to operate on such a barrier, the
      - *   behavior is undefined. The default value of the attribute is
      - *   PTHREAD_PROCESS_PRIVATE.
      - *
      - *   Both constants PTHREAD_PROCESS_SHARED and PTHREAD_PROCESS_PRIVATE are defined
      - *   in pthread.h.
      - *
      - * Parameters:
      - *   attr - barrier attributes to be modified.
      - *   pshared - the new value of the pshared attribute.
      - *
      - * Return Value:
      - *   0 (OK) on success or EINVAL if either attr is invalid or pshared is not one
      - *   of PTHREAD_PROCESS_SHARED or PTHREAD_PROCESS_PRIVATE.
      - *
      - * Assumptions:
      - *
      - ********************************************************************************/
      -
      -int pthread_barrierattr_setpshared(FAR pthread_barrierattr_t *attr, int pshared)
      -{
      -  int ret = OK;
      -
      -  if (!attr || (pshared != PTHREAD_PROCESS_SHARED && pshared != PTHREAD_PROCESS_PRIVATE))
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      attr->pshared = pshared;
      -    }
      -  return ret;
      -}
      diff --git a/nuttx/lib/pthread/pthread_condattrdestroy.c b/nuttx/lib/pthread/pthread_condattrdestroy.c
      deleted file mode 100644
      index d6c3df5d1a..0000000000
      --- a/nuttx/lib/pthread/pthread_condattrdestroy.c
      +++ /dev/null
      @@ -1,82 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_condattrdestroy.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_condattr_destroy
      - *
      - * Description:
      - *   Operations on condition variable attributes
      - *
      - * Parameters:
      - *   None
      - *
      - * Return Value:
      - *   None
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_condattr_destroy(FAR pthread_condattr_t *attr)
      -{
      -  int ret = OK;
      -
      -  sdbg("attr=0x%p\n", attr);
      -
      -  if (!attr)
      -    {
      -      ret = EINVAL;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      -
      -
      -
      diff --git a/nuttx/lib/pthread/pthread_condattrinit.c b/nuttx/lib/pthread/pthread_condattrinit.c
      deleted file mode 100644
      index 5721c61593..0000000000
      --- a/nuttx/lib/pthread/pthread_condattrinit.c
      +++ /dev/null
      @@ -1,85 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_condattrinit.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_condattr_init
      - *
      - * Description:
      - *   Operations on condition variable attributes
      - *
      - * Parameters:
      - *   None
      - *
      - * Return Value:
      - *   None
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_condattr_init(FAR pthread_condattr_t *attr)
      -{
      -  int ret = OK;
      -
      -  sdbg("attr=0x%p\n", attr);
      -
      -  if (!attr)
      -    {
      -      ret = EINVAL;
      -    }
      -  else 
      -    {
      -      *attr = 0;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      -
      -
      diff --git a/nuttx/lib/pthread/pthread_mutexattrdestroy.c b/nuttx/lib/pthread/pthread_mutexattrdestroy.c
      deleted file mode 100644
      index e9868df68b..0000000000
      --- a/nuttx/lib/pthread/pthread_mutexattrdestroy.c
      +++ /dev/null
      @@ -1,104 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_mutexattrdestroy.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_mutexattr_destroy
      - *
      - * Description:
      - *    Destroy mutex attributes.
      - *
      - * Parameters:
      - *    attr
      - *    pshared
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_mutexattr_destroy(FAR pthread_mutexattr_t *attr)
      -{
      -  int ret = OK;
      -
      -  sdbg("attr=0x%p\n", attr);
      -
      -  if (!attr)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      attr->pshared = 0;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      diff --git a/nuttx/lib/pthread/pthread_mutexattrgetpshared.c b/nuttx/lib/pthread/pthread_mutexattrgetpshared.c
      deleted file mode 100644
      index bc6379db5f..0000000000
      --- a/nuttx/lib/pthread/pthread_mutexattrgetpshared.c
      +++ /dev/null
      @@ -1,104 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_mutexattrgetpshared.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_mutexattr_getpshared
      - *
      - * Description:
      - *    Get pshared mutex attribute.
      - *
      - * Parameters:
      - *    attr
      - *    pshared
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_mutexattr_getpshared(FAR pthread_mutexattr_t *attr, FAR int *pshared)
      -{
      -  int ret = OK;
      -
      -  sdbg("attr=0x%p pshared=0x%p\n", attr, pshared);
      -
      -  if (!attr || !pshared)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      *pshared = attr->pshared;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      diff --git a/nuttx/lib/pthread/pthread_mutexattrgettype.c b/nuttx/lib/pthread/pthread_mutexattrgettype.c
      deleted file mode 100644
      index 5fb10f3015..0000000000
      --- a/nuttx/lib/pthread/pthread_mutexattrgettype.c
      +++ /dev/null
      @@ -1,98 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_mutexattrgettype.c
      - *
      - *   Copyright (C) 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -#ifdef CONFIG_MUTEX_TYPES
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function: pthread_mutexattr_gettype
      - *
      - * Description:
      - *   Return the mutex type from the mutex attributes.
      - *
      - * Parameters:
      - *   attr - The mutex attributes to query
      - *   type - Location to return the mutex type
      - *
      - * Return Value:
      - *   0, if the mutex type was successfully return in 'type', or
      - *   EINVAL, if any NULL pointers provided.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_mutexattr_gettype(const pthread_mutexattr_t *attr, int *type)
      -{
      -  if (attr && type)
      -    {
      -      *type = attr->type;
      -      return 0;
      -    }
      -  return EINVAL;
      -}
      -
      -#endif /* CONFIG_MUTEX_TYPES */
      diff --git a/nuttx/lib/pthread/pthread_mutexattrinit.c b/nuttx/lib/pthread/pthread_mutexattrinit.c
      deleted file mode 100644
      index f815bf16c1..0000000000
      --- a/nuttx/lib/pthread/pthread_mutexattrinit.c
      +++ /dev/null
      @@ -1,106 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_mutexattrinit.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_mutexattr_init
      - *
      - * Description:
      - *    Create mutex attributes.
      - *
      - * Parameters:
      - *    attr
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_mutexattr_init(FAR pthread_mutexattr_t *attr)
      -{
      -  int ret = OK;
      -
      -  sdbg("attr=0x%p\n", attr);
      -
      -  if (!attr)
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      attr->pshared = 0;
      -#ifdef CONFIG_MUTEX_TYPES
      -      attr->type    = PTHREAD_MUTEX_DEFAULT;
      -#endif
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      diff --git a/nuttx/lib/pthread/pthread_mutexattrsetpshared.c b/nuttx/lib/pthread/pthread_mutexattrsetpshared.c
      deleted file mode 100644
      index 900476fdd2..0000000000
      --- a/nuttx/lib/pthread/pthread_mutexattrsetpshared.c
      +++ /dev/null
      @@ -1,104 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_mutexattrsetpshared.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  pthread_mutexattr_setpshared
      - *
      - * Description:
      - *    Set pshared  mutex attribute.
      - *
      - * Parameters:
      - *    attr
      - *    pshared
      - *
      - * Return Value:
      - *   0 if successful.  Otherwise, an error code.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_mutexattr_setpshared(FAR pthread_mutexattr_t *attr, int pshared)
      -{
      -  int ret = OK;
      -
      -  sdbg("attr=0x%p pshared=%d\n", attr, pshared);
      -
      -  if (!attr || (pshared != 0 && pshared != 1))
      -    {
      -      ret = EINVAL;
      -    }
      -  else
      -    {
      -      attr->pshared = pshared;
      -    }
      -
      -  sdbg("Returning %d\n", ret);
      -  return ret;
      -}
      diff --git a/nuttx/lib/pthread/pthread_mutexattrsettype.c b/nuttx/lib/pthread/pthread_mutexattrsettype.c
      deleted file mode 100644
      index 81427c757e..0000000000
      --- a/nuttx/lib/pthread/pthread_mutexattrsettype.c
      +++ /dev/null
      @@ -1,98 +0,0 @@
      -/****************************************************************************
      - * lib/pthread/pthread_mutexattrsettype.c
      - *
      - *   Copyright (C) 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -#ifdef CONFIG_MUTEX_TYPES
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function: pthread_mutexattr_settype
      - *
      - * Description:
      - *   Set the mutex type in the mutex attributes.
      - *
      - * Parameters:
      - *   attr - The mutex attributes in which to set the mutex type.
      - *   type - The mutex type value to set.
      - *
      - * Return Value:
      - *   0, if the mutex type was successfully set in 'attr', or
      - *   EINVAL, if 'attr' is NULL or 'type' unrecognized.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int pthread_mutexattr_settype(pthread_mutexattr_t *attr, int type)
      -{
      -  if (attr && type >= PTHREAD_MUTEX_NORMAL && type <= PTHREAD_MUTEX_RECURSIVE)
      -    {
      -      attr->type = type;
      -      return OK;
      -    }
      -  return EINVAL;
      -}
      -
      -#endif /* CONFIG_MUTEX_TYPES */
      diff --git a/nuttx/lib/queue/Make.defs b/nuttx/lib/queue/Make.defs
      deleted file mode 100644
      index 976e7a2b87..0000000000
      --- a/nuttx/lib/queue/Make.defs
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -############################################################################
      -# lib/queue/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the queue C files to the build
      -
      -CSRCS += sq_addlast.c sq_addfirst.c sq_addafter.c \
      -		  sq_rem.c sq_remlast.c sq_remfirst.c sq_remafter.c
      -
      -CSRCS += dq_addlast.c dq_addfirst.c dq_addafter.c dq_addbefore.c \
      -		  dq_rem.c dq_remlast.c dq_remfirst.c
      -
      -# Add the queue directory to the build
      -
      -DEPPATH += --dep-path queue
      -VPATH += :queue
      diff --git a/nuttx/lib/queue/dq_addafter.c b/nuttx/lib/queue/dq_addafter.c
      deleted file mode 100644
      index bfbe0052d8..0000000000
      --- a/nuttx/lib/queue/dq_addafter.c
      +++ /dev/null
      @@ -1,74 +0,0 @@
      -/************************************************************
      - * lib/queue/dq_addafter.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: dq_addafter
      - *
      - * Description:
      - *  dq_addafter function adds 'node' after 'qqqq' in the
      - *  'queue.'
      - *
      - ************************************************************/
      -
      -void dq_addafter(FAR dq_entry_t *prev, FAR dq_entry_t *node,
      -                 dq_queue_t *queue)
      -{
      -  if (!queue->head || prev == queue->tail)
      -    {
      -      dq_addlast(node, queue);
      -    }
      -  else
      -    {
      -      FAR dq_entry_t *next = prev->flink;
      -      node->blink = prev;
      -      node->flink = next;
      -      next->blink = node;
      -      prev->flink = node;
      -    }
      -}
      diff --git a/nuttx/lib/queue/dq_addbefore.c b/nuttx/lib/queue/dq_addbefore.c
      deleted file mode 100644
      index d740ea8309..0000000000
      --- a/nuttx/lib/queue/dq_addbefore.c
      +++ /dev/null
      @@ -1,69 +0,0 @@
      -/****************************************************************************
      - * lib/queue/dq_addbefore.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: dq_addbefore
      - *
      - * Description:
      - *   dq_addbefore adds 'node' before 'next' in 'queue'
      - *
      - ****************************************************************************/
      -
      -void dq_addbefore(FAR dq_entry_t *next, FAR dq_entry_t *node,
      -                  dq_queue_t *queue)
      -{
      -  if (!queue->head || next == queue->head)
      -    {
      -      dq_addfirst(node, queue);
      -    }
      -  else
      -    {
      -      FAR dq_entry_t *prev = next->blink;
      -      node->flink = next;
      -      node->blink = prev;
      -      prev->flink = node;
      -      next->blink = node;
      -    }
      -}
      diff --git a/nuttx/lib/queue/dq_addfirst.c b/nuttx/lib/queue/dq_addfirst.c
      deleted file mode 100644
      index 7c7312de3b..0000000000
      --- a/nuttx/lib/queue/dq_addfirst.c
      +++ /dev/null
      @@ -1,74 +0,0 @@
      -/************************************************************
      - * lib/queue/dq_addfirst.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: dq_addfirst
      - *
      - * Description:
      - *  dq_addfirst affs 'node' at the beginning of 'queue'
      - *
      - ************************************************************/
      -
      -void dq_addfirst(FAR dq_entry_t *node, dq_queue_t *queue)
      -{
      -  node->blink = NULL;
      -  node->flink = queue->head;
      -
      -  if (!queue->head)
      -    {
      -      queue->head = node;
      -      queue->tail = node;
      -    }
      -  else
      -    {
      -      queue->head->blink = node;
      -      queue->head = node;
      -    }
      -}
      -
      diff --git a/nuttx/lib/queue/dq_addlast.c b/nuttx/lib/queue/dq_addlast.c
      deleted file mode 100644
      index 745deb27d1..0000000000
      --- a/nuttx/lib/queue/dq_addlast.c
      +++ /dev/null
      @@ -1,74 +0,0 @@
      -/************************************************************
      - * lib/queue/dq_addlast.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: dq_addlast
      - *
      - * Description
      - *   dq_addlast adds 'node' to the end of 'queue'
      - *
      - ************************************************************/
      -
      -void dq_addlast(FAR dq_entry_t *node, dq_queue_t *queue)
      -{
      -  node->flink = NULL;
      -  node->blink = queue->tail;
      -
      -  if (!queue->head)
      -    {
      -      queue->head = node;
      -      queue->tail = node;
      -    }
      -  else
      -    {
      -      queue->tail->flink = node;
      -      queue->tail        = node;
      -    }
      -}
      -
      diff --git a/nuttx/lib/queue/dq_rem.c b/nuttx/lib/queue/dq_rem.c
      deleted file mode 100644
      index 218427bf84..0000000000
      --- a/nuttx/lib/queue/dq_rem.c
      +++ /dev/null
      @@ -1,84 +0,0 @@
      -/************************************************************
      - * lib/queue/dq_rem.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: dq_rem
      - *
      - * Descripton:
      - *   dq_rem removes 'node' from 'queue'
      - *
      - ************************************************************/
      -
      -void dq_rem(FAR dq_entry_t *node, dq_queue_t *queue)
      -{
      -  FAR dq_entry_t *prev = node->blink;
      -  FAR dq_entry_t *next = node->flink;
      -
      -  if (!prev)
      -    {
      -      queue->head = next;
      -    }
      -  else 
      -    {
      -      prev->flink = next;
      -    }
      -
      -  if (!next)
      -    {
      -      queue->tail = prev;
      -    }
      -  else 
      -    {
      -      next->blink = prev;
      -    }
      -
      -  node->flink = NULL;
      -  node->blink = NULL;
      -}
      -
      diff --git a/nuttx/lib/queue/dq_remfirst.c b/nuttx/lib/queue/dq_remfirst.c
      deleted file mode 100644
      index 26c5fd7a67..0000000000
      --- a/nuttx/lib/queue/dq_remfirst.c
      +++ /dev/null
      @@ -1,82 +0,0 @@
      -/************************************************************
      - * lib/queue/dq_remfirst.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: dq_remfirst
      - *
      - * Description:
      - *   dq_remfirst removes 'node' from the head of 'queue'
      - *
      - ************************************************************/
      -
      -FAR dq_entry_t *dq_remfirst(dq_queue_t *queue)
      -{
      -  FAR dq_entry_t *ret = queue->head;
      -
      -  if (ret)
      -    {
      -      FAR dq_entry_t *next = ret->flink;
      -      if (!next)
      -        {
      -          queue->head = NULL;
      -          queue->tail = NULL;
      -        }
      -      else
      -        {
      -          queue->head = next;
      -          next->blink = NULL;
      -        }
      -
      -      ret->flink = NULL;
      -      ret->blink = NULL;
      -    }
      -
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/queue/dq_remlast.c b/nuttx/lib/queue/dq_remlast.c
      deleted file mode 100644
      index 35adc73e2d..0000000000
      --- a/nuttx/lib/queue/dq_remlast.c
      +++ /dev/null
      @@ -1,78 +0,0 @@
      -/****************************************************************************
      - * lib/queue/dq_remlast.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/***************************************************(************************
      - * Name: dq_remlast
      - *
      - * Description:
      - *   dq_remlast removes the last entry from 'queue'
      - *
      - ****************************************************************************/
      -
      -FAR dq_entry_t *dq_remlast(dq_queue_t *queue)
      -{
      -  FAR dq_entry_t *ret = queue->tail;
      -
      -  if (ret)
      -    {
      -      FAR dq_entry_t *prev = ret->blink;
      -      if (!prev)
      -        {
      -          queue->head = NULL;
      -          queue->tail = NULL;
      -        }
      -      else
      -        {
      -          queue->tail = prev;
      -          prev->flink = NULL;
      -        }
      -
      -      ret->flink = NULL;
      -      ret->blink = NULL;
      -    }
      -
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/queue/sq_addafter.c b/nuttx/lib/queue/sq_addafter.c
      deleted file mode 100644
      index 965ac28444..0000000000
      --- a/nuttx/lib/queue/sq_addafter.c
      +++ /dev/null
      @@ -1,71 +0,0 @@
      -/************************************************************
      - * lib/queue/sq_addafter.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: sq_addafter.c
      - *
      - * Description:
      - *  The sq_addafter function adds 'node' after 'prev' in the
      - *  'queue.'
      - *
      - ************************************************************/
      -
      -void sq_addafter(FAR sq_entry_t *prev, FAR sq_entry_t *node,
      -                 sq_queue_t *queue)
      -{
      -  if (!queue->head || prev == queue->tail)
      -    {
      -      sq_addlast(node, queue);
      -    }
      -  else
      -    {
      -      node->flink = prev->flink;
      -      prev->flink = node;
      -    }
      -}
      diff --git a/nuttx/lib/queue/sq_addfirst.c b/nuttx/lib/queue/sq_addfirst.c
      deleted file mode 100644
      index 8fc8e06199..0000000000
      --- a/nuttx/lib/queue/sq_addfirst.c
      +++ /dev/null
      @@ -1,67 +0,0 @@
      -/************************************************************
      - * lib/queue/sq_addfirst.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: sq_addfirst
      - *
      - * Description:
      - *   The sq_addfirst function places the 'node' at the head
      - *   of the 'queue'
      - *
      - ************************************************************/
      -
      -void sq_addfirst(FAR sq_entry_t *node, sq_queue_t *queue)
      -{
      -  node->flink = queue->head;
      -  if (!queue->head)
      -    {
      -      queue->tail = node;
      -    }
      -  queue->head = node;
      -}
      diff --git a/nuttx/lib/queue/sq_addlast.c b/nuttx/lib/queue/sq_addlast.c
      deleted file mode 100644
      index f9f9625cc0..0000000000
      --- a/nuttx/lib/queue/sq_addlast.c
      +++ /dev/null
      @@ -1,72 +0,0 @@
      -/************************************************************
      - * lib/queue/sq_addlast.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: sq_addlast
      - *
      - * Description:
      - *   The sq_addlast function places the 'node' at the tail of
      - *   the 'queue'
      - ************************************************************/
      -
      -void sq_addlast(FAR sq_entry_t *node, sq_queue_t *queue)
      -{
      -  node->flink = NULL;
      -  if (!queue->head)
      -    {
      -      queue->head = node;
      -      queue->tail = node;
      -    }
      -  else
      -    {
      -      queue->tail->flink = node;
      -      queue->tail        = node;
      -    }
      -}
      -
      diff --git a/nuttx/lib/queue/sq_rem.c b/nuttx/lib/queue/sq_rem.c
      deleted file mode 100644
      index 6ba52354d4..0000000000
      --- a/nuttx/lib/queue/sq_rem.c
      +++ /dev/null
      @@ -1,83 +0,0 @@
      -/************************************************************
      - * lib/queue/sq_rem.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: sq_rem
      - *
      - * Description:
      - *   sq_rem removes a 'node' for 'queue.'
      - *
      - ************************************************************/
      -
      -void sq_rem(FAR sq_entry_t *node, sq_queue_t *queue)
      -{
      -  if (queue->head && node)
      -    {
      -      if (node == queue->head)
      -        {
      -          queue->head = node->flink;
      -          if (node == queue->tail)
      -            {
      -              queue->tail = NULL;
      -            }
      -        }
      -      else
      -        {
      -          FAR sq_entry_t *prev;
      -          for(prev = (FAR sq_entry_t*)queue->head;
      -              prev && prev->flink != node;
      -              prev = prev->flink);
      -
      -          if (prev)
      -            {
      -              sq_remafter(prev, queue);
      -            }
      -        }
      -    }
      -}
      diff --git a/nuttx/lib/queue/sq_remafter.c b/nuttx/lib/queue/sq_remafter.c
      deleted file mode 100644
      index 4dcfb06e44..0000000000
      --- a/nuttx/lib/queue/sq_remafter.c
      +++ /dev/null
      @@ -1,79 +0,0 @@
      -/************************************************************
      - * lib/queue/sq_remafter.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name:
      - *
      - * Description:
      - *   sq_remafter removes the entry following 'node; from the
      - *   'queue'  Returns a reference to the removed entry.
      - *
      - ************************************************************/
      -
      -FAR sq_entry_t *sq_remafter(FAR sq_entry_t *node, sq_queue_t *queue)
      -{
      -  FAR sq_entry_t *ret = node->flink;
      -  if (queue->head && ret)
      -    {
      -      if (queue->tail == ret)
      -        {
      -          queue->tail = node;
      -          node->flink = NULL;
      -        }
      -      else
      -        {
      -          node->flink = ret->flink;
      -        }
      -
      -      ret->flink = NULL;
      -    }
      -
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/queue/sq_remfirst.c b/nuttx/lib/queue/sq_remfirst.c
      deleted file mode 100644
      index 43df6de417..0000000000
      --- a/nuttx/lib/queue/sq_remfirst.c
      +++ /dev/null
      @@ -1,76 +0,0 @@
      -/************************************************************
      - * lib/queue/sq_remfirst.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: sq_remfirst
      - *
      - * Description:
      - *   sq_remfirst function removes the first entry from
      - *   'queue'
      - *
      - ************************************************************/
      -
      -FAR sq_entry_t *sq_remfirst(sq_queue_t *queue)
      -{
      -  FAR sq_entry_t *ret = queue->head;
      -
      -  if (ret)
      -    {
      -      queue->head = ret->flink;
      -      if (!queue->head)
      -        {
      -          queue->tail = NULL;
      -        }
      -
      -      ret->flink = NULL;
      -    }
      -
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/queue/sq_remlast.c b/nuttx/lib/queue/sq_remlast.c
      deleted file mode 100644
      index 92cdbde985..0000000000
      --- a/nuttx/lib/queue/sq_remlast.c
      +++ /dev/null
      @@ -1,87 +0,0 @@
      -/************************************************************
      - * lib/queue/sq_remlast.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -
      -/************************************************************
      - * Name: sq_remlast
      - *
      - * Description:
      - *   Removes the last entry in a singly-linked queue.
      - *
      - ************************************************************/
      -
      -FAR sq_entry_t *sq_remlast(sq_queue_t *queue)
      -{ 
      -  FAR sq_entry_t *ret = queue->tail;
      -
      -  if (ret)
      -    {
      -      if (queue->head == queue->tail)
      -        {
      -          queue->head = NULL;
      -          queue->tail = NULL;
      -        }
      -      else
      -        {
      -          FAR sq_entry_t *prev;
      -          for(prev = queue->head;
      -              prev && prev->flink != ret;
      -              prev = prev->flink);
      -
      -          if (prev)
      -            {
      -              prev->flink = NULL;
      -              queue->tail = prev;
      -            }
      -        }
      -
      -      ret->flink = NULL;
      -    }
      -
      -  return ret;
      -} 
      diff --git a/nuttx/lib/sched/Make.defs b/nuttx/lib/sched/Make.defs
      deleted file mode 100644
      index f398b755e0..0000000000
      --- a/nuttx/lib/sched/Make.defs
      +++ /dev/null
      @@ -1,43 +0,0 @@
      -############################################################################
      -# lib/sched/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the sched C files to the build
      -
      -CSRCS += sched_getprioritymax.c sched_getprioritymin.c
      -
      -# Add the sched directory to the build
      -
      -DEPPATH += --dep-path sched
      -VPATH += :sched
      diff --git a/nuttx/lib/sched/sched_getprioritymax.c b/nuttx/lib/sched/sched_getprioritymax.c
      deleted file mode 100644
      index 14b368dfc0..0000000000
      --- a/nuttx/lib/sched/sched_getprioritymax.c
      +++ /dev/null
      @@ -1,100 +0,0 @@
      -/************************************************************************
      - * lib/sched/sched_getprioritymax.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Definitions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Type Declarations
      - ************************************************************************/
      -
      -/************************************************************************
      - * Global Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Function Prototypes
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Name:  ched_get_priority_max
      - *
      - * Description:
      - *   This function returns the value of the highest possible
      - *   task priority for a specified scheduling policy.
      - *
      - * Inputs:
      - *   policy - Scheduling policy requested.
      - *
      - * Return Value:
      - *   The maximum priority value or -1 (ERROR)
      - *   (errno is not set)
      - *
      - * Assumptions:
      - *
      - ************************************************************************/
      -
      -int sched_get_priority_max(int policy)
      -{
      -  if (policy != SCHED_FIFO && policy != SCHED_RR)
      -    {
      -      return ERROR;
      -    }
      -  else
      -    {
      -      return SCHED_PRIORITY_MAX;
      -    }
      -}
      diff --git a/nuttx/lib/sched/sched_getprioritymin.c b/nuttx/lib/sched/sched_getprioritymin.c
      deleted file mode 100644
      index 86410cb0f6..0000000000
      --- a/nuttx/lib/sched/sched_getprioritymin.c
      +++ /dev/null
      @@ -1,100 +0,0 @@
      -/************************************************************************
      - * lib/sched/sched_getprioritymin.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Definitions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Type Declarations
      - ************************************************************************/
      -
      -/************************************************************************
      - * Global Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Function Prototypes
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Name: sched_get_priority_min
      - *
      - * Description:
      - *   This function returns the value of the lowest possible
      - *   task priority for a specified scheduling policy.
      - *
      - * Inputs:
      - *   policy - Scheduling policy requested.
      - *
      - * Return Value:
      - *   The minimum priority value or -1 (ERROR)
      - *   (errno is not set)
      - *
      - * Assumptions:
      - *
      - ************************************************************************/
      -
      -int sched_get_priority_min(int policy)
      -{ 
      -  if (policy != SCHED_FIFO && policy != SCHED_RR)
      -    {
      -      return ERROR;
      -    }
      -  else
      -    {
      -      return SCHED_PRIORITY_MIN;
      -    }
      -}
      diff --git a/nuttx/lib/semaphore/Make.defs b/nuttx/lib/semaphore/Make.defs
      deleted file mode 100644
      index fdc0fe7d54..0000000000
      --- a/nuttx/lib/semaphore/Make.defs
      +++ /dev/null
      @@ -1,43 +0,0 @@
      -############################################################################
      -# lib/semaphore/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the semaphore C files to the build
      -
      -CSRCS += sem_init.c sem_getvalue.c
      -
      -# Add the semaphore directory to the build
      -
      -DEPPATH += --dep-path semaphore
      -VPATH += :semaphore
      diff --git a/nuttx/lib/semaphore/sem_getvalue.c b/nuttx/lib/semaphore/sem_getvalue.c
      deleted file mode 100644
      index 31c6bb7e06..0000000000
      --- a/nuttx/lib/semaphore/sem_getvalue.c
      +++ /dev/null
      @@ -1,108 +0,0 @@
      -/****************************************************************************
      - * lib/semaphore/sem_getvalue.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  sem_getvalue
      - *
      - * Description:
      - *   This function updates the location referenced by 'sval' argument to
      - *   have the value of the semaphore referenced by 'sem' without effecting
      - *   the state of the semaphore.  The updated value represents the actual
      - *   semaphore value that occurred at some unspecified time during the call,
      - *   but may not reflect the actual value of the semaphore when it is
      - *   returned to the calling task.
      - *
      - *   If 'sem' is locked, the value return by sem_getvalue() will either be
      - *   zero or a negative number whose absolute value represents the number
      - *   of tasks waiting for the semaphore.
      - *
      - * Parameters:
      - *   sem - Semaphore descriptor
      - *   sval - Buffer by which the value is returned
      - *
      - * Return Value:
      - *   0 (OK), or -1 (ERROR) if unsuccessful
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int sem_getvalue(FAR sem_t *sem, FAR int *sval)
      -{
      -  if (sem && sval)
      -    {
      -      *sval = sem->semcount;
      -      return OK;
      -    }
      -  else
      -    {
      -      set_errno(EINVAL);
      -	  return ERROR;
      -    }
      -}
      diff --git a/nuttx/lib/semaphore/sem_init.c b/nuttx/lib/semaphore/sem_init.c
      deleted file mode 100644
      index bc14415f97..0000000000
      --- a/nuttx/lib/semaphore/sem_init.c
      +++ /dev/null
      @@ -1,125 +0,0 @@
      -/****************************************************************************
      - * lib/sem/sem_init.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function: sem_init
      - *
      - * Description:
      - *   This function initializes the UNAMED semaphore sem. Following a
      - *   successful call to sem_init(), the semaophore may be used in subsequent
      - *   calls to sem_wait(), sem_post(), and sem_trywait().  The semaphore
      - *   remains usable until it is destroyed.
      - *
      - *   Only sem itself may be used for performing synchronization. The result
      - *   of referring to copies of sem in calls to sem_wait(), sem_trywait(),
      - *   sem_post(), and sem_destroy() is undefined.
      - *
      - * Parameters:
      - *   sem - Semaphore to be initialized
      - *   pshared - Process sharing (not used)
      - *   value - Semaphore initialization value
      - *
      - * Return Value:
      - *   0 (OK), or -1 (ERROR) if unsuccessful.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int sem_init(FAR sem_t *sem, int pshared, unsigned int value)
      -{
      -  /* Verify that a semaphore was provided and the count is within the valid
      -   * range.
      -   */
      -
      -  if (sem && value <= SEM_VALUE_MAX)
      -    {
      -      /* Initialize the seamphore count */
      -
      -      sem->semcount      = (int16_t)value;
      -
      -      /* Initialize to support priority inheritance */
      -
      -#ifdef CONFIG_PRIORITY_INHERITANCE
      -#  if CONFIG_SEM_PREALLOCHOLDERS > 0
      -      sem->hhead         = NULL;
      -#  else
      -      sem->holder.htcb   = NULL;
      -      sem->holder.counts = 0;
      -#  endif
      -#endif
      -      return OK;
      -    }
      -  else
      -    {
      -      set_errno(EINVAL);
      -      return ERROR;
      -    }
      -}
      diff --git a/nuttx/lib/signal/Make.defs b/nuttx/lib/signal/Make.defs
      deleted file mode 100644
      index e27da9b2e8..0000000000
      --- a/nuttx/lib/signal/Make.defs
      +++ /dev/null
      @@ -1,47 +0,0 @@
      -############################################################################
      -# lib/signal/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -ifneq ($(CONFIG_DISABLE_SIGNALS),y)
      -
      -# Add the signal C files to the build
      -
      -CSRCS += sig_emptyset.c sig_fillset.c sig_addset.c sig_delset.c sig_ismember.c
      -
      -# Add the signal directory to the build
      -
      -DEPPATH += --dep-path signal
      -VPATH += :signal
      -
      -endif
      diff --git a/nuttx/lib/signal/sig_addset.c b/nuttx/lib/signal/sig_addset.c
      deleted file mode 100644
      index 19ba0cb6b6..0000000000
      --- a/nuttx/lib/signal/sig_addset.c
      +++ /dev/null
      @@ -1,100 +0,0 @@
      -/****************************************************************************
      - * lib/signal/sig_addset.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function: sigaddset
      - *
      - * Description:
      - *   This function adds the signal specified by signo to the signal set
      - *   specified by set.
      - *
      - * Parameters:
      - *   set - Signal set to add signal to
      - *   signo - Signal to add
      - *
      - * Return Value:
      - *   0 (OK), or -1 (ERROR) if the signal number is invalid.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int sigaddset(FAR sigset_t *set, int signo)
      -{
      -  int ret = ERROR;
      -
      -  /* Verify the signal */
      -
      -  if (GOOD_SIGNO(signo))
      -    {
      -      /* Add the signal to the set */
      -
      -      *set |= SIGNO2SET(signo);
      -      ret = OK;
      -    }
      -
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/signal/sig_delset.c b/nuttx/lib/signal/sig_delset.c
      deleted file mode 100644
      index 1c661d37f6..0000000000
      --- a/nuttx/lib/signal/sig_delset.c
      +++ /dev/null
      @@ -1,100 +0,0 @@
      -/****************************************************************************
      - * lib/signal/sig_delset.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function: sigdelset
      - *
      - * Description:
      - *   This function deletes the signal specified by signo from the signal
      - *   set specified by the 'set' argument.
      - *
      - * Parameters:
      - *   set - Signal set to delete the signal from
      - *   signo - Signal to delete
      - *
      - * Return Value:
      - *   0 (OK), or -1 (ERROR) if the signal number is invalid.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int sigdelset(FAR sigset_t *set, int signo)
      -{
      -  int ret = ERROR;
      -
      -  /* Verify the signal */
      -
      -  if (GOOD_SIGNO(signo))
      -    {
      -      /* Delete the signal to the set */
      -
      -      *set &= ~SIGNO2SET(signo);
      -      ret = OK;
      -    }
      -
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/signal/sig_emptyset.c b/nuttx/lib/signal/sig_emptyset.c
      deleted file mode 100644
      index ac0c6b3e89..0000000000
      --- a/nuttx/lib/signal/sig_emptyset.c
      +++ /dev/null
      @@ -1,88 +0,0 @@
      -/****************************************************************************
      - * lib/signal/sig_emptyset.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function: sigemptyset
      - *
      - * Description:
      - *   This function initializes the signal set specified by set such that all
      - *   signals are excluded.
      - *
      - * Parameters:
      - *   set - Signal set to initalize
      - *
      - * Return Value:
      - *   0 (OK), or -1 (ERROR) if the signal set cannot be initialized.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int sigemptyset(FAR sigset_t *set)
      -{
      -  *set = NULL_SIGNAL_SET;
      -  return OK;
      -}
      -
      diff --git a/nuttx/lib/signal/sig_fillset.c b/nuttx/lib/signal/sig_fillset.c
      deleted file mode 100644
      index 8697d7577f..0000000000
      --- a/nuttx/lib/signal/sig_fillset.c
      +++ /dev/null
      @@ -1,88 +0,0 @@
      -/****************************************************************************
      - * lib/signal/sig_fillset.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Publics Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function: sigfillset
      - *
      - * Description:
      - *   This function initializes the signal set specified by set such that all
      - *   signals are included.
      - *
      - * Parameters:
      - *   set - Signal set to initalize
      - *
      - * Return Value:
      - *   0 (OK), or -1 (ERROR) if the signal set cannot be initialized.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int sigfillset(FAR sigset_t *set)
      -{
      -  *set = ALL_SIGNAL_SET;
      -  return OK;
      -}
      -
      diff --git a/nuttx/lib/signal/sig_ismember.c b/nuttx/lib/signal/sig_ismember.c
      deleted file mode 100644
      index c5bb091b7b..0000000000
      --- a/nuttx/lib/signal/sig_ismember.c
      +++ /dev/null
      @@ -1,101 +0,0 @@
      -/****************************************************************************
      - * lib/signal/sig_ismember.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function: sigismember
      - *
      - * Description:
      - *   This function tests whether the signal specified by signo is a member
      - *   of the set specified by set.
      - *
      - * Parameters:
      - *   set - Signal set to test
      - *   signo - Signal to test for
      - *
      - * Return Value:
      - *   1 (true), if the specified signal is a member of the set,
      - *   0 (OK or FALSE), if it is not, or
      - *  -1 (ERROR) if the signal number is invalid.
      - *
      - * Assumptions:
      - *
      - ****************************************************************************/
      -
      -int sigismember(FAR const sigset_t *set, int signo)
      -{
      -  int ret = ERROR;
      -
      -  /* Verify the signal */
      -
      -  if (GOOD_SIGNO(signo))
      -    {
      -      /* Check if the signal is in the set */
      -
      -      ret = ((*set & SIGNO2SET(signo)) != 0);
      -    }
      -
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/stdio/Make.defs b/nuttx/lib/stdio/Make.defs
      deleted file mode 100644
      index e4ee5e9699..0000000000
      --- a/nuttx/lib/stdio/Make.defs
      +++ /dev/null
      @@ -1,85 +0,0 @@
      -############################################################################
      -# lib/stdio/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the stdio C files to the build
      -# This first group of C files do not depend on having file descriptors or
      -# C streams.
      -
      -CSRCS += lib_fileno.c lib_printf.c lib_rawprintf.c lib_lowprintf.c \
      -		 lib_sprintf.c lib_asprintf.c lib_snprintf.c lib_libsprintf.c \
      -		 lib_vsprintf.c lib_avsprintf.c lib_vsnprintf.c lib_libvsprintf.c \
      -		 lib_meminstream.c lib_memoutstream.c lib_lowinstream.c \
      -		 lib_lowoutstream.c lib_zeroinstream.c lib_nullinstream.c \
      -		 lib_nulloutstream.c lib_sscanf.c
      -
      -# The remaining sources files depend upon file descriptors
      -
      -ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
      -
      -CSRCS += lib_rawinstream.c lib_rawoutstream.c
      -
      -# And these depend upon both file descriptors and C streams
      -
      -ifneq ($(CONFIG_NFILE_STREAMS),0)
      -
      -CSRCS += lib_fopen.c lib_fclose.c lib_fread.c lib_libfread.c lib_fseek.c \
      -		 lib_ftell.c lib_fsetpos.c lib_fgetpos.c lib_fgetc.c lib_fgets.c \
      -		 lib_gets.c lib_fwrite.c lib_libfwrite.c lib_fflush.c \
      -		 lib_libflushall.c lib_libfflush.c lib_rdflush.c lib_wrflush.c \
      -		 lib_fputc.c lib_puts.c lib_fputs.c lib_ungetc.c lib_vprintf.c \
      -		 lib_fprintf.c lib_vfprintf.c lib_stdinstream.c lib_stdoutstream.c \
      -		 lib_perror.c lib_feof.c lib_ferror.c lib_clearerr.c
      -
      -endif
      -endif
      -
      -# Other support that depends on specific, configured features.
      -
      -ifeq ($(CONFIG_SYSLOG),y)
      -CSRCS += lib_syslogstream.c
      -endif
      -
      -ifeq ($(CONFIG_LIBC_FLOATINGPOINT),y)
      -CSRCS += lib_dtoa.c
      -endif
      -
      -ifeq ($(CONFIG_STDIO_LINEBUFFER),y)
      -CSRCS += lib_libnoflush.c
      -endif
      -
      -# Add the stdio directory to the build
      -
      -DEPPATH += --dep-path stdio
      -VPATH += :stdio
      diff --git a/nuttx/lib/stdio/lib_asprintf.c b/nuttx/lib/stdio/lib_asprintf.c
      deleted file mode 100644
      index 84aaafa462..0000000000
      --- a/nuttx/lib/stdio/lib_asprintf.c
      +++ /dev/null
      @@ -1,105 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_asprintf.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: asprintf
      - *
      - * Description:
      - *   This function is similar to sprintf, except that it dynamically
      - *   allocates a string (as with malloc) to hold the output, instead of
      - *   putting the output in a buffer you allocate in advance.  The ptr
      - *   argument should be the address of a char * object, and a successful
      - *   call to asprintf stores a pointer to the newly allocated string at that
      - *   location.
      - *
      - * Returned Value:
      - *   The returned value is the number of characters allocated for the buffer,
      - *   or less than zero if an error occurred. Usually this means that the buffer
      - *   could not be allocated.
      - *
      - ****************************************************************************/
      -
      -int asprintf (FAR char **ptr, const char *fmt, ...)
      -{
      -  va_list ap;
      -  int ret;
      -
      -  /* Let avsprintf do all of the work */
      -
      -  va_start(ap, fmt);
      -  ret = avsprintf(ptr, fmt, ap);
      -  va_end(ap);
      -
      -  return ret;
      -}
      diff --git a/nuttx/lib/stdio/lib_avsprintf.c b/nuttx/lib/stdio/lib_avsprintf.c
      deleted file mode 100644
      index 8561b97c21..0000000000
      --- a/nuttx/lib/stdio/lib_avsprintf.c
      +++ /dev/null
      @@ -1,146 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_avsprintf.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: avsprintf
      - *
      - * Description:
      - *   This function is similar to vsprintf, except that it dynamically
      - *   allocates a string (as with malloc) to hold the output, instead of
      - *   putting the output in a buffer you allocate in advance.  The ptr
      - *   argument should be the address of a char * object, and a successful
      - *   call to avsprintf stores a pointer to the newly allocated string at that
      - *   location.
      - *
      - * Returned Value:
      - *   The returned value is the number of characters allocated for the buffer,
      - *   or less than zero if an error occurred. Usually this means that the buffer
      - *   could not be allocated.
      - *
      - ****************************************************************************/
      -
      -int avsprintf(FAR char **ptr, const char *fmt, va_list ap)
      -{
      -  struct lib_outstream_s nulloutstream;
      -  struct lib_memoutstream_s memoutstream;
      -  FAR char *buf;
      -  int nbytes;
      -
      -  DEBUGASSERT(ptr && fmt);
      -
      -  /* First, use a nullstream to get the size of the buffer.  The number
      -   * of bytes returned may or may not include the null terminator.
      -   */
      -  
      -  lib_nulloutstream(&nulloutstream);
      -  nbytes = lib_vsprintf((FAR struct lib_outstream_s *)&nulloutstream, fmt, ap);
      -
      -  /* Then allocate a buffer to hold that number of characters, adding one
      -   * for the null terminator.
      -   */
      -
      -  buf = (FAR char *)malloc(nulloutstream.nput + 1);
      -  if (!buf)
      -    {
      -      return ERROR;
      -    }
      -
      -  /* Initialize a memory stream to write into the allocated buffer.  The
      -   * memory stream will reserve one byte at the end of the buffer for the
      -   * null terminator and will not report this in the number of output bytes.
      -   */
      -
      -  lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream,
      -                   buf, nulloutstream.nput + 1);
      -
      -  /* Then let lib_vsprintf do it's real thing */
      -
      -  nbytes = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, fmt, ap);
      -
      -  /* Return a pointer to the string to the caller.  NOTE: the memstream put()
      -   * method has already added the NUL terminator to the end of the string (not
      -   * included in the nput count).
      -   *
      -   * Hmmm.. looks like the memory would be stranded if lib_vsprintf() returned
      -   * an error.  Does that ever happen?
      -   */
      -
      -  DEBUGASSERT(nbytes < 0 || nbytes == nulloutstream.nput);
      -  *ptr = buf;
      -  return nbytes;
      -}
      diff --git a/nuttx/lib/stdio/lib_clearerr.c b/nuttx/lib/stdio/lib_clearerr.c
      deleted file mode 100644
      index 7f7ded5bb4..0000000000
      --- a/nuttx/lib/stdio/lib_clearerr.c
      +++ /dev/null
      @@ -1,69 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_clearerr.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -#if CONFIG_NFILE_STREAMS > 0
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: Functions
      - *
      - * Description:
      - *   Clear any end-of-file or error conditions.
      - *
      - * Returned Value:
      - *   None
      - *
      - ****************************************************************************/
      -
      -void clearerr(FILE *stream)
      -{
      -  stream->fs_flags = 0;
      -}
      -#endif /* CONFIG_NFILE_STREAMS */
      -
      diff --git a/nuttx/lib/stdio/lib_dtoa.c b/nuttx/lib/stdio/lib_dtoa.c
      deleted file mode 100644
      index b8c7db9803..0000000000
      --- a/nuttx/lib/stdio/lib_dtoa.c
      +++ /dev/null
      @@ -1,1641 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_dtoa.c
      - *
      - * This file was ported to NuttX by Yolande Cates.
      - *
      - * Copyright (c) 1990, 1993
      - *      The Regents of the University of California.  All rights reserved.
      - *
      - * This code is derived from software contributed to Berkeley by
      - * Chris Torek.
      - *
      - * 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. All advertising materials mentioning features or use of this software
      - *    must display the following acknowledgement:
      - *      This product includes software developed by the University of
      - *      California, Berkeley and its contributors.
      - * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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 "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -#ifdef Unsigned_Shifts
      -#  define Sign_Extend(a,b) if (b < 0) a |= 0xffff0000;
      -#else
      -#  define Sign_Extend(a,b)      /* no-op */
      -#endif
      -
      -#ifdef CONFIG_ENDIAN_BIG
      -#  define word0(x) ((uint32_t *)&x)[0]
      -#  define word1(x) ((uint32_t *)&x)[1]
      -#else
      -#  define word0(x) ((uint32_t *)&x)[1]
      -#  define word1(x) ((uint32_t *)&x)[0]
      -#endif
      -
      -#ifdef CONFIG_ENDIAN_BIG
      -#  define Storeinc(a,b,c) (((unsigned short *)a)[0] = (unsigned short)b, \
      -                         ((unsigned short *)a)[1] = (unsigned short)c, a++)
      -#else
      -#  define Storeinc(a,b,c) (((unsigned short *)a)[1] = (unsigned short)b, \
      -                         ((unsigned short *)a)[0] = (unsigned short)c, a++)
      -#endif
      -
      -#define Exp_shift  20
      -#define Exp_shift1 20
      -#define Exp_msk1    0x100000
      -#define Exp_msk11   0x100000
      -#define Exp_mask  0x7ff00000
      -#define P 53
      -#define Bias 1023
      -#define IEEE_Arith
      -#define Emin (-1022)
      -#define Exp_1  0x3ff00000
      -#define Exp_11 0x3ff00000
      -#define Ebits 11
      -#define Frac_mask  0xfffff
      -#define Frac_mask1 0xfffff
      -#define Ten_pmax 22
      -#define Bletch 0x10
      -#define Bndry_mask  0xfffff
      -#define Bndry_mask1 0xfffff
      -#define LSB 1
      -#define Sign_bit 0x80000000
      -#define Log2P 1
      -#define Tiny0 0
      -#define Tiny1 1
      -#define Quick_max 14
      -#define Int_max 14
      -#define Infinite(x) (word0(x) == 0x7ff00000)    /* sufficient test for here */
      -
      -#define Kmax 15
      -
      -#define Bcopy(x,y) memcpy((char *)&x->sign, (char *)&y->sign, \
      -                          y->wds*sizeof(long) + 2*sizeof(int))
      -
      -/****************************************************************************
      - * Private Type Definitions
      - ****************************************************************************/
      -
      -struct Bigint
      -{
      -  struct Bigint *next;
      -  int k, maxwds, sign, wds;
      -  unsigned long x[1];
      -};
      -
      -typedef struct Bigint Bigint;
      -
      -/****************************************************************************
      - * Private Data
      - ****************************************************************************/
      -
      -static Bigint *freelist[Kmax + 1];
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -static Bigint *Balloc(int k)
      -{
      -  int x;
      -  Bigint *rv;
      -
      -  if ((rv = freelist[k]))
      -    {
      -      freelist[k] = rv->next;
      -    }
      -  else
      -    {
      -      x = 1 << k;
      -      rv = (Bigint *)lib_malloc(sizeof(Bigint) + (x - 1) * sizeof(long));
      -      rv->k = k;
      -      rv->maxwds = x;
      -    }
      -  rv->sign = rv->wds = 0;
      -  return rv;
      -}
      -
      -static void Bfree(Bigint * v)
      -{
      -  if (v)
      -    {
      -      v->next = freelist[v->k];
      -      freelist[v->k] = v;
      -    }
      -}
      -
      -/* multiply by m and add a */
      -
      -static Bigint *multadd(Bigint * b, int m, int a)
      -{
      -  int i, wds;
      -  unsigned long *x, y;
      -#ifdef Pack_32
      -  unsigned long xi, z;
      -#endif
      -  Bigint *b1;
      -
      -  wds = b->wds;
      -  x = b->x;
      -  i = 0;
      -  do
      -    {
      -#ifdef Pack_32
      -      xi = *x;
      -      y = (xi & 0xffff) * m + a;
      -      z = (xi >> 16) * m + (y >> 16);
      -      a = (int)(z >> 16);
      -      *x++ = (z << 16) + (y & 0xffff);
      -#else
      -      y = *x * m + a;
      -      a = (int)(y >> 16);
      -      *x++ = y & 0xffff;
      -#endif
      -    }
      -  while (++i < wds);
      -  if (a)
      -    {
      -      if (wds >= b->maxwds)
      -        {
      -          b1 = Balloc(b->k + 1);
      -          Bcopy(b1, b);
      -          Bfree(b);
      -          b = b1;
      -        }
      -      b->x[wds++] = a;
      -      b->wds = wds;
      -    }
      -  return b;
      -}
      -
      -static int hi0bits(unsigned long x)
      -{
      -  int k = 0;
      -
      -  if (!(x & 0xffff0000))
      -    {
      -      k = 16;
      -      x <<= 16;
      -    }
      -
      -  if (!(x & 0xff000000))
      -    {
      -      k += 8;
      -      x <<= 8;
      -    }
      -
      -  if (!(x & 0xf0000000))
      -    {
      -      k += 4;
      -      x <<= 4;
      -    }
      -
      -  if (!(x & 0xc0000000))
      -    {
      -      k += 2;
      -      x <<= 2;
      -    }
      -
      -  if (!(x & 0x80000000))
      -    {
      -      k++;
      -      if (!(x & 0x40000000))
      -        {
      -          return 32;
      -        }
      -    }
      -  return k;
      -}
      -
      -static int lo0bits(unsigned long *y)
      -{
      -  int k;
      -  unsigned long x = *y;
      -
      -  if (x & 7)
      -    {
      -      if (x & 1)
      -        {
      -          return 0;
      -        }
      -      if (x & 2)
      -        {
      -          *y = x >> 1;
      -          return 1;
      -        }
      -      *y = x >> 2;
      -      return 2;
      -    }
      -
      -  k = 0;
      -  if (!(x & 0xffff))
      -    {
      -      k = 16;
      -      x >>= 16;
      -    }
      -
      -  if (!(x & 0xff))
      -    {
      -      k += 8;
      -      x >>= 8;
      -    }
      -
      -  if (!(x & 0xf))
      -    {
      -      k += 4;
      -      x >>= 4;
      -    }
      -
      -  if (!(x & 0x3))
      -    {
      -      k += 2;
      -      x >>= 2;
      -    }
      -
      -  if (!(x & 1))
      -    {
      -      k++;
      -      x >>= 1;
      -      if (!x & 1)
      -        {
      -          return 32;
      -        }
      -    }
      -  *y = x;
      -  return k;
      -}
      -
      -static Bigint *i2b(int i)
      -{
      -  Bigint *b;
      -
      -  b = Balloc(1);
      -  b->x[0] = i;
      -  b->wds = 1;
      -  return b;
      -}
      -
      -static Bigint *mult(Bigint * a, Bigint * b)
      -{
      -  Bigint *c;
      -  int k, wa, wb, wc;
      -  unsigned long carry, y, z;
      -  unsigned long *x, *xa, *xae, *xb, *xbe, *xc, *xc0;
      -#ifdef Pack_32
      -  uint32_t z2;
      -#endif
      -
      -  if (a->wds < b->wds)
      -    {
      -      c = a;
      -      a = b;
      -      b = c;
      -    }
      -
      -  k = a->k;
      -  wa = a->wds;
      -  wb = b->wds;
      -  wc = wa + wb;
      -  if (wc > a->maxwds)
      -    {
      -      k++;
      -    }
      -  c = Balloc(k);
      -  for (x = c->x, xa = x + wc; x < xa; x++)
      -    {
      -      *x = 0;
      -    }
      -  xa = a->x;
      -  xae = xa + wa;
      -  xb = b->x;
      -  xbe = xb + wb;
      -  xc0 = c->x;
      -#ifdef Pack_32
      -  for (; xb < xbe; xb++, xc0++)
      -    {
      -      if ((y = *xb & 0xffff))
      -        {
      -          x = xa;
      -          xc = xc0;
      -          carry = 0;
      -          do
      -            {
      -              z = (*x & 0xffff) * y + (*xc & 0xffff) + carry;
      -              carry = z >> 16;
      -              z2 = (*x++ >> 16) * y + (*xc >> 16) + carry;
      -              carry = z2 >> 16;
      -              Storeinc(xc, z2, z);
      -            }
      -          while (x < xae);
      -          *xc = carry;
      -        }
      -      if ((y = *xb >> 16))
      -        {
      -          x = xa;
      -          xc = xc0;
      -          carry = 0;
      -          z2 = *xc;
      -          do
      -            {
      -              z = (*x & 0xffff) * y + (*xc >> 16) + carry;
      -              carry = z >> 16;
      -              Storeinc(xc, z, z2);
      -              z2 = (*x++ >> 16) * y + (*xc & 0xffff) + carry;
      -              carry = z2 >> 16;
      -            }
      -          while (x < xae);
      -          *xc = z2;
      -        }
      -    }
      -#else
      -  for (; xb < xbe; xc0++)
      -    {
      -      if ((y = *xb++))
      -        {
      -          x = xa;
      -          xc = xc0;
      -          carry = 0;
      -          do
      -            {
      -              z = *x++ * y + *xc + carry;
      -              carry = z >> 16;
      -              *xc++ = z & 0xffff;
      -            }
      -          while (x < xae);
      -          *xc = carry;
      -        }
      -    }
      -#endif
      -  for (xc0 = c->x, xc = xc0 + wc; wc > 0 && !*--xc; --wc);
      -  c->wds = wc;
      -  return c;
      -}
      -
      -static Bigint *p5s;
      -
      -static Bigint *pow5mult(Bigint * b, int k)
      -{
      -  Bigint *b1, *p5, *p51;
      -  int i;
      -  static int p05[3] = { 5, 25, 125 };
      -
      -  if ((i = k & 3))
      -    b = multadd(b, p05[i - 1], 0);
      -
      -  if (!(k >>= 2))
      -    {
      -      return b;
      -    }
      -
      -  if (!(p5 = p5s))
      -    {
      -      /* first time */
      -      p5 = p5s = i2b(625);
      -      p5->next = 0;
      -    }
      -
      -  for (;;)
      -    {
      -      if (k & 1)
      -        {
      -          b1 = mult(b, p5);
      -          Bfree(b);
      -          b = b1;
      -        }
      -      if (!(k >>= 1))
      -        {
      -          break;
      -        }
      -
      -      if (!(p51 = p5->next))
      -        {
      -          p51 = p5->next = mult(p5, p5);
      -          p51->next = 0;
      -        }
      -      p5 = p51;
      -    }
      -  return b;
      -}
      -
      -static Bigint *lshift(Bigint * b, int k)
      -{
      -  int i, k1, n, n1;
      -  Bigint *b1;
      -  unsigned long *x, *x1, *xe, z;
      -
      -#ifdef Pack_32
      -  n = k >> 5;
      -#else
      -  n = k >> 4;
      -#endif
      -  k1 = b->k;
      -  n1 = n + b->wds + 1;
      -  for (i = b->maxwds; n1 > i; i <<= 1)
      -    {
      -      k1++;
      -    }
      -  b1 = Balloc(k1);
      -  x1 = b1->x;
      -  for (i = 0; i < n; i++)
      -    {
      -      *x1++ = 0;
      -    }
      -  x = b->x;
      -  xe = x + b->wds;
      -#ifdef Pack_32
      -  if (k &= 0x1f)
      -    {
      -      k1 = 32 - k;
      -      z = 0;
      -      do
      -        {
      -          *x1++ = *x << k | z;
      -          z = *x++ >> k1;
      -        }
      -      while (x < xe);
      -      if ((*x1 = z))
      -        {
      -          ++n1;
      -        }
      -    }
      -#else
      -  if (k &= 0xf)
      -    {
      -      k1 = 16 - k;
      -      z = 0;
      -      do
      -        {
      -          *x1++ = ((*x << k) & 0xffff) | z;
      -          z = *x++ >> k1;
      -        }
      -      while (x < xe);
      -      if ((*x1 = z))
      -        {
      -          ++n1;
      -        }
      -    }
      -#endif
      -  else
      -    do
      -      {
      -        *x1++ = *x++;
      -      }
      -    while (x < xe);
      -  b1->wds = n1 - 1;
      -  Bfree(b);
      -  return b1;
      -}
      -
      -static int cmp(Bigint * a, Bigint * b)
      -{
      -  unsigned long *xa, *xa0, *xb, *xb0;
      -  int i, j;
      -
      -  i = a->wds;
      -  j = b->wds;
      -#ifdef CONFIG_DEBUG_LIB
      -  if (i > 1 && !a->x[i - 1])
      -   {
      -    ldbg("cmp called with a->x[a->wds-1] == 0\n");
      -   }
      -  if (j > 1 && !b->x[j - 1])
      -   {
      -    ldbg("cmp called with b->x[b->wds-1] == 0\n");
      -   }
      -#endif
      -  if (i -= j)
      -    return i;
      -  xa0 = a->x;
      -  xa = xa0 + j;
      -  xb0 = b->x;
      -  xb = xb0 + j;
      -  for (;;)
      -    {
      -      if (*--xa != *--xb)
      -        return *xa < *xb ? -1 : 1;
      -      if (xa <= xa0)
      -        break;
      -    }
      -  return 0;
      -}
      -
      -static Bigint *diff(Bigint * a, Bigint * b)
      -{
      -  Bigint *c;
      -  int i, wa, wb;
      -  long borrow, y;               /* We need signed shifts here. */
      -  unsigned long *xa, *xae, *xb, *xbe, *xc;
      -#ifdef Pack_32
      -  int32_t z;
      -#endif
      -
      -  i = cmp(a, b);
      -  if (!i)
      -    {
      -      c = Balloc(0);
      -      c->wds = 1;
      -      c->x[0] = 0;
      -      return c;
      -    }
      -  if (i < 0)
      -    {
      -      c = a;
      -      a = b;
      -      b = c;
      -      i = 1;
      -    }
      -  else
      -    i = 0;
      -  c = Balloc(a->k);
      -  c->sign = i;
      -  wa = a->wds;
      -  xa = a->x;
      -  xae = xa + wa;
      -  wb = b->wds;
      -  xb = b->x;
      -  xbe = xb + wb;
      -  xc = c->x;
      -  borrow = 0;
      -#ifdef Pack_32
      -  do
      -    {
      -      y = (*xa & 0xffff) - (*xb & 0xffff) + borrow;
      -      borrow = y >> 16;
      -      Sign_Extend(borrow, y);
      -      z = (*xa++ >> 16) - (*xb++ >> 16) + borrow;
      -      borrow = z >> 16;
      -      Sign_Extend(borrow, z);
      -      Storeinc(xc, z, y);
      -    }
      -  while (xb < xbe);
      -  while (xa < xae)
      -    {
      -      y = (*xa & 0xffff) + borrow;
      -      borrow = y >> 16;
      -      Sign_Extend(borrow, y);
      -      z = (*xa++ >> 16) + borrow;
      -      borrow = z >> 16;
      -      Sign_Extend(borrow, z);
      -      Storeinc(xc, z, y);
      -    }
      -#else
      -  do
      -    {
      -      y = *xa++ - *xb++ + borrow;
      -      borrow = y >> 16;
      -      Sign_Extend(borrow, y);
      -      *xc++ = y & 0xffff;
      -    }
      -  while (xb < xbe);
      -  while (xa < xae)
      -    {
      -      y = *xa++ + borrow;
      -      borrow = y >> 16;
      -      Sign_Extend(borrow, y);
      -      *xc++ = y & 0xffff;
      -    }
      -#endif
      -  while (!*--xc)
      -    wa--;
      -  c->wds = wa;
      -  return c;
      -}
      -
      -static Bigint *d2b(double d, int *e, int *bits)
      -{
      -  Bigint *b;
      -  int de, i, k;
      -  unsigned long *x, y, z;
      -
      -#ifdef Pack_32
      -  b = Balloc(1);
      -#else
      -  b = Balloc(2);
      -#endif
      -  x = b->x;
      -
      -  z = word0(d) & Frac_mask;
      -  word0(d) &= 0x7fffffff;       /* clear sign bit, which we ignore */
      -  if ((de = (int)(word0(d) >> Exp_shift)))
      -    z |= Exp_msk1;
      -#ifdef Pack_32
      -  if ((y = word1(d)))
      -    {
      -      if ((k = lo0bits(&y)))
      -        {
      -          x[0] = y | z << (32 - k);
      -          z >>= k;
      -        }
      -      else
      -        x[0] = y;
      -      i = b->wds = (x[1] = z) ? 2 : 1;
      -    }
      -  else
      -    {
      -#ifdef CONFIG_DEBUG_LIB
      -      if (!z)
      -        {
      -          ldbg("Zero passed to d2b\n");
      -        }
      -#endif
      -      k = lo0bits(&z);
      -      x[0] = z;
      -      i = b->wds = 1;
      -      k += 32;
      -    }
      -#else
      -  if ((y = word1(d)))
      -    {
      -      if ((k = lo0bits(&y)))
      -        if (k >= 16)
      -          {
      -            x[0] = y | ((z << (32 - k)) & 0xffff);
      -            x[1] = z >> (k - 16) & 0xffff;
      -            x[2] = z >> k;
      -            i = 2;
      -          }
      -        else
      -          {
      -            x[0] = y & 0xffff;
      -            x[1] = (y >> 16) | ((z << (16 - k)) & 0xffff);
      -            x[2] = z >> k & 0xffff;
      -            x[3] = z >> (k + 16);
      -            i = 3;
      -          }
      -      else
      -        {
      -          x[0] = y & 0xffff;
      -          x[1] = y >> 16;
      -          x[2] = z & 0xffff;
      -          x[3] = z >> 16;
      -          i = 3;
      -        }
      -    }
      -  else
      -    {
      -#ifdef CONFIG_DEBUG_LIB
      -      if (!z)
      -        {
      -          ldbg("Zero passed to d2b\n");
      -        }
      -#endif
      -      k = lo0bits(&z);
      -      if (k >= 16)
      -        {
      -          x[0] = z;
      -          i = 0;
      -        }
      -      else
      -        {
      -          x[0] = z & 0xffff;
      -          x[1] = z >> 16;
      -          i = 1;
      -        }
      -      k += 32;
      -    }
      -  while (!x[i])
      -    --i;
      -  b->wds = i + 1;
      -#endif
      -  if (de)
      -    {
      -      *e = de - Bias - (P - 1) + k;
      -      *bits = P - k;
      -    }
      -  else
      -    {
      -      *e = de - Bias - (P - 1) + 1 + k;
      -#ifdef Pack_32
      -      *bits = 32 * i - hi0bits(x[i - 1]);
      -#else
      -      *bits = (i + 2) * 16 - hi0bits(x[i]);
      -#endif
      -    }
      -  return b;
      -}
      -
      -static const double tens[] = {
      -  1e0, 1e1, 1e2, 1e3, 1e4, 1e5, 1e6, 1e7, 1e8, 1e9,
      -  1e10, 1e11, 1e12, 1e13, 1e14, 1e15, 1e16, 1e17, 1e18, 1e19,
      -  1e20, 1e21, 1e22
      -};
      -
      -#ifdef IEEE_Arith
      -static const double bigtens[] = { 1e16, 1e32, 1e64, 1e128, 1e256 };
      -static const double tinytens[] = { 1e-16, 1e-32, 1e-64, 1e-128, 1e-256 };
      -
      -#  define n_bigtens 5
      -#else
      -static const double bigtens[] = { 1e16, 1e32 };
      -static const double tinytens[] = { 1e-16, 1e-32 };
      -
      -#  define n_bigtens 2
      -#endif
      -
      -static int quorem(Bigint * b, Bigint * S)
      -{
      -  int n;
      -  long borrow, y;
      -  unsigned long carry, q, ys;
      -  unsigned long *bx, *bxe, *sx, *sxe;
      -#ifdef Pack_32
      -  int32_t z;
      -  uint32_t si, zs;
      -#endif
      -
      -  n = S->wds;
      -#ifdef CONFIG_DEBUG_LIB
      -  if (b->wds > n)
      -    {
      -      ldbg("oversize b in quorem\n");
      -    }
      -#endif
      -  if (b->wds < n)
      -    {
      -      return 0;
      -    }
      -  sx = S->x;
      -  sxe = sx + --n;
      -  bx = b->x;
      -  bxe = bx + n;
      -  q = *bxe / (*sxe + 1);        /* ensure q <= true quotient */
      -#ifdef CONFIG_DEBUG_LIB
      -  if (q > 9)
      -   {
      -     ldbg("oversized quotient in quorem\n");
      -   }
      -#endif
      -  if (q)
      -    {
      -      borrow = 0;
      -      carry = 0;
      -      do
      -        {
      -#ifdef Pack_32
      -          si = *sx++;
      -          ys = (si & 0xffff) * q + carry;
      -          zs = (si >> 16) * q + (ys >> 16);
      -          carry = zs >> 16;
      -          y = (*bx & 0xffff) - (ys & 0xffff) + borrow;
      -          borrow = y >> 16;
      -          Sign_Extend(borrow, y);
      -          z = (*bx >> 16) - (zs & 0xffff) + borrow;
      -          borrow = z >> 16;
      -          Sign_Extend(borrow, z);
      -          Storeinc(bx, z, y);
      -#else
      -          ys = *sx++ * q + carry;
      -          carry = ys >> 16;
      -          y = *bx - (ys & 0xffff) + borrow;
      -          borrow = y >> 16;
      -          Sign_Extend(borrow, y);
      -          *bx++ = y & 0xffff;
      -#endif
      -        }
      -      while (sx <= sxe);
      -      if (!*bxe)
      -        {
      -          bx = b->x;
      -          while (--bxe > bx && !*bxe)
      -            --n;
      -          b->wds = n;
      -        }
      -    }
      -  if (cmp(b, S) >= 0)
      -    {
      -      q++;
      -      borrow = 0;
      -      carry = 0;
      -      bx = b->x;
      -      sx = S->x;
      -      do
      -        {
      -#ifdef Pack_32
      -          si = *sx++;
      -          ys = (si & 0xffff) + carry;
      -          zs = (si >> 16) + (ys >> 16);
      -          carry = zs >> 16;
      -          y = (*bx & 0xffff) - (ys & 0xffff) + borrow;
      -          borrow = y >> 16;
      -          Sign_Extend(borrow, y);
      -          z = (*bx >> 16) - (zs & 0xffff) + borrow;
      -          borrow = z >> 16;
      -          Sign_Extend(borrow, z);
      -          Storeinc(bx, z, y);
      -#else
      -          ys = *sx++ + carry;
      -          carry = ys >> 16;
      -          y = *bx - (ys & 0xffff) + borrow;
      -          borrow = y >> 16;
      -          Sign_Extend(borrow, y);
      -          *bx++ = y & 0xffff;
      -#endif
      -        }
      -      while (sx <= sxe);
      -      bx = b->x;
      -      bxe = bx + n;
      -      if (!*bxe)
      -        {
      -          while (--bxe > bx && !*bxe)
      -            --n;
      -          b->wds = n;
      -        }
      -    }
      -  return q;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/* dtoa for IEEE arithmetic (dmg): convert double to ASCII string.
      - *
      - * Inspired by "How to Print Floating-Point Numbers Accurately" by
      - * Guy L. Steele, Jr. and Jon L. White [Proc. ACM SIGPLAN '90, pp. 92-101].
      - *
      - * Modifications:
      - *      1. Rather than iterating, we use a simple numeric overestimate
      - *         to determine k = floor(log10(d)).  We scale relevant
      - *         quantities using O(log2(k)) rather than O(k) multiplications.
      - *      2. For some modes > 2 (corresponding to ecvt and fcvt), we don't
      - *         try to generate digits strictly left to right.  Instead, we
      - *         compute with fewer bits and propagate the carry if necessary
      - *         when rounding the final digit up.  This is often faster.
      - *      3. Under the assumption that input will be rounded nearest,
      - *         mode 0 renders 1e23 as 1e23 rather than 9.999999999999999e22.
      - *         That is, we allow equality in stopping tests when the
      - *         round-nearest rule will give the same floating-point value
      - *         as would satisfaction of the stopping test with strict
      - *         inequality.
      - *      4. We remove common factors of powers of 2 from relevant
      - *         quantities.
      - *      5. When converting floating-point integers less than 1e16,
      - *         we use floating-point arithmetic rather than resorting
      - *         to multiple-precision integers.
      - *      6. When asked to produce fewer than 15 digits, we first try
      - *         to get by with floating-point arithmetic; we resort to
      - *         multiple-precision integer arithmetic only if we cannot
      - *         guarantee that the floating-point calculation has given
      - *         the correctly rounded result.  For k requested digits and
      - *         "uniformly" distributed input, the probability is
      - *         something like 10^(k-15) that we must resort to the int32_t
      - *         calculation.
      - */
      -
      -char *__dtoa(double d, int mode, int ndigits, int *decpt, int *sign, char **rve)
      -{
      -  /* Arguments ndigits, decpt, sign are similar to those of ecvt and fcvt;
      -   * trailing zeros are suppressed from the returned string.  If not null, *rve 
      -   * is set to point to the end of the return value.  If d is +-Infinity or
      -   * NaN, then *decpt is set to 9999.
      -   * 
      -   * mode: 0 ==> shortest string that yields d when read in and rounded to
      -   * nearest. 1 ==> like 0, but with Steele & White stopping rule; e.g. with
      -   * IEEE P754 arithmetic , mode 0 gives 1e23 whereas mode 1 gives
      -   * 9.999999999999999e22. 2 ==> max(1,ndigits) significant digits.  This gives 
      -   * a return value similar to that of ecvt, except that trailing zeros are
      -   * suppressed. 3 ==> through ndigits past the decimal point.  This gives a
      -   * return value similar to that from fcvt, except that trailing zeros are
      -   * suppressed, and ndigits can be negative. 4-9 should give the same return
      -   * values as 2-3, i.e., 4 <= mode <= 9 ==> same return as mode 2 + (mode &
      -   * 1).  These modes are mainly for debugging; often they run slower but
      -   * sometimes faster than modes 2-3. 4,5,8,9 ==> left-to-right digit
      -   * generation. 6-9 ==> don't try fast floating-point estimate (if
      -   * applicable).
      -   * 
      -   * Values of mode other than 0-9 are treated as mode 0.
      -   * 
      -   * Sufficient space is allocated to the return value to hold the suppressed
      -   * trailing zeros. */
      -
      -  int bbits, b2, b5, be, dig, i, ieps, ilim = 0, ilim0, ilim1 = 0,
      -    j, j_1, k, k0, k_check, leftright, m2, m5, s2, s5, spec_case = 0, try_quick;
      -  long L;
      -  int denorm;
      -  unsigned long x;
      -  Bigint *b, *b1, *delta, *mlo = NULL, *mhi, *S;
      -  double d2, ds, eps;
      -  char *s, *s0;
      -  static Bigint *result;
      -  static int result_k;
      -
      -  if (result)
      -    {
      -      result->k = result_k;
      -      result->maxwds = 1 << result_k;
      -      Bfree(result);
      -      result = 0;
      -    }
      -
      -  if (word0(d) & Sign_bit)
      -    {
      -      /* set sign for everything, including 0's and NaNs */
      -      *sign = 1;
      -      word0(d) &= ~Sign_bit;    /* clear sign bit */
      -    }
      -  else
      -    {
      -      *sign = 0;
      -    }
      -
      -#if defined(IEEE_Arith)
      -#  ifdef IEEE_Arith
      -  if ((word0(d) & Exp_mask) == Exp_mask)
      -#else
      -  if (word0(d) == 0x8000)
      -#endif
      -    {
      -      /* Infinity or NaN */
      -      *decpt = 9999;
      -      s =
      -#ifdef IEEE_Arith
      -        !word1(d) && !(word0(d) & 0xfffff) ? "Infinity" :
      -#endif
      -        "NaN";
      -      if (rve)
      -        *rve =
      -#ifdef IEEE_Arith
      -          s[3] ? s + 8 :
      -#endif
      -          s + 3;
      -      return s;
      -    }
      -#endif
      -  if (!d)
      -    {
      -      *decpt = 1;
      -      s = "0";
      -      if (rve)
      -        *rve = s + 1;
      -      return s;
      -    }
      -
      -  b = d2b(d, &be, &bbits);
      -  if ((i = (int)(word0(d) >> Exp_shift1 & (Exp_mask >> Exp_shift1))))
      -    {
      -      d2 = d;
      -      word0(d2) &= Frac_mask1;
      -      word0(d2) |= Exp_11;
      -
      -      /* log(x) ~=~ log(1.5) + (x-1.5)/1.5 log10(x) = log(x) / log(10) ~=~
      -       * log(1.5)/log(10) + (x-1.5)/(1.5*log(10)) log10(d) =
      -       * (i-Bias)*log(2)/log(10) + log10(d2) This suggests computing an
      -       * approximation k to log10(d) by k = (i - Bias)*0.301029995663981 + (
      -       * (d2-1.5)*0.289529654602168 + 0.176091259055681 ); We want k to be too 
      -       * large rather than too small. The error in the first-order Taylor
      -       * series approximation is in our favor, so we just round up the constant 
      -       * enough to compensate for any error in the multiplication of (i - Bias) 
      -       * by 0.301029995663981; since |i - Bias| <= 1077, and 1077 * 0.30103 *
      -       * 2^-52 ~=~ 7.2e-14, adding 1e-13 to the constant term more than
      -       * suffices. Hence we adjust the constant term to 0.1760912590558. (We
      -       * could get a more accurate k by invoking log10, but this is probably
      -       * not worthwhile.) */
      -
      -      i -= Bias;
      -      denorm = 0;
      -    }
      -  else
      -    {
      -      /* d is denormalized */
      -
      -      i = bbits + be + (Bias + (P - 1) - 1);
      -      x = i > 32 ? word0(d) << (64 - i) | word1(d) >> (i - 32)
      -        : word1(d) << (32 - i);
      -      d2 = x;
      -      word0(d2) -= 31 * Exp_msk1;       /* adjust exponent */
      -      i -= (Bias + (P - 1) - 1) + 1;
      -      denorm = 1;
      -    }
      -
      -  ds = (d2 - 1.5) * 0.289529654602168 + 0.1760912590558 + i * 0.301029995663981;
      -  k = (int)ds;
      -  if (ds < 0. && ds != k)
      -    {
      -      k--;  /* want k = floor(ds) */
      -    }
      -  k_check = 1;
      -
      -  if (k >= 0 && k <= Ten_pmax)
      -    {
      -      if (d < tens[k])
      -        k--;
      -      k_check = 0;
      -    }
      -
      -  j = bbits - i - 1;
      -  if (j >= 0)
      -    {
      -      b2 = 0;
      -      s2 = j;
      -    }
      -  else
      -    {
      -      b2 = -j;
      -      s2 = 0;
      -    }
      -
      -  if (k >= 0)
      -    {
      -      b5 = 0;
      -      s5 = k;
      -      s2 += k;
      -    }
      -  else
      -    {
      -      b2 -= k;
      -      b5 = -k;
      -      s5 = 0;
      -    }
      -
      -  if (mode < 0 || mode > 9)
      -    {
      -      mode = 0;
      -    }
      -
      -  try_quick = 1;
      -  if (mode > 5)
      -    {
      -      mode -= 4;
      -      try_quick = 0;
      -    }
      -
      -  leftright = 1;
      -  switch (mode)
      -    {
      -    case 0:
      -    case 1:
      -      ilim = ilim1 = -1;
      -      i = 18;
      -      ndigits = 0;
      -      break;
      -
      -    case 2:
      -      leftright = 0;
      -      /* no break */
      -    case 4:
      -      if (ndigits <= 0)
      -        {
      -          ndigits = 1;
      -        }
      -
      -      ilim = ilim1 = i = ndigits;
      -      break;
      -
      -    case 3:
      -      leftright = 0;
      -      /* no break */
      -    case 5:
      -      i = ndigits + k + 1;
      -      ilim = i;
      -      ilim1 = i - 1;
      -      if (i <= 0)
      -        {
      -          i = 1;
      -        }
      -    }
      -
      -  j = sizeof(unsigned long);
      -  for (result_k = 0;
      -       (signed)(sizeof(Bigint) - sizeof(unsigned long) + j) <= i;
      -       j <<= 1)
      -    {
      -      result_k++;
      -    }
      -
      -  result = Balloc(result_k);
      -  s = s0 = (char *)result;
      -
      -  if (ilim >= 0 && ilim <= Quick_max && try_quick)
      -    {
      -      /* Try to get by with floating-point arithmetic. */
      -
      -      i = 0;
      -      d2 = d;
      -      k0 = k;
      -      ilim0 = ilim;
      -      ieps = 2;                 /* conservative */
      -
      -      if (k > 0)
      -        {
      -          ds = tens[k & 0xf];
      -          j = k >> 4;
      -
      -          if (j & Bletch)
      -            {
      -              /* prevent overflows */
      -              j &= Bletch - 1;
      -              d /= bigtens[n_bigtens - 1];
      -              ieps++;
      -            }
      -
      -          for (; j; j >>= 1, i++)
      -            {
      -              if (j & 1)
      -                {
      -                  ieps++;
      -                  ds *= bigtens[i];
      -                }
      -            }
      -
      -          d /= ds;
      -        }
      -      else if ((j_1 = -k))
      -        {
      -          d *= tens[j_1 & 0xf];
      -          for (j = j_1 >> 4; j; j >>= 1, i++)
      -            {
      -              if (j & 1)
      -                {
      -                  ieps++;
      -                  d *= bigtens[i];
      -                }
      -            }
      -        }
      -
      -      if (k_check && d < 1. && ilim > 0)
      -        {
      -          if (ilim1 <= 0)
      -            {
      -              goto fast_failed;
      -            }
      -
      -          ilim = ilim1;
      -          k--;
      -          d *= 10.;
      -          ieps++;
      -        }
      -
      -      eps = ieps * d + 7.;
      -      word0(eps) -= (P - 1) * Exp_msk1;
      -      if (ilim == 0)
      -        {
      -          S = mhi = 0;
      -          d -= 5.;
      -          if (d > eps)
      -            goto one_digit;
      -          if (d < -eps)
      -            goto no_digits;
      -          goto fast_failed;
      -        }
      -
      -#ifndef No_leftright
      -      if (leftright)
      -        {
      -          /* Use Steele & White method of only generating digits needed. */
      -
      -          eps = 0.5 / tens[ilim - 1] - eps;
      -          for (i = 0;;)
      -            {
      -              L = (int)d;
      -              d -= L;
      -              *s++ = '0' + (int)L;
      -              if (d < eps)
      -                goto ret1;
      -              if (1. - d < eps)
      -                goto bump_up;
      -              if (++i >= ilim)
      -                break;
      -              eps *= 10.;
      -              d *= 10.;
      -            }
      -        }
      -      else
      -        {
      -#endif
      -          /* Generate ilim digits, then fix them up. */
      -          
      -          eps *= tens[ilim - 1];
      -          for (i = 1;; i++, d *= 10.)
      -            {
      -              L = (int)d;
      -              d -= L;
      -              *s++ = '0' + (int)L;
      -              if (i == ilim)
      -                {
      -                  if (d > 0.5 + eps)
      -                    goto bump_up;
      -                  else if (d < 0.5 - eps)
      -                    {
      -                      while (*--s == '0');
      -                      s++;
      -                      goto ret1;
      -                    }
      -                  break;
      -                }
      -            }
      -#ifndef No_leftright
      -        }
      -#endif
      -    fast_failed:
      -      s = s0;
      -      d = d2;
      -      k = k0;
      -      ilim = ilim0;
      -    }
      -
      -  /* Do we have a "small" integer? */
      -
      -  if (be >= 0 && k <= Int_max)
      -    {
      -      /* Yes. */
      -
      -      ds = tens[k];
      -      if (ndigits < 0 && ilim <= 0)
      -        {
      -          S = mhi = 0;
      -          if (ilim < 0 || d <= 5 * ds)
      -            goto no_digits;
      -          goto one_digit;
      -        }
      -
      -      for (i = 1;; i++)
      -        {
      -          L = (int)(d / ds);
      -          d -= L * ds;
      -#ifdef Check_FLT_ROUNDS
      -          /* If FLT_ROUNDS == 2, L will usually be high by 1 */
      -          if (d < 0)
      -            {
      -              L--;
      -              d += ds;
      -            }
      -#endif
      -          *s++ = '0' + (int)L;
      -          if (i == ilim)
      -            {
      -              d += d;
      -              if (d > ds || (d == ds && (L & 1)))
      -                {
      -                bump_up:
      -                  while (*--s == '9')
      -                    if (s == s0)
      -                      {
      -                        k++;
      -                        *s = '0';
      -                        break;
      -                      }
      -                  ++*s++;
      -                }
      -              break;
      -            }
      -          if (!(d *= 10.))
      -            {
      -              break;
      -            }
      -        }
      -
      -      goto ret1;
      -    }
      -
      -  m2 = b2;
      -  m5 = b5;
      -  mhi = mlo = 0;
      -  if (leftright)
      -    {
      -      if (mode < 2)
      -        {
      -          i = denorm ? be + (Bias + (P - 1) - 1 + 1) : 1 + P - bbits;
      -        }
      -      else
      -        {
      -          j = ilim - 1;
      -          if (m5 >= j)
      -            m5 -= j;
      -          else
      -            {
      -              s5 += j -= m5;
      -              b5 += j;
      -              m5 = 0;
      -            }
      -          if ((i = ilim) < 0)
      -            {
      -              m2 -= i;
      -              i = 0;
      -            }
      -        }
      -
      -      b2 += i;
      -      s2 += i;
      -      mhi = i2b(1);
      -    }
      -
      -  if (m2 > 0 && s2 > 0)
      -    {
      -      i = m2 < s2 ? m2 : s2;
      -      b2 -= i;
      -      m2 -= i;
      -      s2 -= i;
      -    }
      -
      -  if (b5 > 0)
      -    {
      -      if (leftright)
      -        {
      -          if (m5 > 0)
      -            {
      -              mhi = pow5mult(mhi, m5);
      -              b1 = mult(mhi, b);
      -              Bfree(b);
      -              b = b1;
      -            }
      -          if ((j = b5 - m5))
      -            b = pow5mult(b, j);
      -        }
      -      else
      -        {
      -          b = pow5mult(b, b5);
      -        }
      -    }
      -
      -  S = i2b(1);
      -  if (s5 > 0)
      -    {
      -      S = pow5mult(S, s5);
      -    }
      -
      -  /* Check for special case that d is a normalized power of 2. */
      -
      -  if (mode < 2)
      -    {
      -      if (!word1(d) && !(word0(d) & Bndry_mask) && word0(d) & Exp_mask)
      -        {
      -          /* The special case */
      -          b2 += Log2P;
      -          s2 += Log2P;
      -          spec_case = 1;
      -        }
      -      else
      -        {
      -          spec_case = 0;
      -        }
      -    }
      -
      -  /* Arrange for convenient computation of quotients: shift left if
      -   * necessary so divisor has 4 leading 0 bits.
      -   *
      -   * Perhaps we should just compute leading 28 bits of S once and for all
      -   * and pass them and a shift to quorem, so it can do shifts and ors
      -   * to compute the numerator for q.
      -   */
      -
      -#ifdef Pack_32
      -  if ((i = ((s5 ? 32 - hi0bits(S->x[S->wds - 1]) : 1) + s2) & 0x1f))
      -    {
      -      i = 32 - i;
      -    }
      -#else
      -  if ((i = ((s5 ? 32 - hi0bits(S->x[S->wds - 1]) : 1) + s2) & 0xf))
      -    {
      -      i = 16 - i;
      -    }
      -#endif
      -
      -  if (i > 4)
      -    {
      -      i -= 4;
      -      b2 += i;
      -      m2 += i;
      -      s2 += i;
      -    }
      -  else if (i < 4)
      -    {
      -      i += 28;
      -      b2 += i;
      -      m2 += i;
      -      s2 += i;
      -    }
      -
      -  if (b2 > 0)
      -    {
      -      b = lshift(b, b2);
      -    }
      -
      -  if (s2 > 0)
      -    {
      -      S = lshift(S, s2);
      -    }
      -
      -  if (k_check)
      -    {
      -      if (cmp(b, S) < 0)
      -        {
      -          k--;
      -          b = multadd(b, 10, 0);        /* we botched the k estimate */
      -          if (leftright)
      -            {
      -              mhi = multadd(mhi, 10, 0);
      -            }
      -
      -          ilim = ilim1;
      -        }
      -    }
      -
      -  if (ilim <= 0 && mode > 2)
      -    {
      -      if (ilim < 0 || cmp(b, S = multadd(S, 5, 0)) <= 0)
      -        {
      -          /* no digits, fcvt style */
      -        no_digits:
      -          k = -1 - ndigits;
      -          goto ret;
      -        }
      -    one_digit:
      -      *s++ = '1';
      -      k++;
      -      goto ret;
      -    }
      -
      -  if (leftright)
      -    {
      -      if (m2 > 0)
      -        {
      -          mhi = lshift(mhi, m2);
      -        }
      -
      -      /* Compute mlo -- check for special case that d is a normalized power of
      -       * 2. */
      -
      -      mlo = mhi;
      -      if (spec_case)
      -        {
      -          mhi = Balloc(mhi->k);
      -          Bcopy(mhi, mlo);
      -          mhi = lshift(mhi, Log2P);
      -        }
      -
      -      for (i = 1;; i++)
      -        {
      -          dig = quorem(b, S) + '0';
      -          /* Do we yet have the shortest decimal string that will round to d? */
      -          j = cmp(b, mlo);
      -          delta = diff(S, mhi);
      -          j_1 = delta->sign ? 1 : cmp(b, delta);
      -          Bfree(delta);
      -#ifndef ROUND_BIASED
      -          if (j_1 == 0 && !mode && !(word1(d) & 1))
      -            {
      -              if (dig == '9')
      -                {
      -                 goto round_9_up;
      -                }
      -
      -              if (j > 0)
      -                {
      -                  dig++;
      -                }
      -
      -              *s++ = dig;
      -              goto ret;
      -            }
      -#endif
      -          if (j < 0 || (j == 0 && !mode
      -#ifndef ROUND_BIASED
      -                        && (!(word1(d) & 1))
      -#endif
      -            ))
      -            {
      -              if ((j_1 > 0))
      -                {
      -                  b = lshift(b, 1);
      -                  j_1 = cmp(b, S);
      -                  if ((j_1 > 0 || (j_1 == 0 && (dig & 1))) && dig++ == '9')
      -                    {
      -                      goto round_9_up;
      -                    }
      -                }
      -
      -              *s++ = dig;
      -              goto ret;
      -            }
      -
      -          if (j_1 > 0)
      -            {
      -              if (dig == '9')
      -                {               /* possible if i == 1 */
      -                round_9_up:
      -                  *s++ = '9';
      -                  goto roundoff;
      -                }
      -
      -              *s++ = dig + 1;
      -              goto ret;
      -            }
      -
      -          *s++ = dig;
      -          if (i == ilim)
      -            {
      -              break;
      -            }
      -
      -          b = multadd(b, 10, 0);
      -          if (mlo == mhi)
      -            {
      -              mlo = mhi = multadd(mhi, 10, 0);
      -            }
      -          else
      -            {
      -              mlo = multadd(mlo, 10, 0);
      -              mhi = multadd(mhi, 10, 0);
      -            }
      -        }
      -    }
      -  else
      -    {
      -      for (i = 1;; i++)
      -        {
      -          *s++ = dig = quorem(b, S) + '0';
      -          if (i >= ilim)
      -            {
      -              break;
      -            }
      -
      -          b = multadd(b, 10, 0);
      -        }
      -    }
      -
      -  /* Round off last digit */
      -
      -  b = lshift(b, 1);
      -  j = cmp(b, S);
      -  if (j > 0 || (j == 0 && (dig & 1)))
      -    {
      -    roundoff:
      -      while (*--s == '9')
      -        if (s == s0)
      -          {
      -            k++;
      -            *s++ = '1';
      -            goto ret;
      -          }
      -      ++*s++;
      -    }
      -  else
      -    {
      -      while (*--s == '0');
      -      s++;
      -    }
      -
      -ret:
      -  Bfree(S);
      -  if (mhi)
      -    {
      -      if (mlo && mlo != mhi)
      -        {
      -          Bfree(mlo);
      -        }
      -
      -      Bfree(mhi);
      -    }
      -ret1:
      -  Bfree(b);
      -  if (s == s0)
      -    {                           /* don't return empty string */
      -      *s++ = '0';
      -      k = 0;
      -    }
      -
      -  *s = 0;
      -  *decpt = k + 1;
      -  if (rve)
      -    {
      -      *rve = s;
      -    }
      -
      -  return s0;
      -}
      diff --git a/nuttx/lib/stdio/lib_fclose.c b/nuttx/lib/stdio/lib_fclose.c
      deleted file mode 100644
      index 8cecb8af3c..0000000000
      --- a/nuttx/lib/stdio/lib_fclose.c
      +++ /dev/null
      @@ -1,154 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fclose.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fclose
      - *
      - * Description
      - *   The fclose() function will flush the stream pointed to by stream
      - *   (writing any buffered output data using lib_fflush()) and close the
      - *   underlying file descriptor.
      - *
      - * Returned Value:
      - *   Upon successful completion 0 is returned. Otherwise, EOF is returned
      - *   and the global variable errno is set to indicate the error. In either
      - *   case any further access (including another call to fclose()) to the
      - *   stream results in undefined behaviour.
      - *
      - ****************************************************************************/
      -
      -int fclose(FAR FILE *stream)
      -{
      -  int err = EINVAL;
      -  int ret = ERROR;
      -  int status;
      -
      -  /* Verify that a stream was provided. */
      -
      -  if (stream)
      -    {
      -      /* Check that the underlying file descriptor corresponds to an an open
      -       * file.
      -       */
      - 
      -      ret = OK;
      -      if (stream->fs_filedes >= 0)
      -        {
      -          /* If the stream was opened for writing, then flush the stream */
      -
      -          if ((stream->fs_oflags & O_WROK) != 0)
      -            {
      -              ret = lib_fflush(stream, true);
      -              err = errno;
      -            }
      -
      -          /* Close the underlying file descriptor and save the return status */
      -
      -          status = close(stream->fs_filedes);
      -
      -          /* If close() returns an error but flush() did not then make sure
      -           * that we return the close() error condition.
      -           */
      -
      -          if (ret == OK)
      -            {
      -              ret = status;
      -              err = errno;
      -            }
      -        }
      -
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -      /* Destroy the semaphore */
      -
      -      sem_destroy(&stream->fs_sem);
      -
      -      /* Release the buffer */
      -
      -      if (stream->fs_bufstart)
      -        {
      -          lib_free(stream->fs_bufstart);
      -        }
      -
      -      /* Clear the whole structure */
      -
      -      memset(stream, 0, sizeof(FILE));
      -#else
      -#if CONFIG_NUNGET_CHARS > 0
      -      /* Reset the number of ungetc characters */
      -
      -      stream->fs_nungotten = 0;
      -#endif
      -      /* Reset the flags */
      -
      -      stream->fs_oflags = 0;
      -#endif
      -      /* Setting the fs_filedescriptor to -1 makes the stream available for reuse */
      -
      -      stream->fs_filedes = -1;
      -    }
      -
      -  /* On an error, reset the errno to the first error encountered and return
      -   * EOF.
      -   */
      -
      -  if (ret != OK)
      -    {
      -      set_errno(err);
      -      return EOF;
      -    }
      -
      -  /* Return success */
      -
      -  return OK;
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_feof.c b/nuttx/lib/stdio/lib_feof.c
      deleted file mode 100644
      index e44c6a3c92..0000000000
      --- a/nuttx/lib/stdio/lib_feof.c
      +++ /dev/null
      @@ -1,77 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_feof.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -#if CONFIG_NFILE_STREAMS > 0
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: feof
      - *
      - * Description:
      - *   The feof() function shall test if the currently file pointer for the
      - *   stream is at the end of file.
      - *
      - * Returned Value:
      - *  This function will return non-zero if the the file pointer is positioned
      - *  at the end of file.
      - *
      - ****************************************************************************/
      -
      -int feof(FILE *stream)
      -{
      -  /* If the end-of-file condition is encountered by any of the C-buffered
      -   * I/O functions that perform read operations, they should set the
      -   * __FS_FLAG_EOF in the fs_flags field of struct file_struct.
      -   */
      -
      -  return (stream->fs_flags & __FS_FLAG_EOF) != 0;
      -}
      -
      -#endif /* CONFIG_NFILE_STREAMS */
      -
      diff --git a/nuttx/lib/stdio/lib_ferror.c b/nuttx/lib/stdio/lib_ferror.c
      deleted file mode 100644
      index 4ad7d8cfca..0000000000
      --- a/nuttx/lib/stdio/lib_ferror.c
      +++ /dev/null
      @@ -1,90 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_ferror.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -#if CONFIG_NFILE_STREAMS > 0
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: ferror
      - *
      - * Description:
      - *   This function will test if the last operation resulted in an eror.  This
      - *   is used to disambiguate EOF and error conditions.
      - *
      - * Return Value:
      - *   A non-zero value is returned to indicate the error condition.
      - *
      - ****************************************************************************/
      -
      -int ferror(FILE *stream)
      -{
      -#if 0
      -  /* If an error is encountered by any of the C-buffered I/O functions, they
      -   * should set the __FS_FLAG_ERROR in the fs_flags field of struct
      -   * file_struct.
      -   */
      -
      -  return (stream->fs_flags & __FS_FLAG_ERROR) != 0;
      -#else
      -  /* However, nothing currenlty sets the __FS_FLAG_ERROR flag (that is a job
      -   * for another day).  The __FS_FLAG_EOF is set by operations that perform
      -   * read operations.  Since ferror()  is probably only called to disambiguate
      -   * the meaning of other functions that return EOF, to indicate either EOF or
      -   * an error, just testing for not EOF is probably sufficient for now.
      -   *
      -   * This approach would not work if ferror() is called in other contexts. In
      -   * those cases, ferror() will always report an error.
      -   */
      -
      -  return (stream->fs_flags & __FS_FLAG_EOF) == 0;
      -#endif
      -}
      -
      -#endif /* CONFIG_NFILE_STREAMS */
      -
      diff --git a/nuttx/lib/stdio/lib_fflush.c b/nuttx/lib/stdio/lib_fflush.c
      deleted file mode 100644
      index d0b5e0185d..0000000000
      --- a/nuttx/lib/stdio/lib_fflush.c
      +++ /dev/null
      @@ -1,132 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fflush.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fflush
      - *
      - * Description:
      - *  The function fflush() forces a write of all user-space buffered data for
      - *  the given output or update stream via the stream's underlying write
      - *  function.  The open status of the stream is unaffected.
      - *
      - *  If the stream argument is NULL, fflush() flushes all open output streams.
      - *
      - * Return:
      - *  OK on success EOF on failure (with errno set appropriately)
      - *
      - ****************************************************************************/
      -
      -int fflush(FAR FILE *stream)
      -{
      -  int ret;
      -
      -  /* Is the stream argument NULL? */
      -
      -  if (!stream)
      -    {
      -      /* Yes... then this is a request to flush all streams */
      -
      -      ret = lib_flushall(sched_getstreams());
      -    }
      -  else
      -    {
      -      ret = lib_fflush(stream, true);
      -    }
      -
      -  /* Check the return value */
      -
      -  if (ret < 0)
      -    {
      -      /* An error occurred during the flush AND/OR we were unable to flush
      -       * all of the buffered write data. Set the errno value.
      -       */
      -
      -      set_errno(-ret);
      -
      -      /* And return EOF on failure. */
      -
      -      return EOF;
      -    }
      -
      -  return OK;
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_fgetc.c b/nuttx/lib/stdio/lib_fgetc.c
      deleted file mode 100644
      index 4b3d0ec44f..0000000000
      --- a/nuttx/lib/stdio/lib_fgetc.c
      +++ /dev/null
      @@ -1,101 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fgetc.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Global Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Private Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - **************************************************************************/
      -
      -/****************************************************************************
      - * fgetc
      - **************************************************************************/
      -
      -int fgetc(FAR FILE *stream)
      -{
      -  unsigned char ch;
      -  ssize_t ret;
      -
      -  ret = lib_fread(&ch, 1, stream);
      -  if (ret > 0)
      -    {
      -      return ch;
      -    }
      -  else
      -    {
      -      return EOF;
      -    }
      -}
      diff --git a/nuttx/lib/stdio/lib_fgetpos.c b/nuttx/lib/stdio/lib_fgetpos.c
      deleted file mode 100644
      index e9e9f4d102..0000000000
      --- a/nuttx/lib/stdio/lib_fgetpos.c
      +++ /dev/null
      @@ -1,123 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fgetpos.c
      - *
      - *   Copyright (C) 2008-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fgetpos
      - *
      - * Description:
      - *   fgetpos() function is an alternate interfaces equivalent to ftell().
      - *   It gets the current value of the file offset and store it in the location
      - *   referenced by pos.  On some non-UNIX systems an fpos_t object may be a
      - *   complex object and fsetpos may be the only way to portably reposition a
      - *   stream.
      - *
      - * Returned Value:
      - *   Zero on succes; -1 on failure with errno set appropriately. 
      - *
      - ****************************************************************************/
      -
      -int fgetpos(FAR FILE *stream, FAR fpos_t *pos)
      -{
      -  long position;
      -
      -#if CONFIG_DEBUG
      -  if (!stream || !pos)
      -    {
      -      set_errno(EINVAL);
      -      return ERROR;
      -    }
      -#endif
      -
      -  position = ftell(stream);
      -  if (position == -1)
      -    {
      -      return ERROR;
      -    }
      -
      -  *pos = (fpos_t)position;
      -  return OK;
      -}
      diff --git a/nuttx/lib/stdio/lib_fgets.c b/nuttx/lib/stdio/lib_fgets.c
      deleted file mode 100644
      index a4f9089ed7..0000000000
      --- a/nuttx/lib/stdio/lib_fgets.c
      +++ /dev/null
      @@ -1,207 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fgets.c
      - *
      - *   Copyright (C) 2007-2008, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -/* Some environments may return CR as end-of-line, others LF, and others
      - * both.  If not specified, the logic here assumes either (but not both) as
      - * the default.
      - */
      -
      -#if defined(CONFIG_EOL_IS_CR)
      -#  undef  CONFIG_EOL_IS_LF
      -#  undef  CONFIG_EOL_IS_BOTH_CRLF
      -#  undef  CONFIG_EOL_IS_EITHER_CRLF
      -#elif defined(CONFIG_EOL_IS_LF)
      -#  undef  CONFIG_EOL_IS_CR
      -#  undef  CONFIG_EOL_IS_BOTH_CRLF
      -#  undef  CONFIG_EOL_IS_EITHER_CRLF
      -#elif defined(CONFIG_EOL_IS_BOTH_CRLF)
      -#  undef  CONFIG_EOL_IS_CR
      -#  undef  CONFIG_EOL_IS_LF
      -#  undef  CONFIG_EOL_IS_EITHER_CRLF
      -#elif defined(CONFIG_EOL_IS_EITHER_CRLF)
      -#  undef  CONFIG_EOL_IS_CR
      -#  undef  CONFIG_EOL_IS_LF
      -#  undef  CONFIG_EOL_IS_BOTH_CRLF
      -#else
      -#  undef  CONFIG_EOL_IS_CR
      -#  undef  CONFIG_EOL_IS_LF
      -#  undef  CONFIG_EOL_IS_BOTH_CRLF
      -#  define CONFIG_EOL_IS_EITHER_CRLF 1
      -#endif
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fgets
      - *
      - * Description:
      - *   fgets() reads in at most one less than 'buflen' characters from stream
      - *   and stores them into the buffer pointed to by 'buf'. Reading stops after
      - *   an EOF or a newline.  If a newline is read, it is stored into the
      - *   buffer.  A null terminator is stored after the last character in the
      - *   buffer.
      - *
      - **************************************************************************/
      -
      -char *fgets(FAR char *buf, int buflen, FILE *stream)
      -{
      -  int  nch = 0;
      -
      -  /* Sanity checks */
      -
      -  if (!stream || !buf || buflen < 1 || stream->fs_filedes < 0)
      -    {
      -      return NULL;
      -    }
      -
      -  if (buflen < 2)
      -    {
      -      *buf = '\0';
      -      return buf;
      -    }
      -
      -  /* Read characters until we have a full line. On each the loop we must
      -   * be assured that there are two free bytes in the line buffer:  One for
      -   * the next character and one for the null terminator.
      -   */
      -
      -  for(;;)
      -    {
      -      /* Get the next character */
      -
      -      int ch = fgetc(stream);
      -
      -      /* Check for end-of-line.  This is tricky only in that some
      -       * environments may return CR as end-of-line, others LF, and
      -       * others both.
      -       */
      -
      -#if  defined(CONFIG_EOL_IS_LF) || defined(CONFIG_EOL_IS_BOTH_CRLF)
      -      if (ch == '\n')
      -#elif defined(CONFIG_EOL_IS_CR)
      -      if (ch == '\r')
      -#elif CONFIG_EOL_IS_EITHER_CRLF
      -      if (ch == '\n' || ch == '\r')
      -#endif
      -        {
      -          /* The newline is stored in the buffer along with the null
      -           * terminator.
      -           */
      -
      -          buf[nch++] = '\n';
      -          buf[nch]   = '\0';
      -          return buf;
      -        }
      -
      -      /* Check for end-of-file */
      -
      -      else if (ch == EOF)
      -        {
      -          /* End of file with no data? */
      -
      -          if (!nch)
      -            {
      -              /* Yes.. return NULL as the end of file mark */
      -
      -              return NULL;
      -            }
      -          else
      -            {
      -              /* Terminate the line */
      -
      -              buf[nch]   = '\0';
      -              return buf;
      -            }
      -        }
      -
      -      /* Otherwise, check if the character is printable and, if so, put the
      -       * character in the line buffer
      -       */
      -
      -      else if (isprint(ch))
      -        {
      -          buf[nch++] = ch;
      -
      -          /* Check if there is room for another character and the line's
      -           * null terminator.  If not then we have to end the line now.
      -           */
      -
      -          if (nch + 1 >= buflen)
      -            {
      -              buf[nch] = '\0';
      -              return buf;
      -            }
      -        }
      -    }
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_fileno.c b/nuttx/lib/stdio/lib_fileno.c
      deleted file mode 100644
      index fca08fc0d4..0000000000
      --- a/nuttx/lib/stdio/lib_fileno.c
      +++ /dev/null
      @@ -1,70 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fileno.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -#if CONFIG_NFILE_STREAMS > 0
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -int fileno(FAR FILE *stream)
      -{
      -  int ret = -1;
      -  if (stream)
      -    {
      -      ret = stream->fs_filedes;
      -    }
      -
      -  if (ret < 0)
      -    {
      -      set_errno(EBADF);
      -      return ERROR;
      -    }
      -
      -  return ret;
      -}
      -#endif /* CONFIG_NFILE_STREAMS */
      -
      diff --git a/nuttx/lib/stdio/lib_fopen.c b/nuttx/lib/stdio/lib_fopen.c
      deleted file mode 100644
      index 29ff4569c2..0000000000
      --- a/nuttx/lib/stdio/lib_fopen.c
      +++ /dev/null
      @@ -1,299 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fopen.c
      - *
      - *   Copyright (C) 2007-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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Types
      - ****************************************************************************/
      -
      -enum open_mode_e
      -{
      -  MODE_NONE = 0, /* No access mode determined */
      -  MODE_R,        /* "r" or "rb" open for reading */
      -  MODE_W,        /* "w" or "wb" open for writing, truncating or creating file */
      -  MODE_A,        /* "a" or "ab" open for writing, appending to file */
      -  MODE_RPLUS,    /* "r+", "rb+", or "r+b" open for update (reading and writing) */
      -  MODE_WPLUS,    /* "w+", "wb+", or "w+b"  open for update, truncating or creating file */
      -  MODE_APLUS     /* "a+", "ab+", or "a+b" open for update, appending to file */
      -};
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_mode2oflags
      - ****************************************************************************/
      -
      -static int lib_mode2oflags(FAR const char *mode)
      -{
      -  enum open_mode_e state;
      -  int oflags;
      -
      -  /* Verify that a mode string was provided.  No error is  */
      -
      -  if (!mode)
      -    {
      -      goto errout;
      -    }
      -
      -  /* Parse the mode string to determine the corresponding open flags */
      -
      -  state  = MODE_NONE;
      -  oflags = 0;
      -
      -  for (; *mode; mode++)
      -    {
      -      switch (*mode)
      -        {
      -          /* Open for read access ("r", "r[+]", "r[b]",  "r[b+]", or "r[+b]") */
      -
      -          case 'r' :
      -            if (state == MODE_NONE)
      -              {
      -                /* Open for read access */
      -
      -                oflags = O_RDOK;
      -                state  = MODE_R;
      -              }
      -            else
      -              {
      -                goto errout;
      -              }
      -            break;
      -
      -          /* Open for write access ("w", "w[+]", "w[b]",  "w[b+]", or "w[+b]") */
      -
      -          case 'w' :
      -            if (state == MODE_NONE)
      -              {
      -                /* Open for write access, truncating any existing file */
      -
      -                oflags = O_WROK|O_CREAT|O_TRUNC;
      -                state  = MODE_W;
      -              }
      -            else
      -              {
      -                goto errout;
      -              }
      -            break;
      -
      -          /* Open for write/append access ("a", "a[+]", "a[b]", "a[b+]", or "a[+b]") */
      -
      -          case 'a' :
      -            if (state == MODE_NONE)
      -              {
      -                /* Write to the end of the file */
      -
      -                oflags = O_WROK|O_CREAT|O_APPEND;
      -                state  = MODE_A;
      -              }
      -            else
      -              {
      -                goto errout;
      -              }
      -            break;
      -
      -          /* Open for update access ("[r]+", "[rb]+]", "[r]+[b]", "[w]+",
      -           * "[wb]+]", "[w]+[b]", "[a]+", "[ab]+]",  "[a]+[b]")
      -           */
      -
      -          case '+' :
      -            switch (state)
      -              {
      -                case MODE_R:
      -                  {
      -                    /* Retain any binary mode selection */
      -
      -                    oflags &= O_BINARY;
      -
      -                    /* Open for read/write access */
      -
      -                    oflags |= O_RDWR;
      -                    state   = MODE_RPLUS;
      -                 }
      -                 break;
      -
      -                case MODE_W:
      -                  {
      -                    /* Retain any binary mode selection */
      -
      -                    oflags &= O_BINARY;
      -
      -                    /* Open for write read/access, truncating any existing file */
      -
      -                    oflags |= O_RDWR|O_CREAT|O_TRUNC;
      -                    state   = MODE_WPLUS;
      -                  }
      -                  break;
      -
      -                case MODE_A:
      -                  {
      -                    /* Retain any binary mode selection */
      -
      -                    oflags &= O_BINARY;
      -
      -                    /* Read from the beginning of the file; write to the end */
      -
      -                    oflags |= O_RDWR|O_CREAT|O_APPEND;
      -                    state   = MODE_APLUS;
      -                  }
      -                  break;
      -
      -                default:
      -                  goto errout;
      -                  break;
      -              }
      -            break;
      -
      -          /* Open for binary access ("[r]b", "[r]b[+]", "[r+]b", "[w]b",
      -           * "[w]b[+]", "[w+]b", "[a]b", "[a]b[+]",  "[a+]b")
      -           */
      -
      -          case 'b' :
      -            if (state != MODE_NONE)
      -              {
      -                /* The file is opened in binary mode */
      -
      -                oflags |= O_BINARY;
      -              }
      -            else
      -              {
      -                goto errout;
      -              }
      -            break;
      -
      -          /* Unrecognized or unsupported mode */
      -
      -          default:
      -            goto errout;
      -            break;
      -        }
      -    }
      -
      -  return oflags;
      -
      -/* Both fopen and fdopen should fail with errno == EINVAL if the mode
      - * string is invalid.
      - */
      -
      -errout:
      -  set_errno(EINVAL);
      -  return ERROR;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fdopen
      - ****************************************************************************/
      -
      -FAR FILE *fdopen(int fd, FAR const char *mode)
      -{
      -  FAR FILE *ret = NULL;
      -  int oflags;
      -
      -  /* Map the open mode string to open flags */
      -
      -  oflags = lib_mode2oflags(mode);
      -  if (oflags >= 0)
      -    {
      -      ret = fs_fdopen(fd, oflags, NULL);
      -    }
      -
      -  return ret;
      -}
      -
      -/****************************************************************************
      - * Name: fopen
      - ****************************************************************************/
      -
      -FAR FILE *fopen(FAR const char *path, FAR const char *mode)
      -{
      -  FAR FILE *ret = NULL;
      -  int oflags;
      -  int fd;
      -
      -  /* Map the open mode string to open flags */
      -
      -  oflags = lib_mode2oflags(mode);
      -  if (oflags < 0)
      -    {
      -      return NULL;
      -    }
      -
      -  /* Open the file */
      -
      -  fd = open(path, oflags, 0666);
      -
      -  /* If the open was successful, then fdopen() the fil using the file
      -   * desciptor returned by open.  If open failed, then just return the
      -   * NULL stream -- open() has already set the errno.
      -   */
      -
      -  if (fd >= 0)
      -    {
      -      ret = fs_fdopen(fd, oflags, NULL);
      -      if (!ret)
      -        {
      -          /* Don't forget to close the file descriptor if any other
      -           * failures are reported by fdopen().
      -           */
      -
      -          (void)close(fd);
      -        }
      -    }
      -  return ret;
      -}
      diff --git a/nuttx/lib/stdio/lib_fprintf.c b/nuttx/lib/stdio/lib_fprintf.c
      deleted file mode 100644
      index a803de4bd0..0000000000
      --- a/nuttx/lib/stdio/lib_fprintf.c
      +++ /dev/null
      @@ -1,93 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fprintf.c
      - *
      - *   Copyright (C) 2007, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fprintf
      - ****************************************************************************/
      -
      -int fprintf(FAR FILE *stream, FAR const char *fmt, ...)
      -{
      -  va_list ap;
      -  int     n;
      -
      -  /* vfprintf into the stream */
      -
      -  va_start(ap, fmt);
      -  n = vfprintf(stream, fmt, ap);
      -  va_end(ap);
      -  return n;
      -}
      diff --git a/nuttx/lib/stdio/lib_fputc.c b/nuttx/lib/stdio/lib_fputc.c
      deleted file mode 100644
      index 121161f102..0000000000
      --- a/nuttx/lib/stdio/lib_fputc.c
      +++ /dev/null
      @@ -1,113 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fputc.c
      - *
      - *   Copyright (C) 2007, 2008, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fputc
      - ****************************************************************************/
      -
      -int fputc(int c, FAR FILE *stream)
      -{
      -  unsigned char buf = (unsigned char)c;
      -  int ret;
      -
      -  ret = lib_fwrite(&buf, 1, stream);
      -  if (ret > 0)
      -    {
      -      /* Flush the buffer if a newline is output */
      -
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -      if (c == '\n')
      -        {
      -          ret = lib_fflush(stream, true);
      -          if (ret < 0)
      -            {
      -              return EOF;
      -            }
      -        }
      -#endif
      -      return c;
      -    }
      -  else
      -    {
      -      return EOF;
      -    }
      -}
      diff --git a/nuttx/lib/stdio/lib_fputs.c b/nuttx/lib/stdio/lib_fputs.c
      deleted file mode 100644
      index 2d6217d4aa..0000000000
      --- a/nuttx/lib/stdio/lib_fputs.c
      +++ /dev/null
      @@ -1,220 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fputs.c
      - *
      - *   Copyright (C) 2007, 2008, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fputs
      - *
      - * Description:
      - *   fputs() writes the string s to stream, without its trailing '\0'.
      - *
      - ****************************************************************************/
      -
      -#if defined(CONFIG_ARCH_ROMGETC)
      -int fputs(FAR const char *s, FAR FILE *stream)
      -{
      -  int nput;
      -  int ret;
      -  char ch;
      -
      -  /* Make sure that a string was provided. */
      -
      -#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */
      -  if (!s)
      -    {
      -      set_errno(EINVAL);
      -      return EOF;
      -    }
      -#endif
      -
      -  /* Write the string.  Loop until the null terminator is encountered */
      -
      -  for (nput = 0, ch = up_romgetc(s); ch; nput++, s++, ch = up_romgetc(s))
      -    {
      -      /* Write the next character to the stream buffer */
      -
      -      ret = lib_fwrite(&ch, 1, stream);
      -      if (ret <= 0)
      -        {
      -          return EOF;
      -        }
      -
      -      /* Flush the buffer if a newline was written to the buffer */
      -
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -      if (ch == '\n')
      -        {
      -          ret = lib_fflush(stream, true);
      -          if (ret < 0)
      -            {
      -              return EOF;
      -            }
      -        }
      -#endif
      -    }
      -
      -  return nput;
      -}
      -
      -#elif defined(CONFIG_STDIO_LINEBUFFER)
      -int fputs(FAR const char *s, FAR FILE *stream)
      -{
      -  int nput;
      -  int ret;
      -
      -  /* Make sure that a string was provided. */
      -
      -#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */
      -  if (!s)
      -    {
      -      set_errno(EINVAL);
      -      return EOF;
      -    }
      -#endif
      -
      -  /* Write the string.  Loop until the null terminator is encountered */
      -
      -  for (nput = 0; *s; nput++, s++)
      -    {
      -      /* Write the next character to the stream buffer */
      -
      -      ret = lib_fwrite(s, 1, stream);
      -      if (ret <= 0)
      -        {
      -          return EOF;
      -        }
      -
      -      /* Flush the buffer if a newline was written to the buffer */
      -
      -      if (*s == '\n')
      -        {
      -          ret = lib_fflush(stream, true);
      -          if (ret < 0)
      -            {
      -              return EOF;
      -            }
      -        }
      -    }
      -
      -  return nput;
      -}
      -
      -#else
      -int fputs(FAR const char *s, FAR FILE *stream)
      -{
      -  int ntowrite;
      -  int nput;
      -
      -  /* Make sure that a string was provided. */
      -
      -#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */
      -  if (!s)
      -    {
      -      set_errno(EINVAL);
      -      return EOF;
      -    }
      -#endif
      -
      -  /* Get the length of the string. */
      -
      -  ntowrite = strlen(s);
      -  if (ntowrite == 0)
      -    {
      -      return 0;
      -    }
      -
      -  /* Write the string */
      -
      -  nput = lib_fwrite(s, ntowrite, stream);
      -  if (nput < 0)
      -    {
      -      return EOF;
      -    }
      -  return nput;
      -}
      -#endif
      diff --git a/nuttx/lib/stdio/lib_fread.c b/nuttx/lib/stdio/lib_fread.c
      deleted file mode 100644
      index 4a4b29256d..0000000000
      --- a/nuttx/lib/stdio/lib_fread.c
      +++ /dev/null
      @@ -1,101 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fread.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fread
      - ****************************************************************************/
      -
      -size_t fread(FAR void *ptr, size_t size, size_t n_items, FAR FILE *stream)
      -{
      -  size_t  full_size = n_items * (size_t)size;
      -  ssize_t bytes_read;
      -  size_t  items_read = 0;
      -
      -  /* Write the data into the stream buffer */
      -
      -  bytes_read = lib_fread(ptr, full_size, stream);
      -  if (bytes_read > 0)
      -    {
      -      /* Return the number of full items read */
      -
      -      items_read = bytes_read / size;
      -    }
      -  return items_read;
      -}
      -
      -
      diff --git a/nuttx/lib/stdio/lib_fseek.c b/nuttx/lib/stdio/lib_fseek.c
      deleted file mode 100644
      index 7380f83b3b..0000000000
      --- a/nuttx/lib/stdio/lib_fseek.c
      +++ /dev/null
      @@ -1,138 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fseek.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fseek
      - *
      - * Description:
      - *   The fseek() function sets the file position indicator for the stream
      - *   pointed to by stream. The new position, measured in bytes, is obtained
      - *   by adding offset bytes to the position specified by whence. If whence is
      - *   set to SEEK_SET, SEEK_CUR, or SEEK_END, the offset is relative to the
      - *   start of the file, the current position indicator, or end-of-file,
      - *   respectively. A successful call to the fseek() function clears the
      - *   end-of-file indicator for the stream and undoes any effects of the ungetc(3)
      - *   function on the same stream.
      - *
      - * Returned Value:
      - *   Zero on succes; -1 on failure with errno set appropriately. 
      - *
      - ****************************************************************************/
      -
      -int fseek(FAR FILE *stream, long int offset, int whence)
      -{
      - #if CONFIG_STDIO_BUFFER_SIZE > 0
      -  /* Flush any valid read/write data in the buffer (also verifies stream) */
      -
      -  if (lib_rdflush(stream) < 0 || lib_wrflush(stream) < 0)
      -    {
      -      return ERROR;
      -    }
      -#else
      -  /* Verify that we were provided with a stream */
      -
      -  if (!stream)
      -    {
      -      set_errno(EBADF);
      -      return ERROR;
      -    }
      -#endif
      -
      -  /* On success or failure, discard any characters saved by ungetc() */
      -
      -#if CONFIG_NUNGET_CHARS > 0
      -  stream->fs_nungotten = 0;
      -#endif
      -
      -  /* Perform the fseek on the underlying file descriptor */
      -
      -  return lseek(stream->fs_filedes, offset, whence) == (off_t)-1 ? ERROR : OK;
      -}
      -
      -
      diff --git a/nuttx/lib/stdio/lib_fsetpos.c b/nuttx/lib/stdio/lib_fsetpos.c
      deleted file mode 100644
      index 13d556521b..0000000000
      --- a/nuttx/lib/stdio/lib_fsetpos.c
      +++ /dev/null
      @@ -1,116 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fsetpos.c
      - *
      - *   Copyright (C) 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fsetpos
      - *
      - * Description:
      - *   fsetpos() function is an alternate interfaces equivalent to fseek()
      - *   (with whence set to  SEEK_SET).  It sets the current value of the file
      - *   offset to value in the location referenced by pos.  On some non-UNIX
      - *   systems an fpos_t object may be a complex object and fsetpos may be the
      - *   only way to portably reposition a stream.
      - *
      - * Returned Value:
      - *   Zero on succes; -1 on failure with errno set appropriately. 
      - *
      - ****************************************************************************/
      -
      -int fsetpos(FAR FILE *stream, FAR fpos_t *pos)
      -{
      -#if CONFIG_DEBUG
      -  if (!stream || !pos)
      -    {
      -      set_errno(EINVAL);
      -      return ERROR;
      -    }
      -#endif
      -
      -  return fseek(stream, (FAR off_t)*pos, SEEK_SET);
      -}
      diff --git a/nuttx/lib/stdio/lib_ftell.c b/nuttx/lib/stdio/lib_ftell.c
      deleted file mode 100644
      index 9476481529..0000000000
      --- a/nuttx/lib/stdio/lib_ftell.c
      +++ /dev/null
      @@ -1,129 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_ftell.c
      - *
      - *   Copyright (C) 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: ftell
      - *
      - * Description:
      - *   ftell() returns the current value of the file position indicator for the
      - *   stream pointed to by stream.
      - *
      - * Returned Value:
      - *   Zero on succes; -1 on failure with errno set appropriately. 
      - *
      - ****************************************************************************/
      -
      -long ftell(FAR FILE *stream)
      -{
      -  off_t position;
      -
      -  /* Verify that we were provided with a stream */
      -
      -  if (!stream)
      -    {
      -      set_errno(EBADF);
      -      return ERROR;
      -    }
      -
      -  /* Perform the lseek to the current position.  This will not move the
      -   * file pointer, but will return its current setting
      -   */
      -
      -  position = lseek(stream->fs_filedes, 0, SEEK_CUR);
      -  if (position != (off_t)-1)
      -    {
      -      return (long)position;
      -    }
      -  else
      -    {
      -      return ERROR;
      -    }
      -}
      -
      -
      diff --git a/nuttx/lib/stdio/lib_fwrite.c b/nuttx/lib/stdio/lib_fwrite.c
      deleted file mode 100644
      index 60e0017463..0000000000
      --- a/nuttx/lib/stdio/lib_fwrite.c
      +++ /dev/null
      @@ -1,99 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_fwrite.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: fwrite
      - ****************************************************************************/
      -
      -size_t fwrite(FAR const void *ptr, size_t size, size_t n_items, FAR FILE *stream)
      -{
      -  size_t  full_size = n_items * (size_t)size;
      -  ssize_t bytes_written;
      -  size_t  items_written = 0;
      -
      -  /* Write the data into the stream buffer */
      -
      -  bytes_written = lib_fwrite(ptr, full_size, stream);
      -  if (bytes_written > 0)
      -    {
      -      /* Return the number of full items written */
      -
      -      items_written = bytes_written / size;
      -    }
      -  return items_written;
      -}
      diff --git a/nuttx/lib/stdio/lib_gets.c b/nuttx/lib/stdio/lib_gets.c
      deleted file mode 100644
      index 95a6b36ebf..0000000000
      --- a/nuttx/lib/stdio/lib_gets.c
      +++ /dev/null
      @@ -1,120 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_gets.c
      - *
      - *   Copyright (C) 2007-2008, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: gets
      - *
      - * Description:
      - *   gets() reads a line from stdin into the buffer pointed to by s until
      - *   either a terminating newline or EOF, which it replaces with '\0'.  No
      - *   check for buffer overrun is performed
      - *
      - *   This API should not be used because it is inherently unsafe.  Consider
      - *   using fgets which is safer and slightly more efficient.
      - *
      - **************************************************************************/
      -
      -FAR char *gets(FAR char *s)
      -{
      -  /* gets is ALMOST the same as fgets using stdin and no length limit
      -   * (hence, the unsafeness of gets).  So let fgets do most of the work.
      -   */
      -
      -  FAR char *ret = fgets(s, INT_MAX, stdin);
      -  if (ret)
      -    {
      -      /* Another subtle difference from fgets is that gets replaces
      -       * end-of-line markers with null terminators. We will do that as
      -       * a second step (with some loss in performance).
      -       */
      -
      -      int len = strlen(ret);
      -      if (len > 0 && ret[len-1] == '\n')
      -        {
      -           ret[len-1] = '\0';
      -        }
      -    }
      -
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_libdtoa.c b/nuttx/lib/stdio/lib_libdtoa.c
      deleted file mode 100644
      index 667c49c535..0000000000
      --- a/nuttx/lib/stdio/lib_libdtoa.c
      +++ /dev/null
      @@ -1,304 +0,0 @@
      -/****************************************************************************
      - * lib/unistd/lib_libdtoa.c
      - *
      - * This file was ported to NuttX by Yolande Cates.
      - *
      - * Copyright (c) 1990, 1993
      - *      The Regents of the University of California.  All rights reserved.
      - *
      - * This code is derived from software contributed to Berkeley by
      - * Chris Torek.
      - *
      - * 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. All advertising materials mentioning features or use of this software
      - *    must display the following acknowledgement:
      - *      This product includes software developed by the University of
      - *      California, Berkeley and its contributors.
      - * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -#define MAX_PREC 16
      -
      -#ifndef MIN
      -#  define MIN(a,b) (a < b ? a : b)
      -#endif
      -
      -#ifndef MAX
      -#  define MAX(a,b) (a > b ? a : b)
      -#endif
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: zeroes
      - *
      - * Description:
      - *   Print the specified number of zeres
      - *
      - ****************************************************************************/
      -
      -static void zeroes(FAR struct lib_outstream_s *obj, int nzeroes)
      -{
      -  int i;
      -
      -  for (i = nzeroes; i > 0; i--)
      -    {
      -      obj->put(obj, '0');
      -    }
      -}
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_dtoa
      - *
      - * Description:
      - *   This is part of lib_vsprintf().  It handles the floating point formats.
      - *   This version supports only the %f (with precision).  If no precision
      - *   was provided in the format, this will use precision == 0 which is
      - *   probably not what you want.
      - *
      - * Input Parameters:
      - *   obj   - The output stream object
      - *   fmt   - The format character.  Not used 'f' is always assumed
      - *   prec  - The number of digits to the right of the decimal point. If no
      - *           precision is provided in the format, this will be zero.  And,
      - *           unfortunately in this case, it will be treated literally as
      - *           a precision of zero.
      - *   flags - Only ALTFORM and SHOWPLUS flags are supported.  ALTFORM only
      - *           applies if prec == 0 which is not supported anyway.
      - *   value - The floating point value to convert.
      - *
      - ****************************************************************************/
      -
      -static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec,
      -                     uint8_t flags, double value)
      -{
      -  FAR char *digits;     /* String returned by __dtoa */
      -  FAR char *digalloc;   /* Copy of digits to be freed after usage */
      -  FAR char *rve;        /* Points to the end of the return value */
      -  int  expt;            /* Integer value of exponent */
      -  int  numlen;          /* Actual number of digits returned by cvt */
      -  int  nchars;          /* Number of characters to print */
      -  int  dsgn;            /* Unused sign indicator */
      -  int  i;
      -
      -  /* Non-zero... positive or negative */
      -
      -  if (value < 0)
      -    {
      -      value = -value;
      -      SET_NEGATE(flags);
      -    }
      -
      -  /* Perform the conversion */
      -
      -  digits   = __dtoa(value, 3, prec, &expt, &dsgn, &rve);
      -  digalloc = digits;
      -  numlen   = rve - digits;
      -
      -  if (IS_NEGATE(flags))
      -    {
      -      obj->put(obj, '-');
      -    }
      -  else if (IS_SHOWPLUS(flags))
      -    {
      -      obj->put(obj, '+');
      -    }
      -
      -  /* Special case exact zero or the case where the number is smaller than
      -   * the print precision.
      -   */
      -
      -  if (value == 0 || expt < -prec)
      -    {
      -      /* kludge for __dtoa irregularity */
      -
      -      obj->put(obj, '0');
      -
      -      /* A decimal point is printed only in the alternate form or if a 
      -       * particular precision is requested.
      -       */
      -
      -      if (prec > 0 || IS_ALTFORM(flags))
      -        {
      -          obj->put(obj, '.');
      -
      -          /* Always print at least one digit to the right of the decimal point. */
      -
      -          prec = MAX(1, prec);
      -        }
      -    }
      -
      -  /* A non-zero value will be printed */
      -
      -  else
      -    {
      -
      -      /* Handle the case where the value is less than 1.0 (in magnitude) and
      -       * will need a leading zero.
      -       */
      -
      -      if (expt <= 0)
      -        {
      -          /* Print a single zero to the left of the decimal point */
      -
      -          obj->put(obj, '0');
      -
      -          /* Print the decimal point */
      -
      -          obj->put(obj, '.');
      -
      -          /* Print any leading zeros to the right of the decimal point */
      -
      -          if (expt < 0)
      -            {
      -              nchars = MIN(-expt, prec);
      -              zeroes(obj, nchars);
      -              prec -= nchars;
      -            }
      -        }
      -
      -      /* Handle the general case where the value is greater than 1.0 (in
      -       * magnitude).
      -       */
      -
      -      else
      -        {
      -          /* Print the integer part to the left of the decimal point */
      -
      -          for (i = expt; i > 0; i--)
      -            {
      -              if (*digits != '\0')
      -                { 
      -                  obj->put(obj, *digits);
      -                  digits++;
      -                }
      -              else
      -                {
      -                  obj->put(obj, '0');
      -                }
      -            }
      -
      -          /* Get the length of the fractional part */
      -
      -          numlen -= expt;
      -
      -          /* If there is no fractional part, then a decimal point is printed
      -           * only in the alternate form or if a particular precision is
      -           * requested.
      -           */
      -
      -          if (numlen > 0 || prec > 0 || IS_ALTFORM(flags))
      -            {
      -              /* Print the decimal point */
      -
      -              obj->put(obj, '.');
      -
      -              /* Always print at least one digit to the right of the decimal
      -               * point.
      -               */
      -
      -              prec = MAX(1, prec);
      -            }
      -        }
      -
      -      /* If a precision was specified, then limit the number digits to the
      -       * right of the decimal point.
      -       */
      -
      -      if (prec > 0)
      -        {
      -          nchars = MIN(numlen, prec);
      -        }
      -      else
      -        {
      -          nchars = numlen;
      -        }
      -
      -      /* Print the fractional part to the right of the decimal point */
      -
      -      for (i = nchars; i > 0; i--)
      -        {
      -          obj->put(obj, *digits);
      -          digits++;
      -        }
      -
      -      /* Decremnt to get the number of trailing zeroes to print */
      -
      -      prec -= nchars;
      -    }
      -
      -  /* Finally, print any trailing zeroes */
      -
      -  zeroes(obj, prec);
      -
      -  /* Is this memory supposed to be freed or not? */
      -
      -#if 0
      -  if (digalloc)
      -    {
      -      free(digalloc);
      -    }
      -#endif
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      diff --git a/nuttx/lib/stdio/lib_libfflush.c b/nuttx/lib/stdio/lib_libfflush.c
      deleted file mode 100644
      index 2a4fe29326..0000000000
      --- a/nuttx/lib/stdio/lib_libfflush.c
      +++ /dev/null
      @@ -1,202 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_libfflush.c
      - *
      - *   Copyright (C) 2007-2008, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_fflush
      - *
      - * Description:
      - *  The function lib_fflush() forces a write of all user-space buffered data for
      - *  the given output or update stream via the stream's underlying write
      - *  function.  The open status of the stream is unaffected.
      - *
      - * Parmeters:
      - *  stream - the stream to flush
      - *  bforce - flush must be complete.
      - *
      - * Return:
      - *  A negated errno value on failure, otherwise the number of bytes remaining
      - *  in the buffer.
      - *
      - ****************************************************************************/
      -
      -ssize_t lib_fflush(FAR FILE *stream, bool bforce)
      -{
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -  FAR const unsigned char *src;
      -  ssize_t bytes_written;
      -  ssize_t nbuffer;
      -
      -  /* Return EBADF if the file is not opened for writing */
      -
      -  if (stream->fs_filedes < 0 || (stream->fs_oflags & O_WROK) == 0)
      -    {
      -      return -EBADF;
      -    }
      -
      -  /* Make sure that we have exclusive access to the stream */
      -
      -  lib_take_semaphore(stream);
      -
      -  /* Make sure that the buffer holds valid data */
      -
      -  if (stream->fs_bufpos  != stream->fs_bufstart)
      -    {
      -       /* Make sure that the buffer holds buffered write data.  We do not
      -        * support concurrent read/write buffer usage.
      -        */
      -
      -       if (stream->fs_bufread != stream->fs_bufstart)
      -        {
      -          /* The buffer holds read data... just return zero meaning "no bytes
      -           * remaining in the buffer."
      -           */
      -
      -          lib_give_semaphore(stream);
      -          return 0;
      -        }
      -
      -      /* How many bytes of write data are used in the buffer now */
      -
      -      nbuffer = stream->fs_bufpos - stream->fs_bufstart;
      -
      -      /* Try to write that amount */
      -
      -      src = stream->fs_bufstart;
      -      do
      -        {
      -          /* Perform the write */
      -
      -          bytes_written = write(stream->fs_filedes, src, nbuffer);
      -          if (bytes_written < 0)
      -            {
      -              /* Write failed.  The cause of the failure is in 'errno'.
      -               * returned the negated errno value.
      -               */
      -
      -              lib_give_semaphore(stream);
      -              return -get_errno();
      -            }
      -
      -          /* Handle partial writes.  fflush() must either return with
      -           * an error condition or with the data successfully flushed
      -           * from the buffer.
      -           */
      -
      -          src     += bytes_written;
      -          nbuffer -= bytes_written;
      -        }
      -      while (bforce && nbuffer > 0);
      -
      -      /* Reset the buffer position to the beginning of the buffer */
      -
      -      stream->fs_bufpos = stream->fs_bufstart;
      -
      -      /* For the case of an incomplete write, nbuffer will be non-zero
      -       * It will hold the number of bytes that were not written.
      -       * Move the data down in the buffer to handle this (rare) case
      -       */
      -
      -      while (nbuffer)
      -       {
      -         *stream->fs_bufpos++ = *src++;
      -         --nbuffer;
      -       }
      -    }
      -
      -  /* Restore normal access to the stream and return the number of bytes
      -   * remaining in the buffer.
      -   */
      -
      -  lib_give_semaphore(stream);
      -  return stream->fs_bufpos - stream->fs_bufstart;
      -#else
      -  /* Return no bytes remaining in the buffer */
      -
      -  return 0;
      -#endif
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_libflushall.c b/nuttx/lib/stdio/lib_libflushall.c
      deleted file mode 100644
      index 9d0a89e9c1..0000000000
      --- a/nuttx/lib/stdio/lib_libflushall.c
      +++ /dev/null
      @@ -1,137 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_libflushall.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_flushall
      - *
      - * Description:
      - *   Called either (1) by the OS when a task exits, or (2) from fflush()
      - *   when a NULL stream argument is provided.
      - *
      - ****************************************************************************/
      -
      -int lib_flushall(FAR struct streamlist *list)
      -{
      -  int lasterrno = OK;
      -  int ret;
      -
      -  /* Make sure that there are streams associated with this thread */
      -
      -  if (list)
      -    {
      -       int i;
      -
      -       /* Process each stream in the thread's stream list */
      -
      -       stream_semtake(list);
      -       for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
      -         {
      -           FILE *stream = &list->sl_streams[i];
      -
      -           /* If the stream is open (i.e., assigned a non-negative file
      -            * descriptor) and opened for writing, then flush all of the pending
      -            * write data in the stream.
      -            */
      -
      -           if (stream->fs_filedes >= 0 && (stream->fs_oflags & O_WROK) != 0)
      -             {
      -               /* Flush the writable FILE */
      -
      -               ret = lib_fflush(stream, true);
      -               if (ret < 0)
      -                 {
      -                   /* An error occurred during the flush AND/OR we were unable
      -                    * to flush all of the buffered write data.  Remember the
      -                    * last errcode.
      -                    */
      -
      -                   lasterrno = ret;
      -                 }
      -             }
      -         }
      -
      -       stream_semgive(list);
      -    }
      -
      -  /* If any flush failed, return the errorcode of the last failed flush */
      -
      -  return lasterrno;
      -}
      diff --git a/nuttx/lib/stdio/lib_libfread.c b/nuttx/lib/stdio/lib_libfread.c
      deleted file mode 100644
      index 5585acbaea..0000000000
      --- a/nuttx/lib/stdio/lib_libfread.c
      +++ /dev/null
      @@ -1,315 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_libfread.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include   /* for CONFIG_STDIO_BUFFER_SIZE */
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_fread
      - ****************************************************************************/
      -
      -ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream)
      -{
      -  unsigned char *dest  = (unsigned char*)ptr;
      -  ssize_t        bytes_read;
      -  int            ret;
      -
      -  /* Make sure that reading from this stream is allowed */
      -
      -  if (!stream || (stream->fs_oflags & O_RDOK) == 0)
      -    {
      -      set_errno(EBADF);
      -      bytes_read = -1;
      -    }
      -  else
      -    {
      -      /* The stream must be stable until we complete the read */
      -
      -      lib_take_semaphore(stream);
      -
      -#if CONFIG_NUNGET_CHARS > 0
      -      /* First, re-read any previously ungotten characters */
      -
      -      while ((stream->fs_nungotten > 0) && (count > 0))
      -        {
      -          /* Decrement the count of ungotten bytes to get an index */
      -
      -          stream->fs_nungotten--;
      -
      -          /* Return the last ungotten byte */
      -
      -          *dest++ = stream->fs_ungotten[stream->fs_nungotten];
      -
      -          /* That's one less byte that we have to read */
      -
      -          count--;
      -        }
      -#endif
      -
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -      /* If the buffer is currently being used for write access, then
      -       * flush all of the buffered write data.  We do not support concurrent
      -       * buffered read/write access.
      -       */
      -
      -      ret = lib_wrflush(stream);
      -      if (ret < 0)
      -        {
      -          lib_give_semaphore(stream);
      -          return ret;
      -        }
      -
      -      /* Now get any other needed chars from the buffer or the file. */
      -
      -      while (count > 0)
      -        {
      -          /* Is there readable data in the buffer? */
      -
      -          while ((count > 0) && (stream->fs_bufpos < stream->fs_bufread))
      -            {
      -              /* Yes, copy a byte into the user buffer */
      -
      -              *dest++ = *stream->fs_bufpos++;
      -              count--;
      -            }
      -
      -          /* The buffer is empty OR we have already supplied the number of
      -           * bytes requested in the read.  Check if we need to read
      -           * more from the file.
      -           */
      -
      -          if (count > 0)
      -            {
      -              size_t buffer_available;
      -
      -              /* We need to read more data into the buffer from the file */
      -
      -              /* Mark the buffer empty */
      -
      -              stream->fs_bufpos = stream->fs_bufread = stream->fs_bufstart;
      -
      -              /* How much space is available in the buffer? */
      -
      -              buffer_available = stream->fs_bufend - stream->fs_bufread;
      -
      -              /* Will the number of bytes that we need to read fit into
      -               * the buffer space that is available? If the read size is
      -               * larger than the buffer, then read some of the data
      -               * directly into the user's buffer.
      -               */
      -
      -              if (count > buffer_available)
      -                {
      -                  bytes_read = read(stream->fs_filedes, dest, count);
      -                  if (bytes_read < 0)
      -                    {
      -                      /* An error occurred on the read.  The error code is
      -                       * in the 'errno' variable.
      -                       */
      -
      -                      goto errout_with_errno;
      -                    }
      -                  else if (bytes_read == 0)
      -                    {
      -                      /* We are at the end of the file.  But we may already
      -                       * have buffered data.  In that case, we will report
      -                       * the EOF indication later.
      -                       */
      -
      -                      goto shortread;
      -                    }
      -                  else
      -                    {
      -                      /* Some bytes were read. Adjust the dest pointer */
      -
      -                      dest  += bytes_read;
      -
      -                      /* Were all of the requested bytes read? */
      -
      -                      if (bytes_read < count)
      -                        {
      -                          /* No.  We must be at the end of file. */
      -
      -                          goto shortread;
      -                        }
      -                      else
      -                        {
      -                          /* Yes.  We are done. */
      -
      -                          count = 0;
      -                        }
      -                    }
      -                }
      -              else
      -                {
      -                  /* The number of bytes required to satisfy the read
      -                   * is less than or equal to the size of the buffer
      -                   * space that we have left. Read as much as we can
      -                   * into the buffer.
      -                   */
      -
      -                  bytes_read = read(stream->fs_filedes, stream->fs_bufread, buffer_available);
      -                  if (bytes_read < 0)
      -                    {
      -                      /* An error occurred on the read.  The error code is
      -                       * in the 'errno' variable.
      -                       */
      -
      -                      goto errout_with_errno;
      -                    }
      -                  else if (bytes_read == 0)
      -                    {
      -                      /* We are at the end of the file.  But we may already
      -                       * have buffered data.  In that case, we will report
      -                       * the EOF indication later.
      -                       */
      -
      -                      goto shortread;
      -                    }
      -                  else
      -                    {
      -                      /* Some bytes were read */
      -
      -                      stream->fs_bufread += bytes_read;
      -                    }
      -                }
      -            }
      -        }
      -#else
      -      /* Now get any other needed chars from the file. */
      -
      -      while (count > 0)
      -        {
      -          bytes_read = read(stream->fs_filedes, dest, count);
      -          if (bytes_read < 0)
      -            {
      -              /* An error occurred on the read.  The error code is
      -               * in the 'errno' variable.
      -               */
      -
      -              goto errout_with_errno;
      -            }
      -          else if (bytes_read == 0)
      -            {
      -              /* We are at the end of the file.  But we may already
      -               * have buffered data.  In that case, we will report
      -               * the EOF indication later.
      -               */
      -
      -              break;
      -            }
      -          else
      -            {
      -              dest  += bytes_read;
      -              count -= bytes_read;
      -            }
      -        }
      -#endif
      -      /* Here after a successful (but perhaps short) read */
      -
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -    shortread:
      -#endif
      -      bytes_read = dest - (unsigned char*)ptr;
      -
      -      /* Set or clear the EOF indicator.  If we get here because of a
      -       * short read and the total number of* bytes read is zero, then
      -       * we must be at the end-of-file.
      -       */
      -
      -      if (bytes_read > 0)
      -        {
      -          stream->fs_flags &= ~__FS_FLAG_EOF;
      -        }
      -      else
      -        {
      -          stream->fs_flags |= __FS_FLAG_EOF;
      -        }
      -    }
      -
      -  lib_give_semaphore(stream);
      -  return bytes_read;  
      -
      -/* Error exits */
      -
      -errout_with_errno:
      -  lib_give_semaphore(stream);
      -  return -get_errno();  
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_libfwrite.c b/nuttx/lib/stdio/lib_libfwrite.c
      deleted file mode 100644
      index e71866b498..0000000000
      --- a/nuttx/lib/stdio/lib_libfwrite.c
      +++ /dev/null
      @@ -1,179 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_libfwrite.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include   /* for CONFIG_STDIO_BUFFER_SIZE */
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_fwrite
      - ****************************************************************************/
      -
      -ssize_t lib_fwrite(FAR const void *ptr, size_t count, FAR FILE *stream)
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -{
      -  FAR const unsigned char *start = ptr;
      -  FAR const unsigned char *src   = ptr;
      -  ssize_t ret = ERROR;
      -  unsigned char *dest;
      -
      -  /* Make sure that writing to this stream is allowed */
      -
      -  if (!stream || (stream->fs_oflags & O_WROK) == 0)
      -    {
      -      set_errno(EBADF);
      -      goto errout;
      -    }
      -
      -  /* Get exclusive access to the stream */
      -
      -  lib_take_semaphore(stream);
      -
      -  /* If the buffer is currently being used for read access, then
      -   * discard all of the read-ahead data.  We do not support concurrent
      -   * buffered read/write access.
      -   */
      -
      -  if (lib_rdflush(stream) < 0)
      -    {
      -      goto errout_with_semaphore;
      -    }
      -
      -  /* Loop until all of the bytes have been buffered */
      -
      -  while (count > 0)
      -    {
      -      /* Determine the number of bytes left in the buffer */
      -
      -      size_t gulp_size = stream->fs_bufend - stream->fs_bufpos;
      -
      -      /* Will the user data fit into the amount of buffer space
      -       * that we have left?
      -       */
      -
      -      if (gulp_size > count)
      -        {
      -          /* Yes, clip the gulp to the size of the user data */
      -
      -          gulp_size = count;
      -        }
      -
      -      /* Adjust the number of bytes remaining to be transferred
      -       * on the next pass through the loop (might be zero).
      -       */
      -
      -      count -= gulp_size;
      -
      -      /* Transfer the data into the buffer */
      -
      -      for (dest = stream->fs_bufpos; gulp_size > 0; gulp_size--)
      -        {
      -          *dest++ = *src++;
      -        }
      -      stream->fs_bufpos = dest;
      -
      -      /* Is the buffer full? */
      -
      -      if (dest >= stream->fs_bufend)
      -        {
      -          /* Flush the buffered data to the IO stream */
      -
      -          int bytes_buffered = lib_fflush(stream, false);
      -          if (bytes_buffered < 0)
      -            {
      -              goto errout_with_semaphore;
      -            }
      -        }
      -    }
      -
      -  /* Return the number of bytes written */
      -
      -  ret = src - start;
      -
      -errout_with_semaphore:
      -  lib_give_semaphore(stream);
      -
      -errout:
      -  return ret;
      -}
      -#else
      -{
      -  return write(stream->fs_filedes, ptr, count);
      -}
      -#endif /* CONFIG_STDIO_BUFFER_SIZE */
      -
      diff --git a/nuttx/lib/stdio/lib_libnoflush.c b/nuttx/lib/stdio/lib_libnoflush.c
      deleted file mode 100644
      index e3b8911534..0000000000
      --- a/nuttx/lib/stdio/lib_libnoflush.c
      +++ /dev/null
      @@ -1,103 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_libnoflush.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_noflush
      - *
      - * Description:
      - *  lib_noflush() provides a common, dummy flush method for output streams
      - *  that are not flushable.  Only used if CONFIG_STDIO_LINEBUFFER is selected.
      - *
      - * Return:
      - *  Always returns OK
      - *
      - ****************************************************************************/
      -
      -int lib_noflush(FAR struct lib_outstream_s *this)
      -{
      -  return OK;
      -}
      -
      -#endif /* CONFIG_STDIO_LINEBUFFER */
      -
      diff --git a/nuttx/lib/stdio/lib_libsprintf.c b/nuttx/lib/stdio/lib_libsprintf.c
      deleted file mode 100644
      index 2474a6f01d..0000000000
      --- a/nuttx/lib/stdio/lib_libsprintf.c
      +++ /dev/null
      @@ -1,90 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_libsprintf.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_sprintf
      - ****************************************************************************/
      -
      -int lib_sprintf(FAR struct lib_outstream_s *obj, const char *fmt, ...)
      -{
      -  va_list ap;
      -  int     n;
      -
      -  /* Let lib_vsprintf do the real work */
      -
      -  va_start(ap, fmt);
      -  n = lib_vsprintf(obj, fmt, ap);
      -  va_end(ap);
      -  return n;
      -}
      diff --git a/nuttx/lib/stdio/lib_libvsprintf.c b/nuttx/lib/stdio/lib_libvsprintf.c
      deleted file mode 100644
      index 30c988599c..0000000000
      --- a/nuttx/lib/stdio/lib_libvsprintf.c
      +++ /dev/null
      @@ -1,1620 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_libvsprintf.c
      - *
      - *   Copyright (C) 2007-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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -/* If you have floating point but no fieldwidth, then use a fixed (but
      - * configurable) floating point precision.
      - */
      -
      -#if defined(CONFIG_LIBC_FLOATINGPOINT) && \
      -    defined(CONFIG_NOPRINTF_FIELDWIDTH) && \
      -   !defined(CONFIG_LIBC_FIXEDPRECISION)
      -#  define CONFIG_LIBC_FIXEDPRECISION 3
      -#endif
      -
      -#define FLAG_SHOWPLUS            0x01
      -#define FLAG_ALTFORM             0x02
      -#define FLAG_HASDOT              0x04
      -#define FLAG_HASASTERISKWIDTH    0x08
      -#define FLAG_HASASTERISKTRUNC    0x10
      -#define FLAG_LONGPRECISION       0x20
      -#define FLAG_LONGLONGPRECISION   0x40
      -#define FLAG_NEGATE              0x80
      -
      -#define SET_SHOWPLUS(f)          do (f) |= FLAG_SHOWPLUS; while (0)
      -#define SET_ALTFORM(f)           do (f) |= FLAG_ALTFORM; while (0)
      -#define SET_HASDOT(f)            do (f) |= FLAG_HASDOT; while (0)
      -#define SET_HASASTERISKWIDTH(f)  do (f) |= FLAG_HASASTERISKWIDTH; while (0)
      -#define SET_HASASTERISKTRUNC(f)  do (f) |= FLAG_HASASTERISKTRUNC; while (0)
      -#define SET_LONGPRECISION(f)     do (f) |= FLAG_LONGPRECISION; while (0)
      -#define SET_LONGLONGPRECISION(f) do (f) |= FLAG_LONGLONGPRECISION; while (0)
      -#define SET_NEGATE(f)            do (f) |= FLAG_NEGATE; while (0)
      -
      -#define CLR_SHOWPLUS(f)          do (f) &= ~FLAG_SHOWPLUS; while (0)
      -#define CLR_ALTFORM(f)           do (f) &= ~FLAG_ALTFORM; while (0)
      -#define CLR_HASDOT(f)            do (f) &= ~FLAG_HASDOT; while (0)
      -#define CLR_HASASTERISKWIDTH(f)  do (f) &= ~FLAG_HASASTERISKWIDTH; while (0)
      -#define CLR_HASASTERISKTRUNC(f)  do (f) &= ~FLAG_HASASTERISKTRUNC; while (0)
      -#define CLR_LONGPRECISION(f)     do (f) &= ~FLAG_LONGPRECISION; while (0)
      -#define CLR_LONGLONGPRECISION(f) do (f) &= ~FLAG_LONGLONGPRECISION; while (0)
      -#define CLR_NEGATE(f)            do (f) &= ~FLAG_NEGATE; while (0)
      -#define CLR_SIGNED(f)            do (f) &= ~(FLAG_SHOWPLUS|FLAG_NEGATE); while (0)
      -
      -#define IS_SHOWPLUS(f)           (((f) & FLAG_SHOWPLUS) != 0)
      -#define IS_ALTFORM(f)            (((f) & FLAG_ALTFORM) != 0)
      -#define IS_HASDOT(f)             (((f) & FLAG_HASDOT) != 0)
      -#define IS_HASASTERISKWIDTH(f)   (((f) & FLAG_HASASTERISKWIDTH) != 0)
      -#define IS_HASASTERISKTRUNC(f)   (((f) & FLAG_HASASTERISKTRUNC) != 0)
      -#define IS_LONGPRECISION(f)      (((f) & FLAG_LONGPRECISION) != 0)
      -#define IS_LONGLONGPRECISION(f)  (((f) & FLAG_LONGLONGPRECISION) != 0)
      -#define IS_NEGATE(f)             (((f) & FLAG_NEGATE) != 0)
      -#define IS_SIGNED(f)             (((f) & (FLAG_SHOWPLUS|FLAG_NEGATE)) != 0)
      -
      -/* If CONFIG_ARCH_ROMGETC is defined, then it is assumed that the format
      - * string data cannot be accessed by simply de-referencing the format string
      - * pointer.  This might be in the case in Harvard architectures where string
      - * data might be stored in instruction space or if string data were stored
      - * on some media like EEPROM or external serial FLASH.  In all of these cases,
      - * string data has to be accessed indirectly using the architecture-supplied
      - * up_romgetc().  The following mechanisms attempt to make these different
      - * access methods indistinguishable in the following code.
      - *
      - * NOTE: It is assumed that string arguments for %s still reside in memory
      - * that can be directly accessed by de-referencing the string pointer.
      - */
      -
      -#ifdef CONFIG_ARCH_ROMGETC
      -#  define FMT_TOP      ch = up_romgetc(src)         /* Loop initialization */
      -#  define FMT_BOTTOM   src++, ch = up_romgetc(src)  /* Bottom of a loop */
      -#  define FMT_CHAR     ch                           /* Access a character */
      -#  define FMT_NEXT     src++; ch = up_romgetc(src)  /* Advance to the next character */
      -#  define FMT_PREV     src--; ch = up_romgetc(src)  /* Backup to the previous character */
      -#else
      -#  define FMT_TOP                                   /* Loop initialization */
      -#  define FMT_BOTTOM   src++                        /* Bottom of a loop */
      -#  define FMT_CHAR     *src                         /* Access a character */
      -#  define FMT_NEXT     src++                        /* Advance to the next character */
      -#  define FMT_PREV     src--                        /* Backup to the previous character */
      -#endif
      - 
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -enum
      -{
      -  FMT_RJUST = 0, /* Default */
      -  FMT_LJUST,
      -  FMT_RJUST0,
      -  FMT_CENTER
      -};
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/* Pointer to ASCII conversion */
      -
      -#ifdef CONFIG_PTR_IS_NOT_INT
      -static void ptohex(FAR struct lib_outstream_s *obj, uint8_t flags, FAR void *p);
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static int  getsizesize(uint8_t fmt, uint8_t flags, FAR void *p)
      -#endif /* CONFIG_NOPRINTF_FIELDWIDTH */
      -#endif /* CONFIG_PTR_IS_NOT_INT */
      -
      -/* Unsigned int to ASCII conversion */
      -
      -static void utodec(FAR struct lib_outstream_s *obj, unsigned int n);
      -static void utohex(FAR struct lib_outstream_s *obj, unsigned int n, uint8_t a);
      -static void utooct(FAR struct lib_outstream_s *obj, unsigned int n);
      -static void utobin(FAR struct lib_outstream_s *obj, unsigned int n);
      -static void utoascii(FAR struct lib_outstream_s *obj, uint8_t fmt,
      -                     uint8_t flags, unsigned int lln);
      -
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static void fixup(uint8_t fmt, FAR uint8_t *flags, int *n);
      -static int  getusize(uint8_t fmt, uint8_t flags, unsigned int lln);
      -#endif
      -
      -/* Unsigned long int to ASCII conversion */
      -
      -#ifdef CONFIG_LONG_IS_NOT_INT
      -static void lutodec(FAR struct lib_outstream_s *obj, unsigned long ln);
      -static void lutohex(FAR struct lib_outstream_s *obj, unsigned long ln, uint8_t a);
      -static void lutooct(FAR struct lib_outstream_s *obj, unsigned long ln);
      -static void lutobin(FAR struct lib_outstream_s *obj, unsigned long ln);
      -static void lutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt,
      -                      uint8_t flags, unsigned long ln);
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static void lfixup(uint8_t fmt, FAR uint8_t *flags, long *ln);
      -static int  getlusize(uint8_t fmt, FAR uint8_t flags, unsigned long ln);
      -#endif
      -#endif
      -
      -/* Unsigned long long int to ASCII conversions */
      -
      -#ifdef CONFIG_HAVE_LONG_LONG
      -static void llutodec(FAR struct lib_outstream_s *obj, unsigned long long lln);
      -static void llutohex(FAR struct lib_outstream_s *obj, unsigned long long lln, uint8_t a);
      -static void llutooct(FAR struct lib_outstream_s *obj, unsigned long long lln);
      -static void llutobin(FAR struct lib_outstream_s *obj, unsigned long long lln);
      -static void llutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt,
      -                       uint8_t flags, unsigned long long lln);
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static void llfixup(uint8_t fmt, FAR uint8_t *flags, FAR long long *lln);
      -static int  getllusize(uint8_t fmt, FAR uint8_t flags, FAR unsigned long long lln);
      -#endif
      -#endif
      -
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static void prejustify(FAR struct lib_outstream_s *obj, uint8_t fmt,
      -                       uint8_t flags, int fieldwidth, int valwidth);
      -static void postjustify(FAR struct lib_outstream_s *obj, uint8_t fmt,
      -                        uint8_t flags, int fieldwidth, int valwidth);
      -#endif
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -static const char g_nullstring[] = "(null)";
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/* Include floating point functions */
      - 
      -#ifdef CONFIG_LIBC_FLOATINGPOINT
      -#  include "stdio/lib_libdtoa.c"
      -#endif
      -
      -/****************************************************************************
      - * Name: ptohex
      - ****************************************************************************/
      -
      -#ifdef CONFIG_PTR_IS_NOT_INT
      -static void ptohex(FAR struct lib_outstream_s *obj, uint8_t flags, FAR void *p)
      -{
      -  union
      -  {
      -    uint32_t  dw;
      -    FAR void *p;
      -  } u;
      -  uint8_t bits;
      -
      -  /* Check for alternate form */
      -
      -  if (IS_ALTFORM(flags))
      -    {
      -      /* Prefix the number with "0x" */
      -
      -      obj->put(obj, '0');
      -      obj->put(obj, 'x');
      -    }
      -
      -  u.dw = 0;
      -  u.p  = p;
      -
      -  for (bits = 8*sizeof(void *); bits > 0; bits -= 4)
      -    {
      -      uint8_t nibble = (uint8_t)((u.dw >> (bits - 4)) & 0xf);
      -      if (nibble < 10)
      -        {
      -          obj->put(obj, nibble + '0');
      -        }
      -      else
      -        {
      -          obj->put(obj, nibble + 'a' - 10);
      -        }
      -    }
      -}
      -
      -/****************************************************************************
      - * Name: getpsize
      - ****************************************************************************/
      -
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static int getpsize(uint8_t flags, FAR void *p)
      -{
      -  struct lib_outstream_s nulloutstream;
      -  lib_nulloutstream(&nulloutstream);
      -
      -  ptohex(&nulloutstream, flags, p);
      -  return nulloutstream.nput;
      -}
      -
      -#endif /* CONFIG_NOPRINTF_FIELDWIDTH */
      -#endif /* CONFIG_PTR_IS_NOT_INT */
      -
      -/****************************************************************************
      - * Name: utodec
      - ****************************************************************************/
      -
      -static void utodec(FAR struct lib_outstream_s *obj, unsigned int n)
      -{
      -  unsigned int remainder = n % 10;
      -  unsigned int dividend  = n / 10;
      -
      -  if (dividend)
      -    {
      -      utodec(obj, dividend);
      -    }
      -
      -  obj->put(obj, (remainder + (unsigned int)'0'));
      -}
      -
      -/****************************************************************************
      - * Name: utohex
      - ****************************************************************************/
      -
      -static void utohex(FAR struct lib_outstream_s *obj, unsigned int n, uint8_t a)
      -{
      -  bool    nonzero = false;
      -  uint8_t bits;
      -
      -  for (bits = 8*sizeof(unsigned int); bits > 0; bits -= 4)
      -    {
      -      uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf);
      -      if (nibble || nonzero)
      -        {
      -          nonzero = true;
      -
      -          if (nibble < 10)
      -            {
      -              obj->put(obj, nibble + '0');
      -            }
      -          else
      -            {
      -              obj->put(obj, nibble + a - 10);
      -            }
      -        }
      -    }
      -
      -  if (!nonzero)
      -    {
      -      obj->put(obj, '0');
      -    }
      -}
      -
      -/****************************************************************************
      - * Name: utooct
      - ****************************************************************************/
      -
      -static void utooct(FAR struct lib_outstream_s *obj, unsigned int n)
      -{
      -  unsigned int remainder = n & 0x7;
      -  unsigned int dividend = n >> 3;
      -
      -  if (dividend)
      -    {
      -      utooct(obj, dividend);
      -    }
      -
      -  obj->put(obj, (remainder + (unsigned int)'0'));
      -}
      -
      -/****************************************************************************
      - * Name: utobin
      - ****************************************************************************/
      -
      -static void utobin(FAR struct lib_outstream_s *obj, unsigned int n)
      -{
      -  unsigned int remainder = n & 1;
      -  unsigned int dividend = n >> 1;
      -
      -  if (dividend)
      -    {
      -      utobin(obj, dividend);
      -    }
      -
      -  obj->put(obj, (remainder + (unsigned int)'0'));
      -}
      -
      -/****************************************************************************
      - * Name: utoascii
      - ****************************************************************************/
      -
      -static void utoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned int n)
      -{
      -  /* Perform the integer conversion according to the format specifier */
      -
      -  switch (fmt)
      -    {
      -      case 'd':
      -      case 'i':
      -        /* Signed base 10 */
      -        {
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -          if ((int)n < 0)
      -            {
      -              obj->put(obj, '-');
      -              n = (unsigned int)(-(int)n);
      -            }
      -          else if (IS_SHOWPLUS(flags))
      -            {
      -              obj->put(obj, '+');
      -            }
      -#endif
      -          /* Convert the unsigned value to a string. */
      -
      -          utodec(obj, n);
      -        }
      -        break;
      -
      -      case 'u':
      -        /* Unigned base 10 */
      -        {
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -          if (IS_SHOWPLUS(flags))
      -            {
      -              obj->put(obj, '+');
      -            }
      -#endif
      -          /* Convert the unsigned value to a string. */
      -
      -          utodec(obj, n);
      -        }
      -        break;
      -
      -#ifndef CONFIG_PTR_IS_NOT_INT
      -      case 'p':
      -#endif
      -      case 'x':
      -      case 'X':
      -        /* Hexadecimal */
      -        {
      -          /* Check for alternate form */
      -
      -          if (IS_ALTFORM(flags))
      -            {
      -              /* Prefix the number with "0x" */
      -
      -              obj->put(obj, '0');
      -              obj->put(obj, 'x');
      -            }
      -
      -          /* Convert the unsigned value to a string. */
      -
      -          if (fmt == 'X')
      -            {
      -              utohex(obj, n, 'A');
      -            }
      -          else
      -            {
      -              utohex(obj, n, 'a');
      -            }
      -        }
      -        break;
      -
      -      case 'o':
      -        /* Octal */
      -         {
      -           /* Check for alternate form */
      -
      -           if (IS_ALTFORM(flags))
      -             {
      -               /* Prefix the number with '0' */
      -
      -               obj->put(obj, '0');
      -             }
      -
      -           /* Convert the unsigned value to a string. */
      -
      -           utooct(obj, n);
      -         }
      -         break;
      -
      -      case 'b':
      -        /* Binary */
      -        {
      -          /* Convert the unsigned value to a string. */
      -
      -          utobin(obj, n);
      -        }
      -        break;
      -
      -#ifdef CONFIG_PTR_IS_NOT_INT
      -      case 'p':
      -#endif
      -      default:
      -        break;
      -    }
      -}
      -
      -/****************************************************************************
      - * Name: fixup
      - ****************************************************************************/
      -
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static void fixup(uint8_t fmt, FAR uint8_t *flags, FAR int *n)
      -{
      -  /* Perform the integer conversion according to the format specifier */
      -
      -  switch (fmt)
      -    {
      -      case 'd':
      -      case 'i':
      -        /* Signed base 10 */
      -
      -        if (*n < 0)
      -          {
      -            SET_NEGATE(*flags);
      -            CLR_SHOWPLUS(*flags);
      -            *n    = -*n;
      -          }
      -        break;
      -
      -      case 'u':
      -        /* Unsigned base 10 */
      -        break;
      -
      -      case 'p':
      -      case 'x':
      -      case 'X':
      -        /* Hexadecimal */
      -      case 'o':
      -        /* Octal */
      -      case 'b':
      -        /* Binary */
      -        CLR_SIGNED(*flags);
      -        break;
      -
      -      default:
      -        break;
      -    }
      -}
      -
      -/****************************************************************************
      - * Name: getusize
      - ****************************************************************************/
      -
      -static int getusize(uint8_t fmt, uint8_t flags, unsigned int n)
      -{
      -  struct lib_outstream_s nulloutstream;
      -  lib_nulloutstream(&nulloutstream);
      -
      -  utoascii(&nulloutstream, fmt, flags, n);
      -  return nulloutstream.nput;
      -}
      -
      -/****************************************************************************
      - * Name: getdblsize
      - ****************************************************************************/
      -
      -#ifdef CONFIG_LIBC_FLOATINGPOINT
      -static int getdblsize(uint8_t fmt, int trunc, uint8_t flags, double n)
      -{
      -  struct lib_outstream_s nulloutstream;
      -  lib_nulloutstream(&nulloutstream);
      -
      -  lib_dtoa(&nulloutstream, fmt, trunc, flags, n);
      -  return nulloutstream.nput;
      -}
      -#endif
      -#endif /* CONFIG_NOPRINTF_FIELDWIDTH */
      -
      -#ifdef CONFIG_LONG_IS_NOT_INT
      -/****************************************************************************
      - * Name: lutodec
      - ****************************************************************************/
      -
      -static void lutodec(FAR struct lib_outstream_s *obj, unsigned long n)
      -{
      -  unsigned int  remainder = n % 10;
      -  unsigned long dividend  = n / 10;
      -
      -  if (dividend)
      -    {
      -      lutodec(obj, dividend);
      -    }
      -
      -  obj->put(obj, (remainder + (unsigned int)'0'));
      -}
      -
      -/****************************************************************************
      - * Name: lutohex
      - ****************************************************************************/
      -
      -static void lutohex(FAR struct lib_outstream_s *obj, unsigned long n, uint8_t a)
      -{
      -  bool    nonzero = false;
      -  uint8_t bits;
      -
      -  for (bits = 8*sizeof(unsigned long); bits > 0; bits -= 4)
      -    {
      -      uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf);
      -      if (nibble || nonzero)
      -        {
      -          nonzero = true;
      -
      -          if (nibble < 10)
      -            {
      -              obj->put(obj, nibble + '0');
      -            }
      -          else
      -            {
      -              obj->put(obj, nibble + a - 10);
      -            }
      -        }
      -    }
      -
      -  if (!nonzero)
      -    {
      -      obj->put(obj, '0');
      -    }
      -}
      -
      -/****************************************************************************
      - * Name: lutooct
      - ****************************************************************************/
      -
      -static void lutooct(FAR struct lib_outstream_s *obj, unsigned long n)
      -{
      -  unsigned int  remainder = n & 0x7;
      -  unsigned long dividend  = n >> 3;
      -
      -  if (dividend)
      -    {
      -      lutooct(obj, dividend);
      -    }
      -
      -  obj->put(obj, (remainder + (unsigned int)'0'));
      -}
      -
      -/****************************************************************************
      - * Name: lutobin
      - ****************************************************************************/
      -
      -static void lutobin(FAR struct lib_outstream_s *obj, unsigned long n)
      -{
      -  unsigned int  remainder = n & 1;
      -  unsigned long dividend  = n >> 1;
      -
      -  if (dividend)
      -    {
      -      lutobin(obj, dividend);
      -    }
      -
      -  obj->put(obj, (remainder + (unsigned int)'0'));
      -}
      -
      -/****************************************************************************
      - * Name: lutoascii
      - ****************************************************************************/
      -
      -static void lutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned long ln)
      -{
      -  /* Perform the integer conversion according to the format specifier */
      -
      -  switch (fmt)
      -    {
      -      case 'd':
      -      case 'i':
      -        /* Signed base 10 */
      -        {
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -          if ((long)ln < 0)
      -            {
      -              obj->put(obj, '-');
      -              ln    = (unsigned long)(-(long)ln);
      -            }
      -          else if (IS_SHOWPLUS(flags))
      -            {
      -              obj->put(obj, '+');
      -            }
      -#endif
      -          /* Convert the unsigned value to a string. */
      -
      -          lutodec(obj, ln);
      -        }
      -        break;
      -
      -      case 'u':
      -        /* Unigned base 10 */
      -        {
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -          if (IS_SHOWPLUS(flags))
      -            {
      -              obj->put(obj, '+');
      -            }
      -#endif
      -          /* Convert the unsigned value to a string. */
      -
      -          lutodec(obj, ln);
      -        }
      -        break;
      -
      -      case 'x':
      -      case 'X':
      -        /* Hexadecimal */
      -        {
      -          /* Check for alternate form */
      -
      -          if (IS_ALTFORM(flags))
      -            {
      -              /* Prefix the number with "0x" */
      -
      -              obj->put(obj, '0');
      -              obj->put(obj, 'x');
      -            }
      -
      -          /* Convert the unsigned value to a string. */
      -
      -          if (fmt == 'X')
      -            {
      -              lutohex(obj, ln, 'A');
      -            }
      -          else
      -            {
      -              lutohex(obj, ln, 'a');
      -            }
      -        }
      -        break;
      -
      -      case 'o':
      -        /* Octal */
      -         {
      -           /* Check for alternate form */
      -
      -           if (IS_ALTFORM(flags))
      -             {
      -               /* Prefix the number with '0' */
      -
      -               obj->put(obj, '0');
      -             }
      -
      -           /* Convert the unsigned value to a string. */
      -
      -           lutooct(obj, ln);
      -         }
      -         break;
      -
      -      case 'b':
      -        /* Binary */
      -        {
      -          /* Convert the unsigned value to a string. */
      -
      -          lutobin(obj, ln);
      -        }
      -        break;
      -
      -      case 'p':
      -      default:
      -        break;
      -    }
      -}
      -
      -/****************************************************************************
      - * Name: lfixup
      - ****************************************************************************/
      -
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static void lfixup(uint8_t fmt, FAR uint8_t *flags, FAR long *ln)
      -{
      -  /* Perform the integer conversion according to the format specifier */
      -
      -  switch (fmt)
      -    {
      -      case 'd':
      -      case 'i':
      -        /* Signed base 10 */
      -
      -        if (*ln < 0)
      -          {
      -            SET_NEGATE(*flags);
      -            CLR_SHOWPLUS(*flags);
      -            *ln    = -*ln;
      -          }
      -        break;
      -
      -      case 'u':
      -        /* Unsigned base 10 */
      -        break;
      -
      -      case 'p':
      -      case 'x':
      -      case 'X':
      -        /* Hexadecimal */
      -      case 'o':
      -        /* Octal */
      -      case 'b':
      -        /* Binary */
      -        CLR_SIGNED(*flags);
      -        break;
      -
      -      default:
      -        break;
      -    }
      -}
      -
      -/****************************************************************************
      - * Name: getlusize
      - ****************************************************************************/
      -
      -static int getlusize(uint8_t fmt, uint8_t flags, unsigned long ln)
      -{
      -  struct lib_outstream_s nulloutstream;
      -  lib_nulloutstream(&nulloutstream);
      -
      -  lutoascii(&nulloutstream, fmt, flags, ln);
      -  return nulloutstream.nput;
      -}
      -
      -#endif /* CONFIG_NOPRINTF_FIELDWIDTH */
      -#endif /* CONFIG_LONG_IS_NOT_INT */
      -
      -#ifdef CONFIG_HAVE_LONG_LONG
      -/****************************************************************************
      - * Name: llutodec
      - ****************************************************************************/
      -
      -static void llutodec(FAR struct lib_outstream_s *obj, unsigned long long n)
      -{
      -  unsigned int remainder = n % 10;
      -  unsigned long long dividend = n / 10;
      -
      -  if (dividend)
      -    {
      -      llutodec(obj, dividend);
      -    }
      -
      -  obj->put(obj, (remainder + (unsigned int)'0'));
      -}
      -
      -/****************************************************************************
      - * Name: llutohex
      - ****************************************************************************/
      -
      -static void llutohex(FAR struct lib_outstream_s *obj, unsigned long long n, uint8_t a)
      -{
      -  bool    nonzero = false;
      -  uint8_t bits;
      -
      -  for (bits = 8*sizeof(unsigned long long); bits > 0; bits -= 4)
      -    {
      -      uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf);
      -      if (nibble || nonzero)
      -        {
      -          nonzero = true;
      -
      -          if (nibble < 10)
      -            {
      -              obj->put(obj, (nibble + '0'));
      -            }
      -          else
      -            {
      -              obj->put(obj, (nibble + a - 10));
      -            }
      -        }
      -    }
      -
      -  if (!nonzero)
      -    {
      -      obj->put(obj, '0');
      -    }
      -}
      -
      -/****************************************************************************
      - * Name: llutooct
      - ****************************************************************************/
      -
      -static void llutooct(FAR struct lib_outstream_s *obj, unsigned long long n)
      -{
      -  unsigned int remainder = n & 0x7;
      -  unsigned long long dividend = n >> 3;
      -
      -  if (dividend)
      -    {
      -      llutooct(obj, dividend);
      -    }
      -
      -  obj->put(obj, (remainder + (unsigned int)'0'));
      -}
      -
      -/****************************************************************************
      - * Name: llutobin
      - ****************************************************************************/
      -
      -static void llutobin(FAR struct lib_outstream_s *obj, unsigned long long n)
      -{
      -  unsigned int remainder = n & 1;
      -  unsigned long long dividend = n >> 1;
      -
      -  if (dividend)
      -    {
      -      llutobin(obj, dividend);
      -    }
      -
      -  obj->put(obj, (remainder + (unsigned int)'0'));
      -}
      -
      -/****************************************************************************
      - * Name: llutoascii
      - ****************************************************************************/
      -
      -static void llutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned long long lln)
      -{
      -  /* Perform the integer conversion according to the format specifier */
      -
      -  switch (fmt)
      -    {
      -      case 'd':
      -      case 'i':
      -        /* Signed base 10 */
      -        {
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -          if ((long long)lln < 0)
      -            {
      -              obj->put(obj, '-');
      -              lln    = (unsigned long long)(-(long long)lln);
      -            }
      -          else if (IS_SHOWPLUS(flags))
      -            {
      -              obj->put(obj, '+');
      -            }
      -#endif
      -          /* Convert the unsigned value to a string. */
      -
      -          llutodec(obj, (unsigned long long)lln);
      -        }
      -        break;
      -
      -      case 'u':
      -        /* Unigned base 10 */
      -        {
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -          if (IS_SHOWPLUS(flags))
      -            {
      -              obj->put(obj, '+');
      -            }
      -#endif
      -          /* Convert the unsigned value to a string. */
      -
      -          llutodec(obj, (unsigned long long)lln);
      -        }
      -        break;
      -
      -      case 'x':
      -      case 'X':
      -        /* Hexadecimal */
      -        {
      -          /* Check for alternate form */
      -
      -          if (IS_ALTFORM(flags))
      -            {
      -              /* Prefix the number with "0x" */
      -
      -              obj->put(obj, '0');
      -              obj->put(obj, 'x');
      -            }
      -
      -          /* Convert the unsigned value to a string. */
      -
      -          if (fmt == 'X')
      -            {
      -              llutohex(obj, (unsigned long long)lln, 'A');
      -            }
      -          else
      -            {
      -              llutohex(obj, (unsigned long long)lln, 'a');
      -            }
      -        }
      -        break;
      -
      -      case 'o':
      -        /* Octal */
      -         {
      -           /* Check for alternate form */
      -
      -           if (IS_ALTFORM(flags))
      -             {
      -               /* Prefix the number with '0' */
      -
      -               obj->put(obj, '0');
      -             }
      -
      -           /* Convert the unsigned value to a string. */
      -
      -           llutooct(obj, (unsigned long long)lln);
      -         }
      -         break;
      -
      -      case 'b':
      -        /* Binary */
      -        {
      -          /* Convert the unsigned value to a string. */
      -
      -          llutobin(obj, (unsigned long long)lln);
      -        }
      -        break;
      -
      -      case 'p':
      -      default:
      -        break;
      -    }
      -}
      -
      -/****************************************************************************
      - * Name: llfixup
      - ****************************************************************************/
      -
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static void llfixup(uint8_t fmt, FAR uint8_t *flags, FAR long long *lln)
      -{
      -  /* Perform the integer conversion according to the format specifier */
      -
      -  switch (fmt)
      -    {
      -      case 'd':
      -      case 'i':
      -        /* Signed base 10 */
      -
      -        if (*lln < 0)
      -          {
      -            SET_NEGATE(*flags);
      -            CLR_SHOWPLUS(*flags);
      -            *lln    = -*lln;
      -          }
      -        break;
      -
      -      case 'u':
      -        /* Unsigned base 10 */
      -        break;
      -
      -      case 'p':
      -      case 'x':
      -      case 'X':
      -        /* Hexadecimal */
      -      case 'o':
      -        /* Octal */
      -      case 'b':
      -        /* Binary */
      -        CLR_SIGNED(*flags);
      -        break;
      -
      -      default:
      -        break;
      -    }
      -}
      -
      -/****************************************************************************
      - * Name: getllusize
      - ****************************************************************************/
      -
      -static int getllusize(uint8_t fmt, uint8_t flags, unsigned long long lln)
      -{
      -  struct lib_outstream_s nulloutstream;
      -  lib_nulloutstream(&nulloutstream);
      -
      -
      -  llutoascii(&nulloutstream, fmt, flags, lln);
      -  return nulloutstream.nput;
      -}
      -
      -#endif /* CONFIG_NOPRINTF_FIELDWIDTH */
      -#endif /* CONFIG_HAVE_LONG_LONG */
      -
      -/****************************************************************************
      - * Name: prejustify
      - ****************************************************************************/
      -
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static void prejustify(FAR struct lib_outstream_s *obj, uint8_t fmt,
      -                       uint8_t flags, int fieldwidth, int valwidth)
      -{
      -  int i;
      -
      -  switch (fmt)
      -    {
      -      default:
      -      case FMT_RJUST:
      -        if (IS_SIGNED(flags))
      -          {
      -            valwidth++;
      -          }
      -
      -        for (i = fieldwidth - valwidth; i > 0; i--)
      -          {
      -            obj->put(obj, ' ');
      -          }
      -
      -        if (IS_NEGATE(flags))
      -          {
      -            obj->put(obj, '-');
      -          }
      -        else if (IS_SHOWPLUS(flags))
      -          {
      -            obj->put(obj, '+');
      -          }
      -        break;
      -
      -      case FMT_RJUST0:
      -         if (IS_NEGATE(flags))
      -          {
      -            obj->put(obj, '-');
      -            valwidth++;
      -          }
      -        else if (IS_SHOWPLUS(flags))
      -          {
      -            obj->put(obj, '+');
      -            valwidth++;
      -          }
      -
      -        for (i = fieldwidth - valwidth; i > 0; i--)
      -          {
      -            obj->put(obj, '0');
      -          }
      -        break;
      -
      -      case FMT_LJUST:
      -         if (IS_NEGATE(flags))
      -          {
      -            obj->put(obj, '-');
      -          }
      -        else if (IS_SHOWPLUS(flags))
      -          {
      -            obj->put(obj, '+');
      -          }
      -        break;
      -    }
      -}
      -#endif
      -
      -/****************************************************************************
      - * Name: postjustify
      - ****************************************************************************/
      -
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -static void postjustify(FAR struct lib_outstream_s *obj, uint8_t fmt,
      -                        uint8_t flags, int fieldwidth, int valwidth)
      -{
      -  int i;
      -
      -  /* Apply field justification to the integer value. */
      -
      -  switch (fmt)
      -    {
      -      default:
      -      case FMT_RJUST:
      -      case FMT_RJUST0:
      -        break;
      -
      -      case FMT_LJUST:
      -        if (IS_SIGNED(flags))
      -          {
      -            valwidth++;
      -          }
      -
      -        for (i = fieldwidth - valwidth; i > 0; i--)
      -          {
      -            obj->put(obj, ' ');
      -          }
      -        break;
      -    }
      -}
      -#endif
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * lib/stdio/lib_vsprintf
      - ****************************************************************************/
      -
      -int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list ap)
      -{
      -  FAR char        *ptmp;
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -  int             width;
      -#ifdef CONFIG_LIBC_FLOATINGPOINT
      -  int             trunc;
      -#endif
      -  uint8_t         fmt;
      -#endif
      -  uint8_t         flags;
      -#ifdef CONFIG_ARCH_ROMGETC
      -  char            ch;
      -#endif
      -
      -  for (FMT_TOP; FMT_CHAR; FMT_BOTTOM)
      -    {
      -      /* Just copy regular characters */
      -
      -      if (FMT_CHAR != '%')
      -        {
      -           /* Output the character */
      -
      -           obj->put(obj, FMT_CHAR);
      -
      -           /* Flush the buffer if a newline is encountered */
      -
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -           if (FMT_CHAR == '\n')
      -             {
      -               /* Should return an error on a failure to flush */
      -
      -               (void)obj->flush(obj);
      -             }
      -#endif
      -           /* Process the next character in the format */
      -
      -           continue;
      -        }
      -
      -      /* We have found a format specifier. Move past it. */
      -
      -      FMT_NEXT;
      -
      -      /* Assume defaults */
      -
      -      flags = 0;
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -      fmt   = FMT_RJUST;
      -      width = 0;
      -#ifdef CONFIG_LIBC_FLOATINGPOINT
      -      trunc = 0;
      -#endif
      -#endif
      -
      -      /* Process each format qualifier. */
      -
      -      for (; FMT_CHAR; FMT_BOTTOM)
      -        {
      -          /* Break out of the loop when the format is known. */
      -
      -          if (strchr("diuxXpobeEfgGlLsc%", FMT_CHAR))
      -            {
      -              break;
      -            }
      -
      -          /* Check for left justification. */
      -
      -          else if (FMT_CHAR == '-')
      -            {
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -              fmt = FMT_LJUST;
      -#endif
      -            }
      -
      -          /* Check for leading zero fill right justification. */
      -
      -          else if (FMT_CHAR == '0')
      -            {
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -              fmt = FMT_RJUST0;
      -#endif
      -            }
      -#if 0
      -          /* Center justification. */
      -
      -          else if (FMT_CHAR == '~')
      -            {
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -              fmt = FMT_CENTER;
      -#endif
      -            }
      -#endif
      -
      -          else if (FMT_CHAR == '*')
      -            {
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -              int value = va_arg(ap, int);
      -              if (IS_HASDOT(flags))
      -                {
      -#ifdef CONFIG_LIBC_FLOATINGPOINT
      -                  trunc = value;
      -                  SET_HASASTERISKTRUNC(flags);
      -#endif
      -                }
      -              else
      -                {
      -                  width = value;
      -                  SET_HASASTERISKWIDTH(flags);
      -                }
      -#endif
      -            }
      -
      -          /* Check for field width */
      -
      -          else if (FMT_CHAR >= '1' && FMT_CHAR <= '9')
      -            {
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -              do
      -                {
      -                  FMT_NEXT;
      -                }
      -              while (FMT_CHAR >= '0' && FMT_CHAR <= '9');
      -#else
      -              /* Accumulate the field width integer. */
      -
      -              int n = ((int)(FMT_CHAR)) - (int)'0';
      -              for (;;)
      -                {
      -                  FMT_NEXT;
      -                  if (FMT_CHAR >= '0' && FMT_CHAR <= '9')
      -                    {
      -                      n = 10*n + (((int)(FMT_CHAR)) - (int)'0');
      -                    }
      -                  else
      -                    {
      -                      break;
      -                    }
      -                }
      -
      -              if (IS_HASDOT(flags))
      -                {
      -#ifdef CONFIG_LIBC_FLOATINGPOINT
      -                  trunc = n;
      -#endif
      -                }
      -              else
      -                {
      -                  width = n;
      -                }
      -#endif
      -              /* Back up to the last digit. */
      -
      -              FMT_PREV;
      -            }
      -
      -          /* Check for a decimal point. */
      -
      -          else if (FMT_CHAR == '.')
      -            {
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -              SET_HASDOT(flags);
      -#endif
      -            }
      -
      -          /* Check for leading plus sign. */
      -
      -          else if (FMT_CHAR == '+')
      -            {
      -              SET_SHOWPLUS(flags);
      -            }
      -
      -          /* Check for alternate form. */
      -
      -          else if (FMT_CHAR == '#')
      -            {
      -              SET_ALTFORM(flags);
      -            }
      -        }
      -
      -      /* "%%" means that a literal '%' was intended (instead of a format
      -       * specification).
      -       */
      -
      -      if (FMT_CHAR == '%')
      -        {
      -          obj->put(obj, '%');
      -          continue;
      -        }
      -
      -      /* Check for the string format. */
      -
      -      if (FMT_CHAR == 's')
      -        {
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -          int swidth;
      -#endif
      -          /* Get the string to output */
      -
      -          ptmp = va_arg(ap, char *);
      -          if (!ptmp)
      -            {
      -              ptmp = (char*)g_nullstring;
      -            }
      -
      -          /* Get the widith of the string and perform right-justification
      -           * operations.
      -           */
      -
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -          swidth = strlen(ptmp);
      -          prejustify(obj, fmt, 0, width, swidth);
      -#endif
      -          /* Concatenate the string into the output */
      -
      -          while (*ptmp)
      -            {
      -              obj->put(obj, *ptmp);
      -              ptmp++;
      -            }
      -
      -          /* Perform left-justification operations. */
      -
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -          postjustify(obj, fmt, 0, width, swidth);
      -#endif
      -          continue;
      -        }
      -
      -      /* Check for the character output */
      -
      -      else if (FMT_CHAR == 'c')
      -        {
      -          /* Just copy the character into the output. */
      -
      -          int n = va_arg(ap, int);
      -          obj->put(obj, n);
      -          continue;
      -        }
      -
      -      /* Check for the long long prefix. */
      -
      -      if (FMT_CHAR == 'L')
      -        {
      -           SET_LONGLONGPRECISION(flags);
      -           FMT_NEXT;
      -        }
      -      else if (FMT_CHAR == 'l')
      -        {
      -          SET_LONGPRECISION(flags);
      -          FMT_NEXT;
      -          if (FMT_CHAR == 'l')
      -            {
      -              SET_LONGLONGPRECISION(flags);
      -              FMT_NEXT;
      -            }
      -        }
      -
      -      /* Handle integer conversions */
      -
      -      if (strchr("diuxXpob", FMT_CHAR))
      -        {
      -#ifdef CONFIG_HAVE_LONG_LONG
      -          if (IS_LONGLONGPRECISION(flags) && FMT_CHAR != 'p')
      -            {
      -              long long lln;
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -              int lluwidth;
      -#endif
      -              /* Extract the long long value. */
      -
      -              lln = va_arg(ap, long long);
      -
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -              /* Output the number */
      -
      -              llutoascii(obj, FMT_CHAR, flags, (unsigned long long)lln);
      -#else
      -              /* Resolve sign-ness and format issues */
      -
      -              llfixup(FMT_CHAR, &flags, &lln);
      -
      -              /* Get the width of the output */
      -
      -              lluwidth = getllusize(FMT_CHAR, flags, lln);
      -
      -              /* Perform left field justification actions */
      -
      -              prejustify(obj, fmt, flags, width, lluwidth);
      -
      -              /* Output the number */
      -
      -              llutoascii(obj, FMT_CHAR, flags, (unsigned long long)lln);
      -
      -              /* Perform right field justification actions */
      -
      -              postjustify(obj, fmt, flags, width, lluwidth);
      -#endif
      -            }
      -          else
      -#endif /* CONFIG_HAVE_LONG_LONG */
      -#ifdef CONFIG_LONG_IS_NOT_INT
      -          if (IS_LONGPRECISION(flags) && FMT_CHAR != 'p')
      -            {
      -              long ln;
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -              int luwidth;
      -#endif
      -              /* Extract the long value. */
      -
      -              ln = va_arg(ap, long);
      -
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -              /* Output the number */
      -
      -              lutoascii(obj, FMT_CHAR, flags, (unsigned long)ln);
      -#else
      -              /* Resolve sign-ness and format issues */
      -
      -              lfixup(FMT_CHAR, &flags, &ln);
      -
      -              /* Get the width of the output */
      -
      -              luwidth = getlusize(FMT_CHAR, flags, ln);
      -
      -              /* Perform left field justification actions */
      -
      -              prejustify(obj, fmt, flags, width, luwidth);
      -
      -              /* Output the number */
      -
      -              lutoascii(obj, FMT_CHAR, flags, (unsigned long)ln);
      -
      -              /* Perform right field justification actions */
      -
      -              postjustify(obj, fmt, flags, width, luwidth);
      -#endif
      -            }
      -          else
      -#endif /* CONFIG_LONG_IS_NOT_INT */
      -#ifdef CONFIG_PTR_IS_NOT_INT
      -          if (FMT_CHAR == 'p')
      -            {
      -              void *p;
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -              int pwidth;
      -#endif
      -              /* Extract the integer value. */
      -
      -              p = va_arg(ap, void *);
      -
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -              /* Output the pointer value */
      -
      -              ptohex(obj, flags, p);
      -#else
      -              /* Resolve sign-ness and format issues */
      -
      -              lfixup(FMT_CHAR, &flags, &ln);
      -
      -              /* Get the width of the output */
      -
      -              luwidth = getpsize(FMT_CHAR, flags, p);
      -
      -              /* Perform left field justification actions */
      -
      -              prejustify(obj, fmt, flags, width, pwidth);
      -
      -              /* Output the pointer value */
      -
      -              ptohex(obj, flags, p);
      -
      -              /* Perform right field justification actions */
      -
      -              postjustify(obj, fmt, flags, width, pwidth);
      -#endif
      -            }
      -          else
      -#endif
      -            {
      -              int n;
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -              int uwidth;
      -#endif
      -              /* Extract the long long value. */
      -
      -              n = va_arg(ap, int);
      -
      -#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      -              /* Output the number */
      -
      -              utoascii(obj, FMT_CHAR, flags, (unsigned int)n);
      -#else
      -              /* Resolve sign-ness and format issues */
      -
      -              fixup(FMT_CHAR, &flags, &n);
      -
      -              /* Get the width of the output */
      -
      -              uwidth = getusize(FMT_CHAR, flags, n);
      -
      -              /* Perform left field justification actions */
      -
      -              prejustify(obj, fmt, flags, width, uwidth);
      -
      -              /* Output the number */
      -
      -              utoascii(obj, FMT_CHAR, flags, (unsigned int)n);
      -
      -              /* Perform right field justification actions */
      -
      -              postjustify(obj, fmt, flags, width, uwidth);
      -#endif
      -            }
      -        }
      -
      -      /* Handle floating point conversions */
      -
      -#ifdef CONFIG_LIBC_FLOATINGPOINT
      -      else if (strchr("eEfgG", FMT_CHAR))
      -        {
      -#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      -          double dblval = va_arg(ap, double);
      -          int dblsize;
      -
      -          /* Get the width of the output */
      -
      -          dblsize = getdblsize(FMT_CHAR, trunc, flags, dblval);
      -
      -          /* Perform left field justification actions */
      -
      -          prejustify(obj, fmt, 0, width, dblsize);
      -
      -          /* Output the number */
      -
      -          lib_dtoa(obj, FMT_CHAR, trunc, flags, dblval);
      -
      -          /* Perform right field justification actions */
      -
      -          postjustify(obj, fmt, 0, width, dblsize);
      -#else
      -          /* Output the number with a fixed precision */
      -
      -          double dblval = va_arg(ap, double);
      -          lib_dtoa(obj, FMT_CHAR, CONFIG_LIBC_FIXEDPRECISION, flags, dblval);
      -#endif
      -        }
      -#endif /* CONFIG_LIBC_FLOATINGPOINT */
      -    }
      -
      -  return obj->nput;
      -}
      -
      -
      diff --git a/nuttx/lib/stdio/lib_lowinstream.c b/nuttx/lib/stdio/lib_lowinstream.c
      deleted file mode 100644
      index 499a647ea2..0000000000
      --- a/nuttx/lib/stdio/lib_lowinstream.c
      +++ /dev/null
      @@ -1,102 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_lowinstream.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -#ifdef CONFIG_ARCH_LOWGETC
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lowinstream_getc
      - ****************************************************************************/
      -
      -static int lowinstream_getc(FAR struct lib_instream_s *this)
      -{
      -  int ret;
      -
      -  DEBUGASSERT(this);
      -
      -  /* Get the next character from the incoming stream */
      -
      -  ret = up_getc(ch)
      -  if (ret != EOF)
      -    {
      -      this->nget++;
      -    }
      -
      -  return ret;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_lowinstream
      - *
      - * Description:
      - *   Initializes a stream for use with low-level, architecture-specific I/O.
      - *
      - * Input parameters:
      - *   lowoutstream - User allocated, uninitialized instance of struct
      - *                  lib_lowoutstream_s to be initialized.
      - *
      - * Returned Value:
      - *   None (User allocated instance initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_lowinstream(FAR struct lib_instream_s *stream)
      -{
      -  stream->get  = lowinstream_getc;
      -  stream->nget = 0;
      -}
      -
      -#endif /* CONFIG_ARCH_LOWGETC */
      diff --git a/nuttx/lib/stdio/lib_lowoutstream.c b/nuttx/lib/stdio/lib_lowoutstream.c
      deleted file mode 100644
      index 092f39ca25..0000000000
      --- a/nuttx/lib/stdio/lib_lowoutstream.c
      +++ /dev/null
      @@ -1,97 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_lowoutstream.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#ifdef CONFIG_ARCH_LOWPUTC
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lowoutstream_putc
      - ****************************************************************************/
      -
      -static void lowoutstream_putc(FAR struct lib_outstream_s *this, int ch)
      -{
      -  DEBUGASSERT(this);
      -
      -  if (up_putc(ch) != EOF)
      -    {
      -      this->nput++;
      -    }
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_lowoutstream
      - *
      - * Description:
      - *   Initializes a stream for use with low-level, architecture-specific I/O.
      - *
      - * Input parameters:
      - *   lowoutstream - User allocated, uninitialized instance of struct
      - *                  lib_lowoutstream_s to be initialized.
      - *
      - * Returned Value:
      - *   None (User allocated instance initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_lowoutstream(FAR struct lib_outstream_s *stream)
      -{
      -  stream->put   = lowoutstream_putc;
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -  stream->flush = lib_noflush;
      -#endif
      -  stream->nput  = 0;
      -}
      -
      -#endif /* CONFIG_ARCH_LOWPUTC */
      diff --git a/nuttx/lib/stdio/lib_lowprintf.c b/nuttx/lib/stdio/lib_lowprintf.c
      deleted file mode 100644
      index 392ef2c6a8..0000000000
      --- a/nuttx/lib/stdio/lib_lowprintf.c
      +++ /dev/null
      @@ -1,128 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_lowprintf.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -#include "lib_internal.h"
      -
      -/* This interface can only be used from within the kernel */
      -
      -#if !defined(CONFIG_NUTTX_KERNEL) || defined(__KERNEL__)
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_lowvprintf
      - ****************************************************************************/
      -
      -#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_SYSLOG)
      -
      -int lib_lowvprintf(const char *fmt, va_list ap)
      -{
      -  struct lib_outstream_s stream;
      -
      -  /* Wrap the stdout in a stream object and let lib_vsprintf do the work. */
      -
      -#ifdef CONFIG_SYSLOG
      -  lib_syslogstream((FAR struct lib_outstream_s *)&stream);
      -#else
      -  lib_lowoutstream((FAR struct lib_outstream_s *)&stream);
      -#endif
      -  return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap);
      -}
      -
      -/****************************************************************************
      - * Name: lib_lowprintf
      - ****************************************************************************/
      -
      -int lib_lowprintf(const char *fmt, ...)
      -{
      -  va_list ap;
      -  int     ret;
      -
      -#ifdef CONFIG_DEBUG_ENABLE
      -  ret = 0;
      -  if (g_dbgenable)
      -#endif
      -    {
      -      va_start(ap, fmt);
      -      ret = lib_lowvprintf(fmt, ap);
      -      va_end(ap);
      -    }
      -
      -  return ret;
      -}
      -
      -#endif /* CONFIG_ARCH_LOWPUTC || CONFIG_SYSLOG */
      -#endif /* __KERNEL__ */
      diff --git a/nuttx/lib/stdio/lib_meminstream.c b/nuttx/lib/stdio/lib_meminstream.c
      deleted file mode 100644
      index a842096fb4..0000000000
      --- a/nuttx/lib/stdio/lib_meminstream.c
      +++ /dev/null
      @@ -1,104 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_meminstream.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: meminstream_getc
      - ****************************************************************************/
      -
      -static int meminstream_getc(FAR struct lib_instream_s *this)
      -{
      -  FAR struct lib_meminstream_s *mthis = (FAR struct lib_meminstream_s *)this;
      -  int ret;
      -
      -  DEBUGASSERT(this);
      -
      -  /* Get the next character (if any) from the buffer */
      -
      -  if (this->nget < mthis->buflen)
      -    {
      -      ret = mthis->buffer[this->nget];
      -      this->nget++;
      -    }
      -  else
      -    {
      -      ret = EOF;
      -    }
      -
      -  return ret;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_meminstream
      - *
      - * Description:
      - *   Initializes a stream for use with a fixed-size memory buffer.
      - *
      - * Input parameters:
      - *   meminstream - User allocated, uninitialized instance of struct
      - *                 lib_meminstream_s to be initialized.
      - *   bufstart    - Address of the beginning of the fixed-size memory buffer
      - *   buflen      - Size of the fixed-sized memory buffer in bytes
      - *
      - * Returned Value:
      - *   None (meminstream initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_meminstream(FAR struct lib_meminstream_s *meminstream,
      -                     FAR const char *bufstart, int buflen)
      -{
      -  meminstream->public.get  = meminstream_getc;
      -  meminstream->public.nget = 0;          /* Will be buffer index */
      -  meminstream->buffer      = bufstart;   /* Start of buffer */
      -  meminstream->buflen      = buflen;     /* Length of the buffer */
      -}
      -
      -
      diff --git a/nuttx/lib/stdio/lib_memoutstream.c b/nuttx/lib/stdio/lib_memoutstream.c
      deleted file mode 100644
      index 21197358b7..0000000000
      --- a/nuttx/lib/stdio/lib_memoutstream.c
      +++ /dev/null
      @@ -1,105 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_memoutstream.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: memoutstream_putc
      - ****************************************************************************/
      -
      -static void memoutstream_putc(FAR struct lib_outstream_s *this, int ch)
      -{
      -  FAR struct lib_memoutstream_s *mthis = (FAR struct lib_memoutstream_s *)this;
      -
      -  DEBUGASSERT(this);
      -
      -  /* If this will not overrun the buffer, then write the character to the
      -   * buffer.  Not that buflen was pre-decremented when the stream was
      -   * created so it is okay to write past the end of the buflen by one.
      -   */
      -
      -  if (this->nput < mthis->buflen)
      -    {
      -      mthis->buffer[this->nput] = ch;
      -      this->nput++;
      -      mthis->buffer[this->nput] = '\0';
      -    }
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_memoutstream
      - *
      - * Description:
      - *   Initializes a stream for use with a fixed-size memory buffer.
      - *
      - * Input parameters:
      - *   memoutstream - User allocated, uninitialized instance of struct
      - *                  lib_memoutstream_s to be initialized.
      - *   bufstart     - Address of the beginning of the fixed-size memory buffer
      - *   buflen       - Size of the fixed-sized memory buffer in bytes
      - *
      - * Returned Value:
      - *   None (memoutstream initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_memoutstream(FAR struct lib_memoutstream_s *memoutstream,
      -                      FAR char *bufstart, int buflen)
      -{
      -  memoutstream->public.put   = memoutstream_putc;
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -  memoutstream->public.flush = lib_noflush;
      -#endif
      -  memoutstream->public.nput  = 0;          /* Will be buffer index */
      -  memoutstream->buffer       = bufstart;   /* Start of buffer */
      -  memoutstream->buflen       = buflen - 1; /* Save space for null terminator */
      -  memoutstream->buffer[0]    = '\0';       /* Start with an empty string */
      -}
      -
      -
      diff --git a/nuttx/lib/stdio/lib_nullinstream.c b/nuttx/lib/stdio/lib_nullinstream.c
      deleted file mode 100644
      index 0eadb0a8e4..0000000000
      --- a/nuttx/lib/stdio/lib_nullinstream.c
      +++ /dev/null
      @@ -1,79 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_nullinstream.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -static int nullinstream_getc(FAR struct lib_instream_s *this)
      -{
      -  return EOF;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_nullinstream
      - *
      - * Description:
      - *   Initializes a NULL stream. The initialized stream will  will return only
      - *   EOF.
      - *
      - * Input parameters:
      - *   nullinstream  - User allocated, uninitialized instance of struct
      - *                   lib_instream_s to be initialized.
      - *
      - * Returned Value:
      - *   None (User allocated instance initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_nullinstream(FAR struct lib_instream_s *nullinstream)
      -{
      -  nullinstream->get  = nullinstream_getc;
      -  nullinstream->nget = 0;
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_nulloutstream.c b/nuttx/lib/stdio/lib_nulloutstream.c
      deleted file mode 100644
      index 69878fd579..0000000000
      --- a/nuttx/lib/stdio/lib_nulloutstream.c
      +++ /dev/null
      @@ -1,84 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_nulloutstream.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -static void nulloutstream_putc(FAR struct lib_outstream_s *this, int ch)
      -{
      -  DEBUGASSERT(this);
      -  this->nput++;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_nulloutstream
      - *
      - * Description:
      - *   Initializes a NULL streams. The initialized stream will write all data
      - *   to the bit-bucket.
      - *
      - * Input parameters:
      - *   nulloutstream - User allocated, uninitialized instance of struct
      - *                   lib_outstream_s to be initialized.
      - *
      - * Returned Value:
      - *   None (User allocated instance initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_nulloutstream(FAR struct lib_outstream_s *nulloutstream)
      -{
      -  nulloutstream->put   = nulloutstream_putc;
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -  nulloutstream->flush = lib_noflush;
      -#endif
      -  nulloutstream->nput  = 0;
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_perror.c b/nuttx/lib/stdio/lib_perror.c
      deleted file mode 100644
      index 867e113f98..0000000000
      --- a/nuttx/lib/stdio/lib_perror.c
      +++ /dev/null
      @@ -1,99 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_perror.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/* POSIX requires that perror provide its output on stderr.  This option may
      - * be defined, however, to provide perror output that is serialized with
      - * other stdout messages.
      - */
      - 
      -#ifdef CONFIG_LIBC_PERROR_STDOUT
      -#  define PERROR_STREAM stdout
      -#else
      -#  define PERROR_STREAM stderr
      -#endif
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: perror
      - ****************************************************************************/
      -
      -void perror(FAR const char *s)
      -{
      -
      -  /* If strerror() is not enabled, then just print the error number */
      -
      -#ifdef CONFIG_LIBC_STRERROR
      -  (void)fprintf(PERROR_STREAM, "%s: %s\n", s, strerror(errno));
      -#else
      -  (void)fprintf(PERROR_STREAM, "%s: Error %d\n", s, errno);
      -#endif
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_printf.c b/nuttx/lib/stdio/lib_printf.c
      deleted file mode 100644
      index 50db06c475..0000000000
      --- a/nuttx/lib/stdio/lib_printf.c
      +++ /dev/null
      @@ -1,109 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_printf.c
      - *
      - *   Copyright (C) 2007-2008, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Global Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Private Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Name: printf
      - **************************************************************************/
      -
      -int printf(const char *fmt, ...)
      -{
      -  va_list ap;
      -  int     ret;
      -
      -  va_start(ap, fmt);
      -#if CONFIG_NFILE_STREAMS > 0
      -  ret = vfprintf(stdout, fmt, ap);
      -#elif CONFIG_NFILE_DESCRIPTORS > 0
      -  ret = lib_rawvprintf(fmt, ap);
      -#elif defined(CONFIG_ARCH_LOWPUTC)
      -  ret = lib_lowvprintf(fmt, ap);
      -#else
      -# ifdef CONFIG_CPP_HAVE_WARNING
      -#   warning "printf has no data sink"
      -# endif
      -  ret = 0;
      -#endif
      -  va_end(ap);
      -
      -  return ret;
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_puts.c b/nuttx/lib/stdio/lib_puts.c
      deleted file mode 100644
      index e63a63917f..0000000000
      --- a/nuttx/lib/stdio/lib_puts.c
      +++ /dev/null
      @@ -1,130 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_puts.c
      - *
      - *   Copyright (C) 2007, 2008, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: puts
      - *
      - * Description:
      - *   puts() writes the string s and a trailing newline to stdout.
      - *
      - ****************************************************************************/
      -
      -int puts(FAR const char *s)
      -{
      -  FILE *stream = stdout;
      -  int nwritten;
      -  int nput = EOF;
      -  int ret;
      -
      -  /* Write the string (the next two steps must be atomic) */
      -
      -  lib_take_semaphore(stream);
      -
      -  /* Write the string without its trailing '\0' */
      -
      -  nwritten = fputs(s, stream);
      -  if (nwritten > 0)
      -    {
      -      /* Followed by a newline */
      -
      -      char newline = '\n';
      -      ret = lib_fwrite(&newline, 1, stream);
      -      if (ret > 0)
      -        {
      -          nput = nwritten + 1;
      -
      -          /* Flush the buffer after the newline is output. */
      -
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -          ret = lib_fflush(stream, true);
      -          if (ret < 0)
      -            {
      -              nput = EOF;
      -            }
      -#endif
      -        }
      -    }
      -
      -  lib_give_semaphore(stdout);
      -  return nput;
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_rawinstream.c b/nuttx/lib/stdio/lib_rawinstream.c
      deleted file mode 100644
      index 9671a27166..0000000000
      --- a/nuttx/lib/stdio/lib_rawinstream.c
      +++ /dev/null
      @@ -1,107 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_rawinstream.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: rawinstream_getc
      - ****************************************************************************/
      -
      -static int rawinstream_getc(FAR struct lib_instream_s *this)
      -{
      -  FAR struct lib_rawinstream_s *rthis = (FAR struct lib_rawinstream_s *)this;
      -  int nwritten;
      -  char ch;
      -
      -  DEBUGASSERT(this && rthis->fd >= 0);
      -
      -  /* Attempt to read one character */
      -
      -  nwritten = read(rthis->fd, &ch, 1);
      -  if (nwritten == 1)
      -    {
      -      this->nget++;
      -      return ch;
      -    }
      -
      -  /* Return EOF on any failure to read from the incoming byte stream. The
      -   * only expected error is EINTR meaning that the read was interrupted
      -   * by a signal.  A Zero return value would indicated an end-of-file
      -   * confition.
      -   */
      -
      -  return EOF;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_rawinstream
      - *
      - * Description:
      - *   Initializes a stream for use with a file descriptor.
      - *
      - * Input parameters:
      - *   rawinstream - User allocated, uninitialized instance of struct
      - *                 lib_rawinstream_s to be initialized.
      - *   fd          - User provided file/socket descriptor (must have been opened
      - *                 for the correct access).
      - *
      - * Returned Value:
      - *   None (User allocated instance initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_rawinstream(FAR struct lib_rawinstream_s *rawinstream, int fd)
      -{
      -  rawinstream->public.get  = rawinstream_getc;
      -  rawinstream->public.nget = 0;
      -  rawinstream->fd          = fd;
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_rawoutstream.c b/nuttx/lib/stdio/lib_rawoutstream.c
      deleted file mode 100644
      index ed813f87aa..0000000000
      --- a/nuttx/lib/stdio/lib_rawoutstream.c
      +++ /dev/null
      @@ -1,115 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_rawoutstream.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: rawoutstream_putc
      - ****************************************************************************/
      -
      -static void rawoutstream_putc(FAR struct lib_outstream_s *this, int ch)
      -{
      -  FAR struct lib_rawoutstream_s *rthis = (FAR struct lib_rawoutstream_s *)this;
      -  int nwritten;
      -  char buffer = ch;
      -
      -  DEBUGASSERT(this && rthis->fd >= 0);
      -
      -  /* Loop until the character is successfully transferred or until an
      -   * irrecoverable error occurs.
      -   */
      -
      -  do
      -    {
      -      nwritten = write(rthis->fd, &buffer, 1);
      -      if (nwritten == 1)
      -        {
      -          this->nput++;
      -          return;
      -        }
      -
      -      /* The only expected error is EINTR, meaning that the write operation
      -       * was awakened by a signal.  Zero would not be a valid return value
      -       * from write().
      -       */
      -
      -      DEBUGASSERT(nwritten < 0);
      -    }
      -  while (get_errno() == EINTR);
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_rawoutstream
      - *
      - * Description:
      - *   Initializes a stream for use with a file descriptor.
      - *
      - * Input parameters:
      - *   rawoutstream - User allocated, uninitialized instance of struct
      - *                  lib_rawoutstream_s to be initialized.
      - *   fd           - User provided file/socket descriptor (must have been opened
      - *                  for write access).
      - *
      - * Returned Value:
      - *   None (User allocated instance initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_rawoutstream(FAR struct lib_rawoutstream_s *rawoutstream, int fd)
      -{
      -  rawoutstream->public.put   = rawoutstream_putc;
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -  rawoutstream->public.flush = lib_noflush;
      -#endif
      -  rawoutstream->public.nput  = 0;
      -  rawoutstream->fd           = fd;
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_rawprintf.c b/nuttx/lib/stdio/lib_rawprintf.c
      deleted file mode 100644
      index 19dfa895e1..0000000000
      --- a/nuttx/lib/stdio/lib_rawprintf.c
      +++ /dev/null
      @@ -1,151 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_rawprintf.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/* Some output destinations are only available from within the kernel */
      -
      -#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__)
      -#  undef CONFIG_SYSLOG
      -#  undef CONFIG_ARCH_LOWPUTC
      -#endif
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_rawvprintf
      - ****************************************************************************/
      -
      -int lib_rawvprintf(const char *fmt, va_list ap)
      -{
      -#if defined(CONFIG_SYSLOG)
      -
      -  struct lib_outstream_s stream;
      -
      -  /* Wrap the low-level output in a stream object and let lib_vsprintf
      -   * do the work.
      -   */
      -
      -  lib_syslogstream((FAR struct lib_outstream_s *)&stream);
      -  return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap);
      -
      -#elif CONFIG_NFILE_DESCRIPTORS > 0
      -
      -  struct lib_rawoutstream_s rawoutstream;
      -
      -  /* Wrap the stdout in a stream object and let lib_vsprintf
      -   * do the work.
      -   */
      -
      -  lib_rawoutstream(&rawoutstream, 1);
      -  return lib_vsprintf(&rawoutstream.public, fmt, ap);
      -
      -#elif defined(CONFIG_ARCH_LOWPUTC)
      -
      -  struct lib_outstream_s stream;
      -
      -  /* Wrap the low-level output in a stream object and let lib_vsprintf
      -   * do the work.
      -   */
      -
      -  lib_lowoutstream((FAR struct lib_outstream_s *)&stream);
      -  return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap);
      -
      -#else
      -  return 0;
      -#endif
      -}
      -
      -/****************************************************************************
      - * Name: lib_rawprintf
      - ****************************************************************************/
      -
      -int lib_rawprintf(const char *fmt, ...)
      -{
      -  va_list ap;
      -  int     ret;
      -
      -#ifdef CONFIG_DEBUG_ENABLE
      -  ret = 0;
      -  if (g_dbgenable)
      -#endif
      -    {
      -      va_start(ap, fmt);
      -      ret = lib_rawvprintf(fmt, ap);
      -      va_end(ap);
      -    }
      -
      -  return ret;
      -}
      diff --git a/nuttx/lib/stdio/lib_rdflush.c b/nuttx/lib/stdio/lib_rdflush.c
      deleted file mode 100644
      index 35c5495c17..0000000000
      --- a/nuttx/lib/stdio/lib_rdflush.c
      +++ /dev/null
      @@ -1,144 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_rdflush.c
      - *
      - *   Copyright (C) 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_rdflush
      - *
      - * Description:
      - *   Flush read data from the I/O buffer and adjust the file pointer to
      - *   account for the unread data
      - *
      - ****************************************************************************/
      -
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -int lib_rdflush(FAR FILE *stream)
      -{
      -  if (!stream)
      -    {
      -      set_errno(EBADF);
      -      return ERROR;
      -    }
      -
      -  /* Get exclusive access to the stream */
      -
      -  lib_take_semaphore(stream);
      -
      -  /* If the buffer is currently being used for read access, then discard all
      -   * of the read-ahead data.  We do not support concurrent buffered read/write
      -   * access.
      -   */
      -
      -  if (stream->fs_bufread != stream->fs_bufstart)
      -    {
      -      /* Now adjust the stream pointer to account for the read-ahead data that
      -       * was not actually read by the user.
      -       */
      -
      -#if CONFIG_NUNGET_CHARS > 0
      -      off_t rdoffset = stream->fs_bufread - stream->fs_bufpos + stream->fs_nungotten;
      -#else
      -      off_t rdoffset = stream->fs_bufread - stream->fs_bufpos;
      -#endif
      -      /* Mark the buffer as empty (do this before calling fseek() because fseek()
      -       * also calls this function).
      -       */
      -
      -      stream->fs_bufpos = stream->fs_bufread = stream->fs_bufstart;
      -#if CONFIG_NUNGET_CHARS > 0
      -      stream->fs_nungotten = 0;
      -#endif
      -      /* Then seek to the position corresponding to the last data read by the user */
      -
      -      if (fseek(stream, -rdoffset, SEEK_CUR) < 0)
      -        {
      -          lib_give_semaphore(stream);
      -          return ERROR;
      -        }
      -    }
      -
      -  lib_give_semaphore(stream);
      -  return OK;
      -}
      -#endif /* CONFIG_STDIO_BUFFER_SIZE */
      -
      diff --git a/nuttx/lib/stdio/lib_snprintf.c b/nuttx/lib/stdio/lib_snprintf.c
      deleted file mode 100644
      index e5ce7b0f02..0000000000
      --- a/nuttx/lib/stdio/lib_snprintf.c
      +++ /dev/null
      @@ -1,99 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_snprintf.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * sprintf
      - ****************************************************************************/
      -
      -int snprintf(FAR char *buf, size_t size, const char *format, ...)
      -{
      -  struct lib_memoutstream_s memoutstream;
      -  va_list ap;
      -  int     n;
      -
      -  /* Initialize a memory stream to write to the buffer */
      -
      -  lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, size);
      -
      -  /* Then let lib_vsprintf do the real work */
      -
      -  va_start(ap, format);
      -  n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, format, ap);
      -  va_end(ap);
      -  return n;
      -}
      diff --git a/nuttx/lib/stdio/lib_sprintf.c b/nuttx/lib/stdio/lib_sprintf.c
      deleted file mode 100644
      index 89fd610330..0000000000
      --- a/nuttx/lib/stdio/lib_sprintf.c
      +++ /dev/null
      @@ -1,95 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_sprintf.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * sprintf
      - ****************************************************************************/
      -
      -int sprintf (FAR char *buf, const char *fmt, ...)
      -{
      -  struct lib_memoutstream_s memoutstream;
      -  va_list ap;
      -  int     n;
      -
      -  /* Initialize a memory stream to write to the buffer */
      -
      -  lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, LIB_BUFLEN_UNKNOWN);
      -
      -  /* Then let lib_vsprintf do the real work */
      -
      -  va_start(ap, fmt);
      -  n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, fmt, ap);
      -  va_end(ap);
      -  return n;
      -}
      diff --git a/nuttx/lib/stdio/lib_sscanf.c b/nuttx/lib/stdio/lib_sscanf.c
      deleted file mode 100644
      index 7e1fae276d..0000000000
      --- a/nuttx/lib/stdio/lib_sscanf.c
      +++ /dev/null
      @@ -1,507 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_sscanf.c
      - *
      - *   Copyright (C) 2007, 2008, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -#define MAXLN 128
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -int vsscanf(char *buf, const char *fmt, va_list ap);
      -
      -/**************************************************************************
      - * Global Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Private Constant Data
      - **************************************************************************/
      -
      -static const char spaces[] = " \t\n\r\f\v";
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  findwidth
      - *
      - * Description:
      - *    Try to figure out the width of the input data.
      - *
      - ****************************************************************************/
      -
      -static int findwidth(FAR const char *buf, FAR const char *fmt)
      -{
      -  FAR const char *next = fmt + 1;
      -
      -  /* No... is there a space after the format? Or does the format string end
      -   * here?
      -   */
      -
      -  if (isspace(*next) || *next == 0)
      -    {
      -      /* Use the input up until the first white space is encountered. */
      -
      -      return strcspn(buf, spaces);
      -    }
      -
      -  /* No.. Another possibility is the the format character is followed by
      -   * some recognizable delimiting value.
      -   */
      -
      -  if (*next != '%')
      -    {
      -      /* If so we will say that the string ends there if we can find that
      -       * delimiter in the input string.
      -       */
      -
      -      FAR const char *ptr = strchr(buf, *next);
      -      if (ptr)
      -        {
      -          return (int)(ptr - buf);
      -        }
      -    }
      -
      -  /* No... the format has not delimiter and is back-to-back with the next
      -   * formats (or no is following by a delimiter that does not exist in the
      -   * input string).  At this point we just bail and Use the input up until
      -   * the first white space is encountered.
      -   *
      -   * NOTE:  This means that values from the following format may be
      -   * concatenated with the first. This is a bug.  We have no generic way of
      -   * determining the width of the data if there is no fieldwith, no space
      -   * separating the input, and no usable delimiter character.
      -   */
      -
      -  return strcspn(buf, spaces);
      -}
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  sscanf
      - *
      - * Description:
      - *    ANSI standard sscanf implementation.
      - *
      - ****************************************************************************/
      -
      -int sscanf(FAR const char *buf, FAR const char *fmt, ...)
      -{
      -  va_list ap;
      -  int     count;
      -
      -  va_start(ap, fmt);
      -  count = vsscanf((FAR char*)buf, fmt, ap);
      -  va_end(ap);
      -  return count;
      -}
      -
      -/****************************************************************************
      - * Function:  vsscanf
      - *
      - * Description:
      - *    ANSI standard vsscanf implementation.
      - *
      - ****************************************************************************/
      -
      -int vsscanf(FAR char *buf, FAR const char *fmt, va_list ap)
      -{
      -  FAR char       *bufstart;
      -  FAR char       *tv;
      -  FAR const char *tc;
      -  bool            lflag;
      -  bool            noassign;
      -  int             count;
      -  int             width;
      -  int             base = 10;
      -  char            tmp[MAXLN];
      -
      -  lvdbg("vsscanf: buf=\"%s\" fmt=\"%s\"\n", buf, fmt);
      -
      -  /* Remember the start of the input buffer.  We will need this for %n
      -   * calculations.
      -   */
      -
      -  bufstart = buf;
      -
      -  /* Parse the format, extracting values from the input buffer as needed */
      -
      -  count    = 0;
      -  width    = 0;
      -  noassign = false;
      -  lflag    = false;
      -
      -  while (*fmt && *buf)
      -    {
      -      /* Skip over white space */
      -
      -      while (isspace(*fmt))
      -        {
      -          fmt++;
      -        }
      -
      -      /* Check for a conversion specifier */
      -
      -      if (*fmt == '%')
      -        {
      -          lvdbg("vsscanf: Specifier found\n");
      -
      -          /* Check for qualifiers on the conversion specifier */
      -          fmt++;
      -          for (; *fmt; fmt++)
      -            {
      -              lvdbg("vsscanf: Processing %c\n", *fmt);
      -
      -              if (strchr("dibouxcsefgn%", *fmt))
      -                {
      -                  break;
      -                }
      -
      -              if (*fmt == '*')
      -                {
      -                  noassign = true;
      -                }
      -              else if (*fmt == 'l' || *fmt == 'L')
      -                {
      -                  /* NOTE: Missing check for long long ('ll') */
      -
      -                  lflag = true;
      -                }
      -              else if (*fmt >= '1' && *fmt <= '9')
      -                {
      -                  for (tc = fmt; isdigit(*fmt); fmt++);
      -                  strncpy(tmp, tc, fmt - tc);
      -                  tmp[fmt - tc] = '\0';
      -                  width = atoi(tmp);
      -                  fmt--;
      -                }
      -            }
      -
      -          /* Process %s:  String conversion */
      -
      -          if (*fmt == 's')
      -            {
      -              lvdbg("vsscanf: Performing string conversion\n");
      -
      -              while (isspace(*buf))
      -                {
      -                  buf++;
      -                }
      -
      -              /* Was a fieldwidth specified? */
      -
      -              if (!width)
      -                {
      -                  /* No... Guess a field width using some heuristics */
      -
      -                  width = findwidth(buf, fmt);
      -                }
      -
      -              if (!noassign)
      -                {
      -                  tv = va_arg(ap, char*);
      -                  strncpy(tv, buf, width);
      -                  tv[width] = '\0';
      -                }
      -
      -              buf += width;
      -            }
      -
      -          /* Process %c:  Character conversion */
      -
      -          else if (*fmt == 'c')
      -            {
      -              lvdbg("vsscanf: Performing character conversion\n");
      -
      -              /* Was a fieldwidth specified? */
      -
      -              if (!width)
      -                {
      -                  /* No, then width is this one single character */
      -
      -                  width = 1;
      -                }
      -
      -              if (!noassign)
      -                {
      -                  tv = va_arg(ap, char*);
      -                  strncpy(tv, buf, width);
      -                  tv[width] = '\0';
      -                }
      -
      -              buf += width;
      -            }
      -
      -          /* Process %d, %o, %b, %x, %u:  Various integer conversions */
      -
      -          else if (strchr("dobxu", *fmt))
      -            {
      -              lvdbg("vsscanf: Performing integer conversion\n");
      -
      -              /* Skip over any white space before the integer string */
      -
      -              while (isspace(*buf))
      -                {
      -                  buf++;
      -                }
      -
      -              /* The base of the integer conversion depends on the specific
      -               * conversion specification.
      -               */
      -
      -              if (*fmt == 'd' || *fmt == 'u')
      -                {
      -                  base = 10;
      -                }
      -              else if (*fmt == 'x')
      -                {
      -                  base = 16;
      -                }
      -              else if (*fmt == 'o')
      -                {
      -                  base = 8;
      -                }
      -              else if (*fmt == 'b')
      -                {
      -                  base = 2;
      -                }
      -
      -              /* Was a fieldwidth specified? */
      -
      -              if (!width)
      -                {
      -                  /* No... Guess a field width using some heuristics */
      -
      -                  width = findwidth(buf, fmt);
      -                }
      -
      -              /* Copy the numeric string into a temporary working buffer. */
      -
      -              strncpy(tmp, buf, width);
      -              tmp[width] = '\0';
      -
      -              lvdbg("vsscanf: tmp[]=\"%s\"\n", tmp);
      -
      -              /* Perform the integer conversion */
      -
      -              buf += width;
      -              if (!noassign)
      -                {
      -#ifdef SDCC
      -                  char *endptr;
      -                  long tmplong = strtol(tmp, &endptr, base);
      -#else
      -                  long tmplong = strtol(tmp, NULL, base);
      -#endif
      -                  if (lflag)
      -                    {
      -                      long *plong = va_arg(ap, long*);
      -                      lvdbg("vsscanf: Return %ld to 0x%p\n", tmplong, plong);
      -                      *plong = tmplong;
      -                    }
      -                  else
      -                    {
      -                      int *pint = va_arg(ap, int*);
      -                      lvdbg("vsscanf: Return %ld to 0x%p\n", tmplong, pint);
      -                      *pint = (int)tmplong;
      -                    }
      -                }
      -            }
      -
      -          /* Process %f:  Floating point conversion */
      -
      -          else if (*fmt == 'f')
      -            {
      -#ifndef CONFIG_LIBC_FLOATINGPOINT
      -              /* No floating point conversions */
      -
      -              void *pv = va_arg(ap, void*);
      -
      -              lvdbg("vsscanf: Return 0.0 to %p\n", pv);
      -              *((double_t*)pv) = 0.0;
      -#else
      -              lvdbg("vsscanf: Performing floating point conversion\n");
      -
      -              /* Skip over any white space before the real string */
      -
      -              while (isspace(*buf))
      -                {
      -                  buf++;
      -                }
      -
      -              /* Was a fieldwidth specified? */
      -
      -              if (!width)
      -                {
      -                  /* No... Guess a field width using some heuristics */
      -
      -                  width = findwidth(buf, fmt);
      -                }
      -
      -              /* Copy the real string into a temporary working buffer. */
      -
      -              strncpy(tmp, buf, width);
      -              tmp[width] = '\0';
      -              buf += width;
      -
      -              lvdbg("vsscanf: tmp[]=\"%s\"\n", tmp);
      -
      -              /* Perform the floating point conversion */
      -
      -              if (!noassign)
      -                {
      -                  /* strtod always returns a double */
      -#ifdef SDCC
      -                  char *endptr;
      -                  double_t dvalue = strtod(tmp,&endptr);
      -#else
      -                  double_t dvalue = strtod(tmp, NULL);
      -#endif
      -                  void *pv = va_arg(ap, void*);
      -
      -                  lvdbg("vsscanf: Return %f to %p\n", dvalue, pv);
      -
      -                  /* But we have to check whether we need to return a
      -                   * float or a double.
      -                   */
      -
      -#ifdef CONFIG_HAVE_DOUBLE
      -                  if (lflag)
      -                    {
      -                      *((double_t*)pv) = dvalue;
      -                    }
      -                  else
      -#endif
      -                    {
      -                      *((float*)pv) = (float)dvalue;
      -                    }
      -                }
      -#endif
      -            }
      -
      -          /* Process %n:  Character count */
      -
      -          else if (*fmt == 'n')
      -            {
      -              lvdbg("vsscanf: Performing character count\n");
      -
      -              if (!noassign)
      -                {
      -                  size_t nchars = (size_t)(buf - bufstart);
      -
      -                  if (lflag)
      -                    {
      -                      long *plong = va_arg(ap, long*);
      -                      *plong = (long)nchars;
      -                    }
      -                  else
      -                    {
      -                      int *pint = va_arg(ap, int*);
      -                      *pint = (int)nchars;
      -                    }
      -                }
      -            }
      -
      -          /* Note %n does not count as a conversion */
      -
      -          if (!noassign && *fmt != 'n')
      -            {
      -              count++;
      -            }
      -
      -          width    = 0;
      -          noassign = false;
      -          lflag    = false;
      -
      -          fmt++;
      -        }
      -
      -    /* Its is not a conversion specifier */
      -
      -      else
      -        {
      -          while (isspace(*buf))
      -            {
      -              buf++;
      -            }
      -
      -          if (*fmt != *buf)
      -            {
      -              break;
      -            }
      -          else
      -            {
      -              fmt++;
      -              buf++;
      -            }
      -        }
      -    }
      -
      -  return count;
      -}
      diff --git a/nuttx/lib/stdio/lib_stdinstream.c b/nuttx/lib/stdio/lib_stdinstream.c
      deleted file mode 100644
      index 77aab9ec88..0000000000
      --- a/nuttx/lib/stdio/lib_stdinstream.c
      +++ /dev/null
      @@ -1,99 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_stdinstream.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: stdinstream_getc
      - ****************************************************************************/
      -
      -static int stdinstream_getc(FAR struct lib_instream_s *this)
      -{
      -  FAR struct lib_stdinstream_s *sthis = (FAR struct lib_stdinstream_s *)this;
      -  int ret;
      -
      -  DEBUGASSERT(this);
      -
      -  /* Get the next character from the incoming stream */
      -
      -  ret = getc(sthis->stream);
      -  if (ret != EOF)
      -    {
      -      this->nget++;
      -    }
      - 
      - return ret;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_stdinstream
      - *
      - * Description:
      - *   Initializes a stream for use with a FILE instance.
      - *
      - * Input parameters:
      - *   stdinstream - User allocated, uninitialized instance of struct
      - *                 lib_stdinstream_s to be initialized.
      - *   stream      - User provided stream instance (must have been opened for
      - *                 read access).
      - *
      - * Returned Value:
      - *   None (User allocated instance initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_stdinstream(FAR struct lib_stdinstream_s *stdinstream,
      -                     FAR FILE *stream)
      -{
      -  stdinstream->public.get  = stdinstream_getc;
      -  stdinstream->public.nget = 0;
      -  stdinstream->stream      = stream;
      -}
      -
      -
      diff --git a/nuttx/lib/stdio/lib_stdoutstream.c b/nuttx/lib/stdio/lib_stdoutstream.c
      deleted file mode 100644
      index 20da5b7026..0000000000
      --- a/nuttx/lib/stdio/lib_stdoutstream.c
      +++ /dev/null
      @@ -1,147 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_stdoutstream.c
      - *
      - *   Copyright (C) 2007-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: stdoutstream_putc
      - ****************************************************************************/
      -
      -static void stdoutstream_putc(FAR struct lib_outstream_s *this, int ch)
      -{
      -  FAR struct lib_stdoutstream_s *sthis = (FAR struct lib_stdoutstream_s *)this;
      -  int result;
      -
      -  DEBUGASSERT(this && sthis->stream);
      -
      -  /* Loop until the character is successfully transferred or an irrecoverable
      -   * error occurs.
      -   */
      -
      -  do
      -    {
      -      result = fputc(ch, sthis->stream);
      -      if (result != EOF)
      -        {
      -          this->nput++;
      -          return;
      -        }
      -
      -      /* EINTR (meaning that fputc was interrupted by a signal) is the only
      -       * recoverable error.
      -       */
      -    }
      -  while (get_errno() == EINTR);
      -}
      -
      -/****************************************************************************
      - * Name: stdoutstream_flush
      - ****************************************************************************/
      -
      -#if defined(CONFIG_STDIO_LINEBUFFER) && CONFIG_STDIO_BUFFER_SIZE > 0
      -int stdoutstream_flush(FAR struct lib_outstream_s *this)
      -{
      -  FAR struct lib_stdoutstream_s *sthis = (FAR struct lib_stdoutstream_s *)this;
      -  return lib_fflush(sthis->stream, true);
      -}
      -#endif
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_stdoutstream
      - *
      - * Description:
      - *   Initializes a stream for use with a FILE instance.
      - *
      - * Input parameters:
      - *   stdoutstream - User allocated, uninitialized instance of struct
      - *                  lib_stdoutstream_s to be initialized.
      - *   stream       - User provided stream instance (must have been opened for
      - *                  write access).
      - *
      - * Returned Value:
      - *   None (User allocated instance initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_stdoutstream(FAR struct lib_stdoutstream_s *stdoutstream,
      -                   FAR FILE *stream)
      -{
      -  /* Select the put operation */
      -
      -  stdoutstream->public.put   = stdoutstream_putc;
      -
      -  /* Select the correct flush operation.  This flush is only called when
      -   * a newline is encountered in the output stream.  However, we do not
      -   * want to support this line buffering behavior if the stream was
      -   * opened in binary mode.  In binary mode, the newline has no special
      -   * meaning.
      -   */
      -
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -  if ((stream->fs_oflags & O_BINARY) == 0)
      -    {
      -      stdoutstream->public.flush = stdoutstream_flush;
      -    }
      -  else
      -#endif
      -    {
      -      stdoutstream->public.flush = lib_noflush;
      -    }
      -#endif
      -
      -  /* Set the number of bytes put to zero and remember the stream */
      -
      -  stdoutstream->public.nput  = 0;
      -  stdoutstream->stream       = stream;
      -}
      -
      -
      diff --git a/nuttx/lib/stdio/lib_syslogstream.c b/nuttx/lib/stdio/lib_syslogstream.c
      deleted file mode 100644
      index 21151b43a1..0000000000
      --- a/nuttx/lib/stdio/lib_syslogstream.c
      +++ /dev/null
      @@ -1,122 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_syslogstream.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -#ifdef CONFIG_SYSLOG
      -
      -/****************************************************************************
      - * Pre-processor definition
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: syslogstream_putc
      - ****************************************************************************/
      -
      -static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch)
      -{
      -  int ret;
      -
      -  /* Try writing until the write was successful or until an irrecoverable
      -   * error occurs.
      -   */
      -
      -  do
      -    {
      -      /* Write the character to the supported logging device */
      -
      -      ret = syslog_putc(ch);
      -      if (ret == OK)
      -        {
      -          this->nput++;
      -          return;
      -        }
      -
      -      /* On failure syslog_putc will return a negated errno value.  The
      -       * errno variable will not be set.  The special value -EINTR means that
      -       * syslog_putc() was awakened by a signal.  This is not a real error and
      -       * must be ignored in this context.
      -       */
      -    }
      -  while (ret == -EINTR);
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_syslogstream
      - *
      - * Description:
      - *   Initializes a stream for use with the configured syslog interface.
      - *
      - * Input parameters:
      - *   lowoutstream - User allocated, uninitialized instance of struct
      - *                  lib_lowoutstream_s to be initialized.
      - *
      - * Returned Value:
      - *   None (User allocated instance initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_syslogstream(FAR struct lib_outstream_s *stream)
      -{
      -  stream->put   = syslogstream_putc;
      -#ifdef CONFIG_STDIO_LINEBUFFER
      -  stream->flush = lib_noflush;
      -#endif
      -  stream->nput  = 0;
      -}
      -
      -#endif /* CONFIG_SYSLOG */
      -
      -
      diff --git a/nuttx/lib/stdio/lib_ungetc.c b/nuttx/lib/stdio/lib_ungetc.c
      deleted file mode 100644
      index c10d4fba1a..0000000000
      --- a/nuttx/lib/stdio/lib_ungetc.c
      +++ /dev/null
      @@ -1,121 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_ungetc.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Global Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Private Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Name: ungetc
      - **************************************************************************/
      -
      -int ungetc(int c, FAR FILE *stream)
      -{
      -#if CONFIG_NUNGET_CHARS > 0
      -  int nungotten;
      -#endif
      -
      -  /* Stream must be open for read access */
      -
      -  if ((stream && stream->fs_filedes < 0) ||
      -      ((stream->fs_oflags & O_RDOK) == 0))
      -    {
      -      set_errno(EBADF);
      -      return EOF;
      -    }
      -
      -#if CONFIG_NUNGET_CHARS > 0
      -  nungotten = stream->fs_nungotten;
      -  if (stream->fs_nungotten < CONFIG_NUNGET_CHARS)
      -    {
      -      stream->fs_ungotten[nungotten] = c;
      -      stream->fs_nungotten = nungotten + 1;
      -      return c;
      -    }
      -  else
      -#endif
      -    {
      -      set_errno(ENOMEM);
      -      return EOF;
      -    }
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_vfprintf.c b/nuttx/lib/stdio/lib_vfprintf.c
      deleted file mode 100644
      index 1c3a2d7fc9..0000000000
      --- a/nuttx/lib/stdio/lib_vfprintf.c
      +++ /dev/null
      @@ -1,102 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_vfprintf.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -int vfprintf(FAR FILE *stream, FAR const char *fmt, va_list ap)
      -{
      -  struct lib_stdoutstream_s stdoutstream;
      -  int  n = ERROR;
      -
      -  if (stream)
      -    {
      -      /* Wrap the stream in a stream object and let lib_vsprintf
      -       * do the work.
      -       */
      -
      -      lib_stdoutstream(&stdoutstream, stream);
      -
      -      /* Hold the stream semaphore throughout the lib_vsprintf
      -       * call so that this thread can get its entire message out
      -       * before being pre-empted by the next thread.
      -       */
      -
      -      lib_take_semaphore(stream);
      -      n = lib_vsprintf(&stdoutstream.public, fmt, ap);
      -      lib_give_semaphore(stream);
      -    }
      -  return n;
      -}
      diff --git a/nuttx/lib/stdio/lib_vprintf.c b/nuttx/lib/stdio/lib_vprintf.c
      deleted file mode 100644
      index d085d58869..0000000000
      --- a/nuttx/lib/stdio/lib_vprintf.c
      +++ /dev/null
      @@ -1,92 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_vprintf.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Function Prototypes
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Global Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Private Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Name: vprintf
      - **************************************************************************/
      -
      -int vprintf(FAR const char *fmt, va_list ap)
      -{
      -  /* vfprintf into stdout */
      -
      -  return vfprintf(stdout, fmt, ap);
      -}
      -
      diff --git a/nuttx/lib/stdio/lib_vsnprintf.c b/nuttx/lib/stdio/lib_vsnprintf.c
      deleted file mode 100644
      index c6f52092d1..0000000000
      --- a/nuttx/lib/stdio/lib_vsnprintf.c
      +++ /dev/null
      @@ -1,96 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_vsnprintf.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: vsnprintf
      - ****************************************************************************/
      -
      -int vsnprintf(FAR char *buf, size_t size, const char *format, va_list ap)
      -{
      -  struct lib_memoutstream_s memoutstream;
      -  int     n;
      -
      -  /* Initialize a memory stream to write to the buffer */
      -
      -  lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, size);
      -
      -  /* Then let lib_vsprintf do the real work */
      -
      -  n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, format, ap);
      -  return n;
      -}
      diff --git a/nuttx/lib/stdio/lib_vsprintf.c b/nuttx/lib/stdio/lib_vsprintf.c
      deleted file mode 100644
      index 5db46664e3..0000000000
      --- a/nuttx/lib/stdio/lib_vsprintf.c
      +++ /dev/null
      @@ -1,92 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_vsprintf.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: vsprintf
      - ****************************************************************************/
      -
      -int vsprintf(FAR char *dest, const char *src, va_list ap)
      -{
      -  struct lib_memoutstream_s memoutstream;
      -
      -  /* Wrap the destination buffer in a stream object and let
      -   * lib/stdio/lib_vsprintf do the work.
      -   */
      -
      -  lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, dest, LIB_BUFLEN_UNKNOWN);
      -  return lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, src, ap);
      -}
      diff --git a/nuttx/lib/stdio/lib_wrflush.c b/nuttx/lib/stdio/lib_wrflush.c
      deleted file mode 100644
      index 39680da6ae..0000000000
      --- a/nuttx/lib/stdio/lib_wrflush.c
      +++ /dev/null
      @@ -1,134 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_wrflush.c
      - *
      - *   Copyright (C) 2008-2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_wrflush
      - *
      - * Description:
      - *   This is simply a version of fflush that does not report an error if
      - *   the file is not open for writing.
      - *
      - ****************************************************************************/
      -
      -int lib_wrflush(FAR FILE *stream)
      -{
      -#if CONFIG_STDIO_BUFFER_SIZE > 0
      -  /* Verify that we were passed a valid (i.e., non-NULL) stream */
      -
      -#ifdef CONFIG_DEBUG
      -  if (!stream)
      -    {
      -      return -EINVAL;
      -    }
      -#endif
      -
      -  /* Verify that the stream is opened for writing... lib_fflush will
      -   * return an error if it is called for a stream that is not opened for
      -   * writing.  Check that first so that this function will not fail in
      -   * that case.
      -   */
      -
      -  if ((stream->fs_oflags & O_WROK) == 0)
      -    {
      -      /* Report that the success was successful if we attempt to flush a
      -       * read-only stream.
      -       */
      -
      -      return OK;
      -    }
      -
      -  /* Flush the stream.   Return success if there is no buffered write data
      -   * -- i.e., that the stream is opened for writing and  that all of the
      -   * buffered write data was successfully flushed by lib_fflush().
      -   */
      -
      -  return lib_fflush(stream, true);
      -#else
      -  /* Verify that we were passed a valid (i.e., non-NULL) stream */
      -
      -#ifdef CONFIG_DEBUG
      -  if (!stream)
      -    {
      -      return -EINVAL;
      -    }
      -#endif
      -
      -  return OK;
      -#endif
      -}
      diff --git a/nuttx/lib/stdio/lib_zeroinstream.c b/nuttx/lib/stdio/lib_zeroinstream.c
      deleted file mode 100644
      index 39a6c22ef3..0000000000
      --- a/nuttx/lib/stdio/lib_zeroinstream.c
      +++ /dev/null
      @@ -1,79 +0,0 @@
      -/****************************************************************************
      - * lib/stdio/lib_zeroinstream.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -static int zeroinstream_getc(FAR struct lib_instream_s *this)
      -{
      -  this->nget++;
      -  return 0;
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_zeroinstream
      - *
      - * Description:
      - *   Initializes a NULL stream.  The initialized stream will return an
      - *   infinitely long stream of zeroes.
      - *
      - * Input parameters:
      - *   zeroinstream  - User allocated, uninitialized instance of struct
      - *                   lib_instream_s to be initialized.
      - *
      - * Returned Value:
      - *   None (User allocated instance initialized).
      - *
      - ****************************************************************************/
      -
      -void lib_zeroinstream(FAR struct lib_instream_s *zeroinstream)
      -{
      -  zeroinstream->get  = zeroinstream_getc;
      -  zeroinstream->nget = 0;
      -}
      -
      diff --git a/nuttx/lib/stdlib/Make.defs b/nuttx/lib/stdlib/Make.defs
      deleted file mode 100644
      index 76e285808a..0000000000
      --- a/nuttx/lib/stdlib/Make.defs
      +++ /dev/null
      @@ -1,44 +0,0 @@
      -############################################################################
      -# lib/stdlib/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the stdlib C files to the build
      -
      -CSRCS += lib_abs.c lib_abort.c lib_imaxabs.c lib_labs.c lib_llabs.c \
      -		  lib_rand.c lib_qsort.c
      -
      -# Add the stdlib directory to the build
      -
      -DEPPATH += --dep-path stdlib
      -VPATH += :stdlib
      diff --git a/nuttx/lib/stdlib/lib_abort.c b/nuttx/lib/stdlib/lib_abort.c
      deleted file mode 100644
      index 84b6009500..0000000000
      --- a/nuttx/lib/stdlib/lib_abort.c
      +++ /dev/null
      @@ -1,121 +0,0 @@
      -/************************************************************************
      - * lib/stdlib/lib_abort.c
      - *
      - *   Copyright (C) 2007, 2009, 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Pre-processor Definitions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Type Declarations
      - ************************************************************************/
      -
      -/************************************************************************
      - * Global Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Variables
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Function Prototypes
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Name: Abort
      - *
      - * Description:
      - *   The abort() first unblocks the SIGABRT signal, and then raises that
      - *   signal for the calling process. This results in the abnormal
      - *   termination of the process unless the SIGABRT signal is caught and
      - *   the signal handler does not return.
      - *
      - *   If the abort() function causes process termination, all open
      - *   streams are closed and flushed.
      - *
      - *   If the SIGABRT signal is ignored, or caught by a handler that
      - *   returns, the abort() function will still terminate the process.
      - *   It does this by restoring the default disposition for SIGABRT and
      - *   then raising the signal for a second time.
      - *
      - * Input parameters:
      - *   None
      - *
      - * Returned Value:
      - *  This function does not return,
      - *
      - ************************************************************************/
      -
      -void abort(void)
      -{
      -  /* NuttX does not support standard signal functionality (like the
      -   * behavior of the SIGABRT signal).  So no attempt is made to provide
      -   * a conformant version of abort() at this time.  This version does not
      -   * signal the calling thread all.
      -   *
      -   * Note that pthread_exit() is called instead of exit().  That is because
      -   * we do no know if abort was called from a pthread or a normal thread
      -   * (we could find out, of course).  If abort() is called from a non-pthread,
      -   * then pthread_exit() should fail and fall back to call exit() anyway.
      -   *
      -   * If exit() is called (either below or via pthread_exit()), then exit()
      -   * will flush and close all open files and terminate the thread.  If this
      -   * function was called from a pthread, then pthread_exit() will complete
      -   * any joins, but will not flush or close any streams.
      -   */
      -
      -#ifdef CONFIG_DISABLE_PTHREAD
      -  exit(EXIT_FAILURE);
      -#else
      -  pthread_exit(NULL);
      -#endif
      -}
      diff --git a/nuttx/lib/stdlib/lib_abs.c b/nuttx/lib/stdlib/lib_abs.c
      deleted file mode 100644
      index 1a0c1671cc..0000000000
      --- a/nuttx/lib/stdlib/lib_abs.c
      +++ /dev/null
      @@ -1,54 +0,0 @@
      -/************************************************************************
      - * lib/stdlib/lib_abs.c
      - *
      - *   Copyright (C) 2010-2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Global Functions
      - ************************************************************************/
      -
      -int abs(int j)
      -{
      -  if (j < 0)
      -    {
      -      j = -j;
      -    }
      -  return j;
      -}
      diff --git a/nuttx/lib/stdlib/lib_imaxabs.c b/nuttx/lib/stdlib/lib_imaxabs.c
      deleted file mode 100644
      index c6e227c7de..0000000000
      --- a/nuttx/lib/stdlib/lib_imaxabs.c
      +++ /dev/null
      @@ -1,54 +0,0 @@
      -/************************************************************************
      - * lib/stdlib//lib_abs.c
      - *
      - *   Copyright (C) 2010-2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Global Functions
      - ************************************************************************/
      -
      -intmax_t imaxabs(intmax_t j)
      -{
      -  if (j < 0)
      -    {
      -      j = -j;
      -    }
      -  return j;
      -}
      diff --git a/nuttx/lib/stdlib/lib_labs.c b/nuttx/lib/stdlib/lib_labs.c
      deleted file mode 100644
      index f7218ee833..0000000000
      --- a/nuttx/lib/stdlib/lib_labs.c
      +++ /dev/null
      @@ -1,54 +0,0 @@
      -/************************************************************************
      - * lib/stdlib/lib_labs.c
      - *
      - *   Copyright (C) 2010-2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Global Functions
      - ************************************************************************/
      -
      -long int labs(long int j)
      -{
      -  if (j < 0)
      -    {
      -      j = -j;
      -    }
      -  return j;
      -}
      diff --git a/nuttx/lib/stdlib/lib_llabs.c b/nuttx/lib/stdlib/lib_llabs.c
      deleted file mode 100644
      index db7d3dbe07..0000000000
      --- a/nuttx/lib/stdlib/lib_llabs.c
      +++ /dev/null
      @@ -1,57 +0,0 @@
      -/************************************************************************
      - * lib/stdlib/lib_llabs.c
      - *
      - *   Copyright (C) 2010-2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Global Functions
      - ************************************************************************/
      -
      -#ifdef CONFIG_HAVE_LONG_LONG
      -long long int llabs(long long int j)
      -{
      -  if (j < 0)
      -    {
      -      j = -j;
      -    }
      -  return j;
      -}
      -#endif
      diff --git a/nuttx/lib/stdlib/lib_qsort.c b/nuttx/lib/stdlib/lib_qsort.c
      deleted file mode 100644
      index 9dd5c00409..0000000000
      --- a/nuttx/lib/stdlib/lib_qsort.c
      +++ /dev/null
      @@ -1,238 +0,0 @@
      -/****************************************************************************
      - * lib/stdlib/lib_qsort.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
      - *   Author: Gregory Nutt 
      - *
      - * Leveraged from:
      - *
      - *  Copyright (c) 1992, 1993
      - *  The Regents of the University of California.  All rights reserved.
      - *
      - * 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. All advertising materials mentioning features or use of this software
      - *    must display the following acknowledgement:
      - *    This product includes software developed by the University of
      - *    California, Berkeley and its contributors.
      - * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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 
      -
      -/****************************************************************************
      - * Preprocessor Definitions
      - ****************************************************************************/
      -
      -#define min(a, b)  (a) < (b) ? a : b
      -
      -#define swapcode(TYPE, parmi, parmj, n) \
      -  { \
      -    long i = (n) / sizeof (TYPE); \
      -    register TYPE *pi = (TYPE *) (parmi); \
      -    register TYPE *pj = (TYPE *) (parmj); \
      -    do { \
      -      register TYPE  t = *pi; \
      -      *pi++ = *pj; \
      -      *pj++ = t; \
      -    } while (--i > 0); \
      -  }
      -
      -#define SWAPINIT(a, size) \
      -  swaptype = ((char *)a - (char *)0) % sizeof(long) || \
      -  size % sizeof(long) ? 2 : size == sizeof(long)? 0 : 1;
      -
      -#define swap(a, b) \
      -  if (swaptype == 0) \
      -    { \
      -      long t = *(long *)(a); \
      -      *(long *)(a) = *(long *)(b); \
      -      *(long *)(b) = t; \
      -    } \
      -  else \
      -    { \
      -      swapfunc(a, b, size, swaptype); \
      -    }
      -
      -#define vecswap(a, b, n) if ((n) > 0) swapfunc(a, b, n, swaptype)
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -static inline void swapfunc(char *a, char *b, int n, int swaptype);
      -static inline char *med3(char *a, char *b, char *c,
      -                         int (*compar)(const void *, const void *));
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -static inline void swapfunc(char *a, char *b, int n, int swaptype)
      -{
      -  if(swaptype <= 1)
      -    {
      -      swapcode(long, a, b, n)
      -    }
      -  else
      -    {
      -      swapcode(char, a, b, n)
      -    }
      -}
      -
      -static inline char *med3(char *a, char *b, char *c,
      -                         int (*compar)(const void *, const void *))
      -{
      -  return compar(a, b) < 0 ?
      -         (compar(b, c) < 0 ? b : (compar(a, c) < 0 ? c : a ))
      -              :(compar(b, c) > 0 ? b : (compar(a, c) < 0 ? a : c ));
      -}
      -
      -/****************************************************************************
      - * Public Function
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: qsort
      - *
      - * Description:
      - *   Qsort routine from Bentley & McIlroy's "Engineering a Sort Function".
      - *
      - ****************************************************************************/
      -
      -void qsort(void *base, size_t nmemb, size_t size,
      -           int(*compar)(const void *, const void *))
      -{
      -  char *pa, *pb, *pc, *pd, *pl, *pm, *pn;
      -  int d, r, swaptype, swap_cnt;
      -
      -loop:
      -  SWAPINIT(base, size);
      -  swap_cnt = 0;
      -  if (nmemb < 7)
      -    {
      -      for (pm = (char *) base + size; pm < (char *) base + nmemb * size; pm += size)
      -        {
      -          for (pl = pm; pl > (char *) base && compar(pl - size, pl) > 0; pl -= size)
      -            {
      -              swap(pl, pl - size);
      -            }
      -        }
      -      return;
      -  }
      -
      -  pm = (char *) base + (nmemb / 2) * size;
      -  if (nmemb > 7)
      -    {
      -      pl = base;
      -      pn = (char *) base + (nmemb - 1) * size;
      -      if (nmemb > 40)
      -        {
      -          d = (nmemb / 8) * size;
      -          pl = med3(pl, pl + d, pl + 2 * d, compar);
      -          pm = med3(pm - d, pm, pm + d, compar);
      -          pn = med3(pn - 2 * d, pn - d, pn, compar);
      -        }
      -      pm = med3(pl, pm, pn, compar);
      -    }
      -  swap(base, pm);
      -  pa = pb = (char *) base + size;
      -
      -  pc = pd = (char *) base + (nmemb - 1) * size;
      -  for (;;)
      -    {
      -      while (pb <= pc && (r = compar(pb, base)) <= 0)
      -        {
      -          if (r == 0)
      -            {
      -              swap_cnt = 1;
      -              swap(pa, pb);
      -              pa += size;
      -            }
      -          pb += size;
      -        }
      -      while (pb <= pc && (r = compar(pc, base)) >= 0)
      -        {
      -          if (r == 0)
      -            {
      -              swap_cnt = 1;
      -              swap(pc, pd);
      -              pd -= size;
      -            }
      -          pc -= size;
      -        }
      -
      -      if (pb > pc)
      -        {
      -          break;
      -        }
      -
      -      swap(pb, pc);
      -      swap_cnt = 1;
      -      pb += size;
      -      pc -= size;
      -    }
      -
      -  if (swap_cnt == 0)
      -    {
      -      /* Switch to insertion sort */
      -
      -      for (pm = (char *) base + size; pm < (char *) base + nmemb * size; pm += size)
      -        {
      -          for (pl = pm; pl > (char *) base && compar(pl - size, pl) > 0; pl -= size)
      -            {
      -              swap(pl, pl - size);
      -            }
      -        }
      -      return;
      -    }
      -
      -  pn = (char *) base + nmemb * size;
      -  r = min(pa - (char *)base, pb - pa);
      -  vecswap(base, pb - r, r);
      -  r = min(pd - pc, pn - pd - size);
      -  vecswap(pb, pn - r, r);
      -
      -  if ((r = pb - pa) > size)
      -    {
      -      qsort(base, r / size, size, compar);
      -    }
      -
      -  if ((r = pd - pc) > size)
      -    {
      -      /* Iterate rather than recurse to save stack space */
      -      base = pn - r;
      -      nmemb = r / size;
      -      goto loop;
      -    }
      -}
      -
      diff --git a/nuttx/lib/stdlib/lib_rand.c b/nuttx/lib/stdlib/lib_rand.c
      deleted file mode 100644
      index 7227c52d0d..0000000000
      --- a/nuttx/lib/stdlib/lib_rand.c
      +++ /dev/null
      @@ -1,220 +0,0 @@
      -/************************************************************
      - * lib/stdlib/lib_rand.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -#include 
      -
      -/************************************************************
      - * Definitions
      - ************************************************************/
      -
      -#ifndef CONFIG_LIB_RAND_ORDER
      -#define CONFIG_LIB_RAND_ORDER 1
      -#endif
      -
      -/* Values needed by the random number generator */
      -
      -#define RND1_CONSTK  470001
      -#define RND1_CONSTP  999563
      -#define RND2_CONSTK1 366528
      -#define RND2_CONSTK2 508531
      -#define RND2_CONSTP  998917
      -#define RND3_CONSTK1 360137
      -#define RND3_CONSTK2 519815
      -#define RND3_CONSTK3 616087
      -#define RND3_CONSTP  997783
      -
      -#if CONFIG_LIB_RAND_ORDER == 1
      -# define RND_CONSTP RND1_CONSTP
      -#elif CONFIG_LIB_RAND_ORDER == 2
      -# define RND_CONSTP RND2_CONSTP
      -#else
      -# define RND_CONSTP RND3_CONSTP
      -#endif
      -
      -/************************************************************
      - * Private Type Declarations
      - ************************************************************/
      -
      -/************************************************************
      - * Private Function Prototypes
      - ************************************************************/
      -
      -static unsigned int nrand(unsigned int nLimit);
      -static double_t frand1(void);
      -#if (CONFIG_LIB_RAND_ORDER > 1)
      -static double_t frand2(void);
      -#if (CONFIG_LIB_RAND_ORDER > 2)
      -static double_t frand3(void);
      -#endif
      -#endif
      -
      -/**********************************************************
      - * Global Constant Data
      - **********************************************************/
      -
      -/************************************************************
      - * Global Variables
      - ************************************************************/
      -
      -/**********************************************************
      - * Private Constant Data
      - **********************************************************/
      -
      -/************************************************************
      - * Private Variables
      - ************************************************************/
      -
      -static unsigned long g_nRandInt1;
      -#if (CONFIG_LIB_RAND_ORDER > 1)
      -static unsigned long g_nRandInt2;
      -#if (CONFIG_LIB_RAND_ORDER > 2)
      -static unsigned long g_nRandInt3;
      -#endif
      -#endif
      -
      -/************************************************************
      - * Private Functions
      - ************************************************************/
      - 
      -static unsigned int nrand(unsigned int nLimit)
      -{
      -  unsigned long nResult;
      -  double_t fRatio;
      -
      -  /* Loop to be sure a legal random number is generated */
      -  do {
      -
      -    /* Get a random integer in the requested range */
      -#if (CONFIG_LIB_RAND_ORDER == 1)
      -    fRatio = frand1();
      -#elif (CONFIG_LIB_RAND_ORDER == 2)
      -    fRatio = frand2();
      -#else
      -    fRatio = frand3();
      -#endif
      -
      -    /* Then, produce the return-able value */
      -    nResult = (unsigned long)(((double_t)nLimit) * fRatio);
      -
      -  } while (nResult >= (unsigned long)nLimit);
      -
      -  return (unsigned int)nResult;
      -
      -} /* end nrand */
      -
      -static double_t frand1(void)
      -{
      -  unsigned long nRandInt;
      -
      -  /* First order congruential generator */
      -  nRandInt = (RND1_CONSTK * g_nRandInt1) % RND1_CONSTP;
      -  g_nRandInt1 = nRandInt;
      -
      -  /* Construct an floating point value in the range from 0.0 up to 1.0 */
      -  return ((double_t)nRandInt) / ((double_t)RND_CONSTP);
      -
      -} /* end frand */
      -
      -#if (CONFIG_LIB_RAND_ORDER > 1)
      -static double_t frand2(void)
      -{
      -  unsigned long nRandInt;
      -
      -  /* Second order congruential generator */
      -  nRandInt = (RND2_CONSTK1 * g_nRandInt1 + RND2_CONSTK2 * g_nRandInt2) %
      -    RND2_CONSTP;
      -  g_nRandInt2 = g_nRandInt1;
      -  g_nRandInt1 = nRandInt;
      -
      -  /* Construct an floating point value in the range from 0.0 up to 1.0 */
      -  return ((double_t)nRandInt) / ((double_t)RND_CONSTP);
      -
      -} /* end frand */
      -
      -#if (CONFIG_LIB_RAND_ORDER > 2)
      -static double_t frand3(void)
      -{
      -  unsigned long nRandInt;
      -
      -  /* Third order congruential generator */
      -  nRandInt = (RND3_CONSTK1 * g_nRandInt1 + RND3_CONSTK2 * g_nRandInt2 +
      -	      RND3_CONSTK2 * g_nRandInt3) % RND3_CONSTP;
      -  g_nRandInt3 = g_nRandInt2;
      -  g_nRandInt2 = g_nRandInt1;
      -  g_nRandInt1 = nRandInt;
      -
      -  /* Construct an floating point value in the range from 0.0 up to 1.0 */
      -  return ((double_t)nRandInt) / ((double_t)RND_CONSTP);
      -
      -} /* end frand */
      -#endif
      -#endif
      -
      -/************************************************************
      - * Public Functions
      - ************************************************************/
      -/************************************************************
      - * Function:  srand, rand
      - ************************************************************/
      -
      -void srand(unsigned int seed)
      -{
      -  g_nRandInt1 = seed;
      -#if (CONFIG_LIB_RAND_ORDER > 1)
      -  g_nRandInt2 = seed;
      -  (void)frand1();
      -#if (CONFIG_LIB_RAND_ORDER > 2)
      -  g_nRandInt3 = seed;
      -  (void)frand2();
      -#endif
      -#endif
      -
      -} /* end srand */
      -
      -int rand(void)
      -{
      -  return (int)nrand(32768);
      -
      -} /* end rand */
      -
      diff --git a/nuttx/lib/string/Make.defs b/nuttx/lib/string/Make.defs
      deleted file mode 100644
      index 191b9ffea5..0000000000
      --- a/nuttx/lib/string/Make.defs
      +++ /dev/null
      @@ -1,58 +0,0 @@
      -############################################################################
      -# lib/string/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the string C files to the build
      -
      -CSRCS += lib_checkbase.c lib_isbasedigit.c lib_memset.c lib_memchr.c \
      -		 lib_memccpy.c lib_memcmp.c lib_memmove.c lib_skipspace.c \
      -		 lib_strcasecmp.c lib_strcat.c lib_strchr.c lib_strcpy.c lib_strcmp.c \
      -		 lib_strcspn.c lib_strdup.c lib_strerror.c lib_strlen.c lib_strnlen.c \
      -		 lib_strncasecmp.c lib_strncat.c lib_strncmp.c lib_strncpy.c \
      -		 lib_strndup.c lib_strcasestr.c lib_strpbrk.c lib_strrchr.c\
      -		 lib_strspn.c lib_strstr.c lib_strtok.c lib_strtokr.c lib_strtol.c \
      -		 lib_strtoll.c lib_strtoul.c lib_strtoull.c lib_strtod.c
      -
      -ifneq ($(CONFIG_ARCH_MEMCPY),y)
      -ifeq ($(CONFIG_MEMCPY_VIK),y)
      -CSRCS += lib_vikmemcpy.c
      -else
      -CSRCS += lib_memcpy.c
      -endif
      -endif
      -
      -# Add the string directory to the build
      -
      -DEPPATH += --dep-path string
      -VPATH += :string
      diff --git a/nuttx/lib/string/lib_checkbase.c b/nuttx/lib/string/lib_checkbase.c
      deleted file mode 100644
      index bc79ab2cec..0000000000
      --- a/nuttx/lib/string/lib_checkbase.c
      +++ /dev/null
      @@ -1,115 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_checkbase.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_checkbase
      - *
      - * Description:
      - *   This is part of the strol() family implementation.  This function checks
      - *   the initial part of a string to see if it can determine the numeric
      - *   base that is represented.
      - *
      - * Assumptions:
      - *   *ptr points to the first, non-whitespace character in the string.
      - *
      - ****************************************************************************/
      - 
      -int lib_checkbase(int base, const char **pptr)
      -{
      -   const char *ptr = *pptr;
      -
      -  /* Check for unspecified base */
      -
      -  if (!base)
      -    {
      -      /* Assume base 10 */
      -
      -      base = 10;
      -
      -      /* Check for leading '0' - that would signify octal or hex (or binary) */
      -
      -      if (*ptr == '0')
      -        {
      -          /* Assume octal */
      -
      -          base = 8;
      -          ptr++;
      -
      -          /* Check for hexidecimal */
      -
      -          if ((*ptr == 'X' || *ptr == 'x') && 
      -              lib_isbasedigit(ptr[1], 16, NULL))
      -            {
      -              base = 16;
      -              ptr++;
      -            }
      -        }
      -    }
      -
      -  /* If it a hexidecimal representation, than discard any leading "0X" or "0x" */
      -
      -  else if (base == 16)
      -    {
      -      if (ptr[0] == '0' && (ptr[1] == 'X' || ptr[1] == 'x'))
      -        {
      -          ptr += 2;
      -        }
      -    }
      -
      -  /* Return the updated pointer and base */
      -
      -  *pptr = ptr;
      -  return base;
      -}
      -
      diff --git a/nuttx/lib/string/lib_isbasedigit.c b/nuttx/lib/string/lib_isbasedigit.c
      deleted file mode 100644
      index a2421bf2a4..0000000000
      --- a/nuttx/lib/string/lib_isbasedigit.c
      +++ /dev/null
      @@ -1,105 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_isbasedigit.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_isbasedigit
      - *
      - * Description:
      - *   Given an ASCII character, ch, and a base (1-36) do two
      - *   things:  1) Determine if ch is a valid charcter, and 2)
      - *   convert ch to its binary value.
      - *
      - ****************************************************************************/
      -
      -bool lib_isbasedigit(int ch, int base, int *value)
      -{
      -  bool ret = false;
      -  int  tmp = 0;
      -
      -  if (base <= 10)
      -    {
      -      if (ch >= '0' && ch <= base + '0' - 1)
      -        {
      -          tmp = ch - '0';
      -          ret = true;
      -        }
      -    }
      -  else if (base <= 36)
      -    {
      -      if (ch >= '0' && ch <= '9')
      -        {
      -          tmp = ch - '0';
      -          ret = true;
      -        }
      -      else if (ch >= 'a' && ch <= 'a' + base - 11)
      -        {
      -          tmp = ch - 'a' + 10;
      -          ret = true;
      -        }
      -      else if (ch >= 'A' && ch <= 'A' + base - 11)
      -        {
      -          tmp = ch - 'A' + 10;
      -          ret = true;
      -        }
      -    }
      -
      -  if (value)
      -    {
      -      *value = tmp;
      -    }
      -  return ret;
      -}
      -
      -
      diff --git a/nuttx/lib/string/lib_memccpy.c b/nuttx/lib/string/lib_memccpy.c
      deleted file mode 100644
      index 1f3dbb52dd..0000000000
      --- a/nuttx/lib/string/lib_memccpy.c
      +++ /dev/null
      @@ -1,99 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_memccpy.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -
      -/****************************************************************************
      - * Name: memccpy
      - *
      - * Description:
      - *   The memccpy() function copies bytes from memory area s2 into s1,
      - *   stopping after the first occurrence of byte c (converted to an unsigned
      - *   char) is copied, or after n bytes are copied, whichever comes first. If
      - *   copying takes place between objects that overlap, the behavior is
      - *   undefined.
      - *
      - * Returned Value:
      - *   The memccpy() function returns a pointer to the byte after the copy of c
      - *   in s1, or a null pointer if c was not found in the first n bytes of s2.
      - *
      - ****************************************************************************/
      -
      -FAR void *memccpy(FAR void *s1, FAR const void *s2, int c, size_t n)
      -{
      -  FAR unsigned char *pout = (FAR unsigned char*)s1;
      -  FAR unsigned char *pin  = (FAR unsigned char*)s2;
      -
      -  /* Copy at most n bytes */
      -
      -  while (n-- > 0)
      -    {
      -      /* Copy one byte */
      -
      -      *pout = *pin++;
      -
      -      /* Did we just copy the terminating byte c? */
      -
      -      if (*pout == (unsigned char)c)
      -        {
      -          /* Yes return a pointer to the byte after the copy of c into s1 */
      -
      -          return (FAR void *)pout;
      -        }
      -
      -      /* No increment to the next destination location */
      -
      -      pout++;
      -    }
      -
      -  /* C was not found in the first n bytes of s2 */
      -
      -  return NULL;
      -}
      diff --git a/nuttx/lib/string/lib_memchr.c b/nuttx/lib/string/lib_memchr.c
      deleted file mode 100644
      index e0dec82700..0000000000
      --- a/nuttx/lib/string/lib_memchr.c
      +++ /dev/null
      @@ -1,80 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_memchr.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: memchr
      - *
      - * Description:
      - *   The memchr() function locates the first occurrence of 'c' (converted to
      - *   an unsigned char) in the initial 'n' bytes (each interpreted as
      - *   unsigned char) of the object pointed to by s.
      - *
      - * Returned Value:
      - *   The memchr() function returns a pointer to the located byte, or a null
      - *   pointer if the byte does not occur in the object.
      - *
      - ****************************************************************************/
      -
      -FAR void *memchr(FAR const void *s, int c, size_t n)
      -{
      -  FAR const unsigned char *p = (FAR const unsigned char *)s;
      -
      -  if (s)
      -    {
      -      while (n--)
      -        {
      -          if (*p == (unsigned char)c)
      -            {
      -              return (FAR void *)p;
      -            }
      -
      -          p++;
      -        }
      -    }
      -
      -  return NULL;
      -}
      diff --git a/nuttx/lib/string/lib_memcmp.c b/nuttx/lib/string/lib_memcmp.c
      deleted file mode 100644
      index eb2e1fd125..0000000000
      --- a/nuttx/lib/string/lib_memcmp.c
      +++ /dev/null
      @@ -1,74 +0,0 @@
      -/************************************************************
      - * lib/string/lib_memcmp.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************
      - * Global Functions
      - ************************************************************/
      -
      -#ifndef CONFIG_ARCH_MEMCMP
      -int memcmp(const void *s1, const void *s2, size_t n)
      -{
      -  unsigned char *p1 = (unsigned char *)s1;
      -  unsigned char *p2 = (unsigned char *)s2;
      -
      -  while (n-- > 0)
      -    {
      -      if (*p1 < *p2)
      -        {
      -          return -1;
      -        }
      -      else if (*p1 > *p2)
      -        {
      -          return 1;
      -        }
      -
      -      p1++;
      -      p2++;
      -    }
      -  return 0;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_memcpy.c b/nuttx/lib/string/lib_memcpy.c
      deleted file mode 100644
      index 3b62edbabd..0000000000
      --- a/nuttx/lib/string/lib_memcpy.c
      +++ /dev/null
      @@ -1,64 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_memcpy.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: memcpy
      - ****************************************************************************/
      -
      -#ifndef CONFIG_ARCH_MEMCPY
      -FAR void *memcpy(FAR void *dest, FAR const void *src, size_t n)
      -{
      -  FAR unsigned char *pout = (FAR unsigned char*)dest;
      -  FAR unsigned char *pin  = (FAR unsigned char*)src;
      -  while (n-- > 0) *pout++ = *pin++;
      -  return dest;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_memmove.c b/nuttx/lib/string/lib_memmove.c
      deleted file mode 100644
      index 85cb79e174..0000000000
      --- a/nuttx/lib/string/lib_memmove.c
      +++ /dev/null
      @@ -1,77 +0,0 @@
      -/************************************************************
      - * lib/string/lib_memmove.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Compilation Switches
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************
      - * Global Functions
      - ************************************************************/
      -
      -#ifndef CONFIG_ARCH_MEMMOVE
      -void *memmove(void *dest, const void *src, size_t count)
      -{
      -  char *tmp, *s;
      -  if (dest <= src)
      -    {
      -      tmp = (char*) dest;
      -      s   = (char*) src;
      -      while (count--)
      -        {
      -	  *tmp++ = *s++;
      -        }
      -    }
      -  else
      -    {
      -      tmp = (char*) dest + count;
      -      s   = (char*) src + count;
      -      while (count--)
      -        {
      -	  *--tmp = *--s;
      -        }
      -    }
      -
      -  return dest;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_memset.c b/nuttx/lib/string/lib_memset.c
      deleted file mode 100644
      index 31c386e928..0000000000
      --- a/nuttx/lib/string/lib_memset.c
      +++ /dev/null
      @@ -1,188 +0,0 @@
      -
      -/****************************************************************************
      - * lib/string/lib_memset.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ****************************************************************************/
      -
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/* Can't support CONFIG_MEMSET_64BIT if the platform does not have 64-bit
      - * integer types.
      - */
      -
      -#ifndef CONFIG_HAVE_LONG_LONG
      -#  undef CONFIG_MEMSET_64BIT
      -#endif
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -#ifndef CONFIG_ARCH_MEMSET
      -void *memset(void *s, int c, size_t n)
      -{
      -#ifdef CONFIG_MEMSET_OPTSPEED
      -  /* This version is optimized for speed (you could do better
      -   * still by exploiting processor caching or memory burst
      -   * knowledge.)
      -   */
      -
      -  uintptr_t addr  = (uintptr_t)s;
      -  uint16_t  val16 = ((uint16_t)c << 8) | (uint16_t)c;
      -  uint32_t  val32 = ((uint32_t)val16 << 16) | (uint32_t)val16;
      -#ifdef CONFIG_MEMSET_64BIT
      -  uint64_t  val64 = ((uint64_t)val32 << 32) | (uint64_t)val32;
      -#endif
      -
      -  /* Make sure that there is something to be cleared */
      -
      -  if (n > 0)
      -    {
      -      /* Align to a 16-bit boundary */
      -
      -      if ((addr & 1) != 0)
      -        {
      -          *(uint8_t*)addr = (uint8_t)c;
      -          addr += 1;
      -          n    -= 1;
      -        }
      -
      -      /* Check if there are at least 16-bits left to be written */
      -
      -      if (n >= 2)
      -        {
      -          /* Align to a 32-bit boundary (we know that the destination
      -           * address is already aligned to at least a 16-bit boundary).
      -           */
      -
      -          if ((addr & 3) != 0)
      -            {
      -              *(uint16_t*)addr = val16;
      -              addr += 2;
      -              n    -= 2;
      -            }
      -
      -#ifndef CONFIG_MEMSET_64BIT
      -          /* Loop while there are at least 32-bits left to be written */
      -
      -          while (n >= 4)
      -            {
      -              *(uint32_t*)addr = val32;
      -              addr += 4;
      -              n    -= 4;
      -            }
      -#else
      -          /* Check if there are at least 32-bits left to be written */
      -
      -          if (n >= 4)
      -            {
      -              /* Align to a 64-bit boundary (we know that the destination
      -               * address is already aligned to at least a 32-bit boundary).
      -               */
      -
      -              if ((addr & 7) != 0)
      -                {
      -                  *(uint32_t*)addr = val32;
      -                  addr += 4;
      -                  n    -= 4;
      -                }
      -
      -              /* Loop while there are at least 64-bits left to be written */
      -
      -              while (n >= 8)
      -                {
      -                  *(uint64_t*)addr = val64;
      -                  addr += 8;
      -                  n    -= 8;
      -                }
      -            }
      -#endif
      -        }
      -
      -#ifdef CONFIG_MEMSET_64BIT
      -      /* We may get here with n in the range 0..7.  If n >= 4, then we should
      -       * have 64-bit alignment.
      -       */
      -
      -      if (n >= 4)
      -        {
      -          *(uint32_t*)addr = val32;
      -          addr += 4;
      -          n    -= 4;
      -        }
      -#endif
      -
      -      /* We may get here under the following conditions:
      -       *
      -       *   n = 0, addr may or may not be aligned
      -       *   n = 1, addr is aligned to at least a 16-bit boundary
      -       *   n = 2, addr is aligned to a 32-bit boundary
      -       *   n = 3, addr is aligned to a 32-bit boundary
      -       */
      -
      -      if (n >= 2)
      -        {
      -          *(uint16_t*)addr = val16;
      -          addr += 2;
      -          n    -= 2;
      -        }
      -
      -      if (n >= 1)
      -        {
      -          *(uint8_t*)addr = (uint8_t)c;
      -        }
      -    }
      -#else
      -  /* This version is optimized for size */
      -
      -  unsigned char *p = (unsigned char*)s;
      -  while (n-- > 0) *p++ = c;
      -#endif
      -  return s;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_skipspace.c b/nuttx/lib/string/lib_skipspace.c
      deleted file mode 100644
      index b4e6588e59..0000000000
      --- a/nuttx/lib/string/lib_skipspace.c
      +++ /dev/null
      @@ -1,69 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_skipspace.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: lib_skipspace
      - *
      - * Description:
      - *   Skip over leading whitespace
      - *
      - ****************************************************************************/
      -
      -void lib_skipspace(const char **pptr)
      -{
      -   const char *ptr = *pptr;
      -   while (isspace(*ptr)) ptr++;
      -   *pptr = ptr;
      -}
      -
      -
      diff --git a/nuttx/lib/string/lib_strcasecmp.c b/nuttx/lib/string/lib_strcasecmp.c
      deleted file mode 100644
      index d4aa8cc031..0000000000
      --- a/nuttx/lib/string/lib_strcasecmp.c
      +++ /dev/null
      @@ -1,65 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strcasecmp.c
      - *
      - *   Copyright (C) 2008-2009, 2011 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.
      - *
      - *****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - *****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Public Functions
      - *****************************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRCMP
      -int strcasecmp(const char *cs, const char *ct)
      -{
      -  int result;
      -  for (;;)
      -    {
      -      if ((result = (int)toupper(*cs) - (int)toupper(*ct)) != 0 || !*cs)
      -        {
      -          break;
      -        }
      -
      -      cs++;
      -      ct++;
      -    }
      -  return result;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strcasestr.c b/nuttx/lib/string/lib_strcasestr.c
      deleted file mode 100644
      index 23f0ab57e6..0000000000
      --- a/nuttx/lib/string/lib_strcasestr.c
      +++ /dev/null
      @@ -1,134 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strstr.c
      - *
      - *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      - *   Author: Gregory Nutt 
      - *
      - * Redistribution and use str 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 str binary form must reproduce the above copyright
      - *    notice, this list of conditions and the following disclaimer str
      - *    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 
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -static FAR char *strcasechr(FAR const char *s, int uc)
      -{
      -  register char ch;
      -
      -  if (s)
      -    {
      -      for (; *s; s++)
      -        {
      -          ch = *s;
      -          if (toupper(ch) == uc)
      -            {
      -              return (FAR char*)s;
      -            }
      -        }
      -    }
      -
      -  return NULL;
      -}
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -FAR char *strcasestr(FAR const char *str, FAR const char *substr)
      -{
      -  const char *candidate;  /* Candidate in str with matching start character */
      -  char         ch;        /* First character of the substring */
      -  int          len;       /* The length of the substring */
      -
      -  /* Special case the empty substring */
      -
      -  len = strlen(substr);
      -  ch  = *substr;
      -
      -  if (!ch)
      -    {
      -      /* We'll say that an empty substring matches at the beginning of
      -       * the string
      -       */
      -
      -      return (char*)str;
      -    }
      -
      -  /* Search for the substring */
      -
      -  candidate = str;
      -  ch        = toupper(ch);
      -
      -  for (;;)
      -    {
      -      /* strcasechr() will return a pointer to the next occurrence of the
      -       * character ch in the string (ignoring case)
      -       */
      -
      -      candidate = strcasechr(candidate, ch);
      -      if (!candidate || strlen(candidate) < len)
      -        {
      -           /* First character of the substring does not appear in the string
      -            * or the remainder of the string is not long enough to contain the
      -            * substring.
      -            */
      -
      -           return NULL;
      -        }
      -
      -      /* Check if this is the beginning of a matching substring (ignoring case) */
      -
      -      if (strncasecmp(candidate, substr, len) == 0)
      -        {
      -           /* Yes.. return the pointer to the first occurrence of the matching
      -            * substring.
      -            */
      -
      -           return (char*)candidate;
      -        }
      -
      -      /* No, find the next candidate after this one */
      -
      -      candidate++;
      -    }
      -
      -  /* Won't get here, but some compilers might complain */
      -
      -  return NULL;
      -}
      -
      diff --git a/nuttx/lib/string/lib_strcat.c b/nuttx/lib/string/lib_strcat.c
      deleted file mode 100644
      index 20350fec07..0000000000
      --- a/nuttx/lib/string/lib_strcat.c
      +++ /dev/null
      @@ -1,62 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strcat.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRCAT
      -char *strcat(char *dest, const char *src)
      -{
      -  char *ret   = dest;
      -
      -  dest  += strlen(dest);
      -  while (*src != '\0')
      -    {
      -      *dest++ = *src++;
      -    }
      -  *dest = '\0';
      -
      -  return ret;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strchr.c b/nuttx/lib/string/lib_strchr.c
      deleted file mode 100644
      index d0bd22a0ea..0000000000
      --- a/nuttx/lib/string/lib_strchr.c
      +++ /dev/null
      @@ -1,78 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strchr.c
      - *
      - *   Copyright (C) 2007, 2009, 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: strchr
      - *
      - * Description:
      - *   The strchr() function locates the first occurrence of 'c' (converted to
      - *   a char) in the string pointed to by 's'. The terminating null byte is
      - *   considered to be part of the string.
      - *
      - * Returned Value:
      - *   Upon completion, strchr() returns a pointer to the byte, or a null
      - *   pointer if the byte was not found.
      - *
      - ****************************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRCHR
      -FAR char *strchr(FAR const char *s, int c)
      -{
      -  if (s)
      -    {
      -      for (; *s; s++)
      -        {
      -          if (*s == c)
      -            {
      -              return (FAR char *)s;
      -            }
      -        }
      -    }
      -
      -  return NULL;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strcmp.c b/nuttx/lib/string/lib_strcmp.c
      deleted file mode 100644
      index 0e3eee8900..0000000000
      --- a/nuttx/lib/string/lib_strcmp.c
      +++ /dev/null
      @@ -1,59 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strcmp.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - *****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - *****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Public Functions
      - *****************************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRCMP
      -int strcmp(const char *cs, const char *ct)
      -{
      -  register signed char result;
      -  for (;;)
      -    {
      -      if ((result = *cs - *ct++) != 0 || !*cs++)
      -	break;
      -    }
      -  return result;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strcpy.c b/nuttx/lib/string/lib_strcpy.c
      deleted file mode 100644
      index e2f70b94e3..0000000000
      --- a/nuttx/lib/string/lib_strcpy.c
      +++ /dev/null
      @@ -1,55 +0,0 @@
      -/************************************************************************
      - * lib/string/lib_strcpy.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Global Functions
      - ************************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRCPY
      -char *strcpy(char *dest, const char *src)
      -{
      -  char *tmp = dest;
      -  while ((*dest++ = *src++) != '\0');
      -  return tmp;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strcspn.c b/nuttx/lib/string/lib_strcspn.c
      deleted file mode 100644
      index 9da89241c5..0000000000
      --- a/nuttx/lib/string/lib_strcspn.c
      +++ /dev/null
      @@ -1,67 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strcspn.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: strcspn
      - *
      - * Description:
      - *  strspn() calculates the length of the initial segment of s which
      - *  consists entirely of characters not in reject
      - *
      - ****************************************************************************/
      -
      -size_t strcspn(const char *s, const char *reject)
      -{
      -  size_t i;
      -  for (i = 0; s[i] && strchr(reject, s[i]) == NULL; i++);
      -  return i;
      -}
      -
      diff --git a/nuttx/lib/string/lib_strdup.c b/nuttx/lib/string/lib_strdup.c
      deleted file mode 100644
      index 44a0cbc0d8..0000000000
      --- a/nuttx/lib/string/lib_strdup.c
      +++ /dev/null
      @@ -1,62 +0,0 @@
      -/************************************************************************
      - * lib/string//lib_strdup.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/************************************************************************
      - * Global Functions
      - ************************************************************************/
      -
      -FAR char *strdup(const char *s)
      -{
      -  FAR char *news = NULL;
      -  if (s)
      -    {
      -      news = (FAR char*)lib_malloc(strlen(s) + 1);
      -      if (news)
      -        {
      -          strcpy(news, s);
      -        }
      -    }
      -  return news;
      -}
      diff --git a/nuttx/lib/string/lib_strerror.c b/nuttx/lib/string/lib_strerror.c
      deleted file mode 100644
      index 249f695c1b..0000000000
      --- a/nuttx/lib/string/lib_strerror.c
      +++ /dev/null
      @@ -1,375 +0,0 @@
      -/************************************************************************
      - * lib/string/lib_strerror.c
      - *
      - *   Copyright (C) 2007, 2009, 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************************
      - * Definitions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Private Types
      - ************************************************************************/
      -
      -struct errno_strmap_s
      -{
      -  uint8_t     errnum;
      -  const char *str;
      -};
      -
      -/************************************************************************
      - * Private Data
      - ************************************************************************/
      -
      -#ifdef CONFIG_LIBC_STRERROR
      -
      -/* This table maps all error numbers to descriptive strings.
      - * The only assumption that the code makes with regard to this
      - * this table is that it is ordered by error number.
      - *
      - * The size of this table is quite large.  Its size can be
      - * reduced by eliminating some of the more obscure error
      - * strings.
      - */
      -
      -#ifndef CONFIG_LIBC_STRERROR_SHORT
      -
      -static const struct errno_strmap_s g_errnomap[] =
      -{
      -  { EPERM,               EPERM_STR           },
      -  { ENOENT,              ENOENT_STR          },
      -  { ESRCH,               ESRCH_STR           },
      -  { EINTR,               EINTR_STR           },
      -  { EIO,                 EIO_STR             },
      -  { ENXIO,               ENXIO_STR           },
      -  { E2BIG,               E2BIG_STR           },
      -  { ENOEXEC,             ENOEXEC_STR         },
      -  { EBADF,               EBADF_STR           },
      -  { ECHILD,              ECHILD_STR          },
      -  { EAGAIN,              EAGAIN_STR          },
      -  { ENOMEM,              ENOMEM_STR          },
      -  { EACCES,              EACCES_STR          },
      -  { EFAULT,              EFAULT_STR          },
      -  { ENOTBLK,             ENOTBLK_STR         },
      -  { EBUSY,               EBUSY_STR           },
      -  { EEXIST,              EEXIST_STR          },
      -  { EXDEV,               EXDEV_STR           },
      -  { ENODEV,              ENODEV_STR          },
      -  { ENOTDIR,             ENOTDIR_STR         },
      -  { EISDIR,              EISDIR_STR          },
      -  { EINVAL,              EINVAL_STR          },
      -  { ENFILE,              ENFILE_STR          },
      -  { EMFILE,              EMFILE_STR          },
      -  { ENOTTY,              ENOTTY_STR          },
      -  { ETXTBSY,             ETXTBSY_STR         },
      -  { EFBIG,               EFBIG_STR           },
      -  { ENOSPC,              ENOSPC_STR          },
      -  { ESPIPE,              ESPIPE_STR          },
      -  { EROFS,               EROFS_STR           },
      -  { EMLINK,              EMLINK_STR          },
      -  { EPIPE,               EPIPE_STR           },
      -  { EDOM,                EDOM_STR            },
      -  { ERANGE,              ERANGE_STR          },
      -  { EDEADLK,             EDEADLK_STR         },
      -  { ENAMETOOLONG,        ENAMETOOLONG_STR    },
      -  { ENOLCK,              ENOLCK_STR          },
      -  { ENOSYS,              ENOSYS_STR          },
      -  { ENOTEMPTY,           ENOTEMPTY_STR       },
      -  { ELOOP,               ELOOP_STR           },
      -  { ENOMSG,              ENOMSG_STR          },
      -  { EIDRM,               EIDRM_STR           },
      -  { ECHRNG,              ECHRNG_STR          },
      -  { EL2NSYNC,            EL2NSYNC_STR        },
      -  { EL3HLT,              EL3HLT_STR          },
      -  { EL3RST,              EL3RST_STR          },
      -  { ELNRNG,              ELNRNG_STR          },
      -  { EUNATCH,             EUNATCH_STR         },
      -  { ENOCSI,              ENOCSI_STR          },
      -  { EL2HLT,              EL2HLT_STR          },
      -  { EBADE,               EBADE_STR           },
      -  { EBADR,               EBADR_STR           },
      -  { EXFULL,              EXFULL_STR          },
      -  { ENOANO,              ENOANO_STR          },
      -  { EBADRQC,             EBADRQC_STR         },
      -  { EBADSLT,             EBADSLT_STR         },
      -  { EBFONT,              EBFONT_STR          },
      -  { ENOSTR,              ENOSTR_STR          },
      -  { ENODATA,             ENODATA_STR         },
      -  { ETIME,               ETIME_STR           },
      -  { ENOSR,               ENOSR_STR           },
      -  { ENONET,              ENONET_STR          },
      -  { ENOPKG,              ENOPKG_STR          },
      -  { EREMOTE,             EREMOTE_STR         },
      -  { ENOLINK,             ENOLINK_STR         },
      -  { EADV,                EADV_STR            },
      -  { ESRMNT,              ESRMNT_STR          },
      -  { ECOMM,               ECOMM_STR           },
      -  { EPROTO,              EPROTO_STR          },
      -  { EMULTIHOP,           EMULTIHOP_STR       },
      -  { EDOTDOT,             EDOTDOT_STR         },
      -  { EBADMSG,             EBADMSG_STR         },
      -  { EOVERFLOW,           EOVERFLOW_STR       },
      -  { ENOTUNIQ,            ENOTUNIQ_STR        },
      -  { EBADFD,              EBADFD_STR          },
      -  { EREMCHG,             EREMCHG_STR         },
      -  { ELIBACC,             ELIBACC_STR         },
      -  { ELIBBAD,             ELIBBAD_STR         },
      -  { ELIBSCN,             ELIBSCN_STR         },
      -  { ELIBMAX,             ELIBMAX_STR         },
      -  { ELIBEXEC,            ELIBEXEC_STR        },
      -  { EILSEQ,              EILSEQ_STR          },
      -  { ERESTART,            ERESTART_STR        },
      -  { ESTRPIPE,            ESTRPIPE_STR        },
      -  { EUSERS,              EUSERS_STR          },
      -  { ENOTSOCK,            ENOTSOCK_STR        },
      -  { EDESTADDRREQ,        EDESTADDRREQ_STR    },
      -  { EMSGSIZE,            EMSGSIZE_STR        },
      -  { EPROTOTYPE,          EPROTOTYPE_STR      },
      -  { ENOPROTOOPT,         ENOPROTOOPT_STR     },
      -  { EPROTONOSUPPORT,     EPROTONOSUPPORT_STR },
      -  { ESOCKTNOSUPPORT,     ESOCKTNOSUPPORT_STR },
      -  { EOPNOTSUPP,          EOPNOTSUPP_STR      },
      -  { EPFNOSUPPORT,        EPFNOSUPPORT_STR    },
      -  { EAFNOSUPPORT,        EAFNOSUPPORT_STR    },
      -  { EADDRINUSE,          EADDRINUSE_STR      },
      -  { EADDRNOTAVAIL,       EADDRNOTAVAIL_STR   },
      -  { ENETDOWN,            ENETDOWN_STR        },
      -  { ENETUNREACH,         ENETUNREACH_STR     },
      -  { ENETRESET,           ENETRESET_STR       },
      -  { ECONNABORTED,        ECONNABORTED_STR    },
      -  { ECONNRESET,          ECONNRESET_STR      },
      -  { ENOBUFS,             ENOBUFS_STR         },
      -  { EISCONN,             EISCONN_STR         },
      -  { ENOTCONN,            ENOTCONN_STR        },
      -  { ESHUTDOWN,           ESHUTDOWN_STR       },
      -  { ETOOMANYREFS,        ETOOMANYREFS_STR    },
      -  { ETIMEDOUT,           ETIMEDOUT_STR       },
      -  { ECONNREFUSED,        ECONNREFUSED_STR    },
      -  { EHOSTDOWN,           EHOSTDOWN_STR       },
      -  { EHOSTUNREACH,        EHOSTUNREACH_STR    },
      -  { EALREADY,            EALREADY_STR        },
      -  { EINPROGRESS,         EINPROGRESS_STR     },
      -  { ESTALE,              ESTALE_STR          },
      -  { EUCLEAN,             EUCLEAN_STR         },
      -  { ENOTNAM,             ENOTNAM_STR         },
      -  { ENAVAIL,             ENAVAIL_STR         },
      -  { EISNAM,              EISNAM_STR          },
      -  { EREMOTEIO,           EREMOTEIO_STR       },
      -  { EDQUOT,              EDQUOT_STR          },
      -  { ENOMEDIUM,           ENOMEDIUM_STR       },
      -  { EMEDIUMTYPE,         EMEDIUMTYPE_STR     }
      -};
      -
      -#else /* CONFIG_LIBC_STRERROR_SHORT */
      -
      -static const struct errno_strmap_s g_errnomap[] =
      -{
      -  { EPERM,               "EPERM"             },
      -  { ENOENT,              "ENOENT"            },
      -  { ESRCH,               "ESRCH"             },
      -  { EINTR,               "EINTR"             },
      -  { EIO,                 "EIO"               },
      -  { ENXIO,               "ENXIO"             },
      -  { E2BIG,               "E2BIG"             },
      -  { ENOEXEC,             "ENOEXEC"           },
      -  { EBADF,               "EBADF"             },
      -  { ECHILD,              "ECHILD"            },
      -  { EAGAIN,              "EAGAIN"            },
      -  { ENOMEM,              "ENOMEM"            },
      -  { EACCES,              "EACCES"            },
      -  { EFAULT,              "EFAULT"            },
      -  { ENOTBLK,             "ENOTBLK"           },
      -  { EBUSY,               "EBUSY"             },
      -  { EEXIST,              "EEXIST"            },
      -  { EXDEV,               "EXDEV"             },
      -  { ENODEV,              "ENODEV"            },
      -  { ENOTDIR,             "ENOTDIR"           },
      -  { EISDIR,              "EISDIR"            },
      -  { EINVAL,              "EINVAL"            },
      -  { ENFILE,              "ENFILE"            },
      -  { EMFILE,              "EMFILE"            },
      -  { ENOTTY,              "ENOTTY"            },
      -  { ETXTBSY,             "ETXTBSY"           },
      -  { EFBIG,               "EFBIG"             },
      -  { ENOSPC,              "ENOSPC"            },
      -  { ESPIPE,              "ESPIPE"            },
      -  { EROFS,               "EROFS"             },
      -  { EMLINK,              "EMLINK"            },
      -  { EPIPE,               "EPIPE"             },
      -  { EDOM,                "EDOM"              },
      -  { ERANGE,              "ERANGE"            },
      -  { EDEADLK,             "EDEADLK"           },
      -  { ENAMETOOLONG,        "ENAMETOOLONG"      },
      -  { ENOLCK,              "ENOLCK"            },
      -  { ENOSYS,              "ENOSYS"            },
      -  { ENOTEMPTY,           "ENOTEMPTY"         },
      -  { ELOOP,               "ELOOP"             },
      -  { ENOMSG,              "ENOMSG"            },
      -  { EIDRM,               "EIDRM"             },
      -  { ECHRNG,              "ECHRNG"            },
      -  { EL2NSYNC,            "EL2NSYNC"          },
      -  { EL3HLT,              "EL3HLT"            },
      -  { EL3RST,              "EL3RST"            },
      -  { EL3RST,              "EL3RST"            },
      -  { EUNATCH,             "EUNATCH"           },
      -  { ENOCSI,              "ENOCSI"            },
      -  { EL2HLT,              "EL2HLT"            },
      -  { EBADE,               "EBADE"             },
      -  { EBADR,               "EBADR"             },
      -  { EXFULL,              "EXFULL"            },
      -  { ENOANO,              "ENOANO"            },
      -  { EBADRQC,             "EBADRQC"           },
      -  { EBADSLT,             "EBADSLT"           },
      -  { EBFONT,              "EBFONT"            },
      -  { ENOSTR,              "ENOSTR"            },
      -  { ENODATA,             "ENODATA"           },
      -  { ETIME,               "ETIME"             },
      -  { ENOSR,               "ENOSR"             },
      -  { ENONET,              "ENONET"            },
      -  { ENOPKG,              "ENOPKG"            },
      -  { EREMOTE,             "EREMOTE"           },
      -  { ENOLINK,             "ENOLINK"           },
      -  { EADV,                "EADV"              },
      -  { ESRMNT,              "ESRMNT"            },
      -  { ECOMM,               "ECOMM"             },
      -  { EPROTO,              "EPROTO"            },
      -  { EMULTIHOP,           "EMULTIHOP"         },
      -  { EDOTDOT,             "EDOTDOT"           },
      -  { EBADMSG,             "EBADMSG"           },
      -  { EOVERFLOW,           "EOVERFLOW"         },
      -  { ENOTUNIQ,            "ENOTUNIQ"          },
      -  { EBADFD,              "EBADFD"            },
      -  { EREMCHG,             "EREMCHG"           },
      -  { ELIBACC,             "ELIBACC"           },
      -  { ELIBBAD,             "ELIBBAD"           },
      -  { ELIBSCN,             "ELIBSCN"           },
      -  { ELIBMAX,             "ELIBMAX"           },
      -  { ELIBEXEC,            "ELIBEXEC"          },
      -  { EILSEQ,              "EILSEQ"            },
      -  { ERESTART,            "ERESTART"          },
      -  { ESTRPIPE,            "ESTRPIPE"          },
      -  { EUSERS,              "EUSERS"            },
      -  { ENOTSOCK,            "ENOTSOCK"          },
      -  { EDESTADDRREQ,        "EDESTADDRREQ"      },
      -  { EMSGSIZE,            "EMSGSIZE"          },
      -  { EPROTOTYPE,          "EPROTOTYPE"        },
      -  { ENOPROTOOPT,         "ENOPROTOOPT"       },
      -  { EPROTONOSUPPORT,     "EPROTONOSUPPORT"   },
      -  { ESOCKTNOSUPPORT,     "ESOCKTNOSUPPORT"   },
      -  { EOPNOTSUPP,          "EOPNOTSUPP"        },
      -  { EPFNOSUPPORT,        "EPFNOSUPPORT"      },
      -  { EAFNOSUPPORT,        "EAFNOSUPPORT"      },
      -  { EADDRINUSE,          "EADDRINUSE"        },
      -  { EADDRNOTAVAIL,       "EADDRNOTAVAIL"     },
      -  { ENETDOWN,            "ENETDOWN"          },
      -  { ENETUNREACH,         "ENETUNREACH"       },
      -  { ENETRESET,           "ENETRESET"         },
      -  { ECONNABORTED,        "ECONNABORTED"      },
      -  { ECONNRESET,          "ECONNRESET"        },
      -  { ENOBUFS,             "ENOBUFS"           },
      -  { EISCONN,             "EISCONN"           },
      -  { ENOTCONN,            "ENOTCONN"          },
      -  { ESHUTDOWN,           "ESHUTDOWN"         },
      -  { ETOOMANYREFS,        "ETOOMANYREFS"      },
      -  { ETIMEDOUT,           "ETIMEDOUT"         },
      -  { ECONNREFUSED,        "ECONNREFUSED"      },
      -  { EHOSTDOWN,           "EHOSTDOWN"         },
      -  { EHOSTUNREACH,        "EHOSTUNREACH"      },
      -  { EALREADY,            "EALREADY"          },
      -  { EINPROGRESS,         "EINPROGRESS"       },
      -  { ESTALE,              "ESTALE"            },
      -  { EUCLEAN,             "EUCLEAN"           },
      -  { ENOTNAM,             "ENOTNAM"           },
      -  { ENAVAIL,             "ENAVAIL"           },
      -  { EISNAM,              "EISNAM"            },
      -  { EREMOTEIO,           "EREMOTEIO"         },
      -  { EDQUOT,              "EDQUOT"            },
      -  { ENOMEDIUM,           "ENOMEDIUM"         },
      -  { EMEDIUMTYPE,         "EMEDIUMTYPE"     }
      -};
      -
      -#endif /* CONFIG_LIBC_STRERROR_SHORT */
      -
      -#define NERRNO_STRS (sizeof(g_errnomap) / sizeof(struct errno_strmap_s))
      -
      -#endif /* CONFIG_LIBC_STRERROR */
      -
      -/************************************************************************
      - * Private Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Public Functions
      - ************************************************************************/
      -
      -/************************************************************************
      - * Name: strerror
      - ************************************************************************/
      -
      -FAR const char *strerror(int errnum)
      -{
      -#ifdef CONFIG_LIBC_STRERROR
      -  int ndxlow = 0;
      -  int ndxhi  = NERRNO_STRS - 1;
      -  int ndxmid;
      -
      -  do
      -    {
      -      ndxmid = (ndxlow + ndxhi) >> 1;
      -      if (errnum > g_errnomap[ndxmid].errnum)
      -        {
      -          ndxlow = ndxmid + 1;
      -        }
      -      else if (errnum < g_errnomap[ndxmid].errnum)
      -        {
      -          ndxhi = ndxmid - 1;
      -        }
      -      else
      -        {
      -          return g_errnomap[ndxmid].str;
      -        }
      -    }
      -  while (ndxlow <= ndxhi);
      -#endif
      -  return "Unknown error";
      -}
      diff --git a/nuttx/lib/string/lib_strlen.c b/nuttx/lib/string/lib_strlen.c
      deleted file mode 100644
      index 8333058091..0000000000
      --- a/nuttx/lib/string/lib_strlen.c
      +++ /dev/null
      @@ -1,55 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strlen.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRLEN
      -size_t strlen(const char *s)
      -{
      -  const char *sc;
      -  for (sc = s; *sc != '\0'; ++sc);
      -  return sc - s;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strncasecmp.c b/nuttx/lib/string/lib_strncasecmp.c
      deleted file mode 100644
      index be369cf0d8..0000000000
      --- a/nuttx/lib/string/lib_strncasecmp.c
      +++ /dev/null
      @@ -1,70 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strncasecmp.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - *****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - *****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - *****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - *****************************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRNCASECMP
      -int strncasecmp(const char *cs, const char *ct, size_t nb)
      -{
      -  int result = 0;
      -  for (; nb > 0; nb--)
      -    {
      -      if ((result = (int)toupper(*cs) - (int)toupper(*ct)) != 0 || !*cs)
      -        {
      -          break;
      -        }
      -
      -      cs++;
      -      ct++;
      -    }
      -  return result;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strncat.c b/nuttx/lib/string/lib_strncat.c
      deleted file mode 100644
      index af893e0f9b..0000000000
      --- a/nuttx/lib/string/lib_strncat.c
      +++ /dev/null
      @@ -1,62 +0,0 @@
      -/************************************************************
      - * lib/string/lib_strncat.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************
      - * Global Functions
      - ************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRNCAT
      -char *strncat(char *dest, const char *src, size_t n)
      -{
      -  char *ret   = dest;
      -
      -  dest  += strlen(dest);
      -  for (; n > 0 && *src != '\0' ; n--)
      -    {
      -      *dest++ = *src++;
      -    }
      -  *dest = '\0';
      -
      -  return ret;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strncmp.c b/nuttx/lib/string/lib_strncmp.c
      deleted file mode 100644
      index ce22820249..0000000000
      --- a/nuttx/lib/string/lib_strncmp.c
      +++ /dev/null
      @@ -1,65 +0,0 @@
      -/****************************************************************************
      - * lib/lib_strncmp.c
      - *
      - *   Copyright (C) 2007-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.
      - *
      - *****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - *****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - *****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - *****************************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRNCMP
      -int strncmp(const char *cs, const char *ct, size_t nb)
      -{
      -  int result = 0;
      -  for (; nb > 0; nb--)
      -    {
      -      if ((result = (int)*cs - (int)*ct++) != 0 || !*cs++)
      -        {
      -          break;
      -        }
      -    }
      -  return result;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strncpy.c b/nuttx/lib/string/lib_strncpy.c
      deleted file mode 100644
      index 149369d508..0000000000
      --- a/nuttx/lib/string/lib_strncpy.c
      +++ /dev/null
      @@ -1,57 +0,0 @@
      -/************************************************************
      - * lib/string/lib_strncpy.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ************************************************************/
      -
      -/************************************************************
      - * Included Files
      - ************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/************************************************************
      - * Global Functions
      - ************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRNCPY
      -char *strncpy(char *dest, const char *src, size_t n)
      -{
      -  char *ret = dest;     /* Value to be returned */
      -  char *end = dest + n; /* End of dest buffer + 1 byte */
      -
      -  while ((*dest++ = *src++) != '\0' && dest != end);
      -  return ret;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strndup.c b/nuttx/lib/string/lib_strndup.c
      deleted file mode 100644
      index ffaf892eaa..0000000000
      --- a/nuttx/lib/string/lib_strndup.c
      +++ /dev/null
      @@ -1,93 +0,0 @@
      -/************************************************************************
      - * lib/string//lib_strndup.c
      - *
      - *   Copyright (C) 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/************************************************************************
      - * Global Functions
      - ************************************************************************/
      -/************************************************************************
      - * Name: strndup
      - *
      - * Description:
      - *   The strndup() function is equivalent to the strdup() function,
      - *   duplicating the provided 's' in a new block of memory allocated as
      - *   if by using malloc(), with the exception being that strndup() copies
      - *   at most 'size' plus one bytes into the newly allocated memory,
      - *   terminating the new string with a NUL character. If the length of 's'
      - *   is larger than 'size', only 'size' bytes will be duplicated. If
      - *   'size' is larger than the length of 's', all bytes in s will be
      - *   copied into the new memory buffer, including the terminating NUL
      - *   character. The newly created string will always be properly
      - *   terminated.
      - *
      - ************************************************************************/
      -
      -FAR char *strndup(FAR const char *s, size_t size)
      -{
      -  FAR char *news = NULL;
      -  if (s)
      -    {
      -      /* Get the size of the new string = MIN(strlen(s), size) */
      -
      -      size_t allocsize = strlen(s);
      -      if (allocsize > size)
      -        {
      -          allocsize = size;
      -        }
      -
      -      /* Allocate the new string, adding 1 for the NUL terminator */
      -
      -      news = (FAR char*)lib_malloc(allocsize + 1);
      -      if (news)
      -        {
      -          /* Copy the string into the allocated memory and add a NUL
      -           * terminator in any case.
      -           */
      -
      -          memcpy(news, s, allocsize);
      -          news[allocsize] = '\0';
      -        }
      -    }
      -  return news;
      -}
      diff --git a/nuttx/lib/string/lib_strnlen.c b/nuttx/lib/string/lib_strnlen.c
      deleted file mode 100644
      index 2b64fe9845..0000000000
      --- a/nuttx/lib/string/lib_strnlen.c
      +++ /dev/null
      @@ -1,62 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strnlen.c
      - *
      - * This file is part of NuttX, contributed by Michael Hrabanek
      - *
      - *   Copyright (C) 2010 Gregory Nutt. All rights reserved.
      - *   Author: Michael Hrabanek
      - *
      - * Derives from the file lib/lib_strlen.c:
      - *
      - *   Copyright (C) 2007, 2008, 2010 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -#ifndef CONFIG_ARCH_STRNLEN
      -size_t strnlen(const char *s, size_t maxlen)
      -{
      -  const char *sc;
      -  for (sc = s; maxlen != 0 && *sc != '\0'; maxlen--, ++sc);
      -  return sc - s;
      -}
      -#endif
      diff --git a/nuttx/lib/string/lib_strpbrk.c b/nuttx/lib/string/lib_strpbrk.c
      deleted file mode 100644
      index 02e2ea2c70..0000000000
      --- a/nuttx/lib/string/lib_strpbrk.c
      +++ /dev/null
      @@ -1,85 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strpbrk.c
      - *
      - *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
      - *   Author: Gregory Nutt 
      - *
      - * Redistribution and use str 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 str binary form must reproduce the above copyright
      - *    notice, this list of conditions and the following disclaimer str
      - *    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 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -char *strpbrk(const char *str, const char *charset)
      -{
      -  /* Sanity checking */
      -
      -#ifdef CONFIG_DEBUG
      -  if (!str || !charset)
      -    {
      -      return NULL;
      -    }
      -#endif
      -    
      -  /* Check each character in the string */
      -
      -  while (*str)
      -    {
      -      /* Check if the character from the string matches any character in the charset */
      -
      -      if (strchr(charset, *str) != NULL)
      -        {
      -          /* Yes, then this position must be the first occurrence in string */
      -
      -          return (char*)str;
      -	}
      -
      -      /* This character from the strings matches none of those in the charset.
      -       * Try the next character from the string.
      -       */
      -
      -      str++;
      -    }
      -
      -  /* We have looked at every character in the string, and none of them match any of
      -   * the characters in charset.
      -   */
      -
      -  return NULL;
      -}
      -
      diff --git a/nuttx/lib/string/lib_strrchr.c b/nuttx/lib/string/lib_strrchr.c
      deleted file mode 100644
      index 91243ce589..0000000000
      --- a/nuttx/lib/string/lib_strrchr.c
      +++ /dev/null
      @@ -1,68 +0,0 @@
      -/************************************************************************
      - * lib/string/lib_strrchr.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ************************************************************************/
      -
      -/************************************************************************
      - * Included Files
      - ************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/************************************************************************
      - * Global Functions
      - ************************************************************************/
      -
      -/* The strrchr() function returns a pointer to the last
      - * occurrence of the character c in the string s.
      - */
      -
      -char *strrchr(const char *s, int c)
      -{
      -  if (s)
      -    {
      -      const char *p = &s[strlen(s) - 1];
      -      for (; p >= s; p--)
      -        {
      -          if (*p == c)
      -            {
      -              return (char*)p;
      -            }
      -        }
      -    }
      -
      -  return NULL;
      -}
      -
      diff --git a/nuttx/lib/string/lib_strspn.c b/nuttx/lib/string/lib_strspn.c
      deleted file mode 100644
      index e7b5ea0a5b..0000000000
      --- a/nuttx/lib/string/lib_strspn.c
      +++ /dev/null
      @@ -1,66 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strspn.c
      - *
      - *   Copyright (C) 2007, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Compilation Switches
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: strspn
      - *
      - * Description:
      - *  strspn() calculates the length of the initial segment of s which
      - *  consists entirely of characters in accept.
      - *
      - ****************************************************************************/
      -
      -size_t strspn(const char *s, const char *accept)
      -{
      -  size_t i;
      -  for (i = 0; s[i] && strchr(accept, s[i]) != NULL; i++);
      -  return i;
      -}
      diff --git a/nuttx/lib/string/lib_strstr.c b/nuttx/lib/string/lib_strstr.c
      deleted file mode 100644
      index b8c896fa2e..0000000000
      --- a/nuttx/lib/string/lib_strstr.c
      +++ /dev/null
      @@ -1,104 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strstr.c
      - *
      - *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
      - *   Author: Gregory Nutt 
      - *
      - * Redistribution and use str 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 str binary form must reproduce the above copyright
      - *    notice, this list of conditions and the following disclaimer str
      - *    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 
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -char *strstr(const char *str, const char *substr)
      -{
      -  const char *candidate;  /* Candidate in str with matching start character */
      -  char         ch;        /* First character of the substring */
      -  int          len;       /* The length of the substring */
      -
      -  /* Special case the empty substring */
      -
      -  len = strlen(substr);
      -  ch  = *substr;
      -
      -  if (!ch)
      -    {
      -      /* We'll say that an empty substring matches at the beginning of
      -       * the string
      -       */
      -
      -      return (char*)str;
      -    }
      -
      -  /* Search for the substring */
      -
      -  candidate = str;
      -  for (;;)
      -    {
      -      /* strchr() will return a pointer to the next occurrence of the
      -       * character ch in the string
      -       */
      -
      -      candidate = strchr(candidate, ch);
      -      if (!candidate || strlen(candidate) < len)
      -        {
      -           /* First character of the substring does not appear in the string
      -            * or the remainder of the string is not long enough to contain the
      -            * substring.
      -            */
      -
      -           return NULL;
      -        }
      -
      -      /* Check if this is the beginning of a matching substring */
      -
      -      if (strncmp(candidate, substr, len) == 0)
      -        {
      -           return (char*)candidate;
      -        }
      -
      -      /* No, find the next candidate after this one */
      -
      -      candidate++;
      -    }
      -
      -  /* Won't get here, but some compilers might complain */
      -
      -  return NULL;
      -}
      -
      diff --git a/nuttx/lib/string/lib_strtod.c b/nuttx/lib/string/lib_strtod.c
      deleted file mode 100644
      index 8fecd45713..0000000000
      --- a/nuttx/lib/string/lib_strtod.c
      +++ /dev/null
      @@ -1,241 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strtod.c
      - * Convert string to double
      - *
      - *   Copyright (C) 2002 Michael Ringgaard. All rights reserved.
      - *   Copyright (C) 2006-2007 H. Peter Anvin.
      - *
      - * 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 of the project 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_HAVE_DOUBLE
      -
      -/****************************************************************************
      - * Pre-processor definitions
      - ****************************************************************************/
      -
      -/* These are predefined with GCC, but could be issues for other compilers. If
      - * not defined, an arbitrary big number is put in for now.  These should be
      - * added to nuttx/compiler for your compiler.
      - */
      -
      -#if !defined(__DBL_MIN_EXP__) || !defined(__DBL_MAX_EXP__)
      -#  ifdef CONFIG_CPP_HAVE_WARNING
      -#    warning "Size of exponent is unknown"
      -#  endif
      -#  undef  __DBL_MIN_EXP__
      -#  define __DBL_MIN_EXP__ (-1021)
      -#  undef  __DBL_MAX_EXP__
      -#  define __DBL_MAX_EXP__ (1024)
      -#endif
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -static inline int is_real(double x)
      -{
      -  const double_t infinite = 1.0/0.0;
      -  return (x < infinite) && (x >= -infinite);
      -}
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/***************************************************(************************
      - * Name: strtod
      - *
      - * Description:
      - *   Convert a string to a double value
      - *
      - ****************************************************************************/
      -
      -double_t strtod(const char *str, char **endptr)
      -{
      -  double_t number;
      -  int exponent;
      -  int negative;
      -  char *p = (char *) str;
      -  double p10;
      -  int n;
      -  int num_digits;
      -  int num_decimals;
      -  const double_t infinite = 1.0/0.0;
      -
      -  /* Skip leading whitespace */
      -
      -  while (isspace(*p))
      -    {
      -      p++;
      -    }
      -
      -  /* Handle optional sign */
      -
      -  negative = 0;
      -  switch (*p)
      -    {
      -    case '-':
      -      negative = 1; /* Fall through to increment position */
      -    case '+':
      -      p++;
      -    }
      -
      -  number       = 0.;
      -  exponent     = 0;
      -  num_digits   = 0;
      -  num_decimals = 0;
      -
      -  /* Process string of digits */
      -
      -  while (isdigit(*p))
      -    {
      -      number = number * 10. + (*p - '0');
      -      p++;
      -      num_digits++;
      -    }
      -
      -  /* Process decimal part */
      -
      -  if (*p == '.')
      -    {
      -      p++;
      -
      -      while (isdigit(*p))
      -      {
      -        number = number * 10. + (*p - '0');
      -        p++;
      -        num_digits++;
      -        num_decimals++;
      -      }
      -
      -      exponent -= num_decimals;
      -    }
      -
      -  if (num_digits == 0)
      -    {
      -      set_errno(ERANGE);
      -      return 0.0;
      -    }
      -
      -  /* Correct for sign */
      -
      -  if (negative)
      -    {
      -      number = -number;
      -    }
      -
      -  /* Process an exponent string */
      -
      -  if (*p == 'e' || *p == 'E')
      -    {
      -      /* Handle optional sign */
      -
      -      negative = 0;
      -      switch(*++p)
      -        {
      -        case '-':
      -          negative = 1;   /* Fall through to increment pos */
      -        case '+':
      -          p++;
      -        }
      -
      -      /* Process string of digits */
      -
      -      n = 0;
      -      while (isdigit(*p))
      -        {
      -          n = n * 10 + (*p - '0');
      -          p++;
      -        }
      -
      -      if (negative)
      -        {
      -          exponent -= n;
      -        }
      -      else
      -        {
      -          exponent += n;
      -        }
      -    }
      -
      -  if (exponent < __DBL_MIN_EXP__ ||
      -      exponent > __DBL_MAX_EXP__)
      -    {
      -      set_errno(ERANGE);
      -      return infinite;
      -    }
      -
      -  /* Scale the result */
      -
      -  p10 = 10.;
      -  n = exponent;
      -  if (n < 0) n = -n;
      -  while (n)
      -    {
      -      if (n & 1)
      -        {
      -          if (exponent < 0)
      -            {
      -              number /= p10;
      -            }
      -          else
      -            {
      -              number *= p10;
      -            }
      -        }
      -      n >>= 1;
      -      p10 *= p10;
      -    }
      -
      -  if (!is_real(number))
      -    {
      -      set_errno(ERANGE);
      -    }
      -
      -  if (endptr)
      -    {
      -      *endptr = p;
      -    }
      -
      -  return number;
      -}
      -
      -#endif /* CONFIG_HAVE_DOUBLE */
      -
      diff --git a/nuttx/lib/string/lib_strtok.c b/nuttx/lib/string/lib_strtok.c
      deleted file mode 100644
      index c409931359..0000000000
      --- a/nuttx/lib/string/lib_strtok.c
      +++ /dev/null
      @@ -1,87 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strtok.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Private Data
      - ****************************************************************************/
      -
      -static char *g_saveptr = NULL;
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: strtok
      - *
      - * Description:
      - *    The  strtok()  function  parses  a string into a
      - *    sequence of tokens.  On the first call to strtok() the
      - *    string to be parsed should be specified in 'str'.  In
      - *    each subsequent call that should parse the same string, 
      - *    'str' should be NULL.
      - *
      - *    The 'delim' argument specifies a set of characters that
      - *    delimit the tokens in the parsed string.  The caller
      - *    may specify different strings in delim in successive
      - *    calls that parse the same string.
      - *
      - *    Each call to strtok() returns a pointer to a null-
      - *    terminated string containing the next token. This
      - *    string  does not include the delimiting character.  If
      - *    no more tokens are found, strtok() returns NULL.
      - *
      - *    A sequence of two or more contiguous delimiter
      - *    characters in the parsed string is considered to be a
      - *    single delimiter. Delimiter characters at the start or
      - *    end of the string are ignored.  The tokens returned by
      - *    strtok() are always non-empty strings.
      - *
      - * Return
      - *    strtok() returns a pointer to the next token, or NULL
      - *    if there are no more tokens.
      - *
      - ****************************************************************************/
      -
      -char *strtok(char *str, const char *delim)
      -{
      -  return strtok_r(str, delim, &g_saveptr);
      -}
      diff --git a/nuttx/lib/string/lib_strtokr.c b/nuttx/lib/string/lib_strtokr.c
      deleted file mode 100644
      index 1c571b6ae5..0000000000
      --- a/nuttx/lib/string/lib_strtokr.c
      +++ /dev/null
      @@ -1,157 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strtokr.c
      - *
      - *   Copyright (C) 2007, 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -/****************************************************************************
      - * Private Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: strtok_r
      - *
      - * Description:
      - *   The strtok_r() function is a reentrant version strtok().
      - *   Like strtok(), it  parses  a string into a sequence of
      - *   tokens.  On the first call to strtok() the string to be
      - *   parsed should be specified in 'str'.  In each subsequent
      - *   call that should parse the same string, 'str' should be
      - *   NULL.
      - *
      - *   The 'saveptr' argument is a pointer to a char *
      - *   variable  that  is  used internally by strtok_r() in
      - *   order to maintain context between successive calls
      - *   that parse the same string.
      - *
      - *   On the first call to strtok_r(), 'str' should point to the
      - *   string to be parsed, and the value of 'saveptr' is 
      - *   ignored.  In subsequent calls, 'str' should be NULL, and
      - *   saveptr should be unchanged since the previous call.
      - *
      - *   The 'delim' argument specifies a set of characters that
      - *   delimit the tokens in the parsed string.  The caller
      - *   may specify different strings in delim in successive
      - *   calls that parse the same string.
      - *
      - *   Each call to strtok_r() returns a pointer to a null-
      - *   terminated string containing the next token. This
      - *   string  does not include the delimiting character.  If
      - *   no more tokens are found, strtok_r() returns NULL.
      - *
      - *   A sequence of two or more contiguous delimiter
      - *   characters in the parsed string is considered to be a
      - *   single delimiter. Delimiter characters at the start or
      - *   end of the string are ignored.  The tokens returned by
      - *   strtok() are always non-empty strings.
      - *
      - * Return
      - *    strtok_r() returns a pointer to the next token, or NULL
      - *    if there are no more tokens.
      - *
      - ****************************************************************************/
      -
      -FAR char *strtok_r(FAR char *str, FAR const char *delim, FAR char **saveptr)
      -{
      -  char *pbegin;
      -  char *pend = NULL;
      -
      -  /* Decide if we are starting a new string or continuing from
      -   * the point we left off.
      -   */
      -
      -  if (str)
      -    {
      -      pbegin = str;
      -    }
      -  else if (saveptr && *saveptr)
      -    {
      -      pbegin = *saveptr;
      -    }
      -  else
      -    {
      -      return NULL;
      -    }
      -
      -  /* Find the beginning of the next token */
      -
      -  for (;
      -       *pbegin && strchr(delim, *pbegin) != NULL;
      -       pbegin++);
      -
      -  /* If we are at the end of the string with nothing
      -   * but delimiters found, then return NULL.
      -   */
      -
      -  if (!*pbegin)
      -    {
      -      return NULL;
      -    }
      -
      -  /* Find the end of the token */
      -
      -  for (pend = pbegin + 1;
      -       *pend && strchr(delim, *pend) == NULL;
      -       pend++);
      -
      -
      -  /* pend either points to the end of the string or to
      -   * the first delimiter after the string.
      -   */
      -
      -  if (*pend)
      -    {
      -      /* Turn the delimiter into a null terminator */
      -
      -      *pend++ = '\0';
      -    }
      -
      -  /* Save the pointer where we left off and return the
      -   * beginning of the token.
      -   */
      -
      -  if (saveptr)
      -    {
      -      *saveptr = pend;
      -    }
      -  return pbegin;
      -}
      diff --git a/nuttx/lib/string/lib_strtol.c b/nuttx/lib/string/lib_strtol.c
      deleted file mode 100644
      index c17d87e635..0000000000
      --- a/nuttx/lib/string/lib_strtol.c
      +++ /dev/null
      @@ -1,103 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strtol.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: strtol
      - *
      - * Description:
      - *   The  strtol() function  converts  the initial part of the string in
      - *   nptr to a long integer value according to the given base, which must be
      - *   between 2 and 36 inclusive, or be the special value 0.
      - *
      - * Warning: does not check for integer overflow!
      - *
      - ****************************************************************************/
      - 
      -long strtol(const char *nptr, char **endptr, int base)
      -{
      -  unsigned long accum = 0;
      -  bool negate = false;
      -
      -  if (nptr)
      -    {
      -      /* Skip leading spaces */
      -
      -      lib_skipspace(&nptr);
      -
      -      /* Check for leading + or - */
      -
      -      if (*nptr == '-')
      -        {
      -          negate = true;
      -          nptr++;
      -        }
      -      else if (*nptr == '+')
      -        {
      -          nptr++;
      -        }
      -
      -      /* Get the unsigned value */
      -
      -      accum = strtoul(nptr, endptr, base);
      -
      -      /* Correct the sign of the result */
      -
      -      if (negate)
      -        {
      -          return -(long)accum;
      -        }
      -    }
      -  return (long)accum;
      -}
      -
      diff --git a/nuttx/lib/string/lib_strtoll.c b/nuttx/lib/string/lib_strtoll.c
      deleted file mode 100644
      index 242e025c07..0000000000
      --- a/nuttx/lib/string/lib_strtoll.c
      +++ /dev/null
      @@ -1,107 +0,0 @@
      -/****************************************************************************
      - * lib/string/lib_strtoll.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -#ifdef CONFIG_HAVE_LONG_LONG
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: strtoll
      - *
      - * Description:
      - *   The  strtol() function  converts  the initial part of the string in
      - *   nptr to a long long integer value according to the given base, which
      - *   must be between 2 and 36 inclusive, or be the special value 0.
      - *
      - * Warning: does not check for integer overflow!
      - *
      - ****************************************************************************/
      - 
      -long long strtoll(const char *nptr, char **endptr, int base)
      -{
      -  unsigned long long accum = 0;
      -  bool negate = false;
      -
      -  if (nptr)
      -    {
      -      /* Skip leading spaces */
      -
      -      lib_skipspace(&nptr);
      -
      -      /* Check for leading + or - */
      -
      -      if (*nptr == '-')
      -        {
      -          negate = true;
      -          nptr++;
      -        }
      -      else if (*nptr == '+')
      -        {
      -          nptr++;
      -        }
      -
      -      /* Get the unsigned value */
      -
      -      accum = strtoull(nptr, endptr, base);
      -
      -      /* Correct the sign of the result */
      -
      -      if (negate)
      -        {
      -          return -(long long)accum;
      -        }
      -    }
      -  return (long long)accum;
      -}
      -
      -#endif
      -
      diff --git a/nuttx/lib/string/lib_strtoul.c b/nuttx/lib/string/lib_strtoul.c
      deleted file mode 100644
      index b0d2d090e6..0000000000
      --- a/nuttx/lib/string/lib_strtoul.c
      +++ /dev/null
      @@ -1,98 +0,0 @@
      -/****************************************************************************
      - * /lib/string/lib_strtoul.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: strtoul
      - *
      - * Description:
      - *   The  strtol() function  converts  the initial part of the string in
      - *   nptr to a long unsigned integer value according to the given base, which
      - *   must be between 2 and 36 inclusive, or be the special value 0.
      - *
      - * Warning: does not check for integer overflow!
      - *
      - ****************************************************************************/
      - 
      -unsigned long strtoul(const char *nptr, char **endptr, int base)
      -{
      -  unsigned long accum = 0;
      -  int value;
      -
      -  if (nptr)
      -    {
      -      /* Skip leading spaces */
      -
      -      lib_skipspace(&nptr);
      -
      -      /* Check for unspecified base */
      -
      -      base = lib_checkbase(base, &nptr);
      -
      -      /* Accumulate each "digit" */
      -
      -      while (lib_isbasedigit(*nptr, base, &value))
      -        {
      -            accum = accum*base + value;
      -            nptr++;
      -        }
      -
      -      /* Return the final pointer to the unused value */
      -
      -      if (endptr)
      -        {
      -          *endptr = (char *)nptr;
      -        }
      -    }
      -   return accum;
      -}
      -
      diff --git a/nuttx/lib/string/lib_strtoull.c b/nuttx/lib/string/lib_strtoull.c
      deleted file mode 100644
      index 6567457c0e..0000000000
      --- a/nuttx/lib/string/lib_strtoull.c
      +++ /dev/null
      @@ -1,100 +0,0 @@
      -/****************************************************************************
      - * /lib/string/lib_strtoull.c
      - *
      - *   Copyright (C) 2009, 2010 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -#include "lib_internal.h"
      -
      -#ifdef CONFIG_HAVE_LONG_LONG
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: strtoull
      - *
      - * Description:
      - *   The  strtol() function  converts  the initial part of the string in
      - *   nptr to a long unsigned integer value according to the given base, which
      - *   must be between 2 and 36 inclusive, or be the special value 0.
      - *
      - ****************************************************************************/
      - 
      -unsigned long long strtoull(const char *nptr, char **endptr, int base)
      -{
      -  unsigned long long accum = 0;
      -  int value;
      -
      -  if (nptr)
      -    {
      -      /* Skip leading spaces */
      -
      -      lib_skipspace(&nptr);
      -
      -      /* Check for unspecified base */
      -
      -      base = lib_checkbase(base, &nptr);
      -
      -      /* Accumulate each "digit" */
      -
      -      while (lib_isbasedigit(*nptr, base, &value))
      -        {
      -            accum = accum*base + value;
      -            nptr++;
      -        }
      -
      -      /* Return the final pointer to the unused value */
      -
      -      if (endptr)
      -        {
      -          *endptr = (char *)nptr;
      -        }
      -    }
      -   return accum;
      -}
      -#endif
      -
      diff --git a/nuttx/lib/string/lib_vikmemcpy.c b/nuttx/lib/string/lib_vikmemcpy.c
      deleted file mode 100644
      index b50942aaa1..0000000000
      --- a/nuttx/lib/string/lib_vikmemcpy.c
      +++ /dev/null
      @@ -1,348 +0,0 @@
      -/****************************************************************************
      - * File: lib/string/lib_vikmemcpy.c
      - *
      - * This is version of the optimized memcpy by Daniel Vik, adapted to the
      - * NuttX environment.
      - *
      - *   Copyright (C) 1999-2010 Daniel Vik
      - *
      - * Adaptations include:
      - * - File name change
      - * - Use of types defined in stdint.h
      - * - Integration with the NuttX configuration system
      - * - Other cosmetic changes for consistency with NuttX coding standards
      - * 
      - * This software is provided 'as-is', without any express or implied
      - * warranty. In no event will the authors be held liable for any
      - * damages arising from the use of this software.
      - * Permission is granted to anyone to use this software for any
      - * purpose, including commercial applications, and to alter it and
      - * redistribute it freely, subject to the following restrictions:
      - * 
      - * 1. The origin of this software must not be misrepresented; you
      - *    must not claim that you wrote the original software. If you
      - *    use this software in a product, an acknowledgment in the
      - *    use this software in a product, an acknowledgment in the
      - *    product documentation would be appreciated but is not
      - *    required.
      - * 
      - * 2. Altered source versions must be plainly marked as such, and
      - *    must not be misrepresented as being the original software.
      - * 
      - * 3. This notice may not be removed or altered from any source
      - *    distribution.
      - * 
      - * Description: Implementation of the standard library function memcpy.
      - *              This implementation of memcpy() is ANSI-C89 compatible.
      - *
      - * The following configuration options can be set:
      - *
      - *   CONFIG_ENDIAN_BIG
      - *     Uses processor with big endian addressing. Default is little endian.
      - *
      - *   CONFIG_MEMCPY_PRE_INC_PTRS
      - *     Use pre increment of pointers. Default is post increment of pointers.
      - *
      - *   CONFIG_MEMCPY_INDEXED_COPY
      - *     Copying data using array indexing. Using this option, disables the
      - *     CONFIG_MEMCPY_PRE_INC_PTRS option.
      - *
      - *   CONFIG_MEMCPY_64BIT - Compiles memcpy for 64 bit architectures
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Configuration definitions.
      - ****************************************************************************/
      -
      -#define CONFIG_MEMCPY_INDEXED_COPY
      -
      -/********************************************************************
      - * Included Files
      - *******************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/********************************************************************
      - * Pre-processor Definitions
      - *******************************************************************/
      -
      -/* Can't support CONFIG_MEMCPY_64BIT if the platform does not have 64-bit
      - * integer types.
      - */
      -
      -#ifndef CONFIG_HAVE_LONG_LONG
      -#  undef CONFIG_MEMCPY_64BIT
      -#endif
      -
      -/* Remove definitions when CONFIG_MEMCPY_INDEXED_COPY is defined */
      -
      -#if defined (CONFIG_MEMCPY_INDEXED_COPY)
      -#  if defined (CONFIG_MEMCPY_PRE_INC_PTRS)
      -#    undef CONFIG_MEMCPY_PRE_INC_PTRS
      -#  endif /* CONFIG_MEMCPY_PRE_INC_PTRS */
      -#endif /* CONFIG_MEMCPY_INDEXED_COPY */
      -
      -/* Definitions for pre and post increment of pointers */
      -
      -#if defined (CONFIG_MEMCPY_PRE_INC_PTRS)
      -
      -#  define START_VAL(x)            (x)--
      -#  define INC_VAL(x)              *++(x)
      -#  define CAST_TO_U8(p, o)        ((uint8_t*)p + o + TYPE_WIDTH)
      -#  define WHILE_DEST_BREAK        (TYPE_WIDTH - 1)
      -#  define PRE_LOOP_ADJUST         - (TYPE_WIDTH - 1)
      -#  define PRE_SWITCH_ADJUST       + 1
      -
      -#else /* CONFIG_MEMCPY_PRE_INC_PTRS */
      -
      -#  define START_VAL(x)
      -#  define INC_VAL(x)              *(x)++
      -#  define CAST_TO_U8(p, o)        ((uint8_t*)p + o)
      -#  define WHILE_DEST_BREAK        0
      -#  define PRE_LOOP_ADJUST
      -#  define PRE_SWITCH_ADJUST
      -
      -#endif /* CONFIG_MEMCPY_PRE_INC_PTRS */
      -
      -/* Definitions for endian-ness */
      -
      -#ifdef CONFIG_ENDIAN_BIG
      -
      -#  define SHL <<
      -#  define SHR >>
      -
      -#else /* CONFIG_ENDIAN_BIG */
      -
      -#  define SHL >>
      -#  define SHR <<
      -
      -#endif /* CONFIG_ENDIAN_BIG */
      -
      -/********************************************************************
      - * Macros for copying words of  different alignment.
      - * Uses incremening pointers.
      - *******************************************************************/
      -
      -#define CP_INCR()                         \
      -{                                         \
      -  INC_VAL(dstN) = INC_VAL(srcN);          \
      -}
      -
      -#define CP_INCR_SH(shl, shr)              \
      -{                                         \
      -  dstWord       = srcWord SHL shl;        \
      -  srcWord       = INC_VAL(srcN);          \
      -  dstWord      |= srcWord SHR shr;        \
      -  INC_VAL(dstN) = dstWord;                \
      -}
      -
      -/********************************************************************
      - * Macros for copying words of  different alignment.
      - * Uses array indexes.
      - *******************************************************************/
      -
      -#define CP_INDEX(idx)                     \
      -{                                         \
      -  dstN[idx] = srcN[idx];                  \
      -}
      -
      -#define CP_INDEX_SH(x, shl, shr)          \
      -{                                         \
      -  dstWord   = srcWord SHL shl;            \
      -  srcWord   = srcN[x];                    \
      -  dstWord  |= srcWord SHR shr;            \
      -  dstN[x]   = dstWord;                    \
      -}
      -
      -/********************************************************************
      - * Macros for copying words of different alignment.
      - * Uses incremening pointers or array indexes depending on
      - * configuration.
      - *******************************************************************/
      -
      -#if defined (CONFIG_MEMCPY_INDEXED_COPY)
      -
      -#  define CP(idx)               CP_INDEX(idx)
      -#  define CP_SH(idx, shl, shr)  CP_INDEX_SH(idx, shl, shr)
      -
      -#  define INC_INDEX(p, o)       ((p) += (o))
      -
      -#else /* CONFIG_MEMCPY_INDEXED_COPY */
      -
      -#  define CP(idx)               CP_INCR()
      -#  define CP_SH(idx, shl, shr)  CP_INCR_SH(shl, shr)
      -
      -#  define INC_INDEX(p, o)
      -
      -#endif /* CONFIG_MEMCPY_INDEXED_COPY */
      -
      -#define COPY_REMAINING(count)                                     \
      -{                                                                 \
      -  START_VAL(dst8);                                                \
      -  START_VAL(src8);                                                \
      -                                                                  \
      -  switch (count)                                                  \
      -    {                                                             \
      -    case 7: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 6: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 5: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 4: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 3: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 2: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 1: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 0:                                                       \
      -    default: break;                                               \
      -    }                                                             \
      -}
      -
      -#define COPY_NO_SHIFT()                                           \
      -{                                                                 \
      -  UIntN* dstN = (UIntN*)(dst8 PRE_LOOP_ADJUST);                   \
      -  UIntN* srcN = (UIntN*)(src8 PRE_LOOP_ADJUST);                   \
      -  size_t length = count / TYPE_WIDTH;                             \
      -                                                                  \
      -  while (length & 7)                                              \
      -    {                                                             \
      -      CP_INCR();                                                  \
      -      length--;                                                   \
      -    }                                                             \
      -                                                                  \
      -  length /= 8;                                                    \
      -                                                                  \
      -  while (length--)                                                \
      -    {                                                             \
      -      CP(0);                                                      \
      -      CP(1);                                                      \
      -      CP(2);                                                      \
      -      CP(3);                                                      \
      -      CP(4);                                                      \
      -      CP(5);                                                      \
      -      CP(6);                                                      \
      -      CP(7);                                                      \
      -                                                                  \
      -      INC_INDEX(dstN, 8);                                         \
      -      INC_INDEX(srcN, 8);                                         \
      -    }                                                             \
      -                                                                  \
      -  src8 = CAST_TO_U8(srcN, 0);                                     \
      -  dst8 = CAST_TO_U8(dstN, 0);                                     \
      -                                                                  \
      -  COPY_REMAINING(count & (TYPE_WIDTH - 1));                       \
      -                                                                  \
      -  return dest;                                                    \
      -}
      -
      -#define COPY_SHIFT(shift)                                         \
      -{                                                                 \
      -  UIntN* dstN  = (UIntN*)((((UIntN)dst8) PRE_LOOP_ADJUST) &       \
      -                           ~(TYPE_WIDTH - 1));                    \
      -  UIntN* srcN  = (UIntN*)((((UIntN)src8) PRE_LOOP_ADJUST) &       \
      -                           ~(TYPE_WIDTH - 1));                    \
      -  size_t length  = count / TYPE_WIDTH;                            \
      -  UIntN srcWord = INC_VAL(srcN);                                  \
      -  UIntN dstWord;                                                  \
      -                                                                  \
      -  while (length & 7)                                              \
      -    {                                                             \
      -      CP_INCR_SH(8 * shift, 8 * (TYPE_WIDTH - shift));            \
      -      length--;                                                   \
      -    }                                                             \
      -                                                                  \
      -  length /= 8;                                                    \
      -                                                                  \
      -  while (length--)                                                \
      -    {                                                             \
      -      CP_SH(0, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(1, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(2, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(3, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(4, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(5, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(6, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(7, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -                                                                  \
      -      INC_INDEX(dstN, 8);                                         \
      -      INC_INDEX(srcN, 8);                                         \
      -    }                                                             \
      -                                                                  \
      -  src8 = CAST_TO_U8(srcN, (shift - TYPE_WIDTH));                  \
      -  dst8 = CAST_TO_U8(dstN, 0);                                     \
      -                                                                  \
      -  COPY_REMAINING(count & (TYPE_WIDTH - 1));                       \
      -                                                                  \
      -  return dest;                                                    \
      -}
      -
      -/********************************************************************
      - * Type Definitions
      - *******************************************************************/
      -
      -#ifdef CONFIG_MEMCPY_64BIT
      -typedef uint64_t            UIntN;
      -#  define TYPE_WIDTH        8L
      -#else
      -typedef uint32_t            UIntN;
      -#  define TYPE_WIDTH        4L
      -#endif
      -
      -/********************************************************************
      - * Public Functions
      - *******************************************************************/
      -/********************************************************************
      - * Name: memcpy
      - *
      - * Description:
      - *   Copies count bytes from src to dest. No overlap check is performed.
      - *
      - * Input Parameters:
      - *   dest        - pointer to destination buffer
      - *   src         - pointer to source buffer
      - *   count       - number of bytes to copy
      - *
      - * Returned Value:
      - *   A pointer to destination buffer
      - *
      - *******************************************************************/
      -
      -void *memcpy(void *dest, const void *src, size_t count) 
      -{
      -  uint8_t *dst8 = (uint8_t*)dest;
      -  uint8_t *src8 = (uint8_t*)src;
      -
      -  if (count < 8)
      -    {
      -      COPY_REMAINING(count);
      -      return dest;
      -    }
      -
      -  START_VAL(dst8);
      -  START_VAL(src8);
      -
      -  while (((UIntN)dst8 & (TYPE_WIDTH - 1)) != WHILE_DEST_BREAK)
      -    {
      -      INC_VAL(dst8) = INC_VAL(src8);
      -      count--;
      -    }
      -
      -  switch ((((UIntN)src8) PRE_SWITCH_ADJUST) & (TYPE_WIDTH - 1))
      -    {
      -    case 0: COPY_NO_SHIFT(); break;
      -    case 1: COPY_SHIFT(1);   break;
      -    case 2: COPY_SHIFT(2);   break;
      -    case 3: COPY_SHIFT(3);   break;
      -#if TYPE_WIDTH > 4
      -    case 4: COPY_SHIFT(4);   break;
      -    case 5: COPY_SHIFT(5);   break;
      -    case 6: COPY_SHIFT(6);   break;
      -    case 7: COPY_SHIFT(7);   break;
      -#endif
      -    }
      -
      -  return dest;
      -}
      diff --git a/nuttx/lib/termios/Make.defs b/nuttx/lib/termios/Make.defs
      deleted file mode 100644
      index a6bb77f835..0000000000
      --- a/nuttx/lib/termios/Make.defs
      +++ /dev/null
      @@ -1,54 +0,0 @@
      -############################################################################
      -# lib/misc/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# termios.h support requires file descriptors and that CONFIG_SERIAL_TERMIOS
      -# is defined
      -
      -ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
      -ifeq ($(CONFIG_SERIAL_TERMIOS),y)
      -
      -# Add the termios C files to the build
      -
      -CSRCS += lib_cfgetspeed.c lib_cfsetspeed.c lib_tcflush.c
      -CSRCS += lib_tcgetattr.c lib_tcsetattr.c
      -
      -# Add the termios directory to the build
      -
      -DEPPATH += --dep-path termios
      -VPATH += termios
      -
      -endif
      -endif
      -
      diff --git a/nuttx/lib/termios/lib_cfgetspeed.c b/nuttx/lib/termios/lib_cfgetspeed.c
      deleted file mode 100644
      index d7f0dc4736..0000000000
      --- a/nuttx/lib/termios/lib_cfgetspeed.c
      +++ /dev/null
      @@ -1,93 +0,0 @@
      -/****************************************************************************
      - * lib/termios/lib_cfgetspeed.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: cfgetspeed
      - *
      - * Descripton:
      - *   The cfgetspeed() function is a non-POSIX function will extract the baud
      - *   from the termios structure to which the termiosp argument points.
      - *
      - *   This function will return exactly the value in the termios data
      - *   structure, without interpretation.
      - *
      - *   NOTE 1: NuttX does not control input/output baud independently.  Both
      - *   must be the same.  The POSIX standard interfaces, cfisetispeed() and
      - *   cfisetospeed() are defined to be cfgetspeed() in termios.h.
      - *   NOTE 2.  In Nuttx, the speed_t is defined to be uint32_t and the baud
      - *   encodings of termios.h are the actual baud values themselves.  Therefore,
      - *   any baud value may be returned here... not just those enumerated in
      - *   termios.h
      - *
      - * Input Parameters:
      - *   termiosp - The termiosp argument is a pointer to a termios structure.
      - *
      - * Returned Value:
      - *   Encoded baud value from the termios structure. 
      - *
      - ****************************************************************************/
      -
      -speed_t cfgetspeed(FAR const struct termios *termiosp)
      -{
      -  DEBUGASSERT(termiosp);
      -  return termiosp->c_speed;
      -}
      diff --git a/nuttx/lib/termios/lib_cfsetspeed.c b/nuttx/lib/termios/lib_cfsetspeed.c
      deleted file mode 100644
      index 714562ff50..0000000000
      --- a/nuttx/lib/termios/lib_cfsetspeed.c
      +++ /dev/null
      @@ -1,116 +0,0 @@
      -/****************************************************************************
      - * lib/termios/lib_cfsetspeed.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: cfsetspeed
      - *
      - * Descripton:
      - *   The cfsetspeed() function is a non-POSIX function that sets the baud
      - *   stored in the structure pointed to by termiosp to speed.
      - *
      - *   There is no effect on the baud set in the hardware until a subsequent
      - *   successful call to tcsetattr() on the same termios structure. 
      - *
      - *   NOTE 1: NuttX does not control input/output baud independently.  Both
      - *   must be the same.  The POSIX standard interfaces, cfisetispeed() and
      - *   cfisetospeed() are defined to be cfsetspeed() in termios.h.
      - *
      - *   NOTE 3:  A consequence of NOTE 1 is that you should never attempt to
      - *   set the input and output baud to different values.
      - *
      - *   Also, the following POSIX requirement cannot be supported: "If the input
      - *   baud rate stored in the termios structure pointed to by termios_p is 0,
      - *   the input baud rate given to the hardware will be the same as the output
      - *   baud rate stored in the termios structure."
      - *
      - *   NOTE 2.  In Nuttx, the speed_t is defined to be uint32_t and the baud
      - *   encodings of termios.h are the actual baud values themselves.  Therefore,
      - *   any baud value can be provided as the speed argument here.  However, if
      - *   you do so, your code will *NOT* be portable to other environments where
      - *   speed_t is smaller and where the termios.h baud values are encoded! To
      - *   avoid portability issues, use the baud definitions in termios.h!
      - *
      - *   Linux, for example, would require this (also non-portable) sequence:
      - *
      - *     cfsetispeed(termiosp, BOTHER);
      - *     termiosp->c_ispeed = baud;
      - *
      - *     cfsetospeed(termiosp, BOTHER);
      - *     termiosp->c_ospeed = baud;
      - *
      - * Input Parameters:
      - *   termiosp - The termiosp argument is a pointer to a termios structure.
      - *   speed - The new input speed
      - *
      - * Returned Value:
      - *   Baud is not checked... OK is always returned (this is non-standard
      - *   behavior). 
      - *
      - ****************************************************************************/
      -
      -int cfsetspeed(FAR struct termios *termiosp, speed_t speed)
      -{
      -  DEBUGASSERT(termiosp);
      -  termiosp->c_speed = speed;
      -  return OK;
      -}
      diff --git a/nuttx/lib/termios/lib_tcflush.c b/nuttx/lib/termios/lib_tcflush.c
      deleted file mode 100644
      index 338524bdda..0000000000
      --- a/nuttx/lib/termios/lib_tcflush.c
      +++ /dev/null
      @@ -1,88 +0,0 @@
      -/****************************************************************************
      - * lib/termios/lib_tcflush.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: tcflush
      - *
      - * Descripton:
      - *   Function for flushing a terminal/serial device
      - *
      - * Input Parameters:
      - *   fd  - The 'fd' argument is an open file descriptor associated with a terminal.
      - *   cmd - The TCFLSH ioctl argument.
      - *
      - * Returned Value:
      - *   Upon successful completion, 0 is returned. Otherwise, -1 is returned and
      - *   errno is set to indicate the error.
      - *
      - ****************************************************************************/
      -
      -int tcflush(int fd, int cmd)
      -{
      -  return ioctl(fd, TCFLSH, (unsigned long)cmd);
      -}
      diff --git a/nuttx/lib/termios/lib_tcgetattr.c b/nuttx/lib/termios/lib_tcgetattr.c
      deleted file mode 100644
      index 500871d9ff..0000000000
      --- a/nuttx/lib/termios/lib_tcgetattr.c
      +++ /dev/null
      @@ -1,93 +0,0 @@
      -/****************************************************************************
      - * lib/termios/lib_tcgetattr.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: tcgetattr
      - *
      - * Descripton:
      - *   The tcgetattr() function gets the parameters associated with the
      - *   terminal referred to by 'fd' and stores them in the termios structure
      - *   referenced by 'termiosp'.
      - *
      - * Input Parameters:
      - *   fd - The 'fd' argument is an open file descriptor associated with a terminal.
      - *   termiosp - The termiosp argument is a pointer to a termios structure.
      - *
      - * Returned Value:
      - *   Upon successful completion, 0 is returned. Otherwise, -1 is returned and
      - *   errno is set to indicate the error.  The following errors may be reported:
      - *
      - *   - EBADF: The 'fd' argument is not a valid file descriptor. 
      - *   - ENOTTY: The file associated with 'fd' is not a terminal. 
      - *
      - ****************************************************************************/
      -
      -int tcgetattr(int fd, FAR struct termios *termiosp)
      -{
      -  return ioctl(fd, TCGETS, (unsigned long)termiosp);
      -}
      diff --git a/nuttx/lib/termios/lib_tcsetattr.c b/nuttx/lib/termios/lib_tcsetattr.c
      deleted file mode 100644
      index 791b519c85..0000000000
      --- a/nuttx/lib/termios/lib_tcsetattr.c
      +++ /dev/null
      @@ -1,122 +0,0 @@
      -/****************************************************************************
      - * lib/termios/lib_tcsetattr.c
      - *
      - *   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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: tcsetattr
      - *
      - * Descripton:
      - *   The tcsetattr() function sets the parameters associated with the
      - *   terminal referred to by the open file descriptor 'fd' from the termios
      - *   structure referenced by 'termiop' as follows:
      - *
      - *   If 'options' is TCSANOW, the change will occur immediately.
      - *
      - *   If 'options' is TCSADRAIN, the change will occur after all output
      - *   written to 'fd' is transmitted. This function should be used when changing
      - *   parameters that affect output.
      - *
      - *   If 'options' is TCSAFLUSH, the change will occur after all
      - *   output written to 'fd' is transmitted, and all input so far received but
      - *   not read will be discarded before the change is made.
      - *
      - *   The tcsetattr() function will return successfully if it was able to
      - *   perform any of the requested actions, even if some of the requested
      - *   actions could not be performed. It will set all the attributes that
      - *   implementation supports as requested and leave all the attributes not
      - *   supported by the implementation unchanged. If no part of the request
      - *   can be honoured, it will return -1 and set errno to EINVAL.
      - *
      - *   The effect of tcsetattr() is undefined if the value of the termios
      - *   structure pointed to by 'termiop' was not derived from the result of
      - *   a call to tcgetattr() on 'fd'; an application should modify only fields
      - *   and flags defined by this specification between the call to tcgetattr()
      - *   and tcsetattr(), leaving all other fields and flags unmodified.
      - *
      - * Returned Value:
      - *
      - *   Upon successful completion, 0 is returned. Otherwise, -1 is returned
      - *   and errno is set to indicate the error.  The following errors may be
      - *   reported:
      - *
      - *   - EBADF: The 'fd' argument is not a valid file descriptor. 
      - *   - EINTR:  A signal interrupted tcsetattr(). 
      - *   - EINVAL: The 'options' argument is not a supported value, or
      - *     an attempt was made to change an attribute represented in the
      - *     termios structure to an unsupported value. 
      - *   - ENOTTY: The file associated with 'fd' is not a terminal. 
      - *
      - ****************************************************************************/
      -
      -int tcsetattr(int fd, int options, FAR const struct termios *termiosp)
      -{
      -  if (options == TCSANOW)
      -    {
      -      return ioctl(fd, TCSETS, (unsigned long)termiosp);
      -    }
      -  return -ENOSYS;
      -}
      diff --git a/nuttx/lib/time/Make.defs b/nuttx/lib/time/Make.defs
      deleted file mode 100644
      index ab74142291..0000000000
      --- a/nuttx/lib/time/Make.defs
      +++ /dev/null
      @@ -1,44 +0,0 @@
      -############################################################################
      -# lib/time/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the time C files to the build
      -
      -CSRCS += lib_mktime.c lib_gmtime.c lib_gmtimer.c lib_strftime.c \
      -		  lib_calendar2utc.c lib_daysbeforemonth.c lib_isleapyear.c lib_time.c
      -
      -# Add the time directory to the build
      -
      -DEPPATH += --dep-path time
      -VPATH += :time
      diff --git a/nuttx/lib/time/lib_calendar2utc.c b/nuttx/lib/time/lib_calendar2utc.c
      deleted file mode 100644
      index e80c292fc6..0000000000
      --- a/nuttx/lib/time/lib_calendar2utc.c
      +++ /dev/null
      @@ -1,209 +0,0 @@
      -/****************************************************************************
      - * lib/time/lib_calendar2utc.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  clock_gregorian2utc, clock_julian2utc
      - *
      - * Description:
      - *    UTC conversion routines.  These conversions are based
      - *    on algorithms from p. 604 of Seidelman, P. K. 1992.
      - *    Explanatory Supplement to the Astronomical Almanac.
      - *    University Science Books, Mill Valley. 
      - *
      - ****************************************************************************/
      -
      -#ifdef CONFIG_GREGORIAN_TIME
      -static time_t clock_gregorian2utc(int year, int month, int day)
      -{
      -  int temp;
      -
      -  /* temp = (month - 14)/12; */
      -
      -  temp = (month <= 2 ? -1:0);
      -
      -  return (1461*(year + 4800 + temp))/4
      -    + (367*(month - 2 - 12*temp))/12
      -    - (3*((year + 4900 + temp)/100))/4 + day - 32075;
      -}
      -
      -#ifdef CONFIG_JULIAN_TIME
      -static time_t clock_julian2utc(int year, int month, int day)
      -{
      -  return 367*year
      -    - (7*(year + 5001 + (month-9)/7))/4
      -    + (275*month)/9
      -    + day + 1729777;
      -}
      -#endif /* CONFIG_JULIAN_TIME */
      -#endif /* CONFIG_GREGORIAN_TIME */
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  clock_calendar2utc
      - *
      - * Description:
      - *    Calendar/UTC conversion based on algorithms from p. 604
      - *    of Seidelman, P. K. 1992.  Explanatory Supplement to
      - *    the Astronomical Almanac.  University Science Books,
      - *    Mill Valley. 
      - *
      - ****************************************************************************/
      -
      -#ifdef CONFIG_GREGORIAN_TIME
      -time_t clock_calendar2utc(int year, int month, int day)
      -{
      -  int dyear;
      -#ifdef CONFIG_JULIAN_TIME
      -  bool isgreg;
      -#endif /* CONFIG_JULIAN_TIME */
      -
      -  /* Correct year & month ranges.  Shift month into range 1-12 */
      -
      -  dyear = (month-1) / 12;	
      -  month -= 12 * dyear;
      -  year += dyear;
      -
      -  if (month < 1)
      -    {
      -      month += 12;
      -      year -= 1;
      -    }
      -
      -#ifdef CONFIG_JULIAN_TIME
      -  /* Determine which calendar to use */
      -
      -  if (year > GREG_YEAR)
      -    {
      -      isgreg = true;
      -    }
      -  else if (year < GREG_YEAR)
      -    {
      -      isgreg = false;
      -    }
      -  else if (month > GREG_MONTH)
      -    {
      -      isgreg = true;
      -    }
      -  else if (month < GREG_MONTH)
      -    {
      -      isgreg = false;
      -    }
      -  else
      -    {
      -      isgreg = (day >= GREG_DAY);
      -    }
      -
      -  /* Calculate and return date */
      -
      -  if (isgreg)
      -    {
      -      return clock_gregorian2utc(year, month, day) - JD_OF_EPOCH;
      -    }
      -  else
      -    {
      -      return clock_julian2utc (year, month, day) - JD_OF_EPOCH;
      -    }
      -
      -#else /* CONFIG_JULIAN_TIME */
      -
      -  return clock_gregorian2utc(year, month, day) - JD_OF_EPOCH;
      -
      -#endif /* CONFIG_JULIAN_TIME */
      -}
      -#else
      -
      -/* A highly simplified version that only handles days in the time
      - * since Jan 1, 1970.
      - */
      -
      -time_t clock_calendar2utc(int year, int month, int day)
      -{
      -  struct tm t;
      -
      -  /* mktime can (kind of) do this */
      -
      -  t.tm_year = year;
      -  t.tm_mon  = month;
      -  t.tm_mday = day;
      -  t.tm_hour = 0;
      -  t.tm_min  = 0;
      -  t.tm_sec  = 0;
      -  return mktime(&t);
      -}
      -#endif /* CONFIG_GREGORIAN_TIME */
      -
      diff --git a/nuttx/lib/time/lib_daysbeforemonth.c b/nuttx/lib/time/lib_daysbeforemonth.c
      deleted file mode 100644
      index 8000b0e7a9..0000000000
      --- a/nuttx/lib/time/lib_daysbeforemonth.c
      +++ /dev/null
      @@ -1,102 +0,0 @@
      -/****************************************************************************
      - * lib/time/lib_daysbeforemonth.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -uint16_t g_daysbeforemonth[13] =
      -{
      -  0, 31, 59, 90, 120, 151, 181, 212, 243, 273, 304, 334, 365
      -};
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  clock_daysbeforemonth
      - *
      - * Description:
      - *    Get the number of days that occurred before the beginning of the month.
      - *
      - ****************************************************************************/
      -
      -int clock_daysbeforemonth(int month, bool leapyear)
      -{
      -  int retval = g_daysbeforemonth[month];
      -  if (month >= 2 && leapyear)
      -    {
      -      retval++;
      -    }
      -  return retval;
      -}
      -
      -
      diff --git a/nuttx/lib/time/lib_gmtime.c b/nuttx/lib/time/lib_gmtime.c
      deleted file mode 100644
      index 99afeded9e..0000000000
      --- a/nuttx/lib/time/lib_gmtime.c
      +++ /dev/null
      @@ -1,93 +0,0 @@
      -/****************************************************************************
      - * lib/time/lib_gmtime.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Public Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Private Variables
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  gmtime
      - *
      - * Description:
      - *  Similar to gmtime_r, but not thread-safe
      - *
      - ****************************************************************************/
      -
      -struct tm *gmtime(const time_t *timer)
      -{
      -  static struct tm tm;
      -  return gmtime_r(timer, &tm);
      -}
      -
      diff --git a/nuttx/lib/time/lib_gmtimer.c b/nuttx/lib/time/lib_gmtimer.c
      deleted file mode 100644
      index ba1c9724f1..0000000000
      --- a/nuttx/lib/time/lib_gmtimer.c
      +++ /dev/null
      @@ -1,355 +0,0 @@
      -/****************************************************************************
      - * lib/time/lib_gmtimer.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -#define SEC_PER_MIN  ((time_t)60)
      -#define SEC_PER_HOUR ((time_t)60 * SEC_PER_MIN)
      -#define SEC_PER_DAY  ((time_t)24 * SEC_PER_HOUR)
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/* Calendar/UTC conversion routines */
      -
      -static void   clock_utc2calendar(time_t utc, int *year, int *month, int *day);
      -#ifdef CONFIG_GREGORIAN_TIME
      -static void   clock_utc2gregorian (time_t jdn, int *year, int *month, int *day);
      -
      -#ifdef CONFIG_JULIAN_TIME
      -static void   clock_utc2julian(time_t jdn, int *year, int *month, int *day);
      -#endif /* CONFIG_JULIAN_TIME */
      -#endif /* CONFIG_GREGORIAN_TIME */
      -
      -/**************************************************************************
      - * Public Constant Data
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/**************************************************************************
      - * Private Variables
      - **************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  clock_calendar2utc, clock_gregorian2utc,
      - *            and clock_julian2utc
      - *
      - * Description:
      - *    Calendar to UTC conversion routines.  These conversions
      - *    are based on algorithms from p. 604 of Seidelman, P. K.
      - *    1992.  Explanatory Supplement to the Astronomical
      - *    Almanac.  University Science Books, Mill Valley. 
      - *
      - ****************************************************************************/
      -
      -#ifdef CONFIG_GREGORIAN_TIME
      -static void clock_utc2calendar(time_t utc, int *year, int *month, int *day)
      -{
      -#ifdef CONFIG_JULIAN_TIME
      -
      -  if (utc >= GREG_DUTC)
      -    {
      -      clock_utc2gregorian(utc + JD_OF_EPOCH, year, month, day);
      -    }
      -  else
      -    {
      -      clock_utc2julian (utc + JD_OF_EPOCH, year, month, day);
      -    }
      -
      -#else /* CONFIG_JULIAN_TIME */
      -
      -  clock_utc2gregorian(utc + JD_OF_EPOCH, year, month, day);
      -
      -#endif /* CONFIG_JULIAN_TIME */
      -}
      -
      -static void clock_utc2gregorian(time_t jd, int *year, int *month, int *day)
      -{
      -  long	l, n, i, j, d, m, y;
      -
      -  l = jd + 68569;
      -  n = (4*l) / 146097;
      -  l = l - (146097*n + 3)/4;
      -  i = (4000*(l+1))/1461001;
      -  l = l - (1461*i)/4 + 31;
      -  j = (80*l)/2447;
      -  d = l - (2447*j)/80;
      -  l = j/11;
      -  m = j + 2 - 12*l;
      -  y = 100*(n-49) + i + l;
      -
      -  *year  = y;
      -  *month = m;
      -  *day   = d;
      -}
      -
      -#ifdef CONFIG_JULIAN_TIME
      -
      -static void clock_utc2julian(time_t jd, int *year, int *month, int *day)
      -{
      -  long	j, k, l, n, d, i, m, y;
      -
      -  j = jd + 1402;
      -  k = (j-1)/1461;
      -  l = j - 1461*k;
      -  n = (l-1)/365 - l/1461;
      -  i = l - 365*n + 30;
      -  j = (80*i)/2447;
      -  d = i - (2447*j)/80;
      -  i = j/11;
      -  m = j + 2 - 12*i;
      -  y = 4*k + n + i - 4716;
      -
      -  *year  = y;
      -  *month = m;
      -  *day   = d;
      -}
      -
      -#endif /* CONFIG_JULIAN_TIME */
      -#else/* CONFIG_GREGORIAN_TIME */
      -
      -/* Only handles dates since Jan 1, 1970 */
      -
      -static void clock_utc2calendar(time_t days, int *year, int *month, int *day)
      -{
      -  int  value;
      -  int  min;
      -  int  max;
      -  int  tmp;
      -  bool leapyear;
      -
      -  /* There is one leap year every four years, so we can get close with the
      -   * following:
      -   */
      -
      -  value   = days  / (4*365 + 1);  /* Number of 4-years periods since the epoch*/
      -  days   -= value * (4*365 + 1);  /* Remaining days */
      -  value <<= 2;                    /* Years since the epoch */
      -
      -  /* Then we will brute force the next 0-3 years */
      -
      -  for (;;)
      -    {
      -      /* Is this year a leap year (we'll need this later too) */
      -
      -      leapyear = clock_isleapyear(value + 1970);
      -
      -      /* Get the number of days in the year */
      -
      -      tmp = (leapyear ? 366 : 365);
      -
      -      /* Do we have that many days? */
      -
      -      if (days >= tmp)
      -        {
      -           /* Yes.. bump up the year */
      -
      -           value++;
      -           days -= tmp;
      -        }
      -      else
      -        {
      -           /* Nope... then go handle months */
      -
      -           break;
      -        }
      -    }
      -
      -  /* At this point, value has the year and days has number days into this year */
      -
      -  *year = 1970 + value;
      -
      -  /* Handle the month (zero based) */
      -
      -  min = 0;
      -  max = 11;
      -
      -  do
      -    {
      -      /* Get the midpoint */
      -
      -      value = (min + max) >> 1;
      -
      -      /* Get the number of days that occurred before the beginning of the month
      -       * following the midpoint.
      -      */
      -
      -      tmp = clock_daysbeforemonth(value + 1, leapyear);
      -
      -      /* Does the number of days before this month that equal or exceed the
      -       * number of days we have remaining?
      -       */
      -
      -      if (tmp > days)
      -        {
      -          /* Yes.. then the month we want is somewhere from 'min' and to the
      -           * midpoint, 'value'.  Could it be the midpoint?
      -           */
      -
      -          tmp = clock_daysbeforemonth(value, leapyear);
      -          if (tmp > days)
      -            {
      -              /* No... The one we want is somewhere between min and value-1 */
      -
      -              max = value - 1;
      -            }
      -          else
      -            {
      -              /* Yes.. 'value' contains the month that we want */
      -
      -              break;
      -            }
      -        }
      -      else
      -        {
      -           /* No... The one we want is somwhere between value+1 and max */
      -
      -           min = value + 1;
      -        }
      -
      -      /* If we break out of the loop because min == max, then we want value
      -       * to be equal to min == max.
      -       */
      -
      -      value = min;
      -    }
      -  while (min < max);
      -
      -  /* The selected month number is in value. Subtract the number of days in the
      -   * selected month
      -   */
      -
      -  days -= clock_daysbeforemonth(value, leapyear);
      -
      -  /* At this point, value has the month into this year (zero based) and days has
      -   * number of days into this month (zero based)
      -   */
      -
      -  *month = value + 1; /* 1-based */
      -  *day   = days + 1;  /* 1-based */
      -}
      -
      -#endif /* CONFIG_GREGORIAN_TIME */
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  gmtime_r
      - *
      - * Description:
      - *  Time conversion (based on the POSIX API)
      - *
      - ****************************************************************************/
      -
      -FAR struct tm *gmtime_r(FAR const time_t *timer, FAR struct tm *result)
      -{
      -  time_t epoch;
      -  time_t jdn;
      -  int    year;
      -  int    month;
      -  int    day;
      -  int    hour;
      -  int    min;
      -  int    sec;
      -
      -  /* Get the seconds since the EPOCH */
      -
      -  epoch = *timer;
      -  sdbg("timer=%d\n", (int)epoch);
      -
      -  /* Convert to days, hours, minutes, and seconds since the EPOCH */
      -
      -  jdn    = epoch / SEC_PER_DAY;
      -  epoch -= SEC_PER_DAY * jdn;
      -
      -  hour   = epoch / SEC_PER_HOUR;
      -  epoch -= SEC_PER_HOUR * hour;
      -
      -  min    = epoch / SEC_PER_MIN;
      -  epoch -= SEC_PER_MIN * min;
      -
      -  sec    = epoch;
      -
      -  sdbg("hour=%d min=%d sec=%d\n",
      -       (int)hour, (int)min, (int)sec);
      -
      -  /* Convert the days since the EPOCH to calendar day */
      -
      -  clock_utc2calendar(jdn, &year, &month, &day);
      -
      -  sdbg("jdn=%d year=%d month=%d day=%d\n",
      -       (int)jdn, (int)year, (int)month, (int)day);
      -
      -  /* Then return the struct tm contents */
      -
      -  result->tm_year = (int)year - 1900; /* Relative to 1900 */
      -  result->tm_mon  = (int)month - 1;   /* zero-based */
      -  result->tm_mday = (int)day;         /* one-based */
      -  result->tm_hour = (int)hour;
      -  result->tm_min  = (int)min;
      -  result->tm_sec  = (int)sec;
      -
      -  return result;
      -}
      -
      diff --git a/nuttx/lib/time/lib_isleapyear.c b/nuttx/lib/time/lib_isleapyear.c
      deleted file mode 100644
      index 966c248e01..0000000000
      --- a/nuttx/lib/time/lib_isleapyear.c
      +++ /dev/null
      @@ -1,88 +0,0 @@
      -/****************************************************************************
      - * lib/time/lib_isleapyear.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  clock_isleapyear
      - *
      - * Description:
      - *    Return true if the specified year is a leap year
      - *
      - ****************************************************************************/
      -
      -int clock_isleapyear(int year)
      -{
      -  return year % 400 ? (year % 100 ? (year % 4 ? 0 : 1) : 0) : 1;
      -}
      -
      diff --git a/nuttx/lib/time/lib_mktime.c b/nuttx/lib/time/lib_mktime.c
      deleted file mode 100644
      index 8c17e7c0ab..0000000000
      --- a/nuttx/lib/time/lib_mktime.c
      +++ /dev/null
      @@ -1,141 +0,0 @@
      -/****************************************************************************
      - * lib/time/lib_mktime.c
      - *
      - *   Copyright (C) 2007, 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  mktime
      - *
      - * Description:
      - *  Time conversion (based on the POSIX API)
      - *
      - ****************************************************************************/
      -
      -#ifdef CONFIG_GREGORIAN_TIME
      -time_t mktime(const struct tm *tp)
      -{
      -  time_t ret;
      -  time_t jdn;
      -
      -  /* Get the EPOCH-relative julian date from the calendar year,
      -   * month, and date
      -   */
      -
      -  jdn = clock_calendar2utc(tp->tm_year+1900, tp->tm_mon+1, tp->tm_mday);
      -  sdbg("jdn=%d tm_year=%d tm_mon=%d tm_mday=%d\n",
      -       (int)jdn, tp->tm_year, tp->tm_mon, tp->tm_mday);
      -
      -  /* Return the seconds into the julian day. */
      -
      -  ret = ((jdn*24 + tp->tm_hour)*60 + tp->tm_min)*60 + tp->tm_sec;
      -  sdbg("ret=%d tm_hour=%d tm_min=%d tm_sec=%d\n",
      -       (int)ret, tp->tm_hour, tp->tm_min, tp->tm_sec);
      -
      -  return ret;
      -}
      -#else
      -
      -/* Simple version that only works for dates within a (relatively) small range
      - * from the epoch.  It does not handle earlier days or longer days where leap
      - * seconds, etc. apply.
      - */
      -
      -time_t mktime(const struct tm *tp)
      -{
      -  unsigned int days;
      -
      -  /* Years since epoch in units of days (ignoring leap years). */
      -
      -  days = (tp->tm_year - 70) * 365;
      -
      -  /* Add in the extra days for the leap years prior to the current year. */
      -
      -  days += (tp->tm_year - 69) >> 2;
      -
      -  /* Add in the days up to the beginning of this month. */
      -
      -  days += (time_t)clock_daysbeforemonth(tp->tm_mon, clock_isleapyear(tp->tm_year + 1900));
      -
      -  /* Add in the days since the beginning of this month (days are 1-based). */
      -
      -  days += tp->tm_mday - 1;
      -
      -  /* Then convert the seconds and add in hours, minutes, and seconds */
      -
      -  return ((days * 24 + tp->tm_hour) * 60 + tp->tm_min) * 60 + tp->tm_sec;
      -}
      -#endif /* CONFIG_GREGORIAN_TIME */
      -
      diff --git a/nuttx/lib/time/lib_strftime.c b/nuttx/lib/time/lib_strftime.c
      deleted file mode 100644
      index cd0804f55d..0000000000
      --- a/nuttx/lib/time/lib_strftime.c
      +++ /dev/null
      @@ -1,398 +0,0 @@
      -/****************************************************************************
      - * lib/time/lib_strftime.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Type Declarations
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Function Prototypes
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Constant Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Data
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Data
      - ****************************************************************************/
      -
      -static const char * const g_abbrevmonthname[12] =
      -{
      -  "Jan", "Feb", "Mar", "Apr", "May", "Jun",
      -  "Jul", "Aug", "Sep", "Oct", "Nov", "Dec"
      -};
      -
      -static const char * const g_monthname[12] =
      -{
      -  "January", "February", "March",     "April",   "May",      "June",
      -  "July",    "August",   "September", "October", "November", "December"
      -};
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  strftime
      - *
      - * Description:
      - *   The  strftime()  function  formats the broken-down time tm according to
      - *   the format specification format and places the result in the  character
      - *   array s of size max.
      - *
      - *   Ordinary characters placed in the format string are copied to s without
      - *   conversion.  Conversion specifications are introduced by a '%'  charac-
      - *   ter,  and  terminated  by  a  conversion  specifier  character, and are
      - *   replaced in s as follows:
      - *
      - *   %b     The abbreviated month name according to the current locale.
      - *   %B     The full month name according to the current locale.
      - *   %C     The century number (year/100) as a 2-digit integer. (SU)
      - *   %d     The day of the month as a decimal number (range 01 to 31).
      - *   %e     Like %d, the day of the month as a decimal number, but a leading
      - *          zero is replaced by a space.
      - *   %h     Equivalent to %b.  (SU)
      - *   %H     The hour as a decimal number using a 24-hour clock (range 00 to 23).
      - *   %I     The  hour as a decimal number using a 12-hour clock (range 01 to 12).
      - *   %j     The day of the year as a decimal number (range 001 to 366).
      - *   %k     The hour (24-hour clock) as a decimal number (range  0  to  23);
      - *          single digits are preceded by a blank.  (See also %H.)  (TZ)
      - *   %l     The  hour  (12-hour  clock) as a decimal number (range 1 to 12);
      - *          single digits are preceded by a blank.  (See also %I.)  (TZ)
      - *   %m     The month as a decimal number (range 01 to 12).
      - *   %M     The minute as a decimal number (range 00 to 59).
      - *   %n     A newline character. (SU)
      - *   %p     Either "AM" or "PM" according to the given time  value, or the
      - *          corresponding  strings  for the current locale.  Noon is treated
      - *          as "PM" and midnight as "AM".
      - *   %P     Like %p but in lowercase: "am" or "pm" or a corresponding string
      - *          for the current locale. (GNU)
      - *   %s     The number of seconds since the Epoch, that is, since 1970-01-01
      - *          00:00:00 UTC. (TZ)
      - *   %S     The second as a decimal number (range 00 to 60).  (The range is
      - *          up to 60 to allow for occasional leap seconds.)
      - *   %t     A tab character. (SU)
      - *   %y     The year as a decimal number without a century (range 00 to 99).
      - *   %Y     The year as a decimal number including the century.
      - *   %%     A literal '%' character.
      - *
      - * Returned Value:
      - *   The strftime() function returns the number of characters placed in  the
      - *    array s, not including the terminating null byte, provided the string,
      - *    including the terminating null byte, fits.  Otherwise,  it returns 0,
      - *    and the contents of the array is undefined. 
      - *
      - ****************************************************************************/
      -
      -size_t strftime(char *s, size_t max, const char *format, const struct tm *tm)
      -{
      -  const char *str;
      -  char       *dest   = s;
      -  int         chleft = max;
      -  int         value;
      -  int         len;
      -
      -  while (*format && chleft > 0)
      -    {
      -      /* Just copy regular characters */
      -
      -      if (*format != '%')
      -        {
      -           *dest++ = *format++;
      -           chleft--;
      -           continue;
      -        }
      -
      -      /* Handle the format character */
      -
      -       format++;
      -       len   = 0;
      -
      -       switch (*format++)
      -         {
      -           /* %a: A three-letter abbreviation for the day of the week. */
      -           /* %A: The full name for the day of the week. */
      -
      -           case 'a':
      -           case 'A':
      -             {
      -               len = snprintf(dest, chleft, "Day"); /* Not supported */
      -             }
      -             break;
      -           
      -           /* %h: Equivalent to %b */
      -
      -           case 'h':
      -
      -           /* %b: The abbreviated month name according to the current locale. */
      -
      -           case 'b':
      -             {
      -               if (tm->tm_mon < 12)
      -                 {
      -                   str = g_abbrevmonthname[tm->tm_mon];
      -                   len = snprintf(dest, chleft, "%s", str);
      -                 }
      -             }
      -             break;
      -
      -           /* %B: The full month name according to the current locale. */
      -
      -           case 'B':
      -             {
      -               if (tm->tm_mon < 12)
      -                 {
      -                   str = g_monthname[tm->tm_mon];
      -                   len = snprintf(dest, chleft, "%s", str);
      -                 }
      -             }
      -             break;
      -
      -           /* %y: The year as a decimal number without a century (range 00 to 99). */
      -
      -           case 'y':
      -
      -           /* %C: The century number (year/100) as a 2-digit integer. */
      -
      -           case 'C':
      -             {
      -               len = snprintf(dest, chleft, "%02d", tm->tm_year % 100);
      -             }
      -             break;
      -
      -           /* %d: The day of the month as a decimal number (range 01 to 31). */
      -
      -           case 'd':
      -             {
      -               len = snprintf(dest, chleft, "%02d", tm->tm_mday);
      -             }
      -             break;
      -
      -           /* %e: Like %d, the day of the month as a decimal number, but a leading
      -            * zero is replaced by a space.
      -            */
      -
      -           case 'e':
      -             {
      -               len = snprintf(dest, chleft, "%2d", tm->tm_mday);
      -             }
      -             break;
      -
      -           /* %H: The hour as a decimal number using a 24-hour clock (range 00  to 23). */
      -
      -           case 'H':
      -             {
      -               len = snprintf(dest, chleft, "%02d", tm->tm_hour);
      -             }
      -             break;
      -
      -           /* %I: The  hour as a decimal number using a 12-hour clock (range 01 to 12). */
      -
      -           case 'I':
      -             {
      -               len = snprintf(dest, chleft, "%02d", tm->tm_hour % 12);
      -             }
      -             break;
      -
      -           /* %j: The day of the year as a decimal number (range 001 to 366). */
      -
      -           case 'j':
      -             {
      -               if (tm->tm_mon < 12)
      -                 {
      -                   value = clock_daysbeforemonth(tm->tm_mon, clock_isleapyear(tm->tm_year)) + tm->tm_mday;
      -                   len   = snprintf(dest, chleft, "%03d", value);
      -                 }
      -             }
      -             break;
      -
      -           /* %k: The hour (24-hour clock) as a decimal number (range  0  to  23);
      -            * single digits are preceded by a blank.
      -            */
      -
      -           case 'k':
      -             {
      -               len = snprintf(dest, chleft, "%2d", tm->tm_hour);
      -             }
      -             break;
      -
      -           /* %l: The  hour  (12-hour  clock) as a decimal number (range 1 to 12);
      -            * single digits are preceded by a blank.
      -            */
      -
      -           case 'l':
      -             {
      -               len = snprintf(dest, chleft, "%2d", tm->tm_hour % 12);
      -             }
      -             break;
      -
      -           /* %m: The month as a decimal number (range 01 to 12). */
      -
      -           case 'm':
      -             {
      -               len = snprintf(dest, chleft, "%02d", tm->tm_mon + 1);
      -             }
      -             break;
      -
      -           /* %M: The minute as a decimal number (range 00 to 59). */
      -
      -           case 'M':
      -             {
      -               len = snprintf(dest, chleft, "%02d", tm->tm_min);
      -             }
      -             break;
      -
      -           /* %n: A newline character. */
      -
      -           case 'n':
      -             {
      -               *dest = '\n';
      -               len   = 1;
      -             }
      -             break;
      -
      -           /* %p: Either "AM" or "PM" according to the given time  value. */
      -
      -           case 'p':
      -             {
      -               if (tm->tm_hour >= 12)
      -                 {
      -                   str = "PM";
      -                 }
      -               else
      -                 {
      -                   str = "AM";
      -                 }
      -               len = snprintf(dest, chleft, "%s", str);
      -             }
      -             break;
      -
      -           /* %P: Like %p but in lowercase: "am" or "pm" */
      -
      -           case 'P':
      -             {
      -               if (tm->tm_hour >= 12)
      -                 {
      -                   str = "pm";
      -                 }
      -               else
      -                 {
      -                   str = "am";
      -                 }
      -               len = snprintf(dest, chleft, "%s", str);
      -             }
      -             break;
      -
      -           /* %s: The number of seconds since the Epoch, that is, since 1970-01-01
      -            * 00:00:00 UTC.
      -            */
      -
      -           case 's':
      -             {
      -               len = snprintf(dest, chleft, "%d", mktime(tm));
      -             }
      -             break;
      -
      -           /* %S: The second as a decimal number (range 00 to 60).  (The range  is
      -            * up to 60 to allow for occasional leap seconds.)
      -            */
      -
      -           case 'S':
      -             {
      -               len = snprintf(dest, chleft, "%02d", tm->tm_sec);
      -             }
      -             break;
      -
      -           /* %t: A tab character. */
      -
      -           case 't':
      -             {
      -               *dest = '\t';
      -               len   = 1;
      -             }
      -             break;
      -
      -           /* %Y: The year as a decimal number including the century. */
      -
      -           case 'Y':
      -             {
      -               len = snprintf(dest, chleft, "%04d", tm->tm_year + 1900);
      -             }
      -             break;
      -
      -           /* %%:  A literal '%' character. */
      -
      -           case '%':
      -             {
      -               *dest = '%';
      -               len   = 1;
      -             }
      -             break;
      -        }
      -
      -      /* Update counts and pointers */
      -
      -      dest   += len;
      -      chleft -= len;
      -    }
      -
      -  return max - chleft;
      -}
      diff --git a/nuttx/lib/time/lib_time.c b/nuttx/lib/time/lib_time.c
      deleted file mode 100644
      index 106a04c366..0000000000
      --- a/nuttx/lib/time/lib_time.c
      +++ /dev/null
      @@ -1,110 +0,0 @@
      -/****************************************************************************
      - * lib/time/lib_time.c
      - *
      - *   Copyright (C) 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -
      -#ifndef CONFIG_DISABLE_CLOCK
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Data
      - ****************************************************************************/
      - 
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Function:  time
      - *
      - * Description:
      - *   Get the current calendar time as a time_t object.  The function returns
      - *   this value, and if the argument is not a null pointer, the value is also
      - *   set to the object pointed by tloc.
      - *
      - *   Note that this function is just a thin wrapper around gettimeofday()
      - *   and is provided for compatibility.  gettimeofday() is the preffered way
      - *   to obtain system time.
      - *
      - * Parameters:
      - *   Pointer to an object of type time_t, where the time value is stored.
      - *   Alternativelly, this parameter can be a null pointer, in which case the
      - *   parameter is not used, but a time_t object is still returned by the
      - *   function.
      - *
      - * Return Value:
      - *   The current calendar time as a time_t object.  If the argument is not
      - *   a null pointer, the return value is the same as the one stored in the
      - *   location pointed by the argument.
      - *
      - *   If the function could not retrieve the calendar time, it returns a -1
      - *   value.
      - *
      - ****************************************************************************/
      -
      -time_t time(time_t *tloc)
      -{
      -  struct timeval tp;
      -  int ret;
      -
      -  /* Get the current time from the system */
      -
      -  ret = gettimeofday(&tp, NULL);
      -  if (ret == OK)
      -    {
      -      /* Return the seconds since the epoch */
      -
      -      if (tloc)
      -        {
      -          *tloc = tp.tv_sec;
      -        }
      -
      -      return tp.tv_sec;
      -    }
      -
      -  return (time_t)ERROR;
      -}
      -
      -#endif /* !CONFIG_DISABLE_CLOCK */
      diff --git a/nuttx/lib/unistd/Make.defs b/nuttx/lib/unistd/Make.defs
      deleted file mode 100644
      index e1441a48d3..0000000000
      --- a/nuttx/lib/unistd/Make.defs
      +++ /dev/null
      @@ -1,49 +0,0 @@
      -############################################################################
      -# lib/unistd/Make.defs
      -#
      -#   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.
      -#
      -############################################################################
      -
      -# Add the unistd C files to the build
      -
      -CSRCS += lib_getopt.c lib_getoptargp.c lib_getoptindp.c lib_getoptoptp.c
      -
      -ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
      -ifneq ($(CONFIG_DISABLE_ENVIRON),y)
      -CSRCS +=  lib_chdir.c lib_getcwd.c
      -endif
      -endif
      -
      -# Add the unistd directory to the build
      -
      -DEPPATH += --dep-path unistd
      -VPATH += :unistd
      diff --git a/nuttx/lib/unistd/lib_chdir.c b/nuttx/lib/unistd/lib_chdir.c
      deleted file mode 100644
      index 3dd1333cec..0000000000
      --- a/nuttx/lib/unistd/lib_chdir.c
      +++ /dev/null
      @@ -1,179 +0,0 @@
      -/****************************************************************************
      - * lib/unistd/lib_chdir.c
      - *
      - *   Copyright (C) 2008-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: _trimdir
      - ****************************************************************************/
      -
      -#if 0
      -static inline void _trimdir(char *path)
      -{
      - /* Skip any trailing '/' characters (unless it is also the leading '/') */
      -
      - int len = strlen(path) - 1;
      - while (len > 0 && path[len] == '/')
      -   {
      -      path[len] = '\0';
      -      len--;
      -   }
      -}
      -#else
      -#  define _trimdir(p)
      -#endif
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: chdir
      - *
      - * Description:
      - *   The chdir() function causes the directory named by the pathname pointed
      - *   to by the 'path' argument to become the current working directory; that
      - *   is, the starting point for path searches for pathnames not beginning
      - *   with '/'.
      - *
      - * Input Parmeters:
      - *   path - A pointer to a directory to use as the new current working
      - *     directory
      - *
      - * Returned Value:
      - *   0(OK) on success; -1(ERROR) on failure with errno set appropriately:
      - *
      - *   EACCES
      - *     Search permission is denied for any component of the pathname.
      - *   ELOOP
      - *     A loop exists in symbolic links encountered during resolution of the
      - *     'path' argument OR more that SYMLOOP_MAX symbolic links in the
      - *     resolution of the 'path' argument.
      - *   ENAMETOOLONG
      - *     The length of the path argument exceeds PATH_MAX or a pathname component
      - *     is longer than NAME_MAX.
      - *   ENOENT
      - *     A component of 'path' does not name an existing directory or path is
      - *     an empty string.
      - *   ENOTDIR
      - *     A component of the pathname is not a directory.
      - *
      - ****************************************************************************/
      -
      -int chdir(FAR const char *path)
      -{
      -  struct stat buf;
      -  char *oldpwd;
      -  char *alloc;
      -  int err;
      -  int ret;
      -
      -  /* Verify the input parameters */
      -
      -  if (!path)
      -    {
      -      err = ENOENT;
      -      goto errout;
      -    }
      -
      -  /* Verify that 'path' refers to a directory */
      -
      -  ret = stat(path, &buf);
      -  if (ret != 0)
      -    {
      -      err = ENOENT;
      -      goto errout;
      -    }
      -
      -  /* Something exists here... is it a directory? */
      -
      -  if (!S_ISDIR(buf.st_mode))
      -    {
      -      err = ENOTDIR;
      -      goto errout;
      -    }
      -
      -  /* Yes, it is a directory. Remove any trailing '/' characters from the path */
      -
      -  _trimdir(path);
      -
      -  /* Replace any preceding OLDPWD with the current PWD (this is to
      -   * support 'cd -' in NSH)
      -   */
      -
      -  sched_lock();
      -  oldpwd = getenv("PWD");
      -  if (!oldpwd)
      -    {
      -      oldpwd = CONFIG_LIB_HOMEDIR;
      -    }
      -
      -  alloc = strdup(oldpwd);  /* kludge needed because environment is realloc'ed */
      -  setenv("OLDPWD", alloc, TRUE);
      -  lib_free(alloc);
      -
      -  /* Set the cwd to the input 'path' */
      -
      -  setenv("PWD", path, TRUE);
      -  sched_unlock();
      -  return OK;
      -
      -errout:
      -  set_errno(err);
      -  return ERROR;
      -}
      -#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_DISABLE_ENVIRON */
      diff --git a/nuttx/lib/unistd/lib_getcwd.c b/nuttx/lib/unistd/lib_getcwd.c
      deleted file mode 100644
      index b94823300b..0000000000
      --- a/nuttx/lib/unistd/lib_getcwd.c
      +++ /dev/null
      @@ -1,132 +0,0 @@
      -/****************************************************************************
      - * lib/unistd/lib_getcwd.c
      - *
      - *   Copyright (C) 2008, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -#include 
      -#include 
      -
      -#include "lib_internal.h"
      -
      -#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)
      -
      -/****************************************************************************
      - * Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Public Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: getwcd
      - *
      - * Description:
      - *   getcwd() function places the absolute pathname of the current working
      - *   directory in the array pointed to by 'buf', and returns 'buf.' The
      - *   pathname copied to the array shall contain no components that are
      - *   symbolic links. The 'size' argument is the size in bytes of the
      - *   character array pointed to by the 'buf' argument.
      - *
      - * Input Parmeters:
      - *   buf - a pointer to the location in which the current working directory
      - *     pathaname is returned.
      - *   size - The size in bytes avaiable at 'buf'
      - *
      - * Returned Value:
      - *   Upon successful completion, getcwd() returns the 'buf' argument.
      - *   Otherwise, getcwd() returns a null pointer and sets errno to indicate
      - *   the error:
      - *
      - *   EINVAL
      - *     The 'size' argument is 0 or the 'buf' argument is NULL.
      - *   ERANGE
      - *     The size argument is greater than 0, but is smaller than the length
      - *     of the currrent working directory pathname +1.
      - *   EACCES
      - *     Read or search permission was denied for a component of the pathname.
      - *   ENOMEM
      - *  Insufficient storage space is available. 
      - *
      - ****************************************************************************/
      -
      -FAR char *getcwd(FAR char *buf, size_t size)
      -{
      -  char *pwd;
      -
      -  /* Verify input parameters */
      -
      -#ifdef CONFIG_DEBUG
      -  if (!buf || !size)
      -    {
      -      set_errno(EINVAL);
      -      return NULL;
      -    }
      -#endif
      -
      -  /* If no working directory is defined, then default to the home directory */
      -
      -  pwd = getenv("PWD");
      -  if (!pwd)
      -    {
      -      pwd = CONFIG_LIB_HOMEDIR;
      -    }
      -
      -  /* Verify that the cwd will fit into the user-provided buffer */
      -
      -  if (strlen(pwd) + 1 > size)
      -    {
      -      set_errno(ERANGE);
      -      return NULL;
      -    }
      -
      -  /* Copy the cwd to the user buffer */
      -
      -  strcpy(buf, pwd);
      -  sched_unlock();
      -  return buf;
      -}
      -#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_DISABLE_ENVIRON */
      diff --git a/nuttx/lib/unistd/lib_getopt.c b/nuttx/lib/unistd/lib_getopt.c
      deleted file mode 100644
      index 832d287213..0000000000
      --- a/nuttx/lib/unistd/lib_getopt.c
      +++ /dev/null
      @@ -1,269 +0,0 @@
      -/****************************************************************************
      - * lib/unistd/lib_getopt.c
      - *
      - *   Copyright (C) 2007-2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -FAR char *optarg; /* Optional argument following option */
      -int optind = 1;   /* Index into argv */
      -int optopt = '?'; /* unrecognized option character */
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -static FAR char *g_optptr       = NULL;
      -static bool      g_binitialized = false;
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: getopt
      - *
      - * Description: getopt() parses command-line arguments.  Its arguments argc
      - *   and argv are the argument count and array as passed to the main()
      - *   function on program invocation.  An element of argv that starts with
      - *   '-' is an option element. The characters of this element (aside from
      - *   the initial '-') are option characters. If getopt() is called repeatedly,
      - *   it returns successively each of the option characters from each of the
      - *   option elements.
      - *
      - *   If getopt() finds another option character, it returns that character,
      - *   updating the external variable optind and a static variable nextchar so
      - *   that the next call to getopt() can resume the scan with the following
      - *   option character or argv-element.
      - *
      - *   If there are no more option characters, getopt() returns -1. Then optind
      - *   is the index in argv of the first argv-element that is not an option.
      - *
      - *   The 'optstring' argument is a string containing the legitimate option
      - *   characters. If such a character is followed by a colon, this indicates
      - *   that the option requires an argument.  If an argument is required for an
      - *   option so getopt() places a pointer to the following text in the same
      - *   argv-element, or the text of the following argv-element, in optarg.
      - *
      - *   NOTES:
      - *   1. opterr is not supported and this implementation of getopt() never
      - *      printfs error messages.
      - *   2. getopt is NOT threadsafe!
      - *   3. This version of getopt() does not reset global variables until
      - *      -1 is returned.  As a result, your command line parsing loops
      - *      must call getopt() repeatedly and continue to parse if other
      - *      errors are returned ('?' or ':') until getopt() finally returns -1.
      - *     (You can also set optind to -1 to force a reset).
      - *
      - * Return: If an option was successfully found, then getopt() returns the
      - *   option character. If all command-line options have been parsed, then
      - *   getopt() returns -1.  If getopt() encounters an option character that
      - *   was not in optstring, then '?' is returned. If getopt() encounters an
      - *   option with a missing argument, then the return value depends on the
      - *   first character in optstring: if it is ':', then ':' is returned;
      - *   otherwise '?' is returned.
      - *
      - ****************************************************************************/
      -
      -int getopt(int argc, FAR char *const argv[], FAR const char *optstring)
      -{
      -  if (argv && optstring && argc > 1)
      -    {
      -      int noarg_ret = '?';
      -      char *optchar;
      -
      -      /* The inital value of optind is 1.  If getopt() is called again in the
      -       * program, optind must be reset to some value <= 1.
      -       */
      -
      -      if (optind < 1 || !g_binitialized)
      -        {
      -          optind         = 1;     /* Skip over the program name */
      -          g_optptr       = NULL;  /* Start at the beginning of the first argument */
      -          g_binitialized = true;  /* Now we are initialized */
      -        }
      -
      -      /* If the first character of opstring s ':', then ':' is in the event of
      -       * a missing argument. Otherwise '?' is returned.
      -       */
      -
      -      if (*optstring == ':')
      -        {
      -           noarg_ret = ':';
      -           optstring++;
      -        }
      -
      -      /* Are we resuming in the middle, or at the end of a string of arguments?
      -       * g_optptr == NULL means that we are started at the beginning of argv[optind];
      -       * *g_optptr == \0 means that we are starting at the beginning of optind+1
      -       */
      -
      -      while (!g_optptr || !*g_optptr)
      -        {
      -          /* We need to start at the beginning of the next argv. Check if we need
      -           * to increment optind
      -           */
      -
      -          if (g_optptr)
      -            {
      -              /* Yes.. Increment it and check for the case where where we have
      -               * processed everything in the argv[] array.
      -               */
      -
      -              optind++;
      -            }
      -
      -          /* Check for the end of the argument list */
      -
      -          g_optptr = argv[optind];
      -          if (!g_optptr)
      -            {
      -              /* There are no more arguments, we are finished */
      -
      -              g_binitialized = false;
      -              return ERROR;
      -            }
      -
      -          /* We are starting at the beginning of argv[optind].  In this case, the
      -           * first character must be '-'
      -           */
      -
      -          if (*g_optptr != '-')
      -            {
      -              /* The argument does not start with '-', we are finished */
      -
      -              g_binitialized = false;
      -              return ERROR;
      -            }
      -
      -          /* Skip over the '-' */
      -
      -          g_optptr++;
      -        }
      -
      -        /* Special case handling of "-" and "-:" */
      -
      -        if (!*g_optptr)
      -          {
      -             optopt = '\0'; /* We'll fix up g_optptr the next time we are called */
      -             return '?';
      -          }
      -
      -        /* Handle the case of "-:" */
      -
      -        if (*g_optptr == ':')
      -          {
      -            optopt = ':';
      -            g_optptr++;
      -            return '?';
      -          }
      -
      -        /* g_optptr now points at the next option and it is not something crazy.
      -         * check if the option is in the list of valid options.
      -         */
      -
      -        optchar = strchr(optstring, *g_optptr);
      -        if (!optchar)
      -          {
      -            /* No this character is not in the list of valid options */
      -
      -            optopt = *g_optptr;
      -            g_optptr++;
      -            return '?';
      -          }
      -
      -        /* Yes, the character is in the list of valid options.  Does it have an
      -         * required argument?
      -         */
      -
      -        if (optchar[1] != ':')
      -          {
      -            /* No, no arguments. Just return the character that we found */
      -
      -            g_optptr++;
      -            return *optchar;
      -          }
      -
      -        /* Yes, it has a required argument.  Is the required argument
      -         * immediately after the command in this same argument?
      -         */
      -
      -        if (g_optptr[1] != '\0')
      -          {
      -              /* Yes, return a pointer into the current argument */
      -
      -              optarg = &g_optptr[1];
      -              optind++;
      -              g_optptr = NULL;
      -              return *optchar;
      -          }
      -
      -        /* No.. is the optional argument the next argument in argv[] ? */
      -
      -        if (argv[optind+1] && *argv[optind+1] != '-')
      -          {
      -            /* Yes.. return that */
      -
      -            optarg = argv[optind+1];
      -            optind += 2;
      -            g_optptr = NULL;
      -            return *optchar;
      -          }
      -
      -        /* No argument was supplied */
      -
      -        optarg = NULL;
      -        optopt = *optchar;
      -        optind++;
      -        return noarg_ret;
      -    }
      -
      -  g_binitialized = false;
      -  return ERROR;
      -}
      diff --git a/nuttx/lib/unistd/lib_getoptargp.c b/nuttx/lib/unistd/lib_getoptargp.c
      deleted file mode 100644
      index 98a4850169..0000000000
      --- a/nuttx/lib/unistd/lib_getoptargp.c
      +++ /dev/null
      @@ -1,73 +0,0 @@
      -/****************************************************************************
      - * lib/unistd/lib_getoptargp.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: getoptargp
      - *
      - * Description:
      - *   Returns a pointer to optarg.  This function is only used for external
      - *   modules that need to access the base, global variable, optarg.
      - *
      - ****************************************************************************/
      -
      -FAR char **getoptargp(void)
      -{
      -  return &optarg;
      -}
      -
      diff --git a/nuttx/lib/unistd/lib_getoptindp.c b/nuttx/lib/unistd/lib_getoptindp.c
      deleted file mode 100644
      index 7714f8e708..0000000000
      --- a/nuttx/lib/unistd/lib_getoptindp.c
      +++ /dev/null
      @@ -1,73 +0,0 @@
      -/****************************************************************************
      - * lib/unistd/lib_getoptindp.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: getoptindp
      - *
      - * Description:
      - *   Returns a pointer to optind.  This function is only used for external
      - *   modules that need to access the base, global variable, optind.
      - *
      - ****************************************************************************/
      -
      -int *getoptindp(void)
      -{
      -  return &optind;
      -}
      -
      diff --git a/nuttx/lib/unistd/lib_getoptoptp.c b/nuttx/lib/unistd/lib_getoptoptp.c
      deleted file mode 100644
      index 4805b7ac3b..0000000000
      --- a/nuttx/lib/unistd/lib_getoptoptp.c
      +++ /dev/null
      @@ -1,73 +0,0 @@
      -/****************************************************************************
      - * lib/unistd/lib_getoptoptp.c
      - *
      - *   Copyright (C) 2009, 2011 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.
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Included Files
      - ****************************************************************************/
      -
      -#include 
      -
      -#include 
      -
      -/****************************************************************************
      - * Pre-processor Definitions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Private Variables
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Global Functions
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Name: getoptoptp
      - *
      - * Description:
      - *   Returns a pointer to optopt.  This function is only used for external
      - *   modules that need to access the base, global variable, optopt.
      - *
      - ****************************************************************************/
      -
      -int *getoptoptp(void)
      -{
      -  return &optopt;
      -}
      -
      diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile
      index 584af4e962..db5675ce76 100644
      --- a/nuttx/libxx/Makefile
      +++ b/nuttx/libxx/Makefile
      @@ -82,7 +82,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT))
       SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS)
       OBJS = $(AOBJS) $(COBJS) $(CXXOBJS)
       
      -BIN = liblibxx$(LIBEXT)
      +BIN = libcxx$(LIBEXT)
       
       all: $(BIN)
       
      
      From a09a1f220c52cde6dd94e8f82457c66f69d46e3d Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sat, 10 Nov 2012 16:06:01 +0000
      Subject: [PATCH 098/206] Trying to recover from deleted directory contents
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5329 42af7a65-404d-4744-a932-0658087f49c3
      ---
       nuttx/lib/Kconfig                             |  275 +++
       nuttx/lib/Makefile                            |  136 ++
       nuttx/lib/README.txt                          |   85 +
       nuttx/lib/dirent/Make.defs                    |   48 +
       nuttx/lib/dirent/lib_readdirr.c               |  122 ++
       nuttx/lib/dirent/lib_telldir.c                |   91 +
       nuttx/lib/fixedmath/Make.defs                 |   43 +
       nuttx/lib/fixedmath/lib_b16atan2.c            |  108 ++
       nuttx/lib/fixedmath/lib_b16cos.c              |   64 +
       nuttx/lib/fixedmath/lib_b16sin.c              |  110 ++
       nuttx/lib/fixedmath/lib_fixedmath.c           |  272 +++
       nuttx/lib/fixedmath/lib_rint.c                |  135 ++
       nuttx/lib/lib.csv                             |  171 ++
       nuttx/lib/lib_internal.h                      |  211 +++
       nuttx/lib/libgen/Make.defs                    |   43 +
       nuttx/lib/libgen/lib_basename.c               |  131 ++
       nuttx/lib/libgen/lib_dirname.c                |  144 ++
       nuttx/lib/math/Kconfig                        |   26 +
       nuttx/lib/math/Make.defs                      |   62 +
       nuttx/lib/math/lib_acos.c                     |   46 +
       nuttx/lib/math/lib_acosf.c                    |   41 +
       nuttx/lib/math/lib_acosl.c                    |   46 +
       nuttx/lib/math/lib_asin.c                     |   69 +
       nuttx/lib/math/lib_asinf.c                    |   65 +
       nuttx/lib/math/lib_asinl.c                    |   69 +
       nuttx/lib/math/lib_atan.c                     |   48 +
       nuttx/lib/math/lib_atan2.c                    |   86 +
       nuttx/lib/math/lib_atan2f.c                   |   81 +
       nuttx/lib/math/lib_atan2l.c                   |   87 +
       nuttx/lib/math/lib_atanf.c                    |   43 +
       nuttx/lib/math/lib_atanl.c                    |   48 +
       nuttx/lib/math/lib_ceil.c                     |   52 +
       nuttx/lib/math/lib_ceilf.c                    |   47 +
       nuttx/lib/math/lib_ceill.c                    |   52 +
       nuttx/lib/math/lib_cos.c                      |   46 +
       nuttx/lib/math/lib_cosf.c                     |   41 +
       nuttx/lib/math/lib_cosh.c                     |   47 +
       nuttx/lib/math/lib_coshf.c                    |   42 +
       nuttx/lib/math/lib_coshl.c                    |   47 +
       nuttx/lib/math/lib_cosl.c                     |   46 +
       nuttx/lib/math/lib_exp.c                      |  126 ++
       nuttx/lib/math/lib_expf.c                     |  112 ++
       nuttx/lib/math/lib_expl.c                     |  126 ++
       nuttx/lib/math/lib_fabs.c                     |   46 +
       nuttx/lib/math/lib_fabsf.c                    |   41 +
       nuttx/lib/math/lib_fabsl.c                    |   46 +
       nuttx/lib/math/lib_floor.c                    |   52 +
       nuttx/lib/math/lib_floorf.c                   |   47 +
       nuttx/lib/math/lib_floorl.c                   |   52 +
       nuttx/lib/math/lib_fmod.c                     |   52 +
       nuttx/lib/math/lib_fmodf.c                    |   47 +
       nuttx/lib/math/lib_fmodl.c                    |   52 +
       nuttx/lib/math/lib_frexp.c                    |   47 +
       nuttx/lib/math/lib_frexpf.c                   |   42 +
       nuttx/lib/math/lib_frexpl.c                   |   47 +
       nuttx/lib/math/lib_ldexp.c                    |   46 +
       nuttx/lib/math/lib_ldexpf.c                   |   41 +
       nuttx/lib/math/lib_ldexpl.c                   |   46 +
       nuttx/lib/math/lib_libexpi.c                  |  103 ++
       nuttx/lib/math/lib_libsqrtapprox.c            |   50 +
       nuttx/lib/math/lib_log.c                      |   82 +
       nuttx/lib/math/lib_log10.c                    |   46 +
       nuttx/lib/math/lib_log10f.c                   |   41 +
       nuttx/lib/math/lib_log10l.c                   |   46 +
       nuttx/lib/math/lib_log2.c                     |   46 +
       nuttx/lib/math/lib_log2f.c                    |   41 +
       nuttx/lib/math/lib_log2l.c                    |   46 +
       nuttx/lib/math/lib_logf.c                     |   77 +
       nuttx/lib/math/lib_logl.c                     |   80 +
       nuttx/lib/math/lib_modf.c                     |   58 +
       nuttx/lib/math/lib_modff.c                    |   55 +
       nuttx/lib/math/lib_modfl.c                    |   61 +
       nuttx/lib/math/lib_pow.c                      |   46 +
       nuttx/lib/math/lib_powf.c                     |   41 +
       nuttx/lib/math/lib_powl.c                     |   46 +
       nuttx/lib/math/lib_sin.c                      |  114 ++
       nuttx/lib/math/lib_sinf.c                     |  104 ++
       nuttx/lib/math/lib_sinh.c                     |   47 +
       nuttx/lib/math/lib_sinhf.c                    |   42 +
       nuttx/lib/math/lib_sinhl.c                    |   47 +
       nuttx/lib/math/lib_sinl.c                     |  114 ++
       nuttx/lib/math/lib_sqrt.c                     |   99 +
       nuttx/lib/math/lib_sqrtf.c                    |   84 +
       nuttx/lib/math/lib_sqrtl.c                    |  101 +
       nuttx/lib/math/lib_tan.c                      |   46 +
       nuttx/lib/math/lib_tanf.c                     |   41 +
       nuttx/lib/math/lib_tanh.c                     |   49 +
       nuttx/lib/math/lib_tanhf.c                    |   44 +
       nuttx/lib/math/lib_tanhl.c                    |   49 +
       nuttx/lib/math/lib_tanl.c                     |   46 +
       nuttx/lib/misc/Make.defs                      |   69 +
       nuttx/lib/misc/lib_crc32.c                    |  123 ++
       nuttx/lib/misc/lib_dbg.c                      |  165 ++
       nuttx/lib/misc/lib_dumpbuffer.c               |  129 ++
       nuttx/lib/misc/lib_filesem.c                  |  145 ++
       nuttx/lib/misc/lib_init.c                     |  207 +++
       nuttx/lib/misc/lib_match.c                    |  148 ++
       nuttx/lib/misc/lib_sendfile.c                 |  297 +++
       nuttx/lib/misc/lib_streamsem.c                |   90 +
       nuttx/lib/mqueue/Make.defs                    |   48 +
       nuttx/lib/mqueue/mq_getattr.c                 |  104 ++
       nuttx/lib/mqueue/mq_setattr.c                 |  118 ++
       nuttx/lib/net/Make.defs                       |   44 +
       nuttx/lib/net/lib_etherntoa.c                 |   69 +
       nuttx/lib/net/lib_htonl.c                     |   68 +
       nuttx/lib/net/lib_htons.c                     |   65 +
       nuttx/lib/net/lib_inetaddr.c                  |   74 +
       nuttx/lib/net/lib_inetntoa.c                  |   79 +
       nuttx/lib/net/lib_inetntop.c                  |  202 ++
       nuttx/lib/net/lib_inetpton.c                  |  338 ++++
       nuttx/lib/pthread/Make.defs                   |   56 +
       nuttx/lib/pthread/pthread_attrdestroy.c       |  108 ++
       .../lib/pthread/pthread_attrgetinheritsched.c |  111 ++
       nuttx/lib/pthread/pthread_attrgetschedparam.c |  110 ++
       .../lib/pthread/pthread_attrgetschedpolicy.c  |  105 ++
       nuttx/lib/pthread/pthread_attrgetstacksize.c  |  106 ++
       nuttx/lib/pthread/pthread_attrinit.c          |  123 ++
       .../lib/pthread/pthread_attrsetinheritsched.c |  113 ++
       nuttx/lib/pthread/pthread_attrsetschedparam.c |  108 ++
       .../lib/pthread/pthread_attrsetschedpolicy.c  |  111 ++
       nuttx/lib/pthread/pthread_attrsetstacksize.c  |  106 ++
       .../lib/pthread/pthread_barrierattrdestroy.c  |  102 +
       .../pthread/pthread_barrierattrgetpshared.c   |  101 +
       nuttx/lib/pthread/pthread_barrierattrinit.c   |  101 +
       .../pthread/pthread_barrierattrsetpshared.c   |  111 ++
       nuttx/lib/pthread/pthread_condattrdestroy.c   |   82 +
       nuttx/lib/pthread/pthread_condattrinit.c      |   85 +
       nuttx/lib/pthread/pthread_mutexattrdestroy.c  |  104 ++
       .../lib/pthread/pthread_mutexattrgetpshared.c |  104 ++
       nuttx/lib/pthread/pthread_mutexattrgettype.c  |   98 +
       nuttx/lib/pthread/pthread_mutexattrinit.c     |  106 ++
       .../lib/pthread/pthread_mutexattrsetpshared.c |  104 ++
       nuttx/lib/pthread/pthread_mutexattrsettype.c  |   98 +
       nuttx/lib/queue/Make.defs                     |   47 +
       nuttx/lib/queue/dq_addafter.c                 |   74 +
       nuttx/lib/queue/dq_addbefore.c                |   69 +
       nuttx/lib/queue/dq_addfirst.c                 |   74 +
       nuttx/lib/queue/dq_addlast.c                  |   74 +
       nuttx/lib/queue/dq_rem.c                      |   84 +
       nuttx/lib/queue/dq_remfirst.c                 |   82 +
       nuttx/lib/queue/dq_remlast.c                  |   78 +
       nuttx/lib/queue/sq_addafter.c                 |   71 +
       nuttx/lib/queue/sq_addfirst.c                 |   67 +
       nuttx/lib/queue/sq_addlast.c                  |   72 +
       nuttx/lib/queue/sq_rem.c                      |   83 +
       nuttx/lib/queue/sq_remafter.c                 |   79 +
       nuttx/lib/queue/sq_remfirst.c                 |   76 +
       nuttx/lib/queue/sq_remlast.c                  |   87 +
       nuttx/lib/sched/Make.defs                     |   43 +
       nuttx/lib/sched/sched_getprioritymax.c        |  100 +
       nuttx/lib/sched/sched_getprioritymin.c        |  100 +
       nuttx/lib/semaphore/Make.defs                 |   43 +
       nuttx/lib/semaphore/sem_getvalue.c            |  108 ++
       nuttx/lib/semaphore/sem_init.c                |  125 ++
       nuttx/lib/signal/Make.defs                    |   47 +
       nuttx/lib/signal/sig_addset.c                 |  100 +
       nuttx/lib/signal/sig_delset.c                 |  100 +
       nuttx/lib/signal/sig_emptyset.c               |   88 +
       nuttx/lib/signal/sig_fillset.c                |   88 +
       nuttx/lib/signal/sig_ismember.c               |  101 +
       nuttx/lib/stdio/Make.defs                     |   85 +
       nuttx/lib/stdio/lib_asprintf.c                |  105 ++
       nuttx/lib/stdio/lib_avsprintf.c               |  146 ++
       nuttx/lib/stdio/lib_clearerr.c                |   69 +
       nuttx/lib/stdio/lib_dtoa.c                    | 1641 +++++++++++++++++
       nuttx/lib/stdio/lib_fclose.c                  |  154 ++
       nuttx/lib/stdio/lib_feof.c                    |   77 +
       nuttx/lib/stdio/lib_ferror.c                  |   90 +
       nuttx/lib/stdio/lib_fflush.c                  |  132 ++
       nuttx/lib/stdio/lib_fgetc.c                   |  101 +
       nuttx/lib/stdio/lib_fgetpos.c                 |  123 ++
       nuttx/lib/stdio/lib_fgets.c                   |  207 +++
       nuttx/lib/stdio/lib_fileno.c                  |   70 +
       nuttx/lib/stdio/lib_fopen.c                   |  299 +++
       nuttx/lib/stdio/lib_fprintf.c                 |   93 +
       nuttx/lib/stdio/lib_fputc.c                   |  113 ++
       nuttx/lib/stdio/lib_fputs.c                   |  220 +++
       nuttx/lib/stdio/lib_fread.c                   |  101 +
       nuttx/lib/stdio/lib_fseek.c                   |  138 ++
       nuttx/lib/stdio/lib_fsetpos.c                 |  116 ++
       nuttx/lib/stdio/lib_ftell.c                   |  129 ++
       nuttx/lib/stdio/lib_fwrite.c                  |   99 +
       nuttx/lib/stdio/lib_gets.c                    |  120 ++
       nuttx/lib/stdio/lib_libdtoa.c                 |  304 +++
       nuttx/lib/stdio/lib_libfflush.c               |  202 ++
       nuttx/lib/stdio/lib_libflushall.c             |  137 ++
       nuttx/lib/stdio/lib_libfread.c                |  315 ++++
       nuttx/lib/stdio/lib_libfwrite.c               |  179 ++
       nuttx/lib/stdio/lib_libnoflush.c              |  103 ++
       nuttx/lib/stdio/lib_libsprintf.c              |   90 +
       nuttx/lib/stdio/lib_libvsprintf.c             | 1620 ++++++++++++++++
       nuttx/lib/stdio/lib_lowinstream.c             |  102 +
       nuttx/lib/stdio/lib_lowoutstream.c            |   97 +
       nuttx/lib/stdio/lib_lowprintf.c               |  128 ++
       nuttx/lib/stdio/lib_meminstream.c             |  104 ++
       nuttx/lib/stdio/lib_memoutstream.c            |  105 ++
       nuttx/lib/stdio/lib_nullinstream.c            |   79 +
       nuttx/lib/stdio/lib_nulloutstream.c           |   84 +
       nuttx/lib/stdio/lib_perror.c                  |   99 +
       nuttx/lib/stdio/lib_printf.c                  |  109 ++
       nuttx/lib/stdio/lib_puts.c                    |  130 ++
       nuttx/lib/stdio/lib_rawinstream.c             |  107 ++
       nuttx/lib/stdio/lib_rawoutstream.c            |  115 ++
       nuttx/lib/stdio/lib_rawprintf.c               |  151 ++
       nuttx/lib/stdio/lib_rdflush.c                 |  144 ++
       nuttx/lib/stdio/lib_snprintf.c                |   99 +
       nuttx/lib/stdio/lib_sprintf.c                 |   95 +
       nuttx/lib/stdio/lib_sscanf.c                  |  507 +++++
       nuttx/lib/stdio/lib_stdinstream.c             |   99 +
       nuttx/lib/stdio/lib_stdoutstream.c            |  147 ++
       nuttx/lib/stdio/lib_syslogstream.c            |  122 ++
       nuttx/lib/stdio/lib_ungetc.c                  |  121 ++
       nuttx/lib/stdio/lib_vfprintf.c                |  102 +
       nuttx/lib/stdio/lib_vprintf.c                 |   92 +
       nuttx/lib/stdio/lib_vsnprintf.c               |   96 +
       nuttx/lib/stdio/lib_vsprintf.c                |   92 +
       nuttx/lib/stdio/lib_wrflush.c                 |  134 ++
       nuttx/lib/stdio/lib_zeroinstream.c            |   79 +
       nuttx/lib/stdlib/Make.defs                    |   44 +
       nuttx/lib/stdlib/lib_abort.c                  |  121 ++
       nuttx/lib/stdlib/lib_abs.c                    |   54 +
       nuttx/lib/stdlib/lib_imaxabs.c                |   54 +
       nuttx/lib/stdlib/lib_labs.c                   |   54 +
       nuttx/lib/stdlib/lib_llabs.c                  |   57 +
       nuttx/lib/stdlib/lib_qsort.c                  |  238 +++
       nuttx/lib/stdlib/lib_rand.c                   |  220 +++
       nuttx/lib/string/Make.defs                    |   58 +
       nuttx/lib/string/lib_checkbase.c              |  115 ++
       nuttx/lib/string/lib_isbasedigit.c            |  105 ++
       nuttx/lib/string/lib_memccpy.c                |   99 +
       nuttx/lib/string/lib_memchr.c                 |   80 +
       nuttx/lib/string/lib_memcmp.c                 |   74 +
       nuttx/lib/string/lib_memcpy.c                 |   64 +
       nuttx/lib/string/lib_memmove.c                |   77 +
       nuttx/lib/string/lib_memset.c                 |  188 ++
       nuttx/lib/string/lib_skipspace.c              |   69 +
       nuttx/lib/string/lib_strcasecmp.c             |   65 +
       nuttx/lib/string/lib_strcasestr.c             |  134 ++
       nuttx/lib/string/lib_strcat.c                 |   62 +
       nuttx/lib/string/lib_strchr.c                 |   78 +
       nuttx/lib/string/lib_strcmp.c                 |   59 +
       nuttx/lib/string/lib_strcpy.c                 |   55 +
       nuttx/lib/string/lib_strcspn.c                |   67 +
       nuttx/lib/string/lib_strdup.c                 |   62 +
       nuttx/lib/string/lib_strerror.c               |  375 ++++
       nuttx/lib/string/lib_strlen.c                 |   55 +
       nuttx/lib/string/lib_strncasecmp.c            |   70 +
       nuttx/lib/string/lib_strncat.c                |   62 +
       nuttx/lib/string/lib_strncmp.c                |   65 +
       nuttx/lib/string/lib_strncpy.c                |   57 +
       nuttx/lib/string/lib_strndup.c                |   93 +
       nuttx/lib/string/lib_strnlen.c                |   62 +
       nuttx/lib/string/lib_strpbrk.c                |   85 +
       nuttx/lib/string/lib_strrchr.c                |   68 +
       nuttx/lib/string/lib_strspn.c                 |   66 +
       nuttx/lib/string/lib_strstr.c                 |  104 ++
       nuttx/lib/string/lib_strtod.c                 |  241 +++
       nuttx/lib/string/lib_strtok.c                 |   87 +
       nuttx/lib/string/lib_strtokr.c                |  157 ++
       nuttx/lib/string/lib_strtol.c                 |  103 ++
       nuttx/lib/string/lib_strtoll.c                |  107 ++
       nuttx/lib/string/lib_strtoul.c                |   98 +
       nuttx/lib/string/lib_strtoull.c               |  100 +
       nuttx/lib/string/lib_vikmemcpy.c              |  348 ++++
       nuttx/lib/termios/Make.defs                   |   54 +
       nuttx/lib/termios/lib_cfgetspeed.c            |   93 +
       nuttx/lib/termios/lib_cfsetspeed.c            |  116 ++
       nuttx/lib/termios/lib_tcflush.c               |   88 +
       nuttx/lib/termios/lib_tcgetattr.c             |   93 +
       nuttx/lib/termios/lib_tcsetattr.c             |  122 ++
       nuttx/lib/time/Make.defs                      |   44 +
       nuttx/lib/time/lib_calendar2utc.c             |  209 +++
       nuttx/lib/time/lib_daysbeforemonth.c          |  102 +
       nuttx/lib/time/lib_gmtime.c                   |   93 +
       nuttx/lib/time/lib_gmtimer.c                  |  355 ++++
       nuttx/lib/time/lib_isleapyear.c               |   88 +
       nuttx/lib/time/lib_mktime.c                   |  141 ++
       nuttx/lib/time/lib_strftime.c                 |  398 ++++
       nuttx/lib/time/lib_time.c                     |  110 ++
       nuttx/lib/unistd/Make.defs                    |   49 +
       nuttx/lib/unistd/lib_chdir.c                  |  179 ++
       nuttx/lib/unistd/lib_getcwd.c                 |  132 ++
       nuttx/lib/unistd/lib_getopt.c                 |  269 +++
       nuttx/lib/unistd/lib_getoptargp.c             |   73 +
       nuttx/lib/unistd/lib_getoptindp.c             |   73 +
       nuttx/lib/unistd/lib_getoptoptp.c             |   73 +
       286 files changed, 32008 insertions(+)
       create mode 100644 nuttx/lib/Kconfig
       create mode 100644 nuttx/lib/Makefile
       create mode 100644 nuttx/lib/README.txt
       create mode 100644 nuttx/lib/dirent/Make.defs
       create mode 100644 nuttx/lib/dirent/lib_readdirr.c
       create mode 100644 nuttx/lib/dirent/lib_telldir.c
       create mode 100644 nuttx/lib/fixedmath/Make.defs
       create mode 100644 nuttx/lib/fixedmath/lib_b16atan2.c
       create mode 100644 nuttx/lib/fixedmath/lib_b16cos.c
       create mode 100644 nuttx/lib/fixedmath/lib_b16sin.c
       create mode 100644 nuttx/lib/fixedmath/lib_fixedmath.c
       create mode 100644 nuttx/lib/fixedmath/lib_rint.c
       create mode 100644 nuttx/lib/lib.csv
       create mode 100644 nuttx/lib/lib_internal.h
       create mode 100644 nuttx/lib/libgen/Make.defs
       create mode 100644 nuttx/lib/libgen/lib_basename.c
       create mode 100644 nuttx/lib/libgen/lib_dirname.c
       create mode 100644 nuttx/lib/math/Kconfig
       create mode 100644 nuttx/lib/math/Make.defs
       create mode 100644 nuttx/lib/math/lib_acos.c
       create mode 100644 nuttx/lib/math/lib_acosf.c
       create mode 100644 nuttx/lib/math/lib_acosl.c
       create mode 100644 nuttx/lib/math/lib_asin.c
       create mode 100644 nuttx/lib/math/lib_asinf.c
       create mode 100644 nuttx/lib/math/lib_asinl.c
       create mode 100644 nuttx/lib/math/lib_atan.c
       create mode 100644 nuttx/lib/math/lib_atan2.c
       create mode 100644 nuttx/lib/math/lib_atan2f.c
       create mode 100644 nuttx/lib/math/lib_atan2l.c
       create mode 100644 nuttx/lib/math/lib_atanf.c
       create mode 100644 nuttx/lib/math/lib_atanl.c
       create mode 100644 nuttx/lib/math/lib_ceil.c
       create mode 100644 nuttx/lib/math/lib_ceilf.c
       create mode 100644 nuttx/lib/math/lib_ceill.c
       create mode 100644 nuttx/lib/math/lib_cos.c
       create mode 100644 nuttx/lib/math/lib_cosf.c
       create mode 100644 nuttx/lib/math/lib_cosh.c
       create mode 100644 nuttx/lib/math/lib_coshf.c
       create mode 100644 nuttx/lib/math/lib_coshl.c
       create mode 100644 nuttx/lib/math/lib_cosl.c
       create mode 100644 nuttx/lib/math/lib_exp.c
       create mode 100644 nuttx/lib/math/lib_expf.c
       create mode 100644 nuttx/lib/math/lib_expl.c
       create mode 100644 nuttx/lib/math/lib_fabs.c
       create mode 100644 nuttx/lib/math/lib_fabsf.c
       create mode 100644 nuttx/lib/math/lib_fabsl.c
       create mode 100644 nuttx/lib/math/lib_floor.c
       create mode 100644 nuttx/lib/math/lib_floorf.c
       create mode 100644 nuttx/lib/math/lib_floorl.c
       create mode 100644 nuttx/lib/math/lib_fmod.c
       create mode 100644 nuttx/lib/math/lib_fmodf.c
       create mode 100644 nuttx/lib/math/lib_fmodl.c
       create mode 100644 nuttx/lib/math/lib_frexp.c
       create mode 100644 nuttx/lib/math/lib_frexpf.c
       create mode 100644 nuttx/lib/math/lib_frexpl.c
       create mode 100644 nuttx/lib/math/lib_ldexp.c
       create mode 100644 nuttx/lib/math/lib_ldexpf.c
       create mode 100644 nuttx/lib/math/lib_ldexpl.c
       create mode 100644 nuttx/lib/math/lib_libexpi.c
       create mode 100644 nuttx/lib/math/lib_libsqrtapprox.c
       create mode 100644 nuttx/lib/math/lib_log.c
       create mode 100644 nuttx/lib/math/lib_log10.c
       create mode 100644 nuttx/lib/math/lib_log10f.c
       create mode 100644 nuttx/lib/math/lib_log10l.c
       create mode 100644 nuttx/lib/math/lib_log2.c
       create mode 100644 nuttx/lib/math/lib_log2f.c
       create mode 100644 nuttx/lib/math/lib_log2l.c
       create mode 100644 nuttx/lib/math/lib_logf.c
       create mode 100644 nuttx/lib/math/lib_logl.c
       create mode 100644 nuttx/lib/math/lib_modf.c
       create mode 100644 nuttx/lib/math/lib_modff.c
       create mode 100644 nuttx/lib/math/lib_modfl.c
       create mode 100644 nuttx/lib/math/lib_pow.c
       create mode 100644 nuttx/lib/math/lib_powf.c
       create mode 100644 nuttx/lib/math/lib_powl.c
       create mode 100644 nuttx/lib/math/lib_sin.c
       create mode 100644 nuttx/lib/math/lib_sinf.c
       create mode 100644 nuttx/lib/math/lib_sinh.c
       create mode 100644 nuttx/lib/math/lib_sinhf.c
       create mode 100644 nuttx/lib/math/lib_sinhl.c
       create mode 100644 nuttx/lib/math/lib_sinl.c
       create mode 100644 nuttx/lib/math/lib_sqrt.c
       create mode 100644 nuttx/lib/math/lib_sqrtf.c
       create mode 100644 nuttx/lib/math/lib_sqrtl.c
       create mode 100644 nuttx/lib/math/lib_tan.c
       create mode 100644 nuttx/lib/math/lib_tanf.c
       create mode 100644 nuttx/lib/math/lib_tanh.c
       create mode 100644 nuttx/lib/math/lib_tanhf.c
       create mode 100644 nuttx/lib/math/lib_tanhl.c
       create mode 100644 nuttx/lib/math/lib_tanl.c
       create mode 100644 nuttx/lib/misc/Make.defs
       create mode 100644 nuttx/lib/misc/lib_crc32.c
       create mode 100644 nuttx/lib/misc/lib_dbg.c
       create mode 100644 nuttx/lib/misc/lib_dumpbuffer.c
       create mode 100644 nuttx/lib/misc/lib_filesem.c
       create mode 100644 nuttx/lib/misc/lib_init.c
       create mode 100644 nuttx/lib/misc/lib_match.c
       create mode 100644 nuttx/lib/misc/lib_sendfile.c
       create mode 100644 nuttx/lib/misc/lib_streamsem.c
       create mode 100644 nuttx/lib/mqueue/Make.defs
       create mode 100644 nuttx/lib/mqueue/mq_getattr.c
       create mode 100644 nuttx/lib/mqueue/mq_setattr.c
       create mode 100644 nuttx/lib/net/Make.defs
       create mode 100644 nuttx/lib/net/lib_etherntoa.c
       create mode 100644 nuttx/lib/net/lib_htonl.c
       create mode 100644 nuttx/lib/net/lib_htons.c
       create mode 100644 nuttx/lib/net/lib_inetaddr.c
       create mode 100644 nuttx/lib/net/lib_inetntoa.c
       create mode 100644 nuttx/lib/net/lib_inetntop.c
       create mode 100644 nuttx/lib/net/lib_inetpton.c
       create mode 100644 nuttx/lib/pthread/Make.defs
       create mode 100644 nuttx/lib/pthread/pthread_attrdestroy.c
       create mode 100644 nuttx/lib/pthread/pthread_attrgetinheritsched.c
       create mode 100644 nuttx/lib/pthread/pthread_attrgetschedparam.c
       create mode 100644 nuttx/lib/pthread/pthread_attrgetschedpolicy.c
       create mode 100644 nuttx/lib/pthread/pthread_attrgetstacksize.c
       create mode 100644 nuttx/lib/pthread/pthread_attrinit.c
       create mode 100644 nuttx/lib/pthread/pthread_attrsetinheritsched.c
       create mode 100644 nuttx/lib/pthread/pthread_attrsetschedparam.c
       create mode 100644 nuttx/lib/pthread/pthread_attrsetschedpolicy.c
       create mode 100644 nuttx/lib/pthread/pthread_attrsetstacksize.c
       create mode 100644 nuttx/lib/pthread/pthread_barrierattrdestroy.c
       create mode 100644 nuttx/lib/pthread/pthread_barrierattrgetpshared.c
       create mode 100644 nuttx/lib/pthread/pthread_barrierattrinit.c
       create mode 100644 nuttx/lib/pthread/pthread_barrierattrsetpshared.c
       create mode 100644 nuttx/lib/pthread/pthread_condattrdestroy.c
       create mode 100644 nuttx/lib/pthread/pthread_condattrinit.c
       create mode 100644 nuttx/lib/pthread/pthread_mutexattrdestroy.c
       create mode 100644 nuttx/lib/pthread/pthread_mutexattrgetpshared.c
       create mode 100644 nuttx/lib/pthread/pthread_mutexattrgettype.c
       create mode 100644 nuttx/lib/pthread/pthread_mutexattrinit.c
       create mode 100644 nuttx/lib/pthread/pthread_mutexattrsetpshared.c
       create mode 100644 nuttx/lib/pthread/pthread_mutexattrsettype.c
       create mode 100644 nuttx/lib/queue/Make.defs
       create mode 100644 nuttx/lib/queue/dq_addafter.c
       create mode 100644 nuttx/lib/queue/dq_addbefore.c
       create mode 100644 nuttx/lib/queue/dq_addfirst.c
       create mode 100644 nuttx/lib/queue/dq_addlast.c
       create mode 100644 nuttx/lib/queue/dq_rem.c
       create mode 100644 nuttx/lib/queue/dq_remfirst.c
       create mode 100644 nuttx/lib/queue/dq_remlast.c
       create mode 100644 nuttx/lib/queue/sq_addafter.c
       create mode 100644 nuttx/lib/queue/sq_addfirst.c
       create mode 100644 nuttx/lib/queue/sq_addlast.c
       create mode 100644 nuttx/lib/queue/sq_rem.c
       create mode 100644 nuttx/lib/queue/sq_remafter.c
       create mode 100644 nuttx/lib/queue/sq_remfirst.c
       create mode 100644 nuttx/lib/queue/sq_remlast.c
       create mode 100644 nuttx/lib/sched/Make.defs
       create mode 100644 nuttx/lib/sched/sched_getprioritymax.c
       create mode 100644 nuttx/lib/sched/sched_getprioritymin.c
       create mode 100644 nuttx/lib/semaphore/Make.defs
       create mode 100644 nuttx/lib/semaphore/sem_getvalue.c
       create mode 100644 nuttx/lib/semaphore/sem_init.c
       create mode 100644 nuttx/lib/signal/Make.defs
       create mode 100644 nuttx/lib/signal/sig_addset.c
       create mode 100644 nuttx/lib/signal/sig_delset.c
       create mode 100644 nuttx/lib/signal/sig_emptyset.c
       create mode 100644 nuttx/lib/signal/sig_fillset.c
       create mode 100644 nuttx/lib/signal/sig_ismember.c
       create mode 100644 nuttx/lib/stdio/Make.defs
       create mode 100644 nuttx/lib/stdio/lib_asprintf.c
       create mode 100644 nuttx/lib/stdio/lib_avsprintf.c
       create mode 100644 nuttx/lib/stdio/lib_clearerr.c
       create mode 100644 nuttx/lib/stdio/lib_dtoa.c
       create mode 100644 nuttx/lib/stdio/lib_fclose.c
       create mode 100644 nuttx/lib/stdio/lib_feof.c
       create mode 100644 nuttx/lib/stdio/lib_ferror.c
       create mode 100644 nuttx/lib/stdio/lib_fflush.c
       create mode 100644 nuttx/lib/stdio/lib_fgetc.c
       create mode 100644 nuttx/lib/stdio/lib_fgetpos.c
       create mode 100644 nuttx/lib/stdio/lib_fgets.c
       create mode 100644 nuttx/lib/stdio/lib_fileno.c
       create mode 100644 nuttx/lib/stdio/lib_fopen.c
       create mode 100644 nuttx/lib/stdio/lib_fprintf.c
       create mode 100644 nuttx/lib/stdio/lib_fputc.c
       create mode 100644 nuttx/lib/stdio/lib_fputs.c
       create mode 100644 nuttx/lib/stdio/lib_fread.c
       create mode 100644 nuttx/lib/stdio/lib_fseek.c
       create mode 100644 nuttx/lib/stdio/lib_fsetpos.c
       create mode 100644 nuttx/lib/stdio/lib_ftell.c
       create mode 100644 nuttx/lib/stdio/lib_fwrite.c
       create mode 100644 nuttx/lib/stdio/lib_gets.c
       create mode 100644 nuttx/lib/stdio/lib_libdtoa.c
       create mode 100644 nuttx/lib/stdio/lib_libfflush.c
       create mode 100644 nuttx/lib/stdio/lib_libflushall.c
       create mode 100644 nuttx/lib/stdio/lib_libfread.c
       create mode 100644 nuttx/lib/stdio/lib_libfwrite.c
       create mode 100644 nuttx/lib/stdio/lib_libnoflush.c
       create mode 100644 nuttx/lib/stdio/lib_libsprintf.c
       create mode 100644 nuttx/lib/stdio/lib_libvsprintf.c
       create mode 100644 nuttx/lib/stdio/lib_lowinstream.c
       create mode 100644 nuttx/lib/stdio/lib_lowoutstream.c
       create mode 100644 nuttx/lib/stdio/lib_lowprintf.c
       create mode 100644 nuttx/lib/stdio/lib_meminstream.c
       create mode 100644 nuttx/lib/stdio/lib_memoutstream.c
       create mode 100644 nuttx/lib/stdio/lib_nullinstream.c
       create mode 100644 nuttx/lib/stdio/lib_nulloutstream.c
       create mode 100644 nuttx/lib/stdio/lib_perror.c
       create mode 100644 nuttx/lib/stdio/lib_printf.c
       create mode 100644 nuttx/lib/stdio/lib_puts.c
       create mode 100644 nuttx/lib/stdio/lib_rawinstream.c
       create mode 100644 nuttx/lib/stdio/lib_rawoutstream.c
       create mode 100644 nuttx/lib/stdio/lib_rawprintf.c
       create mode 100644 nuttx/lib/stdio/lib_rdflush.c
       create mode 100644 nuttx/lib/stdio/lib_snprintf.c
       create mode 100644 nuttx/lib/stdio/lib_sprintf.c
       create mode 100644 nuttx/lib/stdio/lib_sscanf.c
       create mode 100644 nuttx/lib/stdio/lib_stdinstream.c
       create mode 100644 nuttx/lib/stdio/lib_stdoutstream.c
       create mode 100644 nuttx/lib/stdio/lib_syslogstream.c
       create mode 100644 nuttx/lib/stdio/lib_ungetc.c
       create mode 100644 nuttx/lib/stdio/lib_vfprintf.c
       create mode 100644 nuttx/lib/stdio/lib_vprintf.c
       create mode 100644 nuttx/lib/stdio/lib_vsnprintf.c
       create mode 100644 nuttx/lib/stdio/lib_vsprintf.c
       create mode 100644 nuttx/lib/stdio/lib_wrflush.c
       create mode 100644 nuttx/lib/stdio/lib_zeroinstream.c
       create mode 100644 nuttx/lib/stdlib/Make.defs
       create mode 100644 nuttx/lib/stdlib/lib_abort.c
       create mode 100644 nuttx/lib/stdlib/lib_abs.c
       create mode 100644 nuttx/lib/stdlib/lib_imaxabs.c
       create mode 100644 nuttx/lib/stdlib/lib_labs.c
       create mode 100644 nuttx/lib/stdlib/lib_llabs.c
       create mode 100644 nuttx/lib/stdlib/lib_qsort.c
       create mode 100644 nuttx/lib/stdlib/lib_rand.c
       create mode 100644 nuttx/lib/string/Make.defs
       create mode 100644 nuttx/lib/string/lib_checkbase.c
       create mode 100644 nuttx/lib/string/lib_isbasedigit.c
       create mode 100644 nuttx/lib/string/lib_memccpy.c
       create mode 100644 nuttx/lib/string/lib_memchr.c
       create mode 100644 nuttx/lib/string/lib_memcmp.c
       create mode 100644 nuttx/lib/string/lib_memcpy.c
       create mode 100644 nuttx/lib/string/lib_memmove.c
       create mode 100644 nuttx/lib/string/lib_memset.c
       create mode 100644 nuttx/lib/string/lib_skipspace.c
       create mode 100644 nuttx/lib/string/lib_strcasecmp.c
       create mode 100644 nuttx/lib/string/lib_strcasestr.c
       create mode 100644 nuttx/lib/string/lib_strcat.c
       create mode 100644 nuttx/lib/string/lib_strchr.c
       create mode 100644 nuttx/lib/string/lib_strcmp.c
       create mode 100644 nuttx/lib/string/lib_strcpy.c
       create mode 100644 nuttx/lib/string/lib_strcspn.c
       create mode 100644 nuttx/lib/string/lib_strdup.c
       create mode 100644 nuttx/lib/string/lib_strerror.c
       create mode 100644 nuttx/lib/string/lib_strlen.c
       create mode 100644 nuttx/lib/string/lib_strncasecmp.c
       create mode 100644 nuttx/lib/string/lib_strncat.c
       create mode 100644 nuttx/lib/string/lib_strncmp.c
       create mode 100644 nuttx/lib/string/lib_strncpy.c
       create mode 100644 nuttx/lib/string/lib_strndup.c
       create mode 100644 nuttx/lib/string/lib_strnlen.c
       create mode 100644 nuttx/lib/string/lib_strpbrk.c
       create mode 100644 nuttx/lib/string/lib_strrchr.c
       create mode 100644 nuttx/lib/string/lib_strspn.c
       create mode 100644 nuttx/lib/string/lib_strstr.c
       create mode 100644 nuttx/lib/string/lib_strtod.c
       create mode 100644 nuttx/lib/string/lib_strtok.c
       create mode 100644 nuttx/lib/string/lib_strtokr.c
       create mode 100644 nuttx/lib/string/lib_strtol.c
       create mode 100644 nuttx/lib/string/lib_strtoll.c
       create mode 100644 nuttx/lib/string/lib_strtoul.c
       create mode 100644 nuttx/lib/string/lib_strtoull.c
       create mode 100644 nuttx/lib/string/lib_vikmemcpy.c
       create mode 100644 nuttx/lib/termios/Make.defs
       create mode 100644 nuttx/lib/termios/lib_cfgetspeed.c
       create mode 100644 nuttx/lib/termios/lib_cfsetspeed.c
       create mode 100644 nuttx/lib/termios/lib_tcflush.c
       create mode 100644 nuttx/lib/termios/lib_tcgetattr.c
       create mode 100644 nuttx/lib/termios/lib_tcsetattr.c
       create mode 100644 nuttx/lib/time/Make.defs
       create mode 100644 nuttx/lib/time/lib_calendar2utc.c
       create mode 100644 nuttx/lib/time/lib_daysbeforemonth.c
       create mode 100644 nuttx/lib/time/lib_gmtime.c
       create mode 100644 nuttx/lib/time/lib_gmtimer.c
       create mode 100644 nuttx/lib/time/lib_isleapyear.c
       create mode 100644 nuttx/lib/time/lib_mktime.c
       create mode 100644 nuttx/lib/time/lib_strftime.c
       create mode 100644 nuttx/lib/time/lib_time.c
       create mode 100644 nuttx/lib/unistd/Make.defs
       create mode 100644 nuttx/lib/unistd/lib_chdir.c
       create mode 100644 nuttx/lib/unistd/lib_getcwd.c
       create mode 100644 nuttx/lib/unistd/lib_getopt.c
       create mode 100644 nuttx/lib/unistd/lib_getoptargp.c
       create mode 100644 nuttx/lib/unistd/lib_getoptindp.c
       create mode 100644 nuttx/lib/unistd/lib_getoptoptp.c
      
      diff --git a/nuttx/lib/Kconfig b/nuttx/lib/Kconfig
      new file mode 100644
      index 0000000000..1c93bb0475
      --- /dev/null
      +++ b/nuttx/lib/Kconfig
      @@ -0,0 +1,275 @@
      +#
      +# For a description of the syntax of this configuration file,
      +# see misc/tools/kconfig-language.txt.
      +#
      +
      +config STDIO_BUFFER_SIZE
      +	int "C STDIO buffer size"
      +	default 64
      +	---help---
      +		Size of buffers using within the C buffered I/O interfaces.
      +		(printf, putchar, fwrite, etc.).
      +
      +config STDIO_LINEBUFFER
      +	bool "STDIO line buffering"
      +	default y
      +	---help---
      +		Flush buffer I/O whenever a newline character is found in
      +		the output data stream.
      +
      +config NUNGET_CHARS
      +	int "Number unget() characters"
      +	default 2
      +	---help---
      +		Number of characters that can be buffered by ungetc() (Only if NFILE_STREAMS > 0)
      +
      +config LIB_HOMEDIR
      +	string "Home directory"
      +	default "/"
      +	depends on !DISABLE_ENVIRON
      +	---help---
      +		The home directory to use with operations like such as 'cd ~'
      +
      +source lib/math/Kconfig
      +
      +config NOPRINTF_FIELDWIDTH
      +	bool "Disable sprintf support fieldwidth"
      +	default n
      +	---help---
      +	sprintf-related logic is a
      +	little smaller if we do not support fieldwidthes
      +
      +config LIBC_FLOATINGPOINT
      +	bool "Enable floating point in printf"
      +	default n
      +	---help---
      +		By default, floating point
      +		support in printf, sscanf, etc. is disabled.
      +
      +choice
      +	prompt "Newline Options"
      +	default EOL_IS_EITHER_CRLF
      +	---help---
      +		This selection determines the line terminating character that is used.
      +		Some environments may return CR as end-of-line, others LF, and others
      +		both.  If not specified, the default is either CR or LF (but not both)
      +		as the line terminating charactor.
      +
      +config EOL_IS_CR
      +	bool "EOL is CR"
      +
      +config EOL_IS_LF
      +	bool "EOL is LF"
      +
      +config EOL_IS_BOTH_CRLF
      +	bool "EOL is CR and LF"
      +
      +config EOL_IS_EITHER_CRLF
      +	bool "EOL is CR or LF"
      +
      +endchoice
      +
      +config LIBC_STRERROR
      +	bool "Enable strerror"
      +	default n
      +	---help---
      +		strerror() is useful because it decodes 'errno' values into a human readable
      +		strings.  But it can also require a lot of memory.  If this option is selected,
      +		strerror() will still exist in the build but it will not decode error values.
      +		This option should be used by other logic to decide if it should use strerror()
      +		or not.  For example, the NSH application will not use strerror() if this
      +		option is not selected; perror() will not use strerror() is this option is not
      +		selected (see also NSH_STRERROR).
      +
      +config LIBC_STRERROR_SHORT
      +	bool "Use short error descriptions in strerror()"
      +	default n
      +	depends on LIBC_STRERROR
      +	---help---
      +		If this option is selected, then strerror() will use a shortened string when
      +		it decodes the error.  Specifically, strerror() is simply use the string that
      +		is the common name for the error.  For example, the 'errno' value of 2 will
      +		produce the string "No such file or directory" is LIBC_STRERROR_SHORT
      +		is not defined but the string "ENOENT" is LIBC_STRERROR_SHORT is defined.
      +
      +config LIBC_PERROR_STDOUT
      +	bool "perror() to stdout"
      +	default n
      +	---help---
      +		POSIX requires that perror() provide its output on stderr.  This option may
      +		be defined, however, to provide perror() output that is serialized with
      +		other stdout messages.
      +
      +config ARCH_LOWPUTC
      +	bool "Low-level console output"
      +	default "y"
      +	---help---
      +		architecture supports low-level, boot time console output
      +
      +config LIB_SENDFILE_BUFSIZE
      +	int "sendfile() buffer size"
      +	default 512
      +	---help---
      +		Size of the I/O buffer to allocate in sendfile().  Default: 512b
      +
      +config ARCH_ROMGETC
      +	bool "Support for ROM string access"
      +	default n
      +	---help---
      +		In Harvard architectures, data accesses and instruction accesses
      +		occur on different busses, perhaps concurrently.  All data accesses
      +		are performed on the data bus unless special machine instructions
      +		are used to read data from the instruction address space.  Also, in
      +		the typical MCU, the available SRAM data memory is much smaller that
      +		the non-volatile FLASH instruction memory.  So if the application
      +		requires many constant strings, the only practical solution may be
      +		to store those constant strings in FLASH memory where they can only
      +		be accessed using architecture-specific machine instructions.
      +
      +		If ARCH_ROMGETC is defined, then the architecture logic must export
      +		the function up_romgetc().  up_romgetc() will simply read one byte
      +		of data from the instruction space.
      +
      +		If ARCH_ROMGETC, certain C stdio functions are effected: (1) All
      +		format strings in printf, fprintf, sprintf, etc. are assumed to lie
      +		in FLASH (string arguments for %s are still assumed to reside in SRAM).
      +		And (2), the string argument to puts and fputs is assumed to reside
      +		in FLASH.  Clearly, these assumptions may have to modified for the
      +		particular needs of your environment.  There is no "one-size-fits-all"
      +		solution for this problem.
      +
      +config ARCH_OPTIMIZED_FUNCTIONS
      +	bool "Enable arch optimized functions"
      +	default n
      +	---help---
      +		Allow for architecture optimized implementations of certain library
      +		functions.  Architecture-specific implementations can improve overall
      +		system performance.
      +
      +if ARCH_OPTIMIZED_FUNCTIONS
      +config ARCH_MEMCPY
      +	bool "memcpy()"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of memcpy().
      +
      +config MEMCPY_VIK
      +	bool "Vik memcpy()"
      +	default n
      +	depends on !ARCH_MEMCPY
      +	---help---
      +		Select this option to use the optimized memcpy() function by Daniel Vik.
      +		Select this option for improved performance at the expense of increased
      +		size. See licensing information in the top-level COPYING file.
      +
      +if MEMCPY_VIK
      +config MEMCPY_PRE_INC_PTRS
      +	bool "Pre-increment pointers"
      +	default n
      +	---help---
      +		Use pre-increment of pointers. Default is post increment of pointers.
      +
      +config MEMCPY_INDEXED_COPY
      +	bool "Array indexing"
      +	default y
      +	---help---
      +		Copying data using array indexing. Using this option, disables the
      +		MEMCPY_PRE_INC_PTRS option.
      +
      +config MEMCPY_64BIT
      +	bool "64-bit memcpy()"
      +	default n
      +	---help---
      +		Compiles memcpy() for architectures that suppport 64-bit operations
      +		efficiently.
      +
      +endif
      +
      +config ARCH_MEMCMP
      +	bool "memcmp()"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of memcmp().
      +
      +config ARCH_MEMMOVE
      +	bool "memmove()"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of memmove().
      +
      +config ARCH_MEMSET
      +	bool "memset()"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of memset().
      +
      +config MEMSET_OPTSPEED
      +	bool "Optimize memset() for speed"
      +	default n
      +	depends on !ARCH_MEMSET
      +	---help---
      +		Select this option to use a version of memcpy() optimized for speed.
      +		Default: memcpy() is optimized for size.
      +
      +config MEMSET_64BIT
      +	bool "64-bit memset()"
      +	default n
      +	depends on MEMSET_OPTSPEED
      +	---help---
      +		Compiles memset() for architectures that suppport 64-bit operations
      +		efficiently.
      +
      +config ARCH_STRCHR
      +	bool "strchr()"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of strchr().
      +
      +config ARCH_STRCMP
      +	bool "strcmp()"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of strcmp().
      +
      +config ARCH_STRCPY
      +	bool "strcpy()"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of strcpy().
      +
      +config ARCH_STRNCPY
      +	bool "strncpy()"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of strncpy().
      +
      +config ARCH_STRLEN
      +	bool "strlen"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of strlen().
      +
      +config ARCH_STRNLEN
      +	bool "strlen()"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of strnlen().
      +
      +config ARCH_BZERO
      +	bool "bzero()"
      +	default n
      +	---help---
      +		Select this option if the architecture provides an optimized version
      +		of bzero().
      +
      +endif
      diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile
      new file mode 100644
      index 0000000000..406c2276ef
      --- /dev/null
      +++ b/nuttx/lib/Makefile
      @@ -0,0 +1,136 @@
      +############################################################################
      +# lib/Makefile
      +#
      +#   Copyright (C) 2007-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)/Make.defs
      +
      +ASRCS =
      +CSRCS =
      +
      +DEPPATH := --dep-path .
      +VPATH := .
      +
      +include stdio/Make.defs
      +include stdlib/Make.defs
      +include unistd/Make.defs
      +include sched/Make.defs
      +include string/Make.defs
      +include pthread/Make.defs
      +include semaphore/Make.defs
      +include signal/Make.defs
      +include mqueue/Make.defs
      +include math/Make.defs
      +include fixedmath/Make.defs
      +include net/Make.defs
      +include time/Make.defs
      +include libgen/Make.defs
      +include dirent/Make.defs
      +include termios/Make.defs
      +include queue/Make.defs
      +include misc/Make.defs
      +
      +AOBJS = $(ASRCS:.S=$(OBJEXT))
      +COBJS = $(CSRCS:.c=$(OBJEXT))
      +
      +SRCS = $(ASRCS) $(CSRCS)
      +OBJS = $(AOBJS) $(COBJS)
      +
      +UBIN = libulib$(LIBEXT)
      +KBIN = libklib$(LIBEXT)
      +BIN  = liblib$(LIBEXT)
      +
      +all: $(BIN)
      +
      +$(AOBJS): %$(OBJEXT): %.S
      +	$(call ASSEMBLE, $<, $@)
      +
      +$(COBJS): %$(OBJEXT): %.c
      +	$(call COMPILE, $<, $@)
      +
      +$(BIN):	$(OBJS)
      +	@( for obj in $(OBJS) ; do \
      +		$(call ARCHIVE, $@, $${obj}); \
      +	done ; )
      +
      +ifneq ($(BIN),$(UBIN))
      +.userlib:
      +	@$(MAKE) $(UBIN) BIN=$(UBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      +	@touch .userlib
      +
      +$(UBIN): kclean .userlib
      +endif
      +
      +ifneq ($(BIN),$(KBIN))
      +.kernlib:
      +	@$(MAKE) $(KBIN) BIN=$(KBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      +	@touch .kernlib
      +
      +$(KBIN): uclean .kernlib
      +endif
      +
      +.depend: Makefile $(SRCS)
      +	@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@touch $@
      +
      +depend: .depend
      +
      +# Clean Targets:
      +# Clean user-mode temporary files (retaining the UBIN binary)
      +
      +uclean:
      +ifneq ($(OBJEXT),)
      +	@( if [ -f .userlib ]; then rm -f *$(OBJEXT); fi )
      +endif
      +	@rm -f .userlib *~ .*.swp
      +
      +# Clean kernel-mode temporary files (retaining the KBIN binary)
      +
      +kclean:
      +ifneq ($(OBJEXT),)
      +	@( if [ -f .kernlib ]; then rm -f *$(OBJEXT); fi )
      +endif
      +	@rm -f .kernlib *~ .*.swp
      +
      +# Really clean everything
      +
      +clean: uclean kclean
      +	@rm -f $(BIN) $(UBIN) $(KBIN) *~ .*.swp
      +	$(call CLEAN)
      +
      +# Deep clean -- removes all traces of the configuration
      +
      +distclean: clean
      +	@rm -f Make.dep .depend
      +
      +-include Make.dep
      diff --git a/nuttx/lib/README.txt b/nuttx/lib/README.txt
      new file mode 100644
      index 0000000000..e99304841b
      --- /dev/null
      +++ b/nuttx/lib/README.txt
      @@ -0,0 +1,85 @@
      +lib
      +===
      +
      +This directory contains numerous, small functions typically associated with
      +what you would expect to find in a standard C library.  The sub-directories
      +in this directory contain standard interface that can be executed by user-
      +mode programs.
      +
      +Normally, NuttX is built with no protection and all threads running in kerne-
      +mode.  In that model, there is no real architectural distinction between
      +what is a kernel-mode program and what is a user-mode program; the system is
      +more like on multi-threaded program that all runs in kernel-mode.
      +
      +But if the CONFIG_NUTTX_KERNEL option is selected, NuttX will be built into
      +distinct user-mode and kernel-mode sections.  In that case, most of the
      +code in the nuttx/ directory will run in kernel-mode with with exceptions
      +of (1) the user-mode "proxies" found in syscall/proxies, and (2) the
      +standard C library functions found in this directory.  In this build model,
      +it is critical to separate the user-mode OS interfaces in this way.
      +
      +Sub-Directories
      +===============
      +
      +The files in the lib/ directory are organized (mostly) according which file
      +in the include/ directory provides the prototype for library functions.  So
      +we have:
      +
      +  libgen    - libgen.h
      +  fixedmath - fixedmath.h
      +  math      - math.h
      +  mqueue    - pthread.h
      +  net       - Various network-related header files: netinet/ether.h, arpa/inet.h
      +  pthread   - pthread.h
      +  queue     - queue.h
      +  sched     - sched.h
      +  semaphore - semaphore.h
      +  stdio     - stdio.h
      +  stdlib    - stdlib.h
      +  string    - string.h
      +  time      - time.h
      +  unistd    - unistd.h
      +
      +There is also a misc/ subdirectory that contains various internal functions
      +and interfaces from header files that are too few to warrant their own sub-
      +directory:
      +
      + misc       - Nonstandard "glue" logic, debug.h, crc32.h, dirent.h
      +
      +Library Database
      +================
      +
      +Information about functions available in the NuttX C library information is
      +maintained in a database.  That "database" is implemented as a simple comma-
      +separated-value file, lib.csv.  Most spreadsheets programs will accept this
      +format and can be used to maintain the library database.
      +
      +This library database will (eventually) be used to generate symbol library
      +symbol table information that can be exported to external applications.
      +
      +The format of the CSV file for each line is:
      +
      +  Field 1: Function name
      +  Field 2: The header file that contains the function prototype
      +  Field 3: Condition for compilation
      +  Field 4: The type of function return value.
      +  Field 5 - N+5: The type of each of the N formal parameters of the function
      +
      +Each type field has a format as follows:
      +
      +  type name:
      +        For all simpler types
      +  formal type | actual type: 
      +        For array types where the form of the formal (eg. int parm[2])
      +        differs from the type of actual passed parameter (eg. int*).  This
      +        is necessary because you cannot do simple casts to array types.
      +  formal type | union member actual type | union member fieldname:
      +        A similar situation exists for unions.  For example, the formal
      +        parameter type union sigval -- You cannot cast a uintptr_t to
      +        a union sigval, but you can cast to the type of one of the union
      +        member types when passing the actual paramter.  Similarly, we
      +        cannot cast a union sigval to a uinptr_t either.  Rather, we need
      +        to cast a specific union member fieldname to uintptr_t.
      +
      +NOTE: The tool mksymtab can be used to generate a symbol table from this CSV
      +file.  See nuttx/tools/README.txt for further details about the use of mksymtab.
      diff --git a/nuttx/lib/dirent/Make.defs b/nuttx/lib/dirent/Make.defs
      new file mode 100644
      index 0000000000..cc1d6b7839
      --- /dev/null
      +++ b/nuttx/lib/dirent/Make.defs
      @@ -0,0 +1,48 @@
      +############################################################################
      +# lib/dirent/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
      +
      +# Add the dirent C files to the build
      +
      +CSRCS += lib_readdirr.c lib_telldir.c
      +
      +# Add the dirent directory to the build
      +
      +DEPPATH += --dep-path dirent
      +VPATH += :dirent
      +
      +endif
      +
      diff --git a/nuttx/lib/dirent/lib_readdirr.c b/nuttx/lib/dirent/lib_readdirr.c
      new file mode 100644
      index 0000000000..47c5b9a7bd
      --- /dev/null
      +++ b/nuttx/lib/dirent/lib_readdirr.c
      @@ -0,0 +1,122 @@
      +/****************************************************************************
      + * lib/dirent/lib_readdirr.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: readdir_r
      + *
      + * Description:
      + *   The readdir() function returns a pointer to a dirent
      + *   structure representing the next directory entry in the
      + *   directory stream pointed to by dir.  It returns NULL on
      + *   reaching the end-of-file or if an error occurred.
      + *
      + * Inputs:
      + *   dirp -- An instance of type DIR created by a previous
      + *     call to opendir();
      + *   entry -- The  storage  pointed to by entry must be large
      + *     enough for a dirent with an array of char d_name
      + *     members containing at least {NAME_MAX}+1 elements.
      + *   result -- Upon successful return, the pointer returned
      + *     at *result shall have the  same  value  as  the 
      + *     argument entry. Upon reaching the end of the directory
      + *     stream, this pointer shall have the value NULL.
      + *
      + * Return:
      + *   If successful, the readdir_r() function return s zero;
      + *   otherwise, an error number is returned to indicate the
      + *   error.
      + *
      + *   EBADF   - Invalid directory stream descriptor dir
      + *
      + ****************************************************************************/
      +
      +int readdir_r(FAR DIR *dirp, FAR struct dirent *entry,
      +              FAR struct dirent **result)
      +{
      +  struct dirent *tmp;
      +
      +  /* NOTE: The following use or errno is *not* thread-safe */
      +
      +  set_errno(0);
      +  tmp = readdir(dirp);
      +  if (!tmp)
      +    {
      +       int error = get_errno();
      +       if (!error)
      +          {
      +            if (result)
      +              {
      +                *result = NULL;
      +              }
      +            return 0;
      +          }
      +       else
      +          {
      +            return error;
      +          }
      +    }
      +
      +  if (entry)
      +    {
      +      memcpy(entry, tmp, sizeof(struct dirent));
      +    }
      +
      +  if (result)
      +    {
      +      *result = entry;
      +    }
      +  return 0;
      +}
      +
      diff --git a/nuttx/lib/dirent/lib_telldir.c b/nuttx/lib/dirent/lib_telldir.c
      new file mode 100644
      index 0000000000..3753b326e9
      --- /dev/null
      +++ b/nuttx/lib/dirent/lib_telldir.c
      @@ -0,0 +1,91 @@
      +/****************************************************************************
      + * lib/dirent/fs_telldir.c
      + *
      + *   Copyright (C) 2007-2008, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: telldir
      + *
      + * Description:
      + *   The telldir() function returns the current location
      + *   associated with the directory stream dirp.
      + *
      + * Inputs:
      + *   dirp -- An instance of type DIR created by a previous
      + *     call to opendir();
      + *
      + * Return:
      + *   On success, the telldir() function returns the current
      + *   location in the directory stream.  On error, -1 is
      + *   returned, and errno is set appropriately.
      + *
      + *   EBADF - Invalid directory stream descriptor dir
      + *
      + ****************************************************************************/
      +
      +off_t telldir(FAR DIR *dirp)
      +{
      +  struct fs_dirent_s *idir = (struct fs_dirent_s *)dirp;
      +
      +  if (!idir || !idir->fd_root)
      +    {
      +      set_errno(EBADF);
      +      return (off_t)-1;
      +    }
      +
      +  /* Just return the current position */
      +
      +  return idir->fd_position;
      +}
      +
      diff --git a/nuttx/lib/fixedmath/Make.defs b/nuttx/lib/fixedmath/Make.defs
      new file mode 100644
      index 0000000000..578e330153
      --- /dev/null
      +++ b/nuttx/lib/fixedmath/Make.defs
      @@ -0,0 +1,43 @@
      +############################################################################
      +# lib/fixedmath/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the fixed precision math C files to the build
      +
      +CSRCS += lib_rint.c lib_fixedmath.c lib_b16sin.c lib_b16cos.c lib_b16atan2.c
      +
      +# Add the fixed precision math directory to the build
      +
      +DEPPATH += --dep-path fixedmath
      +VPATH += :fixedmath
      diff --git a/nuttx/lib/fixedmath/lib_b16atan2.c b/nuttx/lib/fixedmath/lib_b16atan2.c
      new file mode 100644
      index 0000000000..69d132f80f
      --- /dev/null
      +++ b/nuttx/lib/fixedmath/lib_b16atan2.c
      @@ -0,0 +1,108 @@
      +/****************************************************************************
      + * lib/fixedmath/lib_b16atan2.c
      + *
      + *   Copyright (C) 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +#define B16_C1     0x00000373 /* 0.013480470 */
      +#define B16_C2     0x00000eb7 /* 0.057477314 */
      +#define B16_C3     0x00001f0a /* 0.121239071 */
      +#define B16_C4     0x00003215 /* 0.195635925 */
      +#define B16_C5     0x0000553f /* 0.332994597 */
      +#define B16_C6     0x00010000 /* 0.999995630 */
      +#define B16_HALFPI 0x00019220 /* 1.570796327 */
      +#define B16_PI     0x00032440 /* 3.141592654 */
      +
      +#ifndef MAX
      +#  define MAX(a,b) (a > b ? a : b)
      +#endif
      +
      +#ifndef MIN
      +#  define MIN(a,b) (a < b ? a : b)
      +#endif
      +
      +#ifndef ABS
      +#  define ABS(a)   (a < 0 ? -a : a)
      +#endif
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: b16atan2
      + *
      + * Description:
      + *   atan2 calculates the arctangent of y/x.  (Based on a algorithm I saw
      + *   posted on the internet... now I have lost the link -- sorry).
      + *
      + ****************************************************************************/
      +
      +b16_t b16atan2(b16_t y, b16_t x)
      +{
      +  b16_t t0;
      +  b16_t t1;
      +  b16_t t2;
      +  b16_t t3;
      +
      +  t2 = ABS(x);
      +  t1 = ABS(y);
      +  t0 = MAX(t2, t1);
      +  t1 = MIN(t2, t1);
      +  t2 = ub16inv(t0);
      +  t2 = b16mulb16(t1, t2);
      +
      +  t3 = b16mulb16(t2, t2); 
      +  t0 =                   - B16_C1;
      +  t0 = b16mulb16(t0, t3) + B16_C2;
      +  t0 = b16mulb16(t0, t3) - B16_C3;
      +  t0 = b16mulb16(t0, t3) + B16_C4;
      +  t0 = b16mulb16(t0, t3) - B16_C5;
      +  t0 = b16mulb16(t0, t3) + B16_C6;
      +  t2 = b16mulb16(t0, t2);
      +
      +  t2 = (ABS(y) > ABS(x)) ? B16_HALFPI - t2 : t2;
      +  t2 = (x < 0) ?  B16_PI - t2 : t2;
      +  t2 = (y < 0) ? -t2 : t2;
      +
      +  return t2;
      +}
      diff --git a/nuttx/lib/fixedmath/lib_b16cos.c b/nuttx/lib/fixedmath/lib_b16cos.c
      new file mode 100644
      index 0000000000..3e9229029e
      --- /dev/null
      +++ b/nuttx/lib/fixedmath/lib_b16cos.c
      @@ -0,0 +1,64 @@
      +/****************************************************************************
      + * lib/fixedmath/lib_b16cos.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: b16cos
      + ****************************************************************************/
      +
      +b16_t b16cos(b16_t rad)
      +{
      +  /* Compute cosine: sin(rad + PI/2) = cos(rad) */
      +
      +  rad += b16HALFPI;
      +  if (rad > b16PI)
      +    {
      +      rad -= b16TWOPI;
      +    }
      +  return b16sin(rad);
      +}
      diff --git a/nuttx/lib/fixedmath/lib_b16sin.c b/nuttx/lib/fixedmath/lib_b16sin.c
      new file mode 100644
      index 0000000000..491b0ec782
      --- /dev/null
      +++ b/nuttx/lib/fixedmath/lib_b16sin.c
      @@ -0,0 +1,110 @@
      +/****************************************************************************
      + * lib/fixedmath/lib_b16sin.c
      + *
      + *   Copyright (C) 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +#define b16_P225       0x0000399a
      +#define b16_P405284735 0x000067c1
      +#define b16_1P27323954 0x000145f3
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: b16sin
      + * Ref: http://lab.polygonal.de/2007/07/18/fast-and-accurate-sinecosine-approximation/
      + ****************************************************************************/
      +
      +b16_t b16sin(b16_t rad)
      +{
      +  b16_t tmp1;
      +  b16_t tmp2;
      +  b16_t tmp3;
      +
      +  /* Force angle into the good range */
      +
      +  if (rad < -b16PI)
      +    {
      +      rad += b16TWOPI;
      +    }
      +  else if (rad > b16PI)
      +   {
      +      rad -= b16TWOPI;
      +   }
      +
      +  /* tmp1 = 1.27323954 * rad
      +   * tmp2 = .405284735 * rad * rad
      +   */
      +
      +
      +  tmp1 = b16mulb16(b16_1P27323954, rad);
      +  tmp2 = b16mulb16(b16_P405284735, b16sqr(rad));
      +
      +  if (rad < 0)
      +    {
      +       /* tmp3 = 1.27323954 * rad + .405284735 * rad * rad */
      +
      +       tmp3 = tmp1 + tmp2;
      +    }
      +  else
      +    {
      +       /* tmp3 = 1.27323954 * rad - 0.405284735 * rad * rad */
      +
      +       tmp3 = tmp1 - tmp2;
      +    }
      +
      +  /* tmp1 = tmp3*tmp3 */
      +
      +  tmp1 = b16sqr(tmp3);
      +  if (tmp3 < 0)
      +    {
      +      /* tmp1 = tmp3 * -tmp3 */
      +
      +      tmp1 = -tmp1;
      +    }
      +
      +  /* Return sin = .225 * (tmp3 * (+/-tmp3) - tmp3) + tmp3 */
      +
      +  return b16mulb16(b16_P225, (tmp1 - tmp3)) + tmp3;
      +}
      diff --git a/nuttx/lib/fixedmath/lib_fixedmath.c b/nuttx/lib/fixedmath/lib_fixedmath.c
      new file mode 100644
      index 0000000000..c1a710e739
      --- /dev/null
      +++ b/nuttx/lib/fixedmath/lib_fixedmath.c
      @@ -0,0 +1,272 @@
      +/****************************************************************************
      + * lib/math/lib_fixedmath.c
      + *
      + *   Copyright (C) 2008-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#ifndef CONFIG_HAVE_LONG_LONG
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fixsign
      + ****************************************************************************/
      +
      +static void fixsign(b16_t *parg1, b16_t *parg2, bool *pnegate)
      +{
      +  bool negate = false;
      +  b16_t arg;
      +
      +  arg = *parg1;
      +  if (arg < 0)
      +    {
      +      *parg1 = -arg;
      +      negate = true;
      +    }
      +
      +  arg = *parg2;
      +  if (arg < 0)
      +    {
      +      *parg2 = -arg;
      +      negate ^= true;
      +    }
      +
      +  *pnegate = negate;
      +}
      +
      +/****************************************************************************
      + * Name: adjustsign
      + ****************************************************************************/
      +
      +static b16_t adjustsign(b16_t result, bool negate)
      +{
      +  /* If the product is negative, then we overflowed */
      +
      +  if (result < 0)
      +    {
      +      if (result)
      +        {
      +          return b16MIN;
      +        }
      +      else
      +        {
      +          return b16MAX;
      +        }
      +    }
      +
      +  /* correct the sign of the result */
      +
      +  if (negate)
      +    {
      +      return -result;
      +    }
      +  return result;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: b16mulb16
      + ****************************************************************************/
      +
      +b16_t b16mulb16(b16_t m1, b16_t m2)
      +{
      +  bool negate;
      +  b16_t product;
      +
      +  fixsign(&m1, &m2, &negate);
      +  product = (b16_t)ub16mulub16((ub16_t)m1, (ub16_t)m2);
      +  return adjustsign(product, negate);
      +}
      +
      +/****************************************************************************
      + * Name: ub16mulub16
      + **************************************************************************/
      +
      +ub16_t ub16mulub16(ub16_t m1, ub16_t m2)
      +{
      + /* Let:
      + *
      +  *   m1 = m1i*2**16 + m1f                                            (b16)
      +  *   m2 = m2i*2**16 + m2f                                            (b16)
      +  *
      +  * Then:
      +  *
      +  *  m1*m2 = (m1i*m2i)*2**32 + (m1i*m2f + m2i*m1f)*2**16 + m1f*m2f     (b32)
      +  *        = (m1i*m2i)*2**16 + (m1i*m2f + m2i*m1f) + m1f*m2f*2**-16    (b16)
      +  *        = a*2**16 + b + c*2**-16
      +  */
      +
      +  uint32_t m1i = ((uint32_t)m1 >> 16);
      +  uint32_t m2i = ((uint32_t)m1 >> 16);
      +  uint32_t m1f = ((uint32_t)m1 & 0x0000ffff);
      +  uint32_t m2f = ((uint32_t)m2 & 0x0000ffff);
      +
      +  return (m1i*m2i << 16) + m1i*m2f + m2i*m1f + (((m1f*m2f) + b16HALF) >> 16);
      +}
      +
      +/****************************************************************************
      + * Name: b16sqr
      + **************************************************************************/
      +
      +b16_t b16sqr(b16_t a)
      +{
      +  b16_t sq;
      +
      +  /* The result is always positive.  Just take the absolute value */
      +
      +  if (a < 0)
      +    {
      +      a = -a;
      +    }
      +
      +  /* Overflow occurred if the result is negative */
      +
      +  sq = (b16_t)ub16sqr(a);
      +  if (sq < 0)
      +    {
      +      sq = b16MAX;
      +    }
      +  return sq;
      +}
      +
      +/****************************************************************************
      + * Name: b16divb16
      + **************************************************************************/
      +
      +ub16_t ub16sqr(ub16_t a)
      +{
      + /* Let:
      + *
      +  *   m = mi*2**16 + mf                                               (b16)
      +  *
      +  * Then:
      +  *
      +  *  m*m = (mi*mi)*2**32 + 2*(m1*m2)*2**16 + mf*mf                    (b32)
      +  *      = (mi*mi)*2**16 + 2*(mi*mf)       + mf*mf*2**-16             (b16)
      +  */
      +
      +  uint32_t mi = ((uint32_t)a >> 16);
      +  uint32_t mf = ((uint32_t)a & 0x0000ffff);
      +
      +  return (mi*mi << 16) + (mi*mf << 1) + ((mf*mf + b16HALF) >> 16);
      +}
      +
      +/****************************************************************************
      + * Name: b16divb16
      + **************************************************************************/
      +
      +b16_t b16divb16(b16_t num, b16_t denom)
      +{
      +  bool  negate;
      +  b16_t quotient;
      +
      +  fixsign(&num, &denom, &negate);
      +  quotient = (b16_t)ub16divub16((ub16_t)num, (ub16_t)denom);
      +  return adjustsign(quotient, negate);
      +}
      +
      +/****************************************************************************
      + * Name: ub16divub16
      + **************************************************************************/
      +
      +ub16_t ub16divub16(ub16_t num, ub16_t denom)
      +{
      +  uint32_t term1;
      +  uint32_t numf;
      +  uint32_t product;
      +
      + /* Let:
      +  *
      +  *   num = numi*2**16 + numf                                         (b16)
      +  *   den = deni*2**16 + denf                                         (b16)
      +  *
      +  * Then:
      +  *
      +  *  num/den = numi*2**16 / den + numf / den                          (b0)
      +  *          = numi*2**32 / den + numf*2**16 /den                     (b16)
      +  */
      +
      +  /* Check for overflow in the first part of the quotient */
      +
      +  term1 = ((uint32_t)num & 0xffff0000) / denom;
      +  if (term1 >= 0x00010000)
      +    {
      +        return ub16MAX; /* Will overflow */
      +    }
      +
      +  /* Finish the division */
      +
      +  numf    = num - term1 * denom;
      +  term1 <<= 16;
      +  product = term1 + (numf + (denom >> 1)) / denom;
      +
      +  /* Check for overflow */
      +
      +  if (product < term1)
      +    {
      +        return ub16MAX; /* Overflowed */
      +    }
      +  return product;
      +}
      +
      +#endif
      diff --git a/nuttx/lib/fixedmath/lib_rint.c b/nuttx/lib/fixedmath/lib_rint.c
      new file mode 100644
      index 0000000000..3a6407b8c0
      --- /dev/null
      +++ b/nuttx/lib/fixedmath/lib_rint.c
      @@ -0,0 +1,135 @@
      +/************************************************************
      + * lib/fixedmath/lib_rint.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************
      + * Definitions
      + ************************************************************/
      +
      +/************************************************************
      + * Private Type Declarations
      + ************************************************************/
      +
      +/************************************************************
      + * Private Function Prototypes
      + ************************************************************/
      +
      +/**********************************************************
      + * Global Constant Data
      + **********************************************************/
      +
      +/************************************************************
      + * Global Variables
      + ************************************************************/
      +
      +/**********************************************************
      + * Private Constant Data
      + **********************************************************/
      +
      +/************************************************************
      + * Private Variables
      + ************************************************************/
      +
      +double_t rint(double_t x)
      +{
      +  double_t ret;
      +
      +  /* If the current rounding mode rounds toward negative
      +   * infinity, rint() is identical to floor().  If the current
      +   * rounding mode rounds toward positive infinity, rint() is
      +   * identical to ceil().
      +   */
      +
      +#if defined(CONFIG_FP_ROUND_POSITIVE) && CONFIG_FP_ROUNDING_POSITIVE != 0
      +
      +  ret = ceil(x);
      +
      +#elif defined(CONFIG_FP_ROUND_NEGATIVE) && CONFIG_FP_ROUNDING_NEGATIVE != 0
      +
      +  ret = floor(x);
      +
      +#else
      +
      +  /* In the default rounding mode (round to nearest), rint(x) is the
      +   * integer nearest x with the additional stipulation that if
      +   * |rint(x)-x|=1/2, then rint(x) is even.
      +   */
      +
      +  long     dwinteger  = (long)x;
      +  double_t fremainder = x - (double_t)dwinteger;
      +
      +  if (x < 0.0)
      +    {
      +      /* fremainder should be in range 0 .. -1 */
      +
      +      if (fremainder == -0.5)
      +        {
      +          dwinteger = ((dwinteger+1)&~1);
      +        }
      +      else if (fremainder < -0.5)
      +        {
      +          dwinteger--;
      +        }
      +    }
      +  else
      +    {
      +      /* fremainder should be in range 0 .. 1 */
      +
      +      if (fremainder == 0.5)
      +        {
      +          dwinteger = ((dwinteger+1)&~1);
      +        }
      +      else if (fremainder > 0.5)
      +        {
      +          dwinteger++;
      +        }
      +    }
      +
      +  ret = (double_t)dwinteger;
      +#endif
      +
      +  return ret;
      +}
      diff --git a/nuttx/lib/lib.csv b/nuttx/lib/lib.csv
      new file mode 100644
      index 0000000000..171f64e9b7
      --- /dev/null
      +++ b/nuttx/lib/lib.csv
      @@ -0,0 +1,171 @@
      +"_inet_ntoa","arpa/inet.h","!defined(CONFIG_NET_IPv6) && !defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","in_addr_t"
      +"abort","stdlib.h","","void"
      +"abs","stdlib.h","","int","int"
      +"asprintf","stdio.h","","int","FAR char **","const char *","..."
      +"avsprintf","stdio.h","","int","FAR char **","const char *","va_list"
      +"b16atan2","fixedmath.h","","b16_t","b16_t","b16_t"
      +"b16cos","fixedmath.h","","b16_t","b16_t"
      +"b16divb16","fixedmath.h","","b16_t","b16_t","b16_t"
      +"b16mulb16","fixedmath.h","","b16_t","b16_t","b16_t"
      +"b16sin","fixedmath.h","","b16_t","b16_t"
      +"b16sqr","fixedmath.h","","b16_t","b16_t"
      +"basename","libgen.h","","FAR char","FAR char *"
      +"cfgetspeed","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","speed_t","FAR const struct termios *"
      +"cfsetspeed","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","FAR struct termios *","speed_t"
      +"chdir","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)","int","FAR const char *"
      +"crc32","crc32.h","","uint32_t","FAR const uint8_t *","size_t"
      +"crc32part","crc32.h","","uint32_t","FAR const uint8_t *","size_t","uint32_t"
      +"dbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG)","int","const char *","..."
      +"dbg_enable","debug.h","defined(CONFIG_DEBUG_ENABLE)","void","bool"
      +"dirname","libgen.h","","FAR char","FAR char *"
      +"dq_addafter","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *"
      +"dq_addbefore","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *"
      +"dq_addfirst","queue.h","","void","FAR dq_entry_t *","dq_queue_t *"
      +"dq_addlast","queue.h","","void","FAR dq_entry_t *","dq_queue_t *"
      +"dq_rem","queue.h","","void","FAR dq_entry_t *","dq_queue_t *"
      +"dq_remfirst","queue.h","","FAR dq_entry_t","dq_queue_t *"
      +"dq_remlast","queue.h","","FAR dq_entry_t","dq_queue_t *"
      +"ether_ntoa","netinet/ether.h","","FAR char","FAR const struct ether_addr *"
      +"fclose","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *"
      +"fdopen","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR FILE","int","FAR const char *"
      +"fflush","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *"
      +"fgetc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *"
      +"fgetpos","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR fpos_t *"
      +"fgets","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR char","FAR char *","int","FAR FILE *"
      +"fileno","stdio.h","","int","FAR FILE *"
      +"fopen","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR FILE","FAR const char *","FAR const char *"
      +"fprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR const char *","..."
      +"fputc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","int c","FAR FILE *"
      +"fputs","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *","FAR FILE *"
      +"fread","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","size_t","FAR void *","size_t","size_t","FAR FILE *"
      +"fseek","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","long int","int"
      +"fsetpos","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR fpos_t *"
      +"ftell","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","long","FAR FILE *"
      +"fwrite","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","size_t","FAR const void *","size_t","size_t","FAR FILE *"
      +"getcwd","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)","FAR char","FAR char *","size_t"
      +"getopt","unistd.h","","int","int","FAR char *const[]","FAR const char *"
      +"getoptargp","unistd.h","","FAR char *"
      +"getoptindp","unistd.h","","int"
      +"getoptoptp","unistd.h","","int"
      +"gets","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR char","FAR char *"
      +"gmtime","time.h","","struct tm","const time_t *"
      +"gmtime_r","time.h","","FAR struct tm","FAR const time_t *","FAR struct tm *"
      +"htonl","arpa/inet.h","","uint32_t","uint32_t"
      +"htons","arpa/inet.h","","uint16_t","uint16_t"
      +"imaxabs","stdlib.h","","intmax_t","intmax_t"
      +"inet_addr","arpa/inet.h","","in_addr_t","FAR const char "
      +"inet_ntoa","arpa/inet.h","!defined(CONFIG_NET_IPv6) && defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","struct in_addr"
      +"inet_ntop","arpa/inet.h","","FAR const char","int","FAR const void *","FAR char *","socklen_t"
      +"inet_pton","arpa/inet.h","","int","int","FAR const char *","FAR void *"
      +"labs","stdlib.h","","long int","long int"
      +"lib_dumpbuffer","debug.h","","void","FAR const char *","FAR const uint8_t *","unsigned int"
      +"lib_lowprintf","debug.h","","int","FAR const char *","..."
      +"lib_rawprintf","debug.h","","int","FAR const char *","..."
      +"llabs","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long int","long long int"
      +"lldbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..."
      +"llvdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..."
      +"match","","","int","const char *","const char *"
      +"memccpy","string.h","","FAR void","FAR void *","FAR const void *","int c","size_t"
      +"memchr","string.h","","FAR void","FAR const void *","int c","size_t"
      +"memcmp","string.h","","int","FAR const void *","FAR const void *","size_t"
      +"memcpy","string.h","","FAR void","FAR void *","FAR const void *","size_t"
      +"memmove","string.h","","FAR void","FAR void *","FAR const void *","size_t"
      +"memset","string.h","","FAR void","FAR void *","int c","size_t"
      +"mktime","time.h","","time_t","const struct tm *"
      +"mq_getattr","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","struct mq_attr *"
      +"mq_setattr","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","const struct mq_attr *","struct mq_attr *"
      +"ntohl","arpa/inet.h","","uint32_t","uint32_t"
      +"ntohs","arpa/inet.h","","uint16_t","uint16_t"
      +"perror","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","void","FAR const char *"
      +"printf","stdio.h","","int","const char *","..."
      +"pthread_attr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *"
      +"pthread_attr_getinheritsched","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_attr_t *","FAR int *"
      +"pthread_attr_getschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR struct sched_param *"
      +"pthread_attr_getschedpolicy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int *"
      +"pthread_attr_getstacksize","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR long *"
      +"pthread_attr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *"
      +"pthread_attr_setinheritsched","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int"
      +"pthread_attr_setschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR const struct sched_param *"
      +"pthread_attr_setschedpolicy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int"
      +"pthread_attr_setstacksize","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","long"
      +"pthread_barrierattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *"
      +"pthread_barrierattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_barrierattr_t *","FAR int *"
      +"pthread_barrierattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *"
      +"pthread_barrierattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *","int"
      +"pthread_condattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *"
      +"pthread_condattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *"
      +"pthread_mutexattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *"
      +"pthread_mutexattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","FAR int *"
      +"pthread_mutexattr_gettype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","const pthread_mutexattr_t *","int *"
      +"pthread_mutexattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *"
      +"pthread_mutexattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","int "
      +"pthread_mutexattr_settype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","pthread_mutexattr_t *","int"
      +"puts","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *"
      +"qsort","stdlib.h","","void","void *","size_t","size_t","int(*)(const void *","const void *)"
      +"rand","stdlib.h","","int"
      +"readdir_r","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","int","FAR DIR *","FAR struct dirent *","FAR struct dirent **"
      +"rint","","","double_t","double_t"
      +"sched_get_priority_max","sched.h","","int","int"
      +"sched_get_priority_min","sched.h","","int","int"
      +"sem_getvalue","semaphore.h","","int","FAR sem_t *","FAR int *"
      +"sem_init","semaphore.h","","int","FAR sem_t *","int","unsigned int"
      +"sendfile","sys/sendfile.h","CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0","ssize_t","int","int","off_t","size_t"
      +"sigaddset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *","int"
      +"sigdelset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *","int"
      +"sigemptyset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *"
      +"sigfillset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *"
      +"sigismember","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR const sigset_t *","int"
      +"snprintf","stdio.h","","int","FAR char *","size_t","const char *","..."
      +"sprintf","stdio.h","","int","FAR char *","const char *","..."
      +"sq_addafter","queue.h","","void","FAR sq_entry_t *","FAR sq_entry_t *","FAR sq_queue_t *"
      +"sq_addfirst","queue.h","","void","FAR sq_entry_t *","sq_queue_t *"
      +"sq_addlast","queue.h","","void","FAR sq_entry_t *","sq_queue_t *"
      +"sq_rem","queue.h","","void","FAR sq_entry_t *","sq_queue_t *"
      +"sq_remafter","queue.h","","FAR sq_entry_t","FAR sq_entry_t *","sq_queue_t *"
      +"sq_remfirst","queue.h","","FAR sq_entry_t","sq_queue_t *"
      +"sq_remlast","queue.h","","FAR sq_entry_t","sq_queue_t *"
      +"srand","stdlib.h","","void","unsigned int"
      +"sscanf","stdio.h","","int","const char *","const char *","..."
      +"strcasecmp","string.h","","int","FAR const char *","FAR const char *"
      +"strcasestr","string.h","","FAR char","FAR const char *","FAR const char *"
      +"strcat","string.h","","FAR char","FAR char *","FAR const char *"
      +"strchr","string.h","","FAR char","FAR const char *","int"
      +"strcmp","string.h","","int","FAR const char *","FAR const char *"
      +"strcpy","string.h","","FAR char","char *","FAR const char *"
      +"strcspn","string.h","","size_t","FAR const char *","FAR const char *"
      +"strdup","string.h","","FAR char","FAR const char *"
      +"strerror","string.h","","FAR const char","int"
      +"strftime","time.h","","size_t","char *","size_t","const char *","const struct tm *"
      +"strlen","string.h","","size_t","FAR const char *"
      +"strncasecmp","string.h","","int","FAR const char *","FAR const char *","size_t"
      +"strncat","string.h","","FAR char","FAR char *","FAR const char *","size_t"
      +"strncmp","string.h","","int","FAR const char *","FAR const char *","size_t"
      +"strncpy","string.h","","FAR char","char *","FAR const char *","size_t"
      +"strndup","string.h","","FAR char","FAR const char *","size_t"
      +"strnlen","string.h","","size_t","FAR const char *","size_t"
      +"strpbrk","string.h","","FAR char","FAR const char *","FAR const char *"
      +"strrchr","string.h","","FAR char","FAR const char *","int"
      +"strspn","string.h","","size_t","FAR const char *","FAR const char *"
      +"strstr","string.h","","FAR char","FAR const char *","FAR const char *"
      +"strtod","stdlib.h","","double_t","const char *str","char **endptr"
      +"strtok","string.h","","FAR char","FAR char *","FAR const char *"
      +"strtok_r","string.h","","FAR char","FAR char *","FAR const char *","FAR char **"
      +"strtol","string.h","","long","const char *","char **","int"
      +"strtoll","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long","const char *nptr","char **endptr","int base"
      +"strtoul","stdlib.h","","unsigned long","const char *","char **","int"
      +"strtoull","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","unsigned long long","const char *","char **","int"
      +"tcflush","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int"
      +"tcgetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","FAR struct termios *"
      +"tcsetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int","FAR const struct termios *"
      +"telldir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","off_t","FAR DIR *"
      +"time","time.h","","time_t","time_t *"
      +"ub16divub16","fixedmath.h","","ub16_t","ub16_t","ub16_t"
      +"ub16mulub16","fixedmath.h","","ub16_t","ub16_t","ub16_t"
      +"ub16sqr","fixedmath.h","","ub16_t","ub16_t"
      +"ungetc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","int","FAR FILE *"
      +"vdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE)","int","const char *","..."
      +"vfprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","const char *","va_list"
      +"vprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *","va_list"
      +"vsnprintf","stdio.h","","int","FAR char *","size_t","const char *","va_list"
      +"vsprintf","stdio.h","","int","FAR char *","const char *","va_list"
      +"vsscanf","stdio.h","","int","char *","const char *","va_list"
      diff --git a/nuttx/lib/lib_internal.h b/nuttx/lib/lib_internal.h
      new file mode 100644
      index 0000000000..5da0ac9249
      --- /dev/null
      +++ b/nuttx/lib/lib_internal.h
      @@ -0,0 +1,211 @@
      +/****************************************************************************
      + * lib/lib_internal.h
      + *
      + *   Copyright (C) 2007-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.
      + *
      + ****************************************************************************/
      +
      +#ifndef __LIB_LIB_INTERNAL_H
      +#define __LIB_LIB_INTERNAL_H
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +/* This configuration directory is used in environment variable processing
      + * when we need to reference the user's home directory.  There are no user
      + * directories in NuttX so, by default, this always refers to the root
      + * directory.
      + */
      +
      +#ifndef CONFIG_LIB_HOMEDIR
      +# define CONFIG_LIB_HOMEDIR "/"
      +#endif
      +
      +/* If C std I/O buffering is not supported, then we don't need its semaphore
      + * protection.
      + */
      +
      +#if CONFIG_STDIO_BUFFER_SIZE <= 0
      +#  define lib_sem_initialize(s)
      +#  define lib_take_semaphore(s)
      +#  define lib_give_semaphore(s)
      +#endif
      +
      +/* The NuttX C library an be build in two modes: (1) as a standard, C-libary
      + * that can be used by normal, user-space applications, or (2) as a special,
      + * kernel-mode C-library only used within the OS.  If NuttX is not being
      + * built as separated kernel- and user-space modules, then only the first
      + * mode is supported.
      + */
      +
      +#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
      +#  include 
      +#  define lib_malloc(s)    kmalloc(s)
      +#  define lib_zalloc(s)    kzalloc(s)
      +#  define lib_realloc(p,s) krealloc(p,s)
      +#  define lib_free(p)      kfree(p)
      +#else
      +#  include 
      +#  define lib_malloc(s)    malloc(s)
      +#  define lib_zalloc(s)    zalloc(s)
      +#  define lib_realloc(p,s) realloc(p,s)
      +#  define lib_free(p)      free(p)
      +#endif
      +
      +#define LIB_BUFLEN_UNKNOWN INT_MAX
      +
      +/****************************************************************************
      + * Public Types
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/* Debug output is initially disabled */
      +
      +#ifdef CONFIG_DEBUG_ENABLE
      +extern bool g_dbgenable;
      +#endif
      +
      +/****************************************************************************
      + * Public Function Prototypes
      + ****************************************************************************/
      +
      +/* Defined in lib_streamsem.c */
      +
      +#if CONFIG_NFILE_STREAMS > 0
      +void  stream_semtake(FAR struct streamlist *list);
      +void  stream_semgive(FAR struct streamlist *list);
      +#endif
      +
      +/* Defined in lib_libnoflush.c */
      +
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +int lib_noflush(FAR struct lib_outstream_s *this);
      +#endif
      +
      +/* Defined in lib_libsprintf.c */
      +
      +int lib_sprintf(FAR struct lib_outstream_s *obj,
      +                       const char *fmt, ...);
      +
      +/* Defined lib_libvsprintf.c */
      +
      +int lib_vsprintf(FAR struct lib_outstream_s *obj,
      +                 FAR const char *src, va_list ap);
      +
      +/* Defined lib_rawprintf.c */
      +
      +int lib_rawvprintf(const char *src, va_list ap);
      +
      +/* Defined lib_lowprintf.c */
      +
      +int lib_lowvprintf(const char *src, va_list ap);
      +
      +/* Defined in lib_dtoa.c */
      +
      +#ifdef CONFIG_LIBC_FLOATINGPOINT
      +char *__dtoa(double d, int mode, int ndigits, int *decpt, int *sign,
      +             char **rve);
      +#endif
      +
      +/* Defined in lib_libwrite.c */
      +
      +ssize_t lib_fwrite(FAR const void *ptr, size_t count, FAR FILE *stream);
      +
      +/* Defined in lib_libfread.c */
      +
      +ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream);
      +
      +/* Defined in lib_libfflush.c */
      +
      +ssize_t lib_fflush(FAR FILE *stream, bool bforce);
      +
      +/* Defined in lib_rdflush.c */
      +
      +int lib_rdflush(FAR FILE *stream);
      +
      +/* Defined in lib_wrflush.c */
      +
      +int lib_wrflush(FAR FILE *stream);
      +
      +/* Defined in lib_sem.c */
      +
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +void lib_sem_initialize(FAR struct file_struct *stream);
      +void lib_take_semaphore(FAR struct file_struct *stream);
      +void lib_give_semaphore(FAR struct file_struct *stream);
      +#endif
      +
      +/* Defined in lib_libgetbase.c */
      +
      +int lib_getbase(const char *nptr, const char **endptr);
      +
      +/* Defined in lib_skipspace.c */
      +
      +void lib_skipspace(const char **pptr);
      +
      +/* Defined in lib_isbasedigit.c */
      +
      +bool lib_isbasedigit(int ch, int base, int *value);
      +
      +/* Defined in lib_checkbase.c */
      +
      +int lib_checkbase(int base, const char **pptr);
      +
      +/* Defined in lib_expi.c */
      +
      +#ifdef CONFIG_LIBM
      +double lib_expi(size_t n);
      +#endif
      +
      +/* Defined in lib_libsqrtapprox.c */
      +
      +#ifdef CONFIG_LIBM
      +float lib_sqrtapprox(float x);
      +#endif
      +
      +#endif /* __LIB_LIB_INTERNAL_H */
      diff --git a/nuttx/lib/libgen/Make.defs b/nuttx/lib/libgen/Make.defs
      new file mode 100644
      index 0000000000..f126455124
      --- /dev/null
      +++ b/nuttx/lib/libgen/Make.defs
      @@ -0,0 +1,43 @@
      +############################################################################
      +# lib/libgen/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the libgen C files to the build
      +
      +CSRCS += lib_basename.c lib_dirname.c
      +
      +# Add the libgen directory to the build
      +
      +DEPPATH += --dep-path libgen
      +VPATH += :libgen
      diff --git a/nuttx/lib/libgen/lib_basename.c b/nuttx/lib/libgen/lib_basename.c
      new file mode 100644
      index 0000000000..986c6b8520
      --- /dev/null
      +++ b/nuttx/lib/libgen/lib_basename.c
      @@ -0,0 +1,131 @@
      +/****************************************************************************
      + * lib/libgen/lib_basename.c
      + *
      + *   Copyright (C) 2007, 2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      +
      +static char g_retchar[2];
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function: basename
      + *
      + * Description:
      + *   basename() extracts the filename component from a null-terminated
      + *   pathname string. In the usual case, basename() returns the component
      + *   following the final '/'. Trailing '/' characters are not counted as
      + *   part of the pathname.
      + *
      + *   If path does not contain a slash, basename() returns a copy of path.
      + *   If path is the string "/", then basename() returns the string "/". If
      + *   path is a NULL pointer or points to an empty string, then basename()
      + *   return the string ".".
      + *
      + *   basename() may modify the contents of path, so copies should be passed.
      + *   basename() may return pointers to statically allocated memory which may
      + *   be overwritten by subsequent calls.
      + *
      + * Parameter:
      + *   path The null-terminated string referring to the path to be decomposed
      + *
      + * Return:
      + *   On success the filename component of the path is returned.
      + *
      + ****************************************************************************/
      +
      +FAR char *basename(FAR char *path)
      +{
      +  char *p;
      +  int   len;
      +  int   ch;
      +
      +  /* Handle some corner cases */
      +
      +  if (!path || *path == '\0')
      +    {
      +      ch = '.';
      +      goto out_retchar;
      +    }
      +
      +  /* Check for trailing slash characters */
      +
      +  len = strlen(path);
      +  while (path[len-1] == '/')
      +    {
      +      /* Remove trailing '/' UNLESS this would make a zero length string */
      +      if (len > 1)
      +        {
      +          path[len-1] = '\0';
      +          len--;
      +        }
      +      else
      +        {
      +          ch = '/';
      +          goto out_retchar;
      +        }
      +    }
      +
      +  /* Get the address of the last '/' which is not at the end of the path and,
      +   * therefor, must be just before the beginning of the filename component.
      +   */
      +
      +  p = strrchr(path, '/');
      +  if (p)
      +    {
      +      return p + 1;
      +    }
      +
      +  /* There is no '/' in the path */
      +
      +  return path;
      +
      +out_retchar:
      +  g_retchar[0] = ch;
      +  g_retchar[1] = '\0';
      +  return g_retchar;
      +}
      diff --git a/nuttx/lib/libgen/lib_dirname.c b/nuttx/lib/libgen/lib_dirname.c
      new file mode 100644
      index 0000000000..248293a605
      --- /dev/null
      +++ b/nuttx/lib/libgen/lib_dirname.c
      @@ -0,0 +1,144 @@
      +/****************************************************************************
      + * lib/libgen/lib_dirname.c
      + *
      + *   Copyright (C) 2007, 2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      +
      +static char g_retchar[2];
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function: dirname
      + *
      + * Description:
      + *   dirname() extracts the directory component from a null-terminated
      + *   pathname string. In the usual case, dirname() returns the string up
      + *   to, but not including, the final '/'. Trailing '/' characters are not
      + *   counted as part of the pathname.
      + *
      + *   If path does not contain a slash, dirname() returns the string ".". If
      + *   path is the string "/", then dirname() returns the string "/". If path
      + *   is a NULL pointer or points to an empty string, then dirname() returns
      + *   the string ".".
      + *
      + *   dirname() may modify the contents of path, so copies should be passed.
      + *   dirname() may return pointers to statically allocated memory which may
      + *   be overwritten by subsequent calls.
      + *
      + * Parameter:
      + *   path The null-terminated string referring to the path to be decomposed
      + *
      + * Return:
      + *   On success the directory component of the path is returned.
      + *
      + ****************************************************************************/
      +
      +FAR char *dirname(FAR char *path)
      +{
      +  char *p;
      +  int   len;
      +  int   ch;
      +
      +  /* Handle some corner cases */
      +
      +  if (!path || *path == '\0')
      +    {
      +      ch = '.';
      +      goto out_retchar;
      +    }
      +
      +  /* Check for trailing slash characters */
      +
      +  len = strlen(path);
      +  while (path[len-1] == '/')
      +    {
      +      /* Remove trailing '/' UNLESS this would make a zero length string */
      +      if (len > 1)
      +        {
      +          path[len-1] = '\0';
      +          len--;
      +        }
      +      else
      +        {
      +          ch = '/';
      +          goto out_retchar;
      +        }
      +    }
      +
      +  /* Get the address of the last '/' which is not at the end of the path and,
      +   * therefor, must be the end of the directory component.
      +   */
      +
      +  p = strrchr(path, '/');
      +  if (p)
      +    {
      +      /* Handle the case where the only '/' in the string is the at the beginning
      +       * of the path.
      +       */
      +
      +      if (p == path)
      +        {
      +          ch = '/';
      +          goto out_retchar;
      +        }
      +
      +      /* No, the directory component is the substring before the '/'. */
      +
      +      *p = '\0';
      +      return path;
      +    }
      +
      +  /* There is no '/' in the path */
      +
      +  ch = '.';
      +
      +out_retchar:
      +  g_retchar[0] = ch;
      +  g_retchar[1] = '\0';
      +  return g_retchar;
      +}
      diff --git a/nuttx/lib/math/Kconfig b/nuttx/lib/math/Kconfig
      new file mode 100644
      index 0000000000..c24bfd53f3
      --- /dev/null
      +++ b/nuttx/lib/math/Kconfig
      @@ -0,0 +1,26 @@
      +#
      +# For a description of the syntax of this configuration file,
      +# see misc/tools/kconfig-language.txt.
      +#
      +
      +config LIBM
      +	bool "Math library"
      +	default n
      +	depends on !ARCH_MATH_H
      +	---help---
      +		By default, no math library will be provided by NuttX.  In this this case, it
      +		is assumed that (1) no math library is required, or (2) you will be using the
      +		math.h header file and the libm library provided by your toolchain.
      +
      +		This is may be a very good choice is possible because your toolchain may have
      +		have a highly optimized version of libm.
      +
      +		Another possibility is that you have a custom, architecture-specific math
      +		libary and that the corresponding math.h file resides at arch//include/math.h.
      +		The option is selected via ARCH_MATH_H.  If ARCH_MATH_H is selected,then the include/nuttx/math.h
      + 		header file will be copied to include/math.h where it can be used by your applications.
      +
      +		If ARCH_MATH_H is not defined, then this option can be selected to build a generic,
      +		math library built into NuttX.  This math library comes from the Rhombus OS and
      +		was written by Nick Johnson.  The Rhombus OS math library port was contributed by
      +		Darcy Gong.
      diff --git a/nuttx/lib/math/Make.defs b/nuttx/lib/math/Make.defs
      new file mode 100644
      index 0000000000..73d0be6f3b
      --- /dev/null
      +++ b/nuttx/lib/math/Make.defs
      @@ -0,0 +1,62 @@
      +############################################################################
      +# lib/math/Make.defs
      +#
      +#   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_LIBM),y)
      +
      +# Add the floating point math C files to the build
      +
      +CSRCS += lib_acosf.c lib_asinf.c lib_atan2f.c lib_atanf.c lib_ceilf.c lib_cosf.c
      +CSRCS += lib_coshf.c  lib_expf.c lib_fabsf.c lib_floorf.c lib_fmodf.c lib_frexpf.c
      +CSRCS += lib_ldexpf.c lib_logf.c lib_log10f.c lib_log2f.c lib_modff.c lib_powf.c
      +CSRCS += lib_sinf.c lib_sinhf.c lib_sqrtf.c lib_tanf.c lib_tanhf.c
      +
      +CSRCS += lib_acos.c lib_asin.c lib_atan.c lib_atan2.c lib_ceil.c lib_cos.c
      +CSRCS += lib_cosh.c lib_exp.c lib_fabs.c lib_floor.c lib_fmod.c lib_frexp.c
      +CSRCS += lib_ldexp.c lib_log.c lib_log10.c lib_log2.c lib_modf.c lib_pow.c
      +CSRCS += lib_sin.c lib_sinh.c lib_sqrt.c lib_tan.c lib_tanh.c
      +
      +CSRCS += lib_acosl.c lib_asinl.c lib_atan2l.c lib_atanl.c lib_ceill.c lib_cosl.c
      +CSRCS += lib_coshl.c lib_expl.c lib_fabsl.c lib_floorl.c lib_fmodl.c lib_frexpl.c
      +CSRCS += lib_ldexpl.c lib_logl.c lib_log10l.c lib_log2l.c lib_modfl.c lib_powl.c
      +CSRCS += lib_sinl.c lib_sinhl.c lib_sqrtl.c lib_tanl.c lib_tanhl.c
      +
      +CSRCS += lib_libexpi.c lib_libsqrtapprox.c
      +
      +# Add the floating point math directory to the build
      +
      +DEPPATH += --dep-path math
      +VPATH += :math
      +
      +endif
      diff --git a/nuttx/lib/math/lib_acos.c b/nuttx/lib/math/lib_acos.c
      new file mode 100644
      index 0000000000..d5ec36b9ff
      --- /dev/null
      +++ b/nuttx/lib/math/lib_acos.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_acos.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double acos(double x)
      +{
      +  return (M_PI_2 - asin(x));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_acosf.c b/nuttx/lib/math/lib_acosf.c
      new file mode 100644
      index 0000000000..e14a73a6ea
      --- /dev/null
      +++ b/nuttx/lib/math/lib_acosf.c
      @@ -0,0 +1,41 @@
      +/************************************************************************
      + * lib/math/lib_acosf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float acosf(float x)
      +{
      +  return (M_PI_2 - asinf(x));
      +}
      diff --git a/nuttx/lib/math/lib_acosl.c b/nuttx/lib/math/lib_acosl.c
      new file mode 100644
      index 0000000000..9113305776
      --- /dev/null
      +++ b/nuttx/lib/math/lib_acosl.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_acos.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double acosl(long double x)
      +{
      +  return (M_PI_2 - asinl(x));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_asin.c b/nuttx/lib/math/lib_asin.c
      new file mode 100644
      index 0000000000..61b9535310
      --- /dev/null
      +++ b/nuttx/lib/math/lib_asin.c
      @@ -0,0 +1,69 @@
      +/************************************************************************
      + * lib/math/lib_sin.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double asin(double x)
      +{
      +  long double y, y_sin, y_cos;
      +
      +  y = 0;
      +
      +  while (1)
      +    {
      +      y_sin = sin(y);
      +      y_cos = cos(y);
      +
      +      if (y > M_PI_2 || y < -M_PI_2)
      +        {
      +          y = fmod(y, M_PI);
      +        }
      +
      +      if (y_sin + DBL_EPSILON >= x && y_sin - DBL_EPSILON <= x)
      +        {
      +          break;
      +        }
      +
      +      y = y - (y_sin - x) / y_cos;
      +    }
      +
      +  return y;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_asinf.c b/nuttx/lib/math/lib_asinf.c
      new file mode 100644
      index 0000000000..17669a9346
      --- /dev/null
      +++ b/nuttx/lib/math/lib_asinf.c
      @@ -0,0 +1,65 @@
      +/************************************************************************
      + * lib/math/lib_sinf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float asinf(float x)
      +{
      +  long double y, y_sin, y_cos;
      +
      +  y = 0;
      +
      +  while (1)
      +    {
      +      y_sin = sinf(y);
      +      y_cos = cosf(y);
      +
      +      if (y > M_PI_2 || y < -M_PI_2)
      +        {
      +          y = fmodf(y, M_PI);
      +        }
      +
      +      if (y_sin + FLT_EPSILON >= x && y_sin - FLT_EPSILON <= x)
      +        {
      +          break;
      +        }
      +
      +      y = y - (y_sin - x) / y_cos;
      +    }
      +
      +  return y;
      +}
      +
      diff --git a/nuttx/lib/math/lib_asinl.c b/nuttx/lib/math/lib_asinl.c
      new file mode 100644
      index 0000000000..dbb2bc3a2e
      --- /dev/null
      +++ b/nuttx/lib/math/lib_asinl.c
      @@ -0,0 +1,69 @@
      +/************************************************************************
      + * lib/math/lib_sinl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double asinl(long double x)
      +{
      +  long double y, y_sin, y_cos;
      +
      +  y = 0;
      +
      +  while (1)
      +    {
      +      y_sin = sinl(y);
      +      y_cos = cosl(y);
      +
      +      if (y > M_PI_2 || y < -M_PI_2)
      +        {
      +          y = fmodl(y, M_PI);
      +        }
      +
      +      if (y_sin + LDBL_EPSILON >= x && y_sin - LDBL_EPSILON <= x)
      +        {
      +          break;
      +        }
      +
      +      y = y - (y_sin - x) / y_cos;
      +    }
      +
      +  return y;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_atan.c b/nuttx/lib/math/lib_atan.c
      new file mode 100644
      index 0000000000..b4db8fb313
      --- /dev/null
      +++ b/nuttx/lib/math/lib_atan.c
      @@ -0,0 +1,48 @@
      +/************************************************************************
      + * lib/math/lib_atan.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double atan(double x)
      +{
      +  return asin(x / sqrt(x * x + 1));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_atan2.c b/nuttx/lib/math/lib_atan2.c
      new file mode 100644
      index 0000000000..82d1f47ec3
      --- /dev/null
      +++ b/nuttx/lib/math/lib_atan2.c
      @@ -0,0 +1,86 @@
      +/************************************************************************
      + * lib/math/lib_atan2.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double atan2(double y, double x)
      +{
      +  if (y == 0.0)
      +    {
      +      if (x >= 0.0)
      +        {
      +          return 0.0;
      +        }
      +      else
      +        {
      +          return M_PI;
      +        }
      +    }
      +  else if (y > 0.0)
      +    {
      +      if (x == 0.0)
      +        {
      +          return M_PI_2;
      +        }
      +      else if (x > 0.0)
      +        {
      +          return atan(y / x);
      +        }
      +      else
      +        {
      +          return M_PI - atan(y / x);
      +        }
      +    }
      +  else
      +    {
      +      if (x == 0.0)
      +        {
      +          return M_PI + M_PI_2;
      +        }
      +      else if (x > 0.0)
      +        {
      +          return 2 * M_PI - atan(y / x);
      +        }
      +      else
      +        {
      +          return M_PI + atan(y / x);
      +        }
      +    }
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_atan2f.c b/nuttx/lib/math/lib_atan2f.c
      new file mode 100644
      index 0000000000..a60d32c655
      --- /dev/null
      +++ b/nuttx/lib/math/lib_atan2f.c
      @@ -0,0 +1,81 @@
      +/************************************************************************
      + * lib/math/lib_atan2f.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float atan2f(float y, float x)
      +{
      +  if (y == 0.0)
      +    {
      +      if (x >= 0.0)
      +        {
      +          return 0.0;
      +        }
      +      else
      +        {
      +          return M_PI;
      +        }
      +    }
      +  else if (y > 0.0)
      +    {
      +      if (x == 0.0)
      +        {
      +          return M_PI_2;
      +        }
      +      else if (x > 0.0)
      +        {
      +          return atanf(y / x);
      +        }
      +      else
      +        {
      +          return M_PI - atanf(y / x);
      +        }
      +    }
      +  else
      +    {
      +      if (x == 0.0)
      +        {
      +          return M_PI + M_PI_2;
      +        }
      +      else if (x > 0.0)
      +        {
      +          return 2 * M_PI - atanf(y / x);
      +        }
      +      else
      +        {
      +          return M_PI + atanf(y / x);
      +        }
      +    }
      +}
      diff --git a/nuttx/lib/math/lib_atan2l.c b/nuttx/lib/math/lib_atan2l.c
      new file mode 100644
      index 0000000000..07fcd9669b
      --- /dev/null
      +++ b/nuttx/lib/math/lib_atan2l.c
      @@ -0,0 +1,87 @@
      +/************************************************************************
      + * lib/math/lib_atan2l.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double atan2l(long double y, long double x)
      +{
      +
      +  if (y == 0.0)
      +    {
      +      if (x >= 0.0)
      +        {
      +          return 0.0;
      +        }
      +      else
      +        {
      +          return M_PI;
      +        }
      +    }
      +  else if (y > 0.0)
      +    {
      +      if (x == 0.0)
      +        {
      +          return M_PI_2;
      +        }
      +      else if (x > 0.0)
      +        {
      +          return atanl(y / x);
      +        }
      +      else
      +        {
      +          return M_PI - atanl(y / x);
      +        }
      +    }
      +  else
      +    {
      +      if (x == 0.0)
      +        {
      +          return M_PI + M_PI_2;
      +        }
      +      else if (x > 0.0)
      +        {
      +          return 2 * M_PI - atanl(y / x);
      +        }
      +      else
      +        {
      +          return M_PI + atanl(y / x);
      +        }
      +    }
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_atanf.c b/nuttx/lib/math/lib_atanf.c
      new file mode 100644
      index 0000000000..7c540dd163
      --- /dev/null
      +++ b/nuttx/lib/math/lib_atanf.c
      @@ -0,0 +1,43 @@
      +/************************************************************************
      + * lib/math/lib_atanf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float atanf(float x)
      +{
      +  return asinf(x / sqrtf(x * x + 1));
      +}
      diff --git a/nuttx/lib/math/lib_atanl.c b/nuttx/lib/math/lib_atanl.c
      new file mode 100644
      index 0000000000..0fa2030988
      --- /dev/null
      +++ b/nuttx/lib/math/lib_atanl.c
      @@ -0,0 +1,48 @@
      +/************************************************************************
      + * lib/math/lib_atanl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double atanl(long double x)
      +{
      +  return asinl(x / sqrtl(x * x + 1));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_ceil.c b/nuttx/lib/math/lib_ceil.c
      new file mode 100644
      index 0000000000..0e76029967
      --- /dev/null
      +++ b/nuttx/lib/math/lib_ceil.c
      @@ -0,0 +1,52 @@
      +/************************************************************************
      + * lib/math/lib_ceil.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double ceil(double x)
      +{
      +  modf(x, &x);
      +  if (x > 0.0)
      +    {
      +      x += 1.0;
      +    }
      +
      +  return x;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_ceilf.c b/nuttx/lib/math/lib_ceilf.c
      new file mode 100644
      index 0000000000..0721ffc22a
      --- /dev/null
      +++ b/nuttx/lib/math/lib_ceilf.c
      @@ -0,0 +1,47 @@
      +/************************************************************************
      + * lib/math/lib_ceilf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float ceilf(float x)
      +{
      +  modff(x, &x);
      +  if (x > 0.0)
      +    {
      +      x += 1.0;
      +    }
      +
      +  return x;
      +}
      diff --git a/nuttx/lib/math/lib_ceill.c b/nuttx/lib/math/lib_ceill.c
      new file mode 100644
      index 0000000000..a24b56f683
      --- /dev/null
      +++ b/nuttx/lib/math/lib_ceill.c
      @@ -0,0 +1,52 @@
      +/************************************************************************
      + * lib/math/lib_ceil;.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double ceill(long double x)
      +{
      +  modfl(x, &x);
      +  if (x > 0.0)
      +    {
      +      x += 1.0;
      +    }
      +
      +  return x;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_cos.c b/nuttx/lib/math/lib_cos.c
      new file mode 100644
      index 0000000000..aa672b8559
      --- /dev/null
      +++ b/nuttx/lib/math/lib_cos.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_cos.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double cos(double x)
      +{
      +  return sin(x + M_PI_2);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_cosf.c b/nuttx/lib/math/lib_cosf.c
      new file mode 100644
      index 0000000000..093a8a0024
      --- /dev/null
      +++ b/nuttx/lib/math/lib_cosf.c
      @@ -0,0 +1,41 @@
      +/************************************************************************
      + * lib/math/lib_cosf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float cosf(float x)
      +{
      +  return sinf(x + M_PI_2);
      +}
      diff --git a/nuttx/lib/math/lib_cosh.c b/nuttx/lib/math/lib_cosh.c
      new file mode 100644
      index 0000000000..1be44d2933
      --- /dev/null
      +++ b/nuttx/lib/math/lib_cosh.c
      @@ -0,0 +1,47 @@
      +/************************************************************************
      + * lib/math/lib_cosh.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double cosh(double x)
      +{
      +  x = exp(x);
      +  return ((x + (1.0 / x)) / 2.0);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_coshf.c b/nuttx/lib/math/lib_coshf.c
      new file mode 100644
      index 0000000000..d5e5ea14de
      --- /dev/null
      +++ b/nuttx/lib/math/lib_coshf.c
      @@ -0,0 +1,42 @@
      +/************************************************************************
      + * lib/math/lib_coshf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float coshf(float x)
      +{
      +  x = expf(x);
      +  return ((x + (1.0 / x)) / 2.0);
      +}
      diff --git a/nuttx/lib/math/lib_coshl.c b/nuttx/lib/math/lib_coshl.c
      new file mode 100644
      index 0000000000..4576b88769
      --- /dev/null
      +++ b/nuttx/lib/math/lib_coshl.c
      @@ -0,0 +1,47 @@
      +/************************************************************************
      + * lib/math/lib_coshl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double coshl(long double x)
      +{
      +  x = expl(x);
      +  return ((x + (1.0 / x)) / 2.0);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_cosl.c b/nuttx/lib/math/lib_cosl.c
      new file mode 100644
      index 0000000000..25dd861393
      --- /dev/null
      +++ b/nuttx/lib/math/lib_cosl.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_cosl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double cosl(long double x)
      +{
      +  return sinl(x + M_PI_2);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_exp.c b/nuttx/lib/math/lib_exp.c
      new file mode 100644
      index 0000000000..1e3120453d
      --- /dev/null
      +++ b/nuttx/lib/math/lib_exp.c
      @@ -0,0 +1,126 @@
      +/************************************************************************
      + * lib/math/lib_exp.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +
      +/************************************************************************
      + * Private Data
      + ************************************************************************/
      +
      +static double _dbl_inv_fact[] =
      +{
      +  1.0 / 1.0,                    // 1 / 0!
      +  1.0 / 1.0,                    // 1 / 1!
      +  1.0 / 2.0,                    // 1 / 2!
      +  1.0 / 6.0,                    // 1 / 3!
      +  1.0 / 24.0,                   // 1 / 4!
      +  1.0 / 120.0,                  // 1 / 5!
      +  1.0 / 720.0,                  // 1 / 6!
      +  1.0 / 5040.0,                 // 1 / 7!
      +  1.0 / 40320.0,                // 1 / 8!
      +  1.0 / 362880.0,               // 1 / 9!
      +  1.0 / 3628800.0,              // 1 / 10!
      +  1.0 / 39916800.0,             // 1 / 11!
      +  1.0 / 479001600.0,            // 1 / 12!
      +  1.0 / 6227020800.0,           // 1 / 13!
      +  1.0 / 87178291200.0,          // 1 / 14!
      +  1.0 / 1307674368000.0,        // 1 / 15!
      +  1.0 / 20922789888000.0,       // 1 / 16!
      +  1.0 / 355687428096000.0,      // 1 / 17!
      +  1.0 / 6402373705728000.0,     // 1 / 18!
      +};
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +double exp(double x)
      +{
      +  size_t int_part;
      +  bool invert;
      +  double value;
      +  double x0;
      +  size_t i;
      +
      +  if (x == 0)
      +    {
      +      return 1;
      +    }
      +  else if (x < 0)
      +    {
      +      invert = true;
      +      x = -x;
      +    }
      +  else
      +    {
      +      invert = false;
      +    }
      +
      +  /* Extract integer component */
      +
      +  int_part = (size_t) x;
      +
      +  /* Set x to fractional component */
      +
      +  x -= (double)int_part;
      +
      +  /* Perform Taylor series approximation with nineteen terms */
      +
      +  value = 0.0;
      +  x0 = 1.0;
      +  for (i = 0; i < 19; i++)
      +    {
      +      value += x0 * _dbl_inv_fact[i];
      +      x0 *= x;
      +    }
      +
      +  /* Multiply by exp of the integer component */
      +
      +  value *= lib_expi(int_part);
      +
      +  if (invert)
      +    {
      +      return (1.0 / value);
      +    }
      +  else
      +    {
      +      return value;
      +    }
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_expf.c b/nuttx/lib/math/lib_expf.c
      new file mode 100644
      index 0000000000..eac4641c67
      --- /dev/null
      +++ b/nuttx/lib/math/lib_expf.c
      @@ -0,0 +1,112 @@
      +/************************************************************************
      + * lib/math/lib_expf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/************************************************************************
      + * Private Data
      + ************************************************************************/
      +
      +static float _flt_inv_fact[] =
      +{
      +  1.0 / 1.0,                    // 1/0!
      +  1.0 / 1.0,                    // 1/1!
      +  1.0 / 2.0,                    // 1/2!
      +  1.0 / 6.0,                    // 1/3!
      +  1.0 / 24.0,                   // 1/4!
      +  1.0 / 120.0,                  // 1/5!
      +  1.0 / 720.0,                  // 1/6!
      +  1.0 / 5040.0,                 // 1/7!
      +  1.0 / 40320.0,                // 1/8!
      +  1.0 / 362880.0,               // 1/9!
      +  1.0 / 3628800.0,              // 1/10!
      +};
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float expf(float x)
      +{
      +  size_t int_part;
      +  bool invert;
      +  float value;
      +  float x0;
      +  size_t i;
      +
      +  if (x == 0)
      +    {
      +      return 1;
      +    }
      +  else if (x < 0)
      +    {
      +      invert = true;
      +      x = -x;
      +    }
      +  else
      +    {
      +      invert = false;
      +    }
      +
      +  /* Extract integer component */
      +
      +  int_part = (size_t) x;
      +
      +  /* set x to fractional component */
      +
      +  x -= (float)int_part;
      +
      +  /* Perform Taylor series approximation with eleven terms */
      +
      +  value = 0.0;
      +  x0 = 1.0;
      +  for (i = 0; i < 10; i++)
      +    {
      +      value += x0 * _flt_inv_fact[i];
      +      x0 *= x;
      +    }
      +
      +  /* Multiply by exp of the integer component */
      +
      +  value *= lib_expi(int_part);
      +
      +  if (invert)
      +    {
      +      return (1.0 / value);
      +    }
      +  else
      +    {
      +      return value;
      +    }
      +}
      diff --git a/nuttx/lib/math/lib_expl.c b/nuttx/lib/math/lib_expl.c
      new file mode 100644
      index 0000000000..053103c9bb
      --- /dev/null
      +++ b/nuttx/lib/math/lib_expl.c
      @@ -0,0 +1,126 @@
      +/************************************************************************
      + * lib/math/lib_expl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +
      +/************************************************************************
      + * Private Data
      + ************************************************************************/
      +
      +static long double _ldbl_inv_fact[] =
      +{
      +  1.0 / 1.0,                    // 1 / 0!
      +  1.0 / 1.0,                    // 1 / 1!
      +  1.0 / 2.0,                    // 1 / 2!
      +  1.0 / 6.0,                    // 1 / 3!
      +  1.0 / 24.0,                   // 1 / 4!
      +  1.0 / 120.0,                  // 1 / 5!
      +  1.0 / 720.0,                  // 1 / 6!
      +  1.0 / 5040.0,                 // 1 / 7!
      +  1.0 / 40320.0,                // 1 / 8!
      +  1.0 / 362880.0,               // 1 / 9!
      +  1.0 / 3628800.0,              // 1 / 10!
      +  1.0 / 39916800.0,             // 1 / 11!
      +  1.0 / 479001600.0,            // 1 / 12!
      +  1.0 / 6227020800.0,           // 1 / 13!
      +  1.0 / 87178291200.0,          // 1 / 14!
      +  1.0 / 1307674368000.0,        // 1 / 15!
      +  1.0 / 20922789888000.0,       // 1 / 16!
      +  1.0 / 355687428096000.0,      // 1 / 17!
      +  1.0 / 6402373705728000.0,     // 1 / 18!
      +};
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +long double expl(long double x)
      +{
      +  size_t int_part;
      +  bool invert;
      +  long double value;
      +  long double x0;
      +  size_t i;
      +
      +  if (x == 0)
      +    {
      +      return 1;
      +    }
      +  else if (x < 0)
      +    {
      +      invert = true;
      +      x = -x;
      +    }
      +  else
      +    {
      +      invert = false;
      +    }
      +
      +  /* Extract integer component */
      +
      +  int_part = (size_t) x;
      +
      +  /* Set x to fractional component */
      +
      +  x -= (long double)int_part;
      +
      +  /* Perform Taylor series approximation with nineteen terms */
      +
      +  value = 0.0;
      +  x0 = 1.0;
      +  for (i = 0; i < 19; i++)
      +    {
      +      value += x0 * _ldbl_inv_fact[i];
      +      x0 *= x;
      +    }
      +
      +  /* Multiply by exp of the integer component */
      +
      +  value *= lib_expi(int_part);
      +
      +  if (invert)
      +    {
      +      return (1.0 / value);
      +    }
      +  else
      +    {
      +      return value;
      +    }
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_fabs.c b/nuttx/lib/math/lib_fabs.c
      new file mode 100644
      index 0000000000..ff99ceb642
      --- /dev/null
      +++ b/nuttx/lib/math/lib_fabs.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_fabs.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double fabs(double x)
      +{
      +  return ((x < 0) ? -x : x);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_fabsf.c b/nuttx/lib/math/lib_fabsf.c
      new file mode 100644
      index 0000000000..0ea186ca03
      --- /dev/null
      +++ b/nuttx/lib/math/lib_fabsf.c
      @@ -0,0 +1,41 @@
      +/************************************************************************
      + * lib/math/lib_fabsf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float fabsf(float x)
      +{
      +  return ((x < 0) ? -x : x);
      +}
      diff --git a/nuttx/lib/math/lib_fabsl.c b/nuttx/lib/math/lib_fabsl.c
      new file mode 100644
      index 0000000000..5313d897da
      --- /dev/null
      +++ b/nuttx/lib/math/lib_fabsl.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_fabsl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double fabsl(long double x)
      +{
      +  return ((x < 0) ? -x : x);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_floor.c b/nuttx/lib/math/lib_floor.c
      new file mode 100644
      index 0000000000..f0c4477a04
      --- /dev/null
      +++ b/nuttx/lib/math/lib_floor.c
      @@ -0,0 +1,52 @@
      +/************************************************************************
      + * lib/math/lib_floor.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double floor(double x)
      +{
      +  modf(x, &x);
      +  if (x < 0.0)
      +    {
      +      x -= 1.0;
      +    }
      +
      +  return x;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_floorf.c b/nuttx/lib/math/lib_floorf.c
      new file mode 100644
      index 0000000000..2becb5fac9
      --- /dev/null
      +++ b/nuttx/lib/math/lib_floorf.c
      @@ -0,0 +1,47 @@
      +/************************************************************************
      + * lib/math/lib_floorf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float floorf(float x)
      +{
      +  modff(x, &x);
      +  if (x < 0.0)
      +    {
      +      x -= 1.0;
      +    }
      +
      +  return x;
      +}
      diff --git a/nuttx/lib/math/lib_floorl.c b/nuttx/lib/math/lib_floorl.c
      new file mode 100644
      index 0000000000..e38ce80ed3
      --- /dev/null
      +++ b/nuttx/lib/math/lib_floorl.c
      @@ -0,0 +1,52 @@
      +/************************************************************************
      + * lib/math/lib_floorl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double floorl(long double x)
      +{
      +  modfl(x, &x);
      +  if (x < 0.0)
      +    {
      +      x -= 1.0;
      +    }
      +
      +  return x;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_fmod.c b/nuttx/lib/math/lib_fmod.c
      new file mode 100644
      index 0000000000..939e7e18ad
      --- /dev/null
      +++ b/nuttx/lib/math/lib_fmod.c
      @@ -0,0 +1,52 @@
      +/************************************************************************
      + * lib/math/lib_fmod.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double fmod(double x, double div)
      +{
      +  double n0;
      +
      +  x /= div;
      +  x = modf(x, &n0);
      +  x *= div;
      +
      +  return x;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_fmodf.c b/nuttx/lib/math/lib_fmodf.c
      new file mode 100644
      index 0000000000..085786f172
      --- /dev/null
      +++ b/nuttx/lib/math/lib_fmodf.c
      @@ -0,0 +1,47 @@
      +/************************************************************************
      + * lib/math/lib_fmodf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float fmodf(float x, float div)
      +{
      +  float n0;
      +
      +  x /= div;
      +  x = modff(x, &n0);
      +  x *= div;
      +
      +  return x;
      +}
      diff --git a/nuttx/lib/math/lib_fmodl.c b/nuttx/lib/math/lib_fmodl.c
      new file mode 100644
      index 0000000000..51c5e95ec8
      --- /dev/null
      +++ b/nuttx/lib/math/lib_fmodl.c
      @@ -0,0 +1,52 @@
      +/************************************************************************
      + * lib/math/lib_fmodl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double fmodl(long double x, long double div)
      +{
      +  long double n0;
      +
      +  x /= div;
      +  x = modfl(x, &n0);
      +  x *= div;
      +
      +  return x;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_frexp.c b/nuttx/lib/math/lib_frexp.c
      new file mode 100644
      index 0000000000..56feee8639
      --- /dev/null
      +++ b/nuttx/lib/math/lib_frexp.c
      @@ -0,0 +1,47 @@
      +/************************************************************************
      + * lib/math/lib_frexp.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double frexp(double x, int *exponent)
      +{
      +  *exponent = (int)ceil(log2(x));
      +  return x / ldexp(1.0, *exponent);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_frexpf.c b/nuttx/lib/math/lib_frexpf.c
      new file mode 100644
      index 0000000000..1fb0df3d89
      --- /dev/null
      +++ b/nuttx/lib/math/lib_frexpf.c
      @@ -0,0 +1,42 @@
      +/************************************************************************
      + * lib/math/lib_frexpf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float frexpf(float x, int *exponent)
      +{
      +  *exponent = (int)ceilf(log2f(x));
      +  return x / ldexpf(1.0, *exponent);
      +}
      diff --git a/nuttx/lib/math/lib_frexpl.c b/nuttx/lib/math/lib_frexpl.c
      new file mode 100644
      index 0000000000..87708ad86c
      --- /dev/null
      +++ b/nuttx/lib/math/lib_frexpl.c
      @@ -0,0 +1,47 @@
      +/************************************************************************
      + * lib/math/lib_frexpl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double frexpl(long double x, int *exponent)
      +{
      +  *exponent = (int)ceill(log2(x));
      +  return x / ldexpl(1.0, *exponent);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_ldexp.c b/nuttx/lib/math/lib_ldexp.c
      new file mode 100644
      index 0000000000..4c7b2b721b
      --- /dev/null
      +++ b/nuttx/lib/math/lib_ldexp.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_ldexp.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double ldexp(double x, int n)
      +{
      +  return (x * pow(2.0, (double)n));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_ldexpf.c b/nuttx/lib/math/lib_ldexpf.c
      new file mode 100644
      index 0000000000..c61d633d5c
      --- /dev/null
      +++ b/nuttx/lib/math/lib_ldexpf.c
      @@ -0,0 +1,41 @@
      +/************************************************************************
      + * lib/math/lib_ldexpf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float ldexpf(float x, int n)
      +{
      +  return (x * powf(2.0, (float)n));
      +}
      diff --git a/nuttx/lib/math/lib_ldexpl.c b/nuttx/lib/math/lib_ldexpl.c
      new file mode 100644
      index 0000000000..b9a0f4a865
      --- /dev/null
      +++ b/nuttx/lib/math/lib_ldexpl.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_ldexpl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double ldexpl(long double x, int n)
      +{
      +  return (x * powl(2.0, (long double)n));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_libexpi.c b/nuttx/lib/math/lib_libexpi.c
      new file mode 100644
      index 0000000000..1ec947a71a
      --- /dev/null
      +++ b/nuttx/lib/math/lib_libexpi.c
      @@ -0,0 +1,103 @@
      +/************************************************************************
      + * lib/math/lib_libexpi.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Pre-processor Definitions
      + ************************************************************************/
      +
      +#define M_E2    (M_E * M_E)
      +#define M_E4    (M_E2 * M_E2)
      +#define M_E8    (M_E4 * M_E4)
      +#define M_E16   (M_E8 * M_E8)
      +#define M_E32   (M_E16 * M_E16)
      +#define M_E64   (M_E32 * M_E32)
      +#define M_E128  (M_E64 * M_E64)
      +#define M_E256  (M_E128 * M_E128)
      +#define M_E512  (M_E256 * M_E256)
      +#define M_E1024 (M_E512 * M_E512)
      +
      +/************************************************************************
      + * Private Data
      + ************************************************************************/
      +
      +static double _expi_square_tbl[11] =
      +{
      +  M_E,                          // e^1
      +  M_E2,                         // e^2
      +  M_E4,                         // e^4
      +  M_E8,                         // e^8
      +  M_E16,                        // e^16
      +  M_E32,                        // e^32
      +  M_E64,                        // e^64
      +  M_E128,                       // e^128
      +  M_E256,                       // e^256
      +  M_E512,                       // e^512
      +  M_E1024,                      // e^1024
      +};
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +double lib_expi(size_t n)
      +{
      +  size_t i;
      +  double val;
      +
      +  if (n > 1024)
      +    {
      +      return INFINITY;
      +    }
      +
      +  val = 1.0;
      +
      +  for (i = 0; n; i++)
      +    {
      +      if (n & (1 << i))
      +        {
      +          n   &= ~(1 << i);
      +          val *= _expi_square_tbl[i];
      +        }
      +    }
      +
      +  return val;
      +}
      +
      diff --git a/nuttx/lib/math/lib_libsqrtapprox.c b/nuttx/lib/math/lib_libsqrtapprox.c
      new file mode 100644
      index 0000000000..5c556c3a0e
      --- /dev/null
      +++ b/nuttx/lib/math/lib_libsqrtapprox.c
      @@ -0,0 +1,50 @@
      +/************************************************************************
      + * lib/math/lib_libsqrtapprox.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float lib_sqrtapprox(float x)
      +{
      +  int32_t i;
      +
      +  /* Floats + bit manipulation = +inf fun! */
      +
      +  i = *((int32_t *) & x);
      +  i = 0x1fc00000 + (i >> 1);
      +  x = *((float *)&i);
      +
      +  return x;
      +}
      diff --git a/nuttx/lib/math/lib_log.c b/nuttx/lib/math/lib_log.c
      new file mode 100644
      index 0000000000..1350ba4fea
      --- /dev/null
      +++ b/nuttx/lib/math/lib_log.c
      @@ -0,0 +1,82 @@
      +/************************************************************************
      + * lib/math/lib_log.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double log(double x)
      +{
      +  double y, y_old, ey, epsilon;
      +
      +  y = 0.0;
      +  y_old = 1.0;
      +  epsilon = DBL_EPSILON;
      +
      +  while (y > y_old + epsilon || y < y_old - epsilon)
      +    {
      +      y_old = y;
      +      ey = exp(y);
      +      y -= (ey - x) / ey;
      +
      +      if (y > 700.0)
      +        {
      +          y = 700.0;
      +        }
      +
      +      if (y < -700.0)
      +        {
      +          y = -700.0;
      +        }
      +
      +      epsilon = (fabs(y) > 1.0) ? fabs(y) * DBL_EPSILON : DBL_EPSILON;
      +    }
      +
      +  if (y == 700.0)
      +    {
      +      return INFINITY;
      +    }
      +
      +  if (y == -700.0)
      +    {
      +      return INFINITY;
      +    }
      +
      +  return y;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_log10.c b/nuttx/lib/math/lib_log10.c
      new file mode 100644
      index 0000000000..47854fca44
      --- /dev/null
      +++ b/nuttx/lib/math/lib_log10.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_log10.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double log10(double x)
      +{
      +  return (log(x) / M_LN10);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_log10f.c b/nuttx/lib/math/lib_log10f.c
      new file mode 100644
      index 0000000000..651071920f
      --- /dev/null
      +++ b/nuttx/lib/math/lib_log10f.c
      @@ -0,0 +1,41 @@
      +/************************************************************************
      + * lib/math/lib_log10f.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float log10f(float x)
      +{
      +  return (logf(x) / M_LN10);
      +}
      diff --git a/nuttx/lib/math/lib_log10l.c b/nuttx/lib/math/lib_log10l.c
      new file mode 100644
      index 0000000000..65892262a8
      --- /dev/null
      +++ b/nuttx/lib/math/lib_log10l.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_log10l.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double log10l(long double x)
      +{
      +  return (logl(x) / M_LN10);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_log2.c b/nuttx/lib/math/lib_log2.c
      new file mode 100644
      index 0000000000..0aa1e80101
      --- /dev/null
      +++ b/nuttx/lib/math/lib_log2.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_log2.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double log2(double x)
      +{
      +  return (log(x) / M_LN2);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_log2f.c b/nuttx/lib/math/lib_log2f.c
      new file mode 100644
      index 0000000000..e160ca59e3
      --- /dev/null
      +++ b/nuttx/lib/math/lib_log2f.c
      @@ -0,0 +1,41 @@
      +/************************************************************************
      + * lib/math/lib_log2f.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float log2f(float x)
      +{
      +  return (logf(x) / M_LN2);
      +}
      diff --git a/nuttx/lib/math/lib_log2l.c b/nuttx/lib/math/lib_log2l.c
      new file mode 100644
      index 0000000000..21d26d4d7b
      --- /dev/null
      +++ b/nuttx/lib/math/lib_log2l.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_log2l.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double log2l(long double x)
      +{
      +  return (logl(x) / M_LN2);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_logf.c b/nuttx/lib/math/lib_logf.c
      new file mode 100644
      index 0000000000..1d31aa0c0b
      --- /dev/null
      +++ b/nuttx/lib/math/lib_logf.c
      @@ -0,0 +1,77 @@
      +/************************************************************************
      + * lib/math/lib_logf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float logf(float x)
      +{
      +  float y, y_old, ey, epsilon;
      +
      +  y = 0.0;
      +  y_old = 1.0;
      +  epsilon = FLT_EPSILON;
      +
      +  while (y > y_old + epsilon || y < y_old - epsilon)
      +    {
      +      y_old = y;
      +      ey = exp(y);
      +      y -= (ey - x) / ey;
      +
      +      if (y > 700.0)
      +        {
      +          y = 700.0;
      +        }
      +
      +      if (y < -700.0)
      +        {
      +          y = -700.0;
      +        }
      +
      +      epsilon = (fabs(y) > 1.0) ? fabs(y) * FLT_EPSILON : FLT_EPSILON;
      +    }
      +
      +  if (y == 700.0)
      +    {
      +      return INFINITY;
      +    }
      +
      +  if (y == -700.0)
      +    {
      +      return INFINITY;
      +    }
      +
      +  return y;
      +}
      diff --git a/nuttx/lib/math/lib_logl.c b/nuttx/lib/math/lib_logl.c
      new file mode 100644
      index 0000000000..577f9cee2e
      --- /dev/null
      +++ b/nuttx/lib/math/lib_logl.c
      @@ -0,0 +1,80 @@
      +/************************************************************************
      + * lib/math/lib_lol.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double logl(long double x)
      +{
      +  long double y, y_old, ey, epsilon;
      +
      +  y = 0.0;
      +  y_old = 1.0;
      +  epsilon = LDBL_EPSILON;
      +
      +  while (y > y_old + epsilon || y < y_old - epsilon)
      +    {
      +      y_old = y;
      +      ey = expl(y);
      +      y -= (ey - x) / ey;
      +
      +      if (y > 700.0)
      +        {
      +          y = 700.0;
      +        }
      +
      +      if (y < -700.0)
      +        {
      +          y = -700.0;
      +        }
      +    }
      +
      +  if (y == 700.0)
      +    {
      +      return INFINITY;
      +    }
      +
      +  if (y == -700.0)
      +    {
      +      return INFINITY;
      +    }
      +
      +  return y;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_modf.c b/nuttx/lib/math/lib_modf.c
      new file mode 100644
      index 0000000000..9dc6284c20
      --- /dev/null
      +++ b/nuttx/lib/math/lib_modf.c
      @@ -0,0 +1,58 @@
      +/************************************************************************
      + * lib/math/lib_modf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double modf(double x, double *iptr)
      +{
      +  if (fabs(x) >= 4503599627370496.0)
      +    {
      +      *iptr = x;
      +      return 0.0;
      +    }
      +  else if (fabs(x) < 1.0)
      +    {
      +      *iptr = 0.0;
      +      return x;
      +    }
      +  else
      +    {
      +      *iptr = (double)(int64_t) x;
      +      return (x - *iptr);
      +    }
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_modff.c b/nuttx/lib/math/lib_modff.c
      new file mode 100644
      index 0000000000..4eec2ae17f
      --- /dev/null
      +++ b/nuttx/lib/math/lib_modff.c
      @@ -0,0 +1,55 @@
      +/************************************************************************
      + * lib/math/lib_modff.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float modff(float x, float *iptr)
      +{
      +  if (fabsf(x) >= 8388608.0)
      +    {
      +      *iptr = x;
      +      return 0.0;
      +    }
      +  else if (fabs(x) < 1.0)
      +    {
      +      *iptr = 0.0;
      +      return x;
      +    }
      +  else
      +    {
      +      *iptr = (float)(int)x;
      +      return (x - *iptr);
      +    }
      +}
      diff --git a/nuttx/lib/math/lib_modfl.c b/nuttx/lib/math/lib_modfl.c
      new file mode 100644
      index 0000000000..3b04571f3a
      --- /dev/null
      +++ b/nuttx/lib/math/lib_modfl.c
      @@ -0,0 +1,61 @@
      +/************************************************************************
      + * lib/math/lib_modfl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double modfl(long double x, long double *iptr)
      +{
      +  if (fabs(x) >= 4503599627370496.0)
      +    {
      +      *iptr = x;
      +      return 0.0;
      +    }
      +  else if (fabs(x) < 1.0)
      +    {
      +      *iptr = 0.0;
      +      return x;
      +    }
      +  else
      +    {
      +      *iptr = (long double)(int64_t) x;
      +      return (x - *iptr);
      +    }
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_pow.c b/nuttx/lib/math/lib_pow.c
      new file mode 100644
      index 0000000000..af0a55d32f
      --- /dev/null
      +++ b/nuttx/lib/math/lib_pow.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_pow.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double pow(double b, double e)
      +{
      +  return exp(e * log(b));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_powf.c b/nuttx/lib/math/lib_powf.c
      new file mode 100644
      index 0000000000..a43f9cf82a
      --- /dev/null
      +++ b/nuttx/lib/math/lib_powf.c
      @@ -0,0 +1,41 @@
      +/************************************************************************
      + * lib/math/lib_powf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float powf(float b, float e)
      +{
      +  return expf(e * logf(b));
      +}
      diff --git a/nuttx/lib/math/lib_powl.c b/nuttx/lib/math/lib_powl.c
      new file mode 100644
      index 0000000000..f5fbf042e9
      --- /dev/null
      +++ b/nuttx/lib/math/lib_powl.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_powl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double powl(long double b, long double e)
      +{
      +  return expl(e * logl(b));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_sin.c b/nuttx/lib/math/lib_sin.c
      new file mode 100644
      index 0000000000..c04d6b88b9
      --- /dev/null
      +++ b/nuttx/lib/math/lib_sin.c
      @@ -0,0 +1,114 @@
      +/************************************************************************
      + * lib/math/lib_sin.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +
      +/************************************************************************
      + * Private Data
      + ************************************************************************/
      +
      +static double _dbl_inv_fact[] =
      +{
      +  1.0 / 1.0,                    // 1 / 1!
      +  1.0 / 6.0,                    // 1 / 3!
      +  1.0 / 120.0,                  // 1 / 5!
      +  1.0 / 5040.0,                 // 1 / 7!
      +  1.0 / 362880.0,               // 1 / 9!
      +  1.0 / 39916800.0,             // 1 / 11!
      +  1.0 / 6227020800.0,           // 1 / 13!
      +  1.0 / 1307674368000.0,        // 1 / 15!
      +  1.0 / 355687428096000.0,      // 1 / 17!
      +  1.0 / 121645100408832000.0,   // 1 / 19!
      +};
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +double sin(double x)
      +{
      +  double x_squared;
      +  double sin_x;
      +  size_t i;
      +
      +  /* Move x to [-pi, pi) */
      +
      +  x = fmod(x, 2 * M_PI);
      +  if (x >= M_PI)
      +    {
      +      x -= 2 * M_PI;
      +    }
      +
      +  if (x < -M_PI)
      +    {
      +      x += 2 * M_PI;
      +    }
      +
      +  /* Move x to [-pi/2, pi/2) */
      +
      +  if (x >= M_PI_2)
      +    {
      +      x = M_PI - x;
      +    }
      +
      +  if (x < -M_PI_2)
      +    {
      +      x = -M_PI - x;
      +    }
      +
      +  x_squared = x * x;
      +  sin_x = 0.0;
      +
      +  /* Perform Taylor series approximation for sin(x) with ten terms */
      +
      +  for (i = 0; i < 10; i++)
      +    {
      +      if (i % 2 == 0)
      +        {
      +          sin_x += x * _dbl_inv_fact[i];
      +        }
      +      else
      +        {
      +          sin_x -= x * _dbl_inv_fact[i];
      +        }
      +
      +      x *= x_squared;
      +    }
      +
      +  return sin_x;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_sinf.c b/nuttx/lib/math/lib_sinf.c
      new file mode 100644
      index 0000000000..e298bbba49
      --- /dev/null
      +++ b/nuttx/lib/math/lib_sinf.c
      @@ -0,0 +1,104 @@
      +/************************************************************************
      + * lib/math/lib_sinf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Private Data
      + ************************************************************************/
      +
      +static float _flt_inv_fact[] =
      +{
      +  1.0 / 1.0,                    // 1 / 1!
      +  1.0 / 6.0,                    // 1 / 3!
      +  1.0 / 120.0,                  // 1 / 5!
      +  1.0 / 5040.0,                 // 1 / 7!
      +  1.0 / 362880.0,               // 1 / 9!
      +  1.0 / 39916800.0,             // 1 / 11!
      +};
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float sinf(float x)
      +{
      +  float x_squared;
      +  float sin_x;
      +  size_t i;
      +
      +  /* Move x to [-pi, pi) */
      +
      +  x = fmodf(x, 2 * M_PI);
      +  if (x >= M_PI)
      +    {
      +      x -= 2 * M_PI;
      +    }
      +
      +  if (x < -M_PI)
      +    {
      +      x += 2 * M_PI;
      +    }
      +
      +  /* Move x to [-pi/2, pi/2) */
      +
      +  if (x >= M_PI_2)
      +    {
      +      x = M_PI - x;
      +    }
      +
      +  if (x < -M_PI_2)
      +    {
      +      x = -M_PI - x;
      +    }
      +
      +  x_squared = x * x;
      +  sin_x = 0.0;
      +
      +  /* Perform Taylor series approximation for sin(x) with six terms */
      +
      +  for (i = 0; i < 6; i++)
      +    {
      +      if (i % 2 == 0)
      +        {
      +          sin_x += x * _flt_inv_fact[i];
      +        }
      +      else
      +        {
      +          sin_x -= x * _flt_inv_fact[i];
      +        }
      +
      +      x *= x_squared;
      +    }
      +
      +  return sin_x;
      +}
      diff --git a/nuttx/lib/math/lib_sinh.c b/nuttx/lib/math/lib_sinh.c
      new file mode 100644
      index 0000000000..f33852433b
      --- /dev/null
      +++ b/nuttx/lib/math/lib_sinh.c
      @@ -0,0 +1,47 @@
      +/************************************************************************
      + * lib/math/lib_sinh.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double sinh(double x)
      +{
      +  x = exp(x);
      +  return ((x - (1.0 / x)) / 2.0);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_sinhf.c b/nuttx/lib/math/lib_sinhf.c
      new file mode 100644
      index 0000000000..e15cb14dc4
      --- /dev/null
      +++ b/nuttx/lib/math/lib_sinhf.c
      @@ -0,0 +1,42 @@
      +/************************************************************************
      + * lib/math/lib_sinhf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float sinhf(float x)
      +{
      +  x = expf(x);
      +  return ((x - (1.0 / x)) / 2.0);
      +}
      diff --git a/nuttx/lib/math/lib_sinhl.c b/nuttx/lib/math/lib_sinhl.c
      new file mode 100644
      index 0000000000..b0fea29149
      --- /dev/null
      +++ b/nuttx/lib/math/lib_sinhl.c
      @@ -0,0 +1,47 @@
      +/************************************************************************
      + * lib/math/lib_sinhl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double sinhl(long double x)
      +{
      +  x = expl(x);
      +  return ((x - (1.0 / x)) / 2.0);
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_sinl.c b/nuttx/lib/math/lib_sinl.c
      new file mode 100644
      index 0000000000..a69b548cb3
      --- /dev/null
      +++ b/nuttx/lib/math/lib_sinl.c
      @@ -0,0 +1,114 @@
      +/************************************************************************
      + * lib/math/lib_sinl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +
      +/************************************************************************
      + * Private Data
      + ************************************************************************/
      +
      +static long double _ldbl_inv_fact[] =
      +{
      +  1.0 / 1.0,                    // 1 / 1!
      +  1.0 / 6.0,                    // 1 / 3!
      +  1.0 / 120.0,                  // 1 / 5!
      +  1.0 / 5040.0,                 // 1 / 7!
      +  1.0 / 362880.0,               // 1 / 9!
      +  1.0 / 39916800.0,             // 1 / 11!
      +  1.0 / 6227020800.0,           // 1 / 13!
      +  1.0 / 1307674368000.0,        // 1 / 15!
      +  1.0 / 355687428096000.0,      // 1 / 17!
      +  1.0 / 121645100408832000.0,   // 1 / 19!
      +};
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +long double sinl(long double x)
      +{
      +  long double x_squared;
      +  long double sin_x;
      +  size_t i;
      +
      +  /* Move x to [-pi, pi) */
      +
      +  x = fmodl(x, 2 * M_PI);
      +  if (x >= M_PI)
      +    {
      +      x -= 2 * M_PI;
      +    }
      +
      +  if (x < -M_PI)
      +    {
      +      x += 2 * M_PI;
      +    }
      +
      +  /* Move x to [-pi/2, pi/2) */
      +
      +  if (x >= M_PI_2)
      +    {
      +      x = M_PI - x;
      +    }
      +
      +  if (x < -M_PI_2)
      +    {
      +      x = -M_PI - x;
      +    }
      +
      +  x_squared = x * x;
      +  sin_x = 0.0;
      +
      +  /* Perform Taylor series approximation for sin(x) with ten terms */
      +
      +  for (i = 0; i < 10; i++)
      +    {
      +      if (i % 2 == 0)
      +        {
      +          sin_x += x * _ldbl_inv_fact[i];
      +        }
      +      else
      +        {
      +          sin_x -= x * _ldbl_inv_fact[i];
      +        }
      +
      +      x *= x_squared;
      +    }
      +
      +  return sin_x;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_sqrt.c b/nuttx/lib/math/lib_sqrt.c
      new file mode 100644
      index 0000000000..d77997f7cd
      --- /dev/null
      +++ b/nuttx/lib/math/lib_sqrt.c
      @@ -0,0 +1,99 @@
      +/************************************************************************
      + * lib/math/lib_sqrt.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double sqrt(double x)
      +{
      +  long double y, y1;
      +
      +  if (x < 0.0)
      +    {
      +      errno = EDOM;
      +      return NAN;
      +    }
      +
      +  if (isnan(x))
      +    {
      +      return NAN;
      +    }
      +
      +  if (isinf(x))
      +    {
      +      return INFINITY;
      +    }
      +
      +  if (x == 0.0)
      +    {
      +      return 0.0;
      +    }
      +
      +  /* Guess square root (using bit manipulation) */
      +
      +  y = lib_sqrtapprox(x);
      +
      +  /* Perform four iterations of approximation.  This number (4) is
      +   * definitely optimal
      +   */
      +
      +  y = 0.5 * (y + x / y);
      +  y = 0.5 * (y + x / y);
      +  y = 0.5 * (y + x / y);
      +  y = 0.5 * (y + x / y);
      +
      +  /* If guess was terribe (out of range of float).  Repeat approximation
      +   * until convergence.
      +   */
      +
      +  if (y * y < x - 1.0 || y * y > x + 1.0)
      +    {
      +      y1 = -1.0;
      +      while (y != y1)
      +        {
      +          y1 = y;
      +          y = 0.5 * (y + x / y);
      +        }
      +    }
      +
      +  return y;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_sqrtf.c b/nuttx/lib/math/lib_sqrtf.c
      new file mode 100644
      index 0000000000..81817a0406
      --- /dev/null
      +++ b/nuttx/lib/math/lib_sqrtf.c
      @@ -0,0 +1,84 @@
      +/************************************************************************
      + * lib/math/lib_sqrtf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float sqrtf(float x)
      +{
      +  float y;
      +
      +  /* Filter out invalid/trivial inputs */
      +
      +  if (x < 0.0)
      +    {
      +      errno = EDOM;
      +      return NAN;
      +    }
      +
      +  if (isnan(x))
      +    {
      +      return NAN;
      +    }
      +
      +  if (isinf(x))
      +    {
      +      return INFINITY;
      +    }
      +
      +  if (x == 0.0)
      +    {
      +      return 0.0;
      +    }
      +
      +  /* Guess square root (using bit manipulation) */
      +
      +  y = lib_sqrtapprox(x);
      +
      +  /* Perform three iterations of approximation. This number (3) is
      +   * definitely optimal
      +   */
      +
      +  y = 0.5 * (y + x / y);
      +  y = 0.5 * (y + x / y);
      +  y = 0.5 * (y + x / y);
      +
      +  return y;
      +}
      diff --git a/nuttx/lib/math/lib_sqrtl.c b/nuttx/lib/math/lib_sqrtl.c
      new file mode 100644
      index 0000000000..6674fe50f8
      --- /dev/null
      +++ b/nuttx/lib/math/lib_sqrtl.c
      @@ -0,0 +1,101 @@
      +/************************************************************************
      + * lib/math/lib_sqrtl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009-2011 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double sqrtl(long double x)
      +{
      +  long double y, y1;
      +
      +  /* Filter out invalid/trivial inputs */
      +
      +  if (x < 0.0)
      +    {
      +      errno = EDOM;
      +      return NAN;
      +    }
      +
      +  if (isnan(x))
      +    {
      +    return NAN;
      +    }
      +
      +  if (isinf(x))
      +    {
      +    return INFINITY;
      +    }
      +
      +  if (x == 0.0)
      +    {
      +    return 0.0;
      +    }
      +
      +  /* Guess square root (using bit manipulation) */
      +
      +  y = lib_sqrtapprox(x);
      +
      +  /* Perform four iterations of approximation.  This number (4) is
      +   * definitely optimal
      +   */
      +
      +  y = 0.5 * (y + x / y);
      +  y = 0.5 * (y + x / y);
      +  y = 0.5 * (y + x / y);
      +  y = 0.5 * (y + x / y);
      +
      +  /* If guess was terribe (out of range of float).  Repeat approximation
      +   * until convergence
      +   */
      +
      +  if (y * y < x - 1.0 || y * y > x + 1.0)
      +    {
      +      y1 = -1.0;
      +      while (y != y1)
      +        {
      +          y1 = y;
      +          y = 0.5 * (y + x / y);
      +        }
      +    }
      +
      +  return y;
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_tan.c b/nuttx/lib/math/lib_tan.c
      new file mode 100644
      index 0000000000..bce14b3270
      --- /dev/null
      +++ b/nuttx/lib/math/lib_tan.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_tan.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double tan(double x)
      +{
      +  return (sin(x) / cos(x));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_tanf.c b/nuttx/lib/math/lib_tanf.c
      new file mode 100644
      index 0000000000..3db3bda265
      --- /dev/null
      +++ b/nuttx/lib/math/lib_tanf.c
      @@ -0,0 +1,41 @@
      +/************************************************************************
      + * lib/math/lib_tanf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float tanf(float x)
      +{
      +  return (sinf(x) / cosf(x));
      +}
      diff --git a/nuttx/lib/math/lib_tanh.c b/nuttx/lib/math/lib_tanh.c
      new file mode 100644
      index 0000000000..46fddd06df
      --- /dev/null
      +++ b/nuttx/lib/math/lib_tanh.c
      @@ -0,0 +1,49 @@
      +/************************************************************************
      + * lib/math/lib_tanh.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +double tanh(double x)
      +{
      +  double x0 = exp(x);
      +  double x1 = 1.0 / x0;
      +
      +  return ((x0 + x1) / (x0 - x1));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_tanhf.c b/nuttx/lib/math/lib_tanhf.c
      new file mode 100644
      index 0000000000..94d15cc60d
      --- /dev/null
      +++ b/nuttx/lib/math/lib_tanhf.c
      @@ -0,0 +1,44 @@
      +/************************************************************************
      + * lib/math/lib_tanhf.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +float tanhf(float x)
      +{
      +  float x0 = expf(x);
      +  float x1 = 1.0 / x0;
      +
      +  return ((x0 + x1) / (x0 - x1));
      +}
      diff --git a/nuttx/lib/math/lib_tanhl.c b/nuttx/lib/math/lib_tanhl.c
      new file mode 100644
      index 0000000000..23c11d6672
      --- /dev/null
      +++ b/nuttx/lib/math/lib_tanhl.c
      @@ -0,0 +1,49 @@
      +/************************************************************************
      + * lib/math/lib_tanhl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double tanhl(long double x)
      +{
      +  long double x0 = exp(x);
      +  long double x1 = 1.0 / x0;
      +
      +  return ((x0 + x1) / (x0 - x1));
      +}
      +#endif
      diff --git a/nuttx/lib/math/lib_tanl.c b/nuttx/lib/math/lib_tanl.c
      new file mode 100644
      index 0000000000..4973aa073c
      --- /dev/null
      +++ b/nuttx/lib/math/lib_tanl.c
      @@ -0,0 +1,46 @@
      +/************************************************************************
      + * lib/math/lib_tanl.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Ported by: Darcy Gong
      + *
      + * It derives from the Rhombs OS math library by Nick Johnson which has
      + * a compatibile, MIT-style license:
      + *
      + * Copyright (C) 2009, 2010 Nick Johnson 
      + * 
      + * Permission to use, copy, modify, and distribute this software for any
      + * purpose with or without fee is hereby granted, provided that the above
      + * copyright notice and this permission notice appear in all copies.
      + * 
      + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
      + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
      + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
      + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
      + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
      + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
      + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_DOUBLE
      +long double tanl(long double x)
      +{
      +  return (sinl(x) / cosl(x));
      +}
      +#endif
      diff --git a/nuttx/lib/misc/Make.defs b/nuttx/lib/misc/Make.defs
      new file mode 100644
      index 0000000000..c12533f754
      --- /dev/null
      +++ b/nuttx/lib/misc/Make.defs
      @@ -0,0 +1,69 @@
      +############################################################################
      +# lib/misc/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the internal C files to the build
      +
      +CSRCS += lib_init.c lib_filesem.c
      +
      +# Add C files that depend on file OR socket descriptors
      +
      +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
      +
      +CSRCS += lib_sendfile.c
      +ifneq ($(CONFIG_NFILE_STREAMS),0)
      +CSRCS += lib_streamsem.c
      +endif
      +
      +else
      +ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0)
      +
      +CSRCS += lib_sendfile.c
      +ifneq ($(CONFIG_NFILE_STREAMS),0)
      +CSRCS += lib_streamsem.c
      +endif
      +
      +endif
      +endif
      +
      +# Add the miscellaneous C files to the build
      +
      +CSRCS += lib_match.c
      +CSRCS += lib_crc32.c
      +CSRCS += lib_dbg.c lib_dumpbuffer.c
      +
      +# Add the misc directory to the build
      +
      +DEPPATH += --dep-path misc
      +VPATH += :misc
      diff --git a/nuttx/lib/misc/lib_crc32.c b/nuttx/lib/misc/lib_crc32.c
      new file mode 100644
      index 0000000000..f851598e01
      --- /dev/null
      +++ b/nuttx/lib/misc/lib_crc32.c
      @@ -0,0 +1,123 @@
      +/************************************************************************************************
      + * lib/misc/lib_crc32.c
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
      + *
      + * The logic in this file was developed by Gary S. Brown:
      + *
      + *   COPYRIGHT (C) 1986 Gary S. Brown.  You may use this program, or code or tables
      + *   extracted from it, as desired without restriction.
      + *
      + * First, the polynomial itself and its table of feedback terms.  The polynomial is:
      + *
      + *    X^32+X^26+X^23+X^22+X^16+X^12+X^11+X^10+X^8+X^7+X^5+X^4+X^2+X^1+X^0
      + *
      + * Note that we take it "backwards" and put the highest-order term in the lowest-order bit.
      + * The X^32 term is "implied"; the LSB is the X^31 term, etc.  The X^0 term (usually shown
      + * as "+1") results in the MSB being 1
      + *
      + * Note that the usual hardware shift register implementation, which is what we're using
      + * (we're merely optimizing it by doing eight-bit chunks at a time) shifts bits into the
      + * lowest-order term.  In our implementation, that means shifting towards the right.  Why
      + * do we do it this way?  Because the calculated CRC must be transmitted in order from
      + * highest-order term to lowest-order term.  UARTs transmit characters in order from LSB
      + * to MSB.  By storing the CRC this way we hand it to the UART in the order low-byte to
      + * high-byte; the UART sends each low-bit to hight-bit; and the result is transmission bit
      + * by bit from highest- to lowest-order term without requiring any bit shuffling on our
      + * part.  Reception works similarly
      + *
      + * The feedback terms table consists of 256, 32-bit entries.  Notes
      + *
      + * - The table can be generated at runtime if desired; code to do so is shown later.  It
      + *   might not be obvious, but the feedback terms simply represent the results of eight
      + *   shift/xor operations for all combinations of data and CRC register values
      + *
      + * - The values must be right-shifted by eight bits by the updcrc logic; the shift must
      + *   be u_(bring in zeroes).  On some hardware you could probably optimize the shift in
      + *   assembler by using byte-swap instructions polynomial $edb88320
      +  ************************************************************************************************/
      +
      +/************************************************************************************************
      + * Included Files
      + ************************************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************************************************
      + * Private Data
      + ************************************************************************************************/
      + 
      +static const uint32_t crc32_tab[] =
      +{
      +  0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
      +  0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
      +  0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
      +  0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
      +  0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
      +  0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
      +  0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
      +  0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
      +  0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
      +  0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
      +  0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
      +  0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
      +  0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
      +  0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
      +  0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
      +  0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
      +  0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
      +  0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
      +  0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
      +  0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
      +  0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
      +  0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
      +  0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
      +  0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
      +  0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
      +  0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
      +  0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
      +  0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
      +  0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
      +  0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
      +  0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
      +  0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
      +};
      +
      +/************************************************************************************************
      + * Public Functions
      + ************************************************************************************************/
      +/************************************************************************************************
      + * Name: crc32part
      + *
      + * Description:
      + *   Continue CRC calculation on a part of the buffer.
      + *
      + ************************************************************************************************/
      +
      +uint32_t crc32part(FAR const uint8_t *src, size_t len, uint32_t crc32val)
      +{
      +  size_t i;
      +
      +  for (i = 0;  i < len;  i++)
      +    {
      +      crc32val = crc32_tab[(crc32val ^ src[i]) & 0xff] ^ (crc32val >> 8);
      +    }
      +  return crc32val;
      +}
      +
      +/************************************************************************************************
      + * Name: crc32
      + *
      + * Description:
      + *   Return a 32-bit CRC of the contents of the 'src' buffer, length 'len'
      + *
      + ************************************************************************************************/
      +
      +uint32_t crc32(FAR const uint8_t *src, size_t len)
      +{
      +  return crc32part(src, len, 0);
      +}
      diff --git a/nuttx/lib/misc/lib_dbg.c b/nuttx/lib/misc/lib_dbg.c
      new file mode 100644
      index 0000000000..aacdaa30a9
      --- /dev/null
      +++ b/nuttx/lib/misc/lib_dbg.c
      @@ -0,0 +1,165 @@
      +/****************************************************************************
      + * lib/misc/lib_dbg.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/* Debug output is initially disabled */
      +
      +#ifdef CONFIG_DEBUG_ENABLE
      +bool g_dbgenable;
      +#endif
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: dbg_enable
      + *
      + * Description:
      + *  Enable or disable debug output.
      + *
      + ****************************************************************************/
      +
      +#ifdef CONFIG_DEBUG_ENABLE
      +void dbg_enable(bool enable)
      +{
      +  g_dbgenable = enable;
      +}
      +#endif
      +
      +/****************************************************************************
      + * Name: dbg, lldbg, vdbg
      + *
      + * Description:
      + *  If the cross-compiler's pre-processor does not support variable
      + * length arguments, then these additional APIs will be built.
      + *
      + ****************************************************************************/
      +
      +#ifndef CONFIG_CPP_HAVE_VARARGS
      +#ifdef CONFIG_DEBUG
      +int dbg(const char *format, ...)
      +{
      +  va_list ap;
      +  int     ret;
      +
      +#ifdef CONFIG_DEBUG_ENABLE
      +  ret = 0;
      +  if (g_dbgenable)
      +#endif
      +    {
      +      va_start(ap, format);
      +      ret = lib_rawvprintf(format, ap);
      +      va_end(ap);
      +    }
      +
      +  return ret;
      +}
      +
      +#ifdef CONFIG_ARCH_LOWPUTC
      +int lldbg(const char *format, ...)
      +{
      +  va_list ap;
      +  int     ret;
      +
      +#ifdef CONFIG_DEBUG_ENABLE
      +  ret = 0;
      +  if (g_dbgenable)
      +#endif
      +    {
      +      va_start(ap, format);
      +      ret = lib_lowvprintf(format, ap);
      +      va_end(ap);
      +    }
      +
      +  return ret;
      +}
      +#endif
      +
      +#ifdef CONFIG_DEBUG_VERBOSE
      +int vdbg(const char *format, ...)
      +{
      +  va_list ap;
      +  int     ret;
      +
      +#ifdef CONFIG_DEBUG_ENABLE
      +  ret = 0;
      +  if (g_dbgenable)
      +#endif
      +    {
      +      va_start(ap, format);
      +      ret = lib_rawvprintf(format, ap);
      +      va_end(ap);
      +    }
      +
      +  return ret;
      +}
      +
      +#ifdef CONFIG_ARCH_LOWPUTC
      +int llvdbg(const char *format, ...)
      +{
      +  va_list ap;
      +  int     ret;
      +
      +#ifdef CONFIG_DEBUG_ENABLE
      +  ret = 0;
      +  if (g_dbgenable)
      +#endif
      +    {
      +      va_start(ap, format);
      +      ret = lib_lowvprintf(format, ap);
      +      va_end(ap);
      +    }
      +
      +  return ret;
      +}
      +#endif /* CONFIG_ARCH_LOWPUTC */
      +#endif /* CONFIG_DEBUG_VERBOSE */
      +#endif /* CONFIG_DEBUG */
      +#endif /* CONFIG_CPP_HAVE_VARARGS */
      diff --git a/nuttx/lib/misc/lib_dumpbuffer.c b/nuttx/lib/misc/lib_dumpbuffer.c
      new file mode 100644
      index 0000000000..155468ca12
      --- /dev/null
      +++ b/nuttx/lib/misc/lib_dumpbuffer.c
      @@ -0,0 +1,129 @@
      +/****************************************************************************
      + * lib/misc/lib_dumpbuffer.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor definitions
      + ****************************************************************************/
      +
      +/* Select the lowest level debug interface available */
      +
      +#ifdef CONFIG_CPP_HAVE_VARARGS
      +#  ifdef CONFIG_ARCH_LOWPUTC
      +#    define message(format, arg...) lib_lowprintf(format, ##arg)
      +#  else
      +#    define message(format, arg...) lib_rawprintf(format, ##arg)
      +#  endif
      +#else
      +#  ifdef CONFIG_ARCH_LOWPUTC
      +#    define message lib_lowprintf
      +#  else
      +#    define message lib_rawprintf
      +#  endif
      +#endif
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_dumpbuffer
      + *
      + * Description:
      + *  Do a pretty buffer dump
      + *
      + ****************************************************************************/
      +
      +void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer, unsigned int buflen)
      +{
      +  int i, j, k;
      +
      +  message("%s (%p):\n", msg, buffer);
      +  for (i = 0; i < buflen; i += 32)
      +    {
      +      message("%04x: ", i);
      +      for (j = 0; j < 32; j++)
      +        {
      +          k = i + j;
      +
      +          if (j == 16)
      +            {
      +              message(" ");
      +            }
      +
      +          if (k < buflen)
      +            {
      +              message("%02x", buffer[k]);
      +            }
      +          else
      +            {
      +              message("  ");
      +            }
      +        }
      +
      +      message(" ");
      +      for (j = 0; j < 32; j++)
      +        {
      +         k = i + j;
      +
      +          if (j == 16)
      +            {
      +              message(" ");
      +            }
      +
      +          if (k < buflen)
      +            {
      +              if (buffer[k] >= 0x20 && buffer[k] < 0x7f)
      +                {
      +                  message("%c", buffer[k]);
      +                }
      +              else
      +                {
      +                  message(".");
      +                }
      +            }
      +        }
      +      message("\n");
      +   }
      +}
      diff --git a/nuttx/lib/misc/lib_filesem.c b/nuttx/lib/misc/lib_filesem.c
      new file mode 100644
      index 0000000000..1d1f25c2fd
      --- /dev/null
      +++ b/nuttx/lib/misc/lib_filesem.c
      @@ -0,0 +1,145 @@
      +/************************************************************************
      + * lib/misc/lib_filesem.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +
      +/************************************************************************
      + * Pre-processor Definitions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Data
      + ************************************************************************/
      +
      +/************************************************************************
      + * Global Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * lib_sem_initialize
      + ************************************************************************/
      +
      +void lib_sem_initialize(FAR struct file_struct *stream)
      +{
      +  /* Initialize the LIB semaphore to one (to support one-at-
      +   * a-time access to private data sets.
      +   */
      +
      +  (void)sem_init(&stream->fs_sem, 0, 1);
      +
      +  stream->fs_holder = -1;
      +  stream->fs_counts = 0;
      +}
      +
      +/************************************************************************
      + * lib_take_semaphore
      + ************************************************************************/
      +
      +void lib_take_semaphore(FAR struct file_struct *stream)
      +{
      +  pid_t my_pid = getpid();
      +
      +  /* Do I already have the semaphore? */
      +
      +  if (stream->fs_holder == my_pid)
      +    {
      +      /* Yes, just increment the number of references that I have */
      +
      +      stream->fs_counts++;
      +    }
      +  else
      +    {
      +      /* Take the semaphore (perhaps waiting) */
      +
      +      while (sem_wait(&stream->fs_sem) != 0)
      +	{
      +	  /* The only case that an error should occr here is if
      +	   * the wait was awakened by a signal.
      +	   */
      +
      +	  ASSERT(get_errno() == EINTR);
      +	}
      +
      +      /* We have it.  Claim the stak and return */
      +
      +      stream->fs_holder = my_pid;
      +      stream->fs_counts = 1;
      +    }
      +}
      +
      +/************************************************************************
      + * lib_give_semaphore
      + ************************************************************************/
      +
      +void lib_give_semaphore(FAR struct file_struct *stream)
      +{
      +  pid_t my_pid = getpid();
      +
      +  /* I better be holding at least one reference to the semaphore */
      +
      +  ASSERT(stream->fs_holder == my_pid);
      +
      +  /* Do I hold multiple references to the semphore */
      +
      +  if (stream->fs_counts > 1)
      +    {
      +      /* Yes, just release one count and return */
      +
      +      stream->fs_counts--;
      +    }
      +  else
      +    {
      +      /* Nope, this is the last reference I have */
      +
      +      stream->fs_holder = -1;
      +      stream->fs_counts = 0;
      +      ASSERT(sem_post(&stream->fs_sem) == 0);
      +    }
      +}
      +#endif /* CONFIG_STDIO_BUFFER_SIZE */
      diff --git a/nuttx/lib/misc/lib_init.c b/nuttx/lib/misc/lib_init.c
      new file mode 100644
      index 0000000000..3403a837b9
      --- /dev/null
      +++ b/nuttx/lib/misc/lib_init.c
      @@ -0,0 +1,207 @@
      +/************************************************************
      + * lib/misc/lib_init.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/************************************************************
      + * Definitions
      + ************************************************************/
      +
      +/************************************************************
      + * Private Variables
      + ************************************************************/
      +
      +/************************************************************
      + * Private Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * lib_initialize
      + ************************************************************/
      +
      +/* General library initialization hook */
      +
      +void weak_const_function lib_initialize(void)
      +{
      +}
      +
      +#if CONFIG_NFILE_STREAMS > 0
      +/* The following function is called when a new TCB is allocated.  It
      + * creates the streamlist instance that is stored in the TCB.
      + */
      +
      +FAR struct streamlist *lib_alloclist(void)
      +{
      +  FAR struct streamlist *list;
      +  list = (FAR struct streamlist*)lib_zalloc(sizeof(struct streamlist));
      +  if (list)
      +    {
      +      int i;
      +
      +      /* Start with a reference count of one */
      +
      +      list->sl_crefs = 1;
      +
      +      /* Initialize the list access mutex */
      +
      +      (void)sem_init(&list->sl_sem, 0, 1);
      +
      +      /* Initialize each FILE structure */
      +
      +      for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
      +       {
      +         /* Clear the IOB */
      +
      +          memset(&list->sl_streams[i], 0, sizeof(FILE));
      +
      +          /* Indicate not opened */
      +
      +          list->sl_streams[i].fs_filedes = -1;
      +
      +          /* Initialize the stream semaphore to one to support one-at-
      +           * a-time access to private data sets.
      +           */
      +
      +          lib_sem_initialize(&list->sl_streams[i]);
      +        }
      +    }
      +  return list;
      +
      +}
      +
      +/* This function is called when a TCB is closed (such as with
      + * pthread_create().  It increases the reference count on the stream
      + * list.
      + */
      +
      +void lib_addreflist(FAR struct streamlist *list)
      +{
      +  if (list)
      +    {
      +       /* Increment the reference count on the list.
      +        * NOTE: that we disable interrupts to do this
      +        * (vs. taking the list semaphore).  We do this
      +        * because file cleanup operations often must be
      +        * done from the IDLE task which cannot wait
      +        * on semaphores.
      +        */
      +
      +       register irqstate_t flags = irqsave();
      +       list->sl_crefs++;
      +       irqrestore(flags);
      +    }
      +}
      +
      +/* this function is called when a TCB is destroyed.  Note that is
      + * does not close the file by release this inode.  This happens
      + * separately when the file descriptor list is freed.
      + */
      +
      +void lib_releaselist(FAR struct streamlist *list)
      +{
      +  int crefs;
      +  if (list)
      +    {
      +       /* Decrement the reference count on the list.
      +        * NOTE: that we disable interrupts to do this
      +        * (vs. taking the list semaphore).  We do this
      +        * because file cleanup operations often must be
      +        * done from the IDLE task which cannot wait
      +        * on semaphores.
      +        */
      +
      +       register irqstate_t flags = irqsave();
      +       crefs = --(list->sl_crefs);
      +       irqrestore(flags);
      +
      +       /* If the count decrements to zero, then there is no reference
      +        * to the structure and it should be deallocated.  Since there
      +        * are references, it would be an error if any task still held
      +        * a reference to the list's semaphore.
      +        */
      +
      +       if (crefs <= 0)
      +          {
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +            int i;
      +#endif
      +            /* Destroy the semaphore and release the filelist */
      +
      +            (void)sem_destroy(&list->sl_sem);
      +
      +            /* Release each stream in the list */
      +
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +            for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
      +             {
      +               /* Destroy the semaphore that protects the IO buffer */
      +
      +               (void)sem_destroy(&list->sl_streams[i].fs_sem);
      +
      +               /* Release the IO buffer */
      +               if (list->sl_streams[i].fs_bufstart)
      +                 {
      +                   sched_free(list->sl_streams[i].fs_bufstart);
      +                 }
      +             }
      +#endif
      +           /* Finally, release the list itself */
      +
      +            sched_free(list);
      +         }
      +     }
      +}
      +
      +#endif /* CONFIG_NFILE_STREAMS */
      +
      +
      diff --git a/nuttx/lib/misc/lib_match.c b/nuttx/lib/misc/lib_match.c
      new file mode 100644
      index 0000000000..18e0632ec6
      --- /dev/null
      +++ b/nuttx/lib/misc/lib_match.c
      @@ -0,0 +1,148 @@
      +/****************************************************************************
      + * lib/misc/lib_match.c - simple shell-style filename matcher
      + *
      + * Simple shell-style filename pattern matcher written by Jef Poskanzer
      + * This pattern matcher only handles '?', '*' and '**', and  multiple
      + * patterns separated by '|'.
      + *
      + *   Copyright © 1995,2000 by Jef Poskanzer .
      + *   All rights reserved.
      + *
      + * 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.
      + *
      + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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 
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: match_one
      + *
      + * Description:
      + *   Does all of the work for one '|' delimited pattern
      + *
      + * Returned Value:
      + *   Returns 1 (match) or 0 (no-match).
      + *
      + ****************************************************************************/
      +
      +static int match_one(const char *pattern, int patlen, const char *string)
      +{
      +  const char *p;
      +  int pl;
      +  int i;
      +
      +  for (p = pattern; p - pattern < patlen; p++, string++)
      +    {
      +      if (*p == '?' && *string != '\0')
      +        {
      +          continue;
      +        }
      +
      +      if (*p == '*')
      +        {
      +          p++;
      +          if (*p == '*')
      +            {
      +              /* Double-wildcard matches anything. */
      +
      +              p++;
      +              i = strlen(string);
      +            }
      +          else
      +            {
      +              /* Single-wildcard matches anything but slash. */
      +
      +              i = strcspn(string, "/");
      +            }
      +
      +          pl = patlen - (p - pattern);
      +          for (; i >= 0; i--)
      +            {
      +              if (match_one(p, pl, &(string[i])))
      +                {
      +                  return 1;
      +                }
      +            }
      +          return 0;
      +        }
      +
      +      if (*p != *string)
      +        {
      +          return 0;
      +        }
      +    }
      +
      +  if (*string == '\0')
      +    {
      +      return 1;
      +    }
      +  return 0;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: match
      + *
      + * Description:
      + *   Simple shell-style filename pattern matcher written by Jef Poskanzer
      + *   This pattern matcher only handles '?', '*' and '**', and  multiple
      + *   patterns separated by '|'.
      + *
      + * Returned Value:
      + *   Returns 1 (match) or 0 (no-match).
      + *
      + ****************************************************************************/
      +
      +int match(const char *pattern, const char *string)
      +{
      +  const char *or;
      +
      +  for (;;)
      +    {
      +      or = strchr(pattern, '|');
      +      if (or == (char *)0)
      +        {
      +          return match_one(pattern, strlen(pattern), string);
      +        }
      +
      +      if (match_one(pattern, or - pattern, string))
      +        {
      +          return 1;
      +        }
      +
      +      pattern = or + 1;
      +    }
      +}
      +
      diff --git a/nuttx/lib/misc/lib_sendfile.c b/nuttx/lib/misc/lib_sendfile.c
      new file mode 100644
      index 0000000000..a82eb325e7
      --- /dev/null
      +++ b/nuttx/lib/misc/lib_sendfile.c
      @@ -0,0 +1,297 @@
      +/************************************************************************
      + * lib/misc/lib_streamsem.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#if CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0
      +
      +/************************************************************************
      + * Private types
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Public Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Name: sendfile
      + *
      + * Description:
      + *   sendfile() copies data between one file descriptor and another.
      + *   sendfile() basically just wraps a sequence of reads() and writes()
      + *   to perform a copy.  It serves a purpose in systems where there is
      + *   a penalty for copies to between user and kernal space, but really
      + *   nothing in NuttX but provide some Linux compatible (and adding
      + *   another 'almost standard' interface). 
      + *
      + *   NOTE: This interface is *not* specified in POSIX.1-2001, or other
      + *   standards.  The implementation here is very similar to the Linux
      + *   sendfile interface.  Other UNIX systems implement sendfile() with
      + *   different semantics and prototypes.  sendfile() should not be used
      + *   in portable programs.
      + *
      + * Input Parmeters:
      + *   infd   - A file (or socket) descriptor opened for reading
      + *   outfd  - A descriptor opened for writing.
      + *   offset - If 'offset' is not NULL, then it points to a variable
      + *            holding the file offset from which sendfile() will start
      + *            reading data from 'infd'.  When sendfile() returns, this
      + *            variable will be set to the offset of the byte following
      + *            the last byte that was read.  If 'offset' is not NULL,
      + *            then sendfile() does not modify the current file offset of
      + *            'infd'; otherwise the current file offset is adjusted to
      + *            reflect the number of bytes read from 'infd.'
      + *
      + *            If 'offset' is NULL, then data will be read from 'infd'
      + *            starting at the current file offset, and the file offset
      + *            will be updated by the call.
      + *   count -  The number of bytes to copy between the file descriptors.
      + *
      + * Returned Value:
      + *   If the transfer was successful, the number of bytes written to outfd is
      + *   returned.  On error, -1 is returned, and errno is set appropriately.
      + *   There error values are those returned by read() or write() plus:
      + *
      + *   EINVAL - Bad input parameters.
      + *   ENOMEM - Could not allocated an I/O buffer
      + *
      + ************************************************************************/
      +
      +ssize_t sendfile(int outfd, int infd, off_t *offset, size_t count)
      +{
      +  FAR uint8_t *iobuffer;
      +  FAR uint8_t *wrbuffer;
      +  off_t startpos = 0;
      +  ssize_t nbytesread;
      +  ssize_t nbyteswritten;
      +  size_t  ntransferred;
      +  bool endxfr;
      +
      +  /* Get the current file position. */
      +
      +  if (offset)
      +    {
      +      /* Use lseek to get the current file position */
      +
      +      startpos = lseek(infd, 0, SEEK_CUR);
      +      if (startpos == (off_t)-1)
      +        {
      +          return ERROR;
      +        }
      +
      +      /* Use lseek again to set the new file position */
      +
      +      if (lseek(infd, *offset, SEEK_SET) == (off_t)-1)
      +        {
      +          return ERROR;
      +        }
      +    }
      +
      +  /* Allocate an I/O buffer */
      +
      +  iobuffer = (FAR void *)malloc(CONFIG_LIB_SENDFILE_BUFSIZE);
      +  if (!iobuffer)
      +    {
      +      set_errno(ENOMEM);
      +      return ERROR;
      +    }
      +
      +  /* Now transfer 'count' bytes from the infd to the outfd */
      +
      +  for (ntransferred = 0, endxfr = false; ntransferred < count && !endxfr; )
      +    {
      +      /* Loop until the read side of the transfer comes to some conclusion */
      +
      +      do
      +        {
      +          /* Read a buffer of data from the infd */
      +
      +          nbytesread = read(infd, iobuffer, CONFIG_LIB_SENDFILE_BUFSIZE);
      +
      +          /* Check for end of file */
      +
      +          if (nbytesread == 0)
      +            {
      +              /* End of file.  Break out and return current number of bytes
      +               * transferred.
      +               */
      +
      +              endxfr = true;
      +              break;
      +            }
      +
      +          /* Check for a read ERROR.  EINTR is a special case.  This function
      +           * should break out and return an error if EINTR is returned and
      +           * no data has been transferred.  But what should it do if some
      +           * data has been transferred?  I suppose just continue?
      +           */
      +
      +          else if (nbytesread < 0)
      +            {
      +              /* EINTR is not an error (but will still stop the copy) */
      +
      +#ifndef CONFIG_DISABLE_SIGNALS
      +              if (errno != EINTR || ntransferred == 0)
      +#endif
      +                {
      +                  /* Read error.  Break out and return the error condition. */
      +
      +                  ntransferred = ERROR;
      +                  endxfr       = true;
      +                  break;
      +                }
      +            }
      +        }
      +      while (nbytesread < 0);
      +
      +      /* Was anything read? */
      +
      +      if (!endxfr)
      +        {
      +          /* Yes.. Loop until the read side of the transfer comes to some
      +           * conclusion.
      +           */
      +
      +          wrbuffer = iobuffer;
      +          do
      +            {
      +              /* Write the buffer of data to the outfd */
      +
      +              nbyteswritten = write(outfd, wrbuffer, nbytesread);
      +
      +              /* Check for a complete (or parial) write.  write() should not
      +               * return zero.
      +               */
      +
      +              if (nbyteswritten >= 0)
      +                {
      +                  /* Advance the buffer pointer and decrement the number of bytes
      +                   * remaining in the iobuffer.  Typically, nbytesread will now
      +                   * be zero.
      +                   */
      +
      +                  wrbuffer     += nbyteswritten;
      +                  nbytesread   -= nbyteswritten;
      +
      +                  /* Increment the total number of bytes successfully transferred. */
      +
      +                  ntransferred += nbyteswritten;
      +                }
      +
      +              /* Otherwise an error occurred */
      +
      +              else
      +                {
      +                  /* Check for a read ERROR.  EINTR is a special case.  This
      +                   * function should break out and return an error if EINTR
      +                   * is returned and no data has been transferred.  But what
      +                   * should it do if some data has been transferred?  I
      +                   * suppose just continue?
      +                   */
      +
      +#ifndef CONFIG_DISABLE_SIGNALS
      +                  if (errno != EINTR || ntransferred == 0)
      +#endif
      +                    {
      +                      /* Write error.  Break out and return the error condition */
      +
      +                      ntransferred = ERROR;
      +                      endxfr       = true;
      +                      break;
      +                    }
      +                }
      +            }
      +          while (nbytesread > 0);
      +        }
      +    }
      +
      +  /* Release the I/O buffer */
      +
      +  free(iobuffer);
      +
      +  /* Return the current file position */
      +
      +  if (offset)
      +    {
      +      /* Use lseek to get the current file position */
      +
      +      off_t curpos = lseek(infd, 0, SEEK_CUR);
      +      if (curpos == (off_t)-1)
      +        {
      +          return ERROR;
      +        }
      +
      +      /* Return the current file position */
      +
      +      *offset = curpos;
      +
      +      /* Use lseek again to restore the original file position */
      +
      +      if (lseek(infd, startpos, SEEK_SET) == (off_t)-1)
      +        {
      +          return ERROR;
      +        }
      +    }
      +
      +  /* Finally return the number of bytes actually transferred (or ERROR
      +   * if any failure occurred).
      +   */
      +
      +  return ntransferred;
      +}
      +
      +#endif /* CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0 */
      diff --git a/nuttx/lib/misc/lib_streamsem.c b/nuttx/lib/misc/lib_streamsem.c
      new file mode 100644
      index 0000000000..fdf494e751
      --- /dev/null
      +++ b/nuttx/lib/misc/lib_streamsem.c
      @@ -0,0 +1,90 @@
      +/************************************************************************
      + * lib/misc/lib_streamsem.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/************************************************************************
      + * Private types
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Public Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +void stream_semtake(FAR struct streamlist *list)
      +{
      +  /* Take the semaphore (perhaps waiting) */
      +
      +  while (sem_wait(&list->sl_sem) != 0)
      +    {
      +      /* The only case that an error should occr here is if
      +       * the wait was awakened by a signal.
      +       */
      +
      +      ASSERT(get_errno() == EINTR);
      +    }
      +}
      +
      +void stream_semgive(FAR struct streamlist *list)
      +{
      +  sem_post(&list->sl_sem);
      +}
      +
      +
      diff --git a/nuttx/lib/mqueue/Make.defs b/nuttx/lib/mqueue/Make.defs
      new file mode 100644
      index 0000000000..40dc6c13e6
      --- /dev/null
      +++ b/nuttx/lib/mqueue/Make.defs
      @@ -0,0 +1,48 @@
      +############################################################################
      +# lib/mqueue/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +ifneq ($(CONFIG_DISABLE_MQUEUE),y)
      +
      +# Add the mqueue C files to the build
      +
      +CSRCS += mq_setattr.c mq_getattr.c
      +
      +# Add the mqueue directory to the build
      +
      +DEPPATH += --dep-path mqueue
      +VPATH += :mqueue
      +
      +endif
      +
      diff --git a/nuttx/lib/mqueue/mq_getattr.c b/nuttx/lib/mqueue/mq_getattr.c
      new file mode 100644
      index 0000000000..9c9f47fdce
      --- /dev/null
      +++ b/nuttx/lib/mqueue/mq_getattr.c
      @@ -0,0 +1,104 @@
      +/************************************************************************
      + * lib/mqueue/mq_getattr.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Definitions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Type Declarations
      + ************************************************************************/
      +
      +/************************************************************************
      + * Global Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Function:  mq_getattr
      + *
      + * Description:
      + *   This functions gets status information and attributes
      + *   associated with the specified message queue.
      + *
      + * Parameters:
      + *   mqdes - Message queue descriptor
      + *   mq_stat - Buffer in which to return attributes
      + *
      + * Return Value:
      + *   0 (OK) if attributes provided, -1 (ERROR) otherwise.
      + *
      + * Assumptions:
      + *
      + ************************************************************************/
      +
      +int mq_getattr(mqd_t mqdes, struct mq_attr *mq_stat)
      +{
      +  int ret = ERROR;
      +
      +  if (mqdes && mq_stat)
      +    {
      +      /* Return the attributes */
      +
      +      mq_stat->mq_maxmsg  = mqdes->msgq->maxmsgs;
      +      mq_stat->mq_msgsize = mqdes->msgq->maxmsgsize;
      +      mq_stat->mq_flags   = mqdes->oflags;
      +      mq_stat->mq_curmsgs = mqdes->msgq->nmsgs;
      +
      +      ret = OK;
      +    }
      +
      +  return ret;
      +}
      diff --git a/nuttx/lib/mqueue/mq_setattr.c b/nuttx/lib/mqueue/mq_setattr.c
      new file mode 100644
      index 0000000000..1276d64e8a
      --- /dev/null
      +++ b/nuttx/lib/mqueue/mq_setattr.c
      @@ -0,0 +1,118 @@
      +/************************************************************************
      + * lib/mqueue/mq_setattr.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include           /* O_NONBLOCK */
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Definitions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Type Declarations
      + ************************************************************************/
      +
      +/************************************************************************
      + * Global Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Function:  mq_setattr
      + *
      + * Description:
      + *   This function sets the attributes associated with the
      + *   specified message queue "mqdes."  Only the "O_NONBLOCK"
      + *   bit of the "mq_flags" can be changed.
      + *
      + *   If "oldstat" is non-null, mq_setattr() will store the
      + *   previous message queue attributes at that location (just
      + *   as would have been returned by mq_getattr()).
      + *
      + * Parameters:
      + *   mqdes - Message queue descriptor
      + *   mq_stat - New attributes
      + *   oldstate - Old attributes
      + *
      + * Return Value:
      + *   0 (OK) if attributes are set successfully, otherwise
      + *   -1 (ERROR).
      + *
      + * Assumptions:
      + *
      + ************************************************************************/
      +
      +int mq_setattr(mqd_t mqdes, const struct mq_attr *mq_stat,
      +               struct mq_attr *oldstat)
      +{
      +  int ret = ERROR;
      +
      +  if (mqdes && mq_stat)
      +    {
      +      /* Return the attributes if so requested */
      +
      +      if (oldstat)
      +        {
      +          (void)mq_getattr(mqdes, oldstat);
      +        }
      +
      +      /* Set the new value of the O_NONBLOCK flag. */
      +
      +      mqdes->oflags = ((mq_stat->mq_flags & O_NONBLOCK) |
      +                       (mqdes->oflags & (~O_NONBLOCK)));
      +      ret = OK;
      +    }
      +
      +  return ret;
      +}
      diff --git a/nuttx/lib/net/Make.defs b/nuttx/lib/net/Make.defs
      new file mode 100644
      index 0000000000..ae041bd2c5
      --- /dev/null
      +++ b/nuttx/lib/net/Make.defs
      @@ -0,0 +1,44 @@
      +############################################################################
      +# lib/net/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the networking C files to the build
      +
      +CSRCS += lib_etherntoa.c lib_htons.c lib_htonl.c lib_inetaddr.c
      +CSRCS += lib_inetntoa.c lib_inetntop.c lib_inetpton.c
      +
      +# Add the net directory to the build
      +
      +DEPPATH += --dep-path net
      +VPATH += :net
      diff --git a/nuttx/lib/net/lib_etherntoa.c b/nuttx/lib/net/lib_etherntoa.c
      new file mode 100644
      index 0000000000..f89f205a2e
      --- /dev/null
      +++ b/nuttx/lib/net/lib_etherntoa.c
      @@ -0,0 +1,69 @@
      +/****************************************************************************
      + * lib/net/lib_etherntoa.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: ether_ntoa
      + *
      + * Description:
      + *   The ether_ntoa() function converts the Ethernet host address addr given
      + *   in network byte order to a string in standard hex-digits-and-colons
      + *   notation. The string is returned in a statically allocated buffer, which
      + *   subsequent calls will overwrite.
      + *
      + ****************************************************************************/
      +
      +FAR char *ether_ntoa(FAR const struct ether_addr *addr)
      +{
      +  static char buffer[20];
      +  sprintf(buffer, "%02x:%02x:%02x:%02x:%02x:%02x",
      +          addr->ether_addr_octet[0], addr->ether_addr_octet[1],
      +          addr->ether_addr_octet[2], addr->ether_addr_octet[3],
      +          addr->ether_addr_octet[4], addr->ether_addr_octet[5]);
      +  return buffer;
      +}
      diff --git a/nuttx/lib/net/lib_htonl.c b/nuttx/lib/net/lib_htonl.c
      new file mode 100644
      index 0000000000..e4c3e53838
      --- /dev/null
      +++ b/nuttx/lib/net/lib_htonl.c
      @@ -0,0 +1,68 @@
      +/************************************************************
      + * lib/net/lib_ntohl.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +/************************************************************
      + * Global Functions
      + ************************************************************/
      +
      +uint32_t htonl(uint32_t hl)
      +{
      +#ifdef CONFIG_ENDIAN_BIG
      +  return hl;
      +#else
      +  return (( (hl) >> 24) |
      +          (((hl) >>  8) & 0x0000ff00) |
      +          (((hl) <<  8) & 0x00ff0000) |
      +	  ( (hl) << 24));
      +#endif
      +}
      +
      +uint32_t ntohl(uint32_t nl)
      +{
      +#ifdef CONFIG_ENDIAN_BIG
      +  return nl;
      +#else
      +  return htonl(nl);
      +#endif
      +}
      diff --git a/nuttx/lib/net/lib_htons.c b/nuttx/lib/net/lib_htons.c
      new file mode 100644
      index 0000000000..b4117e1dc2
      --- /dev/null
      +++ b/nuttx/lib/net/lib_htons.c
      @@ -0,0 +1,65 @@
      +/***************************************************************************
      + * lib/net/lib_htons.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ***************************************************************************/
      +
      +/***************************************************************************
      + * Compilation Switches
      + ***************************************************************************/
      +
      +/***************************************************************************
      + * Included Files
      + ***************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +/***************************************************************************
      + * Global Functions
      + ***************************************************************************/
      +
      +uint16_t htons(uint16_t hs)
      +{
      +  return HTONS(hs);
      +}
      +
      +uint16_t ntohs(uint16_t ns)
      +{
      +#ifdef CONFIG_ENDIAN_BIG
      +  return ns;
      +#else
      +  return htons(ns);
      +#endif
      +}
      diff --git a/nuttx/lib/net/lib_inetaddr.c b/nuttx/lib/net/lib_inetaddr.c
      new file mode 100644
      index 0000000000..48b01d682f
      --- /dev/null
      +++ b/nuttx/lib/net/lib_inetaddr.c
      @@ -0,0 +1,74 @@
      +/****************************************************************************
      + * lib/net/lib_inetaddr.c
      + *
      + *   Copyright (C) 2011 Yu Qiang. All rights reserved.
      + *   Author: Yu Qiang 
      + *
      + * This file is a part of NuttX:
      + *
      + *   Copyright (C) 2011 Gregory Nutt. All rights reserved.
      + *
      + * 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 
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * name inet_addr
      + *
      + * Description:
      + *   The inet_addr() function converts the string pointed to by cp, in the
      + *   standard IPv4 dotted decimal notation, to an integer value suitable for
      + *   use as an Internet address.
      + 
      + ****************************************************************************/
      +
      +in_addr_t inet_addr(FAR const char *cp)
      +{
      +  unsigned int a, b, c, d;
      +  uint32_t result;
      +
      +  sscanf(cp, "%u.%u.%u.%u", &a, &b, &c, &d);
      +  result   = a << 8;
      +  result  |= b;
      +  result <<= 8;
      +  result  |= c;
      +  result <<= 8;
      +  result  |= d;
      +  return HTONL(result);
      +}
      diff --git a/nuttx/lib/net/lib_inetntoa.c b/nuttx/lib/net/lib_inetntoa.c
      new file mode 100644
      index 0000000000..0f4fb61df6
      --- /dev/null
      +++ b/nuttx/lib/net/lib_inetntoa.c
      @@ -0,0 +1,79 @@
      +/****************************************************************************
      + * lib/net/lib_inetntoa.c
      + *
      + *   Copyright (C) 2007-2008, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +#ifndef CONFIG_NET_IPv6
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: inet_ntoa
      + *
      + * Description:
      + *   The inet_ntoa() function converts the Internet host address in given in
      + *   network byte order to a string in standard numbers-and-dots notation.
      + *   The string is returned in a statically allocated buffer, which subsequent
      + *   calls will overwrite.
      + *
      + ****************************************************************************/
      +
      +#ifdef CONFIG_CAN_PASS_STRUCTS
      +FAR char *inet_ntoa(struct in_addr in)
      +{
      +  static char buffer[INET_ADDRSTRLEN+2];
      +  FAR char *ptr = (FAR char*)&in.s_addr;
      +  sprintf(buffer, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]);
      +  return buffer;
      +}
      +#else
      +FAR char *_inet_ntoa(in_addr_t in)
      +{
      +  static char buffer[INET_ADDRSTRLEN+2];
      +  FAR char *ptr = (FAR char*)∈
      +  sprintf(buffer, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]);
      +  return buffer;
      +}
      +#endif
      +#endif /* !CONFIG_NET_IPv6 */
      +
      diff --git a/nuttx/lib/net/lib_inetntop.c b/nuttx/lib/net/lib_inetntop.c
      new file mode 100644
      index 0000000000..dc6a2d0d79
      --- /dev/null
      +++ b/nuttx/lib/net/lib_inetntop.c
      @@ -0,0 +1,202 @@
      +/****************************************************************************
      + * lib/net/lib_inetntop.c
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Author: Gregory Nutt 
      + *
      + * Includes some logic extracted from hwport_ftpd, written by Jaehyuk Cho
      + *  which was released under the BSD license.
      + *
      + *   Copyright (C) HWPORT.COM. All rights reserved.
      + *   Author: JAEHYUK CHO 
      + *
      + * 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 
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: inet_ntop
      + *
      + * Description:
      + *  The inet_ntop() function converts a numeric address into a text string
      + *  suitable for presentation.
      + *
      + * Input Parameters:
      + *   af   - The af argument specifies the family of the address. This can be
      + *          AF_INET or AF_INET6.
      + *   src  - The src argument points to a buffer holding an address of the
      + *          specified type.  The address must be in network byte order.
      + *   dst  - The dst argument points to a buffer where the function stores
      + *          the resulting text string; it shall not be NULL.
      + *   size - The size argument specifies the size of this buffer, which must
      + *          be large enough to hold the text string (INET_ADDRSTRLEN
      + *          characters for IPv4, INET6_ADDRSTRLEN characters for IPv6).
      + *
      + * Returned Value:
      + *   inet_ntop() returns a pointer to the buffer containing the text string
      + *   if the conversion succeeds.  Otherwise, NULL is returned and the errno
      + *   is set to indicate the error.  There follow errno values may be set:
      + *
      + *   EAFNOSUPPORT - The af argument is invalid.
      + *   ENOSPC - The size of the inet_ntop() result buffer is inadequate
      + *
      + ****************************************************************************/
      +
      +FAR const char *inet_ntop(int af, FAR const void *src, FAR char *dst, socklen_t size)
      +{
      +  int errval;
      +#ifndef CONFIG_NET_IPv6
      +  FAR char *ptr;
      +
      +  DEBUGASSERT(src && dst);
      +
      +  if (af != AF_INET)
      +    {
      +      errval = EAFNOSUPPORT;
      +      goto errout;
      +    }
      +
      +  if (size < INET_ADDRSTRLEN)
      +    {
      +      errval = ENOSPC;
      +      goto errout;
      +    }
      +
      +  ptr = (FAR char*)src;
      +  sprintf(dst, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]);
      +  return dst;
      +#else
      +  FAR const struct in6_addr *in6_addr;
      +  uint16_t warray[8];
      +  int offset;
      +  int entry;
      +  int count;
      +  int maxentry;
      +  int maxcount;
      + 
      +  DEBUGASSERT(src && dst);
      +
      +  if (af != AF_INET6)
      +    {
      +      errval = EAFNOSUPPORT;
      +      goto errout;
      +    }
      +
      +  if (size < INET6_ADDRSTRLEN)
      +    {
      +      errval = ENOSPC;
      +      goto errout;
      +    }
      +
      +  in6_addr = (FAR const struct in6_addr *)src;
      +  entry    = -1;
      +  maxentry = -1;
      +  maxcount = 0;
      +  offset   = 0;
      +
      +  while (offset < 8)
      +    {
      +      warray[offset] = ntohs(in6_addr->s6_addr16[offset]);
      +      if (warray[offset] == 0)
      +        {
      +          entry = offset;
      +          count = 1;
      +          offset++;
      +
      +          while (offset < 8)
      +            {
      +              warray[offset] = ntohs(in6_addr->s6_addr16[offset]);
      +              if (warray[offset] != 0)
      +                {
      +                  break;
      +                }
      +              offset++;
      +              count++;
      +            }
      +
      +          if (count > maxcount)
      +            {
      +              maxentry = entry;
      +              maxcount = count;
      +            }
      +        }
      +      offset++;
      +    }
      +
      +  offset = 0;
      +  dst[0] = '\0';
      +
      +  while (offset < 8)
      +    {
      +      if (offset == maxentry)
      +        {
      +          size   -= snprintf(&dst[strlen(dst)], size, ":");
      +          offset += maxcount;
      +          if (offset >= 8)
      +            {
      +              size -= snprintf(&dst[strlen(dst)], size, ":");
      +            }
      +        }
      +      else
      +        {
      +          if (offset > 0)
      +            {
      +              size -= snprintf(&dst[strlen(dst)], size, ":");
      +            }
      +
      +          size -= snprintf(&dst[strlen(dst)], size, "%x", warray[offset]);
      +          offset++;
      +        }
      +    }
      +
      +    return dst;
      +#endif
      +
      +errout:
      +    set_errno(errval);
      +    memset(dst, 0, size);
      +    return NULL;
      +}
      diff --git a/nuttx/lib/net/lib_inetpton.c b/nuttx/lib/net/lib_inetpton.c
      new file mode 100644
      index 0000000000..5371cd3f21
      --- /dev/null
      +++ b/nuttx/lib/net/lib_inetpton.c
      @@ -0,0 +1,338 @@
      +/****************************************************************************
      + * lib/net/lib_inetpton.c
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Author: Gregory Nutt 
      + *
      + * Includes some logic extracted from hwport_ftpd, written by Jaehyuk Cho
      + *  which was released under the BSD license.
      + *
      + *   Copyright (C) HWPORT.COM. All rights reserved.
      + *   Author: JAEHYUK CHO 
      + *
      + * 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 
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: inet_pton
      + *
      + * Description:
      + *  The inet_pton() function converts an address in its standard text
      + *  presentation form into its numeric binary form.
      + *
      + *  If the af argument of inet_pton() is AF_INET, the src string will be
      + *  in the standard IPv4 dotted-decimal form:
      + *
      + *    ddd.ddd.ddd.ddd
      + *
      + *  where "ddd" is a one to three digit decimal number between 0 and 255.
      + *
      + *  If the af argument of inet_pton() is AF_INET6, the src string will be in
      + *  one of the following standard IPv6 text forms:
      + *
      + *  1. The preferred form is "x:x:x:x:x:x:x:x", where the 'x' s are the
      + *     hexadecimal values of the eight 16-bit pieces of the address. Leading
      + *     zeros in individual fields can be omitted, but there must be at least
      + *     one numeral in every field.
      + *
      + *  2. A string of contiguous zero fields in the preferred form can be shown
      + *     as "::". The "::" can only appear once in an address. Unspecified
      + *     addresses ( "0:0:0:0:0:0:0:0" ) may be represented simply as "::".
      + *
      + *  3. A third form that is sometimes more convenient when dealing with a
      + *     mixed environment of IPv4 and IPv6 nodes is "x:x:x:x:x:x:d.d.d.d",
      + *     where the 'x' s are the hexadecimal values of the six high-order
      + *     16-bit pieces of the address, and the 'd' s are the decimal values
      + *     of the four low-order 8-bit pieces of the address (standard IPv4
      + *     representation).
      + *
      + * Input Parameters:
      + *   af   - The af argument specifies the family of the address. This can be
      + *          AF_INET or AF_INET6.
      + *   src  - The src argument points to the string being passed in.
      + *   dst  - The dst argument points to a numstr into which the function stores
      + *          the numeric address; this must be large enough to hold the numeric
      + *          address (32 bits for AF_INET, 128 bits for AF_INET6).
      + *
      + * Returned Value:
      + *   The inet_pton() function returns 1 if the conversion succeeds, with the
      + *   address pointed to by dst in network byte order. It will return 0 if the
      + *   input is not a valid IPv4 dotted-decimal string or a valid IPv6 address
      + *   string, or -1 with errno set to EAFNOSUPPOR] if the af argument is unknown.
      + *
      + ****************************************************************************/
      +
      +int inet_pton(int af, FAR const char *src, FAR void *dst)
      +{
      +#ifndef CONFIG_NET_IPv6
      +  size_t srcoffset;
      +  size_t numoffset;
      +  int value;
      +  int ndots;
      +  uint8_t ch;
      +  char numstr[4];
      +  uint8_t *ip;
      +
      +  DEBUGASSERT(src && dst);
      +
      +  if (af != AF_INET)
      +    {
      +      set_errno(EAFNOSUPPORT);
      +      return -1;
      +    }
      +
      +  (void)memset(dst, 0, sizeof(struct in_addr));
      +
      +  ip        = (uint8_t *)dst;
      +  srcoffset = 0;
      +  numoffset = 0;
      +  ndots     = 0;
      +
      +  for(;;)
      +    {
      +      ch = (uint8_t)src[srcoffset++];
      +
      +      if (ch == '.' || ch == '\0')
      +        {
      +          if (ch == '.' && ndots >= 4)
      +            {
      +              /* Too many dots */
      +
      +              break;
      +            }
      +
      +          if (numoffset <= 0)
      +            {
      +              /* Empty numeric string */
      +
      +              break;
      +            }
      +
      +          numstr[numoffset] = '\0';
      +          numoffset = 0;
      +
      +          value = atoi(numstr);
      +          if (value < 0 || value > 255)
      +            {
      +              /* Out of range value */
      +
      +              break;
      +            }
      +
      +          ip[ndots] = (uint8_t)value;
      +
      +          if (ch == '\0')
      +            {
      +              if (ndots != 3)
      +                {
      +                  /* Not enough dots */
      +
      +                  break;
      +                }
      +
      +              /* Return 1 if the conversion succeeds */
      +
      +              return 1;
      +            }
      +
      +          ndots++;
      +        }
      +      else if (ch >= '0' && ch <= '9')
      +        {
      +          numstr[numoffset++] = ch;
      +          if (numoffset >= 4)
      +            {
      +              /* Number is too long */
      +
      +              break;
      +            }
      +        }
      +      else
      +        {
      +          /* Illegal character */
      +
      +          break;
      +        }
      +    }
      +
      +  /* Return zero if there is any problem parsing the input */
      +
      +  return 0;
      +#else
      +  size_t srcoffset;
      +  size_t numoffset;
      +  long value;
      +  int nsep;
      +  int nrsep;
      +  uint8_t ch;
      +  char numstr[5];
      +  uint8_t ip[sizeof(struct in6_addr)];
      +  uint8_t rip[sizeof(struct in6_addr)];
      +  bool rtime;
      +
      +  DEBUGASSERT(src && dst);
      +
      +  if (af != AF_INET6)
      +    {
      +      set_errno(EAFNOSUPPORT);
      +      return -1;
      +    }
      +
      +  (void)memset(dst, 0, sizeof(struct in6_addr));
      +
      +  srcoffset = 0;
      +  numoffset = 0;
      +  nsep      = 0;
      +  nrsep     = 0;
      +  rtime     = false;
      +
      +  for(;;)
      +    {
      +      ch = (uint8_t)src[srcoffset++];
      +
      +      if (ch == ':' || ch == '\0')
      +        {
      +          if (ch == ':' && (nsep + nrsep) >= 8)
      +            {
      +              /* Too many separators */
      +
      +              break;
      +            }
      +
      +          if (ch != '\0' && numoffset <= 0)
      +            {
      +              /* Empty numeric string */
      +
      +              if (rtime && nrsep > 1)
      +                {
      +                  /* dup simple */
      +
      +                  break;
      +                }
      +
      +              numoffset = 0;
      +              rtime = true;
      +              continue;
      +            }
      +
      +          numstr[numoffset] = '\0';
      +          numoffset = 0;
      +
      +          value = strtol(numstr, NULL, 16);
      +          if (value < 0 || value > 0xffff)
      +            {
      +              /* Out of range value */
      +
      +              break;
      +            }
      +
      +          if (!rtime)
      +            {
      +              ip[(nsep << 1) + 0] = (uint8_t)((value >> 8) & 0xff);
      +              ip[(nsep << 1) + 1] = (uint8_t)((value >> 0) & 0xff);
      +              nsep++;
      +            }
      +          else
      +            {
      +              rip[(nrsep << 1) + 0] = (uint8_t)((value >> 8) & 0xff);
      +              rip[(nrsep << 1) + 1] = (uint8_t)((value >> 0) & 0xff);
      +              nrsep++;
      +            }
      +
      +          if (ch == '\0' /* || ch == '/' */)
      +            {
      +              if ((nsep <= 1 && nrsep <= 0) ||
      +                  (nsep + nrsep) < 1 ||
      +                  (nsep + nrsep) > 8)
      +                {
      +                  /* Separator count problem */
      +
      +                  break;
      +                }
      +
      +              if (nsep > 0)
      +                {
      +                  memcpy(dst, &ip[0], nsep << 1);
      +                }
      +
      +              if (nrsep > 0)
      +                {
      +                  memcpy(dst + (16 - (nrsep << 1)), &rip[0], nrsep << 1);
      +                }
      +
      +              /* Return 1 if the conversion succeeds */
      +
      +              return 1;
      +            }
      +        }
      +      else if ((ch >= '0' && ch <= '9') ||
      +               (ch >= 'a' && ch <= 'f') ||
      +               (ch >= 'A' && ch <= 'F'))
      +        {
      +          numstr[numoffset++] = ch;
      +          if (numoffset >= 5)
      +            {
      +              /* Numeric string is too long */
      +
      +              break;
      +            }
      +        }
      +      else
      +        {
      +          /* Illegal character */
      +
      +          break;
      +        }
      +    }
      +
      +
      +  /* Return zero if there is any problem parsing the input */
      +
      +  return 0;
      +#endif
      +}
      diff --git a/nuttx/lib/pthread/Make.defs b/nuttx/lib/pthread/Make.defs
      new file mode 100644
      index 0000000000..a1eba7bb0a
      --- /dev/null
      +++ b/nuttx/lib/pthread/Make.defs
      @@ -0,0 +1,56 @@
      +############################################################################
      +# lib/pthread/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the pthread C files to the build
      +
      +CSRCS += pthread_attrinit.c pthread_attrdestroy.c \
      +		  pthread_attrsetschedpolicy.c pthread_attrgetschedpolicy.c \
      +		  pthread_attrsetinheritsched.c pthread_attrgetinheritsched.c \
      +		  pthread_attrsetstacksize.c pthread_attrgetstacksize.c \
      +		  pthread_attrsetschedparam.c pthread_attrgetschedparam.c \
      +		  pthread_barrierattrinit.c pthread_barrierattrdestroy.c \
      +		  pthread_barrierattrgetpshared.c pthread_barrierattrsetpshared.c \
      +		  pthread_condattrinit.c pthread_condattrdestroy.c \
      +		  pthread_mutexattrinit.c pthread_mutexattrdestroy.c \
      +		  pthread_mutexattrgetpshared.c pthread_mutexattrsetpshared.c
      +
      +ifeq ($(CONFIG_MUTEX_TYPES),y)
      +CSRCS += pthread_mutexattrsettype.c pthread_mutexattrgettype.c
      +endif
      +
      +# Add the pthread directory to the build
      +
      +DEPPATH += --dep-path pthread
      +VPATH += :pthread
      diff --git a/nuttx/lib/pthread/pthread_attrdestroy.c b/nuttx/lib/pthread/pthread_attrdestroy.c
      new file mode 100644
      index 0000000000..103528c7e1
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_attrdestroy.c
      @@ -0,0 +1,108 @@
      +/****************************************************************************
      + * lib/pthread/pthread_attrdestroy.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_attr_destroy
      + *
      + * Description:
      + *    An attributes object can be deleted when it is no longer
      + *     needed.
      + *
      + * Parameters:
      + *   attr
      + *
      + * Return Value:
      + *   0 meaning success
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_attr_destroy(FAR pthread_attr_t *attr)
      +{
      +  int ret;
      +
      +  sdbg("attr=0x%p\n", attr);
      +
      +  if (!attr)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      memset(attr, 0, sizeof(pthread_attr_t));
      +      ret = OK;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      +
      +
      diff --git a/nuttx/lib/pthread/pthread_attrgetinheritsched.c b/nuttx/lib/pthread/pthread_attrgetinheritsched.c
      new file mode 100644
      index 0000000000..02d6e0b7c0
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_attrgetinheritsched.c
      @@ -0,0 +1,111 @@
      +/****************************************************************************
      + * lib/pthread/pthread_attrgetinheritsched.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_attr_getinheritsched
      + *
      + * Description:
      + *   Report whether the scheduling info in the pthread
      + *   attributes will be used or if the thread will
      + *   inherit the properties of the parent.
      + *
      + * Parameters:
      + *   attr
      + *   inheritsched
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_attr_getinheritsched(FAR const pthread_attr_t *attr,
      +                                 FAR int *inheritsched)
      +{
      +  int ret;
      +
      +  sdbg("attr=0x%p inheritsched=0x%p\n", attr, inheritsched);
      +
      +  if (!attr || !inheritsched)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      *inheritsched = (int)attr->inheritsched;
      +      ret = OK;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      +
      +
      diff --git a/nuttx/lib/pthread/pthread_attrgetschedparam.c b/nuttx/lib/pthread/pthread_attrgetschedparam.c
      new file mode 100644
      index 0000000000..c6bf55dea8
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_attrgetschedparam.c
      @@ -0,0 +1,110 @@
      +/****************************************************************************
      + * lib/pthread/pthread_attrgetschedparam.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_attr_getschedparam
      + *
      + * Description:
      + *
      + * Parameters:
      + *   attr
      + *   param
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_attr_getschedparam(FAR pthread_attr_t *attr,
      +                               FAR struct sched_param *param)
      +{
      +  int ret;
      +
      +  sdbg("attr=0x%p param=0x%p\n", attr, param);
      +
      +  if (!attr || !param)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      param->sched_priority = attr->priority;
      +      ret = OK;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      +
      +
      +
      diff --git a/nuttx/lib/pthread/pthread_attrgetschedpolicy.c b/nuttx/lib/pthread/pthread_attrgetschedpolicy.c
      new file mode 100644
      index 0000000000..c42b828c96
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_attrgetschedpolicy.c
      @@ -0,0 +1,105 @@
      +/****************************************************************************
      + * lib/pthread/pthread_attrgetschedpolicy.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_attr_getschedpolicy
      + *
      + * Description:
      + *   Obtain the scheduling algorithm attribute.
      + *
      + * Parameters:
      + *   attr
      + *   policy
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_attr_getschedpolicy(FAR pthread_attr_t *attr, int *policy)
      +{
      +  int ret;
      +
      +  sdbg("attr=0x%p policy=0x%p\n", attr, policy);
      +
      +  if (!attr || !policy)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      *policy = attr->policy;
      +      ret = OK;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      diff --git a/nuttx/lib/pthread/pthread_attrgetstacksize.c b/nuttx/lib/pthread/pthread_attrgetstacksize.c
      new file mode 100644
      index 0000000000..2faa586ba8
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_attrgetstacksize.c
      @@ -0,0 +1,106 @@
      +/****************************************************************************
      + * lib/pthread/pthread_attrgetstacksize.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_attr_getstacksize
      + *
      + * Description:
      + *
      + * Parameters:
      + *   attr
      + *   stacksize
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_attr_getstacksize(FAR pthread_attr_t *attr, FAR long *stacksize)
      +{
      +  int ret;
      +
      +  sdbg("attr=0x%p stacksize=0x%p\n", attr, stacksize);
      +
      +  if (!stacksize)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      *stacksize = attr->stacksize;
      +      ret = OK;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      +
      +
      diff --git a/nuttx/lib/pthread/pthread_attrinit.c b/nuttx/lib/pthread/pthread_attrinit.c
      new file mode 100644
      index 0000000000..d06a535d78
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_attrinit.c
      @@ -0,0 +1,123 @@
      +/****************************************************************************
      + * lib/pthread/pthread_attrinit.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/* Default pthread attributes (see included/nuttx/pthread.h).  When configured
      + * to build separate kernel- and user-address spaces, this global is
      + * duplicated in each address spaced.  This copy can only be shared within
      + * the user address space. 
      + */
      +
      +#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__)
      +pthread_attr_t g_default_pthread_attr = PTHREAD_ATTR_INITIALIZER;
      +#endif
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_attr_init
      + *
      + * Description:
      + *   Initializes a thread attributes object (attr) with
      + *   default values for all of the individual attributes
      + *   used by a given implementation.
      + *
      + * Parameters:
      + *   attr
      + *
      + * Return Value:
      + *   0 on success, otherwise an error number
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_attr_init(FAR pthread_attr_t *attr)
      +{
      +  int ret = OK;
      +
      +  sdbg("attr=0x%p\n", attr);
      +  if (!attr)
      +    {
      +      ret = ENOMEM;
      +    }
      +  else
      +    {
      +      /* Set the child thread priority to be the default
      +       * priority. Set the child stack size to some arbitrary
      +       * default value.
      +       */
      +
      +      memcpy(attr, &g_default_pthread_attr, sizeof(pthread_attr_t));
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/pthread/pthread_attrsetinheritsched.c b/nuttx/lib/pthread/pthread_attrsetinheritsched.c
      new file mode 100644
      index 0000000000..df2c2fba33
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_attrsetinheritsched.c
      @@ -0,0 +1,113 @@
      +/****************************************************************************
      + * lib/pthread/pthread_attrsetinheritsched.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_attr_setinheritsched
      + *
      + * Description:
      + *   Indicate whether the scheduling info in the pthread
      + *   attributes will be used or if the thread will
      + *   inherit the properties of the parent.
      + *
      + * Parameters:
      + *   attr
      + *   policy
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_attr_setinheritsched(FAR pthread_attr_t *attr,
      +                                 int inheritsched)
      +{
      +  int ret;
      +
      +  sdbg("inheritsched=%d\n", inheritsched);
      +
      +  if (!attr ||
      +      (inheritsched != PTHREAD_INHERIT_SCHED &&
      +       inheritsched != PTHREAD_EXPLICIT_SCHED))
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      attr->inheritsched = (uint8_t)inheritsched;
      +      ret = OK;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/pthread/pthread_attrsetschedparam.c b/nuttx/lib/pthread/pthread_attrsetschedparam.c
      new file mode 100644
      index 0000000000..c2ab4d1c41
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_attrsetschedparam.c
      @@ -0,0 +1,108 @@
      +/****************************************************************************
      + * lib/pthread/pthread_attrsetschedparam.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_attr_setschedparam
      + *
      + * Description:
      + *
      + * Parameters:
      + *   attr
      + *   param
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_attr_setschedparam(FAR pthread_attr_t *attr,
      +			       FAR const struct sched_param *param)
      +{
      +  int ret;
      +
      +  sdbg("attr=0x%p param=0x%p\n", attr, param);
      +
      +  if (!attr || !param)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      attr->priority = (short)param->sched_priority;
      +      ret = OK;
      +    }
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      +
      +
      diff --git a/nuttx/lib/pthread/pthread_attrsetschedpolicy.c b/nuttx/lib/pthread/pthread_attrsetschedpolicy.c
      new file mode 100644
      index 0000000000..4e43e635de
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_attrsetschedpolicy.c
      @@ -0,0 +1,111 @@
      +/****************************************************************************
      + * lib/pthread/pthread_attrsetschedpolicy.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_attr_setschedpolicy
      + *
      + * Description:
      + *   Set the scheduling algorithm attribute.
      + *
      + * Parameters:
      + *   attr
      + *   policy
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_attr_setschedpolicy(FAR pthread_attr_t *attr, int policy)
      +{
      +  int ret;
      +
      +  sdbg("attr=0x%p policy=%d\n", attr, policy);
      +
      +#if CONFIG_RR_INTERVAL > 0
      +  if (!attr || (policy != SCHED_FIFO && policy != SCHED_RR))
      +#else
      +  if (!attr || policy != SCHED_FIFO )
      +#endif
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      attr->policy = policy;
      +      ret = OK;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      diff --git a/nuttx/lib/pthread/pthread_attrsetstacksize.c b/nuttx/lib/pthread/pthread_attrsetstacksize.c
      new file mode 100644
      index 0000000000..8a826dd3ac
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_attrsetstacksize.c
      @@ -0,0 +1,106 @@
      +/****************************************************************************
      + * lib/pthread/pthread_attrsetstacksize.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_attr_setstacksize
      + *
      + * Description:
      + *
      + * Parameters:
      + *   attr
      + *   stacksize
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_attr_setstacksize(FAR pthread_attr_t *attr, long stacksize)
      +{
      +  int ret;
      +
      +  sdbg("attr=0x%p stacksize=%ld\n", attr, stacksize);
      +
      +  if (!attr || stacksize < PTHREAD_STACK_MIN)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      attr->stacksize = stacksize;
      +      ret = OK;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/pthread/pthread_barrierattrdestroy.c b/nuttx/lib/pthread/pthread_barrierattrdestroy.c
      new file mode 100644
      index 0000000000..6d16b9cff8
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_barrierattrdestroy.c
      @@ -0,0 +1,102 @@
      +/********************************************************************************
      + * lib/pthread/pthread_barrierattrdestroy.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Included Files
      + ********************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/********************************************************************************
      + * Definitions
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Type Declarations
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Global Variables
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Variables
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Function Prototypes
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Public Functions
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Function: pthread_barrierattr_destroy
      + *
      + * Description:
      + *   The pthread_barrierattr_destroy() function will destroy a barrier attributes
      + *   object.  A destroyed attr attributes object can be reinitialized using
      + *   pthread_barrierattr_init(); the results of otherwise referencing the object
      + *   after it has been destroyed are undefined.
      + *
      + * Parameters:
      + *   attr - barrier attributes to be destroyed.
      + *
      + * Return Value:
      + *   0 (OK) on success or EINVAL if attr is invalid.
      + *
      + * Assumptions:
      + *
      + ********************************************************************************/
      +
      +int pthread_barrierattr_destroy(FAR pthread_barrierattr_t *attr)
      +{
      +  int ret = OK;
      +
      +  if (!attr)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      attr->pshared = PTHREAD_PROCESS_PRIVATE;
      +    }
      +  return ret;
      +}
      diff --git a/nuttx/lib/pthread/pthread_barrierattrgetpshared.c b/nuttx/lib/pthread/pthread_barrierattrgetpshared.c
      new file mode 100644
      index 0000000000..d29bc6dfc8
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_barrierattrgetpshared.c
      @@ -0,0 +1,101 @@
      +/********************************************************************************
      + * lib/pthread/pthread_barrierattrgetpshared.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Included Files
      + ********************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/********************************************************************************
      + * Definitions
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Type Declarations
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Global Variables
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Variables
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Function Prototypes
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Public Functions
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Function: pthread_barrierattr_getpshared
      + *
      + * Description:
      + *   The pthread_barrierattr_getpshared() function will obtain the value of the
      + *   process-shared attribute from the attributes object referenced by attr.
      + *
      + * Parameters:
      + *   attr - barrier attributes to be queried.
      + *   pshared - the location to stored the current value of the pshared attribute.
      + *
      + * Return Value:
      + *   0 (OK) on success or EINVAL if either attr or pshared is invalid.
      + *
      + * Assumptions:
      + *
      + ********************************************************************************/
      +
      +int pthread_barrierattr_getpshared(FAR const pthread_barrierattr_t *attr, FAR int *pshared)
      +{
      +  int ret = OK;
      +
      +  if (!attr || !pshared)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      *pshared = attr->pshared;
      +    }
      +  return ret;
      +}
      diff --git a/nuttx/lib/pthread/pthread_barrierattrinit.c b/nuttx/lib/pthread/pthread_barrierattrinit.c
      new file mode 100644
      index 0000000000..b5f35ca917
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_barrierattrinit.c
      @@ -0,0 +1,101 @@
      +/********************************************************************************
      + * lib/pthread/pthread_barrierattrinit.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Included Files
      + ********************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/********************************************************************************
      + * Definitions
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Type Declarations
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Global Variables
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Variables
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Function Prototypes
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Public Functions
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Function: pthread_barrierattr_init
      + *
      + * Description:
      + *   The pthread_barrierattr_init() function will initialize a barrier attribute
      + *   object attr with the default value for all of the attributes defined by the
      + *   implementation.
      + *
      + * Parameters:
      + *   attr - barrier attributes to be initialized.
      + *
      + * Return Value:
      + *   0 (OK) on success or EINVAL if attr is invalid.
      + *
      + * Assumptions:
      + *
      + ********************************************************************************/
      +
      +int pthread_barrierattr_init(FAR pthread_barrierattr_t *attr)
      +{
      +  int ret = OK;
      +
      +  if (!attr)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      attr->pshared = PTHREAD_PROCESS_PRIVATE;
      +    }
      +  return ret;
      +}
      diff --git a/nuttx/lib/pthread/pthread_barrierattrsetpshared.c b/nuttx/lib/pthread/pthread_barrierattrsetpshared.c
      new file mode 100644
      index 0000000000..d0eecbf5a4
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_barrierattrsetpshared.c
      @@ -0,0 +1,111 @@
      +/********************************************************************************
      + * lib/pthread/pthread_barrierattrsetpshared.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Included Files
      + ********************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/********************************************************************************
      + * Definitions
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Type Declarations
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Global Variables
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Variables
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Private Function Prototypes
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Public Functions
      + ********************************************************************************/
      +
      +/********************************************************************************
      + * Function: pthread_barrierattr_setpshared
      + *
      + * Description:
      + *   The process-shared attribute is set to PTHREAD_PROCESS_SHARED to permit a
      + *   barrier to be operated upon by any thread that has access to the memory where
      + *   the barrier is allocated. If the process-shared attribute is
      + *   PTHREAD_PROCESS_PRIVATE, the barrier can only be operated upon by threads
      + *   created within the same process as the thread that initialized the barrier.
      + *   If threads of different processes attempt to operate on such a barrier, the
      + *   behavior is undefined. The default value of the attribute is
      + *   PTHREAD_PROCESS_PRIVATE.
      + *
      + *   Both constants PTHREAD_PROCESS_SHARED and PTHREAD_PROCESS_PRIVATE are defined
      + *   in pthread.h.
      + *
      + * Parameters:
      + *   attr - barrier attributes to be modified.
      + *   pshared - the new value of the pshared attribute.
      + *
      + * Return Value:
      + *   0 (OK) on success or EINVAL if either attr is invalid or pshared is not one
      + *   of PTHREAD_PROCESS_SHARED or PTHREAD_PROCESS_PRIVATE.
      + *
      + * Assumptions:
      + *
      + ********************************************************************************/
      +
      +int pthread_barrierattr_setpshared(FAR pthread_barrierattr_t *attr, int pshared)
      +{
      +  int ret = OK;
      +
      +  if (!attr || (pshared != PTHREAD_PROCESS_SHARED && pshared != PTHREAD_PROCESS_PRIVATE))
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      attr->pshared = pshared;
      +    }
      +  return ret;
      +}
      diff --git a/nuttx/lib/pthread/pthread_condattrdestroy.c b/nuttx/lib/pthread/pthread_condattrdestroy.c
      new file mode 100644
      index 0000000000..d6c3df5d1a
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_condattrdestroy.c
      @@ -0,0 +1,82 @@
      +/****************************************************************************
      + * lib/pthread/pthread_condattrdestroy.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_condattr_destroy
      + *
      + * Description:
      + *   Operations on condition variable attributes
      + *
      + * Parameters:
      + *   None
      + *
      + * Return Value:
      + *   None
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_condattr_destroy(FAR pthread_condattr_t *attr)
      +{
      +  int ret = OK;
      +
      +  sdbg("attr=0x%p\n", attr);
      +
      +  if (!attr)
      +    {
      +      ret = EINVAL;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      +
      +
      +
      diff --git a/nuttx/lib/pthread/pthread_condattrinit.c b/nuttx/lib/pthread/pthread_condattrinit.c
      new file mode 100644
      index 0000000000..5721c61593
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_condattrinit.c
      @@ -0,0 +1,85 @@
      +/****************************************************************************
      + * lib/pthread/pthread_condattrinit.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_condattr_init
      + *
      + * Description:
      + *   Operations on condition variable attributes
      + *
      + * Parameters:
      + *   None
      + *
      + * Return Value:
      + *   None
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_condattr_init(FAR pthread_condattr_t *attr)
      +{
      +  int ret = OK;
      +
      +  sdbg("attr=0x%p\n", attr);
      +
      +  if (!attr)
      +    {
      +      ret = EINVAL;
      +    }
      +  else 
      +    {
      +      *attr = 0;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      +
      +
      diff --git a/nuttx/lib/pthread/pthread_mutexattrdestroy.c b/nuttx/lib/pthread/pthread_mutexattrdestroy.c
      new file mode 100644
      index 0000000000..e9868df68b
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_mutexattrdestroy.c
      @@ -0,0 +1,104 @@
      +/****************************************************************************
      + * lib/pthread/pthread_mutexattrdestroy.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_mutexattr_destroy
      + *
      + * Description:
      + *    Destroy mutex attributes.
      + *
      + * Parameters:
      + *    attr
      + *    pshared
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_mutexattr_destroy(FAR pthread_mutexattr_t *attr)
      +{
      +  int ret = OK;
      +
      +  sdbg("attr=0x%p\n", attr);
      +
      +  if (!attr)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      attr->pshared = 0;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      diff --git a/nuttx/lib/pthread/pthread_mutexattrgetpshared.c b/nuttx/lib/pthread/pthread_mutexattrgetpshared.c
      new file mode 100644
      index 0000000000..bc6379db5f
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_mutexattrgetpshared.c
      @@ -0,0 +1,104 @@
      +/****************************************************************************
      + * lib/pthread/pthread_mutexattrgetpshared.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_mutexattr_getpshared
      + *
      + * Description:
      + *    Get pshared mutex attribute.
      + *
      + * Parameters:
      + *    attr
      + *    pshared
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_mutexattr_getpshared(FAR pthread_mutexattr_t *attr, FAR int *pshared)
      +{
      +  int ret = OK;
      +
      +  sdbg("attr=0x%p pshared=0x%p\n", attr, pshared);
      +
      +  if (!attr || !pshared)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      *pshared = attr->pshared;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      diff --git a/nuttx/lib/pthread/pthread_mutexattrgettype.c b/nuttx/lib/pthread/pthread_mutexattrgettype.c
      new file mode 100644
      index 0000000000..5fb10f3015
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_mutexattrgettype.c
      @@ -0,0 +1,98 @@
      +/****************************************************************************
      + * lib/pthread/pthread_mutexattrgettype.c
      + *
      + *   Copyright (C) 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +#ifdef CONFIG_MUTEX_TYPES
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function: pthread_mutexattr_gettype
      + *
      + * Description:
      + *   Return the mutex type from the mutex attributes.
      + *
      + * Parameters:
      + *   attr - The mutex attributes to query
      + *   type - Location to return the mutex type
      + *
      + * Return Value:
      + *   0, if the mutex type was successfully return in 'type', or
      + *   EINVAL, if any NULL pointers provided.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_mutexattr_gettype(const pthread_mutexattr_t *attr, int *type)
      +{
      +  if (attr && type)
      +    {
      +      *type = attr->type;
      +      return 0;
      +    }
      +  return EINVAL;
      +}
      +
      +#endif /* CONFIG_MUTEX_TYPES */
      diff --git a/nuttx/lib/pthread/pthread_mutexattrinit.c b/nuttx/lib/pthread/pthread_mutexattrinit.c
      new file mode 100644
      index 0000000000..f815bf16c1
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_mutexattrinit.c
      @@ -0,0 +1,106 @@
      +/****************************************************************************
      + * lib/pthread/pthread_mutexattrinit.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_mutexattr_init
      + *
      + * Description:
      + *    Create mutex attributes.
      + *
      + * Parameters:
      + *    attr
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_mutexattr_init(FAR pthread_mutexattr_t *attr)
      +{
      +  int ret = OK;
      +
      +  sdbg("attr=0x%p\n", attr);
      +
      +  if (!attr)
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      attr->pshared = 0;
      +#ifdef CONFIG_MUTEX_TYPES
      +      attr->type    = PTHREAD_MUTEX_DEFAULT;
      +#endif
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      diff --git a/nuttx/lib/pthread/pthread_mutexattrsetpshared.c b/nuttx/lib/pthread/pthread_mutexattrsetpshared.c
      new file mode 100644
      index 0000000000..900476fdd2
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_mutexattrsetpshared.c
      @@ -0,0 +1,104 @@
      +/****************************************************************************
      + * lib/pthread/pthread_mutexattrsetpshared.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  pthread_mutexattr_setpshared
      + *
      + * Description:
      + *    Set pshared  mutex attribute.
      + *
      + * Parameters:
      + *    attr
      + *    pshared
      + *
      + * Return Value:
      + *   0 if successful.  Otherwise, an error code.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_mutexattr_setpshared(FAR pthread_mutexattr_t *attr, int pshared)
      +{
      +  int ret = OK;
      +
      +  sdbg("attr=0x%p pshared=%d\n", attr, pshared);
      +
      +  if (!attr || (pshared != 0 && pshared != 1))
      +    {
      +      ret = EINVAL;
      +    }
      +  else
      +    {
      +      attr->pshared = pshared;
      +    }
      +
      +  sdbg("Returning %d\n", ret);
      +  return ret;
      +}
      diff --git a/nuttx/lib/pthread/pthread_mutexattrsettype.c b/nuttx/lib/pthread/pthread_mutexattrsettype.c
      new file mode 100644
      index 0000000000..81427c757e
      --- /dev/null
      +++ b/nuttx/lib/pthread/pthread_mutexattrsettype.c
      @@ -0,0 +1,98 @@
      +/****************************************************************************
      + * lib/pthread/pthread_mutexattrsettype.c
      + *
      + *   Copyright (C) 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +#ifdef CONFIG_MUTEX_TYPES
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function: pthread_mutexattr_settype
      + *
      + * Description:
      + *   Set the mutex type in the mutex attributes.
      + *
      + * Parameters:
      + *   attr - The mutex attributes in which to set the mutex type.
      + *   type - The mutex type value to set.
      + *
      + * Return Value:
      + *   0, if the mutex type was successfully set in 'attr', or
      + *   EINVAL, if 'attr' is NULL or 'type' unrecognized.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int pthread_mutexattr_settype(pthread_mutexattr_t *attr, int type)
      +{
      +  if (attr && type >= PTHREAD_MUTEX_NORMAL && type <= PTHREAD_MUTEX_RECURSIVE)
      +    {
      +      attr->type = type;
      +      return OK;
      +    }
      +  return EINVAL;
      +}
      +
      +#endif /* CONFIG_MUTEX_TYPES */
      diff --git a/nuttx/lib/queue/Make.defs b/nuttx/lib/queue/Make.defs
      new file mode 100644
      index 0000000000..976e7a2b87
      --- /dev/null
      +++ b/nuttx/lib/queue/Make.defs
      @@ -0,0 +1,47 @@
      +############################################################################
      +# lib/queue/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the queue C files to the build
      +
      +CSRCS += sq_addlast.c sq_addfirst.c sq_addafter.c \
      +		  sq_rem.c sq_remlast.c sq_remfirst.c sq_remafter.c
      +
      +CSRCS += dq_addlast.c dq_addfirst.c dq_addafter.c dq_addbefore.c \
      +		  dq_rem.c dq_remlast.c dq_remfirst.c
      +
      +# Add the queue directory to the build
      +
      +DEPPATH += --dep-path queue
      +VPATH += :queue
      diff --git a/nuttx/lib/queue/dq_addafter.c b/nuttx/lib/queue/dq_addafter.c
      new file mode 100644
      index 0000000000..bfbe0052d8
      --- /dev/null
      +++ b/nuttx/lib/queue/dq_addafter.c
      @@ -0,0 +1,74 @@
      +/************************************************************
      + * lib/queue/dq_addafter.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: dq_addafter
      + *
      + * Description:
      + *  dq_addafter function adds 'node' after 'qqqq' in the
      + *  'queue.'
      + *
      + ************************************************************/
      +
      +void dq_addafter(FAR dq_entry_t *prev, FAR dq_entry_t *node,
      +                 dq_queue_t *queue)
      +{
      +  if (!queue->head || prev == queue->tail)
      +    {
      +      dq_addlast(node, queue);
      +    }
      +  else
      +    {
      +      FAR dq_entry_t *next = prev->flink;
      +      node->blink = prev;
      +      node->flink = next;
      +      next->blink = node;
      +      prev->flink = node;
      +    }
      +}
      diff --git a/nuttx/lib/queue/dq_addbefore.c b/nuttx/lib/queue/dq_addbefore.c
      new file mode 100644
      index 0000000000..d740ea8309
      --- /dev/null
      +++ b/nuttx/lib/queue/dq_addbefore.c
      @@ -0,0 +1,69 @@
      +/****************************************************************************
      + * lib/queue/dq_addbefore.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: dq_addbefore
      + *
      + * Description:
      + *   dq_addbefore adds 'node' before 'next' in 'queue'
      + *
      + ****************************************************************************/
      +
      +void dq_addbefore(FAR dq_entry_t *next, FAR dq_entry_t *node,
      +                  dq_queue_t *queue)
      +{
      +  if (!queue->head || next == queue->head)
      +    {
      +      dq_addfirst(node, queue);
      +    }
      +  else
      +    {
      +      FAR dq_entry_t *prev = next->blink;
      +      node->flink = next;
      +      node->blink = prev;
      +      prev->flink = node;
      +      next->blink = node;
      +    }
      +}
      diff --git a/nuttx/lib/queue/dq_addfirst.c b/nuttx/lib/queue/dq_addfirst.c
      new file mode 100644
      index 0000000000..7c7312de3b
      --- /dev/null
      +++ b/nuttx/lib/queue/dq_addfirst.c
      @@ -0,0 +1,74 @@
      +/************************************************************
      + * lib/queue/dq_addfirst.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: dq_addfirst
      + *
      + * Description:
      + *  dq_addfirst affs 'node' at the beginning of 'queue'
      + *
      + ************************************************************/
      +
      +void dq_addfirst(FAR dq_entry_t *node, dq_queue_t *queue)
      +{
      +  node->blink = NULL;
      +  node->flink = queue->head;
      +
      +  if (!queue->head)
      +    {
      +      queue->head = node;
      +      queue->tail = node;
      +    }
      +  else
      +    {
      +      queue->head->blink = node;
      +      queue->head = node;
      +    }
      +}
      +
      diff --git a/nuttx/lib/queue/dq_addlast.c b/nuttx/lib/queue/dq_addlast.c
      new file mode 100644
      index 0000000000..745deb27d1
      --- /dev/null
      +++ b/nuttx/lib/queue/dq_addlast.c
      @@ -0,0 +1,74 @@
      +/************************************************************
      + * lib/queue/dq_addlast.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: dq_addlast
      + *
      + * Description
      + *   dq_addlast adds 'node' to the end of 'queue'
      + *
      + ************************************************************/
      +
      +void dq_addlast(FAR dq_entry_t *node, dq_queue_t *queue)
      +{
      +  node->flink = NULL;
      +  node->blink = queue->tail;
      +
      +  if (!queue->head)
      +    {
      +      queue->head = node;
      +      queue->tail = node;
      +    }
      +  else
      +    {
      +      queue->tail->flink = node;
      +      queue->tail        = node;
      +    }
      +}
      +
      diff --git a/nuttx/lib/queue/dq_rem.c b/nuttx/lib/queue/dq_rem.c
      new file mode 100644
      index 0000000000..218427bf84
      --- /dev/null
      +++ b/nuttx/lib/queue/dq_rem.c
      @@ -0,0 +1,84 @@
      +/************************************************************
      + * lib/queue/dq_rem.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: dq_rem
      + *
      + * Descripton:
      + *   dq_rem removes 'node' from 'queue'
      + *
      + ************************************************************/
      +
      +void dq_rem(FAR dq_entry_t *node, dq_queue_t *queue)
      +{
      +  FAR dq_entry_t *prev = node->blink;
      +  FAR dq_entry_t *next = node->flink;
      +
      +  if (!prev)
      +    {
      +      queue->head = next;
      +    }
      +  else 
      +    {
      +      prev->flink = next;
      +    }
      +
      +  if (!next)
      +    {
      +      queue->tail = prev;
      +    }
      +  else 
      +    {
      +      next->blink = prev;
      +    }
      +
      +  node->flink = NULL;
      +  node->blink = NULL;
      +}
      +
      diff --git a/nuttx/lib/queue/dq_remfirst.c b/nuttx/lib/queue/dq_remfirst.c
      new file mode 100644
      index 0000000000..26c5fd7a67
      --- /dev/null
      +++ b/nuttx/lib/queue/dq_remfirst.c
      @@ -0,0 +1,82 @@
      +/************************************************************
      + * lib/queue/dq_remfirst.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: dq_remfirst
      + *
      + * Description:
      + *   dq_remfirst removes 'node' from the head of 'queue'
      + *
      + ************************************************************/
      +
      +FAR dq_entry_t *dq_remfirst(dq_queue_t *queue)
      +{
      +  FAR dq_entry_t *ret = queue->head;
      +
      +  if (ret)
      +    {
      +      FAR dq_entry_t *next = ret->flink;
      +      if (!next)
      +        {
      +          queue->head = NULL;
      +          queue->tail = NULL;
      +        }
      +      else
      +        {
      +          queue->head = next;
      +          next->blink = NULL;
      +        }
      +
      +      ret->flink = NULL;
      +      ret->blink = NULL;
      +    }
      +
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/queue/dq_remlast.c b/nuttx/lib/queue/dq_remlast.c
      new file mode 100644
      index 0000000000..35adc73e2d
      --- /dev/null
      +++ b/nuttx/lib/queue/dq_remlast.c
      @@ -0,0 +1,78 @@
      +/****************************************************************************
      + * lib/queue/dq_remlast.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/***************************************************(************************
      + * Name: dq_remlast
      + *
      + * Description:
      + *   dq_remlast removes the last entry from 'queue'
      + *
      + ****************************************************************************/
      +
      +FAR dq_entry_t *dq_remlast(dq_queue_t *queue)
      +{
      +  FAR dq_entry_t *ret = queue->tail;
      +
      +  if (ret)
      +    {
      +      FAR dq_entry_t *prev = ret->blink;
      +      if (!prev)
      +        {
      +          queue->head = NULL;
      +          queue->tail = NULL;
      +        }
      +      else
      +        {
      +          queue->tail = prev;
      +          prev->flink = NULL;
      +        }
      +
      +      ret->flink = NULL;
      +      ret->blink = NULL;
      +    }
      +
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/queue/sq_addafter.c b/nuttx/lib/queue/sq_addafter.c
      new file mode 100644
      index 0000000000..965ac28444
      --- /dev/null
      +++ b/nuttx/lib/queue/sq_addafter.c
      @@ -0,0 +1,71 @@
      +/************************************************************
      + * lib/queue/sq_addafter.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: sq_addafter.c
      + *
      + * Description:
      + *  The sq_addafter function adds 'node' after 'prev' in the
      + *  'queue.'
      + *
      + ************************************************************/
      +
      +void sq_addafter(FAR sq_entry_t *prev, FAR sq_entry_t *node,
      +                 sq_queue_t *queue)
      +{
      +  if (!queue->head || prev == queue->tail)
      +    {
      +      sq_addlast(node, queue);
      +    }
      +  else
      +    {
      +      node->flink = prev->flink;
      +      prev->flink = node;
      +    }
      +}
      diff --git a/nuttx/lib/queue/sq_addfirst.c b/nuttx/lib/queue/sq_addfirst.c
      new file mode 100644
      index 0000000000..8fc8e06199
      --- /dev/null
      +++ b/nuttx/lib/queue/sq_addfirst.c
      @@ -0,0 +1,67 @@
      +/************************************************************
      + * lib/queue/sq_addfirst.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: sq_addfirst
      + *
      + * Description:
      + *   The sq_addfirst function places the 'node' at the head
      + *   of the 'queue'
      + *
      + ************************************************************/
      +
      +void sq_addfirst(FAR sq_entry_t *node, sq_queue_t *queue)
      +{
      +  node->flink = queue->head;
      +  if (!queue->head)
      +    {
      +      queue->tail = node;
      +    }
      +  queue->head = node;
      +}
      diff --git a/nuttx/lib/queue/sq_addlast.c b/nuttx/lib/queue/sq_addlast.c
      new file mode 100644
      index 0000000000..f9f9625cc0
      --- /dev/null
      +++ b/nuttx/lib/queue/sq_addlast.c
      @@ -0,0 +1,72 @@
      +/************************************************************
      + * lib/queue/sq_addlast.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: sq_addlast
      + *
      + * Description:
      + *   The sq_addlast function places the 'node' at the tail of
      + *   the 'queue'
      + ************************************************************/
      +
      +void sq_addlast(FAR sq_entry_t *node, sq_queue_t *queue)
      +{
      +  node->flink = NULL;
      +  if (!queue->head)
      +    {
      +      queue->head = node;
      +      queue->tail = node;
      +    }
      +  else
      +    {
      +      queue->tail->flink = node;
      +      queue->tail        = node;
      +    }
      +}
      +
      diff --git a/nuttx/lib/queue/sq_rem.c b/nuttx/lib/queue/sq_rem.c
      new file mode 100644
      index 0000000000..6ba52354d4
      --- /dev/null
      +++ b/nuttx/lib/queue/sq_rem.c
      @@ -0,0 +1,83 @@
      +/************************************************************
      + * lib/queue/sq_rem.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: sq_rem
      + *
      + * Description:
      + *   sq_rem removes a 'node' for 'queue.'
      + *
      + ************************************************************/
      +
      +void sq_rem(FAR sq_entry_t *node, sq_queue_t *queue)
      +{
      +  if (queue->head && node)
      +    {
      +      if (node == queue->head)
      +        {
      +          queue->head = node->flink;
      +          if (node == queue->tail)
      +            {
      +              queue->tail = NULL;
      +            }
      +        }
      +      else
      +        {
      +          FAR sq_entry_t *prev;
      +          for(prev = (FAR sq_entry_t*)queue->head;
      +              prev && prev->flink != node;
      +              prev = prev->flink);
      +
      +          if (prev)
      +            {
      +              sq_remafter(prev, queue);
      +            }
      +        }
      +    }
      +}
      diff --git a/nuttx/lib/queue/sq_remafter.c b/nuttx/lib/queue/sq_remafter.c
      new file mode 100644
      index 0000000000..4dcfb06e44
      --- /dev/null
      +++ b/nuttx/lib/queue/sq_remafter.c
      @@ -0,0 +1,79 @@
      +/************************************************************
      + * lib/queue/sq_remafter.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name:
      + *
      + * Description:
      + *   sq_remafter removes the entry following 'node; from the
      + *   'queue'  Returns a reference to the removed entry.
      + *
      + ************************************************************/
      +
      +FAR sq_entry_t *sq_remafter(FAR sq_entry_t *node, sq_queue_t *queue)
      +{
      +  FAR sq_entry_t *ret = node->flink;
      +  if (queue->head && ret)
      +    {
      +      if (queue->tail == ret)
      +        {
      +          queue->tail = node;
      +          node->flink = NULL;
      +        }
      +      else
      +        {
      +          node->flink = ret->flink;
      +        }
      +
      +      ret->flink = NULL;
      +    }
      +
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/queue/sq_remfirst.c b/nuttx/lib/queue/sq_remfirst.c
      new file mode 100644
      index 0000000000..43df6de417
      --- /dev/null
      +++ b/nuttx/lib/queue/sq_remfirst.c
      @@ -0,0 +1,76 @@
      +/************************************************************
      + * lib/queue/sq_remfirst.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: sq_remfirst
      + *
      + * Description:
      + *   sq_remfirst function removes the first entry from
      + *   'queue'
      + *
      + ************************************************************/
      +
      +FAR sq_entry_t *sq_remfirst(sq_queue_t *queue)
      +{
      +  FAR sq_entry_t *ret = queue->head;
      +
      +  if (ret)
      +    {
      +      queue->head = ret->flink;
      +      if (!queue->head)
      +        {
      +          queue->tail = NULL;
      +        }
      +
      +      ret->flink = NULL;
      +    }
      +
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/queue/sq_remlast.c b/nuttx/lib/queue/sq_remlast.c
      new file mode 100644
      index 0000000000..92cdbde985
      --- /dev/null
      +++ b/nuttx/lib/queue/sq_remlast.c
      @@ -0,0 +1,87 @@
      +/************************************************************
      + * lib/queue/sq_remlast.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +
      +/************************************************************
      + * Name: sq_remlast
      + *
      + * Description:
      + *   Removes the last entry in a singly-linked queue.
      + *
      + ************************************************************/
      +
      +FAR sq_entry_t *sq_remlast(sq_queue_t *queue)
      +{ 
      +  FAR sq_entry_t *ret = queue->tail;
      +
      +  if (ret)
      +    {
      +      if (queue->head == queue->tail)
      +        {
      +          queue->head = NULL;
      +          queue->tail = NULL;
      +        }
      +      else
      +        {
      +          FAR sq_entry_t *prev;
      +          for(prev = queue->head;
      +              prev && prev->flink != ret;
      +              prev = prev->flink);
      +
      +          if (prev)
      +            {
      +              prev->flink = NULL;
      +              queue->tail = prev;
      +            }
      +        }
      +
      +      ret->flink = NULL;
      +    }
      +
      +  return ret;
      +} 
      diff --git a/nuttx/lib/sched/Make.defs b/nuttx/lib/sched/Make.defs
      new file mode 100644
      index 0000000000..f398b755e0
      --- /dev/null
      +++ b/nuttx/lib/sched/Make.defs
      @@ -0,0 +1,43 @@
      +############################################################################
      +# lib/sched/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the sched C files to the build
      +
      +CSRCS += sched_getprioritymax.c sched_getprioritymin.c
      +
      +# Add the sched directory to the build
      +
      +DEPPATH += --dep-path sched
      +VPATH += :sched
      diff --git a/nuttx/lib/sched/sched_getprioritymax.c b/nuttx/lib/sched/sched_getprioritymax.c
      new file mode 100644
      index 0000000000..14b368dfc0
      --- /dev/null
      +++ b/nuttx/lib/sched/sched_getprioritymax.c
      @@ -0,0 +1,100 @@
      +/************************************************************************
      + * lib/sched/sched_getprioritymax.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Definitions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Type Declarations
      + ************************************************************************/
      +
      +/************************************************************************
      + * Global Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Function Prototypes
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Name:  ched_get_priority_max
      + *
      + * Description:
      + *   This function returns the value of the highest possible
      + *   task priority for a specified scheduling policy.
      + *
      + * Inputs:
      + *   policy - Scheduling policy requested.
      + *
      + * Return Value:
      + *   The maximum priority value or -1 (ERROR)
      + *   (errno is not set)
      + *
      + * Assumptions:
      + *
      + ************************************************************************/
      +
      +int sched_get_priority_max(int policy)
      +{
      +  if (policy != SCHED_FIFO && policy != SCHED_RR)
      +    {
      +      return ERROR;
      +    }
      +  else
      +    {
      +      return SCHED_PRIORITY_MAX;
      +    }
      +}
      diff --git a/nuttx/lib/sched/sched_getprioritymin.c b/nuttx/lib/sched/sched_getprioritymin.c
      new file mode 100644
      index 0000000000..86410cb0f6
      --- /dev/null
      +++ b/nuttx/lib/sched/sched_getprioritymin.c
      @@ -0,0 +1,100 @@
      +/************************************************************************
      + * lib/sched/sched_getprioritymin.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Definitions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Type Declarations
      + ************************************************************************/
      +
      +/************************************************************************
      + * Global Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Function Prototypes
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Name: sched_get_priority_min
      + *
      + * Description:
      + *   This function returns the value of the lowest possible
      + *   task priority for a specified scheduling policy.
      + *
      + * Inputs:
      + *   policy - Scheduling policy requested.
      + *
      + * Return Value:
      + *   The minimum priority value or -1 (ERROR)
      + *   (errno is not set)
      + *
      + * Assumptions:
      + *
      + ************************************************************************/
      +
      +int sched_get_priority_min(int policy)
      +{ 
      +  if (policy != SCHED_FIFO && policy != SCHED_RR)
      +    {
      +      return ERROR;
      +    }
      +  else
      +    {
      +      return SCHED_PRIORITY_MIN;
      +    }
      +}
      diff --git a/nuttx/lib/semaphore/Make.defs b/nuttx/lib/semaphore/Make.defs
      new file mode 100644
      index 0000000000..fdc0fe7d54
      --- /dev/null
      +++ b/nuttx/lib/semaphore/Make.defs
      @@ -0,0 +1,43 @@
      +############################################################################
      +# lib/semaphore/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the semaphore C files to the build
      +
      +CSRCS += sem_init.c sem_getvalue.c
      +
      +# Add the semaphore directory to the build
      +
      +DEPPATH += --dep-path semaphore
      +VPATH += :semaphore
      diff --git a/nuttx/lib/semaphore/sem_getvalue.c b/nuttx/lib/semaphore/sem_getvalue.c
      new file mode 100644
      index 0000000000..31c6bb7e06
      --- /dev/null
      +++ b/nuttx/lib/semaphore/sem_getvalue.c
      @@ -0,0 +1,108 @@
      +/****************************************************************************
      + * lib/semaphore/sem_getvalue.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  sem_getvalue
      + *
      + * Description:
      + *   This function updates the location referenced by 'sval' argument to
      + *   have the value of the semaphore referenced by 'sem' without effecting
      + *   the state of the semaphore.  The updated value represents the actual
      + *   semaphore value that occurred at some unspecified time during the call,
      + *   but may not reflect the actual value of the semaphore when it is
      + *   returned to the calling task.
      + *
      + *   If 'sem' is locked, the value return by sem_getvalue() will either be
      + *   zero or a negative number whose absolute value represents the number
      + *   of tasks waiting for the semaphore.
      + *
      + * Parameters:
      + *   sem - Semaphore descriptor
      + *   sval - Buffer by which the value is returned
      + *
      + * Return Value:
      + *   0 (OK), or -1 (ERROR) if unsuccessful
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int sem_getvalue(FAR sem_t *sem, FAR int *sval)
      +{
      +  if (sem && sval)
      +    {
      +      *sval = sem->semcount;
      +      return OK;
      +    }
      +  else
      +    {
      +      set_errno(EINVAL);
      +	  return ERROR;
      +    }
      +}
      diff --git a/nuttx/lib/semaphore/sem_init.c b/nuttx/lib/semaphore/sem_init.c
      new file mode 100644
      index 0000000000..bc14415f97
      --- /dev/null
      +++ b/nuttx/lib/semaphore/sem_init.c
      @@ -0,0 +1,125 @@
      +/****************************************************************************
      + * lib/sem/sem_init.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function: sem_init
      + *
      + * Description:
      + *   This function initializes the UNAMED semaphore sem. Following a
      + *   successful call to sem_init(), the semaophore may be used in subsequent
      + *   calls to sem_wait(), sem_post(), and sem_trywait().  The semaphore
      + *   remains usable until it is destroyed.
      + *
      + *   Only sem itself may be used for performing synchronization. The result
      + *   of referring to copies of sem in calls to sem_wait(), sem_trywait(),
      + *   sem_post(), and sem_destroy() is undefined.
      + *
      + * Parameters:
      + *   sem - Semaphore to be initialized
      + *   pshared - Process sharing (not used)
      + *   value - Semaphore initialization value
      + *
      + * Return Value:
      + *   0 (OK), or -1 (ERROR) if unsuccessful.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int sem_init(FAR sem_t *sem, int pshared, unsigned int value)
      +{
      +  /* Verify that a semaphore was provided and the count is within the valid
      +   * range.
      +   */
      +
      +  if (sem && value <= SEM_VALUE_MAX)
      +    {
      +      /* Initialize the seamphore count */
      +
      +      sem->semcount      = (int16_t)value;
      +
      +      /* Initialize to support priority inheritance */
      +
      +#ifdef CONFIG_PRIORITY_INHERITANCE
      +#  if CONFIG_SEM_PREALLOCHOLDERS > 0
      +      sem->hhead         = NULL;
      +#  else
      +      sem->holder.htcb   = NULL;
      +      sem->holder.counts = 0;
      +#  endif
      +#endif
      +      return OK;
      +    }
      +  else
      +    {
      +      set_errno(EINVAL);
      +      return ERROR;
      +    }
      +}
      diff --git a/nuttx/lib/signal/Make.defs b/nuttx/lib/signal/Make.defs
      new file mode 100644
      index 0000000000..e27da9b2e8
      --- /dev/null
      +++ b/nuttx/lib/signal/Make.defs
      @@ -0,0 +1,47 @@
      +############################################################################
      +# lib/signal/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +ifneq ($(CONFIG_DISABLE_SIGNALS),y)
      +
      +# Add the signal C files to the build
      +
      +CSRCS += sig_emptyset.c sig_fillset.c sig_addset.c sig_delset.c sig_ismember.c
      +
      +# Add the signal directory to the build
      +
      +DEPPATH += --dep-path signal
      +VPATH += :signal
      +
      +endif
      diff --git a/nuttx/lib/signal/sig_addset.c b/nuttx/lib/signal/sig_addset.c
      new file mode 100644
      index 0000000000..19ba0cb6b6
      --- /dev/null
      +++ b/nuttx/lib/signal/sig_addset.c
      @@ -0,0 +1,100 @@
      +/****************************************************************************
      + * lib/signal/sig_addset.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function: sigaddset
      + *
      + * Description:
      + *   This function adds the signal specified by signo to the signal set
      + *   specified by set.
      + *
      + * Parameters:
      + *   set - Signal set to add signal to
      + *   signo - Signal to add
      + *
      + * Return Value:
      + *   0 (OK), or -1 (ERROR) if the signal number is invalid.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int sigaddset(FAR sigset_t *set, int signo)
      +{
      +  int ret = ERROR;
      +
      +  /* Verify the signal */
      +
      +  if (GOOD_SIGNO(signo))
      +    {
      +      /* Add the signal to the set */
      +
      +      *set |= SIGNO2SET(signo);
      +      ret = OK;
      +    }
      +
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/signal/sig_delset.c b/nuttx/lib/signal/sig_delset.c
      new file mode 100644
      index 0000000000..1c661d37f6
      --- /dev/null
      +++ b/nuttx/lib/signal/sig_delset.c
      @@ -0,0 +1,100 @@
      +/****************************************************************************
      + * lib/signal/sig_delset.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function: sigdelset
      + *
      + * Description:
      + *   This function deletes the signal specified by signo from the signal
      + *   set specified by the 'set' argument.
      + *
      + * Parameters:
      + *   set - Signal set to delete the signal from
      + *   signo - Signal to delete
      + *
      + * Return Value:
      + *   0 (OK), or -1 (ERROR) if the signal number is invalid.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int sigdelset(FAR sigset_t *set, int signo)
      +{
      +  int ret = ERROR;
      +
      +  /* Verify the signal */
      +
      +  if (GOOD_SIGNO(signo))
      +    {
      +      /* Delete the signal to the set */
      +
      +      *set &= ~SIGNO2SET(signo);
      +      ret = OK;
      +    }
      +
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/signal/sig_emptyset.c b/nuttx/lib/signal/sig_emptyset.c
      new file mode 100644
      index 0000000000..ac0c6b3e89
      --- /dev/null
      +++ b/nuttx/lib/signal/sig_emptyset.c
      @@ -0,0 +1,88 @@
      +/****************************************************************************
      + * lib/signal/sig_emptyset.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function: sigemptyset
      + *
      + * Description:
      + *   This function initializes the signal set specified by set such that all
      + *   signals are excluded.
      + *
      + * Parameters:
      + *   set - Signal set to initalize
      + *
      + * Return Value:
      + *   0 (OK), or -1 (ERROR) if the signal set cannot be initialized.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int sigemptyset(FAR sigset_t *set)
      +{
      +  *set = NULL_SIGNAL_SET;
      +  return OK;
      +}
      +
      diff --git a/nuttx/lib/signal/sig_fillset.c b/nuttx/lib/signal/sig_fillset.c
      new file mode 100644
      index 0000000000..8697d7577f
      --- /dev/null
      +++ b/nuttx/lib/signal/sig_fillset.c
      @@ -0,0 +1,88 @@
      +/****************************************************************************
      + * lib/signal/sig_fillset.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Publics Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function: sigfillset
      + *
      + * Description:
      + *   This function initializes the signal set specified by set such that all
      + *   signals are included.
      + *
      + * Parameters:
      + *   set - Signal set to initalize
      + *
      + * Return Value:
      + *   0 (OK), or -1 (ERROR) if the signal set cannot be initialized.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int sigfillset(FAR sigset_t *set)
      +{
      +  *set = ALL_SIGNAL_SET;
      +  return OK;
      +}
      +
      diff --git a/nuttx/lib/signal/sig_ismember.c b/nuttx/lib/signal/sig_ismember.c
      new file mode 100644
      index 0000000000..c5bb091b7b
      --- /dev/null
      +++ b/nuttx/lib/signal/sig_ismember.c
      @@ -0,0 +1,101 @@
      +/****************************************************************************
      + * lib/signal/sig_ismember.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function: sigismember
      + *
      + * Description:
      + *   This function tests whether the signal specified by signo is a member
      + *   of the set specified by set.
      + *
      + * Parameters:
      + *   set - Signal set to test
      + *   signo - Signal to test for
      + *
      + * Return Value:
      + *   1 (true), if the specified signal is a member of the set,
      + *   0 (OK or FALSE), if it is not, or
      + *  -1 (ERROR) if the signal number is invalid.
      + *
      + * Assumptions:
      + *
      + ****************************************************************************/
      +
      +int sigismember(FAR const sigset_t *set, int signo)
      +{
      +  int ret = ERROR;
      +
      +  /* Verify the signal */
      +
      +  if (GOOD_SIGNO(signo))
      +    {
      +      /* Check if the signal is in the set */
      +
      +      ret = ((*set & SIGNO2SET(signo)) != 0);
      +    }
      +
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/stdio/Make.defs b/nuttx/lib/stdio/Make.defs
      new file mode 100644
      index 0000000000..e4ee5e9699
      --- /dev/null
      +++ b/nuttx/lib/stdio/Make.defs
      @@ -0,0 +1,85 @@
      +############################################################################
      +# lib/stdio/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the stdio C files to the build
      +# This first group of C files do not depend on having file descriptors or
      +# C streams.
      +
      +CSRCS += lib_fileno.c lib_printf.c lib_rawprintf.c lib_lowprintf.c \
      +		 lib_sprintf.c lib_asprintf.c lib_snprintf.c lib_libsprintf.c \
      +		 lib_vsprintf.c lib_avsprintf.c lib_vsnprintf.c lib_libvsprintf.c \
      +		 lib_meminstream.c lib_memoutstream.c lib_lowinstream.c \
      +		 lib_lowoutstream.c lib_zeroinstream.c lib_nullinstream.c \
      +		 lib_nulloutstream.c lib_sscanf.c
      +
      +# The remaining sources files depend upon file descriptors
      +
      +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
      +
      +CSRCS += lib_rawinstream.c lib_rawoutstream.c
      +
      +# And these depend upon both file descriptors and C streams
      +
      +ifneq ($(CONFIG_NFILE_STREAMS),0)
      +
      +CSRCS += lib_fopen.c lib_fclose.c lib_fread.c lib_libfread.c lib_fseek.c \
      +		 lib_ftell.c lib_fsetpos.c lib_fgetpos.c lib_fgetc.c lib_fgets.c \
      +		 lib_gets.c lib_fwrite.c lib_libfwrite.c lib_fflush.c \
      +		 lib_libflushall.c lib_libfflush.c lib_rdflush.c lib_wrflush.c \
      +		 lib_fputc.c lib_puts.c lib_fputs.c lib_ungetc.c lib_vprintf.c \
      +		 lib_fprintf.c lib_vfprintf.c lib_stdinstream.c lib_stdoutstream.c \
      +		 lib_perror.c lib_feof.c lib_ferror.c lib_clearerr.c
      +
      +endif
      +endif
      +
      +# Other support that depends on specific, configured features.
      +
      +ifeq ($(CONFIG_SYSLOG),y)
      +CSRCS += lib_syslogstream.c
      +endif
      +
      +ifeq ($(CONFIG_LIBC_FLOATINGPOINT),y)
      +CSRCS += lib_dtoa.c
      +endif
      +
      +ifeq ($(CONFIG_STDIO_LINEBUFFER),y)
      +CSRCS += lib_libnoflush.c
      +endif
      +
      +# Add the stdio directory to the build
      +
      +DEPPATH += --dep-path stdio
      +VPATH += :stdio
      diff --git a/nuttx/lib/stdio/lib_asprintf.c b/nuttx/lib/stdio/lib_asprintf.c
      new file mode 100644
      index 0000000000..84aaafa462
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_asprintf.c
      @@ -0,0 +1,105 @@
      +/****************************************************************************
      + * lib/stdio/lib_asprintf.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: asprintf
      + *
      + * Description:
      + *   This function is similar to sprintf, except that it dynamically
      + *   allocates a string (as with malloc) to hold the output, instead of
      + *   putting the output in a buffer you allocate in advance.  The ptr
      + *   argument should be the address of a char * object, and a successful
      + *   call to asprintf stores a pointer to the newly allocated string at that
      + *   location.
      + *
      + * Returned Value:
      + *   The returned value is the number of characters allocated for the buffer,
      + *   or less than zero if an error occurred. Usually this means that the buffer
      + *   could not be allocated.
      + *
      + ****************************************************************************/
      +
      +int asprintf (FAR char **ptr, const char *fmt, ...)
      +{
      +  va_list ap;
      +  int ret;
      +
      +  /* Let avsprintf do all of the work */
      +
      +  va_start(ap, fmt);
      +  ret = avsprintf(ptr, fmt, ap);
      +  va_end(ap);
      +
      +  return ret;
      +}
      diff --git a/nuttx/lib/stdio/lib_avsprintf.c b/nuttx/lib/stdio/lib_avsprintf.c
      new file mode 100644
      index 0000000000..8561b97c21
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_avsprintf.c
      @@ -0,0 +1,146 @@
      +/****************************************************************************
      + * lib/stdio/lib_avsprintf.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: avsprintf
      + *
      + * Description:
      + *   This function is similar to vsprintf, except that it dynamically
      + *   allocates a string (as with malloc) to hold the output, instead of
      + *   putting the output in a buffer you allocate in advance.  The ptr
      + *   argument should be the address of a char * object, and a successful
      + *   call to avsprintf stores a pointer to the newly allocated string at that
      + *   location.
      + *
      + * Returned Value:
      + *   The returned value is the number of characters allocated for the buffer,
      + *   or less than zero if an error occurred. Usually this means that the buffer
      + *   could not be allocated.
      + *
      + ****************************************************************************/
      +
      +int avsprintf(FAR char **ptr, const char *fmt, va_list ap)
      +{
      +  struct lib_outstream_s nulloutstream;
      +  struct lib_memoutstream_s memoutstream;
      +  FAR char *buf;
      +  int nbytes;
      +
      +  DEBUGASSERT(ptr && fmt);
      +
      +  /* First, use a nullstream to get the size of the buffer.  The number
      +   * of bytes returned may or may not include the null terminator.
      +   */
      +  
      +  lib_nulloutstream(&nulloutstream);
      +  nbytes = lib_vsprintf((FAR struct lib_outstream_s *)&nulloutstream, fmt, ap);
      +
      +  /* Then allocate a buffer to hold that number of characters, adding one
      +   * for the null terminator.
      +   */
      +
      +  buf = (FAR char *)malloc(nulloutstream.nput + 1);
      +  if (!buf)
      +    {
      +      return ERROR;
      +    }
      +
      +  /* Initialize a memory stream to write into the allocated buffer.  The
      +   * memory stream will reserve one byte at the end of the buffer for the
      +   * null terminator and will not report this in the number of output bytes.
      +   */
      +
      +  lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream,
      +                   buf, nulloutstream.nput + 1);
      +
      +  /* Then let lib_vsprintf do it's real thing */
      +
      +  nbytes = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, fmt, ap);
      +
      +  /* Return a pointer to the string to the caller.  NOTE: the memstream put()
      +   * method has already added the NUL terminator to the end of the string (not
      +   * included in the nput count).
      +   *
      +   * Hmmm.. looks like the memory would be stranded if lib_vsprintf() returned
      +   * an error.  Does that ever happen?
      +   */
      +
      +  DEBUGASSERT(nbytes < 0 || nbytes == nulloutstream.nput);
      +  *ptr = buf;
      +  return nbytes;
      +}
      diff --git a/nuttx/lib/stdio/lib_clearerr.c b/nuttx/lib/stdio/lib_clearerr.c
      new file mode 100644
      index 0000000000..7f7ded5bb4
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_clearerr.c
      @@ -0,0 +1,69 @@
      +/****************************************************************************
      + * lib/stdio/lib_clearerr.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +#if CONFIG_NFILE_STREAMS > 0
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: Functions
      + *
      + * Description:
      + *   Clear any end-of-file or error conditions.
      + *
      + * Returned Value:
      + *   None
      + *
      + ****************************************************************************/
      +
      +void clearerr(FILE *stream)
      +{
      +  stream->fs_flags = 0;
      +}
      +#endif /* CONFIG_NFILE_STREAMS */
      +
      diff --git a/nuttx/lib/stdio/lib_dtoa.c b/nuttx/lib/stdio/lib_dtoa.c
      new file mode 100644
      index 0000000000..b8c7db9803
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_dtoa.c
      @@ -0,0 +1,1641 @@
      +/****************************************************************************
      + * lib/stdio/lib_dtoa.c
      + *
      + * This file was ported to NuttX by Yolande Cates.
      + *
      + * Copyright (c) 1990, 1993
      + *      The Regents of the University of California.  All rights reserved.
      + *
      + * This code is derived from software contributed to Berkeley by
      + * Chris Torek.
      + *
      + * 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. All advertising materials mentioning features or use of this software
      + *    must display the following acknowledgement:
      + *      This product includes software developed by the University of
      + *      California, Berkeley and its contributors.
      + * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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 "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +#ifdef Unsigned_Shifts
      +#  define Sign_Extend(a,b) if (b < 0) a |= 0xffff0000;
      +#else
      +#  define Sign_Extend(a,b)      /* no-op */
      +#endif
      +
      +#ifdef CONFIG_ENDIAN_BIG
      +#  define word0(x) ((uint32_t *)&x)[0]
      +#  define word1(x) ((uint32_t *)&x)[1]
      +#else
      +#  define word0(x) ((uint32_t *)&x)[1]
      +#  define word1(x) ((uint32_t *)&x)[0]
      +#endif
      +
      +#ifdef CONFIG_ENDIAN_BIG
      +#  define Storeinc(a,b,c) (((unsigned short *)a)[0] = (unsigned short)b, \
      +                         ((unsigned short *)a)[1] = (unsigned short)c, a++)
      +#else
      +#  define Storeinc(a,b,c) (((unsigned short *)a)[1] = (unsigned short)b, \
      +                         ((unsigned short *)a)[0] = (unsigned short)c, a++)
      +#endif
      +
      +#define Exp_shift  20
      +#define Exp_shift1 20
      +#define Exp_msk1    0x100000
      +#define Exp_msk11   0x100000
      +#define Exp_mask  0x7ff00000
      +#define P 53
      +#define Bias 1023
      +#define IEEE_Arith
      +#define Emin (-1022)
      +#define Exp_1  0x3ff00000
      +#define Exp_11 0x3ff00000
      +#define Ebits 11
      +#define Frac_mask  0xfffff
      +#define Frac_mask1 0xfffff
      +#define Ten_pmax 22
      +#define Bletch 0x10
      +#define Bndry_mask  0xfffff
      +#define Bndry_mask1 0xfffff
      +#define LSB 1
      +#define Sign_bit 0x80000000
      +#define Log2P 1
      +#define Tiny0 0
      +#define Tiny1 1
      +#define Quick_max 14
      +#define Int_max 14
      +#define Infinite(x) (word0(x) == 0x7ff00000)    /* sufficient test for here */
      +
      +#define Kmax 15
      +
      +#define Bcopy(x,y) memcpy((char *)&x->sign, (char *)&y->sign, \
      +                          y->wds*sizeof(long) + 2*sizeof(int))
      +
      +/****************************************************************************
      + * Private Type Definitions
      + ****************************************************************************/
      +
      +struct Bigint
      +{
      +  struct Bigint *next;
      +  int k, maxwds, sign, wds;
      +  unsigned long x[1];
      +};
      +
      +typedef struct Bigint Bigint;
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      +
      +static Bigint *freelist[Kmax + 1];
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +static Bigint *Balloc(int k)
      +{
      +  int x;
      +  Bigint *rv;
      +
      +  if ((rv = freelist[k]))
      +    {
      +      freelist[k] = rv->next;
      +    }
      +  else
      +    {
      +      x = 1 << k;
      +      rv = (Bigint *)lib_malloc(sizeof(Bigint) + (x - 1) * sizeof(long));
      +      rv->k = k;
      +      rv->maxwds = x;
      +    }
      +  rv->sign = rv->wds = 0;
      +  return rv;
      +}
      +
      +static void Bfree(Bigint * v)
      +{
      +  if (v)
      +    {
      +      v->next = freelist[v->k];
      +      freelist[v->k] = v;
      +    }
      +}
      +
      +/* multiply by m and add a */
      +
      +static Bigint *multadd(Bigint * b, int m, int a)
      +{
      +  int i, wds;
      +  unsigned long *x, y;
      +#ifdef Pack_32
      +  unsigned long xi, z;
      +#endif
      +  Bigint *b1;
      +
      +  wds = b->wds;
      +  x = b->x;
      +  i = 0;
      +  do
      +    {
      +#ifdef Pack_32
      +      xi = *x;
      +      y = (xi & 0xffff) * m + a;
      +      z = (xi >> 16) * m + (y >> 16);
      +      a = (int)(z >> 16);
      +      *x++ = (z << 16) + (y & 0xffff);
      +#else
      +      y = *x * m + a;
      +      a = (int)(y >> 16);
      +      *x++ = y & 0xffff;
      +#endif
      +    }
      +  while (++i < wds);
      +  if (a)
      +    {
      +      if (wds >= b->maxwds)
      +        {
      +          b1 = Balloc(b->k + 1);
      +          Bcopy(b1, b);
      +          Bfree(b);
      +          b = b1;
      +        }
      +      b->x[wds++] = a;
      +      b->wds = wds;
      +    }
      +  return b;
      +}
      +
      +static int hi0bits(unsigned long x)
      +{
      +  int k = 0;
      +
      +  if (!(x & 0xffff0000))
      +    {
      +      k = 16;
      +      x <<= 16;
      +    }
      +
      +  if (!(x & 0xff000000))
      +    {
      +      k += 8;
      +      x <<= 8;
      +    }
      +
      +  if (!(x & 0xf0000000))
      +    {
      +      k += 4;
      +      x <<= 4;
      +    }
      +
      +  if (!(x & 0xc0000000))
      +    {
      +      k += 2;
      +      x <<= 2;
      +    }
      +
      +  if (!(x & 0x80000000))
      +    {
      +      k++;
      +      if (!(x & 0x40000000))
      +        {
      +          return 32;
      +        }
      +    }
      +  return k;
      +}
      +
      +static int lo0bits(unsigned long *y)
      +{
      +  int k;
      +  unsigned long x = *y;
      +
      +  if (x & 7)
      +    {
      +      if (x & 1)
      +        {
      +          return 0;
      +        }
      +      if (x & 2)
      +        {
      +          *y = x >> 1;
      +          return 1;
      +        }
      +      *y = x >> 2;
      +      return 2;
      +    }
      +
      +  k = 0;
      +  if (!(x & 0xffff))
      +    {
      +      k = 16;
      +      x >>= 16;
      +    }
      +
      +  if (!(x & 0xff))
      +    {
      +      k += 8;
      +      x >>= 8;
      +    }
      +
      +  if (!(x & 0xf))
      +    {
      +      k += 4;
      +      x >>= 4;
      +    }
      +
      +  if (!(x & 0x3))
      +    {
      +      k += 2;
      +      x >>= 2;
      +    }
      +
      +  if (!(x & 1))
      +    {
      +      k++;
      +      x >>= 1;
      +      if (!x & 1)
      +        {
      +          return 32;
      +        }
      +    }
      +  *y = x;
      +  return k;
      +}
      +
      +static Bigint *i2b(int i)
      +{
      +  Bigint *b;
      +
      +  b = Balloc(1);
      +  b->x[0] = i;
      +  b->wds = 1;
      +  return b;
      +}
      +
      +static Bigint *mult(Bigint * a, Bigint * b)
      +{
      +  Bigint *c;
      +  int k, wa, wb, wc;
      +  unsigned long carry, y, z;
      +  unsigned long *x, *xa, *xae, *xb, *xbe, *xc, *xc0;
      +#ifdef Pack_32
      +  uint32_t z2;
      +#endif
      +
      +  if (a->wds < b->wds)
      +    {
      +      c = a;
      +      a = b;
      +      b = c;
      +    }
      +
      +  k = a->k;
      +  wa = a->wds;
      +  wb = b->wds;
      +  wc = wa + wb;
      +  if (wc > a->maxwds)
      +    {
      +      k++;
      +    }
      +  c = Balloc(k);
      +  for (x = c->x, xa = x + wc; x < xa; x++)
      +    {
      +      *x = 0;
      +    }
      +  xa = a->x;
      +  xae = xa + wa;
      +  xb = b->x;
      +  xbe = xb + wb;
      +  xc0 = c->x;
      +#ifdef Pack_32
      +  for (; xb < xbe; xb++, xc0++)
      +    {
      +      if ((y = *xb & 0xffff))
      +        {
      +          x = xa;
      +          xc = xc0;
      +          carry = 0;
      +          do
      +            {
      +              z = (*x & 0xffff) * y + (*xc & 0xffff) + carry;
      +              carry = z >> 16;
      +              z2 = (*x++ >> 16) * y + (*xc >> 16) + carry;
      +              carry = z2 >> 16;
      +              Storeinc(xc, z2, z);
      +            }
      +          while (x < xae);
      +          *xc = carry;
      +        }
      +      if ((y = *xb >> 16))
      +        {
      +          x = xa;
      +          xc = xc0;
      +          carry = 0;
      +          z2 = *xc;
      +          do
      +            {
      +              z = (*x & 0xffff) * y + (*xc >> 16) + carry;
      +              carry = z >> 16;
      +              Storeinc(xc, z, z2);
      +              z2 = (*x++ >> 16) * y + (*xc & 0xffff) + carry;
      +              carry = z2 >> 16;
      +            }
      +          while (x < xae);
      +          *xc = z2;
      +        }
      +    }
      +#else
      +  for (; xb < xbe; xc0++)
      +    {
      +      if ((y = *xb++))
      +        {
      +          x = xa;
      +          xc = xc0;
      +          carry = 0;
      +          do
      +            {
      +              z = *x++ * y + *xc + carry;
      +              carry = z >> 16;
      +              *xc++ = z & 0xffff;
      +            }
      +          while (x < xae);
      +          *xc = carry;
      +        }
      +    }
      +#endif
      +  for (xc0 = c->x, xc = xc0 + wc; wc > 0 && !*--xc; --wc);
      +  c->wds = wc;
      +  return c;
      +}
      +
      +static Bigint *p5s;
      +
      +static Bigint *pow5mult(Bigint * b, int k)
      +{
      +  Bigint *b1, *p5, *p51;
      +  int i;
      +  static int p05[3] = { 5, 25, 125 };
      +
      +  if ((i = k & 3))
      +    b = multadd(b, p05[i - 1], 0);
      +
      +  if (!(k >>= 2))
      +    {
      +      return b;
      +    }
      +
      +  if (!(p5 = p5s))
      +    {
      +      /* first time */
      +      p5 = p5s = i2b(625);
      +      p5->next = 0;
      +    }
      +
      +  for (;;)
      +    {
      +      if (k & 1)
      +        {
      +          b1 = mult(b, p5);
      +          Bfree(b);
      +          b = b1;
      +        }
      +      if (!(k >>= 1))
      +        {
      +          break;
      +        }
      +
      +      if (!(p51 = p5->next))
      +        {
      +          p51 = p5->next = mult(p5, p5);
      +          p51->next = 0;
      +        }
      +      p5 = p51;
      +    }
      +  return b;
      +}
      +
      +static Bigint *lshift(Bigint * b, int k)
      +{
      +  int i, k1, n, n1;
      +  Bigint *b1;
      +  unsigned long *x, *x1, *xe, z;
      +
      +#ifdef Pack_32
      +  n = k >> 5;
      +#else
      +  n = k >> 4;
      +#endif
      +  k1 = b->k;
      +  n1 = n + b->wds + 1;
      +  for (i = b->maxwds; n1 > i; i <<= 1)
      +    {
      +      k1++;
      +    }
      +  b1 = Balloc(k1);
      +  x1 = b1->x;
      +  for (i = 0; i < n; i++)
      +    {
      +      *x1++ = 0;
      +    }
      +  x = b->x;
      +  xe = x + b->wds;
      +#ifdef Pack_32
      +  if (k &= 0x1f)
      +    {
      +      k1 = 32 - k;
      +      z = 0;
      +      do
      +        {
      +          *x1++ = *x << k | z;
      +          z = *x++ >> k1;
      +        }
      +      while (x < xe);
      +      if ((*x1 = z))
      +        {
      +          ++n1;
      +        }
      +    }
      +#else
      +  if (k &= 0xf)
      +    {
      +      k1 = 16 - k;
      +      z = 0;
      +      do
      +        {
      +          *x1++ = ((*x << k) & 0xffff) | z;
      +          z = *x++ >> k1;
      +        }
      +      while (x < xe);
      +      if ((*x1 = z))
      +        {
      +          ++n1;
      +        }
      +    }
      +#endif
      +  else
      +    do
      +      {
      +        *x1++ = *x++;
      +      }
      +    while (x < xe);
      +  b1->wds = n1 - 1;
      +  Bfree(b);
      +  return b1;
      +}
      +
      +static int cmp(Bigint * a, Bigint * b)
      +{
      +  unsigned long *xa, *xa0, *xb, *xb0;
      +  int i, j;
      +
      +  i = a->wds;
      +  j = b->wds;
      +#ifdef CONFIG_DEBUG_LIB
      +  if (i > 1 && !a->x[i - 1])
      +   {
      +    ldbg("cmp called with a->x[a->wds-1] == 0\n");
      +   }
      +  if (j > 1 && !b->x[j - 1])
      +   {
      +    ldbg("cmp called with b->x[b->wds-1] == 0\n");
      +   }
      +#endif
      +  if (i -= j)
      +    return i;
      +  xa0 = a->x;
      +  xa = xa0 + j;
      +  xb0 = b->x;
      +  xb = xb0 + j;
      +  for (;;)
      +    {
      +      if (*--xa != *--xb)
      +        return *xa < *xb ? -1 : 1;
      +      if (xa <= xa0)
      +        break;
      +    }
      +  return 0;
      +}
      +
      +static Bigint *diff(Bigint * a, Bigint * b)
      +{
      +  Bigint *c;
      +  int i, wa, wb;
      +  long borrow, y;               /* We need signed shifts here. */
      +  unsigned long *xa, *xae, *xb, *xbe, *xc;
      +#ifdef Pack_32
      +  int32_t z;
      +#endif
      +
      +  i = cmp(a, b);
      +  if (!i)
      +    {
      +      c = Balloc(0);
      +      c->wds = 1;
      +      c->x[0] = 0;
      +      return c;
      +    }
      +  if (i < 0)
      +    {
      +      c = a;
      +      a = b;
      +      b = c;
      +      i = 1;
      +    }
      +  else
      +    i = 0;
      +  c = Balloc(a->k);
      +  c->sign = i;
      +  wa = a->wds;
      +  xa = a->x;
      +  xae = xa + wa;
      +  wb = b->wds;
      +  xb = b->x;
      +  xbe = xb + wb;
      +  xc = c->x;
      +  borrow = 0;
      +#ifdef Pack_32
      +  do
      +    {
      +      y = (*xa & 0xffff) - (*xb & 0xffff) + borrow;
      +      borrow = y >> 16;
      +      Sign_Extend(borrow, y);
      +      z = (*xa++ >> 16) - (*xb++ >> 16) + borrow;
      +      borrow = z >> 16;
      +      Sign_Extend(borrow, z);
      +      Storeinc(xc, z, y);
      +    }
      +  while (xb < xbe);
      +  while (xa < xae)
      +    {
      +      y = (*xa & 0xffff) + borrow;
      +      borrow = y >> 16;
      +      Sign_Extend(borrow, y);
      +      z = (*xa++ >> 16) + borrow;
      +      borrow = z >> 16;
      +      Sign_Extend(borrow, z);
      +      Storeinc(xc, z, y);
      +    }
      +#else
      +  do
      +    {
      +      y = *xa++ - *xb++ + borrow;
      +      borrow = y >> 16;
      +      Sign_Extend(borrow, y);
      +      *xc++ = y & 0xffff;
      +    }
      +  while (xb < xbe);
      +  while (xa < xae)
      +    {
      +      y = *xa++ + borrow;
      +      borrow = y >> 16;
      +      Sign_Extend(borrow, y);
      +      *xc++ = y & 0xffff;
      +    }
      +#endif
      +  while (!*--xc)
      +    wa--;
      +  c->wds = wa;
      +  return c;
      +}
      +
      +static Bigint *d2b(double d, int *e, int *bits)
      +{
      +  Bigint *b;
      +  int de, i, k;
      +  unsigned long *x, y, z;
      +
      +#ifdef Pack_32
      +  b = Balloc(1);
      +#else
      +  b = Balloc(2);
      +#endif
      +  x = b->x;
      +
      +  z = word0(d) & Frac_mask;
      +  word0(d) &= 0x7fffffff;       /* clear sign bit, which we ignore */
      +  if ((de = (int)(word0(d) >> Exp_shift)))
      +    z |= Exp_msk1;
      +#ifdef Pack_32
      +  if ((y = word1(d)))
      +    {
      +      if ((k = lo0bits(&y)))
      +        {
      +          x[0] = y | z << (32 - k);
      +          z >>= k;
      +        }
      +      else
      +        x[0] = y;
      +      i = b->wds = (x[1] = z) ? 2 : 1;
      +    }
      +  else
      +    {
      +#ifdef CONFIG_DEBUG_LIB
      +      if (!z)
      +        {
      +          ldbg("Zero passed to d2b\n");
      +        }
      +#endif
      +      k = lo0bits(&z);
      +      x[0] = z;
      +      i = b->wds = 1;
      +      k += 32;
      +    }
      +#else
      +  if ((y = word1(d)))
      +    {
      +      if ((k = lo0bits(&y)))
      +        if (k >= 16)
      +          {
      +            x[0] = y | ((z << (32 - k)) & 0xffff);
      +            x[1] = z >> (k - 16) & 0xffff;
      +            x[2] = z >> k;
      +            i = 2;
      +          }
      +        else
      +          {
      +            x[0] = y & 0xffff;
      +            x[1] = (y >> 16) | ((z << (16 - k)) & 0xffff);
      +            x[2] = z >> k & 0xffff;
      +            x[3] = z >> (k + 16);
      +            i = 3;
      +          }
      +      else
      +        {
      +          x[0] = y & 0xffff;
      +          x[1] = y >> 16;
      +          x[2] = z & 0xffff;
      +          x[3] = z >> 16;
      +          i = 3;
      +        }
      +    }
      +  else
      +    {
      +#ifdef CONFIG_DEBUG_LIB
      +      if (!z)
      +        {
      +          ldbg("Zero passed to d2b\n");
      +        }
      +#endif
      +      k = lo0bits(&z);
      +      if (k >= 16)
      +        {
      +          x[0] = z;
      +          i = 0;
      +        }
      +      else
      +        {
      +          x[0] = z & 0xffff;
      +          x[1] = z >> 16;
      +          i = 1;
      +        }
      +      k += 32;
      +    }
      +  while (!x[i])
      +    --i;
      +  b->wds = i + 1;
      +#endif
      +  if (de)
      +    {
      +      *e = de - Bias - (P - 1) + k;
      +      *bits = P - k;
      +    }
      +  else
      +    {
      +      *e = de - Bias - (P - 1) + 1 + k;
      +#ifdef Pack_32
      +      *bits = 32 * i - hi0bits(x[i - 1]);
      +#else
      +      *bits = (i + 2) * 16 - hi0bits(x[i]);
      +#endif
      +    }
      +  return b;
      +}
      +
      +static const double tens[] = {
      +  1e0, 1e1, 1e2, 1e3, 1e4, 1e5, 1e6, 1e7, 1e8, 1e9,
      +  1e10, 1e11, 1e12, 1e13, 1e14, 1e15, 1e16, 1e17, 1e18, 1e19,
      +  1e20, 1e21, 1e22
      +};
      +
      +#ifdef IEEE_Arith
      +static const double bigtens[] = { 1e16, 1e32, 1e64, 1e128, 1e256 };
      +static const double tinytens[] = { 1e-16, 1e-32, 1e-64, 1e-128, 1e-256 };
      +
      +#  define n_bigtens 5
      +#else
      +static const double bigtens[] = { 1e16, 1e32 };
      +static const double tinytens[] = { 1e-16, 1e-32 };
      +
      +#  define n_bigtens 2
      +#endif
      +
      +static int quorem(Bigint * b, Bigint * S)
      +{
      +  int n;
      +  long borrow, y;
      +  unsigned long carry, q, ys;
      +  unsigned long *bx, *bxe, *sx, *sxe;
      +#ifdef Pack_32
      +  int32_t z;
      +  uint32_t si, zs;
      +#endif
      +
      +  n = S->wds;
      +#ifdef CONFIG_DEBUG_LIB
      +  if (b->wds > n)
      +    {
      +      ldbg("oversize b in quorem\n");
      +    }
      +#endif
      +  if (b->wds < n)
      +    {
      +      return 0;
      +    }
      +  sx = S->x;
      +  sxe = sx + --n;
      +  bx = b->x;
      +  bxe = bx + n;
      +  q = *bxe / (*sxe + 1);        /* ensure q <= true quotient */
      +#ifdef CONFIG_DEBUG_LIB
      +  if (q > 9)
      +   {
      +     ldbg("oversized quotient in quorem\n");
      +   }
      +#endif
      +  if (q)
      +    {
      +      borrow = 0;
      +      carry = 0;
      +      do
      +        {
      +#ifdef Pack_32
      +          si = *sx++;
      +          ys = (si & 0xffff) * q + carry;
      +          zs = (si >> 16) * q + (ys >> 16);
      +          carry = zs >> 16;
      +          y = (*bx & 0xffff) - (ys & 0xffff) + borrow;
      +          borrow = y >> 16;
      +          Sign_Extend(borrow, y);
      +          z = (*bx >> 16) - (zs & 0xffff) + borrow;
      +          borrow = z >> 16;
      +          Sign_Extend(borrow, z);
      +          Storeinc(bx, z, y);
      +#else
      +          ys = *sx++ * q + carry;
      +          carry = ys >> 16;
      +          y = *bx - (ys & 0xffff) + borrow;
      +          borrow = y >> 16;
      +          Sign_Extend(borrow, y);
      +          *bx++ = y & 0xffff;
      +#endif
      +        }
      +      while (sx <= sxe);
      +      if (!*bxe)
      +        {
      +          bx = b->x;
      +          while (--bxe > bx && !*bxe)
      +            --n;
      +          b->wds = n;
      +        }
      +    }
      +  if (cmp(b, S) >= 0)
      +    {
      +      q++;
      +      borrow = 0;
      +      carry = 0;
      +      bx = b->x;
      +      sx = S->x;
      +      do
      +        {
      +#ifdef Pack_32
      +          si = *sx++;
      +          ys = (si & 0xffff) + carry;
      +          zs = (si >> 16) + (ys >> 16);
      +          carry = zs >> 16;
      +          y = (*bx & 0xffff) - (ys & 0xffff) + borrow;
      +          borrow = y >> 16;
      +          Sign_Extend(borrow, y);
      +          z = (*bx >> 16) - (zs & 0xffff) + borrow;
      +          borrow = z >> 16;
      +          Sign_Extend(borrow, z);
      +          Storeinc(bx, z, y);
      +#else
      +          ys = *sx++ + carry;
      +          carry = ys >> 16;
      +          y = *bx - (ys & 0xffff) + borrow;
      +          borrow = y >> 16;
      +          Sign_Extend(borrow, y);
      +          *bx++ = y & 0xffff;
      +#endif
      +        }
      +      while (sx <= sxe);
      +      bx = b->x;
      +      bxe = bx + n;
      +      if (!*bxe)
      +        {
      +          while (--bxe > bx && !*bxe)
      +            --n;
      +          b->wds = n;
      +        }
      +    }
      +  return q;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/* dtoa for IEEE arithmetic (dmg): convert double to ASCII string.
      + *
      + * Inspired by "How to Print Floating-Point Numbers Accurately" by
      + * Guy L. Steele, Jr. and Jon L. White [Proc. ACM SIGPLAN '90, pp. 92-101].
      + *
      + * Modifications:
      + *      1. Rather than iterating, we use a simple numeric overestimate
      + *         to determine k = floor(log10(d)).  We scale relevant
      + *         quantities using O(log2(k)) rather than O(k) multiplications.
      + *      2. For some modes > 2 (corresponding to ecvt and fcvt), we don't
      + *         try to generate digits strictly left to right.  Instead, we
      + *         compute with fewer bits and propagate the carry if necessary
      + *         when rounding the final digit up.  This is often faster.
      + *      3. Under the assumption that input will be rounded nearest,
      + *         mode 0 renders 1e23 as 1e23 rather than 9.999999999999999e22.
      + *         That is, we allow equality in stopping tests when the
      + *         round-nearest rule will give the same floating-point value
      + *         as would satisfaction of the stopping test with strict
      + *         inequality.
      + *      4. We remove common factors of powers of 2 from relevant
      + *         quantities.
      + *      5. When converting floating-point integers less than 1e16,
      + *         we use floating-point arithmetic rather than resorting
      + *         to multiple-precision integers.
      + *      6. When asked to produce fewer than 15 digits, we first try
      + *         to get by with floating-point arithmetic; we resort to
      + *         multiple-precision integer arithmetic only if we cannot
      + *         guarantee that the floating-point calculation has given
      + *         the correctly rounded result.  For k requested digits and
      + *         "uniformly" distributed input, the probability is
      + *         something like 10^(k-15) that we must resort to the int32_t
      + *         calculation.
      + */
      +
      +char *__dtoa(double d, int mode, int ndigits, int *decpt, int *sign, char **rve)
      +{
      +  /* Arguments ndigits, decpt, sign are similar to those of ecvt and fcvt;
      +   * trailing zeros are suppressed from the returned string.  If not null, *rve 
      +   * is set to point to the end of the return value.  If d is +-Infinity or
      +   * NaN, then *decpt is set to 9999.
      +   * 
      +   * mode: 0 ==> shortest string that yields d when read in and rounded to
      +   * nearest. 1 ==> like 0, but with Steele & White stopping rule; e.g. with
      +   * IEEE P754 arithmetic , mode 0 gives 1e23 whereas mode 1 gives
      +   * 9.999999999999999e22. 2 ==> max(1,ndigits) significant digits.  This gives 
      +   * a return value similar to that of ecvt, except that trailing zeros are
      +   * suppressed. 3 ==> through ndigits past the decimal point.  This gives a
      +   * return value similar to that from fcvt, except that trailing zeros are
      +   * suppressed, and ndigits can be negative. 4-9 should give the same return
      +   * values as 2-3, i.e., 4 <= mode <= 9 ==> same return as mode 2 + (mode &
      +   * 1).  These modes are mainly for debugging; often they run slower but
      +   * sometimes faster than modes 2-3. 4,5,8,9 ==> left-to-right digit
      +   * generation. 6-9 ==> don't try fast floating-point estimate (if
      +   * applicable).
      +   * 
      +   * Values of mode other than 0-9 are treated as mode 0.
      +   * 
      +   * Sufficient space is allocated to the return value to hold the suppressed
      +   * trailing zeros. */
      +
      +  int bbits, b2, b5, be, dig, i, ieps, ilim = 0, ilim0, ilim1 = 0,
      +    j, j_1, k, k0, k_check, leftright, m2, m5, s2, s5, spec_case = 0, try_quick;
      +  long L;
      +  int denorm;
      +  unsigned long x;
      +  Bigint *b, *b1, *delta, *mlo = NULL, *mhi, *S;
      +  double d2, ds, eps;
      +  char *s, *s0;
      +  static Bigint *result;
      +  static int result_k;
      +
      +  if (result)
      +    {
      +      result->k = result_k;
      +      result->maxwds = 1 << result_k;
      +      Bfree(result);
      +      result = 0;
      +    }
      +
      +  if (word0(d) & Sign_bit)
      +    {
      +      /* set sign for everything, including 0's and NaNs */
      +      *sign = 1;
      +      word0(d) &= ~Sign_bit;    /* clear sign bit */
      +    }
      +  else
      +    {
      +      *sign = 0;
      +    }
      +
      +#if defined(IEEE_Arith)
      +#  ifdef IEEE_Arith
      +  if ((word0(d) & Exp_mask) == Exp_mask)
      +#else
      +  if (word0(d) == 0x8000)
      +#endif
      +    {
      +      /* Infinity or NaN */
      +      *decpt = 9999;
      +      s =
      +#ifdef IEEE_Arith
      +        !word1(d) && !(word0(d) & 0xfffff) ? "Infinity" :
      +#endif
      +        "NaN";
      +      if (rve)
      +        *rve =
      +#ifdef IEEE_Arith
      +          s[3] ? s + 8 :
      +#endif
      +          s + 3;
      +      return s;
      +    }
      +#endif
      +  if (!d)
      +    {
      +      *decpt = 1;
      +      s = "0";
      +      if (rve)
      +        *rve = s + 1;
      +      return s;
      +    }
      +
      +  b = d2b(d, &be, &bbits);
      +  if ((i = (int)(word0(d) >> Exp_shift1 & (Exp_mask >> Exp_shift1))))
      +    {
      +      d2 = d;
      +      word0(d2) &= Frac_mask1;
      +      word0(d2) |= Exp_11;
      +
      +      /* log(x) ~=~ log(1.5) + (x-1.5)/1.5 log10(x) = log(x) / log(10) ~=~
      +       * log(1.5)/log(10) + (x-1.5)/(1.5*log(10)) log10(d) =
      +       * (i-Bias)*log(2)/log(10) + log10(d2) This suggests computing an
      +       * approximation k to log10(d) by k = (i - Bias)*0.301029995663981 + (
      +       * (d2-1.5)*0.289529654602168 + 0.176091259055681 ); We want k to be too 
      +       * large rather than too small. The error in the first-order Taylor
      +       * series approximation is in our favor, so we just round up the constant 
      +       * enough to compensate for any error in the multiplication of (i - Bias) 
      +       * by 0.301029995663981; since |i - Bias| <= 1077, and 1077 * 0.30103 *
      +       * 2^-52 ~=~ 7.2e-14, adding 1e-13 to the constant term more than
      +       * suffices. Hence we adjust the constant term to 0.1760912590558. (We
      +       * could get a more accurate k by invoking log10, but this is probably
      +       * not worthwhile.) */
      +
      +      i -= Bias;
      +      denorm = 0;
      +    }
      +  else
      +    {
      +      /* d is denormalized */
      +
      +      i = bbits + be + (Bias + (P - 1) - 1);
      +      x = i > 32 ? word0(d) << (64 - i) | word1(d) >> (i - 32)
      +        : word1(d) << (32 - i);
      +      d2 = x;
      +      word0(d2) -= 31 * Exp_msk1;       /* adjust exponent */
      +      i -= (Bias + (P - 1) - 1) + 1;
      +      denorm = 1;
      +    }
      +
      +  ds = (d2 - 1.5) * 0.289529654602168 + 0.1760912590558 + i * 0.301029995663981;
      +  k = (int)ds;
      +  if (ds < 0. && ds != k)
      +    {
      +      k--;  /* want k = floor(ds) */
      +    }
      +  k_check = 1;
      +
      +  if (k >= 0 && k <= Ten_pmax)
      +    {
      +      if (d < tens[k])
      +        k--;
      +      k_check = 0;
      +    }
      +
      +  j = bbits - i - 1;
      +  if (j >= 0)
      +    {
      +      b2 = 0;
      +      s2 = j;
      +    }
      +  else
      +    {
      +      b2 = -j;
      +      s2 = 0;
      +    }
      +
      +  if (k >= 0)
      +    {
      +      b5 = 0;
      +      s5 = k;
      +      s2 += k;
      +    }
      +  else
      +    {
      +      b2 -= k;
      +      b5 = -k;
      +      s5 = 0;
      +    }
      +
      +  if (mode < 0 || mode > 9)
      +    {
      +      mode = 0;
      +    }
      +
      +  try_quick = 1;
      +  if (mode > 5)
      +    {
      +      mode -= 4;
      +      try_quick = 0;
      +    }
      +
      +  leftright = 1;
      +  switch (mode)
      +    {
      +    case 0:
      +    case 1:
      +      ilim = ilim1 = -1;
      +      i = 18;
      +      ndigits = 0;
      +      break;
      +
      +    case 2:
      +      leftright = 0;
      +      /* no break */
      +    case 4:
      +      if (ndigits <= 0)
      +        {
      +          ndigits = 1;
      +        }
      +
      +      ilim = ilim1 = i = ndigits;
      +      break;
      +
      +    case 3:
      +      leftright = 0;
      +      /* no break */
      +    case 5:
      +      i = ndigits + k + 1;
      +      ilim = i;
      +      ilim1 = i - 1;
      +      if (i <= 0)
      +        {
      +          i = 1;
      +        }
      +    }
      +
      +  j = sizeof(unsigned long);
      +  for (result_k = 0;
      +       (signed)(sizeof(Bigint) - sizeof(unsigned long) + j) <= i;
      +       j <<= 1)
      +    {
      +      result_k++;
      +    }
      +
      +  result = Balloc(result_k);
      +  s = s0 = (char *)result;
      +
      +  if (ilim >= 0 && ilim <= Quick_max && try_quick)
      +    {
      +      /* Try to get by with floating-point arithmetic. */
      +
      +      i = 0;
      +      d2 = d;
      +      k0 = k;
      +      ilim0 = ilim;
      +      ieps = 2;                 /* conservative */
      +
      +      if (k > 0)
      +        {
      +          ds = tens[k & 0xf];
      +          j = k >> 4;
      +
      +          if (j & Bletch)
      +            {
      +              /* prevent overflows */
      +              j &= Bletch - 1;
      +              d /= bigtens[n_bigtens - 1];
      +              ieps++;
      +            }
      +
      +          for (; j; j >>= 1, i++)
      +            {
      +              if (j & 1)
      +                {
      +                  ieps++;
      +                  ds *= bigtens[i];
      +                }
      +            }
      +
      +          d /= ds;
      +        }
      +      else if ((j_1 = -k))
      +        {
      +          d *= tens[j_1 & 0xf];
      +          for (j = j_1 >> 4; j; j >>= 1, i++)
      +            {
      +              if (j & 1)
      +                {
      +                  ieps++;
      +                  d *= bigtens[i];
      +                }
      +            }
      +        }
      +
      +      if (k_check && d < 1. && ilim > 0)
      +        {
      +          if (ilim1 <= 0)
      +            {
      +              goto fast_failed;
      +            }
      +
      +          ilim = ilim1;
      +          k--;
      +          d *= 10.;
      +          ieps++;
      +        }
      +
      +      eps = ieps * d + 7.;
      +      word0(eps) -= (P - 1) * Exp_msk1;
      +      if (ilim == 0)
      +        {
      +          S = mhi = 0;
      +          d -= 5.;
      +          if (d > eps)
      +            goto one_digit;
      +          if (d < -eps)
      +            goto no_digits;
      +          goto fast_failed;
      +        }
      +
      +#ifndef No_leftright
      +      if (leftright)
      +        {
      +          /* Use Steele & White method of only generating digits needed. */
      +
      +          eps = 0.5 / tens[ilim - 1] - eps;
      +          for (i = 0;;)
      +            {
      +              L = (int)d;
      +              d -= L;
      +              *s++ = '0' + (int)L;
      +              if (d < eps)
      +                goto ret1;
      +              if (1. - d < eps)
      +                goto bump_up;
      +              if (++i >= ilim)
      +                break;
      +              eps *= 10.;
      +              d *= 10.;
      +            }
      +        }
      +      else
      +        {
      +#endif
      +          /* Generate ilim digits, then fix them up. */
      +          
      +          eps *= tens[ilim - 1];
      +          for (i = 1;; i++, d *= 10.)
      +            {
      +              L = (int)d;
      +              d -= L;
      +              *s++ = '0' + (int)L;
      +              if (i == ilim)
      +                {
      +                  if (d > 0.5 + eps)
      +                    goto bump_up;
      +                  else if (d < 0.5 - eps)
      +                    {
      +                      while (*--s == '0');
      +                      s++;
      +                      goto ret1;
      +                    }
      +                  break;
      +                }
      +            }
      +#ifndef No_leftright
      +        }
      +#endif
      +    fast_failed:
      +      s = s0;
      +      d = d2;
      +      k = k0;
      +      ilim = ilim0;
      +    }
      +
      +  /* Do we have a "small" integer? */
      +
      +  if (be >= 0 && k <= Int_max)
      +    {
      +      /* Yes. */
      +
      +      ds = tens[k];
      +      if (ndigits < 0 && ilim <= 0)
      +        {
      +          S = mhi = 0;
      +          if (ilim < 0 || d <= 5 * ds)
      +            goto no_digits;
      +          goto one_digit;
      +        }
      +
      +      for (i = 1;; i++)
      +        {
      +          L = (int)(d / ds);
      +          d -= L * ds;
      +#ifdef Check_FLT_ROUNDS
      +          /* If FLT_ROUNDS == 2, L will usually be high by 1 */
      +          if (d < 0)
      +            {
      +              L--;
      +              d += ds;
      +            }
      +#endif
      +          *s++ = '0' + (int)L;
      +          if (i == ilim)
      +            {
      +              d += d;
      +              if (d > ds || (d == ds && (L & 1)))
      +                {
      +                bump_up:
      +                  while (*--s == '9')
      +                    if (s == s0)
      +                      {
      +                        k++;
      +                        *s = '0';
      +                        break;
      +                      }
      +                  ++*s++;
      +                }
      +              break;
      +            }
      +          if (!(d *= 10.))
      +            {
      +              break;
      +            }
      +        }
      +
      +      goto ret1;
      +    }
      +
      +  m2 = b2;
      +  m5 = b5;
      +  mhi = mlo = 0;
      +  if (leftright)
      +    {
      +      if (mode < 2)
      +        {
      +          i = denorm ? be + (Bias + (P - 1) - 1 + 1) : 1 + P - bbits;
      +        }
      +      else
      +        {
      +          j = ilim - 1;
      +          if (m5 >= j)
      +            m5 -= j;
      +          else
      +            {
      +              s5 += j -= m5;
      +              b5 += j;
      +              m5 = 0;
      +            }
      +          if ((i = ilim) < 0)
      +            {
      +              m2 -= i;
      +              i = 0;
      +            }
      +        }
      +
      +      b2 += i;
      +      s2 += i;
      +      mhi = i2b(1);
      +    }
      +
      +  if (m2 > 0 && s2 > 0)
      +    {
      +      i = m2 < s2 ? m2 : s2;
      +      b2 -= i;
      +      m2 -= i;
      +      s2 -= i;
      +    }
      +
      +  if (b5 > 0)
      +    {
      +      if (leftright)
      +        {
      +          if (m5 > 0)
      +            {
      +              mhi = pow5mult(mhi, m5);
      +              b1 = mult(mhi, b);
      +              Bfree(b);
      +              b = b1;
      +            }
      +          if ((j = b5 - m5))
      +            b = pow5mult(b, j);
      +        }
      +      else
      +        {
      +          b = pow5mult(b, b5);
      +        }
      +    }
      +
      +  S = i2b(1);
      +  if (s5 > 0)
      +    {
      +      S = pow5mult(S, s5);
      +    }
      +
      +  /* Check for special case that d is a normalized power of 2. */
      +
      +  if (mode < 2)
      +    {
      +      if (!word1(d) && !(word0(d) & Bndry_mask) && word0(d) & Exp_mask)
      +        {
      +          /* The special case */
      +          b2 += Log2P;
      +          s2 += Log2P;
      +          spec_case = 1;
      +        }
      +      else
      +        {
      +          spec_case = 0;
      +        }
      +    }
      +
      +  /* Arrange for convenient computation of quotients: shift left if
      +   * necessary so divisor has 4 leading 0 bits.
      +   *
      +   * Perhaps we should just compute leading 28 bits of S once and for all
      +   * and pass them and a shift to quorem, so it can do shifts and ors
      +   * to compute the numerator for q.
      +   */
      +
      +#ifdef Pack_32
      +  if ((i = ((s5 ? 32 - hi0bits(S->x[S->wds - 1]) : 1) + s2) & 0x1f))
      +    {
      +      i = 32 - i;
      +    }
      +#else
      +  if ((i = ((s5 ? 32 - hi0bits(S->x[S->wds - 1]) : 1) + s2) & 0xf))
      +    {
      +      i = 16 - i;
      +    }
      +#endif
      +
      +  if (i > 4)
      +    {
      +      i -= 4;
      +      b2 += i;
      +      m2 += i;
      +      s2 += i;
      +    }
      +  else if (i < 4)
      +    {
      +      i += 28;
      +      b2 += i;
      +      m2 += i;
      +      s2 += i;
      +    }
      +
      +  if (b2 > 0)
      +    {
      +      b = lshift(b, b2);
      +    }
      +
      +  if (s2 > 0)
      +    {
      +      S = lshift(S, s2);
      +    }
      +
      +  if (k_check)
      +    {
      +      if (cmp(b, S) < 0)
      +        {
      +          k--;
      +          b = multadd(b, 10, 0);        /* we botched the k estimate */
      +          if (leftright)
      +            {
      +              mhi = multadd(mhi, 10, 0);
      +            }
      +
      +          ilim = ilim1;
      +        }
      +    }
      +
      +  if (ilim <= 0 && mode > 2)
      +    {
      +      if (ilim < 0 || cmp(b, S = multadd(S, 5, 0)) <= 0)
      +        {
      +          /* no digits, fcvt style */
      +        no_digits:
      +          k = -1 - ndigits;
      +          goto ret;
      +        }
      +    one_digit:
      +      *s++ = '1';
      +      k++;
      +      goto ret;
      +    }
      +
      +  if (leftright)
      +    {
      +      if (m2 > 0)
      +        {
      +          mhi = lshift(mhi, m2);
      +        }
      +
      +      /* Compute mlo -- check for special case that d is a normalized power of
      +       * 2. */
      +
      +      mlo = mhi;
      +      if (spec_case)
      +        {
      +          mhi = Balloc(mhi->k);
      +          Bcopy(mhi, mlo);
      +          mhi = lshift(mhi, Log2P);
      +        }
      +
      +      for (i = 1;; i++)
      +        {
      +          dig = quorem(b, S) + '0';
      +          /* Do we yet have the shortest decimal string that will round to d? */
      +          j = cmp(b, mlo);
      +          delta = diff(S, mhi);
      +          j_1 = delta->sign ? 1 : cmp(b, delta);
      +          Bfree(delta);
      +#ifndef ROUND_BIASED
      +          if (j_1 == 0 && !mode && !(word1(d) & 1))
      +            {
      +              if (dig == '9')
      +                {
      +                 goto round_9_up;
      +                }
      +
      +              if (j > 0)
      +                {
      +                  dig++;
      +                }
      +
      +              *s++ = dig;
      +              goto ret;
      +            }
      +#endif
      +          if (j < 0 || (j == 0 && !mode
      +#ifndef ROUND_BIASED
      +                        && (!(word1(d) & 1))
      +#endif
      +            ))
      +            {
      +              if ((j_1 > 0))
      +                {
      +                  b = lshift(b, 1);
      +                  j_1 = cmp(b, S);
      +                  if ((j_1 > 0 || (j_1 == 0 && (dig & 1))) && dig++ == '9')
      +                    {
      +                      goto round_9_up;
      +                    }
      +                }
      +
      +              *s++ = dig;
      +              goto ret;
      +            }
      +
      +          if (j_1 > 0)
      +            {
      +              if (dig == '9')
      +                {               /* possible if i == 1 */
      +                round_9_up:
      +                  *s++ = '9';
      +                  goto roundoff;
      +                }
      +
      +              *s++ = dig + 1;
      +              goto ret;
      +            }
      +
      +          *s++ = dig;
      +          if (i == ilim)
      +            {
      +              break;
      +            }
      +
      +          b = multadd(b, 10, 0);
      +          if (mlo == mhi)
      +            {
      +              mlo = mhi = multadd(mhi, 10, 0);
      +            }
      +          else
      +            {
      +              mlo = multadd(mlo, 10, 0);
      +              mhi = multadd(mhi, 10, 0);
      +            }
      +        }
      +    }
      +  else
      +    {
      +      for (i = 1;; i++)
      +        {
      +          *s++ = dig = quorem(b, S) + '0';
      +          if (i >= ilim)
      +            {
      +              break;
      +            }
      +
      +          b = multadd(b, 10, 0);
      +        }
      +    }
      +
      +  /* Round off last digit */
      +
      +  b = lshift(b, 1);
      +  j = cmp(b, S);
      +  if (j > 0 || (j == 0 && (dig & 1)))
      +    {
      +    roundoff:
      +      while (*--s == '9')
      +        if (s == s0)
      +          {
      +            k++;
      +            *s++ = '1';
      +            goto ret;
      +          }
      +      ++*s++;
      +    }
      +  else
      +    {
      +      while (*--s == '0');
      +      s++;
      +    }
      +
      +ret:
      +  Bfree(S);
      +  if (mhi)
      +    {
      +      if (mlo && mlo != mhi)
      +        {
      +          Bfree(mlo);
      +        }
      +
      +      Bfree(mhi);
      +    }
      +ret1:
      +  Bfree(b);
      +  if (s == s0)
      +    {                           /* don't return empty string */
      +      *s++ = '0';
      +      k = 0;
      +    }
      +
      +  *s = 0;
      +  *decpt = k + 1;
      +  if (rve)
      +    {
      +      *rve = s;
      +    }
      +
      +  return s0;
      +}
      diff --git a/nuttx/lib/stdio/lib_fclose.c b/nuttx/lib/stdio/lib_fclose.c
      new file mode 100644
      index 0000000000..8cecb8af3c
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fclose.c
      @@ -0,0 +1,154 @@
      +/****************************************************************************
      + * lib/stdio/lib_fclose.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fclose
      + *
      + * Description
      + *   The fclose() function will flush the stream pointed to by stream
      + *   (writing any buffered output data using lib_fflush()) and close the
      + *   underlying file descriptor.
      + *
      + * Returned Value:
      + *   Upon successful completion 0 is returned. Otherwise, EOF is returned
      + *   and the global variable errno is set to indicate the error. In either
      + *   case any further access (including another call to fclose()) to the
      + *   stream results in undefined behaviour.
      + *
      + ****************************************************************************/
      +
      +int fclose(FAR FILE *stream)
      +{
      +  int err = EINVAL;
      +  int ret = ERROR;
      +  int status;
      +
      +  /* Verify that a stream was provided. */
      +
      +  if (stream)
      +    {
      +      /* Check that the underlying file descriptor corresponds to an an open
      +       * file.
      +       */
      + 
      +      ret = OK;
      +      if (stream->fs_filedes >= 0)
      +        {
      +          /* If the stream was opened for writing, then flush the stream */
      +
      +          if ((stream->fs_oflags & O_WROK) != 0)
      +            {
      +              ret = lib_fflush(stream, true);
      +              err = errno;
      +            }
      +
      +          /* Close the underlying file descriptor and save the return status */
      +
      +          status = close(stream->fs_filedes);
      +
      +          /* If close() returns an error but flush() did not then make sure
      +           * that we return the close() error condition.
      +           */
      +
      +          if (ret == OK)
      +            {
      +              ret = status;
      +              err = errno;
      +            }
      +        }
      +
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +      /* Destroy the semaphore */
      +
      +      sem_destroy(&stream->fs_sem);
      +
      +      /* Release the buffer */
      +
      +      if (stream->fs_bufstart)
      +        {
      +          lib_free(stream->fs_bufstart);
      +        }
      +
      +      /* Clear the whole structure */
      +
      +      memset(stream, 0, sizeof(FILE));
      +#else
      +#if CONFIG_NUNGET_CHARS > 0
      +      /* Reset the number of ungetc characters */
      +
      +      stream->fs_nungotten = 0;
      +#endif
      +      /* Reset the flags */
      +
      +      stream->fs_oflags = 0;
      +#endif
      +      /* Setting the fs_filedescriptor to -1 makes the stream available for reuse */
      +
      +      stream->fs_filedes = -1;
      +    }
      +
      +  /* On an error, reset the errno to the first error encountered and return
      +   * EOF.
      +   */
      +
      +  if (ret != OK)
      +    {
      +      set_errno(err);
      +      return EOF;
      +    }
      +
      +  /* Return success */
      +
      +  return OK;
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_feof.c b/nuttx/lib/stdio/lib_feof.c
      new file mode 100644
      index 0000000000..e44c6a3c92
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_feof.c
      @@ -0,0 +1,77 @@
      +/****************************************************************************
      + * lib/stdio/lib_feof.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +#if CONFIG_NFILE_STREAMS > 0
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: feof
      + *
      + * Description:
      + *   The feof() function shall test if the currently file pointer for the
      + *   stream is at the end of file.
      + *
      + * Returned Value:
      + *  This function will return non-zero if the the file pointer is positioned
      + *  at the end of file.
      + *
      + ****************************************************************************/
      +
      +int feof(FILE *stream)
      +{
      +  /* If the end-of-file condition is encountered by any of the C-buffered
      +   * I/O functions that perform read operations, they should set the
      +   * __FS_FLAG_EOF in the fs_flags field of struct file_struct.
      +   */
      +
      +  return (stream->fs_flags & __FS_FLAG_EOF) != 0;
      +}
      +
      +#endif /* CONFIG_NFILE_STREAMS */
      +
      diff --git a/nuttx/lib/stdio/lib_ferror.c b/nuttx/lib/stdio/lib_ferror.c
      new file mode 100644
      index 0000000000..4ad7d8cfca
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_ferror.c
      @@ -0,0 +1,90 @@
      +/****************************************************************************
      + * lib/stdio/lib_ferror.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +#if CONFIG_NFILE_STREAMS > 0
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: ferror
      + *
      + * Description:
      + *   This function will test if the last operation resulted in an eror.  This
      + *   is used to disambiguate EOF and error conditions.
      + *
      + * Return Value:
      + *   A non-zero value is returned to indicate the error condition.
      + *
      + ****************************************************************************/
      +
      +int ferror(FILE *stream)
      +{
      +#if 0
      +  /* If an error is encountered by any of the C-buffered I/O functions, they
      +   * should set the __FS_FLAG_ERROR in the fs_flags field of struct
      +   * file_struct.
      +   */
      +
      +  return (stream->fs_flags & __FS_FLAG_ERROR) != 0;
      +#else
      +  /* However, nothing currenlty sets the __FS_FLAG_ERROR flag (that is a job
      +   * for another day).  The __FS_FLAG_EOF is set by operations that perform
      +   * read operations.  Since ferror()  is probably only called to disambiguate
      +   * the meaning of other functions that return EOF, to indicate either EOF or
      +   * an error, just testing for not EOF is probably sufficient for now.
      +   *
      +   * This approach would not work if ferror() is called in other contexts. In
      +   * those cases, ferror() will always report an error.
      +   */
      +
      +  return (stream->fs_flags & __FS_FLAG_EOF) == 0;
      +#endif
      +}
      +
      +#endif /* CONFIG_NFILE_STREAMS */
      +
      diff --git a/nuttx/lib/stdio/lib_fflush.c b/nuttx/lib/stdio/lib_fflush.c
      new file mode 100644
      index 0000000000..d0b5e0185d
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fflush.c
      @@ -0,0 +1,132 @@
      +/****************************************************************************
      + * lib/stdio/lib_fflush.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fflush
      + *
      + * Description:
      + *  The function fflush() forces a write of all user-space buffered data for
      + *  the given output or update stream via the stream's underlying write
      + *  function.  The open status of the stream is unaffected.
      + *
      + *  If the stream argument is NULL, fflush() flushes all open output streams.
      + *
      + * Return:
      + *  OK on success EOF on failure (with errno set appropriately)
      + *
      + ****************************************************************************/
      +
      +int fflush(FAR FILE *stream)
      +{
      +  int ret;
      +
      +  /* Is the stream argument NULL? */
      +
      +  if (!stream)
      +    {
      +      /* Yes... then this is a request to flush all streams */
      +
      +      ret = lib_flushall(sched_getstreams());
      +    }
      +  else
      +    {
      +      ret = lib_fflush(stream, true);
      +    }
      +
      +  /* Check the return value */
      +
      +  if (ret < 0)
      +    {
      +      /* An error occurred during the flush AND/OR we were unable to flush
      +       * all of the buffered write data. Set the errno value.
      +       */
      +
      +      set_errno(-ret);
      +
      +      /* And return EOF on failure. */
      +
      +      return EOF;
      +    }
      +
      +  return OK;
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_fgetc.c b/nuttx/lib/stdio/lib_fgetc.c
      new file mode 100644
      index 0000000000..4b3d0ec44f
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fgetc.c
      @@ -0,0 +1,101 @@
      +/****************************************************************************
      + * lib/stdio/lib_fgetc.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Global Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Private Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + **************************************************************************/
      +
      +/****************************************************************************
      + * fgetc
      + **************************************************************************/
      +
      +int fgetc(FAR FILE *stream)
      +{
      +  unsigned char ch;
      +  ssize_t ret;
      +
      +  ret = lib_fread(&ch, 1, stream);
      +  if (ret > 0)
      +    {
      +      return ch;
      +    }
      +  else
      +    {
      +      return EOF;
      +    }
      +}
      diff --git a/nuttx/lib/stdio/lib_fgetpos.c b/nuttx/lib/stdio/lib_fgetpos.c
      new file mode 100644
      index 0000000000..e9e9f4d102
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fgetpos.c
      @@ -0,0 +1,123 @@
      +/****************************************************************************
      + * lib/stdio/lib_fgetpos.c
      + *
      + *   Copyright (C) 2008-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fgetpos
      + *
      + * Description:
      + *   fgetpos() function is an alternate interfaces equivalent to ftell().
      + *   It gets the current value of the file offset and store it in the location
      + *   referenced by pos.  On some non-UNIX systems an fpos_t object may be a
      + *   complex object and fsetpos may be the only way to portably reposition a
      + *   stream.
      + *
      + * Returned Value:
      + *   Zero on succes; -1 on failure with errno set appropriately. 
      + *
      + ****************************************************************************/
      +
      +int fgetpos(FAR FILE *stream, FAR fpos_t *pos)
      +{
      +  long position;
      +
      +#if CONFIG_DEBUG
      +  if (!stream || !pos)
      +    {
      +      set_errno(EINVAL);
      +      return ERROR;
      +    }
      +#endif
      +
      +  position = ftell(stream);
      +  if (position == -1)
      +    {
      +      return ERROR;
      +    }
      +
      +  *pos = (fpos_t)position;
      +  return OK;
      +}
      diff --git a/nuttx/lib/stdio/lib_fgets.c b/nuttx/lib/stdio/lib_fgets.c
      new file mode 100644
      index 0000000000..a4f9089ed7
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fgets.c
      @@ -0,0 +1,207 @@
      +/****************************************************************************
      + * lib/stdio/lib_fgets.c
      + *
      + *   Copyright (C) 2007-2008, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +/* Some environments may return CR as end-of-line, others LF, and others
      + * both.  If not specified, the logic here assumes either (but not both) as
      + * the default.
      + */
      +
      +#if defined(CONFIG_EOL_IS_CR)
      +#  undef  CONFIG_EOL_IS_LF
      +#  undef  CONFIG_EOL_IS_BOTH_CRLF
      +#  undef  CONFIG_EOL_IS_EITHER_CRLF
      +#elif defined(CONFIG_EOL_IS_LF)
      +#  undef  CONFIG_EOL_IS_CR
      +#  undef  CONFIG_EOL_IS_BOTH_CRLF
      +#  undef  CONFIG_EOL_IS_EITHER_CRLF
      +#elif defined(CONFIG_EOL_IS_BOTH_CRLF)
      +#  undef  CONFIG_EOL_IS_CR
      +#  undef  CONFIG_EOL_IS_LF
      +#  undef  CONFIG_EOL_IS_EITHER_CRLF
      +#elif defined(CONFIG_EOL_IS_EITHER_CRLF)
      +#  undef  CONFIG_EOL_IS_CR
      +#  undef  CONFIG_EOL_IS_LF
      +#  undef  CONFIG_EOL_IS_BOTH_CRLF
      +#else
      +#  undef  CONFIG_EOL_IS_CR
      +#  undef  CONFIG_EOL_IS_LF
      +#  undef  CONFIG_EOL_IS_BOTH_CRLF
      +#  define CONFIG_EOL_IS_EITHER_CRLF 1
      +#endif
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fgets
      + *
      + * Description:
      + *   fgets() reads in at most one less than 'buflen' characters from stream
      + *   and stores them into the buffer pointed to by 'buf'. Reading stops after
      + *   an EOF or a newline.  If a newline is read, it is stored into the
      + *   buffer.  A null terminator is stored after the last character in the
      + *   buffer.
      + *
      + **************************************************************************/
      +
      +char *fgets(FAR char *buf, int buflen, FILE *stream)
      +{
      +  int  nch = 0;
      +
      +  /* Sanity checks */
      +
      +  if (!stream || !buf || buflen < 1 || stream->fs_filedes < 0)
      +    {
      +      return NULL;
      +    }
      +
      +  if (buflen < 2)
      +    {
      +      *buf = '\0';
      +      return buf;
      +    }
      +
      +  /* Read characters until we have a full line. On each the loop we must
      +   * be assured that there are two free bytes in the line buffer:  One for
      +   * the next character and one for the null terminator.
      +   */
      +
      +  for(;;)
      +    {
      +      /* Get the next character */
      +
      +      int ch = fgetc(stream);
      +
      +      /* Check for end-of-line.  This is tricky only in that some
      +       * environments may return CR as end-of-line, others LF, and
      +       * others both.
      +       */
      +
      +#if  defined(CONFIG_EOL_IS_LF) || defined(CONFIG_EOL_IS_BOTH_CRLF)
      +      if (ch == '\n')
      +#elif defined(CONFIG_EOL_IS_CR)
      +      if (ch == '\r')
      +#elif CONFIG_EOL_IS_EITHER_CRLF
      +      if (ch == '\n' || ch == '\r')
      +#endif
      +        {
      +          /* The newline is stored in the buffer along with the null
      +           * terminator.
      +           */
      +
      +          buf[nch++] = '\n';
      +          buf[nch]   = '\0';
      +          return buf;
      +        }
      +
      +      /* Check for end-of-file */
      +
      +      else if (ch == EOF)
      +        {
      +          /* End of file with no data? */
      +
      +          if (!nch)
      +            {
      +              /* Yes.. return NULL as the end of file mark */
      +
      +              return NULL;
      +            }
      +          else
      +            {
      +              /* Terminate the line */
      +
      +              buf[nch]   = '\0';
      +              return buf;
      +            }
      +        }
      +
      +      /* Otherwise, check if the character is printable and, if so, put the
      +       * character in the line buffer
      +       */
      +
      +      else if (isprint(ch))
      +        {
      +          buf[nch++] = ch;
      +
      +          /* Check if there is room for another character and the line's
      +           * null terminator.  If not then we have to end the line now.
      +           */
      +
      +          if (nch + 1 >= buflen)
      +            {
      +              buf[nch] = '\0';
      +              return buf;
      +            }
      +        }
      +    }
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_fileno.c b/nuttx/lib/stdio/lib_fileno.c
      new file mode 100644
      index 0000000000..fca08fc0d4
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fileno.c
      @@ -0,0 +1,70 @@
      +/****************************************************************************
      + * lib/stdio/lib_fileno.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +#if CONFIG_NFILE_STREAMS > 0
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +int fileno(FAR FILE *stream)
      +{
      +  int ret = -1;
      +  if (stream)
      +    {
      +      ret = stream->fs_filedes;
      +    }
      +
      +  if (ret < 0)
      +    {
      +      set_errno(EBADF);
      +      return ERROR;
      +    }
      +
      +  return ret;
      +}
      +#endif /* CONFIG_NFILE_STREAMS */
      +
      diff --git a/nuttx/lib/stdio/lib_fopen.c b/nuttx/lib/stdio/lib_fopen.c
      new file mode 100644
      index 0000000000..29ff4569c2
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fopen.c
      @@ -0,0 +1,299 @@
      +/****************************************************************************
      + * lib/stdio/lib_fopen.c
      + *
      + *   Copyright (C) 2007-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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Types
      + ****************************************************************************/
      +
      +enum open_mode_e
      +{
      +  MODE_NONE = 0, /* No access mode determined */
      +  MODE_R,        /* "r" or "rb" open for reading */
      +  MODE_W,        /* "w" or "wb" open for writing, truncating or creating file */
      +  MODE_A,        /* "a" or "ab" open for writing, appending to file */
      +  MODE_RPLUS,    /* "r+", "rb+", or "r+b" open for update (reading and writing) */
      +  MODE_WPLUS,    /* "w+", "wb+", or "w+b"  open for update, truncating or creating file */
      +  MODE_APLUS     /* "a+", "ab+", or "a+b" open for update, appending to file */
      +};
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_mode2oflags
      + ****************************************************************************/
      +
      +static int lib_mode2oflags(FAR const char *mode)
      +{
      +  enum open_mode_e state;
      +  int oflags;
      +
      +  /* Verify that a mode string was provided.  No error is  */
      +
      +  if (!mode)
      +    {
      +      goto errout;
      +    }
      +
      +  /* Parse the mode string to determine the corresponding open flags */
      +
      +  state  = MODE_NONE;
      +  oflags = 0;
      +
      +  for (; *mode; mode++)
      +    {
      +      switch (*mode)
      +        {
      +          /* Open for read access ("r", "r[+]", "r[b]",  "r[b+]", or "r[+b]") */
      +
      +          case 'r' :
      +            if (state == MODE_NONE)
      +              {
      +                /* Open for read access */
      +
      +                oflags = O_RDOK;
      +                state  = MODE_R;
      +              }
      +            else
      +              {
      +                goto errout;
      +              }
      +            break;
      +
      +          /* Open for write access ("w", "w[+]", "w[b]",  "w[b+]", or "w[+b]") */
      +
      +          case 'w' :
      +            if (state == MODE_NONE)
      +              {
      +                /* Open for write access, truncating any existing file */
      +
      +                oflags = O_WROK|O_CREAT|O_TRUNC;
      +                state  = MODE_W;
      +              }
      +            else
      +              {
      +                goto errout;
      +              }
      +            break;
      +
      +          /* Open for write/append access ("a", "a[+]", "a[b]", "a[b+]", or "a[+b]") */
      +
      +          case 'a' :
      +            if (state == MODE_NONE)
      +              {
      +                /* Write to the end of the file */
      +
      +                oflags = O_WROK|O_CREAT|O_APPEND;
      +                state  = MODE_A;
      +              }
      +            else
      +              {
      +                goto errout;
      +              }
      +            break;
      +
      +          /* Open for update access ("[r]+", "[rb]+]", "[r]+[b]", "[w]+",
      +           * "[wb]+]", "[w]+[b]", "[a]+", "[ab]+]",  "[a]+[b]")
      +           */
      +
      +          case '+' :
      +            switch (state)
      +              {
      +                case MODE_R:
      +                  {
      +                    /* Retain any binary mode selection */
      +
      +                    oflags &= O_BINARY;
      +
      +                    /* Open for read/write access */
      +
      +                    oflags |= O_RDWR;
      +                    state   = MODE_RPLUS;
      +                 }
      +                 break;
      +
      +                case MODE_W:
      +                  {
      +                    /* Retain any binary mode selection */
      +
      +                    oflags &= O_BINARY;
      +
      +                    /* Open for write read/access, truncating any existing file */
      +
      +                    oflags |= O_RDWR|O_CREAT|O_TRUNC;
      +                    state   = MODE_WPLUS;
      +                  }
      +                  break;
      +
      +                case MODE_A:
      +                  {
      +                    /* Retain any binary mode selection */
      +
      +                    oflags &= O_BINARY;
      +
      +                    /* Read from the beginning of the file; write to the end */
      +
      +                    oflags |= O_RDWR|O_CREAT|O_APPEND;
      +                    state   = MODE_APLUS;
      +                  }
      +                  break;
      +
      +                default:
      +                  goto errout;
      +                  break;
      +              }
      +            break;
      +
      +          /* Open for binary access ("[r]b", "[r]b[+]", "[r+]b", "[w]b",
      +           * "[w]b[+]", "[w+]b", "[a]b", "[a]b[+]",  "[a+]b")
      +           */
      +
      +          case 'b' :
      +            if (state != MODE_NONE)
      +              {
      +                /* The file is opened in binary mode */
      +
      +                oflags |= O_BINARY;
      +              }
      +            else
      +              {
      +                goto errout;
      +              }
      +            break;
      +
      +          /* Unrecognized or unsupported mode */
      +
      +          default:
      +            goto errout;
      +            break;
      +        }
      +    }
      +
      +  return oflags;
      +
      +/* Both fopen and fdopen should fail with errno == EINVAL if the mode
      + * string is invalid.
      + */
      +
      +errout:
      +  set_errno(EINVAL);
      +  return ERROR;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fdopen
      + ****************************************************************************/
      +
      +FAR FILE *fdopen(int fd, FAR const char *mode)
      +{
      +  FAR FILE *ret = NULL;
      +  int oflags;
      +
      +  /* Map the open mode string to open flags */
      +
      +  oflags = lib_mode2oflags(mode);
      +  if (oflags >= 0)
      +    {
      +      ret = fs_fdopen(fd, oflags, NULL);
      +    }
      +
      +  return ret;
      +}
      +
      +/****************************************************************************
      + * Name: fopen
      + ****************************************************************************/
      +
      +FAR FILE *fopen(FAR const char *path, FAR const char *mode)
      +{
      +  FAR FILE *ret = NULL;
      +  int oflags;
      +  int fd;
      +
      +  /* Map the open mode string to open flags */
      +
      +  oflags = lib_mode2oflags(mode);
      +  if (oflags < 0)
      +    {
      +      return NULL;
      +    }
      +
      +  /* Open the file */
      +
      +  fd = open(path, oflags, 0666);
      +
      +  /* If the open was successful, then fdopen() the fil using the file
      +   * desciptor returned by open.  If open failed, then just return the
      +   * NULL stream -- open() has already set the errno.
      +   */
      +
      +  if (fd >= 0)
      +    {
      +      ret = fs_fdopen(fd, oflags, NULL);
      +      if (!ret)
      +        {
      +          /* Don't forget to close the file descriptor if any other
      +           * failures are reported by fdopen().
      +           */
      +
      +          (void)close(fd);
      +        }
      +    }
      +  return ret;
      +}
      diff --git a/nuttx/lib/stdio/lib_fprintf.c b/nuttx/lib/stdio/lib_fprintf.c
      new file mode 100644
      index 0000000000..a803de4bd0
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fprintf.c
      @@ -0,0 +1,93 @@
      +/****************************************************************************
      + * lib/stdio/lib_fprintf.c
      + *
      + *   Copyright (C) 2007, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fprintf
      + ****************************************************************************/
      +
      +int fprintf(FAR FILE *stream, FAR const char *fmt, ...)
      +{
      +  va_list ap;
      +  int     n;
      +
      +  /* vfprintf into the stream */
      +
      +  va_start(ap, fmt);
      +  n = vfprintf(stream, fmt, ap);
      +  va_end(ap);
      +  return n;
      +}
      diff --git a/nuttx/lib/stdio/lib_fputc.c b/nuttx/lib/stdio/lib_fputc.c
      new file mode 100644
      index 0000000000..121161f102
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fputc.c
      @@ -0,0 +1,113 @@
      +/****************************************************************************
      + * lib/stdio/lib_fputc.c
      + *
      + *   Copyright (C) 2007, 2008, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fputc
      + ****************************************************************************/
      +
      +int fputc(int c, FAR FILE *stream)
      +{
      +  unsigned char buf = (unsigned char)c;
      +  int ret;
      +
      +  ret = lib_fwrite(&buf, 1, stream);
      +  if (ret > 0)
      +    {
      +      /* Flush the buffer if a newline is output */
      +
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +      if (c == '\n')
      +        {
      +          ret = lib_fflush(stream, true);
      +          if (ret < 0)
      +            {
      +              return EOF;
      +            }
      +        }
      +#endif
      +      return c;
      +    }
      +  else
      +    {
      +      return EOF;
      +    }
      +}
      diff --git a/nuttx/lib/stdio/lib_fputs.c b/nuttx/lib/stdio/lib_fputs.c
      new file mode 100644
      index 0000000000..2d6217d4aa
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fputs.c
      @@ -0,0 +1,220 @@
      +/****************************************************************************
      + * lib/stdio/lib_fputs.c
      + *
      + *   Copyright (C) 2007, 2008, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fputs
      + *
      + * Description:
      + *   fputs() writes the string s to stream, without its trailing '\0'.
      + *
      + ****************************************************************************/
      +
      +#if defined(CONFIG_ARCH_ROMGETC)
      +int fputs(FAR const char *s, FAR FILE *stream)
      +{
      +  int nput;
      +  int ret;
      +  char ch;
      +
      +  /* Make sure that a string was provided. */
      +
      +#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */
      +  if (!s)
      +    {
      +      set_errno(EINVAL);
      +      return EOF;
      +    }
      +#endif
      +
      +  /* Write the string.  Loop until the null terminator is encountered */
      +
      +  for (nput = 0, ch = up_romgetc(s); ch; nput++, s++, ch = up_romgetc(s))
      +    {
      +      /* Write the next character to the stream buffer */
      +
      +      ret = lib_fwrite(&ch, 1, stream);
      +      if (ret <= 0)
      +        {
      +          return EOF;
      +        }
      +
      +      /* Flush the buffer if a newline was written to the buffer */
      +
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +      if (ch == '\n')
      +        {
      +          ret = lib_fflush(stream, true);
      +          if (ret < 0)
      +            {
      +              return EOF;
      +            }
      +        }
      +#endif
      +    }
      +
      +  return nput;
      +}
      +
      +#elif defined(CONFIG_STDIO_LINEBUFFER)
      +int fputs(FAR const char *s, FAR FILE *stream)
      +{
      +  int nput;
      +  int ret;
      +
      +  /* Make sure that a string was provided. */
      +
      +#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */
      +  if (!s)
      +    {
      +      set_errno(EINVAL);
      +      return EOF;
      +    }
      +#endif
      +
      +  /* Write the string.  Loop until the null terminator is encountered */
      +
      +  for (nput = 0; *s; nput++, s++)
      +    {
      +      /* Write the next character to the stream buffer */
      +
      +      ret = lib_fwrite(s, 1, stream);
      +      if (ret <= 0)
      +        {
      +          return EOF;
      +        }
      +
      +      /* Flush the buffer if a newline was written to the buffer */
      +
      +      if (*s == '\n')
      +        {
      +          ret = lib_fflush(stream, true);
      +          if (ret < 0)
      +            {
      +              return EOF;
      +            }
      +        }
      +    }
      +
      +  return nput;
      +}
      +
      +#else
      +int fputs(FAR const char *s, FAR FILE *stream)
      +{
      +  int ntowrite;
      +  int nput;
      +
      +  /* Make sure that a string was provided. */
      +
      +#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */
      +  if (!s)
      +    {
      +      set_errno(EINVAL);
      +      return EOF;
      +    }
      +#endif
      +
      +  /* Get the length of the string. */
      +
      +  ntowrite = strlen(s);
      +  if (ntowrite == 0)
      +    {
      +      return 0;
      +    }
      +
      +  /* Write the string */
      +
      +  nput = lib_fwrite(s, ntowrite, stream);
      +  if (nput < 0)
      +    {
      +      return EOF;
      +    }
      +  return nput;
      +}
      +#endif
      diff --git a/nuttx/lib/stdio/lib_fread.c b/nuttx/lib/stdio/lib_fread.c
      new file mode 100644
      index 0000000000..4a4b29256d
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fread.c
      @@ -0,0 +1,101 @@
      +/****************************************************************************
      + * lib/stdio/lib_fread.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fread
      + ****************************************************************************/
      +
      +size_t fread(FAR void *ptr, size_t size, size_t n_items, FAR FILE *stream)
      +{
      +  size_t  full_size = n_items * (size_t)size;
      +  ssize_t bytes_read;
      +  size_t  items_read = 0;
      +
      +  /* Write the data into the stream buffer */
      +
      +  bytes_read = lib_fread(ptr, full_size, stream);
      +  if (bytes_read > 0)
      +    {
      +      /* Return the number of full items read */
      +
      +      items_read = bytes_read / size;
      +    }
      +  return items_read;
      +}
      +
      +
      diff --git a/nuttx/lib/stdio/lib_fseek.c b/nuttx/lib/stdio/lib_fseek.c
      new file mode 100644
      index 0000000000..7380f83b3b
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fseek.c
      @@ -0,0 +1,138 @@
      +/****************************************************************************
      + * lib/stdio/lib_fseek.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fseek
      + *
      + * Description:
      + *   The fseek() function sets the file position indicator for the stream
      + *   pointed to by stream. The new position, measured in bytes, is obtained
      + *   by adding offset bytes to the position specified by whence. If whence is
      + *   set to SEEK_SET, SEEK_CUR, or SEEK_END, the offset is relative to the
      + *   start of the file, the current position indicator, or end-of-file,
      + *   respectively. A successful call to the fseek() function clears the
      + *   end-of-file indicator for the stream and undoes any effects of the ungetc(3)
      + *   function on the same stream.
      + *
      + * Returned Value:
      + *   Zero on succes; -1 on failure with errno set appropriately. 
      + *
      + ****************************************************************************/
      +
      +int fseek(FAR FILE *stream, long int offset, int whence)
      +{
      + #if CONFIG_STDIO_BUFFER_SIZE > 0
      +  /* Flush any valid read/write data in the buffer (also verifies stream) */
      +
      +  if (lib_rdflush(stream) < 0 || lib_wrflush(stream) < 0)
      +    {
      +      return ERROR;
      +    }
      +#else
      +  /* Verify that we were provided with a stream */
      +
      +  if (!stream)
      +    {
      +      set_errno(EBADF);
      +      return ERROR;
      +    }
      +#endif
      +
      +  /* On success or failure, discard any characters saved by ungetc() */
      +
      +#if CONFIG_NUNGET_CHARS > 0
      +  stream->fs_nungotten = 0;
      +#endif
      +
      +  /* Perform the fseek on the underlying file descriptor */
      +
      +  return lseek(stream->fs_filedes, offset, whence) == (off_t)-1 ? ERROR : OK;
      +}
      +
      +
      diff --git a/nuttx/lib/stdio/lib_fsetpos.c b/nuttx/lib/stdio/lib_fsetpos.c
      new file mode 100644
      index 0000000000..13d556521b
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fsetpos.c
      @@ -0,0 +1,116 @@
      +/****************************************************************************
      + * lib/stdio/lib_fsetpos.c
      + *
      + *   Copyright (C) 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fsetpos
      + *
      + * Description:
      + *   fsetpos() function is an alternate interfaces equivalent to fseek()
      + *   (with whence set to  SEEK_SET).  It sets the current value of the file
      + *   offset to value in the location referenced by pos.  On some non-UNIX
      + *   systems an fpos_t object may be a complex object and fsetpos may be the
      + *   only way to portably reposition a stream.
      + *
      + * Returned Value:
      + *   Zero on succes; -1 on failure with errno set appropriately. 
      + *
      + ****************************************************************************/
      +
      +int fsetpos(FAR FILE *stream, FAR fpos_t *pos)
      +{
      +#if CONFIG_DEBUG
      +  if (!stream || !pos)
      +    {
      +      set_errno(EINVAL);
      +      return ERROR;
      +    }
      +#endif
      +
      +  return fseek(stream, (FAR off_t)*pos, SEEK_SET);
      +}
      diff --git a/nuttx/lib/stdio/lib_ftell.c b/nuttx/lib/stdio/lib_ftell.c
      new file mode 100644
      index 0000000000..9476481529
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_ftell.c
      @@ -0,0 +1,129 @@
      +/****************************************************************************
      + * lib/stdio/lib_ftell.c
      + *
      + *   Copyright (C) 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: ftell
      + *
      + * Description:
      + *   ftell() returns the current value of the file position indicator for the
      + *   stream pointed to by stream.
      + *
      + * Returned Value:
      + *   Zero on succes; -1 on failure with errno set appropriately. 
      + *
      + ****************************************************************************/
      +
      +long ftell(FAR FILE *stream)
      +{
      +  off_t position;
      +
      +  /* Verify that we were provided with a stream */
      +
      +  if (!stream)
      +    {
      +      set_errno(EBADF);
      +      return ERROR;
      +    }
      +
      +  /* Perform the lseek to the current position.  This will not move the
      +   * file pointer, but will return its current setting
      +   */
      +
      +  position = lseek(stream->fs_filedes, 0, SEEK_CUR);
      +  if (position != (off_t)-1)
      +    {
      +      return (long)position;
      +    }
      +  else
      +    {
      +      return ERROR;
      +    }
      +}
      +
      +
      diff --git a/nuttx/lib/stdio/lib_fwrite.c b/nuttx/lib/stdio/lib_fwrite.c
      new file mode 100644
      index 0000000000..60e0017463
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_fwrite.c
      @@ -0,0 +1,99 @@
      +/****************************************************************************
      + * lib/stdio/lib_fwrite.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: fwrite
      + ****************************************************************************/
      +
      +size_t fwrite(FAR const void *ptr, size_t size, size_t n_items, FAR FILE *stream)
      +{
      +  size_t  full_size = n_items * (size_t)size;
      +  ssize_t bytes_written;
      +  size_t  items_written = 0;
      +
      +  /* Write the data into the stream buffer */
      +
      +  bytes_written = lib_fwrite(ptr, full_size, stream);
      +  if (bytes_written > 0)
      +    {
      +      /* Return the number of full items written */
      +
      +      items_written = bytes_written / size;
      +    }
      +  return items_written;
      +}
      diff --git a/nuttx/lib/stdio/lib_gets.c b/nuttx/lib/stdio/lib_gets.c
      new file mode 100644
      index 0000000000..95a6b36ebf
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_gets.c
      @@ -0,0 +1,120 @@
      +/****************************************************************************
      + * lib/stdio/lib_gets.c
      + *
      + *   Copyright (C) 2007-2008, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: gets
      + *
      + * Description:
      + *   gets() reads a line from stdin into the buffer pointed to by s until
      + *   either a terminating newline or EOF, which it replaces with '\0'.  No
      + *   check for buffer overrun is performed
      + *
      + *   This API should not be used because it is inherently unsafe.  Consider
      + *   using fgets which is safer and slightly more efficient.
      + *
      + **************************************************************************/
      +
      +FAR char *gets(FAR char *s)
      +{
      +  /* gets is ALMOST the same as fgets using stdin and no length limit
      +   * (hence, the unsafeness of gets).  So let fgets do most of the work.
      +   */
      +
      +  FAR char *ret = fgets(s, INT_MAX, stdin);
      +  if (ret)
      +    {
      +      /* Another subtle difference from fgets is that gets replaces
      +       * end-of-line markers with null terminators. We will do that as
      +       * a second step (with some loss in performance).
      +       */
      +
      +      int len = strlen(ret);
      +      if (len > 0 && ret[len-1] == '\n')
      +        {
      +           ret[len-1] = '\0';
      +        }
      +    }
      +
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_libdtoa.c b/nuttx/lib/stdio/lib_libdtoa.c
      new file mode 100644
      index 0000000000..667c49c535
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_libdtoa.c
      @@ -0,0 +1,304 @@
      +/****************************************************************************
      + * lib/unistd/lib_libdtoa.c
      + *
      + * This file was ported to NuttX by Yolande Cates.
      + *
      + * Copyright (c) 1990, 1993
      + *      The Regents of the University of California.  All rights reserved.
      + *
      + * This code is derived from software contributed to Berkeley by
      + * Chris Torek.
      + *
      + * 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. All advertising materials mentioning features or use of this software
      + *    must display the following acknowledgement:
      + *      This product includes software developed by the University of
      + *      California, Berkeley and its contributors.
      + * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +#define MAX_PREC 16
      +
      +#ifndef MIN
      +#  define MIN(a,b) (a < b ? a : b)
      +#endif
      +
      +#ifndef MAX
      +#  define MAX(a,b) (a > b ? a : b)
      +#endif
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: zeroes
      + *
      + * Description:
      + *   Print the specified number of zeres
      + *
      + ****************************************************************************/
      +
      +static void zeroes(FAR struct lib_outstream_s *obj, int nzeroes)
      +{
      +  int i;
      +
      +  for (i = nzeroes; i > 0; i--)
      +    {
      +      obj->put(obj, '0');
      +    }
      +}
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_dtoa
      + *
      + * Description:
      + *   This is part of lib_vsprintf().  It handles the floating point formats.
      + *   This version supports only the %f (with precision).  If no precision
      + *   was provided in the format, this will use precision == 0 which is
      + *   probably not what you want.
      + *
      + * Input Parameters:
      + *   obj   - The output stream object
      + *   fmt   - The format character.  Not used 'f' is always assumed
      + *   prec  - The number of digits to the right of the decimal point. If no
      + *           precision is provided in the format, this will be zero.  And,
      + *           unfortunately in this case, it will be treated literally as
      + *           a precision of zero.
      + *   flags - Only ALTFORM and SHOWPLUS flags are supported.  ALTFORM only
      + *           applies if prec == 0 which is not supported anyway.
      + *   value - The floating point value to convert.
      + *
      + ****************************************************************************/
      +
      +static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec,
      +                     uint8_t flags, double value)
      +{
      +  FAR char *digits;     /* String returned by __dtoa */
      +  FAR char *digalloc;   /* Copy of digits to be freed after usage */
      +  FAR char *rve;        /* Points to the end of the return value */
      +  int  expt;            /* Integer value of exponent */
      +  int  numlen;          /* Actual number of digits returned by cvt */
      +  int  nchars;          /* Number of characters to print */
      +  int  dsgn;            /* Unused sign indicator */
      +  int  i;
      +
      +  /* Non-zero... positive or negative */
      +
      +  if (value < 0)
      +    {
      +      value = -value;
      +      SET_NEGATE(flags);
      +    }
      +
      +  /* Perform the conversion */
      +
      +  digits   = __dtoa(value, 3, prec, &expt, &dsgn, &rve);
      +  digalloc = digits;
      +  numlen   = rve - digits;
      +
      +  if (IS_NEGATE(flags))
      +    {
      +      obj->put(obj, '-');
      +    }
      +  else if (IS_SHOWPLUS(flags))
      +    {
      +      obj->put(obj, '+');
      +    }
      +
      +  /* Special case exact zero or the case where the number is smaller than
      +   * the print precision.
      +   */
      +
      +  if (value == 0 || expt < -prec)
      +    {
      +      /* kludge for __dtoa irregularity */
      +
      +      obj->put(obj, '0');
      +
      +      /* A decimal point is printed only in the alternate form or if a 
      +       * particular precision is requested.
      +       */
      +
      +      if (prec > 0 || IS_ALTFORM(flags))
      +        {
      +          obj->put(obj, '.');
      +
      +          /* Always print at least one digit to the right of the decimal point. */
      +
      +          prec = MAX(1, prec);
      +        }
      +    }
      +
      +  /* A non-zero value will be printed */
      +
      +  else
      +    {
      +
      +      /* Handle the case where the value is less than 1.0 (in magnitude) and
      +       * will need a leading zero.
      +       */
      +
      +      if (expt <= 0)
      +        {
      +          /* Print a single zero to the left of the decimal point */
      +
      +          obj->put(obj, '0');
      +
      +          /* Print the decimal point */
      +
      +          obj->put(obj, '.');
      +
      +          /* Print any leading zeros to the right of the decimal point */
      +
      +          if (expt < 0)
      +            {
      +              nchars = MIN(-expt, prec);
      +              zeroes(obj, nchars);
      +              prec -= nchars;
      +            }
      +        }
      +
      +      /* Handle the general case where the value is greater than 1.0 (in
      +       * magnitude).
      +       */
      +
      +      else
      +        {
      +          /* Print the integer part to the left of the decimal point */
      +
      +          for (i = expt; i > 0; i--)
      +            {
      +              if (*digits != '\0')
      +                { 
      +                  obj->put(obj, *digits);
      +                  digits++;
      +                }
      +              else
      +                {
      +                  obj->put(obj, '0');
      +                }
      +            }
      +
      +          /* Get the length of the fractional part */
      +
      +          numlen -= expt;
      +
      +          /* If there is no fractional part, then a decimal point is printed
      +           * only in the alternate form or if a particular precision is
      +           * requested.
      +           */
      +
      +          if (numlen > 0 || prec > 0 || IS_ALTFORM(flags))
      +            {
      +              /* Print the decimal point */
      +
      +              obj->put(obj, '.');
      +
      +              /* Always print at least one digit to the right of the decimal
      +               * point.
      +               */
      +
      +              prec = MAX(1, prec);
      +            }
      +        }
      +
      +      /* If a precision was specified, then limit the number digits to the
      +       * right of the decimal point.
      +       */
      +
      +      if (prec > 0)
      +        {
      +          nchars = MIN(numlen, prec);
      +        }
      +      else
      +        {
      +          nchars = numlen;
      +        }
      +
      +      /* Print the fractional part to the right of the decimal point */
      +
      +      for (i = nchars; i > 0; i--)
      +        {
      +          obj->put(obj, *digits);
      +          digits++;
      +        }
      +
      +      /* Decremnt to get the number of trailing zeroes to print */
      +
      +      prec -= nchars;
      +    }
      +
      +  /* Finally, print any trailing zeroes */
      +
      +  zeroes(obj, prec);
      +
      +  /* Is this memory supposed to be freed or not? */
      +
      +#if 0
      +  if (digalloc)
      +    {
      +      free(digalloc);
      +    }
      +#endif
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      diff --git a/nuttx/lib/stdio/lib_libfflush.c b/nuttx/lib/stdio/lib_libfflush.c
      new file mode 100644
      index 0000000000..2a4fe29326
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_libfflush.c
      @@ -0,0 +1,202 @@
      +/****************************************************************************
      + * lib/stdio/lib_libfflush.c
      + *
      + *   Copyright (C) 2007-2008, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_fflush
      + *
      + * Description:
      + *  The function lib_fflush() forces a write of all user-space buffered data for
      + *  the given output or update stream via the stream's underlying write
      + *  function.  The open status of the stream is unaffected.
      + *
      + * Parmeters:
      + *  stream - the stream to flush
      + *  bforce - flush must be complete.
      + *
      + * Return:
      + *  A negated errno value on failure, otherwise the number of bytes remaining
      + *  in the buffer.
      + *
      + ****************************************************************************/
      +
      +ssize_t lib_fflush(FAR FILE *stream, bool bforce)
      +{
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +  FAR const unsigned char *src;
      +  ssize_t bytes_written;
      +  ssize_t nbuffer;
      +
      +  /* Return EBADF if the file is not opened for writing */
      +
      +  if (stream->fs_filedes < 0 || (stream->fs_oflags & O_WROK) == 0)
      +    {
      +      return -EBADF;
      +    }
      +
      +  /* Make sure that we have exclusive access to the stream */
      +
      +  lib_take_semaphore(stream);
      +
      +  /* Make sure that the buffer holds valid data */
      +
      +  if (stream->fs_bufpos  != stream->fs_bufstart)
      +    {
      +       /* Make sure that the buffer holds buffered write data.  We do not
      +        * support concurrent read/write buffer usage.
      +        */
      +
      +       if (stream->fs_bufread != stream->fs_bufstart)
      +        {
      +          /* The buffer holds read data... just return zero meaning "no bytes
      +           * remaining in the buffer."
      +           */
      +
      +          lib_give_semaphore(stream);
      +          return 0;
      +        }
      +
      +      /* How many bytes of write data are used in the buffer now */
      +
      +      nbuffer = stream->fs_bufpos - stream->fs_bufstart;
      +
      +      /* Try to write that amount */
      +
      +      src = stream->fs_bufstart;
      +      do
      +        {
      +          /* Perform the write */
      +
      +          bytes_written = write(stream->fs_filedes, src, nbuffer);
      +          if (bytes_written < 0)
      +            {
      +              /* Write failed.  The cause of the failure is in 'errno'.
      +               * returned the negated errno value.
      +               */
      +
      +              lib_give_semaphore(stream);
      +              return -get_errno();
      +            }
      +
      +          /* Handle partial writes.  fflush() must either return with
      +           * an error condition or with the data successfully flushed
      +           * from the buffer.
      +           */
      +
      +          src     += bytes_written;
      +          nbuffer -= bytes_written;
      +        }
      +      while (bforce && nbuffer > 0);
      +
      +      /* Reset the buffer position to the beginning of the buffer */
      +
      +      stream->fs_bufpos = stream->fs_bufstart;
      +
      +      /* For the case of an incomplete write, nbuffer will be non-zero
      +       * It will hold the number of bytes that were not written.
      +       * Move the data down in the buffer to handle this (rare) case
      +       */
      +
      +      while (nbuffer)
      +       {
      +         *stream->fs_bufpos++ = *src++;
      +         --nbuffer;
      +       }
      +    }
      +
      +  /* Restore normal access to the stream and return the number of bytes
      +   * remaining in the buffer.
      +   */
      +
      +  lib_give_semaphore(stream);
      +  return stream->fs_bufpos - stream->fs_bufstart;
      +#else
      +  /* Return no bytes remaining in the buffer */
      +
      +  return 0;
      +#endif
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_libflushall.c b/nuttx/lib/stdio/lib_libflushall.c
      new file mode 100644
      index 0000000000..9d0a89e9c1
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_libflushall.c
      @@ -0,0 +1,137 @@
      +/****************************************************************************
      + * lib/stdio/lib_libflushall.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_flushall
      + *
      + * Description:
      + *   Called either (1) by the OS when a task exits, or (2) from fflush()
      + *   when a NULL stream argument is provided.
      + *
      + ****************************************************************************/
      +
      +int lib_flushall(FAR struct streamlist *list)
      +{
      +  int lasterrno = OK;
      +  int ret;
      +
      +  /* Make sure that there are streams associated with this thread */
      +
      +  if (list)
      +    {
      +       int i;
      +
      +       /* Process each stream in the thread's stream list */
      +
      +       stream_semtake(list);
      +       for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
      +         {
      +           FILE *stream = &list->sl_streams[i];
      +
      +           /* If the stream is open (i.e., assigned a non-negative file
      +            * descriptor) and opened for writing, then flush all of the pending
      +            * write data in the stream.
      +            */
      +
      +           if (stream->fs_filedes >= 0 && (stream->fs_oflags & O_WROK) != 0)
      +             {
      +               /* Flush the writable FILE */
      +
      +               ret = lib_fflush(stream, true);
      +               if (ret < 0)
      +                 {
      +                   /* An error occurred during the flush AND/OR we were unable
      +                    * to flush all of the buffered write data.  Remember the
      +                    * last errcode.
      +                    */
      +
      +                   lasterrno = ret;
      +                 }
      +             }
      +         }
      +
      +       stream_semgive(list);
      +    }
      +
      +  /* If any flush failed, return the errorcode of the last failed flush */
      +
      +  return lasterrno;
      +}
      diff --git a/nuttx/lib/stdio/lib_libfread.c b/nuttx/lib/stdio/lib_libfread.c
      new file mode 100644
      index 0000000000..5585acbaea
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_libfread.c
      @@ -0,0 +1,315 @@
      +/****************************************************************************
      + * lib/stdio/lib_libfread.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include   /* for CONFIG_STDIO_BUFFER_SIZE */
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_fread
      + ****************************************************************************/
      +
      +ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream)
      +{
      +  unsigned char *dest  = (unsigned char*)ptr;
      +  ssize_t        bytes_read;
      +  int            ret;
      +
      +  /* Make sure that reading from this stream is allowed */
      +
      +  if (!stream || (stream->fs_oflags & O_RDOK) == 0)
      +    {
      +      set_errno(EBADF);
      +      bytes_read = -1;
      +    }
      +  else
      +    {
      +      /* The stream must be stable until we complete the read */
      +
      +      lib_take_semaphore(stream);
      +
      +#if CONFIG_NUNGET_CHARS > 0
      +      /* First, re-read any previously ungotten characters */
      +
      +      while ((stream->fs_nungotten > 0) && (count > 0))
      +        {
      +          /* Decrement the count of ungotten bytes to get an index */
      +
      +          stream->fs_nungotten--;
      +
      +          /* Return the last ungotten byte */
      +
      +          *dest++ = stream->fs_ungotten[stream->fs_nungotten];
      +
      +          /* That's one less byte that we have to read */
      +
      +          count--;
      +        }
      +#endif
      +
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +      /* If the buffer is currently being used for write access, then
      +       * flush all of the buffered write data.  We do not support concurrent
      +       * buffered read/write access.
      +       */
      +
      +      ret = lib_wrflush(stream);
      +      if (ret < 0)
      +        {
      +          lib_give_semaphore(stream);
      +          return ret;
      +        }
      +
      +      /* Now get any other needed chars from the buffer or the file. */
      +
      +      while (count > 0)
      +        {
      +          /* Is there readable data in the buffer? */
      +
      +          while ((count > 0) && (stream->fs_bufpos < stream->fs_bufread))
      +            {
      +              /* Yes, copy a byte into the user buffer */
      +
      +              *dest++ = *stream->fs_bufpos++;
      +              count--;
      +            }
      +
      +          /* The buffer is empty OR we have already supplied the number of
      +           * bytes requested in the read.  Check if we need to read
      +           * more from the file.
      +           */
      +
      +          if (count > 0)
      +            {
      +              size_t buffer_available;
      +
      +              /* We need to read more data into the buffer from the file */
      +
      +              /* Mark the buffer empty */
      +
      +              stream->fs_bufpos = stream->fs_bufread = stream->fs_bufstart;
      +
      +              /* How much space is available in the buffer? */
      +
      +              buffer_available = stream->fs_bufend - stream->fs_bufread;
      +
      +              /* Will the number of bytes that we need to read fit into
      +               * the buffer space that is available? If the read size is
      +               * larger than the buffer, then read some of the data
      +               * directly into the user's buffer.
      +               */
      +
      +              if (count > buffer_available)
      +                {
      +                  bytes_read = read(stream->fs_filedes, dest, count);
      +                  if (bytes_read < 0)
      +                    {
      +                      /* An error occurred on the read.  The error code is
      +                       * in the 'errno' variable.
      +                       */
      +
      +                      goto errout_with_errno;
      +                    }
      +                  else if (bytes_read == 0)
      +                    {
      +                      /* We are at the end of the file.  But we may already
      +                       * have buffered data.  In that case, we will report
      +                       * the EOF indication later.
      +                       */
      +
      +                      goto shortread;
      +                    }
      +                  else
      +                    {
      +                      /* Some bytes were read. Adjust the dest pointer */
      +
      +                      dest  += bytes_read;
      +
      +                      /* Were all of the requested bytes read? */
      +
      +                      if (bytes_read < count)
      +                        {
      +                          /* No.  We must be at the end of file. */
      +
      +                          goto shortread;
      +                        }
      +                      else
      +                        {
      +                          /* Yes.  We are done. */
      +
      +                          count = 0;
      +                        }
      +                    }
      +                }
      +              else
      +                {
      +                  /* The number of bytes required to satisfy the read
      +                   * is less than or equal to the size of the buffer
      +                   * space that we have left. Read as much as we can
      +                   * into the buffer.
      +                   */
      +
      +                  bytes_read = read(stream->fs_filedes, stream->fs_bufread, buffer_available);
      +                  if (bytes_read < 0)
      +                    {
      +                      /* An error occurred on the read.  The error code is
      +                       * in the 'errno' variable.
      +                       */
      +
      +                      goto errout_with_errno;
      +                    }
      +                  else if (bytes_read == 0)
      +                    {
      +                      /* We are at the end of the file.  But we may already
      +                       * have buffered data.  In that case, we will report
      +                       * the EOF indication later.
      +                       */
      +
      +                      goto shortread;
      +                    }
      +                  else
      +                    {
      +                      /* Some bytes were read */
      +
      +                      stream->fs_bufread += bytes_read;
      +                    }
      +                }
      +            }
      +        }
      +#else
      +      /* Now get any other needed chars from the file. */
      +
      +      while (count > 0)
      +        {
      +          bytes_read = read(stream->fs_filedes, dest, count);
      +          if (bytes_read < 0)
      +            {
      +              /* An error occurred on the read.  The error code is
      +               * in the 'errno' variable.
      +               */
      +
      +              goto errout_with_errno;
      +            }
      +          else if (bytes_read == 0)
      +            {
      +              /* We are at the end of the file.  But we may already
      +               * have buffered data.  In that case, we will report
      +               * the EOF indication later.
      +               */
      +
      +              break;
      +            }
      +          else
      +            {
      +              dest  += bytes_read;
      +              count -= bytes_read;
      +            }
      +        }
      +#endif
      +      /* Here after a successful (but perhaps short) read */
      +
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +    shortread:
      +#endif
      +      bytes_read = dest - (unsigned char*)ptr;
      +
      +      /* Set or clear the EOF indicator.  If we get here because of a
      +       * short read and the total number of* bytes read is zero, then
      +       * we must be at the end-of-file.
      +       */
      +
      +      if (bytes_read > 0)
      +        {
      +          stream->fs_flags &= ~__FS_FLAG_EOF;
      +        }
      +      else
      +        {
      +          stream->fs_flags |= __FS_FLAG_EOF;
      +        }
      +    }
      +
      +  lib_give_semaphore(stream);
      +  return bytes_read;  
      +
      +/* Error exits */
      +
      +errout_with_errno:
      +  lib_give_semaphore(stream);
      +  return -get_errno();  
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_libfwrite.c b/nuttx/lib/stdio/lib_libfwrite.c
      new file mode 100644
      index 0000000000..e71866b498
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_libfwrite.c
      @@ -0,0 +1,179 @@
      +/****************************************************************************
      + * lib/stdio/lib_libfwrite.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include   /* for CONFIG_STDIO_BUFFER_SIZE */
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_fwrite
      + ****************************************************************************/
      +
      +ssize_t lib_fwrite(FAR const void *ptr, size_t count, FAR FILE *stream)
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +{
      +  FAR const unsigned char *start = ptr;
      +  FAR const unsigned char *src   = ptr;
      +  ssize_t ret = ERROR;
      +  unsigned char *dest;
      +
      +  /* Make sure that writing to this stream is allowed */
      +
      +  if (!stream || (stream->fs_oflags & O_WROK) == 0)
      +    {
      +      set_errno(EBADF);
      +      goto errout;
      +    }
      +
      +  /* Get exclusive access to the stream */
      +
      +  lib_take_semaphore(stream);
      +
      +  /* If the buffer is currently being used for read access, then
      +   * discard all of the read-ahead data.  We do not support concurrent
      +   * buffered read/write access.
      +   */
      +
      +  if (lib_rdflush(stream) < 0)
      +    {
      +      goto errout_with_semaphore;
      +    }
      +
      +  /* Loop until all of the bytes have been buffered */
      +
      +  while (count > 0)
      +    {
      +      /* Determine the number of bytes left in the buffer */
      +
      +      size_t gulp_size = stream->fs_bufend - stream->fs_bufpos;
      +
      +      /* Will the user data fit into the amount of buffer space
      +       * that we have left?
      +       */
      +
      +      if (gulp_size > count)
      +        {
      +          /* Yes, clip the gulp to the size of the user data */
      +
      +          gulp_size = count;
      +        }
      +
      +      /* Adjust the number of bytes remaining to be transferred
      +       * on the next pass through the loop (might be zero).
      +       */
      +
      +      count -= gulp_size;
      +
      +      /* Transfer the data into the buffer */
      +
      +      for (dest = stream->fs_bufpos; gulp_size > 0; gulp_size--)
      +        {
      +          *dest++ = *src++;
      +        }
      +      stream->fs_bufpos = dest;
      +
      +      /* Is the buffer full? */
      +
      +      if (dest >= stream->fs_bufend)
      +        {
      +          /* Flush the buffered data to the IO stream */
      +
      +          int bytes_buffered = lib_fflush(stream, false);
      +          if (bytes_buffered < 0)
      +            {
      +              goto errout_with_semaphore;
      +            }
      +        }
      +    }
      +
      +  /* Return the number of bytes written */
      +
      +  ret = src - start;
      +
      +errout_with_semaphore:
      +  lib_give_semaphore(stream);
      +
      +errout:
      +  return ret;
      +}
      +#else
      +{
      +  return write(stream->fs_filedes, ptr, count);
      +}
      +#endif /* CONFIG_STDIO_BUFFER_SIZE */
      +
      diff --git a/nuttx/lib/stdio/lib_libnoflush.c b/nuttx/lib/stdio/lib_libnoflush.c
      new file mode 100644
      index 0000000000..e3b8911534
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_libnoflush.c
      @@ -0,0 +1,103 @@
      +/****************************************************************************
      + * lib/stdio/lib_libnoflush.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_noflush
      + *
      + * Description:
      + *  lib_noflush() provides a common, dummy flush method for output streams
      + *  that are not flushable.  Only used if CONFIG_STDIO_LINEBUFFER is selected.
      + *
      + * Return:
      + *  Always returns OK
      + *
      + ****************************************************************************/
      +
      +int lib_noflush(FAR struct lib_outstream_s *this)
      +{
      +  return OK;
      +}
      +
      +#endif /* CONFIG_STDIO_LINEBUFFER */
      +
      diff --git a/nuttx/lib/stdio/lib_libsprintf.c b/nuttx/lib/stdio/lib_libsprintf.c
      new file mode 100644
      index 0000000000..2474a6f01d
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_libsprintf.c
      @@ -0,0 +1,90 @@
      +/****************************************************************************
      + * lib/stdio/lib_libsprintf.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_sprintf
      + ****************************************************************************/
      +
      +int lib_sprintf(FAR struct lib_outstream_s *obj, const char *fmt, ...)
      +{
      +  va_list ap;
      +  int     n;
      +
      +  /* Let lib_vsprintf do the real work */
      +
      +  va_start(ap, fmt);
      +  n = lib_vsprintf(obj, fmt, ap);
      +  va_end(ap);
      +  return n;
      +}
      diff --git a/nuttx/lib/stdio/lib_libvsprintf.c b/nuttx/lib/stdio/lib_libvsprintf.c
      new file mode 100644
      index 0000000000..30c988599c
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_libvsprintf.c
      @@ -0,0 +1,1620 @@
      +/****************************************************************************
      + * lib/stdio/lib_libvsprintf.c
      + *
      + *   Copyright (C) 2007-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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +/* If you have floating point but no fieldwidth, then use a fixed (but
      + * configurable) floating point precision.
      + */
      +
      +#if defined(CONFIG_LIBC_FLOATINGPOINT) && \
      +    defined(CONFIG_NOPRINTF_FIELDWIDTH) && \
      +   !defined(CONFIG_LIBC_FIXEDPRECISION)
      +#  define CONFIG_LIBC_FIXEDPRECISION 3
      +#endif
      +
      +#define FLAG_SHOWPLUS            0x01
      +#define FLAG_ALTFORM             0x02
      +#define FLAG_HASDOT              0x04
      +#define FLAG_HASASTERISKWIDTH    0x08
      +#define FLAG_HASASTERISKTRUNC    0x10
      +#define FLAG_LONGPRECISION       0x20
      +#define FLAG_LONGLONGPRECISION   0x40
      +#define FLAG_NEGATE              0x80
      +
      +#define SET_SHOWPLUS(f)          do (f) |= FLAG_SHOWPLUS; while (0)
      +#define SET_ALTFORM(f)           do (f) |= FLAG_ALTFORM; while (0)
      +#define SET_HASDOT(f)            do (f) |= FLAG_HASDOT; while (0)
      +#define SET_HASASTERISKWIDTH(f)  do (f) |= FLAG_HASASTERISKWIDTH; while (0)
      +#define SET_HASASTERISKTRUNC(f)  do (f) |= FLAG_HASASTERISKTRUNC; while (0)
      +#define SET_LONGPRECISION(f)     do (f) |= FLAG_LONGPRECISION; while (0)
      +#define SET_LONGLONGPRECISION(f) do (f) |= FLAG_LONGLONGPRECISION; while (0)
      +#define SET_NEGATE(f)            do (f) |= FLAG_NEGATE; while (0)
      +
      +#define CLR_SHOWPLUS(f)          do (f) &= ~FLAG_SHOWPLUS; while (0)
      +#define CLR_ALTFORM(f)           do (f) &= ~FLAG_ALTFORM; while (0)
      +#define CLR_HASDOT(f)            do (f) &= ~FLAG_HASDOT; while (0)
      +#define CLR_HASASTERISKWIDTH(f)  do (f) &= ~FLAG_HASASTERISKWIDTH; while (0)
      +#define CLR_HASASTERISKTRUNC(f)  do (f) &= ~FLAG_HASASTERISKTRUNC; while (0)
      +#define CLR_LONGPRECISION(f)     do (f) &= ~FLAG_LONGPRECISION; while (0)
      +#define CLR_LONGLONGPRECISION(f) do (f) &= ~FLAG_LONGLONGPRECISION; while (0)
      +#define CLR_NEGATE(f)            do (f) &= ~FLAG_NEGATE; while (0)
      +#define CLR_SIGNED(f)            do (f) &= ~(FLAG_SHOWPLUS|FLAG_NEGATE); while (0)
      +
      +#define IS_SHOWPLUS(f)           (((f) & FLAG_SHOWPLUS) != 0)
      +#define IS_ALTFORM(f)            (((f) & FLAG_ALTFORM) != 0)
      +#define IS_HASDOT(f)             (((f) & FLAG_HASDOT) != 0)
      +#define IS_HASASTERISKWIDTH(f)   (((f) & FLAG_HASASTERISKWIDTH) != 0)
      +#define IS_HASASTERISKTRUNC(f)   (((f) & FLAG_HASASTERISKTRUNC) != 0)
      +#define IS_LONGPRECISION(f)      (((f) & FLAG_LONGPRECISION) != 0)
      +#define IS_LONGLONGPRECISION(f)  (((f) & FLAG_LONGLONGPRECISION) != 0)
      +#define IS_NEGATE(f)             (((f) & FLAG_NEGATE) != 0)
      +#define IS_SIGNED(f)             (((f) & (FLAG_SHOWPLUS|FLAG_NEGATE)) != 0)
      +
      +/* If CONFIG_ARCH_ROMGETC is defined, then it is assumed that the format
      + * string data cannot be accessed by simply de-referencing the format string
      + * pointer.  This might be in the case in Harvard architectures where string
      + * data might be stored in instruction space or if string data were stored
      + * on some media like EEPROM or external serial FLASH.  In all of these cases,
      + * string data has to be accessed indirectly using the architecture-supplied
      + * up_romgetc().  The following mechanisms attempt to make these different
      + * access methods indistinguishable in the following code.
      + *
      + * NOTE: It is assumed that string arguments for %s still reside in memory
      + * that can be directly accessed by de-referencing the string pointer.
      + */
      +
      +#ifdef CONFIG_ARCH_ROMGETC
      +#  define FMT_TOP      ch = up_romgetc(src)         /* Loop initialization */
      +#  define FMT_BOTTOM   src++, ch = up_romgetc(src)  /* Bottom of a loop */
      +#  define FMT_CHAR     ch                           /* Access a character */
      +#  define FMT_NEXT     src++; ch = up_romgetc(src)  /* Advance to the next character */
      +#  define FMT_PREV     src--; ch = up_romgetc(src)  /* Backup to the previous character */
      +#else
      +#  define FMT_TOP                                   /* Loop initialization */
      +#  define FMT_BOTTOM   src++                        /* Bottom of a loop */
      +#  define FMT_CHAR     *src                         /* Access a character */
      +#  define FMT_NEXT     src++                        /* Advance to the next character */
      +#  define FMT_PREV     src--                        /* Backup to the previous character */
      +#endif
      + 
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +enum
      +{
      +  FMT_RJUST = 0, /* Default */
      +  FMT_LJUST,
      +  FMT_RJUST0,
      +  FMT_CENTER
      +};
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/* Pointer to ASCII conversion */
      +
      +#ifdef CONFIG_PTR_IS_NOT_INT
      +static void ptohex(FAR struct lib_outstream_s *obj, uint8_t flags, FAR void *p);
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static int  getsizesize(uint8_t fmt, uint8_t flags, FAR void *p)
      +#endif /* CONFIG_NOPRINTF_FIELDWIDTH */
      +#endif /* CONFIG_PTR_IS_NOT_INT */
      +
      +/* Unsigned int to ASCII conversion */
      +
      +static void utodec(FAR struct lib_outstream_s *obj, unsigned int n);
      +static void utohex(FAR struct lib_outstream_s *obj, unsigned int n, uint8_t a);
      +static void utooct(FAR struct lib_outstream_s *obj, unsigned int n);
      +static void utobin(FAR struct lib_outstream_s *obj, unsigned int n);
      +static void utoascii(FAR struct lib_outstream_s *obj, uint8_t fmt,
      +                     uint8_t flags, unsigned int lln);
      +
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static void fixup(uint8_t fmt, FAR uint8_t *flags, int *n);
      +static int  getusize(uint8_t fmt, uint8_t flags, unsigned int lln);
      +#endif
      +
      +/* Unsigned long int to ASCII conversion */
      +
      +#ifdef CONFIG_LONG_IS_NOT_INT
      +static void lutodec(FAR struct lib_outstream_s *obj, unsigned long ln);
      +static void lutohex(FAR struct lib_outstream_s *obj, unsigned long ln, uint8_t a);
      +static void lutooct(FAR struct lib_outstream_s *obj, unsigned long ln);
      +static void lutobin(FAR struct lib_outstream_s *obj, unsigned long ln);
      +static void lutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt,
      +                      uint8_t flags, unsigned long ln);
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static void lfixup(uint8_t fmt, FAR uint8_t *flags, long *ln);
      +static int  getlusize(uint8_t fmt, FAR uint8_t flags, unsigned long ln);
      +#endif
      +#endif
      +
      +/* Unsigned long long int to ASCII conversions */
      +
      +#ifdef CONFIG_HAVE_LONG_LONG
      +static void llutodec(FAR struct lib_outstream_s *obj, unsigned long long lln);
      +static void llutohex(FAR struct lib_outstream_s *obj, unsigned long long lln, uint8_t a);
      +static void llutooct(FAR struct lib_outstream_s *obj, unsigned long long lln);
      +static void llutobin(FAR struct lib_outstream_s *obj, unsigned long long lln);
      +static void llutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt,
      +                       uint8_t flags, unsigned long long lln);
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static void llfixup(uint8_t fmt, FAR uint8_t *flags, FAR long long *lln);
      +static int  getllusize(uint8_t fmt, FAR uint8_t flags, FAR unsigned long long lln);
      +#endif
      +#endif
      +
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static void prejustify(FAR struct lib_outstream_s *obj, uint8_t fmt,
      +                       uint8_t flags, int fieldwidth, int valwidth);
      +static void postjustify(FAR struct lib_outstream_s *obj, uint8_t fmt,
      +                        uint8_t flags, int fieldwidth, int valwidth);
      +#endif
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +static const char g_nullstring[] = "(null)";
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/* Include floating point functions */
      + 
      +#ifdef CONFIG_LIBC_FLOATINGPOINT
      +#  include "stdio/lib_libdtoa.c"
      +#endif
      +
      +/****************************************************************************
      + * Name: ptohex
      + ****************************************************************************/
      +
      +#ifdef CONFIG_PTR_IS_NOT_INT
      +static void ptohex(FAR struct lib_outstream_s *obj, uint8_t flags, FAR void *p)
      +{
      +  union
      +  {
      +    uint32_t  dw;
      +    FAR void *p;
      +  } u;
      +  uint8_t bits;
      +
      +  /* Check for alternate form */
      +
      +  if (IS_ALTFORM(flags))
      +    {
      +      /* Prefix the number with "0x" */
      +
      +      obj->put(obj, '0');
      +      obj->put(obj, 'x');
      +    }
      +
      +  u.dw = 0;
      +  u.p  = p;
      +
      +  for (bits = 8*sizeof(void *); bits > 0; bits -= 4)
      +    {
      +      uint8_t nibble = (uint8_t)((u.dw >> (bits - 4)) & 0xf);
      +      if (nibble < 10)
      +        {
      +          obj->put(obj, nibble + '0');
      +        }
      +      else
      +        {
      +          obj->put(obj, nibble + 'a' - 10);
      +        }
      +    }
      +}
      +
      +/****************************************************************************
      + * Name: getpsize
      + ****************************************************************************/
      +
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static int getpsize(uint8_t flags, FAR void *p)
      +{
      +  struct lib_outstream_s nulloutstream;
      +  lib_nulloutstream(&nulloutstream);
      +
      +  ptohex(&nulloutstream, flags, p);
      +  return nulloutstream.nput;
      +}
      +
      +#endif /* CONFIG_NOPRINTF_FIELDWIDTH */
      +#endif /* CONFIG_PTR_IS_NOT_INT */
      +
      +/****************************************************************************
      + * Name: utodec
      + ****************************************************************************/
      +
      +static void utodec(FAR struct lib_outstream_s *obj, unsigned int n)
      +{
      +  unsigned int remainder = n % 10;
      +  unsigned int dividend  = n / 10;
      +
      +  if (dividend)
      +    {
      +      utodec(obj, dividend);
      +    }
      +
      +  obj->put(obj, (remainder + (unsigned int)'0'));
      +}
      +
      +/****************************************************************************
      + * Name: utohex
      + ****************************************************************************/
      +
      +static void utohex(FAR struct lib_outstream_s *obj, unsigned int n, uint8_t a)
      +{
      +  bool    nonzero = false;
      +  uint8_t bits;
      +
      +  for (bits = 8*sizeof(unsigned int); bits > 0; bits -= 4)
      +    {
      +      uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf);
      +      if (nibble || nonzero)
      +        {
      +          nonzero = true;
      +
      +          if (nibble < 10)
      +            {
      +              obj->put(obj, nibble + '0');
      +            }
      +          else
      +            {
      +              obj->put(obj, nibble + a - 10);
      +            }
      +        }
      +    }
      +
      +  if (!nonzero)
      +    {
      +      obj->put(obj, '0');
      +    }
      +}
      +
      +/****************************************************************************
      + * Name: utooct
      + ****************************************************************************/
      +
      +static void utooct(FAR struct lib_outstream_s *obj, unsigned int n)
      +{
      +  unsigned int remainder = n & 0x7;
      +  unsigned int dividend = n >> 3;
      +
      +  if (dividend)
      +    {
      +      utooct(obj, dividend);
      +    }
      +
      +  obj->put(obj, (remainder + (unsigned int)'0'));
      +}
      +
      +/****************************************************************************
      + * Name: utobin
      + ****************************************************************************/
      +
      +static void utobin(FAR struct lib_outstream_s *obj, unsigned int n)
      +{
      +  unsigned int remainder = n & 1;
      +  unsigned int dividend = n >> 1;
      +
      +  if (dividend)
      +    {
      +      utobin(obj, dividend);
      +    }
      +
      +  obj->put(obj, (remainder + (unsigned int)'0'));
      +}
      +
      +/****************************************************************************
      + * Name: utoascii
      + ****************************************************************************/
      +
      +static void utoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned int n)
      +{
      +  /* Perform the integer conversion according to the format specifier */
      +
      +  switch (fmt)
      +    {
      +      case 'd':
      +      case 'i':
      +        /* Signed base 10 */
      +        {
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +          if ((int)n < 0)
      +            {
      +              obj->put(obj, '-');
      +              n = (unsigned int)(-(int)n);
      +            }
      +          else if (IS_SHOWPLUS(flags))
      +            {
      +              obj->put(obj, '+');
      +            }
      +#endif
      +          /* Convert the unsigned value to a string. */
      +
      +          utodec(obj, n);
      +        }
      +        break;
      +
      +      case 'u':
      +        /* Unigned base 10 */
      +        {
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +          if (IS_SHOWPLUS(flags))
      +            {
      +              obj->put(obj, '+');
      +            }
      +#endif
      +          /* Convert the unsigned value to a string. */
      +
      +          utodec(obj, n);
      +        }
      +        break;
      +
      +#ifndef CONFIG_PTR_IS_NOT_INT
      +      case 'p':
      +#endif
      +      case 'x':
      +      case 'X':
      +        /* Hexadecimal */
      +        {
      +          /* Check for alternate form */
      +
      +          if (IS_ALTFORM(flags))
      +            {
      +              /* Prefix the number with "0x" */
      +
      +              obj->put(obj, '0');
      +              obj->put(obj, 'x');
      +            }
      +
      +          /* Convert the unsigned value to a string. */
      +
      +          if (fmt == 'X')
      +            {
      +              utohex(obj, n, 'A');
      +            }
      +          else
      +            {
      +              utohex(obj, n, 'a');
      +            }
      +        }
      +        break;
      +
      +      case 'o':
      +        /* Octal */
      +         {
      +           /* Check for alternate form */
      +
      +           if (IS_ALTFORM(flags))
      +             {
      +               /* Prefix the number with '0' */
      +
      +               obj->put(obj, '0');
      +             }
      +
      +           /* Convert the unsigned value to a string. */
      +
      +           utooct(obj, n);
      +         }
      +         break;
      +
      +      case 'b':
      +        /* Binary */
      +        {
      +          /* Convert the unsigned value to a string. */
      +
      +          utobin(obj, n);
      +        }
      +        break;
      +
      +#ifdef CONFIG_PTR_IS_NOT_INT
      +      case 'p':
      +#endif
      +      default:
      +        break;
      +    }
      +}
      +
      +/****************************************************************************
      + * Name: fixup
      + ****************************************************************************/
      +
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static void fixup(uint8_t fmt, FAR uint8_t *flags, FAR int *n)
      +{
      +  /* Perform the integer conversion according to the format specifier */
      +
      +  switch (fmt)
      +    {
      +      case 'd':
      +      case 'i':
      +        /* Signed base 10 */
      +
      +        if (*n < 0)
      +          {
      +            SET_NEGATE(*flags);
      +            CLR_SHOWPLUS(*flags);
      +            *n    = -*n;
      +          }
      +        break;
      +
      +      case 'u':
      +        /* Unsigned base 10 */
      +        break;
      +
      +      case 'p':
      +      case 'x':
      +      case 'X':
      +        /* Hexadecimal */
      +      case 'o':
      +        /* Octal */
      +      case 'b':
      +        /* Binary */
      +        CLR_SIGNED(*flags);
      +        break;
      +
      +      default:
      +        break;
      +    }
      +}
      +
      +/****************************************************************************
      + * Name: getusize
      + ****************************************************************************/
      +
      +static int getusize(uint8_t fmt, uint8_t flags, unsigned int n)
      +{
      +  struct lib_outstream_s nulloutstream;
      +  lib_nulloutstream(&nulloutstream);
      +
      +  utoascii(&nulloutstream, fmt, flags, n);
      +  return nulloutstream.nput;
      +}
      +
      +/****************************************************************************
      + * Name: getdblsize
      + ****************************************************************************/
      +
      +#ifdef CONFIG_LIBC_FLOATINGPOINT
      +static int getdblsize(uint8_t fmt, int trunc, uint8_t flags, double n)
      +{
      +  struct lib_outstream_s nulloutstream;
      +  lib_nulloutstream(&nulloutstream);
      +
      +  lib_dtoa(&nulloutstream, fmt, trunc, flags, n);
      +  return nulloutstream.nput;
      +}
      +#endif
      +#endif /* CONFIG_NOPRINTF_FIELDWIDTH */
      +
      +#ifdef CONFIG_LONG_IS_NOT_INT
      +/****************************************************************************
      + * Name: lutodec
      + ****************************************************************************/
      +
      +static void lutodec(FAR struct lib_outstream_s *obj, unsigned long n)
      +{
      +  unsigned int  remainder = n % 10;
      +  unsigned long dividend  = n / 10;
      +
      +  if (dividend)
      +    {
      +      lutodec(obj, dividend);
      +    }
      +
      +  obj->put(obj, (remainder + (unsigned int)'0'));
      +}
      +
      +/****************************************************************************
      + * Name: lutohex
      + ****************************************************************************/
      +
      +static void lutohex(FAR struct lib_outstream_s *obj, unsigned long n, uint8_t a)
      +{
      +  bool    nonzero = false;
      +  uint8_t bits;
      +
      +  for (bits = 8*sizeof(unsigned long); bits > 0; bits -= 4)
      +    {
      +      uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf);
      +      if (nibble || nonzero)
      +        {
      +          nonzero = true;
      +
      +          if (nibble < 10)
      +            {
      +              obj->put(obj, nibble + '0');
      +            }
      +          else
      +            {
      +              obj->put(obj, nibble + a - 10);
      +            }
      +        }
      +    }
      +
      +  if (!nonzero)
      +    {
      +      obj->put(obj, '0');
      +    }
      +}
      +
      +/****************************************************************************
      + * Name: lutooct
      + ****************************************************************************/
      +
      +static void lutooct(FAR struct lib_outstream_s *obj, unsigned long n)
      +{
      +  unsigned int  remainder = n & 0x7;
      +  unsigned long dividend  = n >> 3;
      +
      +  if (dividend)
      +    {
      +      lutooct(obj, dividend);
      +    }
      +
      +  obj->put(obj, (remainder + (unsigned int)'0'));
      +}
      +
      +/****************************************************************************
      + * Name: lutobin
      + ****************************************************************************/
      +
      +static void lutobin(FAR struct lib_outstream_s *obj, unsigned long n)
      +{
      +  unsigned int  remainder = n & 1;
      +  unsigned long dividend  = n >> 1;
      +
      +  if (dividend)
      +    {
      +      lutobin(obj, dividend);
      +    }
      +
      +  obj->put(obj, (remainder + (unsigned int)'0'));
      +}
      +
      +/****************************************************************************
      + * Name: lutoascii
      + ****************************************************************************/
      +
      +static void lutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned long ln)
      +{
      +  /* Perform the integer conversion according to the format specifier */
      +
      +  switch (fmt)
      +    {
      +      case 'd':
      +      case 'i':
      +        /* Signed base 10 */
      +        {
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +          if ((long)ln < 0)
      +            {
      +              obj->put(obj, '-');
      +              ln    = (unsigned long)(-(long)ln);
      +            }
      +          else if (IS_SHOWPLUS(flags))
      +            {
      +              obj->put(obj, '+');
      +            }
      +#endif
      +          /* Convert the unsigned value to a string. */
      +
      +          lutodec(obj, ln);
      +        }
      +        break;
      +
      +      case 'u':
      +        /* Unigned base 10 */
      +        {
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +          if (IS_SHOWPLUS(flags))
      +            {
      +              obj->put(obj, '+');
      +            }
      +#endif
      +          /* Convert the unsigned value to a string. */
      +
      +          lutodec(obj, ln);
      +        }
      +        break;
      +
      +      case 'x':
      +      case 'X':
      +        /* Hexadecimal */
      +        {
      +          /* Check for alternate form */
      +
      +          if (IS_ALTFORM(flags))
      +            {
      +              /* Prefix the number with "0x" */
      +
      +              obj->put(obj, '0');
      +              obj->put(obj, 'x');
      +            }
      +
      +          /* Convert the unsigned value to a string. */
      +
      +          if (fmt == 'X')
      +            {
      +              lutohex(obj, ln, 'A');
      +            }
      +          else
      +            {
      +              lutohex(obj, ln, 'a');
      +            }
      +        }
      +        break;
      +
      +      case 'o':
      +        /* Octal */
      +         {
      +           /* Check for alternate form */
      +
      +           if (IS_ALTFORM(flags))
      +             {
      +               /* Prefix the number with '0' */
      +
      +               obj->put(obj, '0');
      +             }
      +
      +           /* Convert the unsigned value to a string. */
      +
      +           lutooct(obj, ln);
      +         }
      +         break;
      +
      +      case 'b':
      +        /* Binary */
      +        {
      +          /* Convert the unsigned value to a string. */
      +
      +          lutobin(obj, ln);
      +        }
      +        break;
      +
      +      case 'p':
      +      default:
      +        break;
      +    }
      +}
      +
      +/****************************************************************************
      + * Name: lfixup
      + ****************************************************************************/
      +
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static void lfixup(uint8_t fmt, FAR uint8_t *flags, FAR long *ln)
      +{
      +  /* Perform the integer conversion according to the format specifier */
      +
      +  switch (fmt)
      +    {
      +      case 'd':
      +      case 'i':
      +        /* Signed base 10 */
      +
      +        if (*ln < 0)
      +          {
      +            SET_NEGATE(*flags);
      +            CLR_SHOWPLUS(*flags);
      +            *ln    = -*ln;
      +          }
      +        break;
      +
      +      case 'u':
      +        /* Unsigned base 10 */
      +        break;
      +
      +      case 'p':
      +      case 'x':
      +      case 'X':
      +        /* Hexadecimal */
      +      case 'o':
      +        /* Octal */
      +      case 'b':
      +        /* Binary */
      +        CLR_SIGNED(*flags);
      +        break;
      +
      +      default:
      +        break;
      +    }
      +}
      +
      +/****************************************************************************
      + * Name: getlusize
      + ****************************************************************************/
      +
      +static int getlusize(uint8_t fmt, uint8_t flags, unsigned long ln)
      +{
      +  struct lib_outstream_s nulloutstream;
      +  lib_nulloutstream(&nulloutstream);
      +
      +  lutoascii(&nulloutstream, fmt, flags, ln);
      +  return nulloutstream.nput;
      +}
      +
      +#endif /* CONFIG_NOPRINTF_FIELDWIDTH */
      +#endif /* CONFIG_LONG_IS_NOT_INT */
      +
      +#ifdef CONFIG_HAVE_LONG_LONG
      +/****************************************************************************
      + * Name: llutodec
      + ****************************************************************************/
      +
      +static void llutodec(FAR struct lib_outstream_s *obj, unsigned long long n)
      +{
      +  unsigned int remainder = n % 10;
      +  unsigned long long dividend = n / 10;
      +
      +  if (dividend)
      +    {
      +      llutodec(obj, dividend);
      +    }
      +
      +  obj->put(obj, (remainder + (unsigned int)'0'));
      +}
      +
      +/****************************************************************************
      + * Name: llutohex
      + ****************************************************************************/
      +
      +static void llutohex(FAR struct lib_outstream_s *obj, unsigned long long n, uint8_t a)
      +{
      +  bool    nonzero = false;
      +  uint8_t bits;
      +
      +  for (bits = 8*sizeof(unsigned long long); bits > 0; bits -= 4)
      +    {
      +      uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf);
      +      if (nibble || nonzero)
      +        {
      +          nonzero = true;
      +
      +          if (nibble < 10)
      +            {
      +              obj->put(obj, (nibble + '0'));
      +            }
      +          else
      +            {
      +              obj->put(obj, (nibble + a - 10));
      +            }
      +        }
      +    }
      +
      +  if (!nonzero)
      +    {
      +      obj->put(obj, '0');
      +    }
      +}
      +
      +/****************************************************************************
      + * Name: llutooct
      + ****************************************************************************/
      +
      +static void llutooct(FAR struct lib_outstream_s *obj, unsigned long long n)
      +{
      +  unsigned int remainder = n & 0x7;
      +  unsigned long long dividend = n >> 3;
      +
      +  if (dividend)
      +    {
      +      llutooct(obj, dividend);
      +    }
      +
      +  obj->put(obj, (remainder + (unsigned int)'0'));
      +}
      +
      +/****************************************************************************
      + * Name: llutobin
      + ****************************************************************************/
      +
      +static void llutobin(FAR struct lib_outstream_s *obj, unsigned long long n)
      +{
      +  unsigned int remainder = n & 1;
      +  unsigned long long dividend = n >> 1;
      +
      +  if (dividend)
      +    {
      +      llutobin(obj, dividend);
      +    }
      +
      +  obj->put(obj, (remainder + (unsigned int)'0'));
      +}
      +
      +/****************************************************************************
      + * Name: llutoascii
      + ****************************************************************************/
      +
      +static void llutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned long long lln)
      +{
      +  /* Perform the integer conversion according to the format specifier */
      +
      +  switch (fmt)
      +    {
      +      case 'd':
      +      case 'i':
      +        /* Signed base 10 */
      +        {
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +          if ((long long)lln < 0)
      +            {
      +              obj->put(obj, '-');
      +              lln    = (unsigned long long)(-(long long)lln);
      +            }
      +          else if (IS_SHOWPLUS(flags))
      +            {
      +              obj->put(obj, '+');
      +            }
      +#endif
      +          /* Convert the unsigned value to a string. */
      +
      +          llutodec(obj, (unsigned long long)lln);
      +        }
      +        break;
      +
      +      case 'u':
      +        /* Unigned base 10 */
      +        {
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +          if (IS_SHOWPLUS(flags))
      +            {
      +              obj->put(obj, '+');
      +            }
      +#endif
      +          /* Convert the unsigned value to a string. */
      +
      +          llutodec(obj, (unsigned long long)lln);
      +        }
      +        break;
      +
      +      case 'x':
      +      case 'X':
      +        /* Hexadecimal */
      +        {
      +          /* Check for alternate form */
      +
      +          if (IS_ALTFORM(flags))
      +            {
      +              /* Prefix the number with "0x" */
      +
      +              obj->put(obj, '0');
      +              obj->put(obj, 'x');
      +            }
      +
      +          /* Convert the unsigned value to a string. */
      +
      +          if (fmt == 'X')
      +            {
      +              llutohex(obj, (unsigned long long)lln, 'A');
      +            }
      +          else
      +            {
      +              llutohex(obj, (unsigned long long)lln, 'a');
      +            }
      +        }
      +        break;
      +
      +      case 'o':
      +        /* Octal */
      +         {
      +           /* Check for alternate form */
      +
      +           if (IS_ALTFORM(flags))
      +             {
      +               /* Prefix the number with '0' */
      +
      +               obj->put(obj, '0');
      +             }
      +
      +           /* Convert the unsigned value to a string. */
      +
      +           llutooct(obj, (unsigned long long)lln);
      +         }
      +         break;
      +
      +      case 'b':
      +        /* Binary */
      +        {
      +          /* Convert the unsigned value to a string. */
      +
      +          llutobin(obj, (unsigned long long)lln);
      +        }
      +        break;
      +
      +      case 'p':
      +      default:
      +        break;
      +    }
      +}
      +
      +/****************************************************************************
      + * Name: llfixup
      + ****************************************************************************/
      +
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static void llfixup(uint8_t fmt, FAR uint8_t *flags, FAR long long *lln)
      +{
      +  /* Perform the integer conversion according to the format specifier */
      +
      +  switch (fmt)
      +    {
      +      case 'd':
      +      case 'i':
      +        /* Signed base 10 */
      +
      +        if (*lln < 0)
      +          {
      +            SET_NEGATE(*flags);
      +            CLR_SHOWPLUS(*flags);
      +            *lln    = -*lln;
      +          }
      +        break;
      +
      +      case 'u':
      +        /* Unsigned base 10 */
      +        break;
      +
      +      case 'p':
      +      case 'x':
      +      case 'X':
      +        /* Hexadecimal */
      +      case 'o':
      +        /* Octal */
      +      case 'b':
      +        /* Binary */
      +        CLR_SIGNED(*flags);
      +        break;
      +
      +      default:
      +        break;
      +    }
      +}
      +
      +/****************************************************************************
      + * Name: getllusize
      + ****************************************************************************/
      +
      +static int getllusize(uint8_t fmt, uint8_t flags, unsigned long long lln)
      +{
      +  struct lib_outstream_s nulloutstream;
      +  lib_nulloutstream(&nulloutstream);
      +
      +
      +  llutoascii(&nulloutstream, fmt, flags, lln);
      +  return nulloutstream.nput;
      +}
      +
      +#endif /* CONFIG_NOPRINTF_FIELDWIDTH */
      +#endif /* CONFIG_HAVE_LONG_LONG */
      +
      +/****************************************************************************
      + * Name: prejustify
      + ****************************************************************************/
      +
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static void prejustify(FAR struct lib_outstream_s *obj, uint8_t fmt,
      +                       uint8_t flags, int fieldwidth, int valwidth)
      +{
      +  int i;
      +
      +  switch (fmt)
      +    {
      +      default:
      +      case FMT_RJUST:
      +        if (IS_SIGNED(flags))
      +          {
      +            valwidth++;
      +          }
      +
      +        for (i = fieldwidth - valwidth; i > 0; i--)
      +          {
      +            obj->put(obj, ' ');
      +          }
      +
      +        if (IS_NEGATE(flags))
      +          {
      +            obj->put(obj, '-');
      +          }
      +        else if (IS_SHOWPLUS(flags))
      +          {
      +            obj->put(obj, '+');
      +          }
      +        break;
      +
      +      case FMT_RJUST0:
      +         if (IS_NEGATE(flags))
      +          {
      +            obj->put(obj, '-');
      +            valwidth++;
      +          }
      +        else if (IS_SHOWPLUS(flags))
      +          {
      +            obj->put(obj, '+');
      +            valwidth++;
      +          }
      +
      +        for (i = fieldwidth - valwidth; i > 0; i--)
      +          {
      +            obj->put(obj, '0');
      +          }
      +        break;
      +
      +      case FMT_LJUST:
      +         if (IS_NEGATE(flags))
      +          {
      +            obj->put(obj, '-');
      +          }
      +        else if (IS_SHOWPLUS(flags))
      +          {
      +            obj->put(obj, '+');
      +          }
      +        break;
      +    }
      +}
      +#endif
      +
      +/****************************************************************************
      + * Name: postjustify
      + ****************************************************************************/
      +
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +static void postjustify(FAR struct lib_outstream_s *obj, uint8_t fmt,
      +                        uint8_t flags, int fieldwidth, int valwidth)
      +{
      +  int i;
      +
      +  /* Apply field justification to the integer value. */
      +
      +  switch (fmt)
      +    {
      +      default:
      +      case FMT_RJUST:
      +      case FMT_RJUST0:
      +        break;
      +
      +      case FMT_LJUST:
      +        if (IS_SIGNED(flags))
      +          {
      +            valwidth++;
      +          }
      +
      +        for (i = fieldwidth - valwidth; i > 0; i--)
      +          {
      +            obj->put(obj, ' ');
      +          }
      +        break;
      +    }
      +}
      +#endif
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * lib/stdio/lib_vsprintf
      + ****************************************************************************/
      +
      +int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list ap)
      +{
      +  FAR char        *ptmp;
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +  int             width;
      +#ifdef CONFIG_LIBC_FLOATINGPOINT
      +  int             trunc;
      +#endif
      +  uint8_t         fmt;
      +#endif
      +  uint8_t         flags;
      +#ifdef CONFIG_ARCH_ROMGETC
      +  char            ch;
      +#endif
      +
      +  for (FMT_TOP; FMT_CHAR; FMT_BOTTOM)
      +    {
      +      /* Just copy regular characters */
      +
      +      if (FMT_CHAR != '%')
      +        {
      +           /* Output the character */
      +
      +           obj->put(obj, FMT_CHAR);
      +
      +           /* Flush the buffer if a newline is encountered */
      +
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +           if (FMT_CHAR == '\n')
      +             {
      +               /* Should return an error on a failure to flush */
      +
      +               (void)obj->flush(obj);
      +             }
      +#endif
      +           /* Process the next character in the format */
      +
      +           continue;
      +        }
      +
      +      /* We have found a format specifier. Move past it. */
      +
      +      FMT_NEXT;
      +
      +      /* Assume defaults */
      +
      +      flags = 0;
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +      fmt   = FMT_RJUST;
      +      width = 0;
      +#ifdef CONFIG_LIBC_FLOATINGPOINT
      +      trunc = 0;
      +#endif
      +#endif
      +
      +      /* Process each format qualifier. */
      +
      +      for (; FMT_CHAR; FMT_BOTTOM)
      +        {
      +          /* Break out of the loop when the format is known. */
      +
      +          if (strchr("diuxXpobeEfgGlLsc%", FMT_CHAR))
      +            {
      +              break;
      +            }
      +
      +          /* Check for left justification. */
      +
      +          else if (FMT_CHAR == '-')
      +            {
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +              fmt = FMT_LJUST;
      +#endif
      +            }
      +
      +          /* Check for leading zero fill right justification. */
      +
      +          else if (FMT_CHAR == '0')
      +            {
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +              fmt = FMT_RJUST0;
      +#endif
      +            }
      +#if 0
      +          /* Center justification. */
      +
      +          else if (FMT_CHAR == '~')
      +            {
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +              fmt = FMT_CENTER;
      +#endif
      +            }
      +#endif
      +
      +          else if (FMT_CHAR == '*')
      +            {
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +              int value = va_arg(ap, int);
      +              if (IS_HASDOT(flags))
      +                {
      +#ifdef CONFIG_LIBC_FLOATINGPOINT
      +                  trunc = value;
      +                  SET_HASASTERISKTRUNC(flags);
      +#endif
      +                }
      +              else
      +                {
      +                  width = value;
      +                  SET_HASASTERISKWIDTH(flags);
      +                }
      +#endif
      +            }
      +
      +          /* Check for field width */
      +
      +          else if (FMT_CHAR >= '1' && FMT_CHAR <= '9')
      +            {
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +              do
      +                {
      +                  FMT_NEXT;
      +                }
      +              while (FMT_CHAR >= '0' && FMT_CHAR <= '9');
      +#else
      +              /* Accumulate the field width integer. */
      +
      +              int n = ((int)(FMT_CHAR)) - (int)'0';
      +              for (;;)
      +                {
      +                  FMT_NEXT;
      +                  if (FMT_CHAR >= '0' && FMT_CHAR <= '9')
      +                    {
      +                      n = 10*n + (((int)(FMT_CHAR)) - (int)'0');
      +                    }
      +                  else
      +                    {
      +                      break;
      +                    }
      +                }
      +
      +              if (IS_HASDOT(flags))
      +                {
      +#ifdef CONFIG_LIBC_FLOATINGPOINT
      +                  trunc = n;
      +#endif
      +                }
      +              else
      +                {
      +                  width = n;
      +                }
      +#endif
      +              /* Back up to the last digit. */
      +
      +              FMT_PREV;
      +            }
      +
      +          /* Check for a decimal point. */
      +
      +          else if (FMT_CHAR == '.')
      +            {
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +              SET_HASDOT(flags);
      +#endif
      +            }
      +
      +          /* Check for leading plus sign. */
      +
      +          else if (FMT_CHAR == '+')
      +            {
      +              SET_SHOWPLUS(flags);
      +            }
      +
      +          /* Check for alternate form. */
      +
      +          else if (FMT_CHAR == '#')
      +            {
      +              SET_ALTFORM(flags);
      +            }
      +        }
      +
      +      /* "%%" means that a literal '%' was intended (instead of a format
      +       * specification).
      +       */
      +
      +      if (FMT_CHAR == '%')
      +        {
      +          obj->put(obj, '%');
      +          continue;
      +        }
      +
      +      /* Check for the string format. */
      +
      +      if (FMT_CHAR == 's')
      +        {
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +          int swidth;
      +#endif
      +          /* Get the string to output */
      +
      +          ptmp = va_arg(ap, char *);
      +          if (!ptmp)
      +            {
      +              ptmp = (char*)g_nullstring;
      +            }
      +
      +          /* Get the widith of the string and perform right-justification
      +           * operations.
      +           */
      +
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +          swidth = strlen(ptmp);
      +          prejustify(obj, fmt, 0, width, swidth);
      +#endif
      +          /* Concatenate the string into the output */
      +
      +          while (*ptmp)
      +            {
      +              obj->put(obj, *ptmp);
      +              ptmp++;
      +            }
      +
      +          /* Perform left-justification operations. */
      +
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +          postjustify(obj, fmt, 0, width, swidth);
      +#endif
      +          continue;
      +        }
      +
      +      /* Check for the character output */
      +
      +      else if (FMT_CHAR == 'c')
      +        {
      +          /* Just copy the character into the output. */
      +
      +          int n = va_arg(ap, int);
      +          obj->put(obj, n);
      +          continue;
      +        }
      +
      +      /* Check for the long long prefix. */
      +
      +      if (FMT_CHAR == 'L')
      +        {
      +           SET_LONGLONGPRECISION(flags);
      +           FMT_NEXT;
      +        }
      +      else if (FMT_CHAR == 'l')
      +        {
      +          SET_LONGPRECISION(flags);
      +          FMT_NEXT;
      +          if (FMT_CHAR == 'l')
      +            {
      +              SET_LONGLONGPRECISION(flags);
      +              FMT_NEXT;
      +            }
      +        }
      +
      +      /* Handle integer conversions */
      +
      +      if (strchr("diuxXpob", FMT_CHAR))
      +        {
      +#ifdef CONFIG_HAVE_LONG_LONG
      +          if (IS_LONGLONGPRECISION(flags) && FMT_CHAR != 'p')
      +            {
      +              long long lln;
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +              int lluwidth;
      +#endif
      +              /* Extract the long long value. */
      +
      +              lln = va_arg(ap, long long);
      +
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +              /* Output the number */
      +
      +              llutoascii(obj, FMT_CHAR, flags, (unsigned long long)lln);
      +#else
      +              /* Resolve sign-ness and format issues */
      +
      +              llfixup(FMT_CHAR, &flags, &lln);
      +
      +              /* Get the width of the output */
      +
      +              lluwidth = getllusize(FMT_CHAR, flags, lln);
      +
      +              /* Perform left field justification actions */
      +
      +              prejustify(obj, fmt, flags, width, lluwidth);
      +
      +              /* Output the number */
      +
      +              llutoascii(obj, FMT_CHAR, flags, (unsigned long long)lln);
      +
      +              /* Perform right field justification actions */
      +
      +              postjustify(obj, fmt, flags, width, lluwidth);
      +#endif
      +            }
      +          else
      +#endif /* CONFIG_HAVE_LONG_LONG */
      +#ifdef CONFIG_LONG_IS_NOT_INT
      +          if (IS_LONGPRECISION(flags) && FMT_CHAR != 'p')
      +            {
      +              long ln;
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +              int luwidth;
      +#endif
      +              /* Extract the long value. */
      +
      +              ln = va_arg(ap, long);
      +
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +              /* Output the number */
      +
      +              lutoascii(obj, FMT_CHAR, flags, (unsigned long)ln);
      +#else
      +              /* Resolve sign-ness and format issues */
      +
      +              lfixup(FMT_CHAR, &flags, &ln);
      +
      +              /* Get the width of the output */
      +
      +              luwidth = getlusize(FMT_CHAR, flags, ln);
      +
      +              /* Perform left field justification actions */
      +
      +              prejustify(obj, fmt, flags, width, luwidth);
      +
      +              /* Output the number */
      +
      +              lutoascii(obj, FMT_CHAR, flags, (unsigned long)ln);
      +
      +              /* Perform right field justification actions */
      +
      +              postjustify(obj, fmt, flags, width, luwidth);
      +#endif
      +            }
      +          else
      +#endif /* CONFIG_LONG_IS_NOT_INT */
      +#ifdef CONFIG_PTR_IS_NOT_INT
      +          if (FMT_CHAR == 'p')
      +            {
      +              void *p;
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +              int pwidth;
      +#endif
      +              /* Extract the integer value. */
      +
      +              p = va_arg(ap, void *);
      +
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +              /* Output the pointer value */
      +
      +              ptohex(obj, flags, p);
      +#else
      +              /* Resolve sign-ness and format issues */
      +
      +              lfixup(FMT_CHAR, &flags, &ln);
      +
      +              /* Get the width of the output */
      +
      +              luwidth = getpsize(FMT_CHAR, flags, p);
      +
      +              /* Perform left field justification actions */
      +
      +              prejustify(obj, fmt, flags, width, pwidth);
      +
      +              /* Output the pointer value */
      +
      +              ptohex(obj, flags, p);
      +
      +              /* Perform right field justification actions */
      +
      +              postjustify(obj, fmt, flags, width, pwidth);
      +#endif
      +            }
      +          else
      +#endif
      +            {
      +              int n;
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +              int uwidth;
      +#endif
      +              /* Extract the long long value. */
      +
      +              n = va_arg(ap, int);
      +
      +#ifdef CONFIG_NOPRINTF_FIELDWIDTH
      +              /* Output the number */
      +
      +              utoascii(obj, FMT_CHAR, flags, (unsigned int)n);
      +#else
      +              /* Resolve sign-ness and format issues */
      +
      +              fixup(FMT_CHAR, &flags, &n);
      +
      +              /* Get the width of the output */
      +
      +              uwidth = getusize(FMT_CHAR, flags, n);
      +
      +              /* Perform left field justification actions */
      +
      +              prejustify(obj, fmt, flags, width, uwidth);
      +
      +              /* Output the number */
      +
      +              utoascii(obj, FMT_CHAR, flags, (unsigned int)n);
      +
      +              /* Perform right field justification actions */
      +
      +              postjustify(obj, fmt, flags, width, uwidth);
      +#endif
      +            }
      +        }
      +
      +      /* Handle floating point conversions */
      +
      +#ifdef CONFIG_LIBC_FLOATINGPOINT
      +      else if (strchr("eEfgG", FMT_CHAR))
      +        {
      +#ifndef CONFIG_NOPRINTF_FIELDWIDTH
      +          double dblval = va_arg(ap, double);
      +          int dblsize;
      +
      +          /* Get the width of the output */
      +
      +          dblsize = getdblsize(FMT_CHAR, trunc, flags, dblval);
      +
      +          /* Perform left field justification actions */
      +
      +          prejustify(obj, fmt, 0, width, dblsize);
      +
      +          /* Output the number */
      +
      +          lib_dtoa(obj, FMT_CHAR, trunc, flags, dblval);
      +
      +          /* Perform right field justification actions */
      +
      +          postjustify(obj, fmt, 0, width, dblsize);
      +#else
      +          /* Output the number with a fixed precision */
      +
      +          double dblval = va_arg(ap, double);
      +          lib_dtoa(obj, FMT_CHAR, CONFIG_LIBC_FIXEDPRECISION, flags, dblval);
      +#endif
      +        }
      +#endif /* CONFIG_LIBC_FLOATINGPOINT */
      +    }
      +
      +  return obj->nput;
      +}
      +
      +
      diff --git a/nuttx/lib/stdio/lib_lowinstream.c b/nuttx/lib/stdio/lib_lowinstream.c
      new file mode 100644
      index 0000000000..499a647ea2
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_lowinstream.c
      @@ -0,0 +1,102 @@
      +/****************************************************************************
      + * lib/stdio/lib_lowinstream.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +#ifdef CONFIG_ARCH_LOWGETC
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lowinstream_getc
      + ****************************************************************************/
      +
      +static int lowinstream_getc(FAR struct lib_instream_s *this)
      +{
      +  int ret;
      +
      +  DEBUGASSERT(this);
      +
      +  /* Get the next character from the incoming stream */
      +
      +  ret = up_getc(ch)
      +  if (ret != EOF)
      +    {
      +      this->nget++;
      +    }
      +
      +  return ret;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_lowinstream
      + *
      + * Description:
      + *   Initializes a stream for use with low-level, architecture-specific I/O.
      + *
      + * Input parameters:
      + *   lowoutstream - User allocated, uninitialized instance of struct
      + *                  lib_lowoutstream_s to be initialized.
      + *
      + * Returned Value:
      + *   None (User allocated instance initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_lowinstream(FAR struct lib_instream_s *stream)
      +{
      +  stream->get  = lowinstream_getc;
      +  stream->nget = 0;
      +}
      +
      +#endif /* CONFIG_ARCH_LOWGETC */
      diff --git a/nuttx/lib/stdio/lib_lowoutstream.c b/nuttx/lib/stdio/lib_lowoutstream.c
      new file mode 100644
      index 0000000000..092f39ca25
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_lowoutstream.c
      @@ -0,0 +1,97 @@
      +/****************************************************************************
      + * lib/stdio/lib_lowoutstream.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#ifdef CONFIG_ARCH_LOWPUTC
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lowoutstream_putc
      + ****************************************************************************/
      +
      +static void lowoutstream_putc(FAR struct lib_outstream_s *this, int ch)
      +{
      +  DEBUGASSERT(this);
      +
      +  if (up_putc(ch) != EOF)
      +    {
      +      this->nput++;
      +    }
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_lowoutstream
      + *
      + * Description:
      + *   Initializes a stream for use with low-level, architecture-specific I/O.
      + *
      + * Input parameters:
      + *   lowoutstream - User allocated, uninitialized instance of struct
      + *                  lib_lowoutstream_s to be initialized.
      + *
      + * Returned Value:
      + *   None (User allocated instance initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_lowoutstream(FAR struct lib_outstream_s *stream)
      +{
      +  stream->put   = lowoutstream_putc;
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +  stream->flush = lib_noflush;
      +#endif
      +  stream->nput  = 0;
      +}
      +
      +#endif /* CONFIG_ARCH_LOWPUTC */
      diff --git a/nuttx/lib/stdio/lib_lowprintf.c b/nuttx/lib/stdio/lib_lowprintf.c
      new file mode 100644
      index 0000000000..392ef2c6a8
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_lowprintf.c
      @@ -0,0 +1,128 @@
      +/****************************************************************************
      + * lib/stdio/lib_lowprintf.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +#include "lib_internal.h"
      +
      +/* This interface can only be used from within the kernel */
      +
      +#if !defined(CONFIG_NUTTX_KERNEL) || defined(__KERNEL__)
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_lowvprintf
      + ****************************************************************************/
      +
      +#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_SYSLOG)
      +
      +int lib_lowvprintf(const char *fmt, va_list ap)
      +{
      +  struct lib_outstream_s stream;
      +
      +  /* Wrap the stdout in a stream object and let lib_vsprintf do the work. */
      +
      +#ifdef CONFIG_SYSLOG
      +  lib_syslogstream((FAR struct lib_outstream_s *)&stream);
      +#else
      +  lib_lowoutstream((FAR struct lib_outstream_s *)&stream);
      +#endif
      +  return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap);
      +}
      +
      +/****************************************************************************
      + * Name: lib_lowprintf
      + ****************************************************************************/
      +
      +int lib_lowprintf(const char *fmt, ...)
      +{
      +  va_list ap;
      +  int     ret;
      +
      +#ifdef CONFIG_DEBUG_ENABLE
      +  ret = 0;
      +  if (g_dbgenable)
      +#endif
      +    {
      +      va_start(ap, fmt);
      +      ret = lib_lowvprintf(fmt, ap);
      +      va_end(ap);
      +    }
      +
      +  return ret;
      +}
      +
      +#endif /* CONFIG_ARCH_LOWPUTC || CONFIG_SYSLOG */
      +#endif /* __KERNEL__ */
      diff --git a/nuttx/lib/stdio/lib_meminstream.c b/nuttx/lib/stdio/lib_meminstream.c
      new file mode 100644
      index 0000000000..a842096fb4
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_meminstream.c
      @@ -0,0 +1,104 @@
      +/****************************************************************************
      + * lib/stdio/lib_meminstream.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: meminstream_getc
      + ****************************************************************************/
      +
      +static int meminstream_getc(FAR struct lib_instream_s *this)
      +{
      +  FAR struct lib_meminstream_s *mthis = (FAR struct lib_meminstream_s *)this;
      +  int ret;
      +
      +  DEBUGASSERT(this);
      +
      +  /* Get the next character (if any) from the buffer */
      +
      +  if (this->nget < mthis->buflen)
      +    {
      +      ret = mthis->buffer[this->nget];
      +      this->nget++;
      +    }
      +  else
      +    {
      +      ret = EOF;
      +    }
      +
      +  return ret;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_meminstream
      + *
      + * Description:
      + *   Initializes a stream for use with a fixed-size memory buffer.
      + *
      + * Input parameters:
      + *   meminstream - User allocated, uninitialized instance of struct
      + *                 lib_meminstream_s to be initialized.
      + *   bufstart    - Address of the beginning of the fixed-size memory buffer
      + *   buflen      - Size of the fixed-sized memory buffer in bytes
      + *
      + * Returned Value:
      + *   None (meminstream initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_meminstream(FAR struct lib_meminstream_s *meminstream,
      +                     FAR const char *bufstart, int buflen)
      +{
      +  meminstream->public.get  = meminstream_getc;
      +  meminstream->public.nget = 0;          /* Will be buffer index */
      +  meminstream->buffer      = bufstart;   /* Start of buffer */
      +  meminstream->buflen      = buflen;     /* Length of the buffer */
      +}
      +
      +
      diff --git a/nuttx/lib/stdio/lib_memoutstream.c b/nuttx/lib/stdio/lib_memoutstream.c
      new file mode 100644
      index 0000000000..21197358b7
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_memoutstream.c
      @@ -0,0 +1,105 @@
      +/****************************************************************************
      + * lib/stdio/lib_memoutstream.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: memoutstream_putc
      + ****************************************************************************/
      +
      +static void memoutstream_putc(FAR struct lib_outstream_s *this, int ch)
      +{
      +  FAR struct lib_memoutstream_s *mthis = (FAR struct lib_memoutstream_s *)this;
      +
      +  DEBUGASSERT(this);
      +
      +  /* If this will not overrun the buffer, then write the character to the
      +   * buffer.  Not that buflen was pre-decremented when the stream was
      +   * created so it is okay to write past the end of the buflen by one.
      +   */
      +
      +  if (this->nput < mthis->buflen)
      +    {
      +      mthis->buffer[this->nput] = ch;
      +      this->nput++;
      +      mthis->buffer[this->nput] = '\0';
      +    }
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_memoutstream
      + *
      + * Description:
      + *   Initializes a stream for use with a fixed-size memory buffer.
      + *
      + * Input parameters:
      + *   memoutstream - User allocated, uninitialized instance of struct
      + *                  lib_memoutstream_s to be initialized.
      + *   bufstart     - Address of the beginning of the fixed-size memory buffer
      + *   buflen       - Size of the fixed-sized memory buffer in bytes
      + *
      + * Returned Value:
      + *   None (memoutstream initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_memoutstream(FAR struct lib_memoutstream_s *memoutstream,
      +                      FAR char *bufstart, int buflen)
      +{
      +  memoutstream->public.put   = memoutstream_putc;
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +  memoutstream->public.flush = lib_noflush;
      +#endif
      +  memoutstream->public.nput  = 0;          /* Will be buffer index */
      +  memoutstream->buffer       = bufstart;   /* Start of buffer */
      +  memoutstream->buflen       = buflen - 1; /* Save space for null terminator */
      +  memoutstream->buffer[0]    = '\0';       /* Start with an empty string */
      +}
      +
      +
      diff --git a/nuttx/lib/stdio/lib_nullinstream.c b/nuttx/lib/stdio/lib_nullinstream.c
      new file mode 100644
      index 0000000000..0eadb0a8e4
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_nullinstream.c
      @@ -0,0 +1,79 @@
      +/****************************************************************************
      + * lib/stdio/lib_nullinstream.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +static int nullinstream_getc(FAR struct lib_instream_s *this)
      +{
      +  return EOF;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_nullinstream
      + *
      + * Description:
      + *   Initializes a NULL stream. The initialized stream will  will return only
      + *   EOF.
      + *
      + * Input parameters:
      + *   nullinstream  - User allocated, uninitialized instance of struct
      + *                   lib_instream_s to be initialized.
      + *
      + * Returned Value:
      + *   None (User allocated instance initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_nullinstream(FAR struct lib_instream_s *nullinstream)
      +{
      +  nullinstream->get  = nullinstream_getc;
      +  nullinstream->nget = 0;
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_nulloutstream.c b/nuttx/lib/stdio/lib_nulloutstream.c
      new file mode 100644
      index 0000000000..69878fd579
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_nulloutstream.c
      @@ -0,0 +1,84 @@
      +/****************************************************************************
      + * lib/stdio/lib_nulloutstream.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +static void nulloutstream_putc(FAR struct lib_outstream_s *this, int ch)
      +{
      +  DEBUGASSERT(this);
      +  this->nput++;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_nulloutstream
      + *
      + * Description:
      + *   Initializes a NULL streams. The initialized stream will write all data
      + *   to the bit-bucket.
      + *
      + * Input parameters:
      + *   nulloutstream - User allocated, uninitialized instance of struct
      + *                   lib_outstream_s to be initialized.
      + *
      + * Returned Value:
      + *   None (User allocated instance initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_nulloutstream(FAR struct lib_outstream_s *nulloutstream)
      +{
      +  nulloutstream->put   = nulloutstream_putc;
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +  nulloutstream->flush = lib_noflush;
      +#endif
      +  nulloutstream->nput  = 0;
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_perror.c b/nuttx/lib/stdio/lib_perror.c
      new file mode 100644
      index 0000000000..867e113f98
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_perror.c
      @@ -0,0 +1,99 @@
      +/****************************************************************************
      + * lib/stdio/lib_perror.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/* POSIX requires that perror provide its output on stderr.  This option may
      + * be defined, however, to provide perror output that is serialized with
      + * other stdout messages.
      + */
      + 
      +#ifdef CONFIG_LIBC_PERROR_STDOUT
      +#  define PERROR_STREAM stdout
      +#else
      +#  define PERROR_STREAM stderr
      +#endif
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: perror
      + ****************************************************************************/
      +
      +void perror(FAR const char *s)
      +{
      +
      +  /* If strerror() is not enabled, then just print the error number */
      +
      +#ifdef CONFIG_LIBC_STRERROR
      +  (void)fprintf(PERROR_STREAM, "%s: %s\n", s, strerror(errno));
      +#else
      +  (void)fprintf(PERROR_STREAM, "%s: Error %d\n", s, errno);
      +#endif
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_printf.c b/nuttx/lib/stdio/lib_printf.c
      new file mode 100644
      index 0000000000..50db06c475
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_printf.c
      @@ -0,0 +1,109 @@
      +/****************************************************************************
      + * lib/stdio/lib_printf.c
      + *
      + *   Copyright (C) 2007-2008, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Global Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Private Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Name: printf
      + **************************************************************************/
      +
      +int printf(const char *fmt, ...)
      +{
      +  va_list ap;
      +  int     ret;
      +
      +  va_start(ap, fmt);
      +#if CONFIG_NFILE_STREAMS > 0
      +  ret = vfprintf(stdout, fmt, ap);
      +#elif CONFIG_NFILE_DESCRIPTORS > 0
      +  ret = lib_rawvprintf(fmt, ap);
      +#elif defined(CONFIG_ARCH_LOWPUTC)
      +  ret = lib_lowvprintf(fmt, ap);
      +#else
      +# ifdef CONFIG_CPP_HAVE_WARNING
      +#   warning "printf has no data sink"
      +# endif
      +  ret = 0;
      +#endif
      +  va_end(ap);
      +
      +  return ret;
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_puts.c b/nuttx/lib/stdio/lib_puts.c
      new file mode 100644
      index 0000000000..e63a63917f
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_puts.c
      @@ -0,0 +1,130 @@
      +/****************************************************************************
      + * lib/stdio/lib_puts.c
      + *
      + *   Copyright (C) 2007, 2008, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: puts
      + *
      + * Description:
      + *   puts() writes the string s and a trailing newline to stdout.
      + *
      + ****************************************************************************/
      +
      +int puts(FAR const char *s)
      +{
      +  FILE *stream = stdout;
      +  int nwritten;
      +  int nput = EOF;
      +  int ret;
      +
      +  /* Write the string (the next two steps must be atomic) */
      +
      +  lib_take_semaphore(stream);
      +
      +  /* Write the string without its trailing '\0' */
      +
      +  nwritten = fputs(s, stream);
      +  if (nwritten > 0)
      +    {
      +      /* Followed by a newline */
      +
      +      char newline = '\n';
      +      ret = lib_fwrite(&newline, 1, stream);
      +      if (ret > 0)
      +        {
      +          nput = nwritten + 1;
      +
      +          /* Flush the buffer after the newline is output. */
      +
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +          ret = lib_fflush(stream, true);
      +          if (ret < 0)
      +            {
      +              nput = EOF;
      +            }
      +#endif
      +        }
      +    }
      +
      +  lib_give_semaphore(stdout);
      +  return nput;
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_rawinstream.c b/nuttx/lib/stdio/lib_rawinstream.c
      new file mode 100644
      index 0000000000..9671a27166
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_rawinstream.c
      @@ -0,0 +1,107 @@
      +/****************************************************************************
      + * lib/stdio/lib_rawinstream.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: rawinstream_getc
      + ****************************************************************************/
      +
      +static int rawinstream_getc(FAR struct lib_instream_s *this)
      +{
      +  FAR struct lib_rawinstream_s *rthis = (FAR struct lib_rawinstream_s *)this;
      +  int nwritten;
      +  char ch;
      +
      +  DEBUGASSERT(this && rthis->fd >= 0);
      +
      +  /* Attempt to read one character */
      +
      +  nwritten = read(rthis->fd, &ch, 1);
      +  if (nwritten == 1)
      +    {
      +      this->nget++;
      +      return ch;
      +    }
      +
      +  /* Return EOF on any failure to read from the incoming byte stream. The
      +   * only expected error is EINTR meaning that the read was interrupted
      +   * by a signal.  A Zero return value would indicated an end-of-file
      +   * confition.
      +   */
      +
      +  return EOF;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_rawinstream
      + *
      + * Description:
      + *   Initializes a stream for use with a file descriptor.
      + *
      + * Input parameters:
      + *   rawinstream - User allocated, uninitialized instance of struct
      + *                 lib_rawinstream_s to be initialized.
      + *   fd          - User provided file/socket descriptor (must have been opened
      + *                 for the correct access).
      + *
      + * Returned Value:
      + *   None (User allocated instance initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_rawinstream(FAR struct lib_rawinstream_s *rawinstream, int fd)
      +{
      +  rawinstream->public.get  = rawinstream_getc;
      +  rawinstream->public.nget = 0;
      +  rawinstream->fd          = fd;
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_rawoutstream.c b/nuttx/lib/stdio/lib_rawoutstream.c
      new file mode 100644
      index 0000000000..ed813f87aa
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_rawoutstream.c
      @@ -0,0 +1,115 @@
      +/****************************************************************************
      + * lib/stdio/lib_rawoutstream.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: rawoutstream_putc
      + ****************************************************************************/
      +
      +static void rawoutstream_putc(FAR struct lib_outstream_s *this, int ch)
      +{
      +  FAR struct lib_rawoutstream_s *rthis = (FAR struct lib_rawoutstream_s *)this;
      +  int nwritten;
      +  char buffer = ch;
      +
      +  DEBUGASSERT(this && rthis->fd >= 0);
      +
      +  /* Loop until the character is successfully transferred or until an
      +   * irrecoverable error occurs.
      +   */
      +
      +  do
      +    {
      +      nwritten = write(rthis->fd, &buffer, 1);
      +      if (nwritten == 1)
      +        {
      +          this->nput++;
      +          return;
      +        }
      +
      +      /* The only expected error is EINTR, meaning that the write operation
      +       * was awakened by a signal.  Zero would not be a valid return value
      +       * from write().
      +       */
      +
      +      DEBUGASSERT(nwritten < 0);
      +    }
      +  while (get_errno() == EINTR);
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_rawoutstream
      + *
      + * Description:
      + *   Initializes a stream for use with a file descriptor.
      + *
      + * Input parameters:
      + *   rawoutstream - User allocated, uninitialized instance of struct
      + *                  lib_rawoutstream_s to be initialized.
      + *   fd           - User provided file/socket descriptor (must have been opened
      + *                  for write access).
      + *
      + * Returned Value:
      + *   None (User allocated instance initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_rawoutstream(FAR struct lib_rawoutstream_s *rawoutstream, int fd)
      +{
      +  rawoutstream->public.put   = rawoutstream_putc;
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +  rawoutstream->public.flush = lib_noflush;
      +#endif
      +  rawoutstream->public.nput  = 0;
      +  rawoutstream->fd           = fd;
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_rawprintf.c b/nuttx/lib/stdio/lib_rawprintf.c
      new file mode 100644
      index 0000000000..19dfa895e1
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_rawprintf.c
      @@ -0,0 +1,151 @@
      +/****************************************************************************
      + * lib/stdio/lib_rawprintf.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/* Some output destinations are only available from within the kernel */
      +
      +#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__)
      +#  undef CONFIG_SYSLOG
      +#  undef CONFIG_ARCH_LOWPUTC
      +#endif
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_rawvprintf
      + ****************************************************************************/
      +
      +int lib_rawvprintf(const char *fmt, va_list ap)
      +{
      +#if defined(CONFIG_SYSLOG)
      +
      +  struct lib_outstream_s stream;
      +
      +  /* Wrap the low-level output in a stream object and let lib_vsprintf
      +   * do the work.
      +   */
      +
      +  lib_syslogstream((FAR struct lib_outstream_s *)&stream);
      +  return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap);
      +
      +#elif CONFIG_NFILE_DESCRIPTORS > 0
      +
      +  struct lib_rawoutstream_s rawoutstream;
      +
      +  /* Wrap the stdout in a stream object and let lib_vsprintf
      +   * do the work.
      +   */
      +
      +  lib_rawoutstream(&rawoutstream, 1);
      +  return lib_vsprintf(&rawoutstream.public, fmt, ap);
      +
      +#elif defined(CONFIG_ARCH_LOWPUTC)
      +
      +  struct lib_outstream_s stream;
      +
      +  /* Wrap the low-level output in a stream object and let lib_vsprintf
      +   * do the work.
      +   */
      +
      +  lib_lowoutstream((FAR struct lib_outstream_s *)&stream);
      +  return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap);
      +
      +#else
      +  return 0;
      +#endif
      +}
      +
      +/****************************************************************************
      + * Name: lib_rawprintf
      + ****************************************************************************/
      +
      +int lib_rawprintf(const char *fmt, ...)
      +{
      +  va_list ap;
      +  int     ret;
      +
      +#ifdef CONFIG_DEBUG_ENABLE
      +  ret = 0;
      +  if (g_dbgenable)
      +#endif
      +    {
      +      va_start(ap, fmt);
      +      ret = lib_rawvprintf(fmt, ap);
      +      va_end(ap);
      +    }
      +
      +  return ret;
      +}
      diff --git a/nuttx/lib/stdio/lib_rdflush.c b/nuttx/lib/stdio/lib_rdflush.c
      new file mode 100644
      index 0000000000..35c5495c17
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_rdflush.c
      @@ -0,0 +1,144 @@
      +/****************************************************************************
      + * lib/stdio/lib_rdflush.c
      + *
      + *   Copyright (C) 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_rdflush
      + *
      + * Description:
      + *   Flush read data from the I/O buffer and adjust the file pointer to
      + *   account for the unread data
      + *
      + ****************************************************************************/
      +
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +int lib_rdflush(FAR FILE *stream)
      +{
      +  if (!stream)
      +    {
      +      set_errno(EBADF);
      +      return ERROR;
      +    }
      +
      +  /* Get exclusive access to the stream */
      +
      +  lib_take_semaphore(stream);
      +
      +  /* If the buffer is currently being used for read access, then discard all
      +   * of the read-ahead data.  We do not support concurrent buffered read/write
      +   * access.
      +   */
      +
      +  if (stream->fs_bufread != stream->fs_bufstart)
      +    {
      +      /* Now adjust the stream pointer to account for the read-ahead data that
      +       * was not actually read by the user.
      +       */
      +
      +#if CONFIG_NUNGET_CHARS > 0
      +      off_t rdoffset = stream->fs_bufread - stream->fs_bufpos + stream->fs_nungotten;
      +#else
      +      off_t rdoffset = stream->fs_bufread - stream->fs_bufpos;
      +#endif
      +      /* Mark the buffer as empty (do this before calling fseek() because fseek()
      +       * also calls this function).
      +       */
      +
      +      stream->fs_bufpos = stream->fs_bufread = stream->fs_bufstart;
      +#if CONFIG_NUNGET_CHARS > 0
      +      stream->fs_nungotten = 0;
      +#endif
      +      /* Then seek to the position corresponding to the last data read by the user */
      +
      +      if (fseek(stream, -rdoffset, SEEK_CUR) < 0)
      +        {
      +          lib_give_semaphore(stream);
      +          return ERROR;
      +        }
      +    }
      +
      +  lib_give_semaphore(stream);
      +  return OK;
      +}
      +#endif /* CONFIG_STDIO_BUFFER_SIZE */
      +
      diff --git a/nuttx/lib/stdio/lib_snprintf.c b/nuttx/lib/stdio/lib_snprintf.c
      new file mode 100644
      index 0000000000..e5ce7b0f02
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_snprintf.c
      @@ -0,0 +1,99 @@
      +/****************************************************************************
      + * lib/stdio/lib_snprintf.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * sprintf
      + ****************************************************************************/
      +
      +int snprintf(FAR char *buf, size_t size, const char *format, ...)
      +{
      +  struct lib_memoutstream_s memoutstream;
      +  va_list ap;
      +  int     n;
      +
      +  /* Initialize a memory stream to write to the buffer */
      +
      +  lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, size);
      +
      +  /* Then let lib_vsprintf do the real work */
      +
      +  va_start(ap, format);
      +  n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, format, ap);
      +  va_end(ap);
      +  return n;
      +}
      diff --git a/nuttx/lib/stdio/lib_sprintf.c b/nuttx/lib/stdio/lib_sprintf.c
      new file mode 100644
      index 0000000000..89fd610330
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_sprintf.c
      @@ -0,0 +1,95 @@
      +/****************************************************************************
      + * lib/stdio/lib_sprintf.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * sprintf
      + ****************************************************************************/
      +
      +int sprintf (FAR char *buf, const char *fmt, ...)
      +{
      +  struct lib_memoutstream_s memoutstream;
      +  va_list ap;
      +  int     n;
      +
      +  /* Initialize a memory stream to write to the buffer */
      +
      +  lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, LIB_BUFLEN_UNKNOWN);
      +
      +  /* Then let lib_vsprintf do the real work */
      +
      +  va_start(ap, fmt);
      +  n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, fmt, ap);
      +  va_end(ap);
      +  return n;
      +}
      diff --git a/nuttx/lib/stdio/lib_sscanf.c b/nuttx/lib/stdio/lib_sscanf.c
      new file mode 100644
      index 0000000000..7e1fae276d
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_sscanf.c
      @@ -0,0 +1,507 @@
      +/****************************************************************************
      + * lib/stdio/lib_sscanf.c
      + *
      + *   Copyright (C) 2007, 2008, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +#define MAXLN 128
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +int vsscanf(char *buf, const char *fmt, va_list ap);
      +
      +/**************************************************************************
      + * Global Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Private Constant Data
      + **************************************************************************/
      +
      +static const char spaces[] = " \t\n\r\f\v";
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  findwidth
      + *
      + * Description:
      + *    Try to figure out the width of the input data.
      + *
      + ****************************************************************************/
      +
      +static int findwidth(FAR const char *buf, FAR const char *fmt)
      +{
      +  FAR const char *next = fmt + 1;
      +
      +  /* No... is there a space after the format? Or does the format string end
      +   * here?
      +   */
      +
      +  if (isspace(*next) || *next == 0)
      +    {
      +      /* Use the input up until the first white space is encountered. */
      +
      +      return strcspn(buf, spaces);
      +    }
      +
      +  /* No.. Another possibility is the the format character is followed by
      +   * some recognizable delimiting value.
      +   */
      +
      +  if (*next != '%')
      +    {
      +      /* If so we will say that the string ends there if we can find that
      +       * delimiter in the input string.
      +       */
      +
      +      FAR const char *ptr = strchr(buf, *next);
      +      if (ptr)
      +        {
      +          return (int)(ptr - buf);
      +        }
      +    }
      +
      +  /* No... the format has not delimiter and is back-to-back with the next
      +   * formats (or no is following by a delimiter that does not exist in the
      +   * input string).  At this point we just bail and Use the input up until
      +   * the first white space is encountered.
      +   *
      +   * NOTE:  This means that values from the following format may be
      +   * concatenated with the first. This is a bug.  We have no generic way of
      +   * determining the width of the data if there is no fieldwith, no space
      +   * separating the input, and no usable delimiter character.
      +   */
      +
      +  return strcspn(buf, spaces);
      +}
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  sscanf
      + *
      + * Description:
      + *    ANSI standard sscanf implementation.
      + *
      + ****************************************************************************/
      +
      +int sscanf(FAR const char *buf, FAR const char *fmt, ...)
      +{
      +  va_list ap;
      +  int     count;
      +
      +  va_start(ap, fmt);
      +  count = vsscanf((FAR char*)buf, fmt, ap);
      +  va_end(ap);
      +  return count;
      +}
      +
      +/****************************************************************************
      + * Function:  vsscanf
      + *
      + * Description:
      + *    ANSI standard vsscanf implementation.
      + *
      + ****************************************************************************/
      +
      +int vsscanf(FAR char *buf, FAR const char *fmt, va_list ap)
      +{
      +  FAR char       *bufstart;
      +  FAR char       *tv;
      +  FAR const char *tc;
      +  bool            lflag;
      +  bool            noassign;
      +  int             count;
      +  int             width;
      +  int             base = 10;
      +  char            tmp[MAXLN];
      +
      +  lvdbg("vsscanf: buf=\"%s\" fmt=\"%s\"\n", buf, fmt);
      +
      +  /* Remember the start of the input buffer.  We will need this for %n
      +   * calculations.
      +   */
      +
      +  bufstart = buf;
      +
      +  /* Parse the format, extracting values from the input buffer as needed */
      +
      +  count    = 0;
      +  width    = 0;
      +  noassign = false;
      +  lflag    = false;
      +
      +  while (*fmt && *buf)
      +    {
      +      /* Skip over white space */
      +
      +      while (isspace(*fmt))
      +        {
      +          fmt++;
      +        }
      +
      +      /* Check for a conversion specifier */
      +
      +      if (*fmt == '%')
      +        {
      +          lvdbg("vsscanf: Specifier found\n");
      +
      +          /* Check for qualifiers on the conversion specifier */
      +          fmt++;
      +          for (; *fmt; fmt++)
      +            {
      +              lvdbg("vsscanf: Processing %c\n", *fmt);
      +
      +              if (strchr("dibouxcsefgn%", *fmt))
      +                {
      +                  break;
      +                }
      +
      +              if (*fmt == '*')
      +                {
      +                  noassign = true;
      +                }
      +              else if (*fmt == 'l' || *fmt == 'L')
      +                {
      +                  /* NOTE: Missing check for long long ('ll') */
      +
      +                  lflag = true;
      +                }
      +              else if (*fmt >= '1' && *fmt <= '9')
      +                {
      +                  for (tc = fmt; isdigit(*fmt); fmt++);
      +                  strncpy(tmp, tc, fmt - tc);
      +                  tmp[fmt - tc] = '\0';
      +                  width = atoi(tmp);
      +                  fmt--;
      +                }
      +            }
      +
      +          /* Process %s:  String conversion */
      +
      +          if (*fmt == 's')
      +            {
      +              lvdbg("vsscanf: Performing string conversion\n");
      +
      +              while (isspace(*buf))
      +                {
      +                  buf++;
      +                }
      +
      +              /* Was a fieldwidth specified? */
      +
      +              if (!width)
      +                {
      +                  /* No... Guess a field width using some heuristics */
      +
      +                  width = findwidth(buf, fmt);
      +                }
      +
      +              if (!noassign)
      +                {
      +                  tv = va_arg(ap, char*);
      +                  strncpy(tv, buf, width);
      +                  tv[width] = '\0';
      +                }
      +
      +              buf += width;
      +            }
      +
      +          /* Process %c:  Character conversion */
      +
      +          else if (*fmt == 'c')
      +            {
      +              lvdbg("vsscanf: Performing character conversion\n");
      +
      +              /* Was a fieldwidth specified? */
      +
      +              if (!width)
      +                {
      +                  /* No, then width is this one single character */
      +
      +                  width = 1;
      +                }
      +
      +              if (!noassign)
      +                {
      +                  tv = va_arg(ap, char*);
      +                  strncpy(tv, buf, width);
      +                  tv[width] = '\0';
      +                }
      +
      +              buf += width;
      +            }
      +
      +          /* Process %d, %o, %b, %x, %u:  Various integer conversions */
      +
      +          else if (strchr("dobxu", *fmt))
      +            {
      +              lvdbg("vsscanf: Performing integer conversion\n");
      +
      +              /* Skip over any white space before the integer string */
      +
      +              while (isspace(*buf))
      +                {
      +                  buf++;
      +                }
      +
      +              /* The base of the integer conversion depends on the specific
      +               * conversion specification.
      +               */
      +
      +              if (*fmt == 'd' || *fmt == 'u')
      +                {
      +                  base = 10;
      +                }
      +              else if (*fmt == 'x')
      +                {
      +                  base = 16;
      +                }
      +              else if (*fmt == 'o')
      +                {
      +                  base = 8;
      +                }
      +              else if (*fmt == 'b')
      +                {
      +                  base = 2;
      +                }
      +
      +              /* Was a fieldwidth specified? */
      +
      +              if (!width)
      +                {
      +                  /* No... Guess a field width using some heuristics */
      +
      +                  width = findwidth(buf, fmt);
      +                }
      +
      +              /* Copy the numeric string into a temporary working buffer. */
      +
      +              strncpy(tmp, buf, width);
      +              tmp[width] = '\0';
      +
      +              lvdbg("vsscanf: tmp[]=\"%s\"\n", tmp);
      +
      +              /* Perform the integer conversion */
      +
      +              buf += width;
      +              if (!noassign)
      +                {
      +#ifdef SDCC
      +                  char *endptr;
      +                  long tmplong = strtol(tmp, &endptr, base);
      +#else
      +                  long tmplong = strtol(tmp, NULL, base);
      +#endif
      +                  if (lflag)
      +                    {
      +                      long *plong = va_arg(ap, long*);
      +                      lvdbg("vsscanf: Return %ld to 0x%p\n", tmplong, plong);
      +                      *plong = tmplong;
      +                    }
      +                  else
      +                    {
      +                      int *pint = va_arg(ap, int*);
      +                      lvdbg("vsscanf: Return %ld to 0x%p\n", tmplong, pint);
      +                      *pint = (int)tmplong;
      +                    }
      +                }
      +            }
      +
      +          /* Process %f:  Floating point conversion */
      +
      +          else if (*fmt == 'f')
      +            {
      +#ifndef CONFIG_LIBC_FLOATINGPOINT
      +              /* No floating point conversions */
      +
      +              void *pv = va_arg(ap, void*);
      +
      +              lvdbg("vsscanf: Return 0.0 to %p\n", pv);
      +              *((double_t*)pv) = 0.0;
      +#else
      +              lvdbg("vsscanf: Performing floating point conversion\n");
      +
      +              /* Skip over any white space before the real string */
      +
      +              while (isspace(*buf))
      +                {
      +                  buf++;
      +                }
      +
      +              /* Was a fieldwidth specified? */
      +
      +              if (!width)
      +                {
      +                  /* No... Guess a field width using some heuristics */
      +
      +                  width = findwidth(buf, fmt);
      +                }
      +
      +              /* Copy the real string into a temporary working buffer. */
      +
      +              strncpy(tmp, buf, width);
      +              tmp[width] = '\0';
      +              buf += width;
      +
      +              lvdbg("vsscanf: tmp[]=\"%s\"\n", tmp);
      +
      +              /* Perform the floating point conversion */
      +
      +              if (!noassign)
      +                {
      +                  /* strtod always returns a double */
      +#ifdef SDCC
      +                  char *endptr;
      +                  double_t dvalue = strtod(tmp,&endptr);
      +#else
      +                  double_t dvalue = strtod(tmp, NULL);
      +#endif
      +                  void *pv = va_arg(ap, void*);
      +
      +                  lvdbg("vsscanf: Return %f to %p\n", dvalue, pv);
      +
      +                  /* But we have to check whether we need to return a
      +                   * float or a double.
      +                   */
      +
      +#ifdef CONFIG_HAVE_DOUBLE
      +                  if (lflag)
      +                    {
      +                      *((double_t*)pv) = dvalue;
      +                    }
      +                  else
      +#endif
      +                    {
      +                      *((float*)pv) = (float)dvalue;
      +                    }
      +                }
      +#endif
      +            }
      +
      +          /* Process %n:  Character count */
      +
      +          else if (*fmt == 'n')
      +            {
      +              lvdbg("vsscanf: Performing character count\n");
      +
      +              if (!noassign)
      +                {
      +                  size_t nchars = (size_t)(buf - bufstart);
      +
      +                  if (lflag)
      +                    {
      +                      long *plong = va_arg(ap, long*);
      +                      *plong = (long)nchars;
      +                    }
      +                  else
      +                    {
      +                      int *pint = va_arg(ap, int*);
      +                      *pint = (int)nchars;
      +                    }
      +                }
      +            }
      +
      +          /* Note %n does not count as a conversion */
      +
      +          if (!noassign && *fmt != 'n')
      +            {
      +              count++;
      +            }
      +
      +          width    = 0;
      +          noassign = false;
      +          lflag    = false;
      +
      +          fmt++;
      +        }
      +
      +    /* Its is not a conversion specifier */
      +
      +      else
      +        {
      +          while (isspace(*buf))
      +            {
      +              buf++;
      +            }
      +
      +          if (*fmt != *buf)
      +            {
      +              break;
      +            }
      +          else
      +            {
      +              fmt++;
      +              buf++;
      +            }
      +        }
      +    }
      +
      +  return count;
      +}
      diff --git a/nuttx/lib/stdio/lib_stdinstream.c b/nuttx/lib/stdio/lib_stdinstream.c
      new file mode 100644
      index 0000000000..77aab9ec88
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_stdinstream.c
      @@ -0,0 +1,99 @@
      +/****************************************************************************
      + * lib/stdio/lib_stdinstream.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: stdinstream_getc
      + ****************************************************************************/
      +
      +static int stdinstream_getc(FAR struct lib_instream_s *this)
      +{
      +  FAR struct lib_stdinstream_s *sthis = (FAR struct lib_stdinstream_s *)this;
      +  int ret;
      +
      +  DEBUGASSERT(this);
      +
      +  /* Get the next character from the incoming stream */
      +
      +  ret = getc(sthis->stream);
      +  if (ret != EOF)
      +    {
      +      this->nget++;
      +    }
      + 
      + return ret;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_stdinstream
      + *
      + * Description:
      + *   Initializes a stream for use with a FILE instance.
      + *
      + * Input parameters:
      + *   stdinstream - User allocated, uninitialized instance of struct
      + *                 lib_stdinstream_s to be initialized.
      + *   stream      - User provided stream instance (must have been opened for
      + *                 read access).
      + *
      + * Returned Value:
      + *   None (User allocated instance initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_stdinstream(FAR struct lib_stdinstream_s *stdinstream,
      +                     FAR FILE *stream)
      +{
      +  stdinstream->public.get  = stdinstream_getc;
      +  stdinstream->public.nget = 0;
      +  stdinstream->stream      = stream;
      +}
      +
      +
      diff --git a/nuttx/lib/stdio/lib_stdoutstream.c b/nuttx/lib/stdio/lib_stdoutstream.c
      new file mode 100644
      index 0000000000..20da5b7026
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_stdoutstream.c
      @@ -0,0 +1,147 @@
      +/****************************************************************************
      + * lib/stdio/lib_stdoutstream.c
      + *
      + *   Copyright (C) 2007-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: stdoutstream_putc
      + ****************************************************************************/
      +
      +static void stdoutstream_putc(FAR struct lib_outstream_s *this, int ch)
      +{
      +  FAR struct lib_stdoutstream_s *sthis = (FAR struct lib_stdoutstream_s *)this;
      +  int result;
      +
      +  DEBUGASSERT(this && sthis->stream);
      +
      +  /* Loop until the character is successfully transferred or an irrecoverable
      +   * error occurs.
      +   */
      +
      +  do
      +    {
      +      result = fputc(ch, sthis->stream);
      +      if (result != EOF)
      +        {
      +          this->nput++;
      +          return;
      +        }
      +
      +      /* EINTR (meaning that fputc was interrupted by a signal) is the only
      +       * recoverable error.
      +       */
      +    }
      +  while (get_errno() == EINTR);
      +}
      +
      +/****************************************************************************
      + * Name: stdoutstream_flush
      + ****************************************************************************/
      +
      +#if defined(CONFIG_STDIO_LINEBUFFER) && CONFIG_STDIO_BUFFER_SIZE > 0
      +int stdoutstream_flush(FAR struct lib_outstream_s *this)
      +{
      +  FAR struct lib_stdoutstream_s *sthis = (FAR struct lib_stdoutstream_s *)this;
      +  return lib_fflush(sthis->stream, true);
      +}
      +#endif
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_stdoutstream
      + *
      + * Description:
      + *   Initializes a stream for use with a FILE instance.
      + *
      + * Input parameters:
      + *   stdoutstream - User allocated, uninitialized instance of struct
      + *                  lib_stdoutstream_s to be initialized.
      + *   stream       - User provided stream instance (must have been opened for
      + *                  write access).
      + *
      + * Returned Value:
      + *   None (User allocated instance initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_stdoutstream(FAR struct lib_stdoutstream_s *stdoutstream,
      +                   FAR FILE *stream)
      +{
      +  /* Select the put operation */
      +
      +  stdoutstream->public.put   = stdoutstream_putc;
      +
      +  /* Select the correct flush operation.  This flush is only called when
      +   * a newline is encountered in the output stream.  However, we do not
      +   * want to support this line buffering behavior if the stream was
      +   * opened in binary mode.  In binary mode, the newline has no special
      +   * meaning.
      +   */
      +
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +  if ((stream->fs_oflags & O_BINARY) == 0)
      +    {
      +      stdoutstream->public.flush = stdoutstream_flush;
      +    }
      +  else
      +#endif
      +    {
      +      stdoutstream->public.flush = lib_noflush;
      +    }
      +#endif
      +
      +  /* Set the number of bytes put to zero and remember the stream */
      +
      +  stdoutstream->public.nput  = 0;
      +  stdoutstream->stream       = stream;
      +}
      +
      +
      diff --git a/nuttx/lib/stdio/lib_syslogstream.c b/nuttx/lib/stdio/lib_syslogstream.c
      new file mode 100644
      index 0000000000..21151b43a1
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_syslogstream.c
      @@ -0,0 +1,122 @@
      +/****************************************************************************
      + * lib/stdio/lib_syslogstream.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +#ifdef CONFIG_SYSLOG
      +
      +/****************************************************************************
      + * Pre-processor definition
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: syslogstream_putc
      + ****************************************************************************/
      +
      +static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch)
      +{
      +  int ret;
      +
      +  /* Try writing until the write was successful or until an irrecoverable
      +   * error occurs.
      +   */
      +
      +  do
      +    {
      +      /* Write the character to the supported logging device */
      +
      +      ret = syslog_putc(ch);
      +      if (ret == OK)
      +        {
      +          this->nput++;
      +          return;
      +        }
      +
      +      /* On failure syslog_putc will return a negated errno value.  The
      +       * errno variable will not be set.  The special value -EINTR means that
      +       * syslog_putc() was awakened by a signal.  This is not a real error and
      +       * must be ignored in this context.
      +       */
      +    }
      +  while (ret == -EINTR);
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_syslogstream
      + *
      + * Description:
      + *   Initializes a stream for use with the configured syslog interface.
      + *
      + * Input parameters:
      + *   lowoutstream - User allocated, uninitialized instance of struct
      + *                  lib_lowoutstream_s to be initialized.
      + *
      + * Returned Value:
      + *   None (User allocated instance initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_syslogstream(FAR struct lib_outstream_s *stream)
      +{
      +  stream->put   = syslogstream_putc;
      +#ifdef CONFIG_STDIO_LINEBUFFER
      +  stream->flush = lib_noflush;
      +#endif
      +  stream->nput  = 0;
      +}
      +
      +#endif /* CONFIG_SYSLOG */
      +
      +
      diff --git a/nuttx/lib/stdio/lib_ungetc.c b/nuttx/lib/stdio/lib_ungetc.c
      new file mode 100644
      index 0000000000..c10d4fba1a
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_ungetc.c
      @@ -0,0 +1,121 @@
      +/****************************************************************************
      + * lib/stdio/lib_ungetc.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Global Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Private Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Name: ungetc
      + **************************************************************************/
      +
      +int ungetc(int c, FAR FILE *stream)
      +{
      +#if CONFIG_NUNGET_CHARS > 0
      +  int nungotten;
      +#endif
      +
      +  /* Stream must be open for read access */
      +
      +  if ((stream && stream->fs_filedes < 0) ||
      +      ((stream->fs_oflags & O_RDOK) == 0))
      +    {
      +      set_errno(EBADF);
      +      return EOF;
      +    }
      +
      +#if CONFIG_NUNGET_CHARS > 0
      +  nungotten = stream->fs_nungotten;
      +  if (stream->fs_nungotten < CONFIG_NUNGET_CHARS)
      +    {
      +      stream->fs_ungotten[nungotten] = c;
      +      stream->fs_nungotten = nungotten + 1;
      +      return c;
      +    }
      +  else
      +#endif
      +    {
      +      set_errno(ENOMEM);
      +      return EOF;
      +    }
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_vfprintf.c b/nuttx/lib/stdio/lib_vfprintf.c
      new file mode 100644
      index 0000000000..1c3a2d7fc9
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_vfprintf.c
      @@ -0,0 +1,102 @@
      +/****************************************************************************
      + * lib/stdio/lib_vfprintf.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +int vfprintf(FAR FILE *stream, FAR const char *fmt, va_list ap)
      +{
      +  struct lib_stdoutstream_s stdoutstream;
      +  int  n = ERROR;
      +
      +  if (stream)
      +    {
      +      /* Wrap the stream in a stream object and let lib_vsprintf
      +       * do the work.
      +       */
      +
      +      lib_stdoutstream(&stdoutstream, stream);
      +
      +      /* Hold the stream semaphore throughout the lib_vsprintf
      +       * call so that this thread can get its entire message out
      +       * before being pre-empted by the next thread.
      +       */
      +
      +      lib_take_semaphore(stream);
      +      n = lib_vsprintf(&stdoutstream.public, fmt, ap);
      +      lib_give_semaphore(stream);
      +    }
      +  return n;
      +}
      diff --git a/nuttx/lib/stdio/lib_vprintf.c b/nuttx/lib/stdio/lib_vprintf.c
      new file mode 100644
      index 0000000000..d085d58869
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_vprintf.c
      @@ -0,0 +1,92 @@
      +/****************************************************************************
      + * lib/stdio/lib_vprintf.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Function Prototypes
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Global Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Private Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Name: vprintf
      + **************************************************************************/
      +
      +int vprintf(FAR const char *fmt, va_list ap)
      +{
      +  /* vfprintf into stdout */
      +
      +  return vfprintf(stdout, fmt, ap);
      +}
      +
      diff --git a/nuttx/lib/stdio/lib_vsnprintf.c b/nuttx/lib/stdio/lib_vsnprintf.c
      new file mode 100644
      index 0000000000..c6f52092d1
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_vsnprintf.c
      @@ -0,0 +1,96 @@
      +/****************************************************************************
      + * lib/stdio/lib_vsnprintf.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: vsnprintf
      + ****************************************************************************/
      +
      +int vsnprintf(FAR char *buf, size_t size, const char *format, va_list ap)
      +{
      +  struct lib_memoutstream_s memoutstream;
      +  int     n;
      +
      +  /* Initialize a memory stream to write to the buffer */
      +
      +  lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, size);
      +
      +  /* Then let lib_vsprintf do the real work */
      +
      +  n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, format, ap);
      +  return n;
      +}
      diff --git a/nuttx/lib/stdio/lib_vsprintf.c b/nuttx/lib/stdio/lib_vsprintf.c
      new file mode 100644
      index 0000000000..5db46664e3
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_vsprintf.c
      @@ -0,0 +1,92 @@
      +/****************************************************************************
      + * lib/stdio/lib_vsprintf.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: vsprintf
      + ****************************************************************************/
      +
      +int vsprintf(FAR char *dest, const char *src, va_list ap)
      +{
      +  struct lib_memoutstream_s memoutstream;
      +
      +  /* Wrap the destination buffer in a stream object and let
      +   * lib/stdio/lib_vsprintf do the work.
      +   */
      +
      +  lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, dest, LIB_BUFLEN_UNKNOWN);
      +  return lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, src, ap);
      +}
      diff --git a/nuttx/lib/stdio/lib_wrflush.c b/nuttx/lib/stdio/lib_wrflush.c
      new file mode 100644
      index 0000000000..39680da6ae
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_wrflush.c
      @@ -0,0 +1,134 @@
      +/****************************************************************************
      + * lib/stdio/lib_wrflush.c
      + *
      + *   Copyright (C) 2008-2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_wrflush
      + *
      + * Description:
      + *   This is simply a version of fflush that does not report an error if
      + *   the file is not open for writing.
      + *
      + ****************************************************************************/
      +
      +int lib_wrflush(FAR FILE *stream)
      +{
      +#if CONFIG_STDIO_BUFFER_SIZE > 0
      +  /* Verify that we were passed a valid (i.e., non-NULL) stream */
      +
      +#ifdef CONFIG_DEBUG
      +  if (!stream)
      +    {
      +      return -EINVAL;
      +    }
      +#endif
      +
      +  /* Verify that the stream is opened for writing... lib_fflush will
      +   * return an error if it is called for a stream that is not opened for
      +   * writing.  Check that first so that this function will not fail in
      +   * that case.
      +   */
      +
      +  if ((stream->fs_oflags & O_WROK) == 0)
      +    {
      +      /* Report that the success was successful if we attempt to flush a
      +       * read-only stream.
      +       */
      +
      +      return OK;
      +    }
      +
      +  /* Flush the stream.   Return success if there is no buffered write data
      +   * -- i.e., that the stream is opened for writing and  that all of the
      +   * buffered write data was successfully flushed by lib_fflush().
      +   */
      +
      +  return lib_fflush(stream, true);
      +#else
      +  /* Verify that we were passed a valid (i.e., non-NULL) stream */
      +
      +#ifdef CONFIG_DEBUG
      +  if (!stream)
      +    {
      +      return -EINVAL;
      +    }
      +#endif
      +
      +  return OK;
      +#endif
      +}
      diff --git a/nuttx/lib/stdio/lib_zeroinstream.c b/nuttx/lib/stdio/lib_zeroinstream.c
      new file mode 100644
      index 0000000000..39a6c22ef3
      --- /dev/null
      +++ b/nuttx/lib/stdio/lib_zeroinstream.c
      @@ -0,0 +1,79 @@
      +/****************************************************************************
      + * lib/stdio/lib_zeroinstream.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +static int zeroinstream_getc(FAR struct lib_instream_s *this)
      +{
      +  this->nget++;
      +  return 0;
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_zeroinstream
      + *
      + * Description:
      + *   Initializes a NULL stream.  The initialized stream will return an
      + *   infinitely long stream of zeroes.
      + *
      + * Input parameters:
      + *   zeroinstream  - User allocated, uninitialized instance of struct
      + *                   lib_instream_s to be initialized.
      + *
      + * Returned Value:
      + *   None (User allocated instance initialized).
      + *
      + ****************************************************************************/
      +
      +void lib_zeroinstream(FAR struct lib_instream_s *zeroinstream)
      +{
      +  zeroinstream->get  = zeroinstream_getc;
      +  zeroinstream->nget = 0;
      +}
      +
      diff --git a/nuttx/lib/stdlib/Make.defs b/nuttx/lib/stdlib/Make.defs
      new file mode 100644
      index 0000000000..76e285808a
      --- /dev/null
      +++ b/nuttx/lib/stdlib/Make.defs
      @@ -0,0 +1,44 @@
      +############################################################################
      +# lib/stdlib/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the stdlib C files to the build
      +
      +CSRCS += lib_abs.c lib_abort.c lib_imaxabs.c lib_labs.c lib_llabs.c \
      +		  lib_rand.c lib_qsort.c
      +
      +# Add the stdlib directory to the build
      +
      +DEPPATH += --dep-path stdlib
      +VPATH += :stdlib
      diff --git a/nuttx/lib/stdlib/lib_abort.c b/nuttx/lib/stdlib/lib_abort.c
      new file mode 100644
      index 0000000000..84b6009500
      --- /dev/null
      +++ b/nuttx/lib/stdlib/lib_abort.c
      @@ -0,0 +1,121 @@
      +/************************************************************************
      + * lib/stdlib/lib_abort.c
      + *
      + *   Copyright (C) 2007, 2009, 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Pre-processor Definitions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Type Declarations
      + ************************************************************************/
      +
      +/************************************************************************
      + * Global Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Variables
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Function Prototypes
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Name: Abort
      + *
      + * Description:
      + *   The abort() first unblocks the SIGABRT signal, and then raises that
      + *   signal for the calling process. This results in the abnormal
      + *   termination of the process unless the SIGABRT signal is caught and
      + *   the signal handler does not return.
      + *
      + *   If the abort() function causes process termination, all open
      + *   streams are closed and flushed.
      + *
      + *   If the SIGABRT signal is ignored, or caught by a handler that
      + *   returns, the abort() function will still terminate the process.
      + *   It does this by restoring the default disposition for SIGABRT and
      + *   then raising the signal for a second time.
      + *
      + * Input parameters:
      + *   None
      + *
      + * Returned Value:
      + *  This function does not return,
      + *
      + ************************************************************************/
      +
      +void abort(void)
      +{
      +  /* NuttX does not support standard signal functionality (like the
      +   * behavior of the SIGABRT signal).  So no attempt is made to provide
      +   * a conformant version of abort() at this time.  This version does not
      +   * signal the calling thread all.
      +   *
      +   * Note that pthread_exit() is called instead of exit().  That is because
      +   * we do no know if abort was called from a pthread or a normal thread
      +   * (we could find out, of course).  If abort() is called from a non-pthread,
      +   * then pthread_exit() should fail and fall back to call exit() anyway.
      +   *
      +   * If exit() is called (either below or via pthread_exit()), then exit()
      +   * will flush and close all open files and terminate the thread.  If this
      +   * function was called from a pthread, then pthread_exit() will complete
      +   * any joins, but will not flush or close any streams.
      +   */
      +
      +#ifdef CONFIG_DISABLE_PTHREAD
      +  exit(EXIT_FAILURE);
      +#else
      +  pthread_exit(NULL);
      +#endif
      +}
      diff --git a/nuttx/lib/stdlib/lib_abs.c b/nuttx/lib/stdlib/lib_abs.c
      new file mode 100644
      index 0000000000..1a0c1671cc
      --- /dev/null
      +++ b/nuttx/lib/stdlib/lib_abs.c
      @@ -0,0 +1,54 @@
      +/************************************************************************
      + * lib/stdlib/lib_abs.c
      + *
      + *   Copyright (C) 2010-2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Global Functions
      + ************************************************************************/
      +
      +int abs(int j)
      +{
      +  if (j < 0)
      +    {
      +      j = -j;
      +    }
      +  return j;
      +}
      diff --git a/nuttx/lib/stdlib/lib_imaxabs.c b/nuttx/lib/stdlib/lib_imaxabs.c
      new file mode 100644
      index 0000000000..c6e227c7de
      --- /dev/null
      +++ b/nuttx/lib/stdlib/lib_imaxabs.c
      @@ -0,0 +1,54 @@
      +/************************************************************************
      + * lib/stdlib//lib_abs.c
      + *
      + *   Copyright (C) 2010-2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Global Functions
      + ************************************************************************/
      +
      +intmax_t imaxabs(intmax_t j)
      +{
      +  if (j < 0)
      +    {
      +      j = -j;
      +    }
      +  return j;
      +}
      diff --git a/nuttx/lib/stdlib/lib_labs.c b/nuttx/lib/stdlib/lib_labs.c
      new file mode 100644
      index 0000000000..f7218ee833
      --- /dev/null
      +++ b/nuttx/lib/stdlib/lib_labs.c
      @@ -0,0 +1,54 @@
      +/************************************************************************
      + * lib/stdlib/lib_labs.c
      + *
      + *   Copyright (C) 2010-2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Global Functions
      + ************************************************************************/
      +
      +long int labs(long int j)
      +{
      +  if (j < 0)
      +    {
      +      j = -j;
      +    }
      +  return j;
      +}
      diff --git a/nuttx/lib/stdlib/lib_llabs.c b/nuttx/lib/stdlib/lib_llabs.c
      new file mode 100644
      index 0000000000..db7d3dbe07
      --- /dev/null
      +++ b/nuttx/lib/stdlib/lib_llabs.c
      @@ -0,0 +1,57 @@
      +/************************************************************************
      + * lib/stdlib/lib_llabs.c
      + *
      + *   Copyright (C) 2010-2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Global Functions
      + ************************************************************************/
      +
      +#ifdef CONFIG_HAVE_LONG_LONG
      +long long int llabs(long long int j)
      +{
      +  if (j < 0)
      +    {
      +      j = -j;
      +    }
      +  return j;
      +}
      +#endif
      diff --git a/nuttx/lib/stdlib/lib_qsort.c b/nuttx/lib/stdlib/lib_qsort.c
      new file mode 100644
      index 0000000000..9dd5c00409
      --- /dev/null
      +++ b/nuttx/lib/stdlib/lib_qsort.c
      @@ -0,0 +1,238 @@
      +/****************************************************************************
      + * lib/stdlib/lib_qsort.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
      + *   Author: Gregory Nutt 
      + *
      + * Leveraged from:
      + *
      + *  Copyright (c) 1992, 1993
      + *  The Regents of the University of California.  All rights reserved.
      + *
      + * 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. All advertising materials mentioning features or use of this software
      + *    must display the following acknowledgement:
      + *    This product includes software developed by the University of
      + *    California, Berkeley and its contributors.
      + * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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 
      +
      +/****************************************************************************
      + * Preprocessor Definitions
      + ****************************************************************************/
      +
      +#define min(a, b)  (a) < (b) ? a : b
      +
      +#define swapcode(TYPE, parmi, parmj, n) \
      +  { \
      +    long i = (n) / sizeof (TYPE); \
      +    register TYPE *pi = (TYPE *) (parmi); \
      +    register TYPE *pj = (TYPE *) (parmj); \
      +    do { \
      +      register TYPE  t = *pi; \
      +      *pi++ = *pj; \
      +      *pj++ = t; \
      +    } while (--i > 0); \
      +  }
      +
      +#define SWAPINIT(a, size) \
      +  swaptype = ((char *)a - (char *)0) % sizeof(long) || \
      +  size % sizeof(long) ? 2 : size == sizeof(long)? 0 : 1;
      +
      +#define swap(a, b) \
      +  if (swaptype == 0) \
      +    { \
      +      long t = *(long *)(a); \
      +      *(long *)(a) = *(long *)(b); \
      +      *(long *)(b) = t; \
      +    } \
      +  else \
      +    { \
      +      swapfunc(a, b, size, swaptype); \
      +    }
      +
      +#define vecswap(a, b, n) if ((n) > 0) swapfunc(a, b, n, swaptype)
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +static inline void swapfunc(char *a, char *b, int n, int swaptype);
      +static inline char *med3(char *a, char *b, char *c,
      +                         int (*compar)(const void *, const void *));
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +static inline void swapfunc(char *a, char *b, int n, int swaptype)
      +{
      +  if(swaptype <= 1)
      +    {
      +      swapcode(long, a, b, n)
      +    }
      +  else
      +    {
      +      swapcode(char, a, b, n)
      +    }
      +}
      +
      +static inline char *med3(char *a, char *b, char *c,
      +                         int (*compar)(const void *, const void *))
      +{
      +  return compar(a, b) < 0 ?
      +         (compar(b, c) < 0 ? b : (compar(a, c) < 0 ? c : a ))
      +              :(compar(b, c) > 0 ? b : (compar(a, c) < 0 ? a : c ));
      +}
      +
      +/****************************************************************************
      + * Public Function
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: qsort
      + *
      + * Description:
      + *   Qsort routine from Bentley & McIlroy's "Engineering a Sort Function".
      + *
      + ****************************************************************************/
      +
      +void qsort(void *base, size_t nmemb, size_t size,
      +           int(*compar)(const void *, const void *))
      +{
      +  char *pa, *pb, *pc, *pd, *pl, *pm, *pn;
      +  int d, r, swaptype, swap_cnt;
      +
      +loop:
      +  SWAPINIT(base, size);
      +  swap_cnt = 0;
      +  if (nmemb < 7)
      +    {
      +      for (pm = (char *) base + size; pm < (char *) base + nmemb * size; pm += size)
      +        {
      +          for (pl = pm; pl > (char *) base && compar(pl - size, pl) > 0; pl -= size)
      +            {
      +              swap(pl, pl - size);
      +            }
      +        }
      +      return;
      +  }
      +
      +  pm = (char *) base + (nmemb / 2) * size;
      +  if (nmemb > 7)
      +    {
      +      pl = base;
      +      pn = (char *) base + (nmemb - 1) * size;
      +      if (nmemb > 40)
      +        {
      +          d = (nmemb / 8) * size;
      +          pl = med3(pl, pl + d, pl + 2 * d, compar);
      +          pm = med3(pm - d, pm, pm + d, compar);
      +          pn = med3(pn - 2 * d, pn - d, pn, compar);
      +        }
      +      pm = med3(pl, pm, pn, compar);
      +    }
      +  swap(base, pm);
      +  pa = pb = (char *) base + size;
      +
      +  pc = pd = (char *) base + (nmemb - 1) * size;
      +  for (;;)
      +    {
      +      while (pb <= pc && (r = compar(pb, base)) <= 0)
      +        {
      +          if (r == 0)
      +            {
      +              swap_cnt = 1;
      +              swap(pa, pb);
      +              pa += size;
      +            }
      +          pb += size;
      +        }
      +      while (pb <= pc && (r = compar(pc, base)) >= 0)
      +        {
      +          if (r == 0)
      +            {
      +              swap_cnt = 1;
      +              swap(pc, pd);
      +              pd -= size;
      +            }
      +          pc -= size;
      +        }
      +
      +      if (pb > pc)
      +        {
      +          break;
      +        }
      +
      +      swap(pb, pc);
      +      swap_cnt = 1;
      +      pb += size;
      +      pc -= size;
      +    }
      +
      +  if (swap_cnt == 0)
      +    {
      +      /* Switch to insertion sort */
      +
      +      for (pm = (char *) base + size; pm < (char *) base + nmemb * size; pm += size)
      +        {
      +          for (pl = pm; pl > (char *) base && compar(pl - size, pl) > 0; pl -= size)
      +            {
      +              swap(pl, pl - size);
      +            }
      +        }
      +      return;
      +    }
      +
      +  pn = (char *) base + nmemb * size;
      +  r = min(pa - (char *)base, pb - pa);
      +  vecswap(base, pb - r, r);
      +  r = min(pd - pc, pn - pd - size);
      +  vecswap(pb, pn - r, r);
      +
      +  if ((r = pb - pa) > size)
      +    {
      +      qsort(base, r / size, size, compar);
      +    }
      +
      +  if ((r = pd - pc) > size)
      +    {
      +      /* Iterate rather than recurse to save stack space */
      +      base = pn - r;
      +      nmemb = r / size;
      +      goto loop;
      +    }
      +}
      +
      diff --git a/nuttx/lib/stdlib/lib_rand.c b/nuttx/lib/stdlib/lib_rand.c
      new file mode 100644
      index 0000000000..7227c52d0d
      --- /dev/null
      +++ b/nuttx/lib/stdlib/lib_rand.c
      @@ -0,0 +1,220 @@
      +/************************************************************
      + * lib/stdlib/lib_rand.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +#include 
      +
      +/************************************************************
      + * Definitions
      + ************************************************************/
      +
      +#ifndef CONFIG_LIB_RAND_ORDER
      +#define CONFIG_LIB_RAND_ORDER 1
      +#endif
      +
      +/* Values needed by the random number generator */
      +
      +#define RND1_CONSTK  470001
      +#define RND1_CONSTP  999563
      +#define RND2_CONSTK1 366528
      +#define RND2_CONSTK2 508531
      +#define RND2_CONSTP  998917
      +#define RND3_CONSTK1 360137
      +#define RND3_CONSTK2 519815
      +#define RND3_CONSTK3 616087
      +#define RND3_CONSTP  997783
      +
      +#if CONFIG_LIB_RAND_ORDER == 1
      +# define RND_CONSTP RND1_CONSTP
      +#elif CONFIG_LIB_RAND_ORDER == 2
      +# define RND_CONSTP RND2_CONSTP
      +#else
      +# define RND_CONSTP RND3_CONSTP
      +#endif
      +
      +/************************************************************
      + * Private Type Declarations
      + ************************************************************/
      +
      +/************************************************************
      + * Private Function Prototypes
      + ************************************************************/
      +
      +static unsigned int nrand(unsigned int nLimit);
      +static double_t frand1(void);
      +#if (CONFIG_LIB_RAND_ORDER > 1)
      +static double_t frand2(void);
      +#if (CONFIG_LIB_RAND_ORDER > 2)
      +static double_t frand3(void);
      +#endif
      +#endif
      +
      +/**********************************************************
      + * Global Constant Data
      + **********************************************************/
      +
      +/************************************************************
      + * Global Variables
      + ************************************************************/
      +
      +/**********************************************************
      + * Private Constant Data
      + **********************************************************/
      +
      +/************************************************************
      + * Private Variables
      + ************************************************************/
      +
      +static unsigned long g_nRandInt1;
      +#if (CONFIG_LIB_RAND_ORDER > 1)
      +static unsigned long g_nRandInt2;
      +#if (CONFIG_LIB_RAND_ORDER > 2)
      +static unsigned long g_nRandInt3;
      +#endif
      +#endif
      +
      +/************************************************************
      + * Private Functions
      + ************************************************************/
      + 
      +static unsigned int nrand(unsigned int nLimit)
      +{
      +  unsigned long nResult;
      +  double_t fRatio;
      +
      +  /* Loop to be sure a legal random number is generated */
      +  do {
      +
      +    /* Get a random integer in the requested range */
      +#if (CONFIG_LIB_RAND_ORDER == 1)
      +    fRatio = frand1();
      +#elif (CONFIG_LIB_RAND_ORDER == 2)
      +    fRatio = frand2();
      +#else
      +    fRatio = frand3();
      +#endif
      +
      +    /* Then, produce the return-able value */
      +    nResult = (unsigned long)(((double_t)nLimit) * fRatio);
      +
      +  } while (nResult >= (unsigned long)nLimit);
      +
      +  return (unsigned int)nResult;
      +
      +} /* end nrand */
      +
      +static double_t frand1(void)
      +{
      +  unsigned long nRandInt;
      +
      +  /* First order congruential generator */
      +  nRandInt = (RND1_CONSTK * g_nRandInt1) % RND1_CONSTP;
      +  g_nRandInt1 = nRandInt;
      +
      +  /* Construct an floating point value in the range from 0.0 up to 1.0 */
      +  return ((double_t)nRandInt) / ((double_t)RND_CONSTP);
      +
      +} /* end frand */
      +
      +#if (CONFIG_LIB_RAND_ORDER > 1)
      +static double_t frand2(void)
      +{
      +  unsigned long nRandInt;
      +
      +  /* Second order congruential generator */
      +  nRandInt = (RND2_CONSTK1 * g_nRandInt1 + RND2_CONSTK2 * g_nRandInt2) %
      +    RND2_CONSTP;
      +  g_nRandInt2 = g_nRandInt1;
      +  g_nRandInt1 = nRandInt;
      +
      +  /* Construct an floating point value in the range from 0.0 up to 1.0 */
      +  return ((double_t)nRandInt) / ((double_t)RND_CONSTP);
      +
      +} /* end frand */
      +
      +#if (CONFIG_LIB_RAND_ORDER > 2)
      +static double_t frand3(void)
      +{
      +  unsigned long nRandInt;
      +
      +  /* Third order congruential generator */
      +  nRandInt = (RND3_CONSTK1 * g_nRandInt1 + RND3_CONSTK2 * g_nRandInt2 +
      +	      RND3_CONSTK2 * g_nRandInt3) % RND3_CONSTP;
      +  g_nRandInt3 = g_nRandInt2;
      +  g_nRandInt2 = g_nRandInt1;
      +  g_nRandInt1 = nRandInt;
      +
      +  /* Construct an floating point value in the range from 0.0 up to 1.0 */
      +  return ((double_t)nRandInt) / ((double_t)RND_CONSTP);
      +
      +} /* end frand */
      +#endif
      +#endif
      +
      +/************************************************************
      + * Public Functions
      + ************************************************************/
      +/************************************************************
      + * Function:  srand, rand
      + ************************************************************/
      +
      +void srand(unsigned int seed)
      +{
      +  g_nRandInt1 = seed;
      +#if (CONFIG_LIB_RAND_ORDER > 1)
      +  g_nRandInt2 = seed;
      +  (void)frand1();
      +#if (CONFIG_LIB_RAND_ORDER > 2)
      +  g_nRandInt3 = seed;
      +  (void)frand2();
      +#endif
      +#endif
      +
      +} /* end srand */
      +
      +int rand(void)
      +{
      +  return (int)nrand(32768);
      +
      +} /* end rand */
      +
      diff --git a/nuttx/lib/string/Make.defs b/nuttx/lib/string/Make.defs
      new file mode 100644
      index 0000000000..191b9ffea5
      --- /dev/null
      +++ b/nuttx/lib/string/Make.defs
      @@ -0,0 +1,58 @@
      +############################################################################
      +# lib/string/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the string C files to the build
      +
      +CSRCS += lib_checkbase.c lib_isbasedigit.c lib_memset.c lib_memchr.c \
      +		 lib_memccpy.c lib_memcmp.c lib_memmove.c lib_skipspace.c \
      +		 lib_strcasecmp.c lib_strcat.c lib_strchr.c lib_strcpy.c lib_strcmp.c \
      +		 lib_strcspn.c lib_strdup.c lib_strerror.c lib_strlen.c lib_strnlen.c \
      +		 lib_strncasecmp.c lib_strncat.c lib_strncmp.c lib_strncpy.c \
      +		 lib_strndup.c lib_strcasestr.c lib_strpbrk.c lib_strrchr.c\
      +		 lib_strspn.c lib_strstr.c lib_strtok.c lib_strtokr.c lib_strtol.c \
      +		 lib_strtoll.c lib_strtoul.c lib_strtoull.c lib_strtod.c
      +
      +ifneq ($(CONFIG_ARCH_MEMCPY),y)
      +ifeq ($(CONFIG_MEMCPY_VIK),y)
      +CSRCS += lib_vikmemcpy.c
      +else
      +CSRCS += lib_memcpy.c
      +endif
      +endif
      +
      +# Add the string directory to the build
      +
      +DEPPATH += --dep-path string
      +VPATH += :string
      diff --git a/nuttx/lib/string/lib_checkbase.c b/nuttx/lib/string/lib_checkbase.c
      new file mode 100644
      index 0000000000..bc79ab2cec
      --- /dev/null
      +++ b/nuttx/lib/string/lib_checkbase.c
      @@ -0,0 +1,115 @@
      +/****************************************************************************
      + * lib/string/lib_checkbase.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_checkbase
      + *
      + * Description:
      + *   This is part of the strol() family implementation.  This function checks
      + *   the initial part of a string to see if it can determine the numeric
      + *   base that is represented.
      + *
      + * Assumptions:
      + *   *ptr points to the first, non-whitespace character in the string.
      + *
      + ****************************************************************************/
      + 
      +int lib_checkbase(int base, const char **pptr)
      +{
      +   const char *ptr = *pptr;
      +
      +  /* Check for unspecified base */
      +
      +  if (!base)
      +    {
      +      /* Assume base 10 */
      +
      +      base = 10;
      +
      +      /* Check for leading '0' - that would signify octal or hex (or binary) */
      +
      +      if (*ptr == '0')
      +        {
      +          /* Assume octal */
      +
      +          base = 8;
      +          ptr++;
      +
      +          /* Check for hexidecimal */
      +
      +          if ((*ptr == 'X' || *ptr == 'x') && 
      +              lib_isbasedigit(ptr[1], 16, NULL))
      +            {
      +              base = 16;
      +              ptr++;
      +            }
      +        }
      +    }
      +
      +  /* If it a hexidecimal representation, than discard any leading "0X" or "0x" */
      +
      +  else if (base == 16)
      +    {
      +      if (ptr[0] == '0' && (ptr[1] == 'X' || ptr[1] == 'x'))
      +        {
      +          ptr += 2;
      +        }
      +    }
      +
      +  /* Return the updated pointer and base */
      +
      +  *pptr = ptr;
      +  return base;
      +}
      +
      diff --git a/nuttx/lib/string/lib_isbasedigit.c b/nuttx/lib/string/lib_isbasedigit.c
      new file mode 100644
      index 0000000000..a2421bf2a4
      --- /dev/null
      +++ b/nuttx/lib/string/lib_isbasedigit.c
      @@ -0,0 +1,105 @@
      +/****************************************************************************
      + * lib/string/lib_isbasedigit.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_isbasedigit
      + *
      + * Description:
      + *   Given an ASCII character, ch, and a base (1-36) do two
      + *   things:  1) Determine if ch is a valid charcter, and 2)
      + *   convert ch to its binary value.
      + *
      + ****************************************************************************/
      +
      +bool lib_isbasedigit(int ch, int base, int *value)
      +{
      +  bool ret = false;
      +  int  tmp = 0;
      +
      +  if (base <= 10)
      +    {
      +      if (ch >= '0' && ch <= base + '0' - 1)
      +        {
      +          tmp = ch - '0';
      +          ret = true;
      +        }
      +    }
      +  else if (base <= 36)
      +    {
      +      if (ch >= '0' && ch <= '9')
      +        {
      +          tmp = ch - '0';
      +          ret = true;
      +        }
      +      else if (ch >= 'a' && ch <= 'a' + base - 11)
      +        {
      +          tmp = ch - 'a' + 10;
      +          ret = true;
      +        }
      +      else if (ch >= 'A' && ch <= 'A' + base - 11)
      +        {
      +          tmp = ch - 'A' + 10;
      +          ret = true;
      +        }
      +    }
      +
      +  if (value)
      +    {
      +      *value = tmp;
      +    }
      +  return ret;
      +}
      +
      +
      diff --git a/nuttx/lib/string/lib_memccpy.c b/nuttx/lib/string/lib_memccpy.c
      new file mode 100644
      index 0000000000..1f3dbb52dd
      --- /dev/null
      +++ b/nuttx/lib/string/lib_memccpy.c
      @@ -0,0 +1,99 @@
      +/****************************************************************************
      + * lib/string/lib_memccpy.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +
      +/****************************************************************************
      + * Name: memccpy
      + *
      + * Description:
      + *   The memccpy() function copies bytes from memory area s2 into s1,
      + *   stopping after the first occurrence of byte c (converted to an unsigned
      + *   char) is copied, or after n bytes are copied, whichever comes first. If
      + *   copying takes place between objects that overlap, the behavior is
      + *   undefined.
      + *
      + * Returned Value:
      + *   The memccpy() function returns a pointer to the byte after the copy of c
      + *   in s1, or a null pointer if c was not found in the first n bytes of s2.
      + *
      + ****************************************************************************/
      +
      +FAR void *memccpy(FAR void *s1, FAR const void *s2, int c, size_t n)
      +{
      +  FAR unsigned char *pout = (FAR unsigned char*)s1;
      +  FAR unsigned char *pin  = (FAR unsigned char*)s2;
      +
      +  /* Copy at most n bytes */
      +
      +  while (n-- > 0)
      +    {
      +      /* Copy one byte */
      +
      +      *pout = *pin++;
      +
      +      /* Did we just copy the terminating byte c? */
      +
      +      if (*pout == (unsigned char)c)
      +        {
      +          /* Yes return a pointer to the byte after the copy of c into s1 */
      +
      +          return (FAR void *)pout;
      +        }
      +
      +      /* No increment to the next destination location */
      +
      +      pout++;
      +    }
      +
      +  /* C was not found in the first n bytes of s2 */
      +
      +  return NULL;
      +}
      diff --git a/nuttx/lib/string/lib_memchr.c b/nuttx/lib/string/lib_memchr.c
      new file mode 100644
      index 0000000000..e0dec82700
      --- /dev/null
      +++ b/nuttx/lib/string/lib_memchr.c
      @@ -0,0 +1,80 @@
      +/****************************************************************************
      + * lib/string/lib_memchr.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: memchr
      + *
      + * Description:
      + *   The memchr() function locates the first occurrence of 'c' (converted to
      + *   an unsigned char) in the initial 'n' bytes (each interpreted as
      + *   unsigned char) of the object pointed to by s.
      + *
      + * Returned Value:
      + *   The memchr() function returns a pointer to the located byte, or a null
      + *   pointer if the byte does not occur in the object.
      + *
      + ****************************************************************************/
      +
      +FAR void *memchr(FAR const void *s, int c, size_t n)
      +{
      +  FAR const unsigned char *p = (FAR const unsigned char *)s;
      +
      +  if (s)
      +    {
      +      while (n--)
      +        {
      +          if (*p == (unsigned char)c)
      +            {
      +              return (FAR void *)p;
      +            }
      +
      +          p++;
      +        }
      +    }
      +
      +  return NULL;
      +}
      diff --git a/nuttx/lib/string/lib_memcmp.c b/nuttx/lib/string/lib_memcmp.c
      new file mode 100644
      index 0000000000..eb2e1fd125
      --- /dev/null
      +++ b/nuttx/lib/string/lib_memcmp.c
      @@ -0,0 +1,74 @@
      +/************************************************************
      + * lib/string/lib_memcmp.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************
      + * Global Functions
      + ************************************************************/
      +
      +#ifndef CONFIG_ARCH_MEMCMP
      +int memcmp(const void *s1, const void *s2, size_t n)
      +{
      +  unsigned char *p1 = (unsigned char *)s1;
      +  unsigned char *p2 = (unsigned char *)s2;
      +
      +  while (n-- > 0)
      +    {
      +      if (*p1 < *p2)
      +        {
      +          return -1;
      +        }
      +      else if (*p1 > *p2)
      +        {
      +          return 1;
      +        }
      +
      +      p1++;
      +      p2++;
      +    }
      +  return 0;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_memcpy.c b/nuttx/lib/string/lib_memcpy.c
      new file mode 100644
      index 0000000000..3b62edbabd
      --- /dev/null
      +++ b/nuttx/lib/string/lib_memcpy.c
      @@ -0,0 +1,64 @@
      +/****************************************************************************
      + * lib/string/lib_memcpy.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: memcpy
      + ****************************************************************************/
      +
      +#ifndef CONFIG_ARCH_MEMCPY
      +FAR void *memcpy(FAR void *dest, FAR const void *src, size_t n)
      +{
      +  FAR unsigned char *pout = (FAR unsigned char*)dest;
      +  FAR unsigned char *pin  = (FAR unsigned char*)src;
      +  while (n-- > 0) *pout++ = *pin++;
      +  return dest;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_memmove.c b/nuttx/lib/string/lib_memmove.c
      new file mode 100644
      index 0000000000..85cb79e174
      --- /dev/null
      +++ b/nuttx/lib/string/lib_memmove.c
      @@ -0,0 +1,77 @@
      +/************************************************************
      + * lib/string/lib_memmove.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Compilation Switches
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************
      + * Global Functions
      + ************************************************************/
      +
      +#ifndef CONFIG_ARCH_MEMMOVE
      +void *memmove(void *dest, const void *src, size_t count)
      +{
      +  char *tmp, *s;
      +  if (dest <= src)
      +    {
      +      tmp = (char*) dest;
      +      s   = (char*) src;
      +      while (count--)
      +        {
      +	  *tmp++ = *s++;
      +        }
      +    }
      +  else
      +    {
      +      tmp = (char*) dest + count;
      +      s   = (char*) src + count;
      +      while (count--)
      +        {
      +	  *--tmp = *--s;
      +        }
      +    }
      +
      +  return dest;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_memset.c b/nuttx/lib/string/lib_memset.c
      new file mode 100644
      index 0000000000..31c386e928
      --- /dev/null
      +++ b/nuttx/lib/string/lib_memset.c
      @@ -0,0 +1,188 @@
      +
      +/****************************************************************************
      + * lib/string/lib_memset.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ****************************************************************************/
      +
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/* Can't support CONFIG_MEMSET_64BIT if the platform does not have 64-bit
      + * integer types.
      + */
      +
      +#ifndef CONFIG_HAVE_LONG_LONG
      +#  undef CONFIG_MEMSET_64BIT
      +#endif
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +#ifndef CONFIG_ARCH_MEMSET
      +void *memset(void *s, int c, size_t n)
      +{
      +#ifdef CONFIG_MEMSET_OPTSPEED
      +  /* This version is optimized for speed (you could do better
      +   * still by exploiting processor caching or memory burst
      +   * knowledge.)
      +   */
      +
      +  uintptr_t addr  = (uintptr_t)s;
      +  uint16_t  val16 = ((uint16_t)c << 8) | (uint16_t)c;
      +  uint32_t  val32 = ((uint32_t)val16 << 16) | (uint32_t)val16;
      +#ifdef CONFIG_MEMSET_64BIT
      +  uint64_t  val64 = ((uint64_t)val32 << 32) | (uint64_t)val32;
      +#endif
      +
      +  /* Make sure that there is something to be cleared */
      +
      +  if (n > 0)
      +    {
      +      /* Align to a 16-bit boundary */
      +
      +      if ((addr & 1) != 0)
      +        {
      +          *(uint8_t*)addr = (uint8_t)c;
      +          addr += 1;
      +          n    -= 1;
      +        }
      +
      +      /* Check if there are at least 16-bits left to be written */
      +
      +      if (n >= 2)
      +        {
      +          /* Align to a 32-bit boundary (we know that the destination
      +           * address is already aligned to at least a 16-bit boundary).
      +           */
      +
      +          if ((addr & 3) != 0)
      +            {
      +              *(uint16_t*)addr = val16;
      +              addr += 2;
      +              n    -= 2;
      +            }
      +
      +#ifndef CONFIG_MEMSET_64BIT
      +          /* Loop while there are at least 32-bits left to be written */
      +
      +          while (n >= 4)
      +            {
      +              *(uint32_t*)addr = val32;
      +              addr += 4;
      +              n    -= 4;
      +            }
      +#else
      +          /* Check if there are at least 32-bits left to be written */
      +
      +          if (n >= 4)
      +            {
      +              /* Align to a 64-bit boundary (we know that the destination
      +               * address is already aligned to at least a 32-bit boundary).
      +               */
      +
      +              if ((addr & 7) != 0)
      +                {
      +                  *(uint32_t*)addr = val32;
      +                  addr += 4;
      +                  n    -= 4;
      +                }
      +
      +              /* Loop while there are at least 64-bits left to be written */
      +
      +              while (n >= 8)
      +                {
      +                  *(uint64_t*)addr = val64;
      +                  addr += 8;
      +                  n    -= 8;
      +                }
      +            }
      +#endif
      +        }
      +
      +#ifdef CONFIG_MEMSET_64BIT
      +      /* We may get here with n in the range 0..7.  If n >= 4, then we should
      +       * have 64-bit alignment.
      +       */
      +
      +      if (n >= 4)
      +        {
      +          *(uint32_t*)addr = val32;
      +          addr += 4;
      +          n    -= 4;
      +        }
      +#endif
      +
      +      /* We may get here under the following conditions:
      +       *
      +       *   n = 0, addr may or may not be aligned
      +       *   n = 1, addr is aligned to at least a 16-bit boundary
      +       *   n = 2, addr is aligned to a 32-bit boundary
      +       *   n = 3, addr is aligned to a 32-bit boundary
      +       */
      +
      +      if (n >= 2)
      +        {
      +          *(uint16_t*)addr = val16;
      +          addr += 2;
      +          n    -= 2;
      +        }
      +
      +      if (n >= 1)
      +        {
      +          *(uint8_t*)addr = (uint8_t)c;
      +        }
      +    }
      +#else
      +  /* This version is optimized for size */
      +
      +  unsigned char *p = (unsigned char*)s;
      +  while (n-- > 0) *p++ = c;
      +#endif
      +  return s;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_skipspace.c b/nuttx/lib/string/lib_skipspace.c
      new file mode 100644
      index 0000000000..b4e6588e59
      --- /dev/null
      +++ b/nuttx/lib/string/lib_skipspace.c
      @@ -0,0 +1,69 @@
      +/****************************************************************************
      + * lib/string/lib_skipspace.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: lib_skipspace
      + *
      + * Description:
      + *   Skip over leading whitespace
      + *
      + ****************************************************************************/
      +
      +void lib_skipspace(const char **pptr)
      +{
      +   const char *ptr = *pptr;
      +   while (isspace(*ptr)) ptr++;
      +   *pptr = ptr;
      +}
      +
      +
      diff --git a/nuttx/lib/string/lib_strcasecmp.c b/nuttx/lib/string/lib_strcasecmp.c
      new file mode 100644
      index 0000000000..d4aa8cc031
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strcasecmp.c
      @@ -0,0 +1,65 @@
      +/****************************************************************************
      + * lib/string/lib_strcasecmp.c
      + *
      + *   Copyright (C) 2008-2009, 2011 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.
      + *
      + *****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + *****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Public Functions
      + *****************************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRCMP
      +int strcasecmp(const char *cs, const char *ct)
      +{
      +  int result;
      +  for (;;)
      +    {
      +      if ((result = (int)toupper(*cs) - (int)toupper(*ct)) != 0 || !*cs)
      +        {
      +          break;
      +        }
      +
      +      cs++;
      +      ct++;
      +    }
      +  return result;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strcasestr.c b/nuttx/lib/string/lib_strcasestr.c
      new file mode 100644
      index 0000000000..23f0ab57e6
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strcasestr.c
      @@ -0,0 +1,134 @@
      +/****************************************************************************
      + * lib/string/lib_strstr.c
      + *
      + *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      + *   Author: Gregory Nutt 
      + *
      + * Redistribution and use str 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 str binary form must reproduce the above copyright
      + *    notice, this list of conditions and the following disclaimer str
      + *    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 
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +static FAR char *strcasechr(FAR const char *s, int uc)
      +{
      +  register char ch;
      +
      +  if (s)
      +    {
      +      for (; *s; s++)
      +        {
      +          ch = *s;
      +          if (toupper(ch) == uc)
      +            {
      +              return (FAR char*)s;
      +            }
      +        }
      +    }
      +
      +  return NULL;
      +}
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +FAR char *strcasestr(FAR const char *str, FAR const char *substr)
      +{
      +  const char *candidate;  /* Candidate in str with matching start character */
      +  char         ch;        /* First character of the substring */
      +  int          len;       /* The length of the substring */
      +
      +  /* Special case the empty substring */
      +
      +  len = strlen(substr);
      +  ch  = *substr;
      +
      +  if (!ch)
      +    {
      +      /* We'll say that an empty substring matches at the beginning of
      +       * the string
      +       */
      +
      +      return (char*)str;
      +    }
      +
      +  /* Search for the substring */
      +
      +  candidate = str;
      +  ch        = toupper(ch);
      +
      +  for (;;)
      +    {
      +      /* strcasechr() will return a pointer to the next occurrence of the
      +       * character ch in the string (ignoring case)
      +       */
      +
      +      candidate = strcasechr(candidate, ch);
      +      if (!candidate || strlen(candidate) < len)
      +        {
      +           /* First character of the substring does not appear in the string
      +            * or the remainder of the string is not long enough to contain the
      +            * substring.
      +            */
      +
      +           return NULL;
      +        }
      +
      +      /* Check if this is the beginning of a matching substring (ignoring case) */
      +
      +      if (strncasecmp(candidate, substr, len) == 0)
      +        {
      +           /* Yes.. return the pointer to the first occurrence of the matching
      +            * substring.
      +            */
      +
      +           return (char*)candidate;
      +        }
      +
      +      /* No, find the next candidate after this one */
      +
      +      candidate++;
      +    }
      +
      +  /* Won't get here, but some compilers might complain */
      +
      +  return NULL;
      +}
      +
      diff --git a/nuttx/lib/string/lib_strcat.c b/nuttx/lib/string/lib_strcat.c
      new file mode 100644
      index 0000000000..20350fec07
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strcat.c
      @@ -0,0 +1,62 @@
      +/****************************************************************************
      + * lib/string/lib_strcat.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRCAT
      +char *strcat(char *dest, const char *src)
      +{
      +  char *ret   = dest;
      +
      +  dest  += strlen(dest);
      +  while (*src != '\0')
      +    {
      +      *dest++ = *src++;
      +    }
      +  *dest = '\0';
      +
      +  return ret;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strchr.c b/nuttx/lib/string/lib_strchr.c
      new file mode 100644
      index 0000000000..d0bd22a0ea
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strchr.c
      @@ -0,0 +1,78 @@
      +/****************************************************************************
      + * lib/string/lib_strchr.c
      + *
      + *   Copyright (C) 2007, 2009, 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: strchr
      + *
      + * Description:
      + *   The strchr() function locates the first occurrence of 'c' (converted to
      + *   a char) in the string pointed to by 's'. The terminating null byte is
      + *   considered to be part of the string.
      + *
      + * Returned Value:
      + *   Upon completion, strchr() returns a pointer to the byte, or a null
      + *   pointer if the byte was not found.
      + *
      + ****************************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRCHR
      +FAR char *strchr(FAR const char *s, int c)
      +{
      +  if (s)
      +    {
      +      for (; *s; s++)
      +        {
      +          if (*s == c)
      +            {
      +              return (FAR char *)s;
      +            }
      +        }
      +    }
      +
      +  return NULL;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strcmp.c b/nuttx/lib/string/lib_strcmp.c
      new file mode 100644
      index 0000000000..0e3eee8900
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strcmp.c
      @@ -0,0 +1,59 @@
      +/****************************************************************************
      + * lib/string/lib_strcmp.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + *****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + *****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Public Functions
      + *****************************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRCMP
      +int strcmp(const char *cs, const char *ct)
      +{
      +  register signed char result;
      +  for (;;)
      +    {
      +      if ((result = *cs - *ct++) != 0 || !*cs++)
      +	break;
      +    }
      +  return result;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strcpy.c b/nuttx/lib/string/lib_strcpy.c
      new file mode 100644
      index 0000000000..e2f70b94e3
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strcpy.c
      @@ -0,0 +1,55 @@
      +/************************************************************************
      + * lib/string/lib_strcpy.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Global Functions
      + ************************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRCPY
      +char *strcpy(char *dest, const char *src)
      +{
      +  char *tmp = dest;
      +  while ((*dest++ = *src++) != '\0');
      +  return tmp;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strcspn.c b/nuttx/lib/string/lib_strcspn.c
      new file mode 100644
      index 0000000000..9da89241c5
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strcspn.c
      @@ -0,0 +1,67 @@
      +/****************************************************************************
      + * lib/string/lib_strcspn.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: strcspn
      + *
      + * Description:
      + *  strspn() calculates the length of the initial segment of s which
      + *  consists entirely of characters not in reject
      + *
      + ****************************************************************************/
      +
      +size_t strcspn(const char *s, const char *reject)
      +{
      +  size_t i;
      +  for (i = 0; s[i] && strchr(reject, s[i]) == NULL; i++);
      +  return i;
      +}
      +
      diff --git a/nuttx/lib/string/lib_strdup.c b/nuttx/lib/string/lib_strdup.c
      new file mode 100644
      index 0000000000..44a0cbc0d8
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strdup.c
      @@ -0,0 +1,62 @@
      +/************************************************************************
      + * lib/string//lib_strdup.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/************************************************************************
      + * Global Functions
      + ************************************************************************/
      +
      +FAR char *strdup(const char *s)
      +{
      +  FAR char *news = NULL;
      +  if (s)
      +    {
      +      news = (FAR char*)lib_malloc(strlen(s) + 1);
      +      if (news)
      +        {
      +          strcpy(news, s);
      +        }
      +    }
      +  return news;
      +}
      diff --git a/nuttx/lib/string/lib_strerror.c b/nuttx/lib/string/lib_strerror.c
      new file mode 100644
      index 0000000000..249f695c1b
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strerror.c
      @@ -0,0 +1,375 @@
      +/************************************************************************
      + * lib/string/lib_strerror.c
      + *
      + *   Copyright (C) 2007, 2009, 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************************
      + * Definitions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Private Types
      + ************************************************************************/
      +
      +struct errno_strmap_s
      +{
      +  uint8_t     errnum;
      +  const char *str;
      +};
      +
      +/************************************************************************
      + * Private Data
      + ************************************************************************/
      +
      +#ifdef CONFIG_LIBC_STRERROR
      +
      +/* This table maps all error numbers to descriptive strings.
      + * The only assumption that the code makes with regard to this
      + * this table is that it is ordered by error number.
      + *
      + * The size of this table is quite large.  Its size can be
      + * reduced by eliminating some of the more obscure error
      + * strings.
      + */
      +
      +#ifndef CONFIG_LIBC_STRERROR_SHORT
      +
      +static const struct errno_strmap_s g_errnomap[] =
      +{
      +  { EPERM,               EPERM_STR           },
      +  { ENOENT,              ENOENT_STR          },
      +  { ESRCH,               ESRCH_STR           },
      +  { EINTR,               EINTR_STR           },
      +  { EIO,                 EIO_STR             },
      +  { ENXIO,               ENXIO_STR           },
      +  { E2BIG,               E2BIG_STR           },
      +  { ENOEXEC,             ENOEXEC_STR         },
      +  { EBADF,               EBADF_STR           },
      +  { ECHILD,              ECHILD_STR          },
      +  { EAGAIN,              EAGAIN_STR          },
      +  { ENOMEM,              ENOMEM_STR          },
      +  { EACCES,              EACCES_STR          },
      +  { EFAULT,              EFAULT_STR          },
      +  { ENOTBLK,             ENOTBLK_STR         },
      +  { EBUSY,               EBUSY_STR           },
      +  { EEXIST,              EEXIST_STR          },
      +  { EXDEV,               EXDEV_STR           },
      +  { ENODEV,              ENODEV_STR          },
      +  { ENOTDIR,             ENOTDIR_STR         },
      +  { EISDIR,              EISDIR_STR          },
      +  { EINVAL,              EINVAL_STR          },
      +  { ENFILE,              ENFILE_STR          },
      +  { EMFILE,              EMFILE_STR          },
      +  { ENOTTY,              ENOTTY_STR          },
      +  { ETXTBSY,             ETXTBSY_STR         },
      +  { EFBIG,               EFBIG_STR           },
      +  { ENOSPC,              ENOSPC_STR          },
      +  { ESPIPE,              ESPIPE_STR          },
      +  { EROFS,               EROFS_STR           },
      +  { EMLINK,              EMLINK_STR          },
      +  { EPIPE,               EPIPE_STR           },
      +  { EDOM,                EDOM_STR            },
      +  { ERANGE,              ERANGE_STR          },
      +  { EDEADLK,             EDEADLK_STR         },
      +  { ENAMETOOLONG,        ENAMETOOLONG_STR    },
      +  { ENOLCK,              ENOLCK_STR          },
      +  { ENOSYS,              ENOSYS_STR          },
      +  { ENOTEMPTY,           ENOTEMPTY_STR       },
      +  { ELOOP,               ELOOP_STR           },
      +  { ENOMSG,              ENOMSG_STR          },
      +  { EIDRM,               EIDRM_STR           },
      +  { ECHRNG,              ECHRNG_STR          },
      +  { EL2NSYNC,            EL2NSYNC_STR        },
      +  { EL3HLT,              EL3HLT_STR          },
      +  { EL3RST,              EL3RST_STR          },
      +  { ELNRNG,              ELNRNG_STR          },
      +  { EUNATCH,             EUNATCH_STR         },
      +  { ENOCSI,              ENOCSI_STR          },
      +  { EL2HLT,              EL2HLT_STR          },
      +  { EBADE,               EBADE_STR           },
      +  { EBADR,               EBADR_STR           },
      +  { EXFULL,              EXFULL_STR          },
      +  { ENOANO,              ENOANO_STR          },
      +  { EBADRQC,             EBADRQC_STR         },
      +  { EBADSLT,             EBADSLT_STR         },
      +  { EBFONT,              EBFONT_STR          },
      +  { ENOSTR,              ENOSTR_STR          },
      +  { ENODATA,             ENODATA_STR         },
      +  { ETIME,               ETIME_STR           },
      +  { ENOSR,               ENOSR_STR           },
      +  { ENONET,              ENONET_STR          },
      +  { ENOPKG,              ENOPKG_STR          },
      +  { EREMOTE,             EREMOTE_STR         },
      +  { ENOLINK,             ENOLINK_STR         },
      +  { EADV,                EADV_STR            },
      +  { ESRMNT,              ESRMNT_STR          },
      +  { ECOMM,               ECOMM_STR           },
      +  { EPROTO,              EPROTO_STR          },
      +  { EMULTIHOP,           EMULTIHOP_STR       },
      +  { EDOTDOT,             EDOTDOT_STR         },
      +  { EBADMSG,             EBADMSG_STR         },
      +  { EOVERFLOW,           EOVERFLOW_STR       },
      +  { ENOTUNIQ,            ENOTUNIQ_STR        },
      +  { EBADFD,              EBADFD_STR          },
      +  { EREMCHG,             EREMCHG_STR         },
      +  { ELIBACC,             ELIBACC_STR         },
      +  { ELIBBAD,             ELIBBAD_STR         },
      +  { ELIBSCN,             ELIBSCN_STR         },
      +  { ELIBMAX,             ELIBMAX_STR         },
      +  { ELIBEXEC,            ELIBEXEC_STR        },
      +  { EILSEQ,              EILSEQ_STR          },
      +  { ERESTART,            ERESTART_STR        },
      +  { ESTRPIPE,            ESTRPIPE_STR        },
      +  { EUSERS,              EUSERS_STR          },
      +  { ENOTSOCK,            ENOTSOCK_STR        },
      +  { EDESTADDRREQ,        EDESTADDRREQ_STR    },
      +  { EMSGSIZE,            EMSGSIZE_STR        },
      +  { EPROTOTYPE,          EPROTOTYPE_STR      },
      +  { ENOPROTOOPT,         ENOPROTOOPT_STR     },
      +  { EPROTONOSUPPORT,     EPROTONOSUPPORT_STR },
      +  { ESOCKTNOSUPPORT,     ESOCKTNOSUPPORT_STR },
      +  { EOPNOTSUPP,          EOPNOTSUPP_STR      },
      +  { EPFNOSUPPORT,        EPFNOSUPPORT_STR    },
      +  { EAFNOSUPPORT,        EAFNOSUPPORT_STR    },
      +  { EADDRINUSE,          EADDRINUSE_STR      },
      +  { EADDRNOTAVAIL,       EADDRNOTAVAIL_STR   },
      +  { ENETDOWN,            ENETDOWN_STR        },
      +  { ENETUNREACH,         ENETUNREACH_STR     },
      +  { ENETRESET,           ENETRESET_STR       },
      +  { ECONNABORTED,        ECONNABORTED_STR    },
      +  { ECONNRESET,          ECONNRESET_STR      },
      +  { ENOBUFS,             ENOBUFS_STR         },
      +  { EISCONN,             EISCONN_STR         },
      +  { ENOTCONN,            ENOTCONN_STR        },
      +  { ESHUTDOWN,           ESHUTDOWN_STR       },
      +  { ETOOMANYREFS,        ETOOMANYREFS_STR    },
      +  { ETIMEDOUT,           ETIMEDOUT_STR       },
      +  { ECONNREFUSED,        ECONNREFUSED_STR    },
      +  { EHOSTDOWN,           EHOSTDOWN_STR       },
      +  { EHOSTUNREACH,        EHOSTUNREACH_STR    },
      +  { EALREADY,            EALREADY_STR        },
      +  { EINPROGRESS,         EINPROGRESS_STR     },
      +  { ESTALE,              ESTALE_STR          },
      +  { EUCLEAN,             EUCLEAN_STR         },
      +  { ENOTNAM,             ENOTNAM_STR         },
      +  { ENAVAIL,             ENAVAIL_STR         },
      +  { EISNAM,              EISNAM_STR          },
      +  { EREMOTEIO,           EREMOTEIO_STR       },
      +  { EDQUOT,              EDQUOT_STR          },
      +  { ENOMEDIUM,           ENOMEDIUM_STR       },
      +  { EMEDIUMTYPE,         EMEDIUMTYPE_STR     }
      +};
      +
      +#else /* CONFIG_LIBC_STRERROR_SHORT */
      +
      +static const struct errno_strmap_s g_errnomap[] =
      +{
      +  { EPERM,               "EPERM"             },
      +  { ENOENT,              "ENOENT"            },
      +  { ESRCH,               "ESRCH"             },
      +  { EINTR,               "EINTR"             },
      +  { EIO,                 "EIO"               },
      +  { ENXIO,               "ENXIO"             },
      +  { E2BIG,               "E2BIG"             },
      +  { ENOEXEC,             "ENOEXEC"           },
      +  { EBADF,               "EBADF"             },
      +  { ECHILD,              "ECHILD"            },
      +  { EAGAIN,              "EAGAIN"            },
      +  { ENOMEM,              "ENOMEM"            },
      +  { EACCES,              "EACCES"            },
      +  { EFAULT,              "EFAULT"            },
      +  { ENOTBLK,             "ENOTBLK"           },
      +  { EBUSY,               "EBUSY"             },
      +  { EEXIST,              "EEXIST"            },
      +  { EXDEV,               "EXDEV"             },
      +  { ENODEV,              "ENODEV"            },
      +  { ENOTDIR,             "ENOTDIR"           },
      +  { EISDIR,              "EISDIR"            },
      +  { EINVAL,              "EINVAL"            },
      +  { ENFILE,              "ENFILE"            },
      +  { EMFILE,              "EMFILE"            },
      +  { ENOTTY,              "ENOTTY"            },
      +  { ETXTBSY,             "ETXTBSY"           },
      +  { EFBIG,               "EFBIG"             },
      +  { ENOSPC,              "ENOSPC"            },
      +  { ESPIPE,              "ESPIPE"            },
      +  { EROFS,               "EROFS"             },
      +  { EMLINK,              "EMLINK"            },
      +  { EPIPE,               "EPIPE"             },
      +  { EDOM,                "EDOM"              },
      +  { ERANGE,              "ERANGE"            },
      +  { EDEADLK,             "EDEADLK"           },
      +  { ENAMETOOLONG,        "ENAMETOOLONG"      },
      +  { ENOLCK,              "ENOLCK"            },
      +  { ENOSYS,              "ENOSYS"            },
      +  { ENOTEMPTY,           "ENOTEMPTY"         },
      +  { ELOOP,               "ELOOP"             },
      +  { ENOMSG,              "ENOMSG"            },
      +  { EIDRM,               "EIDRM"             },
      +  { ECHRNG,              "ECHRNG"            },
      +  { EL2NSYNC,            "EL2NSYNC"          },
      +  { EL3HLT,              "EL3HLT"            },
      +  { EL3RST,              "EL3RST"            },
      +  { EL3RST,              "EL3RST"            },
      +  { EUNATCH,             "EUNATCH"           },
      +  { ENOCSI,              "ENOCSI"            },
      +  { EL2HLT,              "EL2HLT"            },
      +  { EBADE,               "EBADE"             },
      +  { EBADR,               "EBADR"             },
      +  { EXFULL,              "EXFULL"            },
      +  { ENOANO,              "ENOANO"            },
      +  { EBADRQC,             "EBADRQC"           },
      +  { EBADSLT,             "EBADSLT"           },
      +  { EBFONT,              "EBFONT"            },
      +  { ENOSTR,              "ENOSTR"            },
      +  { ENODATA,             "ENODATA"           },
      +  { ETIME,               "ETIME"             },
      +  { ENOSR,               "ENOSR"             },
      +  { ENONET,              "ENONET"            },
      +  { ENOPKG,              "ENOPKG"            },
      +  { EREMOTE,             "EREMOTE"           },
      +  { ENOLINK,             "ENOLINK"           },
      +  { EADV,                "EADV"              },
      +  { ESRMNT,              "ESRMNT"            },
      +  { ECOMM,               "ECOMM"             },
      +  { EPROTO,              "EPROTO"            },
      +  { EMULTIHOP,           "EMULTIHOP"         },
      +  { EDOTDOT,             "EDOTDOT"           },
      +  { EBADMSG,             "EBADMSG"           },
      +  { EOVERFLOW,           "EOVERFLOW"         },
      +  { ENOTUNIQ,            "ENOTUNIQ"          },
      +  { EBADFD,              "EBADFD"            },
      +  { EREMCHG,             "EREMCHG"           },
      +  { ELIBACC,             "ELIBACC"           },
      +  { ELIBBAD,             "ELIBBAD"           },
      +  { ELIBSCN,             "ELIBSCN"           },
      +  { ELIBMAX,             "ELIBMAX"           },
      +  { ELIBEXEC,            "ELIBEXEC"          },
      +  { EILSEQ,              "EILSEQ"            },
      +  { ERESTART,            "ERESTART"          },
      +  { ESTRPIPE,            "ESTRPIPE"          },
      +  { EUSERS,              "EUSERS"            },
      +  { ENOTSOCK,            "ENOTSOCK"          },
      +  { EDESTADDRREQ,        "EDESTADDRREQ"      },
      +  { EMSGSIZE,            "EMSGSIZE"          },
      +  { EPROTOTYPE,          "EPROTOTYPE"        },
      +  { ENOPROTOOPT,         "ENOPROTOOPT"       },
      +  { EPROTONOSUPPORT,     "EPROTONOSUPPORT"   },
      +  { ESOCKTNOSUPPORT,     "ESOCKTNOSUPPORT"   },
      +  { EOPNOTSUPP,          "EOPNOTSUPP"        },
      +  { EPFNOSUPPORT,        "EPFNOSUPPORT"      },
      +  { EAFNOSUPPORT,        "EAFNOSUPPORT"      },
      +  { EADDRINUSE,          "EADDRINUSE"        },
      +  { EADDRNOTAVAIL,       "EADDRNOTAVAIL"     },
      +  { ENETDOWN,            "ENETDOWN"          },
      +  { ENETUNREACH,         "ENETUNREACH"       },
      +  { ENETRESET,           "ENETRESET"         },
      +  { ECONNABORTED,        "ECONNABORTED"      },
      +  { ECONNRESET,          "ECONNRESET"        },
      +  { ENOBUFS,             "ENOBUFS"           },
      +  { EISCONN,             "EISCONN"           },
      +  { ENOTCONN,            "ENOTCONN"          },
      +  { ESHUTDOWN,           "ESHUTDOWN"         },
      +  { ETOOMANYREFS,        "ETOOMANYREFS"      },
      +  { ETIMEDOUT,           "ETIMEDOUT"         },
      +  { ECONNREFUSED,        "ECONNREFUSED"      },
      +  { EHOSTDOWN,           "EHOSTDOWN"         },
      +  { EHOSTUNREACH,        "EHOSTUNREACH"      },
      +  { EALREADY,            "EALREADY"          },
      +  { EINPROGRESS,         "EINPROGRESS"       },
      +  { ESTALE,              "ESTALE"            },
      +  { EUCLEAN,             "EUCLEAN"           },
      +  { ENOTNAM,             "ENOTNAM"           },
      +  { ENAVAIL,             "ENAVAIL"           },
      +  { EISNAM,              "EISNAM"            },
      +  { EREMOTEIO,           "EREMOTEIO"         },
      +  { EDQUOT,              "EDQUOT"            },
      +  { ENOMEDIUM,           "ENOMEDIUM"         },
      +  { EMEDIUMTYPE,         "EMEDIUMTYPE"     }
      +};
      +
      +#endif /* CONFIG_LIBC_STRERROR_SHORT */
      +
      +#define NERRNO_STRS (sizeof(g_errnomap) / sizeof(struct errno_strmap_s))
      +
      +#endif /* CONFIG_LIBC_STRERROR */
      +
      +/************************************************************************
      + * Private Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Public Functions
      + ************************************************************************/
      +
      +/************************************************************************
      + * Name: strerror
      + ************************************************************************/
      +
      +FAR const char *strerror(int errnum)
      +{
      +#ifdef CONFIG_LIBC_STRERROR
      +  int ndxlow = 0;
      +  int ndxhi  = NERRNO_STRS - 1;
      +  int ndxmid;
      +
      +  do
      +    {
      +      ndxmid = (ndxlow + ndxhi) >> 1;
      +      if (errnum > g_errnomap[ndxmid].errnum)
      +        {
      +          ndxlow = ndxmid + 1;
      +        }
      +      else if (errnum < g_errnomap[ndxmid].errnum)
      +        {
      +          ndxhi = ndxmid - 1;
      +        }
      +      else
      +        {
      +          return g_errnomap[ndxmid].str;
      +        }
      +    }
      +  while (ndxlow <= ndxhi);
      +#endif
      +  return "Unknown error";
      +}
      diff --git a/nuttx/lib/string/lib_strlen.c b/nuttx/lib/string/lib_strlen.c
      new file mode 100644
      index 0000000000..8333058091
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strlen.c
      @@ -0,0 +1,55 @@
      +/****************************************************************************
      + * lib/string/lib_strlen.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRLEN
      +size_t strlen(const char *s)
      +{
      +  const char *sc;
      +  for (sc = s; *sc != '\0'; ++sc);
      +  return sc - s;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strncasecmp.c b/nuttx/lib/string/lib_strncasecmp.c
      new file mode 100644
      index 0000000000..be369cf0d8
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strncasecmp.c
      @@ -0,0 +1,70 @@
      +/****************************************************************************
      + * lib/string/lib_strncasecmp.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + *****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + *****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + *****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + *****************************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRNCASECMP
      +int strncasecmp(const char *cs, const char *ct, size_t nb)
      +{
      +  int result = 0;
      +  for (; nb > 0; nb--)
      +    {
      +      if ((result = (int)toupper(*cs) - (int)toupper(*ct)) != 0 || !*cs)
      +        {
      +          break;
      +        }
      +
      +      cs++;
      +      ct++;
      +    }
      +  return result;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strncat.c b/nuttx/lib/string/lib_strncat.c
      new file mode 100644
      index 0000000000..af893e0f9b
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strncat.c
      @@ -0,0 +1,62 @@
      +/************************************************************
      + * lib/string/lib_strncat.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************
      + * Global Functions
      + ************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRNCAT
      +char *strncat(char *dest, const char *src, size_t n)
      +{
      +  char *ret   = dest;
      +
      +  dest  += strlen(dest);
      +  for (; n > 0 && *src != '\0' ; n--)
      +    {
      +      *dest++ = *src++;
      +    }
      +  *dest = '\0';
      +
      +  return ret;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strncmp.c b/nuttx/lib/string/lib_strncmp.c
      new file mode 100644
      index 0000000000..ce22820249
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strncmp.c
      @@ -0,0 +1,65 @@
      +/****************************************************************************
      + * lib/lib_strncmp.c
      + *
      + *   Copyright (C) 2007-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.
      + *
      + *****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + *****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + *****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + *****************************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRNCMP
      +int strncmp(const char *cs, const char *ct, size_t nb)
      +{
      +  int result = 0;
      +  for (; nb > 0; nb--)
      +    {
      +      if ((result = (int)*cs - (int)*ct++) != 0 || !*cs++)
      +        {
      +          break;
      +        }
      +    }
      +  return result;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strncpy.c b/nuttx/lib/string/lib_strncpy.c
      new file mode 100644
      index 0000000000..149369d508
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strncpy.c
      @@ -0,0 +1,57 @@
      +/************************************************************
      + * lib/string/lib_strncpy.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ************************************************************/
      +
      +/************************************************************
      + * Included Files
      + ************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/************************************************************
      + * Global Functions
      + ************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRNCPY
      +char *strncpy(char *dest, const char *src, size_t n)
      +{
      +  char *ret = dest;     /* Value to be returned */
      +  char *end = dest + n; /* End of dest buffer + 1 byte */
      +
      +  while ((*dest++ = *src++) != '\0' && dest != end);
      +  return ret;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strndup.c b/nuttx/lib/string/lib_strndup.c
      new file mode 100644
      index 0000000000..ffaf892eaa
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strndup.c
      @@ -0,0 +1,93 @@
      +/************************************************************************
      + * lib/string//lib_strndup.c
      + *
      + *   Copyright (C) 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/************************************************************************
      + * Global Functions
      + ************************************************************************/
      +/************************************************************************
      + * Name: strndup
      + *
      + * Description:
      + *   The strndup() function is equivalent to the strdup() function,
      + *   duplicating the provided 's' in a new block of memory allocated as
      + *   if by using malloc(), with the exception being that strndup() copies
      + *   at most 'size' plus one bytes into the newly allocated memory,
      + *   terminating the new string with a NUL character. If the length of 's'
      + *   is larger than 'size', only 'size' bytes will be duplicated. If
      + *   'size' is larger than the length of 's', all bytes in s will be
      + *   copied into the new memory buffer, including the terminating NUL
      + *   character. The newly created string will always be properly
      + *   terminated.
      + *
      + ************************************************************************/
      +
      +FAR char *strndup(FAR const char *s, size_t size)
      +{
      +  FAR char *news = NULL;
      +  if (s)
      +    {
      +      /* Get the size of the new string = MIN(strlen(s), size) */
      +
      +      size_t allocsize = strlen(s);
      +      if (allocsize > size)
      +        {
      +          allocsize = size;
      +        }
      +
      +      /* Allocate the new string, adding 1 for the NUL terminator */
      +
      +      news = (FAR char*)lib_malloc(allocsize + 1);
      +      if (news)
      +        {
      +          /* Copy the string into the allocated memory and add a NUL
      +           * terminator in any case.
      +           */
      +
      +          memcpy(news, s, allocsize);
      +          news[allocsize] = '\0';
      +        }
      +    }
      +  return news;
      +}
      diff --git a/nuttx/lib/string/lib_strnlen.c b/nuttx/lib/string/lib_strnlen.c
      new file mode 100644
      index 0000000000..2b64fe9845
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strnlen.c
      @@ -0,0 +1,62 @@
      +/****************************************************************************
      + * lib/string/lib_strnlen.c
      + *
      + * This file is part of NuttX, contributed by Michael Hrabanek
      + *
      + *   Copyright (C) 2010 Gregory Nutt. All rights reserved.
      + *   Author: Michael Hrabanek
      + *
      + * Derives from the file lib/lib_strlen.c:
      + *
      + *   Copyright (C) 2007, 2008, 2010 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +#ifndef CONFIG_ARCH_STRNLEN
      +size_t strnlen(const char *s, size_t maxlen)
      +{
      +  const char *sc;
      +  for (sc = s; maxlen != 0 && *sc != '\0'; maxlen--, ++sc);
      +  return sc - s;
      +}
      +#endif
      diff --git a/nuttx/lib/string/lib_strpbrk.c b/nuttx/lib/string/lib_strpbrk.c
      new file mode 100644
      index 0000000000..02e2ea2c70
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strpbrk.c
      @@ -0,0 +1,85 @@
      +/****************************************************************************
      + * lib/string/lib_strpbrk.c
      + *
      + *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
      + *   Author: Gregory Nutt 
      + *
      + * Redistribution and use str 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 str binary form must reproduce the above copyright
      + *    notice, this list of conditions and the following disclaimer str
      + *    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 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +char *strpbrk(const char *str, const char *charset)
      +{
      +  /* Sanity checking */
      +
      +#ifdef CONFIG_DEBUG
      +  if (!str || !charset)
      +    {
      +      return NULL;
      +    }
      +#endif
      +    
      +  /* Check each character in the string */
      +
      +  while (*str)
      +    {
      +      /* Check if the character from the string matches any character in the charset */
      +
      +      if (strchr(charset, *str) != NULL)
      +        {
      +          /* Yes, then this position must be the first occurrence in string */
      +
      +          return (char*)str;
      +	}
      +
      +      /* This character from the strings matches none of those in the charset.
      +       * Try the next character from the string.
      +       */
      +
      +      str++;
      +    }
      +
      +  /* We have looked at every character in the string, and none of them match any of
      +   * the characters in charset.
      +   */
      +
      +  return NULL;
      +}
      +
      diff --git a/nuttx/lib/string/lib_strrchr.c b/nuttx/lib/string/lib_strrchr.c
      new file mode 100644
      index 0000000000..91243ce589
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strrchr.c
      @@ -0,0 +1,68 @@
      +/************************************************************************
      + * lib/string/lib_strrchr.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ************************************************************************/
      +
      +/************************************************************************
      + * Included Files
      + ************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/************************************************************************
      + * Global Functions
      + ************************************************************************/
      +
      +/* The strrchr() function returns a pointer to the last
      + * occurrence of the character c in the string s.
      + */
      +
      +char *strrchr(const char *s, int c)
      +{
      +  if (s)
      +    {
      +      const char *p = &s[strlen(s) - 1];
      +      for (; p >= s; p--)
      +        {
      +          if (*p == c)
      +            {
      +              return (char*)p;
      +            }
      +        }
      +    }
      +
      +  return NULL;
      +}
      +
      diff --git a/nuttx/lib/string/lib_strspn.c b/nuttx/lib/string/lib_strspn.c
      new file mode 100644
      index 0000000000..e7b5ea0a5b
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strspn.c
      @@ -0,0 +1,66 @@
      +/****************************************************************************
      + * lib/string/lib_strspn.c
      + *
      + *   Copyright (C) 2007, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Compilation Switches
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: strspn
      + *
      + * Description:
      + *  strspn() calculates the length of the initial segment of s which
      + *  consists entirely of characters in accept.
      + *
      + ****************************************************************************/
      +
      +size_t strspn(const char *s, const char *accept)
      +{
      +  size_t i;
      +  for (i = 0; s[i] && strchr(accept, s[i]) != NULL; i++);
      +  return i;
      +}
      diff --git a/nuttx/lib/string/lib_strstr.c b/nuttx/lib/string/lib_strstr.c
      new file mode 100644
      index 0000000000..b8c896fa2e
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strstr.c
      @@ -0,0 +1,104 @@
      +/****************************************************************************
      + * lib/string/lib_strstr.c
      + *
      + *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
      + *   Author: Gregory Nutt 
      + *
      + * Redistribution and use str 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 str binary form must reproduce the above copyright
      + *    notice, this list of conditions and the following disclaimer str
      + *    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 
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +char *strstr(const char *str, const char *substr)
      +{
      +  const char *candidate;  /* Candidate in str with matching start character */
      +  char         ch;        /* First character of the substring */
      +  int          len;       /* The length of the substring */
      +
      +  /* Special case the empty substring */
      +
      +  len = strlen(substr);
      +  ch  = *substr;
      +
      +  if (!ch)
      +    {
      +      /* We'll say that an empty substring matches at the beginning of
      +       * the string
      +       */
      +
      +      return (char*)str;
      +    }
      +
      +  /* Search for the substring */
      +
      +  candidate = str;
      +  for (;;)
      +    {
      +      /* strchr() will return a pointer to the next occurrence of the
      +       * character ch in the string
      +       */
      +
      +      candidate = strchr(candidate, ch);
      +      if (!candidate || strlen(candidate) < len)
      +        {
      +           /* First character of the substring does not appear in the string
      +            * or the remainder of the string is not long enough to contain the
      +            * substring.
      +            */
      +
      +           return NULL;
      +        }
      +
      +      /* Check if this is the beginning of a matching substring */
      +
      +      if (strncmp(candidate, substr, len) == 0)
      +        {
      +           return (char*)candidate;
      +        }
      +
      +      /* No, find the next candidate after this one */
      +
      +      candidate++;
      +    }
      +
      +  /* Won't get here, but some compilers might complain */
      +
      +  return NULL;
      +}
      +
      diff --git a/nuttx/lib/string/lib_strtod.c b/nuttx/lib/string/lib_strtod.c
      new file mode 100644
      index 0000000000..8fecd45713
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strtod.c
      @@ -0,0 +1,241 @@
      +/****************************************************************************
      + * lib/string/lib_strtod.c
      + * Convert string to double
      + *
      + *   Copyright (C) 2002 Michael Ringgaard. All rights reserved.
      + *   Copyright (C) 2006-2007 H. Peter Anvin.
      + *
      + * 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 of the project 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_HAVE_DOUBLE
      +
      +/****************************************************************************
      + * Pre-processor definitions
      + ****************************************************************************/
      +
      +/* These are predefined with GCC, but could be issues for other compilers. If
      + * not defined, an arbitrary big number is put in for now.  These should be
      + * added to nuttx/compiler for your compiler.
      + */
      +
      +#if !defined(__DBL_MIN_EXP__) || !defined(__DBL_MAX_EXP__)
      +#  ifdef CONFIG_CPP_HAVE_WARNING
      +#    warning "Size of exponent is unknown"
      +#  endif
      +#  undef  __DBL_MIN_EXP__
      +#  define __DBL_MIN_EXP__ (-1021)
      +#  undef  __DBL_MAX_EXP__
      +#  define __DBL_MAX_EXP__ (1024)
      +#endif
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +static inline int is_real(double x)
      +{
      +  const double_t infinite = 1.0/0.0;
      +  return (x < infinite) && (x >= -infinite);
      +}
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/***************************************************(************************
      + * Name: strtod
      + *
      + * Description:
      + *   Convert a string to a double value
      + *
      + ****************************************************************************/
      +
      +double_t strtod(const char *str, char **endptr)
      +{
      +  double_t number;
      +  int exponent;
      +  int negative;
      +  char *p = (char *) str;
      +  double p10;
      +  int n;
      +  int num_digits;
      +  int num_decimals;
      +  const double_t infinite = 1.0/0.0;
      +
      +  /* Skip leading whitespace */
      +
      +  while (isspace(*p))
      +    {
      +      p++;
      +    }
      +
      +  /* Handle optional sign */
      +
      +  negative = 0;
      +  switch (*p)
      +    {
      +    case '-':
      +      negative = 1; /* Fall through to increment position */
      +    case '+':
      +      p++;
      +    }
      +
      +  number       = 0.;
      +  exponent     = 0;
      +  num_digits   = 0;
      +  num_decimals = 0;
      +
      +  /* Process string of digits */
      +
      +  while (isdigit(*p))
      +    {
      +      number = number * 10. + (*p - '0');
      +      p++;
      +      num_digits++;
      +    }
      +
      +  /* Process decimal part */
      +
      +  if (*p == '.')
      +    {
      +      p++;
      +
      +      while (isdigit(*p))
      +      {
      +        number = number * 10. + (*p - '0');
      +        p++;
      +        num_digits++;
      +        num_decimals++;
      +      }
      +
      +      exponent -= num_decimals;
      +    }
      +
      +  if (num_digits == 0)
      +    {
      +      set_errno(ERANGE);
      +      return 0.0;
      +    }
      +
      +  /* Correct for sign */
      +
      +  if (negative)
      +    {
      +      number = -number;
      +    }
      +
      +  /* Process an exponent string */
      +
      +  if (*p == 'e' || *p == 'E')
      +    {
      +      /* Handle optional sign */
      +
      +      negative = 0;
      +      switch(*++p)
      +        {
      +        case '-':
      +          negative = 1;   /* Fall through to increment pos */
      +        case '+':
      +          p++;
      +        }
      +
      +      /* Process string of digits */
      +
      +      n = 0;
      +      while (isdigit(*p))
      +        {
      +          n = n * 10 + (*p - '0');
      +          p++;
      +        }
      +
      +      if (negative)
      +        {
      +          exponent -= n;
      +        }
      +      else
      +        {
      +          exponent += n;
      +        }
      +    }
      +
      +  if (exponent < __DBL_MIN_EXP__ ||
      +      exponent > __DBL_MAX_EXP__)
      +    {
      +      set_errno(ERANGE);
      +      return infinite;
      +    }
      +
      +  /* Scale the result */
      +
      +  p10 = 10.;
      +  n = exponent;
      +  if (n < 0) n = -n;
      +  while (n)
      +    {
      +      if (n & 1)
      +        {
      +          if (exponent < 0)
      +            {
      +              number /= p10;
      +            }
      +          else
      +            {
      +              number *= p10;
      +            }
      +        }
      +      n >>= 1;
      +      p10 *= p10;
      +    }
      +
      +  if (!is_real(number))
      +    {
      +      set_errno(ERANGE);
      +    }
      +
      +  if (endptr)
      +    {
      +      *endptr = p;
      +    }
      +
      +  return number;
      +}
      +
      +#endif /* CONFIG_HAVE_DOUBLE */
      +
      diff --git a/nuttx/lib/string/lib_strtok.c b/nuttx/lib/string/lib_strtok.c
      new file mode 100644
      index 0000000000..c409931359
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strtok.c
      @@ -0,0 +1,87 @@
      +/****************************************************************************
      + * lib/string/lib_strtok.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      +
      +static char *g_saveptr = NULL;
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: strtok
      + *
      + * Description:
      + *    The  strtok()  function  parses  a string into a
      + *    sequence of tokens.  On the first call to strtok() the
      + *    string to be parsed should be specified in 'str'.  In
      + *    each subsequent call that should parse the same string, 
      + *    'str' should be NULL.
      + *
      + *    The 'delim' argument specifies a set of characters that
      + *    delimit the tokens in the parsed string.  The caller
      + *    may specify different strings in delim in successive
      + *    calls that parse the same string.
      + *
      + *    Each call to strtok() returns a pointer to a null-
      + *    terminated string containing the next token. This
      + *    string  does not include the delimiting character.  If
      + *    no more tokens are found, strtok() returns NULL.
      + *
      + *    A sequence of two or more contiguous delimiter
      + *    characters in the parsed string is considered to be a
      + *    single delimiter. Delimiter characters at the start or
      + *    end of the string are ignored.  The tokens returned by
      + *    strtok() are always non-empty strings.
      + *
      + * Return
      + *    strtok() returns a pointer to the next token, or NULL
      + *    if there are no more tokens.
      + *
      + ****************************************************************************/
      +
      +char *strtok(char *str, const char *delim)
      +{
      +  return strtok_r(str, delim, &g_saveptr);
      +}
      diff --git a/nuttx/lib/string/lib_strtokr.c b/nuttx/lib/string/lib_strtokr.c
      new file mode 100644
      index 0000000000..1c571b6ae5
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strtokr.c
      @@ -0,0 +1,157 @@
      +/****************************************************************************
      + * lib/string/lib_strtokr.c
      + *
      + *   Copyright (C) 2007, 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: strtok_r
      + *
      + * Description:
      + *   The strtok_r() function is a reentrant version strtok().
      + *   Like strtok(), it  parses  a string into a sequence of
      + *   tokens.  On the first call to strtok() the string to be
      + *   parsed should be specified in 'str'.  In each subsequent
      + *   call that should parse the same string, 'str' should be
      + *   NULL.
      + *
      + *   The 'saveptr' argument is a pointer to a char *
      + *   variable  that  is  used internally by strtok_r() in
      + *   order to maintain context between successive calls
      + *   that parse the same string.
      + *
      + *   On the first call to strtok_r(), 'str' should point to the
      + *   string to be parsed, and the value of 'saveptr' is 
      + *   ignored.  In subsequent calls, 'str' should be NULL, and
      + *   saveptr should be unchanged since the previous call.
      + *
      + *   The 'delim' argument specifies a set of characters that
      + *   delimit the tokens in the parsed string.  The caller
      + *   may specify different strings in delim in successive
      + *   calls that parse the same string.
      + *
      + *   Each call to strtok_r() returns a pointer to a null-
      + *   terminated string containing the next token. This
      + *   string  does not include the delimiting character.  If
      + *   no more tokens are found, strtok_r() returns NULL.
      + *
      + *   A sequence of two or more contiguous delimiter
      + *   characters in the parsed string is considered to be a
      + *   single delimiter. Delimiter characters at the start or
      + *   end of the string are ignored.  The tokens returned by
      + *   strtok() are always non-empty strings.
      + *
      + * Return
      + *    strtok_r() returns a pointer to the next token, or NULL
      + *    if there are no more tokens.
      + *
      + ****************************************************************************/
      +
      +FAR char *strtok_r(FAR char *str, FAR const char *delim, FAR char **saveptr)
      +{
      +  char *pbegin;
      +  char *pend = NULL;
      +
      +  /* Decide if we are starting a new string or continuing from
      +   * the point we left off.
      +   */
      +
      +  if (str)
      +    {
      +      pbegin = str;
      +    }
      +  else if (saveptr && *saveptr)
      +    {
      +      pbegin = *saveptr;
      +    }
      +  else
      +    {
      +      return NULL;
      +    }
      +
      +  /* Find the beginning of the next token */
      +
      +  for (;
      +       *pbegin && strchr(delim, *pbegin) != NULL;
      +       pbegin++);
      +
      +  /* If we are at the end of the string with nothing
      +   * but delimiters found, then return NULL.
      +   */
      +
      +  if (!*pbegin)
      +    {
      +      return NULL;
      +    }
      +
      +  /* Find the end of the token */
      +
      +  for (pend = pbegin + 1;
      +       *pend && strchr(delim, *pend) == NULL;
      +       pend++);
      +
      +
      +  /* pend either points to the end of the string or to
      +   * the first delimiter after the string.
      +   */
      +
      +  if (*pend)
      +    {
      +      /* Turn the delimiter into a null terminator */
      +
      +      *pend++ = '\0';
      +    }
      +
      +  /* Save the pointer where we left off and return the
      +   * beginning of the token.
      +   */
      +
      +  if (saveptr)
      +    {
      +      *saveptr = pend;
      +    }
      +  return pbegin;
      +}
      diff --git a/nuttx/lib/string/lib_strtol.c b/nuttx/lib/string/lib_strtol.c
      new file mode 100644
      index 0000000000..c17d87e635
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strtol.c
      @@ -0,0 +1,103 @@
      +/****************************************************************************
      + * lib/string/lib_strtol.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: strtol
      + *
      + * Description:
      + *   The  strtol() function  converts  the initial part of the string in
      + *   nptr to a long integer value according to the given base, which must be
      + *   between 2 and 36 inclusive, or be the special value 0.
      + *
      + * Warning: does not check for integer overflow!
      + *
      + ****************************************************************************/
      + 
      +long strtol(const char *nptr, char **endptr, int base)
      +{
      +  unsigned long accum = 0;
      +  bool negate = false;
      +
      +  if (nptr)
      +    {
      +      /* Skip leading spaces */
      +
      +      lib_skipspace(&nptr);
      +
      +      /* Check for leading + or - */
      +
      +      if (*nptr == '-')
      +        {
      +          negate = true;
      +          nptr++;
      +        }
      +      else if (*nptr == '+')
      +        {
      +          nptr++;
      +        }
      +
      +      /* Get the unsigned value */
      +
      +      accum = strtoul(nptr, endptr, base);
      +
      +      /* Correct the sign of the result */
      +
      +      if (negate)
      +        {
      +          return -(long)accum;
      +        }
      +    }
      +  return (long)accum;
      +}
      +
      diff --git a/nuttx/lib/string/lib_strtoll.c b/nuttx/lib/string/lib_strtoll.c
      new file mode 100644
      index 0000000000..242e025c07
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strtoll.c
      @@ -0,0 +1,107 @@
      +/****************************************************************************
      + * lib/string/lib_strtoll.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +#ifdef CONFIG_HAVE_LONG_LONG
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: strtoll
      + *
      + * Description:
      + *   The  strtol() function  converts  the initial part of the string in
      + *   nptr to a long long integer value according to the given base, which
      + *   must be between 2 and 36 inclusive, or be the special value 0.
      + *
      + * Warning: does not check for integer overflow!
      + *
      + ****************************************************************************/
      + 
      +long long strtoll(const char *nptr, char **endptr, int base)
      +{
      +  unsigned long long accum = 0;
      +  bool negate = false;
      +
      +  if (nptr)
      +    {
      +      /* Skip leading spaces */
      +
      +      lib_skipspace(&nptr);
      +
      +      /* Check for leading + or - */
      +
      +      if (*nptr == '-')
      +        {
      +          negate = true;
      +          nptr++;
      +        }
      +      else if (*nptr == '+')
      +        {
      +          nptr++;
      +        }
      +
      +      /* Get the unsigned value */
      +
      +      accum = strtoull(nptr, endptr, base);
      +
      +      /* Correct the sign of the result */
      +
      +      if (negate)
      +        {
      +          return -(long long)accum;
      +        }
      +    }
      +  return (long long)accum;
      +}
      +
      +#endif
      +
      diff --git a/nuttx/lib/string/lib_strtoul.c b/nuttx/lib/string/lib_strtoul.c
      new file mode 100644
      index 0000000000..b0d2d090e6
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strtoul.c
      @@ -0,0 +1,98 @@
      +/****************************************************************************
      + * /lib/string/lib_strtoul.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: strtoul
      + *
      + * Description:
      + *   The  strtol() function  converts  the initial part of the string in
      + *   nptr to a long unsigned integer value according to the given base, which
      + *   must be between 2 and 36 inclusive, or be the special value 0.
      + *
      + * Warning: does not check for integer overflow!
      + *
      + ****************************************************************************/
      + 
      +unsigned long strtoul(const char *nptr, char **endptr, int base)
      +{
      +  unsigned long accum = 0;
      +  int value;
      +
      +  if (nptr)
      +    {
      +      /* Skip leading spaces */
      +
      +      lib_skipspace(&nptr);
      +
      +      /* Check for unspecified base */
      +
      +      base = lib_checkbase(base, &nptr);
      +
      +      /* Accumulate each "digit" */
      +
      +      while (lib_isbasedigit(*nptr, base, &value))
      +        {
      +            accum = accum*base + value;
      +            nptr++;
      +        }
      +
      +      /* Return the final pointer to the unused value */
      +
      +      if (endptr)
      +        {
      +          *endptr = (char *)nptr;
      +        }
      +    }
      +   return accum;
      +}
      +
      diff --git a/nuttx/lib/string/lib_strtoull.c b/nuttx/lib/string/lib_strtoull.c
      new file mode 100644
      index 0000000000..6567457c0e
      --- /dev/null
      +++ b/nuttx/lib/string/lib_strtoull.c
      @@ -0,0 +1,100 @@
      +/****************************************************************************
      + * /lib/string/lib_strtoull.c
      + *
      + *   Copyright (C) 2009, 2010 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +#include "lib_internal.h"
      +
      +#ifdef CONFIG_HAVE_LONG_LONG
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: strtoull
      + *
      + * Description:
      + *   The  strtol() function  converts  the initial part of the string in
      + *   nptr to a long unsigned integer value according to the given base, which
      + *   must be between 2 and 36 inclusive, or be the special value 0.
      + *
      + ****************************************************************************/
      + 
      +unsigned long long strtoull(const char *nptr, char **endptr, int base)
      +{
      +  unsigned long long accum = 0;
      +  int value;
      +
      +  if (nptr)
      +    {
      +      /* Skip leading spaces */
      +
      +      lib_skipspace(&nptr);
      +
      +      /* Check for unspecified base */
      +
      +      base = lib_checkbase(base, &nptr);
      +
      +      /* Accumulate each "digit" */
      +
      +      while (lib_isbasedigit(*nptr, base, &value))
      +        {
      +            accum = accum*base + value;
      +            nptr++;
      +        }
      +
      +      /* Return the final pointer to the unused value */
      +
      +      if (endptr)
      +        {
      +          *endptr = (char *)nptr;
      +        }
      +    }
      +   return accum;
      +}
      +#endif
      +
      diff --git a/nuttx/lib/string/lib_vikmemcpy.c b/nuttx/lib/string/lib_vikmemcpy.c
      new file mode 100644
      index 0000000000..b50942aaa1
      --- /dev/null
      +++ b/nuttx/lib/string/lib_vikmemcpy.c
      @@ -0,0 +1,348 @@
      +/****************************************************************************
      + * File: lib/string/lib_vikmemcpy.c
      + *
      + * This is version of the optimized memcpy by Daniel Vik, adapted to the
      + * NuttX environment.
      + *
      + *   Copyright (C) 1999-2010 Daniel Vik
      + *
      + * Adaptations include:
      + * - File name change
      + * - Use of types defined in stdint.h
      + * - Integration with the NuttX configuration system
      + * - Other cosmetic changes for consistency with NuttX coding standards
      + * 
      + * This software is provided 'as-is', without any express or implied
      + * warranty. In no event will the authors be held liable for any
      + * damages arising from the use of this software.
      + * Permission is granted to anyone to use this software for any
      + * purpose, including commercial applications, and to alter it and
      + * redistribute it freely, subject to the following restrictions:
      + * 
      + * 1. The origin of this software must not be misrepresented; you
      + *    must not claim that you wrote the original software. If you
      + *    use this software in a product, an acknowledgment in the
      + *    use this software in a product, an acknowledgment in the
      + *    product documentation would be appreciated but is not
      + *    required.
      + * 
      + * 2. Altered source versions must be plainly marked as such, and
      + *    must not be misrepresented as being the original software.
      + * 
      + * 3. This notice may not be removed or altered from any source
      + *    distribution.
      + * 
      + * Description: Implementation of the standard library function memcpy.
      + *              This implementation of memcpy() is ANSI-C89 compatible.
      + *
      + * The following configuration options can be set:
      + *
      + *   CONFIG_ENDIAN_BIG
      + *     Uses processor with big endian addressing. Default is little endian.
      + *
      + *   CONFIG_MEMCPY_PRE_INC_PTRS
      + *     Use pre increment of pointers. Default is post increment of pointers.
      + *
      + *   CONFIG_MEMCPY_INDEXED_COPY
      + *     Copying data using array indexing. Using this option, disables the
      + *     CONFIG_MEMCPY_PRE_INC_PTRS option.
      + *
      + *   CONFIG_MEMCPY_64BIT - Compiles memcpy for 64 bit architectures
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Configuration definitions.
      + ****************************************************************************/
      +
      +#define CONFIG_MEMCPY_INDEXED_COPY
      +
      +/********************************************************************
      + * Included Files
      + *******************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/********************************************************************
      + * Pre-processor Definitions
      + *******************************************************************/
      +
      +/* Can't support CONFIG_MEMCPY_64BIT if the platform does not have 64-bit
      + * integer types.
      + */
      +
      +#ifndef CONFIG_HAVE_LONG_LONG
      +#  undef CONFIG_MEMCPY_64BIT
      +#endif
      +
      +/* Remove definitions when CONFIG_MEMCPY_INDEXED_COPY is defined */
      +
      +#if defined (CONFIG_MEMCPY_INDEXED_COPY)
      +#  if defined (CONFIG_MEMCPY_PRE_INC_PTRS)
      +#    undef CONFIG_MEMCPY_PRE_INC_PTRS
      +#  endif /* CONFIG_MEMCPY_PRE_INC_PTRS */
      +#endif /* CONFIG_MEMCPY_INDEXED_COPY */
      +
      +/* Definitions for pre and post increment of pointers */
      +
      +#if defined (CONFIG_MEMCPY_PRE_INC_PTRS)
      +
      +#  define START_VAL(x)            (x)--
      +#  define INC_VAL(x)              *++(x)
      +#  define CAST_TO_U8(p, o)        ((uint8_t*)p + o + TYPE_WIDTH)
      +#  define WHILE_DEST_BREAK        (TYPE_WIDTH - 1)
      +#  define PRE_LOOP_ADJUST         - (TYPE_WIDTH - 1)
      +#  define PRE_SWITCH_ADJUST       + 1
      +
      +#else /* CONFIG_MEMCPY_PRE_INC_PTRS */
      +
      +#  define START_VAL(x)
      +#  define INC_VAL(x)              *(x)++
      +#  define CAST_TO_U8(p, o)        ((uint8_t*)p + o)
      +#  define WHILE_DEST_BREAK        0
      +#  define PRE_LOOP_ADJUST
      +#  define PRE_SWITCH_ADJUST
      +
      +#endif /* CONFIG_MEMCPY_PRE_INC_PTRS */
      +
      +/* Definitions for endian-ness */
      +
      +#ifdef CONFIG_ENDIAN_BIG
      +
      +#  define SHL <<
      +#  define SHR >>
      +
      +#else /* CONFIG_ENDIAN_BIG */
      +
      +#  define SHL >>
      +#  define SHR <<
      +
      +#endif /* CONFIG_ENDIAN_BIG */
      +
      +/********************************************************************
      + * Macros for copying words of  different alignment.
      + * Uses incremening pointers.
      + *******************************************************************/
      +
      +#define CP_INCR()                         \
      +{                                         \
      +  INC_VAL(dstN) = INC_VAL(srcN);          \
      +}
      +
      +#define CP_INCR_SH(shl, shr)              \
      +{                                         \
      +  dstWord       = srcWord SHL shl;        \
      +  srcWord       = INC_VAL(srcN);          \
      +  dstWord      |= srcWord SHR shr;        \
      +  INC_VAL(dstN) = dstWord;                \
      +}
      +
      +/********************************************************************
      + * Macros for copying words of  different alignment.
      + * Uses array indexes.
      + *******************************************************************/
      +
      +#define CP_INDEX(idx)                     \
      +{                                         \
      +  dstN[idx] = srcN[idx];                  \
      +}
      +
      +#define CP_INDEX_SH(x, shl, shr)          \
      +{                                         \
      +  dstWord   = srcWord SHL shl;            \
      +  srcWord   = srcN[x];                    \
      +  dstWord  |= srcWord SHR shr;            \
      +  dstN[x]   = dstWord;                    \
      +}
      +
      +/********************************************************************
      + * Macros for copying words of different alignment.
      + * Uses incremening pointers or array indexes depending on
      + * configuration.
      + *******************************************************************/
      +
      +#if defined (CONFIG_MEMCPY_INDEXED_COPY)
      +
      +#  define CP(idx)               CP_INDEX(idx)
      +#  define CP_SH(idx, shl, shr)  CP_INDEX_SH(idx, shl, shr)
      +
      +#  define INC_INDEX(p, o)       ((p) += (o))
      +
      +#else /* CONFIG_MEMCPY_INDEXED_COPY */
      +
      +#  define CP(idx)               CP_INCR()
      +#  define CP_SH(idx, shl, shr)  CP_INCR_SH(shl, shr)
      +
      +#  define INC_INDEX(p, o)
      +
      +#endif /* CONFIG_MEMCPY_INDEXED_COPY */
      +
      +#define COPY_REMAINING(count)                                     \
      +{                                                                 \
      +  START_VAL(dst8);                                                \
      +  START_VAL(src8);                                                \
      +                                                                  \
      +  switch (count)                                                  \
      +    {                                                             \
      +    case 7: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 6: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 5: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 4: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 3: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 2: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 1: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 0:                                                       \
      +    default: break;                                               \
      +    }                                                             \
      +}
      +
      +#define COPY_NO_SHIFT()                                           \
      +{                                                                 \
      +  UIntN* dstN = (UIntN*)(dst8 PRE_LOOP_ADJUST);                   \
      +  UIntN* srcN = (UIntN*)(src8 PRE_LOOP_ADJUST);                   \
      +  size_t length = count / TYPE_WIDTH;                             \
      +                                                                  \
      +  while (length & 7)                                              \
      +    {                                                             \
      +      CP_INCR();                                                  \
      +      length--;                                                   \
      +    }                                                             \
      +                                                                  \
      +  length /= 8;                                                    \
      +                                                                  \
      +  while (length--)                                                \
      +    {                                                             \
      +      CP(0);                                                      \
      +      CP(1);                                                      \
      +      CP(2);                                                      \
      +      CP(3);                                                      \
      +      CP(4);                                                      \
      +      CP(5);                                                      \
      +      CP(6);                                                      \
      +      CP(7);                                                      \
      +                                                                  \
      +      INC_INDEX(dstN, 8);                                         \
      +      INC_INDEX(srcN, 8);                                         \
      +    }                                                             \
      +                                                                  \
      +  src8 = CAST_TO_U8(srcN, 0);                                     \
      +  dst8 = CAST_TO_U8(dstN, 0);                                     \
      +                                                                  \
      +  COPY_REMAINING(count & (TYPE_WIDTH - 1));                       \
      +                                                                  \
      +  return dest;                                                    \
      +}
      +
      +#define COPY_SHIFT(shift)                                         \
      +{                                                                 \
      +  UIntN* dstN  = (UIntN*)((((UIntN)dst8) PRE_LOOP_ADJUST) &       \
      +                           ~(TYPE_WIDTH - 1));                    \
      +  UIntN* srcN  = (UIntN*)((((UIntN)src8) PRE_LOOP_ADJUST) &       \
      +                           ~(TYPE_WIDTH - 1));                    \
      +  size_t length  = count / TYPE_WIDTH;                            \
      +  UIntN srcWord = INC_VAL(srcN);                                  \
      +  UIntN dstWord;                                                  \
      +                                                                  \
      +  while (length & 7)                                              \
      +    {                                                             \
      +      CP_INCR_SH(8 * shift, 8 * (TYPE_WIDTH - shift));            \
      +      length--;                                                   \
      +    }                                                             \
      +                                                                  \
      +  length /= 8;                                                    \
      +                                                                  \
      +  while (length--)                                                \
      +    {                                                             \
      +      CP_SH(0, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(1, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(2, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(3, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(4, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(5, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(6, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(7, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +                                                                  \
      +      INC_INDEX(dstN, 8);                                         \
      +      INC_INDEX(srcN, 8);                                         \
      +    }                                                             \
      +                                                                  \
      +  src8 = CAST_TO_U8(srcN, (shift - TYPE_WIDTH));                  \
      +  dst8 = CAST_TO_U8(dstN, 0);                                     \
      +                                                                  \
      +  COPY_REMAINING(count & (TYPE_WIDTH - 1));                       \
      +                                                                  \
      +  return dest;                                                    \
      +}
      +
      +/********************************************************************
      + * Type Definitions
      + *******************************************************************/
      +
      +#ifdef CONFIG_MEMCPY_64BIT
      +typedef uint64_t            UIntN;
      +#  define TYPE_WIDTH        8L
      +#else
      +typedef uint32_t            UIntN;
      +#  define TYPE_WIDTH        4L
      +#endif
      +
      +/********************************************************************
      + * Public Functions
      + *******************************************************************/
      +/********************************************************************
      + * Name: memcpy
      + *
      + * Description:
      + *   Copies count bytes from src to dest. No overlap check is performed.
      + *
      + * Input Parameters:
      + *   dest        - pointer to destination buffer
      + *   src         - pointer to source buffer
      + *   count       - number of bytes to copy
      + *
      + * Returned Value:
      + *   A pointer to destination buffer
      + *
      + *******************************************************************/
      +
      +void *memcpy(void *dest, const void *src, size_t count) 
      +{
      +  uint8_t *dst8 = (uint8_t*)dest;
      +  uint8_t *src8 = (uint8_t*)src;
      +
      +  if (count < 8)
      +    {
      +      COPY_REMAINING(count);
      +      return dest;
      +    }
      +
      +  START_VAL(dst8);
      +  START_VAL(src8);
      +
      +  while (((UIntN)dst8 & (TYPE_WIDTH - 1)) != WHILE_DEST_BREAK)
      +    {
      +      INC_VAL(dst8) = INC_VAL(src8);
      +      count--;
      +    }
      +
      +  switch ((((UIntN)src8) PRE_SWITCH_ADJUST) & (TYPE_WIDTH - 1))
      +    {
      +    case 0: COPY_NO_SHIFT(); break;
      +    case 1: COPY_SHIFT(1);   break;
      +    case 2: COPY_SHIFT(2);   break;
      +    case 3: COPY_SHIFT(3);   break;
      +#if TYPE_WIDTH > 4
      +    case 4: COPY_SHIFT(4);   break;
      +    case 5: COPY_SHIFT(5);   break;
      +    case 6: COPY_SHIFT(6);   break;
      +    case 7: COPY_SHIFT(7);   break;
      +#endif
      +    }
      +
      +  return dest;
      +}
      diff --git a/nuttx/lib/termios/Make.defs b/nuttx/lib/termios/Make.defs
      new file mode 100644
      index 0000000000..a6bb77f835
      --- /dev/null
      +++ b/nuttx/lib/termios/Make.defs
      @@ -0,0 +1,54 @@
      +############################################################################
      +# lib/misc/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# termios.h support requires file descriptors and that CONFIG_SERIAL_TERMIOS
      +# is defined
      +
      +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
      +ifeq ($(CONFIG_SERIAL_TERMIOS),y)
      +
      +# Add the termios C files to the build
      +
      +CSRCS += lib_cfgetspeed.c lib_cfsetspeed.c lib_tcflush.c
      +CSRCS += lib_tcgetattr.c lib_tcsetattr.c
      +
      +# Add the termios directory to the build
      +
      +DEPPATH += --dep-path termios
      +VPATH += termios
      +
      +endif
      +endif
      +
      diff --git a/nuttx/lib/termios/lib_cfgetspeed.c b/nuttx/lib/termios/lib_cfgetspeed.c
      new file mode 100644
      index 0000000000..d7f0dc4736
      --- /dev/null
      +++ b/nuttx/lib/termios/lib_cfgetspeed.c
      @@ -0,0 +1,93 @@
      +/****************************************************************************
      + * lib/termios/lib_cfgetspeed.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: cfgetspeed
      + *
      + * Descripton:
      + *   The cfgetspeed() function is a non-POSIX function will extract the baud
      + *   from the termios structure to which the termiosp argument points.
      + *
      + *   This function will return exactly the value in the termios data
      + *   structure, without interpretation.
      + *
      + *   NOTE 1: NuttX does not control input/output baud independently.  Both
      + *   must be the same.  The POSIX standard interfaces, cfisetispeed() and
      + *   cfisetospeed() are defined to be cfgetspeed() in termios.h.
      + *   NOTE 2.  In Nuttx, the speed_t is defined to be uint32_t and the baud
      + *   encodings of termios.h are the actual baud values themselves.  Therefore,
      + *   any baud value may be returned here... not just those enumerated in
      + *   termios.h
      + *
      + * Input Parameters:
      + *   termiosp - The termiosp argument is a pointer to a termios structure.
      + *
      + * Returned Value:
      + *   Encoded baud value from the termios structure. 
      + *
      + ****************************************************************************/
      +
      +speed_t cfgetspeed(FAR const struct termios *termiosp)
      +{
      +  DEBUGASSERT(termiosp);
      +  return termiosp->c_speed;
      +}
      diff --git a/nuttx/lib/termios/lib_cfsetspeed.c b/nuttx/lib/termios/lib_cfsetspeed.c
      new file mode 100644
      index 0000000000..714562ff50
      --- /dev/null
      +++ b/nuttx/lib/termios/lib_cfsetspeed.c
      @@ -0,0 +1,116 @@
      +/****************************************************************************
      + * lib/termios/lib_cfsetspeed.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: cfsetspeed
      + *
      + * Descripton:
      + *   The cfsetspeed() function is a non-POSIX function that sets the baud
      + *   stored in the structure pointed to by termiosp to speed.
      + *
      + *   There is no effect on the baud set in the hardware until a subsequent
      + *   successful call to tcsetattr() on the same termios structure. 
      + *
      + *   NOTE 1: NuttX does not control input/output baud independently.  Both
      + *   must be the same.  The POSIX standard interfaces, cfisetispeed() and
      + *   cfisetospeed() are defined to be cfsetspeed() in termios.h.
      + *
      + *   NOTE 3:  A consequence of NOTE 1 is that you should never attempt to
      + *   set the input and output baud to different values.
      + *
      + *   Also, the following POSIX requirement cannot be supported: "If the input
      + *   baud rate stored in the termios structure pointed to by termios_p is 0,
      + *   the input baud rate given to the hardware will be the same as the output
      + *   baud rate stored in the termios structure."
      + *
      + *   NOTE 2.  In Nuttx, the speed_t is defined to be uint32_t and the baud
      + *   encodings of termios.h are the actual baud values themselves.  Therefore,
      + *   any baud value can be provided as the speed argument here.  However, if
      + *   you do so, your code will *NOT* be portable to other environments where
      + *   speed_t is smaller and where the termios.h baud values are encoded! To
      + *   avoid portability issues, use the baud definitions in termios.h!
      + *
      + *   Linux, for example, would require this (also non-portable) sequence:
      + *
      + *     cfsetispeed(termiosp, BOTHER);
      + *     termiosp->c_ispeed = baud;
      + *
      + *     cfsetospeed(termiosp, BOTHER);
      + *     termiosp->c_ospeed = baud;
      + *
      + * Input Parameters:
      + *   termiosp - The termiosp argument is a pointer to a termios structure.
      + *   speed - The new input speed
      + *
      + * Returned Value:
      + *   Baud is not checked... OK is always returned (this is non-standard
      + *   behavior). 
      + *
      + ****************************************************************************/
      +
      +int cfsetspeed(FAR struct termios *termiosp, speed_t speed)
      +{
      +  DEBUGASSERT(termiosp);
      +  termiosp->c_speed = speed;
      +  return OK;
      +}
      diff --git a/nuttx/lib/termios/lib_tcflush.c b/nuttx/lib/termios/lib_tcflush.c
      new file mode 100644
      index 0000000000..338524bdda
      --- /dev/null
      +++ b/nuttx/lib/termios/lib_tcflush.c
      @@ -0,0 +1,88 @@
      +/****************************************************************************
      + * lib/termios/lib_tcflush.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: tcflush
      + *
      + * Descripton:
      + *   Function for flushing a terminal/serial device
      + *
      + * Input Parameters:
      + *   fd  - The 'fd' argument is an open file descriptor associated with a terminal.
      + *   cmd - The TCFLSH ioctl argument.
      + *
      + * Returned Value:
      + *   Upon successful completion, 0 is returned. Otherwise, -1 is returned and
      + *   errno is set to indicate the error.
      + *
      + ****************************************************************************/
      +
      +int tcflush(int fd, int cmd)
      +{
      +  return ioctl(fd, TCFLSH, (unsigned long)cmd);
      +}
      diff --git a/nuttx/lib/termios/lib_tcgetattr.c b/nuttx/lib/termios/lib_tcgetattr.c
      new file mode 100644
      index 0000000000..500871d9ff
      --- /dev/null
      +++ b/nuttx/lib/termios/lib_tcgetattr.c
      @@ -0,0 +1,93 @@
      +/****************************************************************************
      + * lib/termios/lib_tcgetattr.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: tcgetattr
      + *
      + * Descripton:
      + *   The tcgetattr() function gets the parameters associated with the
      + *   terminal referred to by 'fd' and stores them in the termios structure
      + *   referenced by 'termiosp'.
      + *
      + * Input Parameters:
      + *   fd - The 'fd' argument is an open file descriptor associated with a terminal.
      + *   termiosp - The termiosp argument is a pointer to a termios structure.
      + *
      + * Returned Value:
      + *   Upon successful completion, 0 is returned. Otherwise, -1 is returned and
      + *   errno is set to indicate the error.  The following errors may be reported:
      + *
      + *   - EBADF: The 'fd' argument is not a valid file descriptor. 
      + *   - ENOTTY: The file associated with 'fd' is not a terminal. 
      + *
      + ****************************************************************************/
      +
      +int tcgetattr(int fd, FAR struct termios *termiosp)
      +{
      +  return ioctl(fd, TCGETS, (unsigned long)termiosp);
      +}
      diff --git a/nuttx/lib/termios/lib_tcsetattr.c b/nuttx/lib/termios/lib_tcsetattr.c
      new file mode 100644
      index 0000000000..791b519c85
      --- /dev/null
      +++ b/nuttx/lib/termios/lib_tcsetattr.c
      @@ -0,0 +1,122 @@
      +/****************************************************************************
      + * lib/termios/lib_tcsetattr.c
      + *
      + *   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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: tcsetattr
      + *
      + * Descripton:
      + *   The tcsetattr() function sets the parameters associated with the
      + *   terminal referred to by the open file descriptor 'fd' from the termios
      + *   structure referenced by 'termiop' as follows:
      + *
      + *   If 'options' is TCSANOW, the change will occur immediately.
      + *
      + *   If 'options' is TCSADRAIN, the change will occur after all output
      + *   written to 'fd' is transmitted. This function should be used when changing
      + *   parameters that affect output.
      + *
      + *   If 'options' is TCSAFLUSH, the change will occur after all
      + *   output written to 'fd' is transmitted, and all input so far received but
      + *   not read will be discarded before the change is made.
      + *
      + *   The tcsetattr() function will return successfully if it was able to
      + *   perform any of the requested actions, even if some of the requested
      + *   actions could not be performed. It will set all the attributes that
      + *   implementation supports as requested and leave all the attributes not
      + *   supported by the implementation unchanged. If no part of the request
      + *   can be honoured, it will return -1 and set errno to EINVAL.
      + *
      + *   The effect of tcsetattr() is undefined if the value of the termios
      + *   structure pointed to by 'termiop' was not derived from the result of
      + *   a call to tcgetattr() on 'fd'; an application should modify only fields
      + *   and flags defined by this specification between the call to tcgetattr()
      + *   and tcsetattr(), leaving all other fields and flags unmodified.
      + *
      + * Returned Value:
      + *
      + *   Upon successful completion, 0 is returned. Otherwise, -1 is returned
      + *   and errno is set to indicate the error.  The following errors may be
      + *   reported:
      + *
      + *   - EBADF: The 'fd' argument is not a valid file descriptor. 
      + *   - EINTR:  A signal interrupted tcsetattr(). 
      + *   - EINVAL: The 'options' argument is not a supported value, or
      + *     an attempt was made to change an attribute represented in the
      + *     termios structure to an unsupported value. 
      + *   - ENOTTY: The file associated with 'fd' is not a terminal. 
      + *
      + ****************************************************************************/
      +
      +int tcsetattr(int fd, int options, FAR const struct termios *termiosp)
      +{
      +  if (options == TCSANOW)
      +    {
      +      return ioctl(fd, TCSETS, (unsigned long)termiosp);
      +    }
      +  return -ENOSYS;
      +}
      diff --git a/nuttx/lib/time/Make.defs b/nuttx/lib/time/Make.defs
      new file mode 100644
      index 0000000000..ab74142291
      --- /dev/null
      +++ b/nuttx/lib/time/Make.defs
      @@ -0,0 +1,44 @@
      +############################################################################
      +# lib/time/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the time C files to the build
      +
      +CSRCS += lib_mktime.c lib_gmtime.c lib_gmtimer.c lib_strftime.c \
      +		  lib_calendar2utc.c lib_daysbeforemonth.c lib_isleapyear.c lib_time.c
      +
      +# Add the time directory to the build
      +
      +DEPPATH += --dep-path time
      +VPATH += :time
      diff --git a/nuttx/lib/time/lib_calendar2utc.c b/nuttx/lib/time/lib_calendar2utc.c
      new file mode 100644
      index 0000000000..e80c292fc6
      --- /dev/null
      +++ b/nuttx/lib/time/lib_calendar2utc.c
      @@ -0,0 +1,209 @@
      +/****************************************************************************
      + * lib/time/lib_calendar2utc.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  clock_gregorian2utc, clock_julian2utc
      + *
      + * Description:
      + *    UTC conversion routines.  These conversions are based
      + *    on algorithms from p. 604 of Seidelman, P. K. 1992.
      + *    Explanatory Supplement to the Astronomical Almanac.
      + *    University Science Books, Mill Valley. 
      + *
      + ****************************************************************************/
      +
      +#ifdef CONFIG_GREGORIAN_TIME
      +static time_t clock_gregorian2utc(int year, int month, int day)
      +{
      +  int temp;
      +
      +  /* temp = (month - 14)/12; */
      +
      +  temp = (month <= 2 ? -1:0);
      +
      +  return (1461*(year + 4800 + temp))/4
      +    + (367*(month - 2 - 12*temp))/12
      +    - (3*((year + 4900 + temp)/100))/4 + day - 32075;
      +}
      +
      +#ifdef CONFIG_JULIAN_TIME
      +static time_t clock_julian2utc(int year, int month, int day)
      +{
      +  return 367*year
      +    - (7*(year + 5001 + (month-9)/7))/4
      +    + (275*month)/9
      +    + day + 1729777;
      +}
      +#endif /* CONFIG_JULIAN_TIME */
      +#endif /* CONFIG_GREGORIAN_TIME */
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  clock_calendar2utc
      + *
      + * Description:
      + *    Calendar/UTC conversion based on algorithms from p. 604
      + *    of Seidelman, P. K. 1992.  Explanatory Supplement to
      + *    the Astronomical Almanac.  University Science Books,
      + *    Mill Valley. 
      + *
      + ****************************************************************************/
      +
      +#ifdef CONFIG_GREGORIAN_TIME
      +time_t clock_calendar2utc(int year, int month, int day)
      +{
      +  int dyear;
      +#ifdef CONFIG_JULIAN_TIME
      +  bool isgreg;
      +#endif /* CONFIG_JULIAN_TIME */
      +
      +  /* Correct year & month ranges.  Shift month into range 1-12 */
      +
      +  dyear = (month-1) / 12;	
      +  month -= 12 * dyear;
      +  year += dyear;
      +
      +  if (month < 1)
      +    {
      +      month += 12;
      +      year -= 1;
      +    }
      +
      +#ifdef CONFIG_JULIAN_TIME
      +  /* Determine which calendar to use */
      +
      +  if (year > GREG_YEAR)
      +    {
      +      isgreg = true;
      +    }
      +  else if (year < GREG_YEAR)
      +    {
      +      isgreg = false;
      +    }
      +  else if (month > GREG_MONTH)
      +    {
      +      isgreg = true;
      +    }
      +  else if (month < GREG_MONTH)
      +    {
      +      isgreg = false;
      +    }
      +  else
      +    {
      +      isgreg = (day >= GREG_DAY);
      +    }
      +
      +  /* Calculate and return date */
      +
      +  if (isgreg)
      +    {
      +      return clock_gregorian2utc(year, month, day) - JD_OF_EPOCH;
      +    }
      +  else
      +    {
      +      return clock_julian2utc (year, month, day) - JD_OF_EPOCH;
      +    }
      +
      +#else /* CONFIG_JULIAN_TIME */
      +
      +  return clock_gregorian2utc(year, month, day) - JD_OF_EPOCH;
      +
      +#endif /* CONFIG_JULIAN_TIME */
      +}
      +#else
      +
      +/* A highly simplified version that only handles days in the time
      + * since Jan 1, 1970.
      + */
      +
      +time_t clock_calendar2utc(int year, int month, int day)
      +{
      +  struct tm t;
      +
      +  /* mktime can (kind of) do this */
      +
      +  t.tm_year = year;
      +  t.tm_mon  = month;
      +  t.tm_mday = day;
      +  t.tm_hour = 0;
      +  t.tm_min  = 0;
      +  t.tm_sec  = 0;
      +  return mktime(&t);
      +}
      +#endif /* CONFIG_GREGORIAN_TIME */
      +
      diff --git a/nuttx/lib/time/lib_daysbeforemonth.c b/nuttx/lib/time/lib_daysbeforemonth.c
      new file mode 100644
      index 0000000000..8000b0e7a9
      --- /dev/null
      +++ b/nuttx/lib/time/lib_daysbeforemonth.c
      @@ -0,0 +1,102 @@
      +/****************************************************************************
      + * lib/time/lib_daysbeforemonth.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +uint16_t g_daysbeforemonth[13] =
      +{
      +  0, 31, 59, 90, 120, 151, 181, 212, 243, 273, 304, 334, 365
      +};
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  clock_daysbeforemonth
      + *
      + * Description:
      + *    Get the number of days that occurred before the beginning of the month.
      + *
      + ****************************************************************************/
      +
      +int clock_daysbeforemonth(int month, bool leapyear)
      +{
      +  int retval = g_daysbeforemonth[month];
      +  if (month >= 2 && leapyear)
      +    {
      +      retval++;
      +    }
      +  return retval;
      +}
      +
      +
      diff --git a/nuttx/lib/time/lib_gmtime.c b/nuttx/lib/time/lib_gmtime.c
      new file mode 100644
      index 0000000000..99afeded9e
      --- /dev/null
      +++ b/nuttx/lib/time/lib_gmtime.c
      @@ -0,0 +1,93 @@
      +/****************************************************************************
      + * lib/time/lib_gmtime.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Public Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Private Variables
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  gmtime
      + *
      + * Description:
      + *  Similar to gmtime_r, but not thread-safe
      + *
      + ****************************************************************************/
      +
      +struct tm *gmtime(const time_t *timer)
      +{
      +  static struct tm tm;
      +  return gmtime_r(timer, &tm);
      +}
      +
      diff --git a/nuttx/lib/time/lib_gmtimer.c b/nuttx/lib/time/lib_gmtimer.c
      new file mode 100644
      index 0000000000..ba1c9724f1
      --- /dev/null
      +++ b/nuttx/lib/time/lib_gmtimer.c
      @@ -0,0 +1,355 @@
      +/****************************************************************************
      + * lib/time/lib_gmtimer.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +#define SEC_PER_MIN  ((time_t)60)
      +#define SEC_PER_HOUR ((time_t)60 * SEC_PER_MIN)
      +#define SEC_PER_DAY  ((time_t)24 * SEC_PER_HOUR)
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/* Calendar/UTC conversion routines */
      +
      +static void   clock_utc2calendar(time_t utc, int *year, int *month, int *day);
      +#ifdef CONFIG_GREGORIAN_TIME
      +static void   clock_utc2gregorian (time_t jdn, int *year, int *month, int *day);
      +
      +#ifdef CONFIG_JULIAN_TIME
      +static void   clock_utc2julian(time_t jdn, int *year, int *month, int *day);
      +#endif /* CONFIG_JULIAN_TIME */
      +#endif /* CONFIG_GREGORIAN_TIME */
      +
      +/**************************************************************************
      + * Public Constant Data
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/**************************************************************************
      + * Private Variables
      + **************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  clock_calendar2utc, clock_gregorian2utc,
      + *            and clock_julian2utc
      + *
      + * Description:
      + *    Calendar to UTC conversion routines.  These conversions
      + *    are based on algorithms from p. 604 of Seidelman, P. K.
      + *    1992.  Explanatory Supplement to the Astronomical
      + *    Almanac.  University Science Books, Mill Valley. 
      + *
      + ****************************************************************************/
      +
      +#ifdef CONFIG_GREGORIAN_TIME
      +static void clock_utc2calendar(time_t utc, int *year, int *month, int *day)
      +{
      +#ifdef CONFIG_JULIAN_TIME
      +
      +  if (utc >= GREG_DUTC)
      +    {
      +      clock_utc2gregorian(utc + JD_OF_EPOCH, year, month, day);
      +    }
      +  else
      +    {
      +      clock_utc2julian (utc + JD_OF_EPOCH, year, month, day);
      +    }
      +
      +#else /* CONFIG_JULIAN_TIME */
      +
      +  clock_utc2gregorian(utc + JD_OF_EPOCH, year, month, day);
      +
      +#endif /* CONFIG_JULIAN_TIME */
      +}
      +
      +static void clock_utc2gregorian(time_t jd, int *year, int *month, int *day)
      +{
      +  long	l, n, i, j, d, m, y;
      +
      +  l = jd + 68569;
      +  n = (4*l) / 146097;
      +  l = l - (146097*n + 3)/4;
      +  i = (4000*(l+1))/1461001;
      +  l = l - (1461*i)/4 + 31;
      +  j = (80*l)/2447;
      +  d = l - (2447*j)/80;
      +  l = j/11;
      +  m = j + 2 - 12*l;
      +  y = 100*(n-49) + i + l;
      +
      +  *year  = y;
      +  *month = m;
      +  *day   = d;
      +}
      +
      +#ifdef CONFIG_JULIAN_TIME
      +
      +static void clock_utc2julian(time_t jd, int *year, int *month, int *day)
      +{
      +  long	j, k, l, n, d, i, m, y;
      +
      +  j = jd + 1402;
      +  k = (j-1)/1461;
      +  l = j - 1461*k;
      +  n = (l-1)/365 - l/1461;
      +  i = l - 365*n + 30;
      +  j = (80*i)/2447;
      +  d = i - (2447*j)/80;
      +  i = j/11;
      +  m = j + 2 - 12*i;
      +  y = 4*k + n + i - 4716;
      +
      +  *year  = y;
      +  *month = m;
      +  *day   = d;
      +}
      +
      +#endif /* CONFIG_JULIAN_TIME */
      +#else/* CONFIG_GREGORIAN_TIME */
      +
      +/* Only handles dates since Jan 1, 1970 */
      +
      +static void clock_utc2calendar(time_t days, int *year, int *month, int *day)
      +{
      +  int  value;
      +  int  min;
      +  int  max;
      +  int  tmp;
      +  bool leapyear;
      +
      +  /* There is one leap year every four years, so we can get close with the
      +   * following:
      +   */
      +
      +  value   = days  / (4*365 + 1);  /* Number of 4-years periods since the epoch*/
      +  days   -= value * (4*365 + 1);  /* Remaining days */
      +  value <<= 2;                    /* Years since the epoch */
      +
      +  /* Then we will brute force the next 0-3 years */
      +
      +  for (;;)
      +    {
      +      /* Is this year a leap year (we'll need this later too) */
      +
      +      leapyear = clock_isleapyear(value + 1970);
      +
      +      /* Get the number of days in the year */
      +
      +      tmp = (leapyear ? 366 : 365);
      +
      +      /* Do we have that many days? */
      +
      +      if (days >= tmp)
      +        {
      +           /* Yes.. bump up the year */
      +
      +           value++;
      +           days -= tmp;
      +        }
      +      else
      +        {
      +           /* Nope... then go handle months */
      +
      +           break;
      +        }
      +    }
      +
      +  /* At this point, value has the year and days has number days into this year */
      +
      +  *year = 1970 + value;
      +
      +  /* Handle the month (zero based) */
      +
      +  min = 0;
      +  max = 11;
      +
      +  do
      +    {
      +      /* Get the midpoint */
      +
      +      value = (min + max) >> 1;
      +
      +      /* Get the number of days that occurred before the beginning of the month
      +       * following the midpoint.
      +      */
      +
      +      tmp = clock_daysbeforemonth(value + 1, leapyear);
      +
      +      /* Does the number of days before this month that equal or exceed the
      +       * number of days we have remaining?
      +       */
      +
      +      if (tmp > days)
      +        {
      +          /* Yes.. then the month we want is somewhere from 'min' and to the
      +           * midpoint, 'value'.  Could it be the midpoint?
      +           */
      +
      +          tmp = clock_daysbeforemonth(value, leapyear);
      +          if (tmp > days)
      +            {
      +              /* No... The one we want is somewhere between min and value-1 */
      +
      +              max = value - 1;
      +            }
      +          else
      +            {
      +              /* Yes.. 'value' contains the month that we want */
      +
      +              break;
      +            }
      +        }
      +      else
      +        {
      +           /* No... The one we want is somwhere between value+1 and max */
      +
      +           min = value + 1;
      +        }
      +
      +      /* If we break out of the loop because min == max, then we want value
      +       * to be equal to min == max.
      +       */
      +
      +      value = min;
      +    }
      +  while (min < max);
      +
      +  /* The selected month number is in value. Subtract the number of days in the
      +   * selected month
      +   */
      +
      +  days -= clock_daysbeforemonth(value, leapyear);
      +
      +  /* At this point, value has the month into this year (zero based) and days has
      +   * number of days into this month (zero based)
      +   */
      +
      +  *month = value + 1; /* 1-based */
      +  *day   = days + 1;  /* 1-based */
      +}
      +
      +#endif /* CONFIG_GREGORIAN_TIME */
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  gmtime_r
      + *
      + * Description:
      + *  Time conversion (based on the POSIX API)
      + *
      + ****************************************************************************/
      +
      +FAR struct tm *gmtime_r(FAR const time_t *timer, FAR struct tm *result)
      +{
      +  time_t epoch;
      +  time_t jdn;
      +  int    year;
      +  int    month;
      +  int    day;
      +  int    hour;
      +  int    min;
      +  int    sec;
      +
      +  /* Get the seconds since the EPOCH */
      +
      +  epoch = *timer;
      +  sdbg("timer=%d\n", (int)epoch);
      +
      +  /* Convert to days, hours, minutes, and seconds since the EPOCH */
      +
      +  jdn    = epoch / SEC_PER_DAY;
      +  epoch -= SEC_PER_DAY * jdn;
      +
      +  hour   = epoch / SEC_PER_HOUR;
      +  epoch -= SEC_PER_HOUR * hour;
      +
      +  min    = epoch / SEC_PER_MIN;
      +  epoch -= SEC_PER_MIN * min;
      +
      +  sec    = epoch;
      +
      +  sdbg("hour=%d min=%d sec=%d\n",
      +       (int)hour, (int)min, (int)sec);
      +
      +  /* Convert the days since the EPOCH to calendar day */
      +
      +  clock_utc2calendar(jdn, &year, &month, &day);
      +
      +  sdbg("jdn=%d year=%d month=%d day=%d\n",
      +       (int)jdn, (int)year, (int)month, (int)day);
      +
      +  /* Then return the struct tm contents */
      +
      +  result->tm_year = (int)year - 1900; /* Relative to 1900 */
      +  result->tm_mon  = (int)month - 1;   /* zero-based */
      +  result->tm_mday = (int)day;         /* one-based */
      +  result->tm_hour = (int)hour;
      +  result->tm_min  = (int)min;
      +  result->tm_sec  = (int)sec;
      +
      +  return result;
      +}
      +
      diff --git a/nuttx/lib/time/lib_isleapyear.c b/nuttx/lib/time/lib_isleapyear.c
      new file mode 100644
      index 0000000000..966c248e01
      --- /dev/null
      +++ b/nuttx/lib/time/lib_isleapyear.c
      @@ -0,0 +1,88 @@
      +/****************************************************************************
      + * lib/time/lib_isleapyear.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  clock_isleapyear
      + *
      + * Description:
      + *    Return true if the specified year is a leap year
      + *
      + ****************************************************************************/
      +
      +int clock_isleapyear(int year)
      +{
      +  return year % 400 ? (year % 100 ? (year % 4 ? 0 : 1) : 0) : 1;
      +}
      +
      diff --git a/nuttx/lib/time/lib_mktime.c b/nuttx/lib/time/lib_mktime.c
      new file mode 100644
      index 0000000000..8c17e7c0ab
      --- /dev/null
      +++ b/nuttx/lib/time/lib_mktime.c
      @@ -0,0 +1,141 @@
      +/****************************************************************************
      + * lib/time/lib_mktime.c
      + *
      + *   Copyright (C) 2007, 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  mktime
      + *
      + * Description:
      + *  Time conversion (based on the POSIX API)
      + *
      + ****************************************************************************/
      +
      +#ifdef CONFIG_GREGORIAN_TIME
      +time_t mktime(const struct tm *tp)
      +{
      +  time_t ret;
      +  time_t jdn;
      +
      +  /* Get the EPOCH-relative julian date from the calendar year,
      +   * month, and date
      +   */
      +
      +  jdn = clock_calendar2utc(tp->tm_year+1900, tp->tm_mon+1, tp->tm_mday);
      +  sdbg("jdn=%d tm_year=%d tm_mon=%d tm_mday=%d\n",
      +       (int)jdn, tp->tm_year, tp->tm_mon, tp->tm_mday);
      +
      +  /* Return the seconds into the julian day. */
      +
      +  ret = ((jdn*24 + tp->tm_hour)*60 + tp->tm_min)*60 + tp->tm_sec;
      +  sdbg("ret=%d tm_hour=%d tm_min=%d tm_sec=%d\n",
      +       (int)ret, tp->tm_hour, tp->tm_min, tp->tm_sec);
      +
      +  return ret;
      +}
      +#else
      +
      +/* Simple version that only works for dates within a (relatively) small range
      + * from the epoch.  It does not handle earlier days or longer days where leap
      + * seconds, etc. apply.
      + */
      +
      +time_t mktime(const struct tm *tp)
      +{
      +  unsigned int days;
      +
      +  /* Years since epoch in units of days (ignoring leap years). */
      +
      +  days = (tp->tm_year - 70) * 365;
      +
      +  /* Add in the extra days for the leap years prior to the current year. */
      +
      +  days += (tp->tm_year - 69) >> 2;
      +
      +  /* Add in the days up to the beginning of this month. */
      +
      +  days += (time_t)clock_daysbeforemonth(tp->tm_mon, clock_isleapyear(tp->tm_year + 1900));
      +
      +  /* Add in the days since the beginning of this month (days are 1-based). */
      +
      +  days += tp->tm_mday - 1;
      +
      +  /* Then convert the seconds and add in hours, minutes, and seconds */
      +
      +  return ((days * 24 + tp->tm_hour) * 60 + tp->tm_min) * 60 + tp->tm_sec;
      +}
      +#endif /* CONFIG_GREGORIAN_TIME */
      +
      diff --git a/nuttx/lib/time/lib_strftime.c b/nuttx/lib/time/lib_strftime.c
      new file mode 100644
      index 0000000000..cd0804f55d
      --- /dev/null
      +++ b/nuttx/lib/time/lib_strftime.c
      @@ -0,0 +1,398 @@
      +/****************************************************************************
      + * lib/time/lib_strftime.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Type Declarations
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Function Prototypes
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Constant Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Data
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      +
      +static const char * const g_abbrevmonthname[12] =
      +{
      +  "Jan", "Feb", "Mar", "Apr", "May", "Jun",
      +  "Jul", "Aug", "Sep", "Oct", "Nov", "Dec"
      +};
      +
      +static const char * const g_monthname[12] =
      +{
      +  "January", "February", "March",     "April",   "May",      "June",
      +  "July",    "August",   "September", "October", "November", "December"
      +};
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  strftime
      + *
      + * Description:
      + *   The  strftime()  function  formats the broken-down time tm according to
      + *   the format specification format and places the result in the  character
      + *   array s of size max.
      + *
      + *   Ordinary characters placed in the format string are copied to s without
      + *   conversion.  Conversion specifications are introduced by a '%'  charac-
      + *   ter,  and  terminated  by  a  conversion  specifier  character, and are
      + *   replaced in s as follows:
      + *
      + *   %b     The abbreviated month name according to the current locale.
      + *   %B     The full month name according to the current locale.
      + *   %C     The century number (year/100) as a 2-digit integer. (SU)
      + *   %d     The day of the month as a decimal number (range 01 to 31).
      + *   %e     Like %d, the day of the month as a decimal number, but a leading
      + *          zero is replaced by a space.
      + *   %h     Equivalent to %b.  (SU)
      + *   %H     The hour as a decimal number using a 24-hour clock (range 00 to 23).
      + *   %I     The  hour as a decimal number using a 12-hour clock (range 01 to 12).
      + *   %j     The day of the year as a decimal number (range 001 to 366).
      + *   %k     The hour (24-hour clock) as a decimal number (range  0  to  23);
      + *          single digits are preceded by a blank.  (See also %H.)  (TZ)
      + *   %l     The  hour  (12-hour  clock) as a decimal number (range 1 to 12);
      + *          single digits are preceded by a blank.  (See also %I.)  (TZ)
      + *   %m     The month as a decimal number (range 01 to 12).
      + *   %M     The minute as a decimal number (range 00 to 59).
      + *   %n     A newline character. (SU)
      + *   %p     Either "AM" or "PM" according to the given time  value, or the
      + *          corresponding  strings  for the current locale.  Noon is treated
      + *          as "PM" and midnight as "AM".
      + *   %P     Like %p but in lowercase: "am" or "pm" or a corresponding string
      + *          for the current locale. (GNU)
      + *   %s     The number of seconds since the Epoch, that is, since 1970-01-01
      + *          00:00:00 UTC. (TZ)
      + *   %S     The second as a decimal number (range 00 to 60).  (The range is
      + *          up to 60 to allow for occasional leap seconds.)
      + *   %t     A tab character. (SU)
      + *   %y     The year as a decimal number without a century (range 00 to 99).
      + *   %Y     The year as a decimal number including the century.
      + *   %%     A literal '%' character.
      + *
      + * Returned Value:
      + *   The strftime() function returns the number of characters placed in  the
      + *    array s, not including the terminating null byte, provided the string,
      + *    including the terminating null byte, fits.  Otherwise,  it returns 0,
      + *    and the contents of the array is undefined. 
      + *
      + ****************************************************************************/
      +
      +size_t strftime(char *s, size_t max, const char *format, const struct tm *tm)
      +{
      +  const char *str;
      +  char       *dest   = s;
      +  int         chleft = max;
      +  int         value;
      +  int         len;
      +
      +  while (*format && chleft > 0)
      +    {
      +      /* Just copy regular characters */
      +
      +      if (*format != '%')
      +        {
      +           *dest++ = *format++;
      +           chleft--;
      +           continue;
      +        }
      +
      +      /* Handle the format character */
      +
      +       format++;
      +       len   = 0;
      +
      +       switch (*format++)
      +         {
      +           /* %a: A three-letter abbreviation for the day of the week. */
      +           /* %A: The full name for the day of the week. */
      +
      +           case 'a':
      +           case 'A':
      +             {
      +               len = snprintf(dest, chleft, "Day"); /* Not supported */
      +             }
      +             break;
      +           
      +           /* %h: Equivalent to %b */
      +
      +           case 'h':
      +
      +           /* %b: The abbreviated month name according to the current locale. */
      +
      +           case 'b':
      +             {
      +               if (tm->tm_mon < 12)
      +                 {
      +                   str = g_abbrevmonthname[tm->tm_mon];
      +                   len = snprintf(dest, chleft, "%s", str);
      +                 }
      +             }
      +             break;
      +
      +           /* %B: The full month name according to the current locale. */
      +
      +           case 'B':
      +             {
      +               if (tm->tm_mon < 12)
      +                 {
      +                   str = g_monthname[tm->tm_mon];
      +                   len = snprintf(dest, chleft, "%s", str);
      +                 }
      +             }
      +             break;
      +
      +           /* %y: The year as a decimal number without a century (range 00 to 99). */
      +
      +           case 'y':
      +
      +           /* %C: The century number (year/100) as a 2-digit integer. */
      +
      +           case 'C':
      +             {
      +               len = snprintf(dest, chleft, "%02d", tm->tm_year % 100);
      +             }
      +             break;
      +
      +           /* %d: The day of the month as a decimal number (range 01 to 31). */
      +
      +           case 'd':
      +             {
      +               len = snprintf(dest, chleft, "%02d", tm->tm_mday);
      +             }
      +             break;
      +
      +           /* %e: Like %d, the day of the month as a decimal number, but a leading
      +            * zero is replaced by a space.
      +            */
      +
      +           case 'e':
      +             {
      +               len = snprintf(dest, chleft, "%2d", tm->tm_mday);
      +             }
      +             break;
      +
      +           /* %H: The hour as a decimal number using a 24-hour clock (range 00  to 23). */
      +
      +           case 'H':
      +             {
      +               len = snprintf(dest, chleft, "%02d", tm->tm_hour);
      +             }
      +             break;
      +
      +           /* %I: The  hour as a decimal number using a 12-hour clock (range 01 to 12). */
      +
      +           case 'I':
      +             {
      +               len = snprintf(dest, chleft, "%02d", tm->tm_hour % 12);
      +             }
      +             break;
      +
      +           /* %j: The day of the year as a decimal number (range 001 to 366). */
      +
      +           case 'j':
      +             {
      +               if (tm->tm_mon < 12)
      +                 {
      +                   value = clock_daysbeforemonth(tm->tm_mon, clock_isleapyear(tm->tm_year)) + tm->tm_mday;
      +                   len   = snprintf(dest, chleft, "%03d", value);
      +                 }
      +             }
      +             break;
      +
      +           /* %k: The hour (24-hour clock) as a decimal number (range  0  to  23);
      +            * single digits are preceded by a blank.
      +            */
      +
      +           case 'k':
      +             {
      +               len = snprintf(dest, chleft, "%2d", tm->tm_hour);
      +             }
      +             break;
      +
      +           /* %l: The  hour  (12-hour  clock) as a decimal number (range 1 to 12);
      +            * single digits are preceded by a blank.
      +            */
      +
      +           case 'l':
      +             {
      +               len = snprintf(dest, chleft, "%2d", tm->tm_hour % 12);
      +             }
      +             break;
      +
      +           /* %m: The month as a decimal number (range 01 to 12). */
      +
      +           case 'm':
      +             {
      +               len = snprintf(dest, chleft, "%02d", tm->tm_mon + 1);
      +             }
      +             break;
      +
      +           /* %M: The minute as a decimal number (range 00 to 59). */
      +
      +           case 'M':
      +             {
      +               len = snprintf(dest, chleft, "%02d", tm->tm_min);
      +             }
      +             break;
      +
      +           /* %n: A newline character. */
      +
      +           case 'n':
      +             {
      +               *dest = '\n';
      +               len   = 1;
      +             }
      +             break;
      +
      +           /* %p: Either "AM" or "PM" according to the given time  value. */
      +
      +           case 'p':
      +             {
      +               if (tm->tm_hour >= 12)
      +                 {
      +                   str = "PM";
      +                 }
      +               else
      +                 {
      +                   str = "AM";
      +                 }
      +               len = snprintf(dest, chleft, "%s", str);
      +             }
      +             break;
      +
      +           /* %P: Like %p but in lowercase: "am" or "pm" */
      +
      +           case 'P':
      +             {
      +               if (tm->tm_hour >= 12)
      +                 {
      +                   str = "pm";
      +                 }
      +               else
      +                 {
      +                   str = "am";
      +                 }
      +               len = snprintf(dest, chleft, "%s", str);
      +             }
      +             break;
      +
      +           /* %s: The number of seconds since the Epoch, that is, since 1970-01-01
      +            * 00:00:00 UTC.
      +            */
      +
      +           case 's':
      +             {
      +               len = snprintf(dest, chleft, "%d", mktime(tm));
      +             }
      +             break;
      +
      +           /* %S: The second as a decimal number (range 00 to 60).  (The range  is
      +            * up to 60 to allow for occasional leap seconds.)
      +            */
      +
      +           case 'S':
      +             {
      +               len = snprintf(dest, chleft, "%02d", tm->tm_sec);
      +             }
      +             break;
      +
      +           /* %t: A tab character. */
      +
      +           case 't':
      +             {
      +               *dest = '\t';
      +               len   = 1;
      +             }
      +             break;
      +
      +           /* %Y: The year as a decimal number including the century. */
      +
      +           case 'Y':
      +             {
      +               len = snprintf(dest, chleft, "%04d", tm->tm_year + 1900);
      +             }
      +             break;
      +
      +           /* %%:  A literal '%' character. */
      +
      +           case '%':
      +             {
      +               *dest = '%';
      +               len   = 1;
      +             }
      +             break;
      +        }
      +
      +      /* Update counts and pointers */
      +
      +      dest   += len;
      +      chleft -= len;
      +    }
      +
      +  return max - chleft;
      +}
      diff --git a/nuttx/lib/time/lib_time.c b/nuttx/lib/time/lib_time.c
      new file mode 100644
      index 0000000000..106a04c366
      --- /dev/null
      +++ b/nuttx/lib/time/lib_time.c
      @@ -0,0 +1,110 @@
      +/****************************************************************************
      + * lib/time/lib_time.c
      + *
      + *   Copyright (C) 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +
      +#ifndef CONFIG_DISABLE_CLOCK
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Data
      + ****************************************************************************/
      + 
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Function:  time
      + *
      + * Description:
      + *   Get the current calendar time as a time_t object.  The function returns
      + *   this value, and if the argument is not a null pointer, the value is also
      + *   set to the object pointed by tloc.
      + *
      + *   Note that this function is just a thin wrapper around gettimeofday()
      + *   and is provided for compatibility.  gettimeofday() is the preffered way
      + *   to obtain system time.
      + *
      + * Parameters:
      + *   Pointer to an object of type time_t, where the time value is stored.
      + *   Alternativelly, this parameter can be a null pointer, in which case the
      + *   parameter is not used, but a time_t object is still returned by the
      + *   function.
      + *
      + * Return Value:
      + *   The current calendar time as a time_t object.  If the argument is not
      + *   a null pointer, the return value is the same as the one stored in the
      + *   location pointed by the argument.
      + *
      + *   If the function could not retrieve the calendar time, it returns a -1
      + *   value.
      + *
      + ****************************************************************************/
      +
      +time_t time(time_t *tloc)
      +{
      +  struct timeval tp;
      +  int ret;
      +
      +  /* Get the current time from the system */
      +
      +  ret = gettimeofday(&tp, NULL);
      +  if (ret == OK)
      +    {
      +      /* Return the seconds since the epoch */
      +
      +      if (tloc)
      +        {
      +          *tloc = tp.tv_sec;
      +        }
      +
      +      return tp.tv_sec;
      +    }
      +
      +  return (time_t)ERROR;
      +}
      +
      +#endif /* !CONFIG_DISABLE_CLOCK */
      diff --git a/nuttx/lib/unistd/Make.defs b/nuttx/lib/unistd/Make.defs
      new file mode 100644
      index 0000000000..e1441a48d3
      --- /dev/null
      +++ b/nuttx/lib/unistd/Make.defs
      @@ -0,0 +1,49 @@
      +############################################################################
      +# lib/unistd/Make.defs
      +#
      +#   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.
      +#
      +############################################################################
      +
      +# Add the unistd C files to the build
      +
      +CSRCS += lib_getopt.c lib_getoptargp.c lib_getoptindp.c lib_getoptoptp.c
      +
      +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
      +ifneq ($(CONFIG_DISABLE_ENVIRON),y)
      +CSRCS +=  lib_chdir.c lib_getcwd.c
      +endif
      +endif
      +
      +# Add the unistd directory to the build
      +
      +DEPPATH += --dep-path unistd
      +VPATH += :unistd
      diff --git a/nuttx/lib/unistd/lib_chdir.c b/nuttx/lib/unistd/lib_chdir.c
      new file mode 100644
      index 0000000000..3dd1333cec
      --- /dev/null
      +++ b/nuttx/lib/unistd/lib_chdir.c
      @@ -0,0 +1,179 @@
      +/****************************************************************************
      + * lib/unistd/lib_chdir.c
      + *
      + *   Copyright (C) 2008-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: _trimdir
      + ****************************************************************************/
      +
      +#if 0
      +static inline void _trimdir(char *path)
      +{
      + /* Skip any trailing '/' characters (unless it is also the leading '/') */
      +
      + int len = strlen(path) - 1;
      + while (len > 0 && path[len] == '/')
      +   {
      +      path[len] = '\0';
      +      len--;
      +   }
      +}
      +#else
      +#  define _trimdir(p)
      +#endif
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: chdir
      + *
      + * Description:
      + *   The chdir() function causes the directory named by the pathname pointed
      + *   to by the 'path' argument to become the current working directory; that
      + *   is, the starting point for path searches for pathnames not beginning
      + *   with '/'.
      + *
      + * Input Parmeters:
      + *   path - A pointer to a directory to use as the new current working
      + *     directory
      + *
      + * Returned Value:
      + *   0(OK) on success; -1(ERROR) on failure with errno set appropriately:
      + *
      + *   EACCES
      + *     Search permission is denied for any component of the pathname.
      + *   ELOOP
      + *     A loop exists in symbolic links encountered during resolution of the
      + *     'path' argument OR more that SYMLOOP_MAX symbolic links in the
      + *     resolution of the 'path' argument.
      + *   ENAMETOOLONG
      + *     The length of the path argument exceeds PATH_MAX or a pathname component
      + *     is longer than NAME_MAX.
      + *   ENOENT
      + *     A component of 'path' does not name an existing directory or path is
      + *     an empty string.
      + *   ENOTDIR
      + *     A component of the pathname is not a directory.
      + *
      + ****************************************************************************/
      +
      +int chdir(FAR const char *path)
      +{
      +  struct stat buf;
      +  char *oldpwd;
      +  char *alloc;
      +  int err;
      +  int ret;
      +
      +  /* Verify the input parameters */
      +
      +  if (!path)
      +    {
      +      err = ENOENT;
      +      goto errout;
      +    }
      +
      +  /* Verify that 'path' refers to a directory */
      +
      +  ret = stat(path, &buf);
      +  if (ret != 0)
      +    {
      +      err = ENOENT;
      +      goto errout;
      +    }
      +
      +  /* Something exists here... is it a directory? */
      +
      +  if (!S_ISDIR(buf.st_mode))
      +    {
      +      err = ENOTDIR;
      +      goto errout;
      +    }
      +
      +  /* Yes, it is a directory. Remove any trailing '/' characters from the path */
      +
      +  _trimdir(path);
      +
      +  /* Replace any preceding OLDPWD with the current PWD (this is to
      +   * support 'cd -' in NSH)
      +   */
      +
      +  sched_lock();
      +  oldpwd = getenv("PWD");
      +  if (!oldpwd)
      +    {
      +      oldpwd = CONFIG_LIB_HOMEDIR;
      +    }
      +
      +  alloc = strdup(oldpwd);  /* kludge needed because environment is realloc'ed */
      +  setenv("OLDPWD", alloc, TRUE);
      +  lib_free(alloc);
      +
      +  /* Set the cwd to the input 'path' */
      +
      +  setenv("PWD", path, TRUE);
      +  sched_unlock();
      +  return OK;
      +
      +errout:
      +  set_errno(err);
      +  return ERROR;
      +}
      +#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_DISABLE_ENVIRON */
      diff --git a/nuttx/lib/unistd/lib_getcwd.c b/nuttx/lib/unistd/lib_getcwd.c
      new file mode 100644
      index 0000000000..b94823300b
      --- /dev/null
      +++ b/nuttx/lib/unistd/lib_getcwd.c
      @@ -0,0 +1,132 @@
      +/****************************************************************************
      + * lib/unistd/lib_getcwd.c
      + *
      + *   Copyright (C) 2008, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +#include 
      +#include 
      +
      +#include "lib_internal.h"
      +
      +#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)
      +
      +/****************************************************************************
      + * Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Public Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: getwcd
      + *
      + * Description:
      + *   getcwd() function places the absolute pathname of the current working
      + *   directory in the array pointed to by 'buf', and returns 'buf.' The
      + *   pathname copied to the array shall contain no components that are
      + *   symbolic links. The 'size' argument is the size in bytes of the
      + *   character array pointed to by the 'buf' argument.
      + *
      + * Input Parmeters:
      + *   buf - a pointer to the location in which the current working directory
      + *     pathaname is returned.
      + *   size - The size in bytes avaiable at 'buf'
      + *
      + * Returned Value:
      + *   Upon successful completion, getcwd() returns the 'buf' argument.
      + *   Otherwise, getcwd() returns a null pointer and sets errno to indicate
      + *   the error:
      + *
      + *   EINVAL
      + *     The 'size' argument is 0 or the 'buf' argument is NULL.
      + *   ERANGE
      + *     The size argument is greater than 0, but is smaller than the length
      + *     of the currrent working directory pathname +1.
      + *   EACCES
      + *     Read or search permission was denied for a component of the pathname.
      + *   ENOMEM
      + *  Insufficient storage space is available. 
      + *
      + ****************************************************************************/
      +
      +FAR char *getcwd(FAR char *buf, size_t size)
      +{
      +  char *pwd;
      +
      +  /* Verify input parameters */
      +
      +#ifdef CONFIG_DEBUG
      +  if (!buf || !size)
      +    {
      +      set_errno(EINVAL);
      +      return NULL;
      +    }
      +#endif
      +
      +  /* If no working directory is defined, then default to the home directory */
      +
      +  pwd = getenv("PWD");
      +  if (!pwd)
      +    {
      +      pwd = CONFIG_LIB_HOMEDIR;
      +    }
      +
      +  /* Verify that the cwd will fit into the user-provided buffer */
      +
      +  if (strlen(pwd) + 1 > size)
      +    {
      +      set_errno(ERANGE);
      +      return NULL;
      +    }
      +
      +  /* Copy the cwd to the user buffer */
      +
      +  strcpy(buf, pwd);
      +  sched_unlock();
      +  return buf;
      +}
      +#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_DISABLE_ENVIRON */
      diff --git a/nuttx/lib/unistd/lib_getopt.c b/nuttx/lib/unistd/lib_getopt.c
      new file mode 100644
      index 0000000000..832d287213
      --- /dev/null
      +++ b/nuttx/lib/unistd/lib_getopt.c
      @@ -0,0 +1,269 @@
      +/****************************************************************************
      + * lib/unistd/lib_getopt.c
      + *
      + *   Copyright (C) 2007-2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +FAR char *optarg; /* Optional argument following option */
      +int optind = 1;   /* Index into argv */
      +int optopt = '?'; /* unrecognized option character */
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +static FAR char *g_optptr       = NULL;
      +static bool      g_binitialized = false;
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: getopt
      + *
      + * Description: getopt() parses command-line arguments.  Its arguments argc
      + *   and argv are the argument count and array as passed to the main()
      + *   function on program invocation.  An element of argv that starts with
      + *   '-' is an option element. The characters of this element (aside from
      + *   the initial '-') are option characters. If getopt() is called repeatedly,
      + *   it returns successively each of the option characters from each of the
      + *   option elements.
      + *
      + *   If getopt() finds another option character, it returns that character,
      + *   updating the external variable optind and a static variable nextchar so
      + *   that the next call to getopt() can resume the scan with the following
      + *   option character or argv-element.
      + *
      + *   If there are no more option characters, getopt() returns -1. Then optind
      + *   is the index in argv of the first argv-element that is not an option.
      + *
      + *   The 'optstring' argument is a string containing the legitimate option
      + *   characters. If such a character is followed by a colon, this indicates
      + *   that the option requires an argument.  If an argument is required for an
      + *   option so getopt() places a pointer to the following text in the same
      + *   argv-element, or the text of the following argv-element, in optarg.
      + *
      + *   NOTES:
      + *   1. opterr is not supported and this implementation of getopt() never
      + *      printfs error messages.
      + *   2. getopt is NOT threadsafe!
      + *   3. This version of getopt() does not reset global variables until
      + *      -1 is returned.  As a result, your command line parsing loops
      + *      must call getopt() repeatedly and continue to parse if other
      + *      errors are returned ('?' or ':') until getopt() finally returns -1.
      + *     (You can also set optind to -1 to force a reset).
      + *
      + * Return: If an option was successfully found, then getopt() returns the
      + *   option character. If all command-line options have been parsed, then
      + *   getopt() returns -1.  If getopt() encounters an option character that
      + *   was not in optstring, then '?' is returned. If getopt() encounters an
      + *   option with a missing argument, then the return value depends on the
      + *   first character in optstring: if it is ':', then ':' is returned;
      + *   otherwise '?' is returned.
      + *
      + ****************************************************************************/
      +
      +int getopt(int argc, FAR char *const argv[], FAR const char *optstring)
      +{
      +  if (argv && optstring && argc > 1)
      +    {
      +      int noarg_ret = '?';
      +      char *optchar;
      +
      +      /* The inital value of optind is 1.  If getopt() is called again in the
      +       * program, optind must be reset to some value <= 1.
      +       */
      +
      +      if (optind < 1 || !g_binitialized)
      +        {
      +          optind         = 1;     /* Skip over the program name */
      +          g_optptr       = NULL;  /* Start at the beginning of the first argument */
      +          g_binitialized = true;  /* Now we are initialized */
      +        }
      +
      +      /* If the first character of opstring s ':', then ':' is in the event of
      +       * a missing argument. Otherwise '?' is returned.
      +       */
      +
      +      if (*optstring == ':')
      +        {
      +           noarg_ret = ':';
      +           optstring++;
      +        }
      +
      +      /* Are we resuming in the middle, or at the end of a string of arguments?
      +       * g_optptr == NULL means that we are started at the beginning of argv[optind];
      +       * *g_optptr == \0 means that we are starting at the beginning of optind+1
      +       */
      +
      +      while (!g_optptr || !*g_optptr)
      +        {
      +          /* We need to start at the beginning of the next argv. Check if we need
      +           * to increment optind
      +           */
      +
      +          if (g_optptr)
      +            {
      +              /* Yes.. Increment it and check for the case where where we have
      +               * processed everything in the argv[] array.
      +               */
      +
      +              optind++;
      +            }
      +
      +          /* Check for the end of the argument list */
      +
      +          g_optptr = argv[optind];
      +          if (!g_optptr)
      +            {
      +              /* There are no more arguments, we are finished */
      +
      +              g_binitialized = false;
      +              return ERROR;
      +            }
      +
      +          /* We are starting at the beginning of argv[optind].  In this case, the
      +           * first character must be '-'
      +           */
      +
      +          if (*g_optptr != '-')
      +            {
      +              /* The argument does not start with '-', we are finished */
      +
      +              g_binitialized = false;
      +              return ERROR;
      +            }
      +
      +          /* Skip over the '-' */
      +
      +          g_optptr++;
      +        }
      +
      +        /* Special case handling of "-" and "-:" */
      +
      +        if (!*g_optptr)
      +          {
      +             optopt = '\0'; /* We'll fix up g_optptr the next time we are called */
      +             return '?';
      +          }
      +
      +        /* Handle the case of "-:" */
      +
      +        if (*g_optptr == ':')
      +          {
      +            optopt = ':';
      +            g_optptr++;
      +            return '?';
      +          }
      +
      +        /* g_optptr now points at the next option and it is not something crazy.
      +         * check if the option is in the list of valid options.
      +         */
      +
      +        optchar = strchr(optstring, *g_optptr);
      +        if (!optchar)
      +          {
      +            /* No this character is not in the list of valid options */
      +
      +            optopt = *g_optptr;
      +            g_optptr++;
      +            return '?';
      +          }
      +
      +        /* Yes, the character is in the list of valid options.  Does it have an
      +         * required argument?
      +         */
      +
      +        if (optchar[1] != ':')
      +          {
      +            /* No, no arguments. Just return the character that we found */
      +
      +            g_optptr++;
      +            return *optchar;
      +          }
      +
      +        /* Yes, it has a required argument.  Is the required argument
      +         * immediately after the command in this same argument?
      +         */
      +
      +        if (g_optptr[1] != '\0')
      +          {
      +              /* Yes, return a pointer into the current argument */
      +
      +              optarg = &g_optptr[1];
      +              optind++;
      +              g_optptr = NULL;
      +              return *optchar;
      +          }
      +
      +        /* No.. is the optional argument the next argument in argv[] ? */
      +
      +        if (argv[optind+1] && *argv[optind+1] != '-')
      +          {
      +            /* Yes.. return that */
      +
      +            optarg = argv[optind+1];
      +            optind += 2;
      +            g_optptr = NULL;
      +            return *optchar;
      +          }
      +
      +        /* No argument was supplied */
      +
      +        optarg = NULL;
      +        optopt = *optchar;
      +        optind++;
      +        return noarg_ret;
      +    }
      +
      +  g_binitialized = false;
      +  return ERROR;
      +}
      diff --git a/nuttx/lib/unistd/lib_getoptargp.c b/nuttx/lib/unistd/lib_getoptargp.c
      new file mode 100644
      index 0000000000..98a4850169
      --- /dev/null
      +++ b/nuttx/lib/unistd/lib_getoptargp.c
      @@ -0,0 +1,73 @@
      +/****************************************************************************
      + * lib/unistd/lib_getoptargp.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: getoptargp
      + *
      + * Description:
      + *   Returns a pointer to optarg.  This function is only used for external
      + *   modules that need to access the base, global variable, optarg.
      + *
      + ****************************************************************************/
      +
      +FAR char **getoptargp(void)
      +{
      +  return &optarg;
      +}
      +
      diff --git a/nuttx/lib/unistd/lib_getoptindp.c b/nuttx/lib/unistd/lib_getoptindp.c
      new file mode 100644
      index 0000000000..7714f8e708
      --- /dev/null
      +++ b/nuttx/lib/unistd/lib_getoptindp.c
      @@ -0,0 +1,73 @@
      +/****************************************************************************
      + * lib/unistd/lib_getoptindp.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: getoptindp
      + *
      + * Description:
      + *   Returns a pointer to optind.  This function is only used for external
      + *   modules that need to access the base, global variable, optind.
      + *
      + ****************************************************************************/
      +
      +int *getoptindp(void)
      +{
      +  return &optind;
      +}
      +
      diff --git a/nuttx/lib/unistd/lib_getoptoptp.c b/nuttx/lib/unistd/lib_getoptoptp.c
      new file mode 100644
      index 0000000000..4805b7ac3b
      --- /dev/null
      +++ b/nuttx/lib/unistd/lib_getoptoptp.c
      @@ -0,0 +1,73 @@
      +/****************************************************************************
      + * lib/unistd/lib_getoptoptp.c
      + *
      + *   Copyright (C) 2009, 2011 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.
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Included Files
      + ****************************************************************************/
      +
      +#include 
      +
      +#include 
      +
      +/****************************************************************************
      + * Pre-processor Definitions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Private Variables
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Global Functions
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Name: getoptoptp
      + *
      + * Description:
      + *   Returns a pointer to optopt.  This function is only used for external
      + *   modules that need to access the base, global variable, optopt.
      + *
      + ****************************************************************************/
      +
      +int *getoptoptp(void)
      +{
      +  return &optopt;
      +}
      +
      
      From 6d8270ffc52370931aa7a0ac985078ea10718457 Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sat, 10 Nov 2012 16:19:12 +0000
      Subject: [PATCH 099/206] Still trying to recover directory contents
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5330 42af7a65-404d-4744-a932-0658087f49c3
      ---
       nuttx/{lib => libc}/Kconfig                                 | 0
       nuttx/{lib => libc}/Makefile                                | 0
       nuttx/{lib => libc}/README.txt                              | 0
       nuttx/{lib => libc}/dirent/Make.defs                        | 0
       nuttx/{lib => libc}/dirent/lib_readdirr.c                   | 0
       nuttx/{lib => libc}/dirent/lib_telldir.c                    | 0
       nuttx/{lib => libc}/fixedmath/Make.defs                     | 0
       nuttx/{lib => libc}/fixedmath/lib_b16atan2.c                | 0
       nuttx/{lib => libc}/fixedmath/lib_b16cos.c                  | 0
       nuttx/{lib => libc}/fixedmath/lib_b16sin.c                  | 0
       nuttx/{lib => libc}/fixedmath/lib_fixedmath.c               | 0
       nuttx/{lib => libc}/fixedmath/lib_rint.c                    | 0
       nuttx/{lib => libc}/lib.csv                                 | 0
       nuttx/{lib => libc}/lib_internal.h                          | 0
       nuttx/{lib => libc}/libgen/Make.defs                        | 0
       nuttx/{lib => libc}/libgen/lib_basename.c                   | 0
       nuttx/{lib => libc}/libgen/lib_dirname.c                    | 0
       nuttx/{lib => libc}/math/Kconfig                            | 0
       nuttx/{lib => libc}/math/Make.defs                          | 0
       nuttx/{lib => libc}/math/lib_acos.c                         | 0
       nuttx/{lib => libc}/math/lib_acosf.c                        | 0
       nuttx/{lib => libc}/math/lib_acosl.c                        | 0
       nuttx/{lib => libc}/math/lib_asin.c                         | 0
       nuttx/{lib => libc}/math/lib_asinf.c                        | 0
       nuttx/{lib => libc}/math/lib_asinl.c                        | 0
       nuttx/{lib => libc}/math/lib_atan.c                         | 0
       nuttx/{lib => libc}/math/lib_atan2.c                        | 0
       nuttx/{lib => libc}/math/lib_atan2f.c                       | 0
       nuttx/{lib => libc}/math/lib_atan2l.c                       | 0
       nuttx/{lib => libc}/math/lib_atanf.c                        | 0
       nuttx/{lib => libc}/math/lib_atanl.c                        | 0
       nuttx/{lib => libc}/math/lib_ceil.c                         | 0
       nuttx/{lib => libc}/math/lib_ceilf.c                        | 0
       nuttx/{lib => libc}/math/lib_ceill.c                        | 0
       nuttx/{lib => libc}/math/lib_cos.c                          | 0
       nuttx/{lib => libc}/math/lib_cosf.c                         | 0
       nuttx/{lib => libc}/math/lib_cosh.c                         | 0
       nuttx/{lib => libc}/math/lib_coshf.c                        | 0
       nuttx/{lib => libc}/math/lib_coshl.c                        | 0
       nuttx/{lib => libc}/math/lib_cosl.c                         | 0
       nuttx/{lib => libc}/math/lib_exp.c                          | 0
       nuttx/{lib => libc}/math/lib_expf.c                         | 0
       nuttx/{lib => libc}/math/lib_expl.c                         | 0
       nuttx/{lib => libc}/math/lib_fabs.c                         | 0
       nuttx/{lib => libc}/math/lib_fabsf.c                        | 0
       nuttx/{lib => libc}/math/lib_fabsl.c                        | 0
       nuttx/{lib => libc}/math/lib_floor.c                        | 0
       nuttx/{lib => libc}/math/lib_floorf.c                       | 0
       nuttx/{lib => libc}/math/lib_floorl.c                       | 0
       nuttx/{lib => libc}/math/lib_fmod.c                         | 0
       nuttx/{lib => libc}/math/lib_fmodf.c                        | 0
       nuttx/{lib => libc}/math/lib_fmodl.c                        | 0
       nuttx/{lib => libc}/math/lib_frexp.c                        | 0
       nuttx/{lib => libc}/math/lib_frexpf.c                       | 0
       nuttx/{lib => libc}/math/lib_frexpl.c                       | 0
       nuttx/{lib => libc}/math/lib_ldexp.c                        | 0
       nuttx/{lib => libc}/math/lib_ldexpf.c                       | 0
       nuttx/{lib => libc}/math/lib_ldexpl.c                       | 0
       nuttx/{lib => libc}/math/lib_libexpi.c                      | 0
       nuttx/{lib => libc}/math/lib_libsqrtapprox.c                | 0
       nuttx/{lib => libc}/math/lib_log.c                          | 0
       nuttx/{lib => libc}/math/lib_log10.c                        | 0
       nuttx/{lib => libc}/math/lib_log10f.c                       | 0
       nuttx/{lib => libc}/math/lib_log10l.c                       | 0
       nuttx/{lib => libc}/math/lib_log2.c                         | 0
       nuttx/{lib => libc}/math/lib_log2f.c                        | 0
       nuttx/{lib => libc}/math/lib_log2l.c                        | 0
       nuttx/{lib => libc}/math/lib_logf.c                         | 0
       nuttx/{lib => libc}/math/lib_logl.c                         | 0
       nuttx/{lib => libc}/math/lib_modf.c                         | 0
       nuttx/{lib => libc}/math/lib_modff.c                        | 0
       nuttx/{lib => libc}/math/lib_modfl.c                        | 0
       nuttx/{lib => libc}/math/lib_pow.c                          | 0
       nuttx/{lib => libc}/math/lib_powf.c                         | 0
       nuttx/{lib => libc}/math/lib_powl.c                         | 0
       nuttx/{lib => libc}/math/lib_sin.c                          | 0
       nuttx/{lib => libc}/math/lib_sinf.c                         | 0
       nuttx/{lib => libc}/math/lib_sinh.c                         | 0
       nuttx/{lib => libc}/math/lib_sinhf.c                        | 0
       nuttx/{lib => libc}/math/lib_sinhl.c                        | 0
       nuttx/{lib => libc}/math/lib_sinl.c                         | 0
       nuttx/{lib => libc}/math/lib_sqrt.c                         | 0
       nuttx/{lib => libc}/math/lib_sqrtf.c                        | 0
       nuttx/{lib => libc}/math/lib_sqrtl.c                        | 0
       nuttx/{lib => libc}/math/lib_tan.c                          | 0
       nuttx/{lib => libc}/math/lib_tanf.c                         | 0
       nuttx/{lib => libc}/math/lib_tanh.c                         | 0
       nuttx/{lib => libc}/math/lib_tanhf.c                        | 0
       nuttx/{lib => libc}/math/lib_tanhl.c                        | 0
       nuttx/{lib => libc}/math/lib_tanl.c                         | 0
       nuttx/{lib => libc}/misc/Make.defs                          | 0
       nuttx/{lib => libc}/misc/lib_crc32.c                        | 0
       nuttx/{lib => libc}/misc/lib_dbg.c                          | 0
       nuttx/{lib => libc}/misc/lib_dumpbuffer.c                   | 0
       nuttx/{lib => libc}/misc/lib_filesem.c                      | 0
       nuttx/{lib => libc}/misc/lib_init.c                         | 0
       nuttx/{lib => libc}/misc/lib_match.c                        | 0
       nuttx/{lib => libc}/misc/lib_sendfile.c                     | 0
       nuttx/{lib => libc}/misc/lib_streamsem.c                    | 0
       nuttx/{lib => libc}/mqueue/Make.defs                        | 0
       nuttx/{lib => libc}/mqueue/mq_getattr.c                     | 0
       nuttx/{lib => libc}/mqueue/mq_setattr.c                     | 0
       nuttx/{lib => libc}/net/Make.defs                           | 0
       nuttx/{lib => libc}/net/lib_etherntoa.c                     | 0
       nuttx/{lib => libc}/net/lib_htonl.c                         | 0
       nuttx/{lib => libc}/net/lib_htons.c                         | 0
       nuttx/{lib => libc}/net/lib_inetaddr.c                      | 0
       nuttx/{lib => libc}/net/lib_inetntoa.c                      | 0
       nuttx/{lib => libc}/net/lib_inetntop.c                      | 0
       nuttx/{lib => libc}/net/lib_inetpton.c                      | 0
       nuttx/{lib => libc}/pthread/Make.defs                       | 0
       nuttx/{lib => libc}/pthread/pthread_attrdestroy.c           | 0
       nuttx/{lib => libc}/pthread/pthread_attrgetinheritsched.c   | 0
       nuttx/{lib => libc}/pthread/pthread_attrgetschedparam.c     | 0
       nuttx/{lib => libc}/pthread/pthread_attrgetschedpolicy.c    | 0
       nuttx/{lib => libc}/pthread/pthread_attrgetstacksize.c      | 0
       nuttx/{lib => libc}/pthread/pthread_attrinit.c              | 0
       nuttx/{lib => libc}/pthread/pthread_attrsetinheritsched.c   | 0
       nuttx/{lib => libc}/pthread/pthread_attrsetschedparam.c     | 0
       nuttx/{lib => libc}/pthread/pthread_attrsetschedpolicy.c    | 0
       nuttx/{lib => libc}/pthread/pthread_attrsetstacksize.c      | 0
       nuttx/{lib => libc}/pthread/pthread_barrierattrdestroy.c    | 0
       nuttx/{lib => libc}/pthread/pthread_barrierattrgetpshared.c | 0
       nuttx/{lib => libc}/pthread/pthread_barrierattrinit.c       | 0
       nuttx/{lib => libc}/pthread/pthread_barrierattrsetpshared.c | 0
       nuttx/{lib => libc}/pthread/pthread_condattrdestroy.c       | 0
       nuttx/{lib => libc}/pthread/pthread_condattrinit.c          | 0
       nuttx/{lib => libc}/pthread/pthread_mutexattrdestroy.c      | 0
       nuttx/{lib => libc}/pthread/pthread_mutexattrgetpshared.c   | 0
       nuttx/{lib => libc}/pthread/pthread_mutexattrgettype.c      | 0
       nuttx/{lib => libc}/pthread/pthread_mutexattrinit.c         | 0
       nuttx/{lib => libc}/pthread/pthread_mutexattrsetpshared.c   | 0
       nuttx/{lib => libc}/pthread/pthread_mutexattrsettype.c      | 0
       nuttx/{lib => libc}/queue/Make.defs                         | 0
       nuttx/{lib => libc}/queue/dq_addafter.c                     | 0
       nuttx/{lib => libc}/queue/dq_addbefore.c                    | 0
       nuttx/{lib => libc}/queue/dq_addfirst.c                     | 0
       nuttx/{lib => libc}/queue/dq_addlast.c                      | 0
       nuttx/{lib => libc}/queue/dq_rem.c                          | 0
       nuttx/{lib => libc}/queue/dq_remfirst.c                     | 0
       nuttx/{lib => libc}/queue/dq_remlast.c                      | 0
       nuttx/{lib => libc}/queue/sq_addafter.c                     | 0
       nuttx/{lib => libc}/queue/sq_addfirst.c                     | 0
       nuttx/{lib => libc}/queue/sq_addlast.c                      | 0
       nuttx/{lib => libc}/queue/sq_rem.c                          | 0
       nuttx/{lib => libc}/queue/sq_remafter.c                     | 0
       nuttx/{lib => libc}/queue/sq_remfirst.c                     | 0
       nuttx/{lib => libc}/queue/sq_remlast.c                      | 0
       nuttx/{lib => libc}/sched/Make.defs                         | 0
       nuttx/{lib => libc}/sched/sched_getprioritymax.c            | 0
       nuttx/{lib => libc}/sched/sched_getprioritymin.c            | 0
       nuttx/{lib => libc}/semaphore/Make.defs                     | 0
       nuttx/{lib => libc}/semaphore/sem_getvalue.c                | 0
       nuttx/{lib => libc}/semaphore/sem_init.c                    | 0
       nuttx/{lib => libc}/signal/Make.defs                        | 0
       nuttx/{lib => libc}/signal/sig_addset.c                     | 0
       nuttx/{lib => libc}/signal/sig_delset.c                     | 0
       nuttx/{lib => libc}/signal/sig_emptyset.c                   | 0
       nuttx/{lib => libc}/signal/sig_fillset.c                    | 0
       nuttx/{lib => libc}/signal/sig_ismember.c                   | 0
       nuttx/{lib => libc}/stdio/Make.defs                         | 0
       nuttx/{lib => libc}/stdio/lib_asprintf.c                    | 0
       nuttx/{lib => libc}/stdio/lib_avsprintf.c                   | 0
       nuttx/{lib => libc}/stdio/lib_clearerr.c                    | 0
       nuttx/{lib => libc}/stdio/lib_dtoa.c                        | 0
       nuttx/{lib => libc}/stdio/lib_fclose.c                      | 0
       nuttx/{lib => libc}/stdio/lib_feof.c                        | 0
       nuttx/{lib => libc}/stdio/lib_ferror.c                      | 0
       nuttx/{lib => libc}/stdio/lib_fflush.c                      | 0
       nuttx/{lib => libc}/stdio/lib_fgetc.c                       | 0
       nuttx/{lib => libc}/stdio/lib_fgetpos.c                     | 0
       nuttx/{lib => libc}/stdio/lib_fgets.c                       | 0
       nuttx/{lib => libc}/stdio/lib_fileno.c                      | 0
       nuttx/{lib => libc}/stdio/lib_fopen.c                       | 0
       nuttx/{lib => libc}/stdio/lib_fprintf.c                     | 0
       nuttx/{lib => libc}/stdio/lib_fputc.c                       | 0
       nuttx/{lib => libc}/stdio/lib_fputs.c                       | 0
       nuttx/{lib => libc}/stdio/lib_fread.c                       | 0
       nuttx/{lib => libc}/stdio/lib_fseek.c                       | 0
       nuttx/{lib => libc}/stdio/lib_fsetpos.c                     | 0
       nuttx/{lib => libc}/stdio/lib_ftell.c                       | 0
       nuttx/{lib => libc}/stdio/lib_fwrite.c                      | 0
       nuttx/{lib => libc}/stdio/lib_gets.c                        | 0
       nuttx/{lib => libc}/stdio/lib_libdtoa.c                     | 0
       nuttx/{lib => libc}/stdio/lib_libfflush.c                   | 0
       nuttx/{lib => libc}/stdio/lib_libflushall.c                 | 0
       nuttx/{lib => libc}/stdio/lib_libfread.c                    | 0
       nuttx/{lib => libc}/stdio/lib_libfwrite.c                   | 0
       nuttx/{lib => libc}/stdio/lib_libnoflush.c                  | 0
       nuttx/{lib => libc}/stdio/lib_libsprintf.c                  | 0
       nuttx/{lib => libc}/stdio/lib_libvsprintf.c                 | 0
       nuttx/{lib => libc}/stdio/lib_lowinstream.c                 | 0
       nuttx/{lib => libc}/stdio/lib_lowoutstream.c                | 0
       nuttx/{lib => libc}/stdio/lib_lowprintf.c                   | 0
       nuttx/{lib => libc}/stdio/lib_meminstream.c                 | 0
       nuttx/{lib => libc}/stdio/lib_memoutstream.c                | 0
       nuttx/{lib => libc}/stdio/lib_nullinstream.c                | 0
       nuttx/{lib => libc}/stdio/lib_nulloutstream.c               | 0
       nuttx/{lib => libc}/stdio/lib_perror.c                      | 0
       nuttx/{lib => libc}/stdio/lib_printf.c                      | 0
       nuttx/{lib => libc}/stdio/lib_puts.c                        | 0
       nuttx/{lib => libc}/stdio/lib_rawinstream.c                 | 0
       nuttx/{lib => libc}/stdio/lib_rawoutstream.c                | 0
       nuttx/{lib => libc}/stdio/lib_rawprintf.c                   | 0
       nuttx/{lib => libc}/stdio/lib_rdflush.c                     | 0
       nuttx/{lib => libc}/stdio/lib_snprintf.c                    | 0
       nuttx/{lib => libc}/stdio/lib_sprintf.c                     | 0
       nuttx/{lib => libc}/stdio/lib_sscanf.c                      | 0
       nuttx/{lib => libc}/stdio/lib_stdinstream.c                 | 0
       nuttx/{lib => libc}/stdio/lib_stdoutstream.c                | 0
       nuttx/{lib => libc}/stdio/lib_syslogstream.c                | 0
       nuttx/{lib => libc}/stdio/lib_ungetc.c                      | 0
       nuttx/{lib => libc}/stdio/lib_vfprintf.c                    | 0
       nuttx/{lib => libc}/stdio/lib_vprintf.c                     | 0
       nuttx/{lib => libc}/stdio/lib_vsnprintf.c                   | 0
       nuttx/{lib => libc}/stdio/lib_vsprintf.c                    | 0
       nuttx/{lib => libc}/stdio/lib_wrflush.c                     | 0
       nuttx/{lib => libc}/stdio/lib_zeroinstream.c                | 0
       nuttx/{lib => libc}/stdlib/Make.defs                        | 0
       nuttx/{lib => libc}/stdlib/lib_abort.c                      | 0
       nuttx/{lib => libc}/stdlib/lib_abs.c                        | 0
       nuttx/{lib => libc}/stdlib/lib_imaxabs.c                    | 0
       nuttx/{lib => libc}/stdlib/lib_labs.c                       | 0
       nuttx/{lib => libc}/stdlib/lib_llabs.c                      | 0
       nuttx/{lib => libc}/stdlib/lib_qsort.c                      | 0
       nuttx/{lib => libc}/stdlib/lib_rand.c                       | 0
       nuttx/{lib => libc}/string/Make.defs                        | 0
       nuttx/{lib => libc}/string/lib_checkbase.c                  | 0
       nuttx/{lib => libc}/string/lib_isbasedigit.c                | 0
       nuttx/{lib => libc}/string/lib_memccpy.c                    | 0
       nuttx/{lib => libc}/string/lib_memchr.c                     | 0
       nuttx/{lib => libc}/string/lib_memcmp.c                     | 0
       nuttx/{lib => libc}/string/lib_memcpy.c                     | 0
       nuttx/{lib => libc}/string/lib_memmove.c                    | 0
       nuttx/{lib => libc}/string/lib_memset.c                     | 0
       nuttx/{lib => libc}/string/lib_skipspace.c                  | 0
       nuttx/{lib => libc}/string/lib_strcasecmp.c                 | 0
       nuttx/{lib => libc}/string/lib_strcasestr.c                 | 0
       nuttx/{lib => libc}/string/lib_strcat.c                     | 0
       nuttx/{lib => libc}/string/lib_strchr.c                     | 0
       nuttx/{lib => libc}/string/lib_strcmp.c                     | 0
       nuttx/{lib => libc}/string/lib_strcpy.c                     | 0
       nuttx/{lib => libc}/string/lib_strcspn.c                    | 0
       nuttx/{lib => libc}/string/lib_strdup.c                     | 0
       nuttx/{lib => libc}/string/lib_strerror.c                   | 0
       nuttx/{lib => libc}/string/lib_strlen.c                     | 0
       nuttx/{lib => libc}/string/lib_strncasecmp.c                | 0
       nuttx/{lib => libc}/string/lib_strncat.c                    | 0
       nuttx/{lib => libc}/string/lib_strncmp.c                    | 0
       nuttx/{lib => libc}/string/lib_strncpy.c                    | 0
       nuttx/{lib => libc}/string/lib_strndup.c                    | 0
       nuttx/{lib => libc}/string/lib_strnlen.c                    | 0
       nuttx/{lib => libc}/string/lib_strpbrk.c                    | 0
       nuttx/{lib => libc}/string/lib_strrchr.c                    | 0
       nuttx/{lib => libc}/string/lib_strspn.c                     | 0
       nuttx/{lib => libc}/string/lib_strstr.c                     | 0
       nuttx/{lib => libc}/string/lib_strtod.c                     | 0
       nuttx/{lib => libc}/string/lib_strtok.c                     | 0
       nuttx/{lib => libc}/string/lib_strtokr.c                    | 0
       nuttx/{lib => libc}/string/lib_strtol.c                     | 0
       nuttx/{lib => libc}/string/lib_strtoll.c                    | 0
       nuttx/{lib => libc}/string/lib_strtoul.c                    | 0
       nuttx/{lib => libc}/string/lib_strtoull.c                   | 0
       nuttx/{lib => libc}/string/lib_vikmemcpy.c                  | 0
       nuttx/{lib => libc}/termios/Make.defs                       | 0
       nuttx/{lib => libc}/termios/lib_cfgetspeed.c                | 0
       nuttx/{lib => libc}/termios/lib_cfsetspeed.c                | 0
       nuttx/{lib => libc}/termios/lib_tcflush.c                   | 0
       nuttx/{lib => libc}/termios/lib_tcgetattr.c                 | 0
       nuttx/{lib => libc}/termios/lib_tcsetattr.c                 | 0
       nuttx/{lib => libc}/time/Make.defs                          | 0
       nuttx/{lib => libc}/time/lib_calendar2utc.c                 | 0
       nuttx/{lib => libc}/time/lib_daysbeforemonth.c              | 0
       nuttx/{lib => libc}/time/lib_gmtime.c                       | 0
       nuttx/{lib => libc}/time/lib_gmtimer.c                      | 0
       nuttx/{lib => libc}/time/lib_isleapyear.c                   | 0
       nuttx/{lib => libc}/time/lib_mktime.c                       | 0
       nuttx/{lib => libc}/time/lib_strftime.c                     | 0
       nuttx/{lib => libc}/time/lib_time.c                         | 0
       nuttx/{lib => libc}/unistd/Make.defs                        | 0
       nuttx/{lib => libc}/unistd/lib_chdir.c                      | 0
       nuttx/{lib => libc}/unistd/lib_getcwd.c                     | 0
       nuttx/{lib => libc}/unistd/lib_getopt.c                     | 0
       nuttx/{lib => libc}/unistd/lib_getoptargp.c                 | 0
       nuttx/{lib => libc}/unistd/lib_getoptindp.c                 | 0
       nuttx/{lib => libc}/unistd/lib_getoptoptp.c                 | 0
       286 files changed, 0 insertions(+), 0 deletions(-)
       rename nuttx/{lib => libc}/Kconfig (100%)
       rename nuttx/{lib => libc}/Makefile (100%)
       rename nuttx/{lib => libc}/README.txt (100%)
       rename nuttx/{lib => libc}/dirent/Make.defs (100%)
       rename nuttx/{lib => libc}/dirent/lib_readdirr.c (100%)
       rename nuttx/{lib => libc}/dirent/lib_telldir.c (100%)
       rename nuttx/{lib => libc}/fixedmath/Make.defs (100%)
       rename nuttx/{lib => libc}/fixedmath/lib_b16atan2.c (100%)
       rename nuttx/{lib => libc}/fixedmath/lib_b16cos.c (100%)
       rename nuttx/{lib => libc}/fixedmath/lib_b16sin.c (100%)
       rename nuttx/{lib => libc}/fixedmath/lib_fixedmath.c (100%)
       rename nuttx/{lib => libc}/fixedmath/lib_rint.c (100%)
       rename nuttx/{lib => libc}/lib.csv (100%)
       rename nuttx/{lib => libc}/lib_internal.h (100%)
       rename nuttx/{lib => libc}/libgen/Make.defs (100%)
       rename nuttx/{lib => libc}/libgen/lib_basename.c (100%)
       rename nuttx/{lib => libc}/libgen/lib_dirname.c (100%)
       rename nuttx/{lib => libc}/math/Kconfig (100%)
       rename nuttx/{lib => libc}/math/Make.defs (100%)
       rename nuttx/{lib => libc}/math/lib_acos.c (100%)
       rename nuttx/{lib => libc}/math/lib_acosf.c (100%)
       rename nuttx/{lib => libc}/math/lib_acosl.c (100%)
       rename nuttx/{lib => libc}/math/lib_asin.c (100%)
       rename nuttx/{lib => libc}/math/lib_asinf.c (100%)
       rename nuttx/{lib => libc}/math/lib_asinl.c (100%)
       rename nuttx/{lib => libc}/math/lib_atan.c (100%)
       rename nuttx/{lib => libc}/math/lib_atan2.c (100%)
       rename nuttx/{lib => libc}/math/lib_atan2f.c (100%)
       rename nuttx/{lib => libc}/math/lib_atan2l.c (100%)
       rename nuttx/{lib => libc}/math/lib_atanf.c (100%)
       rename nuttx/{lib => libc}/math/lib_atanl.c (100%)
       rename nuttx/{lib => libc}/math/lib_ceil.c (100%)
       rename nuttx/{lib => libc}/math/lib_ceilf.c (100%)
       rename nuttx/{lib => libc}/math/lib_ceill.c (100%)
       rename nuttx/{lib => libc}/math/lib_cos.c (100%)
       rename nuttx/{lib => libc}/math/lib_cosf.c (100%)
       rename nuttx/{lib => libc}/math/lib_cosh.c (100%)
       rename nuttx/{lib => libc}/math/lib_coshf.c (100%)
       rename nuttx/{lib => libc}/math/lib_coshl.c (100%)
       rename nuttx/{lib => libc}/math/lib_cosl.c (100%)
       rename nuttx/{lib => libc}/math/lib_exp.c (100%)
       rename nuttx/{lib => libc}/math/lib_expf.c (100%)
       rename nuttx/{lib => libc}/math/lib_expl.c (100%)
       rename nuttx/{lib => libc}/math/lib_fabs.c (100%)
       rename nuttx/{lib => libc}/math/lib_fabsf.c (100%)
       rename nuttx/{lib => libc}/math/lib_fabsl.c (100%)
       rename nuttx/{lib => libc}/math/lib_floor.c (100%)
       rename nuttx/{lib => libc}/math/lib_floorf.c (100%)
       rename nuttx/{lib => libc}/math/lib_floorl.c (100%)
       rename nuttx/{lib => libc}/math/lib_fmod.c (100%)
       rename nuttx/{lib => libc}/math/lib_fmodf.c (100%)
       rename nuttx/{lib => libc}/math/lib_fmodl.c (100%)
       rename nuttx/{lib => libc}/math/lib_frexp.c (100%)
       rename nuttx/{lib => libc}/math/lib_frexpf.c (100%)
       rename nuttx/{lib => libc}/math/lib_frexpl.c (100%)
       rename nuttx/{lib => libc}/math/lib_ldexp.c (100%)
       rename nuttx/{lib => libc}/math/lib_ldexpf.c (100%)
       rename nuttx/{lib => libc}/math/lib_ldexpl.c (100%)
       rename nuttx/{lib => libc}/math/lib_libexpi.c (100%)
       rename nuttx/{lib => libc}/math/lib_libsqrtapprox.c (100%)
       rename nuttx/{lib => libc}/math/lib_log.c (100%)
       rename nuttx/{lib => libc}/math/lib_log10.c (100%)
       rename nuttx/{lib => libc}/math/lib_log10f.c (100%)
       rename nuttx/{lib => libc}/math/lib_log10l.c (100%)
       rename nuttx/{lib => libc}/math/lib_log2.c (100%)
       rename nuttx/{lib => libc}/math/lib_log2f.c (100%)
       rename nuttx/{lib => libc}/math/lib_log2l.c (100%)
       rename nuttx/{lib => libc}/math/lib_logf.c (100%)
       rename nuttx/{lib => libc}/math/lib_logl.c (100%)
       rename nuttx/{lib => libc}/math/lib_modf.c (100%)
       rename nuttx/{lib => libc}/math/lib_modff.c (100%)
       rename nuttx/{lib => libc}/math/lib_modfl.c (100%)
       rename nuttx/{lib => libc}/math/lib_pow.c (100%)
       rename nuttx/{lib => libc}/math/lib_powf.c (100%)
       rename nuttx/{lib => libc}/math/lib_powl.c (100%)
       rename nuttx/{lib => libc}/math/lib_sin.c (100%)
       rename nuttx/{lib => libc}/math/lib_sinf.c (100%)
       rename nuttx/{lib => libc}/math/lib_sinh.c (100%)
       rename nuttx/{lib => libc}/math/lib_sinhf.c (100%)
       rename nuttx/{lib => libc}/math/lib_sinhl.c (100%)
       rename nuttx/{lib => libc}/math/lib_sinl.c (100%)
       rename nuttx/{lib => libc}/math/lib_sqrt.c (100%)
       rename nuttx/{lib => libc}/math/lib_sqrtf.c (100%)
       rename nuttx/{lib => libc}/math/lib_sqrtl.c (100%)
       rename nuttx/{lib => libc}/math/lib_tan.c (100%)
       rename nuttx/{lib => libc}/math/lib_tanf.c (100%)
       rename nuttx/{lib => libc}/math/lib_tanh.c (100%)
       rename nuttx/{lib => libc}/math/lib_tanhf.c (100%)
       rename nuttx/{lib => libc}/math/lib_tanhl.c (100%)
       rename nuttx/{lib => libc}/math/lib_tanl.c (100%)
       rename nuttx/{lib => libc}/misc/Make.defs (100%)
       rename nuttx/{lib => libc}/misc/lib_crc32.c (100%)
       rename nuttx/{lib => libc}/misc/lib_dbg.c (100%)
       rename nuttx/{lib => libc}/misc/lib_dumpbuffer.c (100%)
       rename nuttx/{lib => libc}/misc/lib_filesem.c (100%)
       rename nuttx/{lib => libc}/misc/lib_init.c (100%)
       rename nuttx/{lib => libc}/misc/lib_match.c (100%)
       rename nuttx/{lib => libc}/misc/lib_sendfile.c (100%)
       rename nuttx/{lib => libc}/misc/lib_streamsem.c (100%)
       rename nuttx/{lib => libc}/mqueue/Make.defs (100%)
       rename nuttx/{lib => libc}/mqueue/mq_getattr.c (100%)
       rename nuttx/{lib => libc}/mqueue/mq_setattr.c (100%)
       rename nuttx/{lib => libc}/net/Make.defs (100%)
       rename nuttx/{lib => libc}/net/lib_etherntoa.c (100%)
       rename nuttx/{lib => libc}/net/lib_htonl.c (100%)
       rename nuttx/{lib => libc}/net/lib_htons.c (100%)
       rename nuttx/{lib => libc}/net/lib_inetaddr.c (100%)
       rename nuttx/{lib => libc}/net/lib_inetntoa.c (100%)
       rename nuttx/{lib => libc}/net/lib_inetntop.c (100%)
       rename nuttx/{lib => libc}/net/lib_inetpton.c (100%)
       rename nuttx/{lib => libc}/pthread/Make.defs (100%)
       rename nuttx/{lib => libc}/pthread/pthread_attrdestroy.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_attrgetinheritsched.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_attrgetschedparam.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_attrgetschedpolicy.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_attrgetstacksize.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_attrinit.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_attrsetinheritsched.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_attrsetschedparam.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_attrsetschedpolicy.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_attrsetstacksize.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_barrierattrdestroy.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_barrierattrgetpshared.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_barrierattrinit.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_barrierattrsetpshared.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_condattrdestroy.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_condattrinit.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_mutexattrdestroy.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_mutexattrgetpshared.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_mutexattrgettype.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_mutexattrinit.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_mutexattrsetpshared.c (100%)
       rename nuttx/{lib => libc}/pthread/pthread_mutexattrsettype.c (100%)
       rename nuttx/{lib => libc}/queue/Make.defs (100%)
       rename nuttx/{lib => libc}/queue/dq_addafter.c (100%)
       rename nuttx/{lib => libc}/queue/dq_addbefore.c (100%)
       rename nuttx/{lib => libc}/queue/dq_addfirst.c (100%)
       rename nuttx/{lib => libc}/queue/dq_addlast.c (100%)
       rename nuttx/{lib => libc}/queue/dq_rem.c (100%)
       rename nuttx/{lib => libc}/queue/dq_remfirst.c (100%)
       rename nuttx/{lib => libc}/queue/dq_remlast.c (100%)
       rename nuttx/{lib => libc}/queue/sq_addafter.c (100%)
       rename nuttx/{lib => libc}/queue/sq_addfirst.c (100%)
       rename nuttx/{lib => libc}/queue/sq_addlast.c (100%)
       rename nuttx/{lib => libc}/queue/sq_rem.c (100%)
       rename nuttx/{lib => libc}/queue/sq_remafter.c (100%)
       rename nuttx/{lib => libc}/queue/sq_remfirst.c (100%)
       rename nuttx/{lib => libc}/queue/sq_remlast.c (100%)
       rename nuttx/{lib => libc}/sched/Make.defs (100%)
       rename nuttx/{lib => libc}/sched/sched_getprioritymax.c (100%)
       rename nuttx/{lib => libc}/sched/sched_getprioritymin.c (100%)
       rename nuttx/{lib => libc}/semaphore/Make.defs (100%)
       rename nuttx/{lib => libc}/semaphore/sem_getvalue.c (100%)
       rename nuttx/{lib => libc}/semaphore/sem_init.c (100%)
       rename nuttx/{lib => libc}/signal/Make.defs (100%)
       rename nuttx/{lib => libc}/signal/sig_addset.c (100%)
       rename nuttx/{lib => libc}/signal/sig_delset.c (100%)
       rename nuttx/{lib => libc}/signal/sig_emptyset.c (100%)
       rename nuttx/{lib => libc}/signal/sig_fillset.c (100%)
       rename nuttx/{lib => libc}/signal/sig_ismember.c (100%)
       rename nuttx/{lib => libc}/stdio/Make.defs (100%)
       rename nuttx/{lib => libc}/stdio/lib_asprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_avsprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_clearerr.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_dtoa.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fclose.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_feof.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_ferror.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fflush.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fgetc.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fgetpos.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fgets.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fileno.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fopen.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fputc.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fputs.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fread.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fseek.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fsetpos.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_ftell.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_fwrite.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_gets.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_libdtoa.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_libfflush.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_libflushall.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_libfread.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_libfwrite.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_libnoflush.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_libsprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_libvsprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_lowinstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_lowoutstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_lowprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_meminstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_memoutstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_nullinstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_nulloutstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_perror.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_printf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_puts.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_rawinstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_rawoutstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_rawprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_rdflush.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_snprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_sprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_sscanf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_stdinstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_stdoutstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_syslogstream.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_ungetc.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_vfprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_vprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_vsnprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_vsprintf.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_wrflush.c (100%)
       rename nuttx/{lib => libc}/stdio/lib_zeroinstream.c (100%)
       rename nuttx/{lib => libc}/stdlib/Make.defs (100%)
       rename nuttx/{lib => libc}/stdlib/lib_abort.c (100%)
       rename nuttx/{lib => libc}/stdlib/lib_abs.c (100%)
       rename nuttx/{lib => libc}/stdlib/lib_imaxabs.c (100%)
       rename nuttx/{lib => libc}/stdlib/lib_labs.c (100%)
       rename nuttx/{lib => libc}/stdlib/lib_llabs.c (100%)
       rename nuttx/{lib => libc}/stdlib/lib_qsort.c (100%)
       rename nuttx/{lib => libc}/stdlib/lib_rand.c (100%)
       rename nuttx/{lib => libc}/string/Make.defs (100%)
       rename nuttx/{lib => libc}/string/lib_checkbase.c (100%)
       rename nuttx/{lib => libc}/string/lib_isbasedigit.c (100%)
       rename nuttx/{lib => libc}/string/lib_memccpy.c (100%)
       rename nuttx/{lib => libc}/string/lib_memchr.c (100%)
       rename nuttx/{lib => libc}/string/lib_memcmp.c (100%)
       rename nuttx/{lib => libc}/string/lib_memcpy.c (100%)
       rename nuttx/{lib => libc}/string/lib_memmove.c (100%)
       rename nuttx/{lib => libc}/string/lib_memset.c (100%)
       rename nuttx/{lib => libc}/string/lib_skipspace.c (100%)
       rename nuttx/{lib => libc}/string/lib_strcasecmp.c (100%)
       rename nuttx/{lib => libc}/string/lib_strcasestr.c (100%)
       rename nuttx/{lib => libc}/string/lib_strcat.c (100%)
       rename nuttx/{lib => libc}/string/lib_strchr.c (100%)
       rename nuttx/{lib => libc}/string/lib_strcmp.c (100%)
       rename nuttx/{lib => libc}/string/lib_strcpy.c (100%)
       rename nuttx/{lib => libc}/string/lib_strcspn.c (100%)
       rename nuttx/{lib => libc}/string/lib_strdup.c (100%)
       rename nuttx/{lib => libc}/string/lib_strerror.c (100%)
       rename nuttx/{lib => libc}/string/lib_strlen.c (100%)
       rename nuttx/{lib => libc}/string/lib_strncasecmp.c (100%)
       rename nuttx/{lib => libc}/string/lib_strncat.c (100%)
       rename nuttx/{lib => libc}/string/lib_strncmp.c (100%)
       rename nuttx/{lib => libc}/string/lib_strncpy.c (100%)
       rename nuttx/{lib => libc}/string/lib_strndup.c (100%)
       rename nuttx/{lib => libc}/string/lib_strnlen.c (100%)
       rename nuttx/{lib => libc}/string/lib_strpbrk.c (100%)
       rename nuttx/{lib => libc}/string/lib_strrchr.c (100%)
       rename nuttx/{lib => libc}/string/lib_strspn.c (100%)
       rename nuttx/{lib => libc}/string/lib_strstr.c (100%)
       rename nuttx/{lib => libc}/string/lib_strtod.c (100%)
       rename nuttx/{lib => libc}/string/lib_strtok.c (100%)
       rename nuttx/{lib => libc}/string/lib_strtokr.c (100%)
       rename nuttx/{lib => libc}/string/lib_strtol.c (100%)
       rename nuttx/{lib => libc}/string/lib_strtoll.c (100%)
       rename nuttx/{lib => libc}/string/lib_strtoul.c (100%)
       rename nuttx/{lib => libc}/string/lib_strtoull.c (100%)
       rename nuttx/{lib => libc}/string/lib_vikmemcpy.c (100%)
       rename nuttx/{lib => libc}/termios/Make.defs (100%)
       rename nuttx/{lib => libc}/termios/lib_cfgetspeed.c (100%)
       rename nuttx/{lib => libc}/termios/lib_cfsetspeed.c (100%)
       rename nuttx/{lib => libc}/termios/lib_tcflush.c (100%)
       rename nuttx/{lib => libc}/termios/lib_tcgetattr.c (100%)
       rename nuttx/{lib => libc}/termios/lib_tcsetattr.c (100%)
       rename nuttx/{lib => libc}/time/Make.defs (100%)
       rename nuttx/{lib => libc}/time/lib_calendar2utc.c (100%)
       rename nuttx/{lib => libc}/time/lib_daysbeforemonth.c (100%)
       rename nuttx/{lib => libc}/time/lib_gmtime.c (100%)
       rename nuttx/{lib => libc}/time/lib_gmtimer.c (100%)
       rename nuttx/{lib => libc}/time/lib_isleapyear.c (100%)
       rename nuttx/{lib => libc}/time/lib_mktime.c (100%)
       rename nuttx/{lib => libc}/time/lib_strftime.c (100%)
       rename nuttx/{lib => libc}/time/lib_time.c (100%)
       rename nuttx/{lib => libc}/unistd/Make.defs (100%)
       rename nuttx/{lib => libc}/unistd/lib_chdir.c (100%)
       rename nuttx/{lib => libc}/unistd/lib_getcwd.c (100%)
       rename nuttx/{lib => libc}/unistd/lib_getopt.c (100%)
       rename nuttx/{lib => libc}/unistd/lib_getoptargp.c (100%)
       rename nuttx/{lib => libc}/unistd/lib_getoptindp.c (100%)
       rename nuttx/{lib => libc}/unistd/lib_getoptoptp.c (100%)
      
      diff --git a/nuttx/lib/Kconfig b/nuttx/libc/Kconfig
      similarity index 100%
      rename from nuttx/lib/Kconfig
      rename to nuttx/libc/Kconfig
      diff --git a/nuttx/lib/Makefile b/nuttx/libc/Makefile
      similarity index 100%
      rename from nuttx/lib/Makefile
      rename to nuttx/libc/Makefile
      diff --git a/nuttx/lib/README.txt b/nuttx/libc/README.txt
      similarity index 100%
      rename from nuttx/lib/README.txt
      rename to nuttx/libc/README.txt
      diff --git a/nuttx/lib/dirent/Make.defs b/nuttx/libc/dirent/Make.defs
      similarity index 100%
      rename from nuttx/lib/dirent/Make.defs
      rename to nuttx/libc/dirent/Make.defs
      diff --git a/nuttx/lib/dirent/lib_readdirr.c b/nuttx/libc/dirent/lib_readdirr.c
      similarity index 100%
      rename from nuttx/lib/dirent/lib_readdirr.c
      rename to nuttx/libc/dirent/lib_readdirr.c
      diff --git a/nuttx/lib/dirent/lib_telldir.c b/nuttx/libc/dirent/lib_telldir.c
      similarity index 100%
      rename from nuttx/lib/dirent/lib_telldir.c
      rename to nuttx/libc/dirent/lib_telldir.c
      diff --git a/nuttx/lib/fixedmath/Make.defs b/nuttx/libc/fixedmath/Make.defs
      similarity index 100%
      rename from nuttx/lib/fixedmath/Make.defs
      rename to nuttx/libc/fixedmath/Make.defs
      diff --git a/nuttx/lib/fixedmath/lib_b16atan2.c b/nuttx/libc/fixedmath/lib_b16atan2.c
      similarity index 100%
      rename from nuttx/lib/fixedmath/lib_b16atan2.c
      rename to nuttx/libc/fixedmath/lib_b16atan2.c
      diff --git a/nuttx/lib/fixedmath/lib_b16cos.c b/nuttx/libc/fixedmath/lib_b16cos.c
      similarity index 100%
      rename from nuttx/lib/fixedmath/lib_b16cos.c
      rename to nuttx/libc/fixedmath/lib_b16cos.c
      diff --git a/nuttx/lib/fixedmath/lib_b16sin.c b/nuttx/libc/fixedmath/lib_b16sin.c
      similarity index 100%
      rename from nuttx/lib/fixedmath/lib_b16sin.c
      rename to nuttx/libc/fixedmath/lib_b16sin.c
      diff --git a/nuttx/lib/fixedmath/lib_fixedmath.c b/nuttx/libc/fixedmath/lib_fixedmath.c
      similarity index 100%
      rename from nuttx/lib/fixedmath/lib_fixedmath.c
      rename to nuttx/libc/fixedmath/lib_fixedmath.c
      diff --git a/nuttx/lib/fixedmath/lib_rint.c b/nuttx/libc/fixedmath/lib_rint.c
      similarity index 100%
      rename from nuttx/lib/fixedmath/lib_rint.c
      rename to nuttx/libc/fixedmath/lib_rint.c
      diff --git a/nuttx/lib/lib.csv b/nuttx/libc/lib.csv
      similarity index 100%
      rename from nuttx/lib/lib.csv
      rename to nuttx/libc/lib.csv
      diff --git a/nuttx/lib/lib_internal.h b/nuttx/libc/lib_internal.h
      similarity index 100%
      rename from nuttx/lib/lib_internal.h
      rename to nuttx/libc/lib_internal.h
      diff --git a/nuttx/lib/libgen/Make.defs b/nuttx/libc/libgen/Make.defs
      similarity index 100%
      rename from nuttx/lib/libgen/Make.defs
      rename to nuttx/libc/libgen/Make.defs
      diff --git a/nuttx/lib/libgen/lib_basename.c b/nuttx/libc/libgen/lib_basename.c
      similarity index 100%
      rename from nuttx/lib/libgen/lib_basename.c
      rename to nuttx/libc/libgen/lib_basename.c
      diff --git a/nuttx/lib/libgen/lib_dirname.c b/nuttx/libc/libgen/lib_dirname.c
      similarity index 100%
      rename from nuttx/lib/libgen/lib_dirname.c
      rename to nuttx/libc/libgen/lib_dirname.c
      diff --git a/nuttx/lib/math/Kconfig b/nuttx/libc/math/Kconfig
      similarity index 100%
      rename from nuttx/lib/math/Kconfig
      rename to nuttx/libc/math/Kconfig
      diff --git a/nuttx/lib/math/Make.defs b/nuttx/libc/math/Make.defs
      similarity index 100%
      rename from nuttx/lib/math/Make.defs
      rename to nuttx/libc/math/Make.defs
      diff --git a/nuttx/lib/math/lib_acos.c b/nuttx/libc/math/lib_acos.c
      similarity index 100%
      rename from nuttx/lib/math/lib_acos.c
      rename to nuttx/libc/math/lib_acos.c
      diff --git a/nuttx/lib/math/lib_acosf.c b/nuttx/libc/math/lib_acosf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_acosf.c
      rename to nuttx/libc/math/lib_acosf.c
      diff --git a/nuttx/lib/math/lib_acosl.c b/nuttx/libc/math/lib_acosl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_acosl.c
      rename to nuttx/libc/math/lib_acosl.c
      diff --git a/nuttx/lib/math/lib_asin.c b/nuttx/libc/math/lib_asin.c
      similarity index 100%
      rename from nuttx/lib/math/lib_asin.c
      rename to nuttx/libc/math/lib_asin.c
      diff --git a/nuttx/lib/math/lib_asinf.c b/nuttx/libc/math/lib_asinf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_asinf.c
      rename to nuttx/libc/math/lib_asinf.c
      diff --git a/nuttx/lib/math/lib_asinl.c b/nuttx/libc/math/lib_asinl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_asinl.c
      rename to nuttx/libc/math/lib_asinl.c
      diff --git a/nuttx/lib/math/lib_atan.c b/nuttx/libc/math/lib_atan.c
      similarity index 100%
      rename from nuttx/lib/math/lib_atan.c
      rename to nuttx/libc/math/lib_atan.c
      diff --git a/nuttx/lib/math/lib_atan2.c b/nuttx/libc/math/lib_atan2.c
      similarity index 100%
      rename from nuttx/lib/math/lib_atan2.c
      rename to nuttx/libc/math/lib_atan2.c
      diff --git a/nuttx/lib/math/lib_atan2f.c b/nuttx/libc/math/lib_atan2f.c
      similarity index 100%
      rename from nuttx/lib/math/lib_atan2f.c
      rename to nuttx/libc/math/lib_atan2f.c
      diff --git a/nuttx/lib/math/lib_atan2l.c b/nuttx/libc/math/lib_atan2l.c
      similarity index 100%
      rename from nuttx/lib/math/lib_atan2l.c
      rename to nuttx/libc/math/lib_atan2l.c
      diff --git a/nuttx/lib/math/lib_atanf.c b/nuttx/libc/math/lib_atanf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_atanf.c
      rename to nuttx/libc/math/lib_atanf.c
      diff --git a/nuttx/lib/math/lib_atanl.c b/nuttx/libc/math/lib_atanl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_atanl.c
      rename to nuttx/libc/math/lib_atanl.c
      diff --git a/nuttx/lib/math/lib_ceil.c b/nuttx/libc/math/lib_ceil.c
      similarity index 100%
      rename from nuttx/lib/math/lib_ceil.c
      rename to nuttx/libc/math/lib_ceil.c
      diff --git a/nuttx/lib/math/lib_ceilf.c b/nuttx/libc/math/lib_ceilf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_ceilf.c
      rename to nuttx/libc/math/lib_ceilf.c
      diff --git a/nuttx/lib/math/lib_ceill.c b/nuttx/libc/math/lib_ceill.c
      similarity index 100%
      rename from nuttx/lib/math/lib_ceill.c
      rename to nuttx/libc/math/lib_ceill.c
      diff --git a/nuttx/lib/math/lib_cos.c b/nuttx/libc/math/lib_cos.c
      similarity index 100%
      rename from nuttx/lib/math/lib_cos.c
      rename to nuttx/libc/math/lib_cos.c
      diff --git a/nuttx/lib/math/lib_cosf.c b/nuttx/libc/math/lib_cosf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_cosf.c
      rename to nuttx/libc/math/lib_cosf.c
      diff --git a/nuttx/lib/math/lib_cosh.c b/nuttx/libc/math/lib_cosh.c
      similarity index 100%
      rename from nuttx/lib/math/lib_cosh.c
      rename to nuttx/libc/math/lib_cosh.c
      diff --git a/nuttx/lib/math/lib_coshf.c b/nuttx/libc/math/lib_coshf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_coshf.c
      rename to nuttx/libc/math/lib_coshf.c
      diff --git a/nuttx/lib/math/lib_coshl.c b/nuttx/libc/math/lib_coshl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_coshl.c
      rename to nuttx/libc/math/lib_coshl.c
      diff --git a/nuttx/lib/math/lib_cosl.c b/nuttx/libc/math/lib_cosl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_cosl.c
      rename to nuttx/libc/math/lib_cosl.c
      diff --git a/nuttx/lib/math/lib_exp.c b/nuttx/libc/math/lib_exp.c
      similarity index 100%
      rename from nuttx/lib/math/lib_exp.c
      rename to nuttx/libc/math/lib_exp.c
      diff --git a/nuttx/lib/math/lib_expf.c b/nuttx/libc/math/lib_expf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_expf.c
      rename to nuttx/libc/math/lib_expf.c
      diff --git a/nuttx/lib/math/lib_expl.c b/nuttx/libc/math/lib_expl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_expl.c
      rename to nuttx/libc/math/lib_expl.c
      diff --git a/nuttx/lib/math/lib_fabs.c b/nuttx/libc/math/lib_fabs.c
      similarity index 100%
      rename from nuttx/lib/math/lib_fabs.c
      rename to nuttx/libc/math/lib_fabs.c
      diff --git a/nuttx/lib/math/lib_fabsf.c b/nuttx/libc/math/lib_fabsf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_fabsf.c
      rename to nuttx/libc/math/lib_fabsf.c
      diff --git a/nuttx/lib/math/lib_fabsl.c b/nuttx/libc/math/lib_fabsl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_fabsl.c
      rename to nuttx/libc/math/lib_fabsl.c
      diff --git a/nuttx/lib/math/lib_floor.c b/nuttx/libc/math/lib_floor.c
      similarity index 100%
      rename from nuttx/lib/math/lib_floor.c
      rename to nuttx/libc/math/lib_floor.c
      diff --git a/nuttx/lib/math/lib_floorf.c b/nuttx/libc/math/lib_floorf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_floorf.c
      rename to nuttx/libc/math/lib_floorf.c
      diff --git a/nuttx/lib/math/lib_floorl.c b/nuttx/libc/math/lib_floorl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_floorl.c
      rename to nuttx/libc/math/lib_floorl.c
      diff --git a/nuttx/lib/math/lib_fmod.c b/nuttx/libc/math/lib_fmod.c
      similarity index 100%
      rename from nuttx/lib/math/lib_fmod.c
      rename to nuttx/libc/math/lib_fmod.c
      diff --git a/nuttx/lib/math/lib_fmodf.c b/nuttx/libc/math/lib_fmodf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_fmodf.c
      rename to nuttx/libc/math/lib_fmodf.c
      diff --git a/nuttx/lib/math/lib_fmodl.c b/nuttx/libc/math/lib_fmodl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_fmodl.c
      rename to nuttx/libc/math/lib_fmodl.c
      diff --git a/nuttx/lib/math/lib_frexp.c b/nuttx/libc/math/lib_frexp.c
      similarity index 100%
      rename from nuttx/lib/math/lib_frexp.c
      rename to nuttx/libc/math/lib_frexp.c
      diff --git a/nuttx/lib/math/lib_frexpf.c b/nuttx/libc/math/lib_frexpf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_frexpf.c
      rename to nuttx/libc/math/lib_frexpf.c
      diff --git a/nuttx/lib/math/lib_frexpl.c b/nuttx/libc/math/lib_frexpl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_frexpl.c
      rename to nuttx/libc/math/lib_frexpl.c
      diff --git a/nuttx/lib/math/lib_ldexp.c b/nuttx/libc/math/lib_ldexp.c
      similarity index 100%
      rename from nuttx/lib/math/lib_ldexp.c
      rename to nuttx/libc/math/lib_ldexp.c
      diff --git a/nuttx/lib/math/lib_ldexpf.c b/nuttx/libc/math/lib_ldexpf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_ldexpf.c
      rename to nuttx/libc/math/lib_ldexpf.c
      diff --git a/nuttx/lib/math/lib_ldexpl.c b/nuttx/libc/math/lib_ldexpl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_ldexpl.c
      rename to nuttx/libc/math/lib_ldexpl.c
      diff --git a/nuttx/lib/math/lib_libexpi.c b/nuttx/libc/math/lib_libexpi.c
      similarity index 100%
      rename from nuttx/lib/math/lib_libexpi.c
      rename to nuttx/libc/math/lib_libexpi.c
      diff --git a/nuttx/lib/math/lib_libsqrtapprox.c b/nuttx/libc/math/lib_libsqrtapprox.c
      similarity index 100%
      rename from nuttx/lib/math/lib_libsqrtapprox.c
      rename to nuttx/libc/math/lib_libsqrtapprox.c
      diff --git a/nuttx/lib/math/lib_log.c b/nuttx/libc/math/lib_log.c
      similarity index 100%
      rename from nuttx/lib/math/lib_log.c
      rename to nuttx/libc/math/lib_log.c
      diff --git a/nuttx/lib/math/lib_log10.c b/nuttx/libc/math/lib_log10.c
      similarity index 100%
      rename from nuttx/lib/math/lib_log10.c
      rename to nuttx/libc/math/lib_log10.c
      diff --git a/nuttx/lib/math/lib_log10f.c b/nuttx/libc/math/lib_log10f.c
      similarity index 100%
      rename from nuttx/lib/math/lib_log10f.c
      rename to nuttx/libc/math/lib_log10f.c
      diff --git a/nuttx/lib/math/lib_log10l.c b/nuttx/libc/math/lib_log10l.c
      similarity index 100%
      rename from nuttx/lib/math/lib_log10l.c
      rename to nuttx/libc/math/lib_log10l.c
      diff --git a/nuttx/lib/math/lib_log2.c b/nuttx/libc/math/lib_log2.c
      similarity index 100%
      rename from nuttx/lib/math/lib_log2.c
      rename to nuttx/libc/math/lib_log2.c
      diff --git a/nuttx/lib/math/lib_log2f.c b/nuttx/libc/math/lib_log2f.c
      similarity index 100%
      rename from nuttx/lib/math/lib_log2f.c
      rename to nuttx/libc/math/lib_log2f.c
      diff --git a/nuttx/lib/math/lib_log2l.c b/nuttx/libc/math/lib_log2l.c
      similarity index 100%
      rename from nuttx/lib/math/lib_log2l.c
      rename to nuttx/libc/math/lib_log2l.c
      diff --git a/nuttx/lib/math/lib_logf.c b/nuttx/libc/math/lib_logf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_logf.c
      rename to nuttx/libc/math/lib_logf.c
      diff --git a/nuttx/lib/math/lib_logl.c b/nuttx/libc/math/lib_logl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_logl.c
      rename to nuttx/libc/math/lib_logl.c
      diff --git a/nuttx/lib/math/lib_modf.c b/nuttx/libc/math/lib_modf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_modf.c
      rename to nuttx/libc/math/lib_modf.c
      diff --git a/nuttx/lib/math/lib_modff.c b/nuttx/libc/math/lib_modff.c
      similarity index 100%
      rename from nuttx/lib/math/lib_modff.c
      rename to nuttx/libc/math/lib_modff.c
      diff --git a/nuttx/lib/math/lib_modfl.c b/nuttx/libc/math/lib_modfl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_modfl.c
      rename to nuttx/libc/math/lib_modfl.c
      diff --git a/nuttx/lib/math/lib_pow.c b/nuttx/libc/math/lib_pow.c
      similarity index 100%
      rename from nuttx/lib/math/lib_pow.c
      rename to nuttx/libc/math/lib_pow.c
      diff --git a/nuttx/lib/math/lib_powf.c b/nuttx/libc/math/lib_powf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_powf.c
      rename to nuttx/libc/math/lib_powf.c
      diff --git a/nuttx/lib/math/lib_powl.c b/nuttx/libc/math/lib_powl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_powl.c
      rename to nuttx/libc/math/lib_powl.c
      diff --git a/nuttx/lib/math/lib_sin.c b/nuttx/libc/math/lib_sin.c
      similarity index 100%
      rename from nuttx/lib/math/lib_sin.c
      rename to nuttx/libc/math/lib_sin.c
      diff --git a/nuttx/lib/math/lib_sinf.c b/nuttx/libc/math/lib_sinf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_sinf.c
      rename to nuttx/libc/math/lib_sinf.c
      diff --git a/nuttx/lib/math/lib_sinh.c b/nuttx/libc/math/lib_sinh.c
      similarity index 100%
      rename from nuttx/lib/math/lib_sinh.c
      rename to nuttx/libc/math/lib_sinh.c
      diff --git a/nuttx/lib/math/lib_sinhf.c b/nuttx/libc/math/lib_sinhf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_sinhf.c
      rename to nuttx/libc/math/lib_sinhf.c
      diff --git a/nuttx/lib/math/lib_sinhl.c b/nuttx/libc/math/lib_sinhl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_sinhl.c
      rename to nuttx/libc/math/lib_sinhl.c
      diff --git a/nuttx/lib/math/lib_sinl.c b/nuttx/libc/math/lib_sinl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_sinl.c
      rename to nuttx/libc/math/lib_sinl.c
      diff --git a/nuttx/lib/math/lib_sqrt.c b/nuttx/libc/math/lib_sqrt.c
      similarity index 100%
      rename from nuttx/lib/math/lib_sqrt.c
      rename to nuttx/libc/math/lib_sqrt.c
      diff --git a/nuttx/lib/math/lib_sqrtf.c b/nuttx/libc/math/lib_sqrtf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_sqrtf.c
      rename to nuttx/libc/math/lib_sqrtf.c
      diff --git a/nuttx/lib/math/lib_sqrtl.c b/nuttx/libc/math/lib_sqrtl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_sqrtl.c
      rename to nuttx/libc/math/lib_sqrtl.c
      diff --git a/nuttx/lib/math/lib_tan.c b/nuttx/libc/math/lib_tan.c
      similarity index 100%
      rename from nuttx/lib/math/lib_tan.c
      rename to nuttx/libc/math/lib_tan.c
      diff --git a/nuttx/lib/math/lib_tanf.c b/nuttx/libc/math/lib_tanf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_tanf.c
      rename to nuttx/libc/math/lib_tanf.c
      diff --git a/nuttx/lib/math/lib_tanh.c b/nuttx/libc/math/lib_tanh.c
      similarity index 100%
      rename from nuttx/lib/math/lib_tanh.c
      rename to nuttx/libc/math/lib_tanh.c
      diff --git a/nuttx/lib/math/lib_tanhf.c b/nuttx/libc/math/lib_tanhf.c
      similarity index 100%
      rename from nuttx/lib/math/lib_tanhf.c
      rename to nuttx/libc/math/lib_tanhf.c
      diff --git a/nuttx/lib/math/lib_tanhl.c b/nuttx/libc/math/lib_tanhl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_tanhl.c
      rename to nuttx/libc/math/lib_tanhl.c
      diff --git a/nuttx/lib/math/lib_tanl.c b/nuttx/libc/math/lib_tanl.c
      similarity index 100%
      rename from nuttx/lib/math/lib_tanl.c
      rename to nuttx/libc/math/lib_tanl.c
      diff --git a/nuttx/lib/misc/Make.defs b/nuttx/libc/misc/Make.defs
      similarity index 100%
      rename from nuttx/lib/misc/Make.defs
      rename to nuttx/libc/misc/Make.defs
      diff --git a/nuttx/lib/misc/lib_crc32.c b/nuttx/libc/misc/lib_crc32.c
      similarity index 100%
      rename from nuttx/lib/misc/lib_crc32.c
      rename to nuttx/libc/misc/lib_crc32.c
      diff --git a/nuttx/lib/misc/lib_dbg.c b/nuttx/libc/misc/lib_dbg.c
      similarity index 100%
      rename from nuttx/lib/misc/lib_dbg.c
      rename to nuttx/libc/misc/lib_dbg.c
      diff --git a/nuttx/lib/misc/lib_dumpbuffer.c b/nuttx/libc/misc/lib_dumpbuffer.c
      similarity index 100%
      rename from nuttx/lib/misc/lib_dumpbuffer.c
      rename to nuttx/libc/misc/lib_dumpbuffer.c
      diff --git a/nuttx/lib/misc/lib_filesem.c b/nuttx/libc/misc/lib_filesem.c
      similarity index 100%
      rename from nuttx/lib/misc/lib_filesem.c
      rename to nuttx/libc/misc/lib_filesem.c
      diff --git a/nuttx/lib/misc/lib_init.c b/nuttx/libc/misc/lib_init.c
      similarity index 100%
      rename from nuttx/lib/misc/lib_init.c
      rename to nuttx/libc/misc/lib_init.c
      diff --git a/nuttx/lib/misc/lib_match.c b/nuttx/libc/misc/lib_match.c
      similarity index 100%
      rename from nuttx/lib/misc/lib_match.c
      rename to nuttx/libc/misc/lib_match.c
      diff --git a/nuttx/lib/misc/lib_sendfile.c b/nuttx/libc/misc/lib_sendfile.c
      similarity index 100%
      rename from nuttx/lib/misc/lib_sendfile.c
      rename to nuttx/libc/misc/lib_sendfile.c
      diff --git a/nuttx/lib/misc/lib_streamsem.c b/nuttx/libc/misc/lib_streamsem.c
      similarity index 100%
      rename from nuttx/lib/misc/lib_streamsem.c
      rename to nuttx/libc/misc/lib_streamsem.c
      diff --git a/nuttx/lib/mqueue/Make.defs b/nuttx/libc/mqueue/Make.defs
      similarity index 100%
      rename from nuttx/lib/mqueue/Make.defs
      rename to nuttx/libc/mqueue/Make.defs
      diff --git a/nuttx/lib/mqueue/mq_getattr.c b/nuttx/libc/mqueue/mq_getattr.c
      similarity index 100%
      rename from nuttx/lib/mqueue/mq_getattr.c
      rename to nuttx/libc/mqueue/mq_getattr.c
      diff --git a/nuttx/lib/mqueue/mq_setattr.c b/nuttx/libc/mqueue/mq_setattr.c
      similarity index 100%
      rename from nuttx/lib/mqueue/mq_setattr.c
      rename to nuttx/libc/mqueue/mq_setattr.c
      diff --git a/nuttx/lib/net/Make.defs b/nuttx/libc/net/Make.defs
      similarity index 100%
      rename from nuttx/lib/net/Make.defs
      rename to nuttx/libc/net/Make.defs
      diff --git a/nuttx/lib/net/lib_etherntoa.c b/nuttx/libc/net/lib_etherntoa.c
      similarity index 100%
      rename from nuttx/lib/net/lib_etherntoa.c
      rename to nuttx/libc/net/lib_etherntoa.c
      diff --git a/nuttx/lib/net/lib_htonl.c b/nuttx/libc/net/lib_htonl.c
      similarity index 100%
      rename from nuttx/lib/net/lib_htonl.c
      rename to nuttx/libc/net/lib_htonl.c
      diff --git a/nuttx/lib/net/lib_htons.c b/nuttx/libc/net/lib_htons.c
      similarity index 100%
      rename from nuttx/lib/net/lib_htons.c
      rename to nuttx/libc/net/lib_htons.c
      diff --git a/nuttx/lib/net/lib_inetaddr.c b/nuttx/libc/net/lib_inetaddr.c
      similarity index 100%
      rename from nuttx/lib/net/lib_inetaddr.c
      rename to nuttx/libc/net/lib_inetaddr.c
      diff --git a/nuttx/lib/net/lib_inetntoa.c b/nuttx/libc/net/lib_inetntoa.c
      similarity index 100%
      rename from nuttx/lib/net/lib_inetntoa.c
      rename to nuttx/libc/net/lib_inetntoa.c
      diff --git a/nuttx/lib/net/lib_inetntop.c b/nuttx/libc/net/lib_inetntop.c
      similarity index 100%
      rename from nuttx/lib/net/lib_inetntop.c
      rename to nuttx/libc/net/lib_inetntop.c
      diff --git a/nuttx/lib/net/lib_inetpton.c b/nuttx/libc/net/lib_inetpton.c
      similarity index 100%
      rename from nuttx/lib/net/lib_inetpton.c
      rename to nuttx/libc/net/lib_inetpton.c
      diff --git a/nuttx/lib/pthread/Make.defs b/nuttx/libc/pthread/Make.defs
      similarity index 100%
      rename from nuttx/lib/pthread/Make.defs
      rename to nuttx/libc/pthread/Make.defs
      diff --git a/nuttx/lib/pthread/pthread_attrdestroy.c b/nuttx/libc/pthread/pthread_attrdestroy.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_attrdestroy.c
      rename to nuttx/libc/pthread/pthread_attrdestroy.c
      diff --git a/nuttx/lib/pthread/pthread_attrgetinheritsched.c b/nuttx/libc/pthread/pthread_attrgetinheritsched.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_attrgetinheritsched.c
      rename to nuttx/libc/pthread/pthread_attrgetinheritsched.c
      diff --git a/nuttx/lib/pthread/pthread_attrgetschedparam.c b/nuttx/libc/pthread/pthread_attrgetschedparam.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_attrgetschedparam.c
      rename to nuttx/libc/pthread/pthread_attrgetschedparam.c
      diff --git a/nuttx/lib/pthread/pthread_attrgetschedpolicy.c b/nuttx/libc/pthread/pthread_attrgetschedpolicy.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_attrgetschedpolicy.c
      rename to nuttx/libc/pthread/pthread_attrgetschedpolicy.c
      diff --git a/nuttx/lib/pthread/pthread_attrgetstacksize.c b/nuttx/libc/pthread/pthread_attrgetstacksize.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_attrgetstacksize.c
      rename to nuttx/libc/pthread/pthread_attrgetstacksize.c
      diff --git a/nuttx/lib/pthread/pthread_attrinit.c b/nuttx/libc/pthread/pthread_attrinit.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_attrinit.c
      rename to nuttx/libc/pthread/pthread_attrinit.c
      diff --git a/nuttx/lib/pthread/pthread_attrsetinheritsched.c b/nuttx/libc/pthread/pthread_attrsetinheritsched.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_attrsetinheritsched.c
      rename to nuttx/libc/pthread/pthread_attrsetinheritsched.c
      diff --git a/nuttx/lib/pthread/pthread_attrsetschedparam.c b/nuttx/libc/pthread/pthread_attrsetschedparam.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_attrsetschedparam.c
      rename to nuttx/libc/pthread/pthread_attrsetschedparam.c
      diff --git a/nuttx/lib/pthread/pthread_attrsetschedpolicy.c b/nuttx/libc/pthread/pthread_attrsetschedpolicy.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_attrsetschedpolicy.c
      rename to nuttx/libc/pthread/pthread_attrsetschedpolicy.c
      diff --git a/nuttx/lib/pthread/pthread_attrsetstacksize.c b/nuttx/libc/pthread/pthread_attrsetstacksize.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_attrsetstacksize.c
      rename to nuttx/libc/pthread/pthread_attrsetstacksize.c
      diff --git a/nuttx/lib/pthread/pthread_barrierattrdestroy.c b/nuttx/libc/pthread/pthread_barrierattrdestroy.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_barrierattrdestroy.c
      rename to nuttx/libc/pthread/pthread_barrierattrdestroy.c
      diff --git a/nuttx/lib/pthread/pthread_barrierattrgetpshared.c b/nuttx/libc/pthread/pthread_barrierattrgetpshared.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_barrierattrgetpshared.c
      rename to nuttx/libc/pthread/pthread_barrierattrgetpshared.c
      diff --git a/nuttx/lib/pthread/pthread_barrierattrinit.c b/nuttx/libc/pthread/pthread_barrierattrinit.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_barrierattrinit.c
      rename to nuttx/libc/pthread/pthread_barrierattrinit.c
      diff --git a/nuttx/lib/pthread/pthread_barrierattrsetpshared.c b/nuttx/libc/pthread/pthread_barrierattrsetpshared.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_barrierattrsetpshared.c
      rename to nuttx/libc/pthread/pthread_barrierattrsetpshared.c
      diff --git a/nuttx/lib/pthread/pthread_condattrdestroy.c b/nuttx/libc/pthread/pthread_condattrdestroy.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_condattrdestroy.c
      rename to nuttx/libc/pthread/pthread_condattrdestroy.c
      diff --git a/nuttx/lib/pthread/pthread_condattrinit.c b/nuttx/libc/pthread/pthread_condattrinit.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_condattrinit.c
      rename to nuttx/libc/pthread/pthread_condattrinit.c
      diff --git a/nuttx/lib/pthread/pthread_mutexattrdestroy.c b/nuttx/libc/pthread/pthread_mutexattrdestroy.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_mutexattrdestroy.c
      rename to nuttx/libc/pthread/pthread_mutexattrdestroy.c
      diff --git a/nuttx/lib/pthread/pthread_mutexattrgetpshared.c b/nuttx/libc/pthread/pthread_mutexattrgetpshared.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_mutexattrgetpshared.c
      rename to nuttx/libc/pthread/pthread_mutexattrgetpshared.c
      diff --git a/nuttx/lib/pthread/pthread_mutexattrgettype.c b/nuttx/libc/pthread/pthread_mutexattrgettype.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_mutexattrgettype.c
      rename to nuttx/libc/pthread/pthread_mutexattrgettype.c
      diff --git a/nuttx/lib/pthread/pthread_mutexattrinit.c b/nuttx/libc/pthread/pthread_mutexattrinit.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_mutexattrinit.c
      rename to nuttx/libc/pthread/pthread_mutexattrinit.c
      diff --git a/nuttx/lib/pthread/pthread_mutexattrsetpshared.c b/nuttx/libc/pthread/pthread_mutexattrsetpshared.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_mutexattrsetpshared.c
      rename to nuttx/libc/pthread/pthread_mutexattrsetpshared.c
      diff --git a/nuttx/lib/pthread/pthread_mutexattrsettype.c b/nuttx/libc/pthread/pthread_mutexattrsettype.c
      similarity index 100%
      rename from nuttx/lib/pthread/pthread_mutexattrsettype.c
      rename to nuttx/libc/pthread/pthread_mutexattrsettype.c
      diff --git a/nuttx/lib/queue/Make.defs b/nuttx/libc/queue/Make.defs
      similarity index 100%
      rename from nuttx/lib/queue/Make.defs
      rename to nuttx/libc/queue/Make.defs
      diff --git a/nuttx/lib/queue/dq_addafter.c b/nuttx/libc/queue/dq_addafter.c
      similarity index 100%
      rename from nuttx/lib/queue/dq_addafter.c
      rename to nuttx/libc/queue/dq_addafter.c
      diff --git a/nuttx/lib/queue/dq_addbefore.c b/nuttx/libc/queue/dq_addbefore.c
      similarity index 100%
      rename from nuttx/lib/queue/dq_addbefore.c
      rename to nuttx/libc/queue/dq_addbefore.c
      diff --git a/nuttx/lib/queue/dq_addfirst.c b/nuttx/libc/queue/dq_addfirst.c
      similarity index 100%
      rename from nuttx/lib/queue/dq_addfirst.c
      rename to nuttx/libc/queue/dq_addfirst.c
      diff --git a/nuttx/lib/queue/dq_addlast.c b/nuttx/libc/queue/dq_addlast.c
      similarity index 100%
      rename from nuttx/lib/queue/dq_addlast.c
      rename to nuttx/libc/queue/dq_addlast.c
      diff --git a/nuttx/lib/queue/dq_rem.c b/nuttx/libc/queue/dq_rem.c
      similarity index 100%
      rename from nuttx/lib/queue/dq_rem.c
      rename to nuttx/libc/queue/dq_rem.c
      diff --git a/nuttx/lib/queue/dq_remfirst.c b/nuttx/libc/queue/dq_remfirst.c
      similarity index 100%
      rename from nuttx/lib/queue/dq_remfirst.c
      rename to nuttx/libc/queue/dq_remfirst.c
      diff --git a/nuttx/lib/queue/dq_remlast.c b/nuttx/libc/queue/dq_remlast.c
      similarity index 100%
      rename from nuttx/lib/queue/dq_remlast.c
      rename to nuttx/libc/queue/dq_remlast.c
      diff --git a/nuttx/lib/queue/sq_addafter.c b/nuttx/libc/queue/sq_addafter.c
      similarity index 100%
      rename from nuttx/lib/queue/sq_addafter.c
      rename to nuttx/libc/queue/sq_addafter.c
      diff --git a/nuttx/lib/queue/sq_addfirst.c b/nuttx/libc/queue/sq_addfirst.c
      similarity index 100%
      rename from nuttx/lib/queue/sq_addfirst.c
      rename to nuttx/libc/queue/sq_addfirst.c
      diff --git a/nuttx/lib/queue/sq_addlast.c b/nuttx/libc/queue/sq_addlast.c
      similarity index 100%
      rename from nuttx/lib/queue/sq_addlast.c
      rename to nuttx/libc/queue/sq_addlast.c
      diff --git a/nuttx/lib/queue/sq_rem.c b/nuttx/libc/queue/sq_rem.c
      similarity index 100%
      rename from nuttx/lib/queue/sq_rem.c
      rename to nuttx/libc/queue/sq_rem.c
      diff --git a/nuttx/lib/queue/sq_remafter.c b/nuttx/libc/queue/sq_remafter.c
      similarity index 100%
      rename from nuttx/lib/queue/sq_remafter.c
      rename to nuttx/libc/queue/sq_remafter.c
      diff --git a/nuttx/lib/queue/sq_remfirst.c b/nuttx/libc/queue/sq_remfirst.c
      similarity index 100%
      rename from nuttx/lib/queue/sq_remfirst.c
      rename to nuttx/libc/queue/sq_remfirst.c
      diff --git a/nuttx/lib/queue/sq_remlast.c b/nuttx/libc/queue/sq_remlast.c
      similarity index 100%
      rename from nuttx/lib/queue/sq_remlast.c
      rename to nuttx/libc/queue/sq_remlast.c
      diff --git a/nuttx/lib/sched/Make.defs b/nuttx/libc/sched/Make.defs
      similarity index 100%
      rename from nuttx/lib/sched/Make.defs
      rename to nuttx/libc/sched/Make.defs
      diff --git a/nuttx/lib/sched/sched_getprioritymax.c b/nuttx/libc/sched/sched_getprioritymax.c
      similarity index 100%
      rename from nuttx/lib/sched/sched_getprioritymax.c
      rename to nuttx/libc/sched/sched_getprioritymax.c
      diff --git a/nuttx/lib/sched/sched_getprioritymin.c b/nuttx/libc/sched/sched_getprioritymin.c
      similarity index 100%
      rename from nuttx/lib/sched/sched_getprioritymin.c
      rename to nuttx/libc/sched/sched_getprioritymin.c
      diff --git a/nuttx/lib/semaphore/Make.defs b/nuttx/libc/semaphore/Make.defs
      similarity index 100%
      rename from nuttx/lib/semaphore/Make.defs
      rename to nuttx/libc/semaphore/Make.defs
      diff --git a/nuttx/lib/semaphore/sem_getvalue.c b/nuttx/libc/semaphore/sem_getvalue.c
      similarity index 100%
      rename from nuttx/lib/semaphore/sem_getvalue.c
      rename to nuttx/libc/semaphore/sem_getvalue.c
      diff --git a/nuttx/lib/semaphore/sem_init.c b/nuttx/libc/semaphore/sem_init.c
      similarity index 100%
      rename from nuttx/lib/semaphore/sem_init.c
      rename to nuttx/libc/semaphore/sem_init.c
      diff --git a/nuttx/lib/signal/Make.defs b/nuttx/libc/signal/Make.defs
      similarity index 100%
      rename from nuttx/lib/signal/Make.defs
      rename to nuttx/libc/signal/Make.defs
      diff --git a/nuttx/lib/signal/sig_addset.c b/nuttx/libc/signal/sig_addset.c
      similarity index 100%
      rename from nuttx/lib/signal/sig_addset.c
      rename to nuttx/libc/signal/sig_addset.c
      diff --git a/nuttx/lib/signal/sig_delset.c b/nuttx/libc/signal/sig_delset.c
      similarity index 100%
      rename from nuttx/lib/signal/sig_delset.c
      rename to nuttx/libc/signal/sig_delset.c
      diff --git a/nuttx/lib/signal/sig_emptyset.c b/nuttx/libc/signal/sig_emptyset.c
      similarity index 100%
      rename from nuttx/lib/signal/sig_emptyset.c
      rename to nuttx/libc/signal/sig_emptyset.c
      diff --git a/nuttx/lib/signal/sig_fillset.c b/nuttx/libc/signal/sig_fillset.c
      similarity index 100%
      rename from nuttx/lib/signal/sig_fillset.c
      rename to nuttx/libc/signal/sig_fillset.c
      diff --git a/nuttx/lib/signal/sig_ismember.c b/nuttx/libc/signal/sig_ismember.c
      similarity index 100%
      rename from nuttx/lib/signal/sig_ismember.c
      rename to nuttx/libc/signal/sig_ismember.c
      diff --git a/nuttx/lib/stdio/Make.defs b/nuttx/libc/stdio/Make.defs
      similarity index 100%
      rename from nuttx/lib/stdio/Make.defs
      rename to nuttx/libc/stdio/Make.defs
      diff --git a/nuttx/lib/stdio/lib_asprintf.c b/nuttx/libc/stdio/lib_asprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_asprintf.c
      rename to nuttx/libc/stdio/lib_asprintf.c
      diff --git a/nuttx/lib/stdio/lib_avsprintf.c b/nuttx/libc/stdio/lib_avsprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_avsprintf.c
      rename to nuttx/libc/stdio/lib_avsprintf.c
      diff --git a/nuttx/lib/stdio/lib_clearerr.c b/nuttx/libc/stdio/lib_clearerr.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_clearerr.c
      rename to nuttx/libc/stdio/lib_clearerr.c
      diff --git a/nuttx/lib/stdio/lib_dtoa.c b/nuttx/libc/stdio/lib_dtoa.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_dtoa.c
      rename to nuttx/libc/stdio/lib_dtoa.c
      diff --git a/nuttx/lib/stdio/lib_fclose.c b/nuttx/libc/stdio/lib_fclose.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fclose.c
      rename to nuttx/libc/stdio/lib_fclose.c
      diff --git a/nuttx/lib/stdio/lib_feof.c b/nuttx/libc/stdio/lib_feof.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_feof.c
      rename to nuttx/libc/stdio/lib_feof.c
      diff --git a/nuttx/lib/stdio/lib_ferror.c b/nuttx/libc/stdio/lib_ferror.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_ferror.c
      rename to nuttx/libc/stdio/lib_ferror.c
      diff --git a/nuttx/lib/stdio/lib_fflush.c b/nuttx/libc/stdio/lib_fflush.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fflush.c
      rename to nuttx/libc/stdio/lib_fflush.c
      diff --git a/nuttx/lib/stdio/lib_fgetc.c b/nuttx/libc/stdio/lib_fgetc.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fgetc.c
      rename to nuttx/libc/stdio/lib_fgetc.c
      diff --git a/nuttx/lib/stdio/lib_fgetpos.c b/nuttx/libc/stdio/lib_fgetpos.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fgetpos.c
      rename to nuttx/libc/stdio/lib_fgetpos.c
      diff --git a/nuttx/lib/stdio/lib_fgets.c b/nuttx/libc/stdio/lib_fgets.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fgets.c
      rename to nuttx/libc/stdio/lib_fgets.c
      diff --git a/nuttx/lib/stdio/lib_fileno.c b/nuttx/libc/stdio/lib_fileno.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fileno.c
      rename to nuttx/libc/stdio/lib_fileno.c
      diff --git a/nuttx/lib/stdio/lib_fopen.c b/nuttx/libc/stdio/lib_fopen.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fopen.c
      rename to nuttx/libc/stdio/lib_fopen.c
      diff --git a/nuttx/lib/stdio/lib_fprintf.c b/nuttx/libc/stdio/lib_fprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fprintf.c
      rename to nuttx/libc/stdio/lib_fprintf.c
      diff --git a/nuttx/lib/stdio/lib_fputc.c b/nuttx/libc/stdio/lib_fputc.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fputc.c
      rename to nuttx/libc/stdio/lib_fputc.c
      diff --git a/nuttx/lib/stdio/lib_fputs.c b/nuttx/libc/stdio/lib_fputs.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fputs.c
      rename to nuttx/libc/stdio/lib_fputs.c
      diff --git a/nuttx/lib/stdio/lib_fread.c b/nuttx/libc/stdio/lib_fread.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fread.c
      rename to nuttx/libc/stdio/lib_fread.c
      diff --git a/nuttx/lib/stdio/lib_fseek.c b/nuttx/libc/stdio/lib_fseek.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fseek.c
      rename to nuttx/libc/stdio/lib_fseek.c
      diff --git a/nuttx/lib/stdio/lib_fsetpos.c b/nuttx/libc/stdio/lib_fsetpos.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fsetpos.c
      rename to nuttx/libc/stdio/lib_fsetpos.c
      diff --git a/nuttx/lib/stdio/lib_ftell.c b/nuttx/libc/stdio/lib_ftell.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_ftell.c
      rename to nuttx/libc/stdio/lib_ftell.c
      diff --git a/nuttx/lib/stdio/lib_fwrite.c b/nuttx/libc/stdio/lib_fwrite.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_fwrite.c
      rename to nuttx/libc/stdio/lib_fwrite.c
      diff --git a/nuttx/lib/stdio/lib_gets.c b/nuttx/libc/stdio/lib_gets.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_gets.c
      rename to nuttx/libc/stdio/lib_gets.c
      diff --git a/nuttx/lib/stdio/lib_libdtoa.c b/nuttx/libc/stdio/lib_libdtoa.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_libdtoa.c
      rename to nuttx/libc/stdio/lib_libdtoa.c
      diff --git a/nuttx/lib/stdio/lib_libfflush.c b/nuttx/libc/stdio/lib_libfflush.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_libfflush.c
      rename to nuttx/libc/stdio/lib_libfflush.c
      diff --git a/nuttx/lib/stdio/lib_libflushall.c b/nuttx/libc/stdio/lib_libflushall.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_libflushall.c
      rename to nuttx/libc/stdio/lib_libflushall.c
      diff --git a/nuttx/lib/stdio/lib_libfread.c b/nuttx/libc/stdio/lib_libfread.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_libfread.c
      rename to nuttx/libc/stdio/lib_libfread.c
      diff --git a/nuttx/lib/stdio/lib_libfwrite.c b/nuttx/libc/stdio/lib_libfwrite.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_libfwrite.c
      rename to nuttx/libc/stdio/lib_libfwrite.c
      diff --git a/nuttx/lib/stdio/lib_libnoflush.c b/nuttx/libc/stdio/lib_libnoflush.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_libnoflush.c
      rename to nuttx/libc/stdio/lib_libnoflush.c
      diff --git a/nuttx/lib/stdio/lib_libsprintf.c b/nuttx/libc/stdio/lib_libsprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_libsprintf.c
      rename to nuttx/libc/stdio/lib_libsprintf.c
      diff --git a/nuttx/lib/stdio/lib_libvsprintf.c b/nuttx/libc/stdio/lib_libvsprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_libvsprintf.c
      rename to nuttx/libc/stdio/lib_libvsprintf.c
      diff --git a/nuttx/lib/stdio/lib_lowinstream.c b/nuttx/libc/stdio/lib_lowinstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_lowinstream.c
      rename to nuttx/libc/stdio/lib_lowinstream.c
      diff --git a/nuttx/lib/stdio/lib_lowoutstream.c b/nuttx/libc/stdio/lib_lowoutstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_lowoutstream.c
      rename to nuttx/libc/stdio/lib_lowoutstream.c
      diff --git a/nuttx/lib/stdio/lib_lowprintf.c b/nuttx/libc/stdio/lib_lowprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_lowprintf.c
      rename to nuttx/libc/stdio/lib_lowprintf.c
      diff --git a/nuttx/lib/stdio/lib_meminstream.c b/nuttx/libc/stdio/lib_meminstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_meminstream.c
      rename to nuttx/libc/stdio/lib_meminstream.c
      diff --git a/nuttx/lib/stdio/lib_memoutstream.c b/nuttx/libc/stdio/lib_memoutstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_memoutstream.c
      rename to nuttx/libc/stdio/lib_memoutstream.c
      diff --git a/nuttx/lib/stdio/lib_nullinstream.c b/nuttx/libc/stdio/lib_nullinstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_nullinstream.c
      rename to nuttx/libc/stdio/lib_nullinstream.c
      diff --git a/nuttx/lib/stdio/lib_nulloutstream.c b/nuttx/libc/stdio/lib_nulloutstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_nulloutstream.c
      rename to nuttx/libc/stdio/lib_nulloutstream.c
      diff --git a/nuttx/lib/stdio/lib_perror.c b/nuttx/libc/stdio/lib_perror.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_perror.c
      rename to nuttx/libc/stdio/lib_perror.c
      diff --git a/nuttx/lib/stdio/lib_printf.c b/nuttx/libc/stdio/lib_printf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_printf.c
      rename to nuttx/libc/stdio/lib_printf.c
      diff --git a/nuttx/lib/stdio/lib_puts.c b/nuttx/libc/stdio/lib_puts.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_puts.c
      rename to nuttx/libc/stdio/lib_puts.c
      diff --git a/nuttx/lib/stdio/lib_rawinstream.c b/nuttx/libc/stdio/lib_rawinstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_rawinstream.c
      rename to nuttx/libc/stdio/lib_rawinstream.c
      diff --git a/nuttx/lib/stdio/lib_rawoutstream.c b/nuttx/libc/stdio/lib_rawoutstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_rawoutstream.c
      rename to nuttx/libc/stdio/lib_rawoutstream.c
      diff --git a/nuttx/lib/stdio/lib_rawprintf.c b/nuttx/libc/stdio/lib_rawprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_rawprintf.c
      rename to nuttx/libc/stdio/lib_rawprintf.c
      diff --git a/nuttx/lib/stdio/lib_rdflush.c b/nuttx/libc/stdio/lib_rdflush.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_rdflush.c
      rename to nuttx/libc/stdio/lib_rdflush.c
      diff --git a/nuttx/lib/stdio/lib_snprintf.c b/nuttx/libc/stdio/lib_snprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_snprintf.c
      rename to nuttx/libc/stdio/lib_snprintf.c
      diff --git a/nuttx/lib/stdio/lib_sprintf.c b/nuttx/libc/stdio/lib_sprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_sprintf.c
      rename to nuttx/libc/stdio/lib_sprintf.c
      diff --git a/nuttx/lib/stdio/lib_sscanf.c b/nuttx/libc/stdio/lib_sscanf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_sscanf.c
      rename to nuttx/libc/stdio/lib_sscanf.c
      diff --git a/nuttx/lib/stdio/lib_stdinstream.c b/nuttx/libc/stdio/lib_stdinstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_stdinstream.c
      rename to nuttx/libc/stdio/lib_stdinstream.c
      diff --git a/nuttx/lib/stdio/lib_stdoutstream.c b/nuttx/libc/stdio/lib_stdoutstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_stdoutstream.c
      rename to nuttx/libc/stdio/lib_stdoutstream.c
      diff --git a/nuttx/lib/stdio/lib_syslogstream.c b/nuttx/libc/stdio/lib_syslogstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_syslogstream.c
      rename to nuttx/libc/stdio/lib_syslogstream.c
      diff --git a/nuttx/lib/stdio/lib_ungetc.c b/nuttx/libc/stdio/lib_ungetc.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_ungetc.c
      rename to nuttx/libc/stdio/lib_ungetc.c
      diff --git a/nuttx/lib/stdio/lib_vfprintf.c b/nuttx/libc/stdio/lib_vfprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_vfprintf.c
      rename to nuttx/libc/stdio/lib_vfprintf.c
      diff --git a/nuttx/lib/stdio/lib_vprintf.c b/nuttx/libc/stdio/lib_vprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_vprintf.c
      rename to nuttx/libc/stdio/lib_vprintf.c
      diff --git a/nuttx/lib/stdio/lib_vsnprintf.c b/nuttx/libc/stdio/lib_vsnprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_vsnprintf.c
      rename to nuttx/libc/stdio/lib_vsnprintf.c
      diff --git a/nuttx/lib/stdio/lib_vsprintf.c b/nuttx/libc/stdio/lib_vsprintf.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_vsprintf.c
      rename to nuttx/libc/stdio/lib_vsprintf.c
      diff --git a/nuttx/lib/stdio/lib_wrflush.c b/nuttx/libc/stdio/lib_wrflush.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_wrflush.c
      rename to nuttx/libc/stdio/lib_wrflush.c
      diff --git a/nuttx/lib/stdio/lib_zeroinstream.c b/nuttx/libc/stdio/lib_zeroinstream.c
      similarity index 100%
      rename from nuttx/lib/stdio/lib_zeroinstream.c
      rename to nuttx/libc/stdio/lib_zeroinstream.c
      diff --git a/nuttx/lib/stdlib/Make.defs b/nuttx/libc/stdlib/Make.defs
      similarity index 100%
      rename from nuttx/lib/stdlib/Make.defs
      rename to nuttx/libc/stdlib/Make.defs
      diff --git a/nuttx/lib/stdlib/lib_abort.c b/nuttx/libc/stdlib/lib_abort.c
      similarity index 100%
      rename from nuttx/lib/stdlib/lib_abort.c
      rename to nuttx/libc/stdlib/lib_abort.c
      diff --git a/nuttx/lib/stdlib/lib_abs.c b/nuttx/libc/stdlib/lib_abs.c
      similarity index 100%
      rename from nuttx/lib/stdlib/lib_abs.c
      rename to nuttx/libc/stdlib/lib_abs.c
      diff --git a/nuttx/lib/stdlib/lib_imaxabs.c b/nuttx/libc/stdlib/lib_imaxabs.c
      similarity index 100%
      rename from nuttx/lib/stdlib/lib_imaxabs.c
      rename to nuttx/libc/stdlib/lib_imaxabs.c
      diff --git a/nuttx/lib/stdlib/lib_labs.c b/nuttx/libc/stdlib/lib_labs.c
      similarity index 100%
      rename from nuttx/lib/stdlib/lib_labs.c
      rename to nuttx/libc/stdlib/lib_labs.c
      diff --git a/nuttx/lib/stdlib/lib_llabs.c b/nuttx/libc/stdlib/lib_llabs.c
      similarity index 100%
      rename from nuttx/lib/stdlib/lib_llabs.c
      rename to nuttx/libc/stdlib/lib_llabs.c
      diff --git a/nuttx/lib/stdlib/lib_qsort.c b/nuttx/libc/stdlib/lib_qsort.c
      similarity index 100%
      rename from nuttx/lib/stdlib/lib_qsort.c
      rename to nuttx/libc/stdlib/lib_qsort.c
      diff --git a/nuttx/lib/stdlib/lib_rand.c b/nuttx/libc/stdlib/lib_rand.c
      similarity index 100%
      rename from nuttx/lib/stdlib/lib_rand.c
      rename to nuttx/libc/stdlib/lib_rand.c
      diff --git a/nuttx/lib/string/Make.defs b/nuttx/libc/string/Make.defs
      similarity index 100%
      rename from nuttx/lib/string/Make.defs
      rename to nuttx/libc/string/Make.defs
      diff --git a/nuttx/lib/string/lib_checkbase.c b/nuttx/libc/string/lib_checkbase.c
      similarity index 100%
      rename from nuttx/lib/string/lib_checkbase.c
      rename to nuttx/libc/string/lib_checkbase.c
      diff --git a/nuttx/lib/string/lib_isbasedigit.c b/nuttx/libc/string/lib_isbasedigit.c
      similarity index 100%
      rename from nuttx/lib/string/lib_isbasedigit.c
      rename to nuttx/libc/string/lib_isbasedigit.c
      diff --git a/nuttx/lib/string/lib_memccpy.c b/nuttx/libc/string/lib_memccpy.c
      similarity index 100%
      rename from nuttx/lib/string/lib_memccpy.c
      rename to nuttx/libc/string/lib_memccpy.c
      diff --git a/nuttx/lib/string/lib_memchr.c b/nuttx/libc/string/lib_memchr.c
      similarity index 100%
      rename from nuttx/lib/string/lib_memchr.c
      rename to nuttx/libc/string/lib_memchr.c
      diff --git a/nuttx/lib/string/lib_memcmp.c b/nuttx/libc/string/lib_memcmp.c
      similarity index 100%
      rename from nuttx/lib/string/lib_memcmp.c
      rename to nuttx/libc/string/lib_memcmp.c
      diff --git a/nuttx/lib/string/lib_memcpy.c b/nuttx/libc/string/lib_memcpy.c
      similarity index 100%
      rename from nuttx/lib/string/lib_memcpy.c
      rename to nuttx/libc/string/lib_memcpy.c
      diff --git a/nuttx/lib/string/lib_memmove.c b/nuttx/libc/string/lib_memmove.c
      similarity index 100%
      rename from nuttx/lib/string/lib_memmove.c
      rename to nuttx/libc/string/lib_memmove.c
      diff --git a/nuttx/lib/string/lib_memset.c b/nuttx/libc/string/lib_memset.c
      similarity index 100%
      rename from nuttx/lib/string/lib_memset.c
      rename to nuttx/libc/string/lib_memset.c
      diff --git a/nuttx/lib/string/lib_skipspace.c b/nuttx/libc/string/lib_skipspace.c
      similarity index 100%
      rename from nuttx/lib/string/lib_skipspace.c
      rename to nuttx/libc/string/lib_skipspace.c
      diff --git a/nuttx/lib/string/lib_strcasecmp.c b/nuttx/libc/string/lib_strcasecmp.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strcasecmp.c
      rename to nuttx/libc/string/lib_strcasecmp.c
      diff --git a/nuttx/lib/string/lib_strcasestr.c b/nuttx/libc/string/lib_strcasestr.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strcasestr.c
      rename to nuttx/libc/string/lib_strcasestr.c
      diff --git a/nuttx/lib/string/lib_strcat.c b/nuttx/libc/string/lib_strcat.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strcat.c
      rename to nuttx/libc/string/lib_strcat.c
      diff --git a/nuttx/lib/string/lib_strchr.c b/nuttx/libc/string/lib_strchr.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strchr.c
      rename to nuttx/libc/string/lib_strchr.c
      diff --git a/nuttx/lib/string/lib_strcmp.c b/nuttx/libc/string/lib_strcmp.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strcmp.c
      rename to nuttx/libc/string/lib_strcmp.c
      diff --git a/nuttx/lib/string/lib_strcpy.c b/nuttx/libc/string/lib_strcpy.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strcpy.c
      rename to nuttx/libc/string/lib_strcpy.c
      diff --git a/nuttx/lib/string/lib_strcspn.c b/nuttx/libc/string/lib_strcspn.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strcspn.c
      rename to nuttx/libc/string/lib_strcspn.c
      diff --git a/nuttx/lib/string/lib_strdup.c b/nuttx/libc/string/lib_strdup.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strdup.c
      rename to nuttx/libc/string/lib_strdup.c
      diff --git a/nuttx/lib/string/lib_strerror.c b/nuttx/libc/string/lib_strerror.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strerror.c
      rename to nuttx/libc/string/lib_strerror.c
      diff --git a/nuttx/lib/string/lib_strlen.c b/nuttx/libc/string/lib_strlen.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strlen.c
      rename to nuttx/libc/string/lib_strlen.c
      diff --git a/nuttx/lib/string/lib_strncasecmp.c b/nuttx/libc/string/lib_strncasecmp.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strncasecmp.c
      rename to nuttx/libc/string/lib_strncasecmp.c
      diff --git a/nuttx/lib/string/lib_strncat.c b/nuttx/libc/string/lib_strncat.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strncat.c
      rename to nuttx/libc/string/lib_strncat.c
      diff --git a/nuttx/lib/string/lib_strncmp.c b/nuttx/libc/string/lib_strncmp.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strncmp.c
      rename to nuttx/libc/string/lib_strncmp.c
      diff --git a/nuttx/lib/string/lib_strncpy.c b/nuttx/libc/string/lib_strncpy.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strncpy.c
      rename to nuttx/libc/string/lib_strncpy.c
      diff --git a/nuttx/lib/string/lib_strndup.c b/nuttx/libc/string/lib_strndup.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strndup.c
      rename to nuttx/libc/string/lib_strndup.c
      diff --git a/nuttx/lib/string/lib_strnlen.c b/nuttx/libc/string/lib_strnlen.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strnlen.c
      rename to nuttx/libc/string/lib_strnlen.c
      diff --git a/nuttx/lib/string/lib_strpbrk.c b/nuttx/libc/string/lib_strpbrk.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strpbrk.c
      rename to nuttx/libc/string/lib_strpbrk.c
      diff --git a/nuttx/lib/string/lib_strrchr.c b/nuttx/libc/string/lib_strrchr.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strrchr.c
      rename to nuttx/libc/string/lib_strrchr.c
      diff --git a/nuttx/lib/string/lib_strspn.c b/nuttx/libc/string/lib_strspn.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strspn.c
      rename to nuttx/libc/string/lib_strspn.c
      diff --git a/nuttx/lib/string/lib_strstr.c b/nuttx/libc/string/lib_strstr.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strstr.c
      rename to nuttx/libc/string/lib_strstr.c
      diff --git a/nuttx/lib/string/lib_strtod.c b/nuttx/libc/string/lib_strtod.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strtod.c
      rename to nuttx/libc/string/lib_strtod.c
      diff --git a/nuttx/lib/string/lib_strtok.c b/nuttx/libc/string/lib_strtok.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strtok.c
      rename to nuttx/libc/string/lib_strtok.c
      diff --git a/nuttx/lib/string/lib_strtokr.c b/nuttx/libc/string/lib_strtokr.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strtokr.c
      rename to nuttx/libc/string/lib_strtokr.c
      diff --git a/nuttx/lib/string/lib_strtol.c b/nuttx/libc/string/lib_strtol.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strtol.c
      rename to nuttx/libc/string/lib_strtol.c
      diff --git a/nuttx/lib/string/lib_strtoll.c b/nuttx/libc/string/lib_strtoll.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strtoll.c
      rename to nuttx/libc/string/lib_strtoll.c
      diff --git a/nuttx/lib/string/lib_strtoul.c b/nuttx/libc/string/lib_strtoul.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strtoul.c
      rename to nuttx/libc/string/lib_strtoul.c
      diff --git a/nuttx/lib/string/lib_strtoull.c b/nuttx/libc/string/lib_strtoull.c
      similarity index 100%
      rename from nuttx/lib/string/lib_strtoull.c
      rename to nuttx/libc/string/lib_strtoull.c
      diff --git a/nuttx/lib/string/lib_vikmemcpy.c b/nuttx/libc/string/lib_vikmemcpy.c
      similarity index 100%
      rename from nuttx/lib/string/lib_vikmemcpy.c
      rename to nuttx/libc/string/lib_vikmemcpy.c
      diff --git a/nuttx/lib/termios/Make.defs b/nuttx/libc/termios/Make.defs
      similarity index 100%
      rename from nuttx/lib/termios/Make.defs
      rename to nuttx/libc/termios/Make.defs
      diff --git a/nuttx/lib/termios/lib_cfgetspeed.c b/nuttx/libc/termios/lib_cfgetspeed.c
      similarity index 100%
      rename from nuttx/lib/termios/lib_cfgetspeed.c
      rename to nuttx/libc/termios/lib_cfgetspeed.c
      diff --git a/nuttx/lib/termios/lib_cfsetspeed.c b/nuttx/libc/termios/lib_cfsetspeed.c
      similarity index 100%
      rename from nuttx/lib/termios/lib_cfsetspeed.c
      rename to nuttx/libc/termios/lib_cfsetspeed.c
      diff --git a/nuttx/lib/termios/lib_tcflush.c b/nuttx/libc/termios/lib_tcflush.c
      similarity index 100%
      rename from nuttx/lib/termios/lib_tcflush.c
      rename to nuttx/libc/termios/lib_tcflush.c
      diff --git a/nuttx/lib/termios/lib_tcgetattr.c b/nuttx/libc/termios/lib_tcgetattr.c
      similarity index 100%
      rename from nuttx/lib/termios/lib_tcgetattr.c
      rename to nuttx/libc/termios/lib_tcgetattr.c
      diff --git a/nuttx/lib/termios/lib_tcsetattr.c b/nuttx/libc/termios/lib_tcsetattr.c
      similarity index 100%
      rename from nuttx/lib/termios/lib_tcsetattr.c
      rename to nuttx/libc/termios/lib_tcsetattr.c
      diff --git a/nuttx/lib/time/Make.defs b/nuttx/libc/time/Make.defs
      similarity index 100%
      rename from nuttx/lib/time/Make.defs
      rename to nuttx/libc/time/Make.defs
      diff --git a/nuttx/lib/time/lib_calendar2utc.c b/nuttx/libc/time/lib_calendar2utc.c
      similarity index 100%
      rename from nuttx/lib/time/lib_calendar2utc.c
      rename to nuttx/libc/time/lib_calendar2utc.c
      diff --git a/nuttx/lib/time/lib_daysbeforemonth.c b/nuttx/libc/time/lib_daysbeforemonth.c
      similarity index 100%
      rename from nuttx/lib/time/lib_daysbeforemonth.c
      rename to nuttx/libc/time/lib_daysbeforemonth.c
      diff --git a/nuttx/lib/time/lib_gmtime.c b/nuttx/libc/time/lib_gmtime.c
      similarity index 100%
      rename from nuttx/lib/time/lib_gmtime.c
      rename to nuttx/libc/time/lib_gmtime.c
      diff --git a/nuttx/lib/time/lib_gmtimer.c b/nuttx/libc/time/lib_gmtimer.c
      similarity index 100%
      rename from nuttx/lib/time/lib_gmtimer.c
      rename to nuttx/libc/time/lib_gmtimer.c
      diff --git a/nuttx/lib/time/lib_isleapyear.c b/nuttx/libc/time/lib_isleapyear.c
      similarity index 100%
      rename from nuttx/lib/time/lib_isleapyear.c
      rename to nuttx/libc/time/lib_isleapyear.c
      diff --git a/nuttx/lib/time/lib_mktime.c b/nuttx/libc/time/lib_mktime.c
      similarity index 100%
      rename from nuttx/lib/time/lib_mktime.c
      rename to nuttx/libc/time/lib_mktime.c
      diff --git a/nuttx/lib/time/lib_strftime.c b/nuttx/libc/time/lib_strftime.c
      similarity index 100%
      rename from nuttx/lib/time/lib_strftime.c
      rename to nuttx/libc/time/lib_strftime.c
      diff --git a/nuttx/lib/time/lib_time.c b/nuttx/libc/time/lib_time.c
      similarity index 100%
      rename from nuttx/lib/time/lib_time.c
      rename to nuttx/libc/time/lib_time.c
      diff --git a/nuttx/lib/unistd/Make.defs b/nuttx/libc/unistd/Make.defs
      similarity index 100%
      rename from nuttx/lib/unistd/Make.defs
      rename to nuttx/libc/unistd/Make.defs
      diff --git a/nuttx/lib/unistd/lib_chdir.c b/nuttx/libc/unistd/lib_chdir.c
      similarity index 100%
      rename from nuttx/lib/unistd/lib_chdir.c
      rename to nuttx/libc/unistd/lib_chdir.c
      diff --git a/nuttx/lib/unistd/lib_getcwd.c b/nuttx/libc/unistd/lib_getcwd.c
      similarity index 100%
      rename from nuttx/lib/unistd/lib_getcwd.c
      rename to nuttx/libc/unistd/lib_getcwd.c
      diff --git a/nuttx/lib/unistd/lib_getopt.c b/nuttx/libc/unistd/lib_getopt.c
      similarity index 100%
      rename from nuttx/lib/unistd/lib_getopt.c
      rename to nuttx/libc/unistd/lib_getopt.c
      diff --git a/nuttx/lib/unistd/lib_getoptargp.c b/nuttx/libc/unistd/lib_getoptargp.c
      similarity index 100%
      rename from nuttx/lib/unistd/lib_getoptargp.c
      rename to nuttx/libc/unistd/lib_getoptargp.c
      diff --git a/nuttx/lib/unistd/lib_getoptindp.c b/nuttx/libc/unistd/lib_getoptindp.c
      similarity index 100%
      rename from nuttx/lib/unistd/lib_getoptindp.c
      rename to nuttx/libc/unistd/lib_getoptindp.c
      diff --git a/nuttx/lib/unistd/lib_getoptoptp.c b/nuttx/libc/unistd/lib_getoptoptp.c
      similarity index 100%
      rename from nuttx/lib/unistd/lib_getoptoptp.c
      rename to nuttx/libc/unistd/lib_getoptoptp.c
      
      From 5b5b007db3961ef389227030f3490becca6b11c3 Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sat, 10 Nov 2012 16:34:46 +0000
      Subject: [PATCH 100/206] OK.. I think the directory has been recovered and
       renamed
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5331 42af7a65-404d-4744-a932-0658087f49c3
      ---
       nuttx/libc/Kconfig                            |   2 +-
       nuttx/libc/Makefile                           |   8 +-
       nuttx/libc/README.txt                         |   2 +-
       nuttx/libc/dirent/Make.defs                   |   2 +-
       nuttx/libc/dirent/lib_readdirr.c              |   2 +-
       nuttx/libc/dirent/lib_telldir.c               |   2 +-
       nuttx/libc/fixedmath/Make.defs                |   2 +-
       nuttx/libc/fixedmath/lib_b16atan2.c           |   2 +-
       nuttx/libc/fixedmath/lib_b16cos.c             |   2 +-
       nuttx/libc/fixedmath/lib_b16sin.c             |   2 +-
       nuttx/libc/fixedmath/lib_fixedmath.c          |   2 +-
       nuttx/libc/fixedmath/lib_rint.c               |   2 +-
       nuttx/libc/lib_internal.h                     |   2 +-
       nuttx/libc/libgen/Make.defs                   |   2 +-
       nuttx/libc/libgen/lib_basename.c              |   2 +-
       nuttx/libc/libgen/lib_dirname.c               |   2 +-
       nuttx/libc/math/Make.defs                     |   2 +-
       nuttx/libc/math/lib_acos.c                    |   2 +-
       nuttx/libc/math/lib_acosf.c                   |   2 +-
       nuttx/libc/math/lib_acosl.c                   |   2 +-
       nuttx/libc/math/lib_asin.c                    |   2 +-
       nuttx/libc/math/lib_asinf.c                   |   2 +-
       nuttx/libc/math/lib_asinl.c                   |   2 +-
       nuttx/libc/math/lib_atan.c                    |   2 +-
       nuttx/libc/math/lib_atan2.c                   |   2 +-
       nuttx/libc/math/lib_atan2f.c                  |   2 +-
       nuttx/libc/math/lib_atan2l.c                  |   2 +-
       nuttx/libc/math/lib_atanf.c                   |   2 +-
       nuttx/libc/math/lib_atanl.c                   |   2 +-
       nuttx/libc/math/lib_ceil.c                    |   2 +-
       nuttx/libc/math/lib_ceilf.c                   |   2 +-
       nuttx/libc/math/lib_ceill.c                   |   2 +-
       nuttx/libc/math/lib_cos.c                     |   2 +-
       nuttx/libc/math/lib_cosf.c                    |   2 +-
       nuttx/libc/math/lib_cosh.c                    |   2 +-
       nuttx/libc/math/lib_coshf.c                   |   2 +-
       nuttx/libc/math/lib_coshl.c                   |   2 +-
       nuttx/libc/math/lib_cosl.c                    |   2 +-
       nuttx/libc/math/lib_exp.c                     |   2 +-
       nuttx/libc/math/lib_expf.c                    |   2 +-
       nuttx/libc/math/lib_expl.c                    |   2 +-
       nuttx/libc/math/lib_fabs.c                    |   2 +-
       nuttx/libc/math/lib_fabsf.c                   |   2 +-
       nuttx/libc/math/lib_fabsl.c                   |   2 +-
       nuttx/libc/math/lib_floor.c                   |   2 +-
       nuttx/libc/math/lib_floorf.c                  |   2 +-
       nuttx/libc/math/lib_floorl.c                  |   2 +-
       nuttx/libc/math/lib_fmod.c                    |   2 +-
       nuttx/libc/math/lib_fmodf.c                   |   2 +-
       nuttx/libc/math/lib_fmodl.c                   |   2 +-
       nuttx/libc/math/lib_frexp.c                   |   2 +-
       nuttx/libc/math/lib_frexpf.c                  |   2 +-
       nuttx/libc/math/lib_frexpl.c                  |   2 +-
       nuttx/libc/math/lib_ldexp.c                   |   2 +-
       nuttx/libc/math/lib_ldexpf.c                  |   2 +-
       nuttx/libc/math/lib_ldexpl.c                  |   2 +-
       nuttx/libc/math/lib_libexpi.c                 |   2 +-
       nuttx/libc/math/lib_libsqrtapprox.c           |   2 +-
       nuttx/libc/math/lib_log.c                     |   2 +-
       nuttx/libc/math/lib_log10.c                   |   2 +-
       nuttx/libc/math/lib_log10f.c                  |   2 +-
       nuttx/libc/math/lib_log10l.c                  |   2 +-
       nuttx/libc/math/lib_log2.c                    |   2 +-
       nuttx/libc/math/lib_log2f.c                   |   2 +-
       nuttx/libc/math/lib_log2l.c                   |   2 +-
       nuttx/libc/math/lib_logf.c                    |   2 +-
       nuttx/libc/math/lib_logl.c                    |   2 +-
       nuttx/libc/math/lib_modf.c                    |   2 +-
       nuttx/libc/math/lib_modff.c                   |   2 +-
       nuttx/libc/math/lib_modfl.c                   |   2 +-
       nuttx/libc/math/lib_pow.c                     |   2 +-
       nuttx/libc/math/lib_powf.c                    |   2 +-
       nuttx/libc/math/lib_powl.c                    |   2 +-
       nuttx/libc/math/lib_sin.c                     |   2 +-
       nuttx/libc/math/lib_sinf.c                    |   2 +-
       nuttx/libc/math/lib_sinh.c                    |   2 +-
       nuttx/libc/math/lib_sinhf.c                   |   2 +-
       nuttx/libc/math/lib_sinhl.c                   |   2 +-
       nuttx/libc/math/lib_sinl.c                    |   2 +-
       nuttx/libc/math/lib_sqrt.c                    |   2 +-
       nuttx/libc/math/lib_sqrtf.c                   |   2 +-
       nuttx/libc/math/lib_sqrtl.c                   |   2 +-
       nuttx/libc/math/lib_tan.c                     |   2 +-
       nuttx/libc/math/lib_tanf.c                    |   2 +-
       nuttx/libc/math/lib_tanh.c                    |   2 +-
       nuttx/libc/math/lib_tanhf.c                   |   2 +-
       nuttx/libc/math/lib_tanhl.c                   |   2 +-
       nuttx/libc/math/lib_tanl.c                    |   2 +-
       nuttx/libc/misc/Make.defs                     |   2 +-
       nuttx/libc/misc/lib_crc32.c                   |   2 +-
       nuttx/libc/misc/lib_dbg.c                     |   2 +-
       nuttx/libc/misc/lib_dumpbuffer.c              |   2 +-
       nuttx/libc/misc/lib_filesem.c                 |   2 +-
       nuttx/libc/misc/lib_init.c                    |   2 +-
       nuttx/libc/misc/lib_match.c                   |   2 +-
       nuttx/libc/misc/lib_sendfile.c                |   2 +-
       nuttx/libc/misc/lib_streamsem.c               |   2 +-
       nuttx/libc/mqueue/Make.defs                   |   2 +-
       nuttx/libc/mqueue/mq_getattr.c                |   2 +-
       nuttx/libc/mqueue/mq_setattr.c                |   2 +-
       nuttx/libc/net/Make.defs                      |   2 +-
       nuttx/libc/net/lib_etherntoa.c                |   2 +-
       nuttx/libc/net/lib_htonl.c                    |   2 +-
       nuttx/libc/net/lib_htons.c                    |   2 +-
       nuttx/libc/net/lib_inetaddr.c                 |   2 +-
       nuttx/libc/net/lib_inetntoa.c                 |   2 +-
       nuttx/libc/net/lib_inetntop.c                 |   2 +-
       nuttx/libc/net/lib_inetpton.c                 |   2 +-
       nuttx/libc/pthread/Make.defs                  |   2 +-
       nuttx/libc/pthread/pthread_attrdestroy.c      |   2 +-
       .../pthread/pthread_attrgetinheritsched.c     |   2 +-
       .../libc/pthread/pthread_attrgetschedparam.c  |   2 +-
       .../libc/pthread/pthread_attrgetschedpolicy.c |   2 +-
       nuttx/libc/pthread/pthread_attrgetstacksize.c |   2 +-
       nuttx/libc/pthread/pthread_attrinit.c         |   2 +-
       .../pthread/pthread_attrsetinheritsched.c     |   2 +-
       .../libc/pthread/pthread_attrsetschedparam.c  |   2 +-
       .../libc/pthread/pthread_attrsetschedpolicy.c |   2 +-
       nuttx/libc/pthread/pthread_attrsetstacksize.c |   2 +-
       .../libc/pthread/pthread_barrierattrdestroy.c |   2 +-
       .../pthread/pthread_barrierattrgetpshared.c   |   2 +-
       nuttx/libc/pthread/pthread_barrierattrinit.c  |   2 +-
       .../pthread/pthread_barrierattrsetpshared.c   |   2 +-
       nuttx/libc/pthread/pthread_condattrdestroy.c  |   2 +-
       nuttx/libc/pthread/pthread_condattrinit.c     |   2 +-
       nuttx/libc/pthread/pthread_mutexattrdestroy.c |   2 +-
       .../pthread/pthread_mutexattrgetpshared.c     |   2 +-
       nuttx/libc/pthread/pthread_mutexattrgettype.c |   2 +-
       nuttx/libc/pthread/pthread_mutexattrinit.c    |   2 +-
       .../pthread/pthread_mutexattrsetpshared.c     |   2 +-
       nuttx/libc/pthread/pthread_mutexattrsettype.c |   2 +-
       nuttx/libc/queue/Make.defs                    |   2 +-
       nuttx/libc/queue/dq_addafter.c                |   2 +-
       nuttx/libc/queue/dq_addbefore.c               |   2 +-
       nuttx/libc/queue/dq_addfirst.c                |   2 +-
       nuttx/libc/queue/dq_addlast.c                 |   2 +-
       nuttx/libc/queue/dq_rem.c                     |   2 +-
       nuttx/libc/queue/dq_remfirst.c                |   2 +-
       nuttx/libc/queue/dq_remlast.c                 |   2 +-
       nuttx/libc/queue/sq_addafter.c                |   2 +-
       nuttx/libc/queue/sq_addfirst.c                |   2 +-
       nuttx/libc/queue/sq_addlast.c                 |   2 +-
       nuttx/libc/queue/sq_rem.c                     |   2 +-
       nuttx/libc/queue/sq_remafter.c                |   2 +-
       nuttx/libc/queue/sq_remfirst.c                |   2 +-
       nuttx/libc/queue/sq_remlast.c                 |   2 +-
       nuttx/libc/sched/Make.defs                    |   2 +-
       nuttx/libc/sched/sched_getprioritymax.c       |   2 +-
       nuttx/libc/sched/sched_getprioritymin.c       |   2 +-
       nuttx/libc/semaphore/Make.defs                |   2 +-
       nuttx/libc/semaphore/sem_getvalue.c           |   2 +-
       nuttx/libc/semaphore/sem_init.c               |   2 +-
       nuttx/libc/signal/Make.defs                   |   2 +-
       nuttx/libc/signal/sig_addset.c                |   2 +-
       nuttx/libc/signal/sig_delset.c                |   2 +-
       nuttx/libc/signal/sig_emptyset.c              |   2 +-
       nuttx/libc/signal/sig_fillset.c               |   2 +-
       nuttx/libc/signal/sig_ismember.c              |   2 +-
       nuttx/libc/stdio/Make.defs                    |   2 +-
       nuttx/libc/stdio/lib_asprintf.c               |   2 +-
       nuttx/libc/stdio/lib_avsprintf.c              |   2 +-
       nuttx/libc/stdio/lib_clearerr.c               |   2 +-
       nuttx/libc/stdio/lib_dtoa.c                   |   2 +-
       nuttx/libc/stdio/lib_fclose.c                 |   2 +-
       nuttx/libc/stdio/lib_feof.c                   |   2 +-
       nuttx/libc/stdio/lib_ferror.c                 |   2 +-
       nuttx/libc/stdio/lib_fflush.c                 |   2 +-
       nuttx/libc/stdio/lib_fgetc.c                  |   2 +-
       nuttx/libc/stdio/lib_fgetpos.c                |   2 +-
       nuttx/libc/stdio/lib_fgets.c                  |   2 +-
       nuttx/libc/stdio/lib_fileno.c                 |   2 +-
       nuttx/libc/stdio/lib_fopen.c                  |   2 +-
       nuttx/libc/stdio/lib_fprintf.c                |   2 +-
       nuttx/libc/stdio/lib_fputc.c                  |   2 +-
       nuttx/libc/stdio/lib_fputs.c                  |   2 +-
       nuttx/libc/stdio/lib_fread.c                  |   2 +-
       nuttx/libc/stdio/lib_fseek.c                  |   2 +-
       nuttx/libc/stdio/lib_fsetpos.c                |   2 +-
       nuttx/libc/stdio/lib_ftell.c                  |   2 +-
       nuttx/libc/stdio/lib_fwrite.c                 |   2 +-
       nuttx/libc/stdio/lib_gets.c                   |   2 +-
       nuttx/libc/stdio/lib_libdtoa.c                |   2 +-
       nuttx/libc/stdio/lib_libfflush.c              |   2 +-
       nuttx/libc/stdio/lib_libflushall.c            |   2 +-
       nuttx/libc/stdio/lib_libfread.c               |   2 +-
       nuttx/libc/stdio/lib_libfwrite.c              |   2 +-
       nuttx/libc/stdio/lib_libnoflush.c             |   2 +-
       nuttx/libc/stdio/lib_libsprintf.c             |   2 +-
       nuttx/libc/stdio/lib_libvsprintf.c            |   4 +-
       nuttx/libc/stdio/lib_lowinstream.c            |   2 +-
       nuttx/libc/stdio/lib_lowoutstream.c           |   2 +-
       nuttx/libc/stdio/lib_lowprintf.c              |   2 +-
       nuttx/libc/stdio/lib_meminstream.c            |   2 +-
       nuttx/libc/stdio/lib_memoutstream.c           |   2 +-
       nuttx/libc/stdio/lib_nullinstream.c           |   2 +-
       nuttx/libc/stdio/lib_nulloutstream.c          |   2 +-
       nuttx/libc/stdio/lib_perror.c                 |   2 +-
       nuttx/libc/stdio/lib_printf.c                 |   2 +-
       nuttx/libc/stdio/lib_puts.c                   |   2 +-
       nuttx/libc/stdio/lib_rawinstream.c            |   2 +-
       nuttx/libc/stdio/lib_rawoutstream.c           |   2 +-
       nuttx/libc/stdio/lib_rawprintf.c              |   2 +-
       nuttx/libc/stdio/lib_rdflush.c                |   2 +-
       nuttx/libc/stdio/lib_snprintf.c               |   2 +-
       nuttx/libc/stdio/lib_sprintf.c                |   2 +-
       nuttx/libc/stdio/lib_sscanf.c                 |   2 +-
       nuttx/libc/stdio/lib_stdinstream.c            |   2 +-
       nuttx/libc/stdio/lib_stdoutstream.c           |   2 +-
       nuttx/libc/stdio/lib_syslogstream.c           |   2 +-
       nuttx/libc/stdio/lib_ungetc.c                 |   2 +-
       nuttx/libc/stdio/lib_vfprintf.c               |   2 +-
       nuttx/libc/stdio/lib_vprintf.c                |   2 +-
       nuttx/libc/stdio/lib_vsnprintf.c              |   2 +-
       nuttx/libc/stdio/lib_vsprintf.c               |   4 +-
       nuttx/libc/stdio/lib_wrflush.c                |   2 +-
       nuttx/libc/stdio/lib_zeroinstream.c           |   2 +-
       nuttx/libc/stdlib/Make.defs                   |   2 +-
       nuttx/libc/stdlib/lib_abort.c                 |   2 +-
       nuttx/libc/stdlib/lib_abs.c                   |   2 +-
       nuttx/libc/stdlib/lib_imaxabs.c               |   2 +-
       nuttx/libc/stdlib/lib_labs.c                  |   2 +-
       nuttx/libc/stdlib/lib_llabs.c                 |   2 +-
       nuttx/libc/stdlib/lib_qsort.c                 |   2 +-
       nuttx/libc/stdlib/lib_rand.c                  |   2 +-
       nuttx/libc/string/Make.defs                   |   2 +-
       nuttx/libc/string/lib_checkbase.c             |   2 +-
       nuttx/libc/string/lib_isbasedigit.c           |   2 +-
       nuttx/libc/string/lib_memccpy.c               |   2 +-
       nuttx/libc/string/lib_memchr.c                |   2 +-
       nuttx/libc/string/lib_memcmp.c                |   2 +-
       nuttx/libc/string/lib_memcpy.c                |   2 +-
       nuttx/libc/string/lib_memmove.c               |   2 +-
       nuttx/libc/string/lib_memset.c                |   2 +-
       nuttx/libc/string/lib_skipspace.c             |   2 +-
       nuttx/libc/string/lib_strcasecmp.c            |   2 +-
       nuttx/libc/string/lib_strcasestr.c            |   2 +-
       nuttx/libc/string/lib_strcat.c                |   2 +-
       nuttx/libc/string/lib_strchr.c                |   2 +-
       nuttx/libc/string/lib_strcmp.c                |   2 +-
       nuttx/libc/string/lib_strcpy.c                |   2 +-
       nuttx/libc/string/lib_strcspn.c               |   2 +-
       nuttx/libc/string/lib_strdup.c                |   2 +-
       nuttx/libc/string/lib_strerror.c              |   2 +-
       nuttx/libc/string/lib_strlen.c                |   2 +-
       nuttx/libc/string/lib_strncasecmp.c           |   2 +-
       nuttx/libc/string/lib_strncat.c               |   2 +-
       nuttx/libc/string/lib_strncmp.c               |   2 +-
       nuttx/libc/string/lib_strncpy.c               |   2 +-
       nuttx/libc/string/lib_strndup.c               |   2 +-
       nuttx/libc/string/lib_strnlen.c               |   4 +-
       nuttx/libc/string/lib_strpbrk.c               |   2 +-
       nuttx/libc/string/lib_strrchr.c               |   2 +-
       nuttx/libc/string/lib_strspn.c                |   2 +-
       nuttx/libc/string/lib_strstr.c                |   2 +-
       nuttx/libc/string/lib_strtod.c                |   2 +-
       nuttx/libc/string/lib_strtok.c                |   2 +-
       nuttx/libc/string/lib_strtokr.c               |   2 +-
       nuttx/libc/string/lib_strtol.c                |   2 +-
       nuttx/libc/string/lib_strtoll.c               |   2 +-
       nuttx/libc/string/lib_strtoul.c               |   2 +-
       nuttx/libc/string/lib_strtoull.c              |   2 +-
       nuttx/libc/string/lib_vikmemcpy.c             | 696 +++++++++---------
       nuttx/libc/termios/Make.defs                  |   2 +-
       nuttx/libc/termios/lib_cfgetspeed.c           |   2 +-
       nuttx/libc/termios/lib_cfsetspeed.c           |   2 +-
       nuttx/libc/termios/lib_tcflush.c              |   2 +-
       nuttx/libc/termios/lib_tcgetattr.c            |   2 +-
       nuttx/libc/termios/lib_tcsetattr.c            |   2 +-
       nuttx/libc/time/Make.defs                     |   2 +-
       nuttx/libc/time/lib_calendar2utc.c            |   2 +-
       nuttx/libc/time/lib_daysbeforemonth.c         |   2 +-
       nuttx/libc/time/lib_gmtime.c                  |   2 +-
       nuttx/libc/time/lib_gmtimer.c                 |   2 +-
       nuttx/libc/time/lib_isleapyear.c              |   2 +-
       nuttx/libc/time/lib_mktime.c                  |   2 +-
       nuttx/libc/time/lib_strftime.c                |   2 +-
       nuttx/libc/time/lib_time.c                    |   2 +-
       nuttx/libc/unistd/Make.defs                   |   2 +-
       nuttx/libc/unistd/lib_chdir.c                 |   2 +-
       nuttx/libc/unistd/lib_getcwd.c                |   2 +-
       nuttx/libc/unistd/lib_getopt.c                |   2 +-
       nuttx/libc/unistd/lib_getoptargp.c            |   2 +-
       nuttx/libc/unistd/lib_getoptindp.c            |   2 +-
       nuttx/libc/unistd/lib_getoptoptp.c            |   2 +-
       284 files changed, 637 insertions(+), 637 deletions(-)
      
      diff --git a/nuttx/libc/Kconfig b/nuttx/libc/Kconfig
      index 1c93bb0475..bd470be7f5 100644
      --- a/nuttx/libc/Kconfig
      +++ b/nuttx/libc/Kconfig
      @@ -30,7 +30,7 @@ config LIB_HOMEDIR
       	---help---
       		The home directory to use with operations like such as 'cd ~'
       
      -source lib/math/Kconfig
      +source libc/math/Kconfig
       
       config NOPRINTF_FIELDWIDTH
       	bool "Disable sprintf support fieldwidth"
      diff --git a/nuttx/libc/Makefile b/nuttx/libc/Makefile
      index 406c2276ef..318816ba71 100644
      --- a/nuttx/libc/Makefile
      +++ b/nuttx/libc/Makefile
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/Makefile
      +# libc/Makefile
       #
       #   Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      @@ -66,9 +66,9 @@ COBJS = $(CSRCS:.c=$(OBJEXT))
       SRCS = $(ASRCS) $(CSRCS)
       OBJS = $(AOBJS) $(COBJS)
       
      -UBIN = libulib$(LIBEXT)
      -KBIN = libklib$(LIBEXT)
      -BIN  = liblib$(LIBEXT)
      +UBIN = libuc$(LIBEXT)
      +KBIN = libkc$(LIBEXT)
      +BIN  = libc$(LIBEXT)
       
       all: $(BIN)
       
      diff --git a/nuttx/libc/README.txt b/nuttx/libc/README.txt
      index e99304841b..ed672d0388 100644
      --- a/nuttx/libc/README.txt
      +++ b/nuttx/libc/README.txt
      @@ -21,7 +21,7 @@ it is critical to separate the user-mode OS interfaces in this way.
       Sub-Directories
       ===============
       
      -The files in the lib/ directory are organized (mostly) according which file
      +The files in the libc/ directory are organized (mostly) according which file
       in the include/ directory provides the prototype for library functions.  So
       we have:
       
      diff --git a/nuttx/libc/dirent/Make.defs b/nuttx/libc/dirent/Make.defs
      index cc1d6b7839..f2927bed82 100644
      --- a/nuttx/libc/dirent/Make.defs
      +++ b/nuttx/libc/dirent/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/dirent/Make.defs
      +# libc/dirent/Make.defs
       #
       #   Copyright (C) 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/dirent/lib_readdirr.c b/nuttx/libc/dirent/lib_readdirr.c
      index 47c5b9a7bd..93c99ac283 100644
      --- a/nuttx/libc/dirent/lib_readdirr.c
      +++ b/nuttx/libc/dirent/lib_readdirr.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/dirent/lib_readdirr.c
      + * libc/dirent/lib_readdirr.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/dirent/lib_telldir.c b/nuttx/libc/dirent/lib_telldir.c
      index 3753b326e9..f77a4a1c21 100644
      --- a/nuttx/libc/dirent/lib_telldir.c
      +++ b/nuttx/libc/dirent/lib_telldir.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/dirent/fs_telldir.c
      + * libc/dirent/fs_telldir.c
        *
        *   Copyright (C) 2007-2008, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/fixedmath/Make.defs b/nuttx/libc/fixedmath/Make.defs
      index 578e330153..b53df2b2c0 100644
      --- a/nuttx/libc/fixedmath/Make.defs
      +++ b/nuttx/libc/fixedmath/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/fixedmath/Make.defs
      +# libc/fixedmath/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/fixedmath/lib_b16atan2.c b/nuttx/libc/fixedmath/lib_b16atan2.c
      index 69d132f80f..443ab7be34 100644
      --- a/nuttx/libc/fixedmath/lib_b16atan2.c
      +++ b/nuttx/libc/fixedmath/lib_b16atan2.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/fixedmath/lib_b16atan2.c
      + * libc/fixedmath/lib_b16atan2.c
        *
        *   Copyright (C) 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/fixedmath/lib_b16cos.c b/nuttx/libc/fixedmath/lib_b16cos.c
      index 3e9229029e..0ebe482624 100644
      --- a/nuttx/libc/fixedmath/lib_b16cos.c
      +++ b/nuttx/libc/fixedmath/lib_b16cos.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/fixedmath/lib_b16cos.c
      + * libc/fixedmath/lib_b16cos.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/fixedmath/lib_b16sin.c b/nuttx/libc/fixedmath/lib_b16sin.c
      index 491b0ec782..9cd2f0da3e 100644
      --- a/nuttx/libc/fixedmath/lib_b16sin.c
      +++ b/nuttx/libc/fixedmath/lib_b16sin.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/fixedmath/lib_b16sin.c
      + * libc/fixedmath/lib_b16sin.c
        *
        *   Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/fixedmath/lib_fixedmath.c b/nuttx/libc/fixedmath/lib_fixedmath.c
      index c1a710e739..9e9213b4fc 100644
      --- a/nuttx/libc/fixedmath/lib_fixedmath.c
      +++ b/nuttx/libc/fixedmath/lib_fixedmath.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/math/lib_fixedmath.c
      + * libc/math/lib_fixedmath.c
        *
        *   Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/fixedmath/lib_rint.c b/nuttx/libc/fixedmath/lib_rint.c
      index 3a6407b8c0..a1212c970b 100644
      --- a/nuttx/libc/fixedmath/lib_rint.c
      +++ b/nuttx/libc/fixedmath/lib_rint.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/fixedmath/lib_rint.c
      + * libc/fixedmath/lib_rint.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/lib_internal.h b/nuttx/libc/lib_internal.h
      index 5da0ac9249..c09c751d4a 100644
      --- a/nuttx/libc/lib_internal.h
      +++ b/nuttx/libc/lib_internal.h
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/lib_internal.h
      + * libc/lib_internal.h
        *
        *   Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/libgen/Make.defs b/nuttx/libc/libgen/Make.defs
      index f126455124..6e786655d9 100644
      --- a/nuttx/libc/libgen/Make.defs
      +++ b/nuttx/libc/libgen/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/libgen/Make.defs
      +# libc/libgen/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/libgen/lib_basename.c b/nuttx/libc/libgen/lib_basename.c
      index 986c6b8520..68188edbf5 100644
      --- a/nuttx/libc/libgen/lib_basename.c
      +++ b/nuttx/libc/libgen/lib_basename.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/libgen/lib_basename.c
      + * libc/libgen/lib_basename.c
        *
        *   Copyright (C) 2007, 2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/libgen/lib_dirname.c b/nuttx/libc/libgen/lib_dirname.c
      index 248293a605..6d076fd610 100644
      --- a/nuttx/libc/libgen/lib_dirname.c
      +++ b/nuttx/libc/libgen/lib_dirname.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/libgen/lib_dirname.c
      + * libc/libgen/lib_dirname.c
        *
        *   Copyright (C) 2007, 2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/math/Make.defs b/nuttx/libc/math/Make.defs
      index 73d0be6f3b..bc6a265f0e 100644
      --- a/nuttx/libc/math/Make.defs
      +++ b/nuttx/libc/math/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/math/Make.defs
      +# libc/math/Make.defs
       #
       #   Copyright (C) 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/math/lib_acos.c b/nuttx/libc/math/lib_acos.c
      index d5ec36b9ff..147003237f 100644
      --- a/nuttx/libc/math/lib_acos.c
      +++ b/nuttx/libc/math/lib_acos.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_acos.c
      + * libc/math/lib_acos.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_acosf.c b/nuttx/libc/math/lib_acosf.c
      index e14a73a6ea..447b2767f1 100644
      --- a/nuttx/libc/math/lib_acosf.c
      +++ b/nuttx/libc/math/lib_acosf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_acosf.c
      + * libc/math/lib_acosf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_acosl.c b/nuttx/libc/math/lib_acosl.c
      index 9113305776..a0f2262380 100644
      --- a/nuttx/libc/math/lib_acosl.c
      +++ b/nuttx/libc/math/lib_acosl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_acos.c
      + * libc/math/lib_acos.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_asin.c b/nuttx/libc/math/lib_asin.c
      index 61b9535310..d9941a7e5b 100644
      --- a/nuttx/libc/math/lib_asin.c
      +++ b/nuttx/libc/math/lib_asin.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sin.c
      + * libc/math/lib_sin.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_asinf.c b/nuttx/libc/math/lib_asinf.c
      index 17669a9346..57e518acb4 100644
      --- a/nuttx/libc/math/lib_asinf.c
      +++ b/nuttx/libc/math/lib_asinf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sinf.c
      + * libc/math/lib_sinf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_asinl.c b/nuttx/libc/math/lib_asinl.c
      index dbb2bc3a2e..19f284e535 100644
      --- a/nuttx/libc/math/lib_asinl.c
      +++ b/nuttx/libc/math/lib_asinl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sinl.c
      + * libc/math/lib_sinl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_atan.c b/nuttx/libc/math/lib_atan.c
      index b4db8fb313..44d68ece2f 100644
      --- a/nuttx/libc/math/lib_atan.c
      +++ b/nuttx/libc/math/lib_atan.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_atan.c
      + * libc/math/lib_atan.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_atan2.c b/nuttx/libc/math/lib_atan2.c
      index 82d1f47ec3..6d7d2ad482 100644
      --- a/nuttx/libc/math/lib_atan2.c
      +++ b/nuttx/libc/math/lib_atan2.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_atan2.c
      + * libc/math/lib_atan2.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_atan2f.c b/nuttx/libc/math/lib_atan2f.c
      index a60d32c655..7ff9af1305 100644
      --- a/nuttx/libc/math/lib_atan2f.c
      +++ b/nuttx/libc/math/lib_atan2f.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_atan2f.c
      + * libc/math/lib_atan2f.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_atan2l.c b/nuttx/libc/math/lib_atan2l.c
      index 07fcd9669b..48bfd06f39 100644
      --- a/nuttx/libc/math/lib_atan2l.c
      +++ b/nuttx/libc/math/lib_atan2l.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_atan2l.c
      + * libc/math/lib_atan2l.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_atanf.c b/nuttx/libc/math/lib_atanf.c
      index 7c540dd163..a84605787a 100644
      --- a/nuttx/libc/math/lib_atanf.c
      +++ b/nuttx/libc/math/lib_atanf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_atanf.c
      + * libc/math/lib_atanf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_atanl.c b/nuttx/libc/math/lib_atanl.c
      index 0fa2030988..752d493070 100644
      --- a/nuttx/libc/math/lib_atanl.c
      +++ b/nuttx/libc/math/lib_atanl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_atanl.c
      + * libc/math/lib_atanl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_ceil.c b/nuttx/libc/math/lib_ceil.c
      index 0e76029967..3c6678dc1d 100644
      --- a/nuttx/libc/math/lib_ceil.c
      +++ b/nuttx/libc/math/lib_ceil.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_ceil.c
      + * libc/math/lib_ceil.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_ceilf.c b/nuttx/libc/math/lib_ceilf.c
      index 0721ffc22a..afbe2cf13b 100644
      --- a/nuttx/libc/math/lib_ceilf.c
      +++ b/nuttx/libc/math/lib_ceilf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_ceilf.c
      + * libc/math/lib_ceilf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_ceill.c b/nuttx/libc/math/lib_ceill.c
      index a24b56f683..757016b530 100644
      --- a/nuttx/libc/math/lib_ceill.c
      +++ b/nuttx/libc/math/lib_ceill.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_ceil;.c
      + * libc/math/lib_ceil;.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_cos.c b/nuttx/libc/math/lib_cos.c
      index aa672b8559..4b4e1a20b9 100644
      --- a/nuttx/libc/math/lib_cos.c
      +++ b/nuttx/libc/math/lib_cos.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_cos.c
      + * libc/math/lib_cos.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_cosf.c b/nuttx/libc/math/lib_cosf.c
      index 093a8a0024..d9ac951f62 100644
      --- a/nuttx/libc/math/lib_cosf.c
      +++ b/nuttx/libc/math/lib_cosf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_cosf.c
      + * libc/math/lib_cosf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_cosh.c b/nuttx/libc/math/lib_cosh.c
      index 1be44d2933..3246ea5f96 100644
      --- a/nuttx/libc/math/lib_cosh.c
      +++ b/nuttx/libc/math/lib_cosh.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_cosh.c
      + * libc/math/lib_cosh.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_coshf.c b/nuttx/libc/math/lib_coshf.c
      index d5e5ea14de..f0c28ab2ea 100644
      --- a/nuttx/libc/math/lib_coshf.c
      +++ b/nuttx/libc/math/lib_coshf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_coshf.c
      + * libc/math/lib_coshf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_coshl.c b/nuttx/libc/math/lib_coshl.c
      index 4576b88769..957ec61a73 100644
      --- a/nuttx/libc/math/lib_coshl.c
      +++ b/nuttx/libc/math/lib_coshl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_coshl.c
      + * libc/math/lib_coshl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_cosl.c b/nuttx/libc/math/lib_cosl.c
      index 25dd861393..972d4aa9da 100644
      --- a/nuttx/libc/math/lib_cosl.c
      +++ b/nuttx/libc/math/lib_cosl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_cosl.c
      + * libc/math/lib_cosl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_exp.c b/nuttx/libc/math/lib_exp.c
      index 1e3120453d..62494251de 100644
      --- a/nuttx/libc/math/lib_exp.c
      +++ b/nuttx/libc/math/lib_exp.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_exp.c
      + * libc/math/lib_exp.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_expf.c b/nuttx/libc/math/lib_expf.c
      index eac4641c67..3e43c54a6c 100644
      --- a/nuttx/libc/math/lib_expf.c
      +++ b/nuttx/libc/math/lib_expf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_expf.c
      + * libc/math/lib_expf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_expl.c b/nuttx/libc/math/lib_expl.c
      index 053103c9bb..231faa35f1 100644
      --- a/nuttx/libc/math/lib_expl.c
      +++ b/nuttx/libc/math/lib_expl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_expl.c
      + * libc/math/lib_expl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_fabs.c b/nuttx/libc/math/lib_fabs.c
      index ff99ceb642..774755087b 100644
      --- a/nuttx/libc/math/lib_fabs.c
      +++ b/nuttx/libc/math/lib_fabs.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_fabs.c
      + * libc/math/lib_fabs.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_fabsf.c b/nuttx/libc/math/lib_fabsf.c
      index 0ea186ca03..4c8ebae620 100644
      --- a/nuttx/libc/math/lib_fabsf.c
      +++ b/nuttx/libc/math/lib_fabsf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_fabsf.c
      + * libc/math/lib_fabsf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_fabsl.c b/nuttx/libc/math/lib_fabsl.c
      index 5313d897da..96ac7d5db3 100644
      --- a/nuttx/libc/math/lib_fabsl.c
      +++ b/nuttx/libc/math/lib_fabsl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_fabsl.c
      + * libc/math/lib_fabsl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_floor.c b/nuttx/libc/math/lib_floor.c
      index f0c4477a04..3330607ce9 100644
      --- a/nuttx/libc/math/lib_floor.c
      +++ b/nuttx/libc/math/lib_floor.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_floor.c
      + * libc/math/lib_floor.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_floorf.c b/nuttx/libc/math/lib_floorf.c
      index 2becb5fac9..81483d4c9c 100644
      --- a/nuttx/libc/math/lib_floorf.c
      +++ b/nuttx/libc/math/lib_floorf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_floorf.c
      + * libc/math/lib_floorf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_floorl.c b/nuttx/libc/math/lib_floorl.c
      index e38ce80ed3..0d9ec43b45 100644
      --- a/nuttx/libc/math/lib_floorl.c
      +++ b/nuttx/libc/math/lib_floorl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_floorl.c
      + * libc/math/lib_floorl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_fmod.c b/nuttx/libc/math/lib_fmod.c
      index 939e7e18ad..c66210cdea 100644
      --- a/nuttx/libc/math/lib_fmod.c
      +++ b/nuttx/libc/math/lib_fmod.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_fmod.c
      + * libc/math/lib_fmod.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_fmodf.c b/nuttx/libc/math/lib_fmodf.c
      index 085786f172..d70bb791ca 100644
      --- a/nuttx/libc/math/lib_fmodf.c
      +++ b/nuttx/libc/math/lib_fmodf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_fmodf.c
      + * libc/math/lib_fmodf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_fmodl.c b/nuttx/libc/math/lib_fmodl.c
      index 51c5e95ec8..1299bf6e89 100644
      --- a/nuttx/libc/math/lib_fmodl.c
      +++ b/nuttx/libc/math/lib_fmodl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_fmodl.c
      + * libc/math/lib_fmodl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_frexp.c b/nuttx/libc/math/lib_frexp.c
      index 56feee8639..b9576dfd4d 100644
      --- a/nuttx/libc/math/lib_frexp.c
      +++ b/nuttx/libc/math/lib_frexp.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_frexp.c
      + * libc/math/lib_frexp.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_frexpf.c b/nuttx/libc/math/lib_frexpf.c
      index 1fb0df3d89..d93ffb1731 100644
      --- a/nuttx/libc/math/lib_frexpf.c
      +++ b/nuttx/libc/math/lib_frexpf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_frexpf.c
      + * libc/math/lib_frexpf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_frexpl.c b/nuttx/libc/math/lib_frexpl.c
      index 87708ad86c..90993b137b 100644
      --- a/nuttx/libc/math/lib_frexpl.c
      +++ b/nuttx/libc/math/lib_frexpl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_frexpl.c
      + * libc/math/lib_frexpl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_ldexp.c b/nuttx/libc/math/lib_ldexp.c
      index 4c7b2b721b..9b74d53d71 100644
      --- a/nuttx/libc/math/lib_ldexp.c
      +++ b/nuttx/libc/math/lib_ldexp.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_ldexp.c
      + * libc/math/lib_ldexp.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_ldexpf.c b/nuttx/libc/math/lib_ldexpf.c
      index c61d633d5c..f3aaf555b4 100644
      --- a/nuttx/libc/math/lib_ldexpf.c
      +++ b/nuttx/libc/math/lib_ldexpf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_ldexpf.c
      + * libc/math/lib_ldexpf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_ldexpl.c b/nuttx/libc/math/lib_ldexpl.c
      index b9a0f4a865..29764aaba3 100644
      --- a/nuttx/libc/math/lib_ldexpl.c
      +++ b/nuttx/libc/math/lib_ldexpl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_ldexpl.c
      + * libc/math/lib_ldexpl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_libexpi.c b/nuttx/libc/math/lib_libexpi.c
      index 1ec947a71a..33ba537b1e 100644
      --- a/nuttx/libc/math/lib_libexpi.c
      +++ b/nuttx/libc/math/lib_libexpi.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_libexpi.c
      + * libc/math/lib_libexpi.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_libsqrtapprox.c b/nuttx/libc/math/lib_libsqrtapprox.c
      index 5c556c3a0e..b6a9b0d54c 100644
      --- a/nuttx/libc/math/lib_libsqrtapprox.c
      +++ b/nuttx/libc/math/lib_libsqrtapprox.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_libsqrtapprox.c
      + * libc/math/lib_libsqrtapprox.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_log.c b/nuttx/libc/math/lib_log.c
      index 1350ba4fea..7156f6b411 100644
      --- a/nuttx/libc/math/lib_log.c
      +++ b/nuttx/libc/math/lib_log.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_log.c
      + * libc/math/lib_log.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_log10.c b/nuttx/libc/math/lib_log10.c
      index 47854fca44..9daa914925 100644
      --- a/nuttx/libc/math/lib_log10.c
      +++ b/nuttx/libc/math/lib_log10.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_log10.c
      + * libc/math/lib_log10.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_log10f.c b/nuttx/libc/math/lib_log10f.c
      index 651071920f..778daedd5b 100644
      --- a/nuttx/libc/math/lib_log10f.c
      +++ b/nuttx/libc/math/lib_log10f.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_log10f.c
      + * libc/math/lib_log10f.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_log10l.c b/nuttx/libc/math/lib_log10l.c
      index 65892262a8..efbeb721b4 100644
      --- a/nuttx/libc/math/lib_log10l.c
      +++ b/nuttx/libc/math/lib_log10l.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_log10l.c
      + * libc/math/lib_log10l.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_log2.c b/nuttx/libc/math/lib_log2.c
      index 0aa1e80101..4da39acdc3 100644
      --- a/nuttx/libc/math/lib_log2.c
      +++ b/nuttx/libc/math/lib_log2.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_log2.c
      + * libc/math/lib_log2.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_log2f.c b/nuttx/libc/math/lib_log2f.c
      index e160ca59e3..f514e5a9e0 100644
      --- a/nuttx/libc/math/lib_log2f.c
      +++ b/nuttx/libc/math/lib_log2f.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_log2f.c
      + * libc/math/lib_log2f.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_log2l.c b/nuttx/libc/math/lib_log2l.c
      index 21d26d4d7b..21e80a930f 100644
      --- a/nuttx/libc/math/lib_log2l.c
      +++ b/nuttx/libc/math/lib_log2l.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_log2l.c
      + * libc/math/lib_log2l.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_logf.c b/nuttx/libc/math/lib_logf.c
      index 1d31aa0c0b..3815fef84c 100644
      --- a/nuttx/libc/math/lib_logf.c
      +++ b/nuttx/libc/math/lib_logf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_logf.c
      + * libc/math/lib_logf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_logl.c b/nuttx/libc/math/lib_logl.c
      index 577f9cee2e..6128160114 100644
      --- a/nuttx/libc/math/lib_logl.c
      +++ b/nuttx/libc/math/lib_logl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_lol.c
      + * libc/math/lib_lol.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_modf.c b/nuttx/libc/math/lib_modf.c
      index 9dc6284c20..f3f25f6fb0 100644
      --- a/nuttx/libc/math/lib_modf.c
      +++ b/nuttx/libc/math/lib_modf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_modf.c
      + * libc/math/lib_modf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_modff.c b/nuttx/libc/math/lib_modff.c
      index 4eec2ae17f..28d3a3ae0b 100644
      --- a/nuttx/libc/math/lib_modff.c
      +++ b/nuttx/libc/math/lib_modff.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_modff.c
      + * libc/math/lib_modff.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_modfl.c b/nuttx/libc/math/lib_modfl.c
      index 3b04571f3a..77bba0e0c0 100644
      --- a/nuttx/libc/math/lib_modfl.c
      +++ b/nuttx/libc/math/lib_modfl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_modfl.c
      + * libc/math/lib_modfl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_pow.c b/nuttx/libc/math/lib_pow.c
      index af0a55d32f..a19d491fad 100644
      --- a/nuttx/libc/math/lib_pow.c
      +++ b/nuttx/libc/math/lib_pow.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_pow.c
      + * libc/math/lib_pow.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_powf.c b/nuttx/libc/math/lib_powf.c
      index a43f9cf82a..5709048982 100644
      --- a/nuttx/libc/math/lib_powf.c
      +++ b/nuttx/libc/math/lib_powf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_powf.c
      + * libc/math/lib_powf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_powl.c b/nuttx/libc/math/lib_powl.c
      index f5fbf042e9..81438217cf 100644
      --- a/nuttx/libc/math/lib_powl.c
      +++ b/nuttx/libc/math/lib_powl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_powl.c
      + * libc/math/lib_powl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_sin.c b/nuttx/libc/math/lib_sin.c
      index c04d6b88b9..e005d98cb6 100644
      --- a/nuttx/libc/math/lib_sin.c
      +++ b/nuttx/libc/math/lib_sin.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sin.c
      + * libc/math/lib_sin.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_sinf.c b/nuttx/libc/math/lib_sinf.c
      index e298bbba49..9e493d8efc 100644
      --- a/nuttx/libc/math/lib_sinf.c
      +++ b/nuttx/libc/math/lib_sinf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sinf.c
      + * libc/math/lib_sinf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_sinh.c b/nuttx/libc/math/lib_sinh.c
      index f33852433b..0c3e2d11d8 100644
      --- a/nuttx/libc/math/lib_sinh.c
      +++ b/nuttx/libc/math/lib_sinh.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sinh.c
      + * libc/math/lib_sinh.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_sinhf.c b/nuttx/libc/math/lib_sinhf.c
      index e15cb14dc4..e9d198440f 100644
      --- a/nuttx/libc/math/lib_sinhf.c
      +++ b/nuttx/libc/math/lib_sinhf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sinhf.c
      + * libc/math/lib_sinhf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_sinhl.c b/nuttx/libc/math/lib_sinhl.c
      index b0fea29149..a1bcad81e8 100644
      --- a/nuttx/libc/math/lib_sinhl.c
      +++ b/nuttx/libc/math/lib_sinhl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sinhl.c
      + * libc/math/lib_sinhl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_sinl.c b/nuttx/libc/math/lib_sinl.c
      index a69b548cb3..6ed539a39d 100644
      --- a/nuttx/libc/math/lib_sinl.c
      +++ b/nuttx/libc/math/lib_sinl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sinl.c
      + * libc/math/lib_sinl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_sqrt.c b/nuttx/libc/math/lib_sqrt.c
      index d77997f7cd..e8a1c42ea2 100644
      --- a/nuttx/libc/math/lib_sqrt.c
      +++ b/nuttx/libc/math/lib_sqrt.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sqrt.c
      + * libc/math/lib_sqrt.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_sqrtf.c b/nuttx/libc/math/lib_sqrtf.c
      index 81817a0406..cf45ccacc3 100644
      --- a/nuttx/libc/math/lib_sqrtf.c
      +++ b/nuttx/libc/math/lib_sqrtf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sqrtf.c
      + * libc/math/lib_sqrtf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_sqrtl.c b/nuttx/libc/math/lib_sqrtl.c
      index 6674fe50f8..4035992feb 100644
      --- a/nuttx/libc/math/lib_sqrtl.c
      +++ b/nuttx/libc/math/lib_sqrtl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_sqrtl.c
      + * libc/math/lib_sqrtl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_tan.c b/nuttx/libc/math/lib_tan.c
      index bce14b3270..4c091c09bc 100644
      --- a/nuttx/libc/math/lib_tan.c
      +++ b/nuttx/libc/math/lib_tan.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_tan.c
      + * libc/math/lib_tan.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_tanf.c b/nuttx/libc/math/lib_tanf.c
      index 3db3bda265..0c9110a0b7 100644
      --- a/nuttx/libc/math/lib_tanf.c
      +++ b/nuttx/libc/math/lib_tanf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_tanf.c
      + * libc/math/lib_tanf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_tanh.c b/nuttx/libc/math/lib_tanh.c
      index 46fddd06df..3b9ea0f418 100644
      --- a/nuttx/libc/math/lib_tanh.c
      +++ b/nuttx/libc/math/lib_tanh.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_tanh.c
      + * libc/math/lib_tanh.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_tanhf.c b/nuttx/libc/math/lib_tanhf.c
      index 94d15cc60d..43d4182044 100644
      --- a/nuttx/libc/math/lib_tanhf.c
      +++ b/nuttx/libc/math/lib_tanhf.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_tanhf.c
      + * libc/math/lib_tanhf.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_tanhl.c b/nuttx/libc/math/lib_tanhl.c
      index 23c11d6672..5aafd1e7b9 100644
      --- a/nuttx/libc/math/lib_tanhl.c
      +++ b/nuttx/libc/math/lib_tanhl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_tanhl.c
      + * libc/math/lib_tanhl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/math/lib_tanl.c b/nuttx/libc/math/lib_tanl.c
      index 4973aa073c..e77abe0f1e 100644
      --- a/nuttx/libc/math/lib_tanl.c
      +++ b/nuttx/libc/math/lib_tanl.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/math/lib_tanl.c
      + * libc/math/lib_tanl.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/misc/Make.defs b/nuttx/libc/misc/Make.defs
      index c12533f754..f4284ac60c 100644
      --- a/nuttx/libc/misc/Make.defs
      +++ b/nuttx/libc/misc/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/misc/Make.defs
      +# libc/misc/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/misc/lib_crc32.c b/nuttx/libc/misc/lib_crc32.c
      index f851598e01..ae73ba3d79 100644
      --- a/nuttx/libc/misc/lib_crc32.c
      +++ b/nuttx/libc/misc/lib_crc32.c
      @@ -1,5 +1,5 @@
       /************************************************************************************************
      - * lib/misc/lib_crc32.c
      + * libc/misc/lib_crc32.c
        *
        * This file is a part of NuttX:
        *
      diff --git a/nuttx/libc/misc/lib_dbg.c b/nuttx/libc/misc/lib_dbg.c
      index aacdaa30a9..5605ff828f 100644
      --- a/nuttx/libc/misc/lib_dbg.c
      +++ b/nuttx/libc/misc/lib_dbg.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/misc/lib_dbg.c
      + * libc/misc/lib_dbg.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/misc/lib_dumpbuffer.c b/nuttx/libc/misc/lib_dumpbuffer.c
      index 155468ca12..52158b2204 100644
      --- a/nuttx/libc/misc/lib_dumpbuffer.c
      +++ b/nuttx/libc/misc/lib_dumpbuffer.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/misc/lib_dumpbuffer.c
      + * libc/misc/lib_dumpbuffer.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/misc/lib_filesem.c b/nuttx/libc/misc/lib_filesem.c
      index 1d1f25c2fd..5cc4624ec6 100644
      --- a/nuttx/libc/misc/lib_filesem.c
      +++ b/nuttx/libc/misc/lib_filesem.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/misc/lib_filesem.c
      + * libc/misc/lib_filesem.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/misc/lib_init.c b/nuttx/libc/misc/lib_init.c
      index 3403a837b9..6a120f7b13 100644
      --- a/nuttx/libc/misc/lib_init.c
      +++ b/nuttx/libc/misc/lib_init.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/misc/lib_init.c
      + * libc/misc/lib_init.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/misc/lib_match.c b/nuttx/libc/misc/lib_match.c
      index 18e0632ec6..a8cfad3293 100644
      --- a/nuttx/libc/misc/lib_match.c
      +++ b/nuttx/libc/misc/lib_match.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/misc/lib_match.c - simple shell-style filename matcher
      + * libc/misc/lib_match.c - simple shell-style filename matcher
        *
        * Simple shell-style filename pattern matcher written by Jef Poskanzer
        * This pattern matcher only handles '?', '*' and '**', and  multiple
      diff --git a/nuttx/libc/misc/lib_sendfile.c b/nuttx/libc/misc/lib_sendfile.c
      index a82eb325e7..8a38dc317e 100644
      --- a/nuttx/libc/misc/lib_sendfile.c
      +++ b/nuttx/libc/misc/lib_sendfile.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/misc/lib_streamsem.c
      + * libc/misc/lib_streamsem.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/misc/lib_streamsem.c b/nuttx/libc/misc/lib_streamsem.c
      index fdf494e751..e38298bdbb 100644
      --- a/nuttx/libc/misc/lib_streamsem.c
      +++ b/nuttx/libc/misc/lib_streamsem.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/misc/lib_streamsem.c
      + * libc/misc/lib_streamsem.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/mqueue/Make.defs b/nuttx/libc/mqueue/Make.defs
      index 40dc6c13e6..826970fa32 100644
      --- a/nuttx/libc/mqueue/Make.defs
      +++ b/nuttx/libc/mqueue/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/mqueue/Make.defs
      +# libc/mqueue/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/mqueue/mq_getattr.c b/nuttx/libc/mqueue/mq_getattr.c
      index 9c9f47fdce..2fc0e131be 100644
      --- a/nuttx/libc/mqueue/mq_getattr.c
      +++ b/nuttx/libc/mqueue/mq_getattr.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/mqueue/mq_getattr.c
      + * libc/mqueue/mq_getattr.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/mqueue/mq_setattr.c b/nuttx/libc/mqueue/mq_setattr.c
      index 1276d64e8a..45a848e6d7 100644
      --- a/nuttx/libc/mqueue/mq_setattr.c
      +++ b/nuttx/libc/mqueue/mq_setattr.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/mqueue/mq_setattr.c
      + * libc/mqueue/mq_setattr.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/net/Make.defs b/nuttx/libc/net/Make.defs
      index ae041bd2c5..9d4e5c06b3 100644
      --- a/nuttx/libc/net/Make.defs
      +++ b/nuttx/libc/net/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/net/Make.defs
      +# libc/net/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/net/lib_etherntoa.c b/nuttx/libc/net/lib_etherntoa.c
      index f89f205a2e..91fb01c570 100644
      --- a/nuttx/libc/net/lib_etherntoa.c
      +++ b/nuttx/libc/net/lib_etherntoa.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/net/lib_etherntoa.c
      + * libc/net/lib_etherntoa.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/net/lib_htonl.c b/nuttx/libc/net/lib_htonl.c
      index e4c3e53838..a10f54f379 100644
      --- a/nuttx/libc/net/lib_htonl.c
      +++ b/nuttx/libc/net/lib_htonl.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/net/lib_ntohl.c
      + * libc/net/lib_ntohl.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/net/lib_htons.c b/nuttx/libc/net/lib_htons.c
      index b4117e1dc2..13addd9136 100644
      --- a/nuttx/libc/net/lib_htons.c
      +++ b/nuttx/libc/net/lib_htons.c
      @@ -1,5 +1,5 @@
       /***************************************************************************
      - * lib/net/lib_htons.c
      + * libc/net/lib_htons.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/net/lib_inetaddr.c b/nuttx/libc/net/lib_inetaddr.c
      index 48b01d682f..46c6c548dc 100644
      --- a/nuttx/libc/net/lib_inetaddr.c
      +++ b/nuttx/libc/net/lib_inetaddr.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/net/lib_inetaddr.c
      + * libc/net/lib_inetaddr.c
        *
        *   Copyright (C) 2011 Yu Qiang. All rights reserved.
        *   Author: Yu Qiang 
      diff --git a/nuttx/libc/net/lib_inetntoa.c b/nuttx/libc/net/lib_inetntoa.c
      index 0f4fb61df6..e2d92d8648 100644
      --- a/nuttx/libc/net/lib_inetntoa.c
      +++ b/nuttx/libc/net/lib_inetntoa.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/net/lib_inetntoa.c
      + * libc/net/lib_inetntoa.c
        *
        *   Copyright (C) 2007-2008, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/net/lib_inetntop.c b/nuttx/libc/net/lib_inetntop.c
      index dc6a2d0d79..25c32c48cf 100644
      --- a/nuttx/libc/net/lib_inetntop.c
      +++ b/nuttx/libc/net/lib_inetntop.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/net/lib_inetntop.c
      + * libc/net/lib_inetntop.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/net/lib_inetpton.c b/nuttx/libc/net/lib_inetpton.c
      index 5371cd3f21..c5f117535b 100644
      --- a/nuttx/libc/net/lib_inetpton.c
      +++ b/nuttx/libc/net/lib_inetpton.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/net/lib_inetpton.c
      + * libc/net/lib_inetpton.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/Make.defs b/nuttx/libc/pthread/Make.defs
      index a1eba7bb0a..07e4f05701 100644
      --- a/nuttx/libc/pthread/Make.defs
      +++ b/nuttx/libc/pthread/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/pthread/Make.defs
      +# libc/pthread/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_attrdestroy.c b/nuttx/libc/pthread/pthread_attrdestroy.c
      index 103528c7e1..37ad46ebcd 100644
      --- a/nuttx/libc/pthread/pthread_attrdestroy.c
      +++ b/nuttx/libc/pthread/pthread_attrdestroy.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_attrdestroy.c
      + * libc/pthread/pthread_attrdestroy.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_attrgetinheritsched.c b/nuttx/libc/pthread/pthread_attrgetinheritsched.c
      index 02d6e0b7c0..6ec8ae71f6 100644
      --- a/nuttx/libc/pthread/pthread_attrgetinheritsched.c
      +++ b/nuttx/libc/pthread/pthread_attrgetinheritsched.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_attrgetinheritsched.c
      + * libc/pthread/pthread_attrgetinheritsched.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_attrgetschedparam.c b/nuttx/libc/pthread/pthread_attrgetschedparam.c
      index c6bf55dea8..6bcc9618e9 100644
      --- a/nuttx/libc/pthread/pthread_attrgetschedparam.c
      +++ b/nuttx/libc/pthread/pthread_attrgetschedparam.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_attrgetschedparam.c
      + * libc/pthread/pthread_attrgetschedparam.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_attrgetschedpolicy.c b/nuttx/libc/pthread/pthread_attrgetschedpolicy.c
      index c42b828c96..8845e2bd81 100644
      --- a/nuttx/libc/pthread/pthread_attrgetschedpolicy.c
      +++ b/nuttx/libc/pthread/pthread_attrgetschedpolicy.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_attrgetschedpolicy.c
      + * libc/pthread/pthread_attrgetschedpolicy.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_attrgetstacksize.c b/nuttx/libc/pthread/pthread_attrgetstacksize.c
      index 2faa586ba8..9fde29e810 100644
      --- a/nuttx/libc/pthread/pthread_attrgetstacksize.c
      +++ b/nuttx/libc/pthread/pthread_attrgetstacksize.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_attrgetstacksize.c
      + * libc/pthread/pthread_attrgetstacksize.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_attrinit.c b/nuttx/libc/pthread/pthread_attrinit.c
      index d06a535d78..427a582b91 100644
      --- a/nuttx/libc/pthread/pthread_attrinit.c
      +++ b/nuttx/libc/pthread/pthread_attrinit.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_attrinit.c
      + * libc/pthread/pthread_attrinit.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_attrsetinheritsched.c b/nuttx/libc/pthread/pthread_attrsetinheritsched.c
      index df2c2fba33..1102fe176a 100644
      --- a/nuttx/libc/pthread/pthread_attrsetinheritsched.c
      +++ b/nuttx/libc/pthread/pthread_attrsetinheritsched.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_attrsetinheritsched.c
      + * libc/pthread/pthread_attrsetinheritsched.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_attrsetschedparam.c b/nuttx/libc/pthread/pthread_attrsetschedparam.c
      index c2ab4d1c41..587d62206b 100644
      --- a/nuttx/libc/pthread/pthread_attrsetschedparam.c
      +++ b/nuttx/libc/pthread/pthread_attrsetschedparam.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_attrsetschedparam.c
      + * libc/pthread/pthread_attrsetschedparam.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_attrsetschedpolicy.c b/nuttx/libc/pthread/pthread_attrsetschedpolicy.c
      index 4e43e635de..e1d1c86195 100644
      --- a/nuttx/libc/pthread/pthread_attrsetschedpolicy.c
      +++ b/nuttx/libc/pthread/pthread_attrsetschedpolicy.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_attrsetschedpolicy.c
      + * libc/pthread/pthread_attrsetschedpolicy.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_attrsetstacksize.c b/nuttx/libc/pthread/pthread_attrsetstacksize.c
      index 8a826dd3ac..fca993baf8 100644
      --- a/nuttx/libc/pthread/pthread_attrsetstacksize.c
      +++ b/nuttx/libc/pthread/pthread_attrsetstacksize.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_attrsetstacksize.c
      + * libc/pthread/pthread_attrsetstacksize.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_barrierattrdestroy.c b/nuttx/libc/pthread/pthread_barrierattrdestroy.c
      index 6d16b9cff8..5519caa61f 100644
      --- a/nuttx/libc/pthread/pthread_barrierattrdestroy.c
      +++ b/nuttx/libc/pthread/pthread_barrierattrdestroy.c
      @@ -1,5 +1,5 @@
       /********************************************************************************
      - * lib/pthread/pthread_barrierattrdestroy.c
      + * libc/pthread/pthread_barrierattrdestroy.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_barrierattrgetpshared.c b/nuttx/libc/pthread/pthread_barrierattrgetpshared.c
      index d29bc6dfc8..83faffae08 100644
      --- a/nuttx/libc/pthread/pthread_barrierattrgetpshared.c
      +++ b/nuttx/libc/pthread/pthread_barrierattrgetpshared.c
      @@ -1,5 +1,5 @@
       /********************************************************************************
      - * lib/pthread/pthread_barrierattrgetpshared.c
      + * libc/pthread/pthread_barrierattrgetpshared.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_barrierattrinit.c b/nuttx/libc/pthread/pthread_barrierattrinit.c
      index b5f35ca917..7ab1018835 100644
      --- a/nuttx/libc/pthread/pthread_barrierattrinit.c
      +++ b/nuttx/libc/pthread/pthread_barrierattrinit.c
      @@ -1,5 +1,5 @@
       /********************************************************************************
      - * lib/pthread/pthread_barrierattrinit.c
      + * libc/pthread/pthread_barrierattrinit.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_barrierattrsetpshared.c b/nuttx/libc/pthread/pthread_barrierattrsetpshared.c
      index d0eecbf5a4..2585de7a0d 100644
      --- a/nuttx/libc/pthread/pthread_barrierattrsetpshared.c
      +++ b/nuttx/libc/pthread/pthread_barrierattrsetpshared.c
      @@ -1,5 +1,5 @@
       /********************************************************************************
      - * lib/pthread/pthread_barrierattrsetpshared.c
      + * libc/pthread/pthread_barrierattrsetpshared.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_condattrdestroy.c b/nuttx/libc/pthread/pthread_condattrdestroy.c
      index d6c3df5d1a..30a0c4db1b 100644
      --- a/nuttx/libc/pthread/pthread_condattrdestroy.c
      +++ b/nuttx/libc/pthread/pthread_condattrdestroy.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_condattrdestroy.c
      + * libc/pthread/pthread_condattrdestroy.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_condattrinit.c b/nuttx/libc/pthread/pthread_condattrinit.c
      index 5721c61593..511376f2e6 100644
      --- a/nuttx/libc/pthread/pthread_condattrinit.c
      +++ b/nuttx/libc/pthread/pthread_condattrinit.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_condattrinit.c
      + * libc/pthread/pthread_condattrinit.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_mutexattrdestroy.c b/nuttx/libc/pthread/pthread_mutexattrdestroy.c
      index e9868df68b..82a13c300e 100644
      --- a/nuttx/libc/pthread/pthread_mutexattrdestroy.c
      +++ b/nuttx/libc/pthread/pthread_mutexattrdestroy.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_mutexattrdestroy.c
      + * libc/pthread/pthread_mutexattrdestroy.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_mutexattrgetpshared.c b/nuttx/libc/pthread/pthread_mutexattrgetpshared.c
      index bc6379db5f..dc18484ec5 100644
      --- a/nuttx/libc/pthread/pthread_mutexattrgetpshared.c
      +++ b/nuttx/libc/pthread/pthread_mutexattrgetpshared.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_mutexattrgetpshared.c
      + * libc/pthread/pthread_mutexattrgetpshared.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_mutexattrgettype.c b/nuttx/libc/pthread/pthread_mutexattrgettype.c
      index 5fb10f3015..3b8b3ec052 100644
      --- a/nuttx/libc/pthread/pthread_mutexattrgettype.c
      +++ b/nuttx/libc/pthread/pthread_mutexattrgettype.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_mutexattrgettype.c
      + * libc/pthread/pthread_mutexattrgettype.c
        *
        *   Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_mutexattrinit.c b/nuttx/libc/pthread/pthread_mutexattrinit.c
      index f815bf16c1..f8c2721953 100644
      --- a/nuttx/libc/pthread/pthread_mutexattrinit.c
      +++ b/nuttx/libc/pthread/pthread_mutexattrinit.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_mutexattrinit.c
      + * libc/pthread/pthread_mutexattrinit.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_mutexattrsetpshared.c b/nuttx/libc/pthread/pthread_mutexattrsetpshared.c
      index 900476fdd2..7501fd980b 100644
      --- a/nuttx/libc/pthread/pthread_mutexattrsetpshared.c
      +++ b/nuttx/libc/pthread/pthread_mutexattrsetpshared.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_mutexattrsetpshared.c
      + * libc/pthread/pthread_mutexattrsetpshared.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/pthread/pthread_mutexattrsettype.c b/nuttx/libc/pthread/pthread_mutexattrsettype.c
      index 81427c757e..068a27dc26 100644
      --- a/nuttx/libc/pthread/pthread_mutexattrsettype.c
      +++ b/nuttx/libc/pthread/pthread_mutexattrsettype.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/pthread/pthread_mutexattrsettype.c
      + * libc/pthread/pthread_mutexattrsettype.c
        *
        *   Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/Make.defs b/nuttx/libc/queue/Make.defs
      index 976e7a2b87..9a843dbdc9 100644
      --- a/nuttx/libc/queue/Make.defs
      +++ b/nuttx/libc/queue/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/queue/Make.defs
      +# libc/queue/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/dq_addafter.c b/nuttx/libc/queue/dq_addafter.c
      index bfbe0052d8..e4d1abf63d 100644
      --- a/nuttx/libc/queue/dq_addafter.c
      +++ b/nuttx/libc/queue/dq_addafter.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/dq_addafter.c
      + * libc/queue/dq_addafter.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/dq_addbefore.c b/nuttx/libc/queue/dq_addbefore.c
      index d740ea8309..3c403fc944 100644
      --- a/nuttx/libc/queue/dq_addbefore.c
      +++ b/nuttx/libc/queue/dq_addbefore.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/queue/dq_addbefore.c
      + * libc/queue/dq_addbefore.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/dq_addfirst.c b/nuttx/libc/queue/dq_addfirst.c
      index 7c7312de3b..56767b9289 100644
      --- a/nuttx/libc/queue/dq_addfirst.c
      +++ b/nuttx/libc/queue/dq_addfirst.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/dq_addfirst.c
      + * libc/queue/dq_addfirst.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/dq_addlast.c b/nuttx/libc/queue/dq_addlast.c
      index 745deb27d1..3ef08abd05 100644
      --- a/nuttx/libc/queue/dq_addlast.c
      +++ b/nuttx/libc/queue/dq_addlast.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/dq_addlast.c
      + * libc/queue/dq_addlast.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/dq_rem.c b/nuttx/libc/queue/dq_rem.c
      index 218427bf84..db20762c75 100644
      --- a/nuttx/libc/queue/dq_rem.c
      +++ b/nuttx/libc/queue/dq_rem.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/dq_rem.c
      + * libc/queue/dq_rem.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/dq_remfirst.c b/nuttx/libc/queue/dq_remfirst.c
      index 26c5fd7a67..e87acc3382 100644
      --- a/nuttx/libc/queue/dq_remfirst.c
      +++ b/nuttx/libc/queue/dq_remfirst.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/dq_remfirst.c
      + * libc/queue/dq_remfirst.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/dq_remlast.c b/nuttx/libc/queue/dq_remlast.c
      index 35adc73e2d..18c1823359 100644
      --- a/nuttx/libc/queue/dq_remlast.c
      +++ b/nuttx/libc/queue/dq_remlast.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/queue/dq_remlast.c
      + * libc/queue/dq_remlast.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/sq_addafter.c b/nuttx/libc/queue/sq_addafter.c
      index 965ac28444..5d47feba0f 100644
      --- a/nuttx/libc/queue/sq_addafter.c
      +++ b/nuttx/libc/queue/sq_addafter.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/sq_addafter.c
      + * libc/queue/sq_addafter.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/sq_addfirst.c b/nuttx/libc/queue/sq_addfirst.c
      index 8fc8e06199..9624861541 100644
      --- a/nuttx/libc/queue/sq_addfirst.c
      +++ b/nuttx/libc/queue/sq_addfirst.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/sq_addfirst.c
      + * libc/queue/sq_addfirst.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/sq_addlast.c b/nuttx/libc/queue/sq_addlast.c
      index f9f9625cc0..faa07efb5c 100644
      --- a/nuttx/libc/queue/sq_addlast.c
      +++ b/nuttx/libc/queue/sq_addlast.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/sq_addlast.c
      + * libc/queue/sq_addlast.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/sq_rem.c b/nuttx/libc/queue/sq_rem.c
      index 6ba52354d4..720be182cd 100644
      --- a/nuttx/libc/queue/sq_rem.c
      +++ b/nuttx/libc/queue/sq_rem.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/sq_rem.c
      + * libc/queue/sq_rem.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/sq_remafter.c b/nuttx/libc/queue/sq_remafter.c
      index 4dcfb06e44..0545a00f95 100644
      --- a/nuttx/libc/queue/sq_remafter.c
      +++ b/nuttx/libc/queue/sq_remafter.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/sq_remafter.c
      + * libc/queue/sq_remafter.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/sq_remfirst.c b/nuttx/libc/queue/sq_remfirst.c
      index 43df6de417..f81c18dc2e 100644
      --- a/nuttx/libc/queue/sq_remfirst.c
      +++ b/nuttx/libc/queue/sq_remfirst.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/sq_remfirst.c
      + * libc/queue/sq_remfirst.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/queue/sq_remlast.c b/nuttx/libc/queue/sq_remlast.c
      index 92cdbde985..8f045e4932 100644
      --- a/nuttx/libc/queue/sq_remlast.c
      +++ b/nuttx/libc/queue/sq_remlast.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/queue/sq_remlast.c
      + * libc/queue/sq_remlast.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/sched/Make.defs b/nuttx/libc/sched/Make.defs
      index f398b755e0..d2356db0f1 100644
      --- a/nuttx/libc/sched/Make.defs
      +++ b/nuttx/libc/sched/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/sched/Make.defs
      +# libc/sched/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/sched/sched_getprioritymax.c b/nuttx/libc/sched/sched_getprioritymax.c
      index 14b368dfc0..6ea37e76a9 100644
      --- a/nuttx/libc/sched/sched_getprioritymax.c
      +++ b/nuttx/libc/sched/sched_getprioritymax.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/sched/sched_getprioritymax.c
      + * libc/sched/sched_getprioritymax.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/sched/sched_getprioritymin.c b/nuttx/libc/sched/sched_getprioritymin.c
      index 86410cb0f6..dbb46d81eb 100644
      --- a/nuttx/libc/sched/sched_getprioritymin.c
      +++ b/nuttx/libc/sched/sched_getprioritymin.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/sched/sched_getprioritymin.c
      + * libc/sched/sched_getprioritymin.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/semaphore/Make.defs b/nuttx/libc/semaphore/Make.defs
      index fdc0fe7d54..b6551ff96a 100644
      --- a/nuttx/libc/semaphore/Make.defs
      +++ b/nuttx/libc/semaphore/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/semaphore/Make.defs
      +# libc/semaphore/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/semaphore/sem_getvalue.c b/nuttx/libc/semaphore/sem_getvalue.c
      index 31c6bb7e06..ce9d12611a 100644
      --- a/nuttx/libc/semaphore/sem_getvalue.c
      +++ b/nuttx/libc/semaphore/sem_getvalue.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/semaphore/sem_getvalue.c
      + * libc/semaphore/sem_getvalue.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/semaphore/sem_init.c b/nuttx/libc/semaphore/sem_init.c
      index bc14415f97..7732eb57a5 100644
      --- a/nuttx/libc/semaphore/sem_init.c
      +++ b/nuttx/libc/semaphore/sem_init.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/sem/sem_init.c
      + * libc/sem/sem_init.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/signal/Make.defs b/nuttx/libc/signal/Make.defs
      index e27da9b2e8..fe7eb180e7 100644
      --- a/nuttx/libc/signal/Make.defs
      +++ b/nuttx/libc/signal/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/signal/Make.defs
      +# libc/signal/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/signal/sig_addset.c b/nuttx/libc/signal/sig_addset.c
      index 19ba0cb6b6..06ddabd6b2 100644
      --- a/nuttx/libc/signal/sig_addset.c
      +++ b/nuttx/libc/signal/sig_addset.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/signal/sig_addset.c
      + * libc/signal/sig_addset.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/signal/sig_delset.c b/nuttx/libc/signal/sig_delset.c
      index 1c661d37f6..04112d8729 100644
      --- a/nuttx/libc/signal/sig_delset.c
      +++ b/nuttx/libc/signal/sig_delset.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/signal/sig_delset.c
      + * libc/signal/sig_delset.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/signal/sig_emptyset.c b/nuttx/libc/signal/sig_emptyset.c
      index ac0c6b3e89..16ddd3f68f 100644
      --- a/nuttx/libc/signal/sig_emptyset.c
      +++ b/nuttx/libc/signal/sig_emptyset.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/signal/sig_emptyset.c
      + * libc/signal/sig_emptyset.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/signal/sig_fillset.c b/nuttx/libc/signal/sig_fillset.c
      index 8697d7577f..99ee95c1ff 100644
      --- a/nuttx/libc/signal/sig_fillset.c
      +++ b/nuttx/libc/signal/sig_fillset.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/signal/sig_fillset.c
      + * libc/signal/sig_fillset.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/signal/sig_ismember.c b/nuttx/libc/signal/sig_ismember.c
      index c5bb091b7b..1a8590e003 100644
      --- a/nuttx/libc/signal/sig_ismember.c
      +++ b/nuttx/libc/signal/sig_ismember.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/signal/sig_ismember.c
      + * libc/signal/sig_ismember.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/Make.defs b/nuttx/libc/stdio/Make.defs
      index e4ee5e9699..e18ab0220f 100644
      --- a/nuttx/libc/stdio/Make.defs
      +++ b/nuttx/libc/stdio/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/stdio/Make.defs
      +# libc/stdio/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_asprintf.c b/nuttx/libc/stdio/lib_asprintf.c
      index 84aaafa462..20ca6de326 100644
      --- a/nuttx/libc/stdio/lib_asprintf.c
      +++ b/nuttx/libc/stdio/lib_asprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_asprintf.c
      + * libc/stdio/lib_asprintf.c
        *
        *   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_avsprintf.c b/nuttx/libc/stdio/lib_avsprintf.c
      index 8561b97c21..15ff8c9fbd 100644
      --- a/nuttx/libc/stdio/lib_avsprintf.c
      +++ b/nuttx/libc/stdio/lib_avsprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_avsprintf.c
      + * libc/stdio/lib_avsprintf.c
        *
        *   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_clearerr.c b/nuttx/libc/stdio/lib_clearerr.c
      index 7f7ded5bb4..589b56feb6 100644
      --- a/nuttx/libc/stdio/lib_clearerr.c
      +++ b/nuttx/libc/stdio/lib_clearerr.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_clearerr.c
      + * libc/stdio/lib_clearerr.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_dtoa.c b/nuttx/libc/stdio/lib_dtoa.c
      index b8c7db9803..44290ae328 100644
      --- a/nuttx/libc/stdio/lib_dtoa.c
      +++ b/nuttx/libc/stdio/lib_dtoa.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_dtoa.c
      + * libc/stdio/lib_dtoa.c
        *
        * This file was ported to NuttX by Yolande Cates.
        *
      diff --git a/nuttx/libc/stdio/lib_fclose.c b/nuttx/libc/stdio/lib_fclose.c
      index 8cecb8af3c..c04537adf7 100644
      --- a/nuttx/libc/stdio/lib_fclose.c
      +++ b/nuttx/libc/stdio/lib_fclose.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fclose.c
      + * libc/stdio/lib_fclose.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_feof.c b/nuttx/libc/stdio/lib_feof.c
      index e44c6a3c92..e036398fda 100644
      --- a/nuttx/libc/stdio/lib_feof.c
      +++ b/nuttx/libc/stdio/lib_feof.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_feof.c
      + * libc/stdio/lib_feof.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_ferror.c b/nuttx/libc/stdio/lib_ferror.c
      index 4ad7d8cfca..a977394cb1 100644
      --- a/nuttx/libc/stdio/lib_ferror.c
      +++ b/nuttx/libc/stdio/lib_ferror.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_ferror.c
      + * libc/stdio/lib_ferror.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fflush.c b/nuttx/libc/stdio/lib_fflush.c
      index d0b5e0185d..a84a14a599 100644
      --- a/nuttx/libc/stdio/lib_fflush.c
      +++ b/nuttx/libc/stdio/lib_fflush.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fflush.c
      + * libc/stdio/lib_fflush.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fgetc.c b/nuttx/libc/stdio/lib_fgetc.c
      index 4b3d0ec44f..81e2e4ba72 100644
      --- a/nuttx/libc/stdio/lib_fgetc.c
      +++ b/nuttx/libc/stdio/lib_fgetc.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fgetc.c
      + * libc/stdio/lib_fgetc.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fgetpos.c b/nuttx/libc/stdio/lib_fgetpos.c
      index e9e9f4d102..7663ca2dbe 100644
      --- a/nuttx/libc/stdio/lib_fgetpos.c
      +++ b/nuttx/libc/stdio/lib_fgetpos.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fgetpos.c
      + * libc/stdio/lib_fgetpos.c
        *
        *   Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fgets.c b/nuttx/libc/stdio/lib_fgets.c
      index a4f9089ed7..c2c98a38b6 100644
      --- a/nuttx/libc/stdio/lib_fgets.c
      +++ b/nuttx/libc/stdio/lib_fgets.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fgets.c
      + * libc/stdio/lib_fgets.c
        *
        *   Copyright (C) 2007-2008, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fileno.c b/nuttx/libc/stdio/lib_fileno.c
      index fca08fc0d4..f227aa372b 100644
      --- a/nuttx/libc/stdio/lib_fileno.c
      +++ b/nuttx/libc/stdio/lib_fileno.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fileno.c
      + * libc/stdio/lib_fileno.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fopen.c b/nuttx/libc/stdio/lib_fopen.c
      index 29ff4569c2..cb68b35843 100644
      --- a/nuttx/libc/stdio/lib_fopen.c
      +++ b/nuttx/libc/stdio/lib_fopen.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fopen.c
      + * libc/stdio/lib_fopen.c
        *
        *   Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fprintf.c b/nuttx/libc/stdio/lib_fprintf.c
      index a803de4bd0..5b6fe58f42 100644
      --- a/nuttx/libc/stdio/lib_fprintf.c
      +++ b/nuttx/libc/stdio/lib_fprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fprintf.c
      + * libc/stdio/lib_fprintf.c
        *
        *   Copyright (C) 2007, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fputc.c b/nuttx/libc/stdio/lib_fputc.c
      index 121161f102..5d8065b431 100644
      --- a/nuttx/libc/stdio/lib_fputc.c
      +++ b/nuttx/libc/stdio/lib_fputc.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fputc.c
      + * libc/stdio/lib_fputc.c
        *
        *   Copyright (C) 2007, 2008, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fputs.c b/nuttx/libc/stdio/lib_fputs.c
      index 2d6217d4aa..7b87a89d00 100644
      --- a/nuttx/libc/stdio/lib_fputs.c
      +++ b/nuttx/libc/stdio/lib_fputs.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fputs.c
      + * libc/stdio/lib_fputs.c
        *
        *   Copyright (C) 2007, 2008, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fread.c b/nuttx/libc/stdio/lib_fread.c
      index 4a4b29256d..6717141225 100644
      --- a/nuttx/libc/stdio/lib_fread.c
      +++ b/nuttx/libc/stdio/lib_fread.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fread.c
      + * libc/stdio/lib_fread.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fseek.c b/nuttx/libc/stdio/lib_fseek.c
      index 7380f83b3b..36216d94a9 100644
      --- a/nuttx/libc/stdio/lib_fseek.c
      +++ b/nuttx/libc/stdio/lib_fseek.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fseek.c
      + * libc/stdio/lib_fseek.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fsetpos.c b/nuttx/libc/stdio/lib_fsetpos.c
      index 13d556521b..3d79a18775 100644
      --- a/nuttx/libc/stdio/lib_fsetpos.c
      +++ b/nuttx/libc/stdio/lib_fsetpos.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fsetpos.c
      + * libc/stdio/lib_fsetpos.c
        *
        *   Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_ftell.c b/nuttx/libc/stdio/lib_ftell.c
      index 9476481529..99fc20f340 100644
      --- a/nuttx/libc/stdio/lib_ftell.c
      +++ b/nuttx/libc/stdio/lib_ftell.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_ftell.c
      + * libc/stdio/lib_ftell.c
        *
        *   Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_fwrite.c b/nuttx/libc/stdio/lib_fwrite.c
      index 60e0017463..e8de004feb 100644
      --- a/nuttx/libc/stdio/lib_fwrite.c
      +++ b/nuttx/libc/stdio/lib_fwrite.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_fwrite.c
      + * libc/stdio/lib_fwrite.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_gets.c b/nuttx/libc/stdio/lib_gets.c
      index 95a6b36ebf..39c31d273d 100644
      --- a/nuttx/libc/stdio/lib_gets.c
      +++ b/nuttx/libc/stdio/lib_gets.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_gets.c
      + * libc/stdio/lib_gets.c
        *
        *   Copyright (C) 2007-2008, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_libdtoa.c b/nuttx/libc/stdio/lib_libdtoa.c
      index 667c49c535..29f61fd76e 100644
      --- a/nuttx/libc/stdio/lib_libdtoa.c
      +++ b/nuttx/libc/stdio/lib_libdtoa.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/unistd/lib_libdtoa.c
      + * libc/unistd/lib_libdtoa.c
        *
        * This file was ported to NuttX by Yolande Cates.
        *
      diff --git a/nuttx/libc/stdio/lib_libfflush.c b/nuttx/libc/stdio/lib_libfflush.c
      index 2a4fe29326..f2f0cfe144 100644
      --- a/nuttx/libc/stdio/lib_libfflush.c
      +++ b/nuttx/libc/stdio/lib_libfflush.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_libfflush.c
      + * libc/stdio/lib_libfflush.c
        *
        *   Copyright (C) 2007-2008, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_libflushall.c b/nuttx/libc/stdio/lib_libflushall.c
      index 9d0a89e9c1..7ac3da7e0e 100644
      --- a/nuttx/libc/stdio/lib_libflushall.c
      +++ b/nuttx/libc/stdio/lib_libflushall.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_libflushall.c
      + * libc/stdio/lib_libflushall.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_libfread.c b/nuttx/libc/stdio/lib_libfread.c
      index 5585acbaea..bc6479037d 100644
      --- a/nuttx/libc/stdio/lib_libfread.c
      +++ b/nuttx/libc/stdio/lib_libfread.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_libfread.c
      + * libc/stdio/lib_libfread.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_libfwrite.c b/nuttx/libc/stdio/lib_libfwrite.c
      index e71866b498..b917b3b564 100644
      --- a/nuttx/libc/stdio/lib_libfwrite.c
      +++ b/nuttx/libc/stdio/lib_libfwrite.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_libfwrite.c
      + * libc/stdio/lib_libfwrite.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_libnoflush.c b/nuttx/libc/stdio/lib_libnoflush.c
      index e3b8911534..076f8a17e6 100644
      --- a/nuttx/libc/stdio/lib_libnoflush.c
      +++ b/nuttx/libc/stdio/lib_libnoflush.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_libnoflush.c
      + * libc/stdio/lib_libnoflush.c
        *
        *   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_libsprintf.c b/nuttx/libc/stdio/lib_libsprintf.c
      index 2474a6f01d..2d820ab37b 100644
      --- a/nuttx/libc/stdio/lib_libsprintf.c
      +++ b/nuttx/libc/stdio/lib_libsprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_libsprintf.c
      + * libc/stdio/lib_libsprintf.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_libvsprintf.c b/nuttx/libc/stdio/lib_libvsprintf.c
      index 30c988599c..9a391610dc 100644
      --- a/nuttx/libc/stdio/lib_libvsprintf.c
      +++ b/nuttx/libc/stdio/lib_libvsprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_libvsprintf.c
      + * libc/stdio/lib_libvsprintf.c
        *
        *   Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      @@ -1161,7 +1161,7 @@ static void postjustify(FAR struct lib_outstream_s *obj, uint8_t fmt,
        ****************************************************************************/
       
       /****************************************************************************
      - * lib/stdio/lib_vsprintf
      + * libc/stdio/lib_vsprintf
        ****************************************************************************/
       
       int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list ap)
      diff --git a/nuttx/libc/stdio/lib_lowinstream.c b/nuttx/libc/stdio/lib_lowinstream.c
      index 499a647ea2..7284601e8e 100644
      --- a/nuttx/libc/stdio/lib_lowinstream.c
      +++ b/nuttx/libc/stdio/lib_lowinstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_lowinstream.c
      + * libc/stdio/lib_lowinstream.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_lowoutstream.c b/nuttx/libc/stdio/lib_lowoutstream.c
      index 092f39ca25..f600bc614a 100644
      --- a/nuttx/libc/stdio/lib_lowoutstream.c
      +++ b/nuttx/libc/stdio/lib_lowoutstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_lowoutstream.c
      + * libc/stdio/lib_lowoutstream.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_lowprintf.c b/nuttx/libc/stdio/lib_lowprintf.c
      index 392ef2c6a8..f7d4ffe2fe 100644
      --- a/nuttx/libc/stdio/lib_lowprintf.c
      +++ b/nuttx/libc/stdio/lib_lowprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_lowprintf.c
      + * libc/stdio/lib_lowprintf.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_meminstream.c b/nuttx/libc/stdio/lib_meminstream.c
      index a842096fb4..2a30d956d6 100644
      --- a/nuttx/libc/stdio/lib_meminstream.c
      +++ b/nuttx/libc/stdio/lib_meminstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_meminstream.c
      + * libc/stdio/lib_meminstream.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_memoutstream.c b/nuttx/libc/stdio/lib_memoutstream.c
      index 21197358b7..efd527cbc5 100644
      --- a/nuttx/libc/stdio/lib_memoutstream.c
      +++ b/nuttx/libc/stdio/lib_memoutstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_memoutstream.c
      + * libc/stdio/lib_memoutstream.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_nullinstream.c b/nuttx/libc/stdio/lib_nullinstream.c
      index 0eadb0a8e4..aeb0af3790 100644
      --- a/nuttx/libc/stdio/lib_nullinstream.c
      +++ b/nuttx/libc/stdio/lib_nullinstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_nullinstream.c
      + * libc/stdio/lib_nullinstream.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_nulloutstream.c b/nuttx/libc/stdio/lib_nulloutstream.c
      index 69878fd579..5742953448 100644
      --- a/nuttx/libc/stdio/lib_nulloutstream.c
      +++ b/nuttx/libc/stdio/lib_nulloutstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_nulloutstream.c
      + * libc/stdio/lib_nulloutstream.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_perror.c b/nuttx/libc/stdio/lib_perror.c
      index 867e113f98..1818983292 100644
      --- a/nuttx/libc/stdio/lib_perror.c
      +++ b/nuttx/libc/stdio/lib_perror.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_perror.c
      + * libc/stdio/lib_perror.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_printf.c b/nuttx/libc/stdio/lib_printf.c
      index 50db06c475..0e90c7ca5a 100644
      --- a/nuttx/libc/stdio/lib_printf.c
      +++ b/nuttx/libc/stdio/lib_printf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_printf.c
      + * libc/stdio/lib_printf.c
        *
        *   Copyright (C) 2007-2008, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_puts.c b/nuttx/libc/stdio/lib_puts.c
      index e63a63917f..53eda7081e 100644
      --- a/nuttx/libc/stdio/lib_puts.c
      +++ b/nuttx/libc/stdio/lib_puts.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_puts.c
      + * libc/stdio/lib_puts.c
        *
        *   Copyright (C) 2007, 2008, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_rawinstream.c b/nuttx/libc/stdio/lib_rawinstream.c
      index 9671a27166..55456769eb 100644
      --- a/nuttx/libc/stdio/lib_rawinstream.c
      +++ b/nuttx/libc/stdio/lib_rawinstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_rawinstream.c
      + * libc/stdio/lib_rawinstream.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_rawoutstream.c b/nuttx/libc/stdio/lib_rawoutstream.c
      index ed813f87aa..e1fe371346 100644
      --- a/nuttx/libc/stdio/lib_rawoutstream.c
      +++ b/nuttx/libc/stdio/lib_rawoutstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_rawoutstream.c
      + * libc/stdio/lib_rawoutstream.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_rawprintf.c b/nuttx/libc/stdio/lib_rawprintf.c
      index 19dfa895e1..98bbbea053 100644
      --- a/nuttx/libc/stdio/lib_rawprintf.c
      +++ b/nuttx/libc/stdio/lib_rawprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_rawprintf.c
      + * libc/stdio/lib_rawprintf.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_rdflush.c b/nuttx/libc/stdio/lib_rdflush.c
      index 35c5495c17..c6136792bb 100644
      --- a/nuttx/libc/stdio/lib_rdflush.c
      +++ b/nuttx/libc/stdio/lib_rdflush.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_rdflush.c
      + * libc/stdio/lib_rdflush.c
        *
        *   Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_snprintf.c b/nuttx/libc/stdio/lib_snprintf.c
      index e5ce7b0f02..a4ba0dbb30 100644
      --- a/nuttx/libc/stdio/lib_snprintf.c
      +++ b/nuttx/libc/stdio/lib_snprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_snprintf.c
      + * libc/stdio/lib_snprintf.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_sprintf.c b/nuttx/libc/stdio/lib_sprintf.c
      index 89fd610330..deb0669a3b 100644
      --- a/nuttx/libc/stdio/lib_sprintf.c
      +++ b/nuttx/libc/stdio/lib_sprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_sprintf.c
      + * libc/stdio/lib_sprintf.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_sscanf.c b/nuttx/libc/stdio/lib_sscanf.c
      index 7e1fae276d..77a6cf212f 100644
      --- a/nuttx/libc/stdio/lib_sscanf.c
      +++ b/nuttx/libc/stdio/lib_sscanf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_sscanf.c
      + * libc/stdio/lib_sscanf.c
        *
        *   Copyright (C) 2007, 2008, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_stdinstream.c b/nuttx/libc/stdio/lib_stdinstream.c
      index 77aab9ec88..261b266346 100644
      --- a/nuttx/libc/stdio/lib_stdinstream.c
      +++ b/nuttx/libc/stdio/lib_stdinstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_stdinstream.c
      + * libc/stdio/lib_stdinstream.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_stdoutstream.c b/nuttx/libc/stdio/lib_stdoutstream.c
      index 20da5b7026..dfe67271f1 100644
      --- a/nuttx/libc/stdio/lib_stdoutstream.c
      +++ b/nuttx/libc/stdio/lib_stdoutstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_stdoutstream.c
      + * libc/stdio/lib_stdoutstream.c
        *
        *   Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_syslogstream.c b/nuttx/libc/stdio/lib_syslogstream.c
      index 21151b43a1..5529c5de8c 100644
      --- a/nuttx/libc/stdio/lib_syslogstream.c
      +++ b/nuttx/libc/stdio/lib_syslogstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_syslogstream.c
      + * libc/stdio/lib_syslogstream.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_ungetc.c b/nuttx/libc/stdio/lib_ungetc.c
      index c10d4fba1a..178aeddd10 100644
      --- a/nuttx/libc/stdio/lib_ungetc.c
      +++ b/nuttx/libc/stdio/lib_ungetc.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_ungetc.c
      + * libc/stdio/lib_ungetc.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_vfprintf.c b/nuttx/libc/stdio/lib_vfprintf.c
      index 1c3a2d7fc9..cd117ddc30 100644
      --- a/nuttx/libc/stdio/lib_vfprintf.c
      +++ b/nuttx/libc/stdio/lib_vfprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_vfprintf.c
      + * libc/stdio/lib_vfprintf.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_vprintf.c b/nuttx/libc/stdio/lib_vprintf.c
      index d085d58869..6ddfe2b246 100644
      --- a/nuttx/libc/stdio/lib_vprintf.c
      +++ b/nuttx/libc/stdio/lib_vprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_vprintf.c
      + * libc/stdio/lib_vprintf.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_vsnprintf.c b/nuttx/libc/stdio/lib_vsnprintf.c
      index c6f52092d1..f7fd02e427 100644
      --- a/nuttx/libc/stdio/lib_vsnprintf.c
      +++ b/nuttx/libc/stdio/lib_vsnprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_vsnprintf.c
      + * libc/stdio/lib_vsnprintf.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_vsprintf.c b/nuttx/libc/stdio/lib_vsprintf.c
      index 5db46664e3..b6d80808f9 100644
      --- a/nuttx/libc/stdio/lib_vsprintf.c
      +++ b/nuttx/libc/stdio/lib_vsprintf.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_vsprintf.c
      + * libc/stdio/lib_vsprintf.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      @@ -84,7 +84,7 @@ int vsprintf(FAR char *dest, const char *src, va_list ap)
         struct lib_memoutstream_s memoutstream;
       
         /* Wrap the destination buffer in a stream object and let
      -   * lib/stdio/lib_vsprintf do the work.
      +   * libc/stdio/lib_vsprintf do the work.
          */
       
         lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, dest, LIB_BUFLEN_UNKNOWN);
      diff --git a/nuttx/libc/stdio/lib_wrflush.c b/nuttx/libc/stdio/lib_wrflush.c
      index 39680da6ae..40b8e38c8d 100644
      --- a/nuttx/libc/stdio/lib_wrflush.c
      +++ b/nuttx/libc/stdio/lib_wrflush.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_wrflush.c
      + * libc/stdio/lib_wrflush.c
        *
        *   Copyright (C) 2008-2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdio/lib_zeroinstream.c b/nuttx/libc/stdio/lib_zeroinstream.c
      index 39a6c22ef3..a52ecc1d06 100644
      --- a/nuttx/libc/stdio/lib_zeroinstream.c
      +++ b/nuttx/libc/stdio/lib_zeroinstream.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdio/lib_zeroinstream.c
      + * libc/stdio/lib_zeroinstream.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdlib/Make.defs b/nuttx/libc/stdlib/Make.defs
      index 76e285808a..dcc4dab26a 100644
      --- a/nuttx/libc/stdlib/Make.defs
      +++ b/nuttx/libc/stdlib/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/stdlib/Make.defs
      +# libc/stdlib/Make.defs
       #
       #   Copyright (C) 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdlib/lib_abort.c b/nuttx/libc/stdlib/lib_abort.c
      index 84b6009500..1c7442c7f5 100644
      --- a/nuttx/libc/stdlib/lib_abort.c
      +++ b/nuttx/libc/stdlib/lib_abort.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/stdlib/lib_abort.c
      + * libc/stdlib/lib_abort.c
        *
        *   Copyright (C) 2007, 2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdlib/lib_abs.c b/nuttx/libc/stdlib/lib_abs.c
      index 1a0c1671cc..a4e4ec6694 100644
      --- a/nuttx/libc/stdlib/lib_abs.c
      +++ b/nuttx/libc/stdlib/lib_abs.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/stdlib/lib_abs.c
      + * libc/stdlib/lib_abs.c
        *
        *   Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdlib/lib_imaxabs.c b/nuttx/libc/stdlib/lib_imaxabs.c
      index c6e227c7de..d365043727 100644
      --- a/nuttx/libc/stdlib/lib_imaxabs.c
      +++ b/nuttx/libc/stdlib/lib_imaxabs.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/stdlib//lib_abs.c
      + * libc/stdlib//lib_abs.c
        *
        *   Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdlib/lib_labs.c b/nuttx/libc/stdlib/lib_labs.c
      index f7218ee833..7cf92a0a19 100644
      --- a/nuttx/libc/stdlib/lib_labs.c
      +++ b/nuttx/libc/stdlib/lib_labs.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/stdlib/lib_labs.c
      + * libc/stdlib/lib_labs.c
        *
        *   Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdlib/lib_llabs.c b/nuttx/libc/stdlib/lib_llabs.c
      index db7d3dbe07..3630d1716f 100644
      --- a/nuttx/libc/stdlib/lib_llabs.c
      +++ b/nuttx/libc/stdlib/lib_llabs.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/stdlib/lib_llabs.c
      + * libc/stdlib/lib_llabs.c
        *
        *   Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdlib/lib_qsort.c b/nuttx/libc/stdlib/lib_qsort.c
      index 9dd5c00409..021e782d40 100644
      --- a/nuttx/libc/stdlib/lib_qsort.c
      +++ b/nuttx/libc/stdlib/lib_qsort.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/stdlib/lib_qsort.c
      + * libc/stdlib/lib_qsort.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/stdlib/lib_rand.c b/nuttx/libc/stdlib/lib_rand.c
      index 7227c52d0d..cb998fb12e 100644
      --- a/nuttx/libc/stdlib/lib_rand.c
      +++ b/nuttx/libc/stdlib/lib_rand.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/stdlib/lib_rand.c
      + * libc/stdlib/lib_rand.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/Make.defs b/nuttx/libc/string/Make.defs
      index 191b9ffea5..311c8afd27 100644
      --- a/nuttx/libc/string/Make.defs
      +++ b/nuttx/libc/string/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/string/Make.defs
      +# libc/string/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_checkbase.c b/nuttx/libc/string/lib_checkbase.c
      index bc79ab2cec..32ae58dca3 100644
      --- a/nuttx/libc/string/lib_checkbase.c
      +++ b/nuttx/libc/string/lib_checkbase.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_checkbase.c
      + * libc/string/lib_checkbase.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_isbasedigit.c b/nuttx/libc/string/lib_isbasedigit.c
      index a2421bf2a4..dff8138811 100644
      --- a/nuttx/libc/string/lib_isbasedigit.c
      +++ b/nuttx/libc/string/lib_isbasedigit.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_isbasedigit.c
      + * libc/string/lib_isbasedigit.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_memccpy.c b/nuttx/libc/string/lib_memccpy.c
      index 1f3dbb52dd..1d77f58fe9 100644
      --- a/nuttx/libc/string/lib_memccpy.c
      +++ b/nuttx/libc/string/lib_memccpy.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_memccpy.c
      + * libc/string/lib_memccpy.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_memchr.c b/nuttx/libc/string/lib_memchr.c
      index e0dec82700..0ac6091042 100644
      --- a/nuttx/libc/string/lib_memchr.c
      +++ b/nuttx/libc/string/lib_memchr.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_memchr.c
      + * libc/string/lib_memchr.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_memcmp.c b/nuttx/libc/string/lib_memcmp.c
      index eb2e1fd125..e1722a4d8d 100644
      --- a/nuttx/libc/string/lib_memcmp.c
      +++ b/nuttx/libc/string/lib_memcmp.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/string/lib_memcmp.c
      + * libc/string/lib_memcmp.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_memcpy.c b/nuttx/libc/string/lib_memcpy.c
      index 3b62edbabd..2ebd5beee1 100644
      --- a/nuttx/libc/string/lib_memcpy.c
      +++ b/nuttx/libc/string/lib_memcpy.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_memcpy.c
      + * libc/string/lib_memcpy.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_memmove.c b/nuttx/libc/string/lib_memmove.c
      index 85cb79e174..cbc26fb26f 100644
      --- a/nuttx/libc/string/lib_memmove.c
      +++ b/nuttx/libc/string/lib_memmove.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/string/lib_memmove.c
      + * libc/string/lib_memmove.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_memset.c b/nuttx/libc/string/lib_memset.c
      index 31c386e928..0b98ebf96f 100644
      --- a/nuttx/libc/string/lib_memset.c
      +++ b/nuttx/libc/string/lib_memset.c
      @@ -1,6 +1,6 @@
       
       /****************************************************************************
      - * lib/string/lib_memset.c
      + * libc/string/lib_memset.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_skipspace.c b/nuttx/libc/string/lib_skipspace.c
      index b4e6588e59..4b72b1ec37 100644
      --- a/nuttx/libc/string/lib_skipspace.c
      +++ b/nuttx/libc/string/lib_skipspace.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_skipspace.c
      + * libc/string/lib_skipspace.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strcasecmp.c b/nuttx/libc/string/lib_strcasecmp.c
      index d4aa8cc031..df6f08118d 100644
      --- a/nuttx/libc/string/lib_strcasecmp.c
      +++ b/nuttx/libc/string/lib_strcasecmp.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strcasecmp.c
      + * libc/string/lib_strcasecmp.c
        *
        *   Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strcasestr.c b/nuttx/libc/string/lib_strcasestr.c
      index 23f0ab57e6..5a8d53beef 100644
      --- a/nuttx/libc/string/lib_strcasestr.c
      +++ b/nuttx/libc/string/lib_strcasestr.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strstr.c
      + * libc/string/lib_strstr.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strcat.c b/nuttx/libc/string/lib_strcat.c
      index 20350fec07..b331d3f1c1 100644
      --- a/nuttx/libc/string/lib_strcat.c
      +++ b/nuttx/libc/string/lib_strcat.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strcat.c
      + * libc/string/lib_strcat.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strchr.c b/nuttx/libc/string/lib_strchr.c
      index d0bd22a0ea..e6af56eee5 100644
      --- a/nuttx/libc/string/lib_strchr.c
      +++ b/nuttx/libc/string/lib_strchr.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strchr.c
      + * libc/string/lib_strchr.c
        *
        *   Copyright (C) 2007, 2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strcmp.c b/nuttx/libc/string/lib_strcmp.c
      index 0e3eee8900..d4036cd3ea 100644
      --- a/nuttx/libc/string/lib_strcmp.c
      +++ b/nuttx/libc/string/lib_strcmp.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strcmp.c
      + * libc/string/lib_strcmp.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strcpy.c b/nuttx/libc/string/lib_strcpy.c
      index e2f70b94e3..7a0576f5af 100644
      --- a/nuttx/libc/string/lib_strcpy.c
      +++ b/nuttx/libc/string/lib_strcpy.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/string/lib_strcpy.c
      + * libc/string/lib_strcpy.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strcspn.c b/nuttx/libc/string/lib_strcspn.c
      index 9da89241c5..23e913fadf 100644
      --- a/nuttx/libc/string/lib_strcspn.c
      +++ b/nuttx/libc/string/lib_strcspn.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strcspn.c
      + * libc/string/lib_strcspn.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strdup.c b/nuttx/libc/string/lib_strdup.c
      index 44a0cbc0d8..a5b3a1e8c1 100644
      --- a/nuttx/libc/string/lib_strdup.c
      +++ b/nuttx/libc/string/lib_strdup.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/string//lib_strdup.c
      + * libc/string//lib_strdup.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strerror.c b/nuttx/libc/string/lib_strerror.c
      index 249f695c1b..0c7ca28fd8 100644
      --- a/nuttx/libc/string/lib_strerror.c
      +++ b/nuttx/libc/string/lib_strerror.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/string/lib_strerror.c
      + * libc/string/lib_strerror.c
        *
        *   Copyright (C) 2007, 2009, 2011-2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strlen.c b/nuttx/libc/string/lib_strlen.c
      index 8333058091..6077858e23 100644
      --- a/nuttx/libc/string/lib_strlen.c
      +++ b/nuttx/libc/string/lib_strlen.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strlen.c
      + * libc/string/lib_strlen.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strncasecmp.c b/nuttx/libc/string/lib_strncasecmp.c
      index be369cf0d8..35f701c5ef 100644
      --- a/nuttx/libc/string/lib_strncasecmp.c
      +++ b/nuttx/libc/string/lib_strncasecmp.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strncasecmp.c
      + * libc/string/lib_strncasecmp.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strncat.c b/nuttx/libc/string/lib_strncat.c
      index af893e0f9b..78c54835e0 100644
      --- a/nuttx/libc/string/lib_strncat.c
      +++ b/nuttx/libc/string/lib_strncat.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/string/lib_strncat.c
      + * libc/string/lib_strncat.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strncmp.c b/nuttx/libc/string/lib_strncmp.c
      index ce22820249..dd8b57fd0b 100644
      --- a/nuttx/libc/string/lib_strncmp.c
      +++ b/nuttx/libc/string/lib_strncmp.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/lib_strncmp.c
      + * libc/lib_strncmp.c
        *
        *   Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strncpy.c b/nuttx/libc/string/lib_strncpy.c
      index 149369d508..8a97aa67b7 100644
      --- a/nuttx/libc/string/lib_strncpy.c
      +++ b/nuttx/libc/string/lib_strncpy.c
      @@ -1,5 +1,5 @@
       /************************************************************
      - * lib/string/lib_strncpy.c
      + * libc/string/lib_strncpy.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strndup.c b/nuttx/libc/string/lib_strndup.c
      index ffaf892eaa..524e09754e 100644
      --- a/nuttx/libc/string/lib_strndup.c
      +++ b/nuttx/libc/string/lib_strndup.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/string//lib_strndup.c
      + * libc/string//lib_strndup.c
        *
        *   Copyright (C) 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strnlen.c b/nuttx/libc/string/lib_strnlen.c
      index 2b64fe9845..9bc3064cb1 100644
      --- a/nuttx/libc/string/lib_strnlen.c
      +++ b/nuttx/libc/string/lib_strnlen.c
      @@ -1,12 +1,12 @@
       /****************************************************************************
      - * lib/string/lib_strnlen.c
      + * libc/string/lib_strnlen.c
        *
        * This file is part of NuttX, contributed by Michael Hrabanek
        *
        *   Copyright (C) 2010 Gregory Nutt. All rights reserved.
        *   Author: Michael Hrabanek
        *
      - * Derives from the file lib/lib_strlen.c:
      + * Derives from the file libc/lib_strlen.c:
        *
        *   Copyright (C) 2007, 2008, 2010 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strpbrk.c b/nuttx/libc/string/lib_strpbrk.c
      index 02e2ea2c70..ef9b0f3e97 100644
      --- a/nuttx/libc/string/lib_strpbrk.c
      +++ b/nuttx/libc/string/lib_strpbrk.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strpbrk.c
      + * libc/string/lib_strpbrk.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strrchr.c b/nuttx/libc/string/lib_strrchr.c
      index 91243ce589..08575c82bf 100644
      --- a/nuttx/libc/string/lib_strrchr.c
      +++ b/nuttx/libc/string/lib_strrchr.c
      @@ -1,5 +1,5 @@
       /************************************************************************
      - * lib/string/lib_strrchr.c
      + * libc/string/lib_strrchr.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strspn.c b/nuttx/libc/string/lib_strspn.c
      index e7b5ea0a5b..6894b2b9dc 100644
      --- a/nuttx/libc/string/lib_strspn.c
      +++ b/nuttx/libc/string/lib_strspn.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strspn.c
      + * libc/string/lib_strspn.c
        *
        *   Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strstr.c b/nuttx/libc/string/lib_strstr.c
      index b8c896fa2e..02f4809d2b 100644
      --- a/nuttx/libc/string/lib_strstr.c
      +++ b/nuttx/libc/string/lib_strstr.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strstr.c
      + * libc/string/lib_strstr.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strtod.c b/nuttx/libc/string/lib_strtod.c
      index 8fecd45713..58dfd6a292 100644
      --- a/nuttx/libc/string/lib_strtod.c
      +++ b/nuttx/libc/string/lib_strtod.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strtod.c
      + * libc/string/lib_strtod.c
        * Convert string to double
        *
        *   Copyright (C) 2002 Michael Ringgaard. All rights reserved.
      diff --git a/nuttx/libc/string/lib_strtok.c b/nuttx/libc/string/lib_strtok.c
      index c409931359..85d6597d74 100644
      --- a/nuttx/libc/string/lib_strtok.c
      +++ b/nuttx/libc/string/lib_strtok.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strtok.c
      + * libc/string/lib_strtok.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strtokr.c b/nuttx/libc/string/lib_strtokr.c
      index 1c571b6ae5..c7845be642 100644
      --- a/nuttx/libc/string/lib_strtokr.c
      +++ b/nuttx/libc/string/lib_strtokr.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strtokr.c
      + * libc/string/lib_strtokr.c
        *
        *   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strtol.c b/nuttx/libc/string/lib_strtol.c
      index c17d87e635..6ac0d6827d 100644
      --- a/nuttx/libc/string/lib_strtol.c
      +++ b/nuttx/libc/string/lib_strtol.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strtol.c
      + * libc/string/lib_strtol.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strtoll.c b/nuttx/libc/string/lib_strtoll.c
      index 242e025c07..99fba08eba 100644
      --- a/nuttx/libc/string/lib_strtoll.c
      +++ b/nuttx/libc/string/lib_strtoll.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/string/lib_strtoll.c
      + * libc/string/lib_strtoll.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strtoul.c b/nuttx/libc/string/lib_strtoul.c
      index b0d2d090e6..8f27ae3f2d 100644
      --- a/nuttx/libc/string/lib_strtoul.c
      +++ b/nuttx/libc/string/lib_strtoul.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * /lib/string/lib_strtoul.c
      + * /libc/string/lib_strtoul.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_strtoull.c b/nuttx/libc/string/lib_strtoull.c
      index 6567457c0e..4808114afe 100644
      --- a/nuttx/libc/string/lib_strtoull.c
      +++ b/nuttx/libc/string/lib_strtoull.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * /lib/string/lib_strtoull.c
      + * /libc/string/lib_strtoull.c
        *
        *   Copyright (C) 2009, 2010 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/string/lib_vikmemcpy.c b/nuttx/libc/string/lib_vikmemcpy.c
      index b50942aaa1..28bf4a4ced 100644
      --- a/nuttx/libc/string/lib_vikmemcpy.c
      +++ b/nuttx/libc/string/lib_vikmemcpy.c
      @@ -1,348 +1,348 @@
      -/****************************************************************************
      - * File: lib/string/lib_vikmemcpy.c
      - *
      - * This is version of the optimized memcpy by Daniel Vik, adapted to the
      - * NuttX environment.
      - *
      - *   Copyright (C) 1999-2010 Daniel Vik
      - *
      - * Adaptations include:
      - * - File name change
      - * - Use of types defined in stdint.h
      - * - Integration with the NuttX configuration system
      - * - Other cosmetic changes for consistency with NuttX coding standards
      - * 
      - * This software is provided 'as-is', without any express or implied
      - * warranty. In no event will the authors be held liable for any
      - * damages arising from the use of this software.
      - * Permission is granted to anyone to use this software for any
      - * purpose, including commercial applications, and to alter it and
      - * redistribute it freely, subject to the following restrictions:
      - * 
      - * 1. The origin of this software must not be misrepresented; you
      - *    must not claim that you wrote the original software. If you
      - *    use this software in a product, an acknowledgment in the
      - *    use this software in a product, an acknowledgment in the
      - *    product documentation would be appreciated but is not
      - *    required.
      - * 
      - * 2. Altered source versions must be plainly marked as such, and
      - *    must not be misrepresented as being the original software.
      - * 
      - * 3. This notice may not be removed or altered from any source
      - *    distribution.
      - * 
      - * Description: Implementation of the standard library function memcpy.
      - *              This implementation of memcpy() is ANSI-C89 compatible.
      - *
      - * The following configuration options can be set:
      - *
      - *   CONFIG_ENDIAN_BIG
      - *     Uses processor with big endian addressing. Default is little endian.
      - *
      - *   CONFIG_MEMCPY_PRE_INC_PTRS
      - *     Use pre increment of pointers. Default is post increment of pointers.
      - *
      - *   CONFIG_MEMCPY_INDEXED_COPY
      - *     Copying data using array indexing. Using this option, disables the
      - *     CONFIG_MEMCPY_PRE_INC_PTRS option.
      - *
      - *   CONFIG_MEMCPY_64BIT - Compiles memcpy for 64 bit architectures
      - *
      - ****************************************************************************/
      -
      -/****************************************************************************
      - * Configuration definitions.
      - ****************************************************************************/
      -
      -#define CONFIG_MEMCPY_INDEXED_COPY
      -
      -/********************************************************************
      - * Included Files
      - *******************************************************************/
      -
      -#include 
      -#include 
      -
      -#include 
      -#include 
      -#include 
      -
      -/********************************************************************
      - * Pre-processor Definitions
      - *******************************************************************/
      -
      -/* Can't support CONFIG_MEMCPY_64BIT if the platform does not have 64-bit
      - * integer types.
      - */
      -
      -#ifndef CONFIG_HAVE_LONG_LONG
      -#  undef CONFIG_MEMCPY_64BIT
      -#endif
      -
      -/* Remove definitions when CONFIG_MEMCPY_INDEXED_COPY is defined */
      -
      -#if defined (CONFIG_MEMCPY_INDEXED_COPY)
      -#  if defined (CONFIG_MEMCPY_PRE_INC_PTRS)
      -#    undef CONFIG_MEMCPY_PRE_INC_PTRS
      -#  endif /* CONFIG_MEMCPY_PRE_INC_PTRS */
      -#endif /* CONFIG_MEMCPY_INDEXED_COPY */
      -
      -/* Definitions for pre and post increment of pointers */
      -
      -#if defined (CONFIG_MEMCPY_PRE_INC_PTRS)
      -
      -#  define START_VAL(x)            (x)--
      -#  define INC_VAL(x)              *++(x)
      -#  define CAST_TO_U8(p, o)        ((uint8_t*)p + o + TYPE_WIDTH)
      -#  define WHILE_DEST_BREAK        (TYPE_WIDTH - 1)
      -#  define PRE_LOOP_ADJUST         - (TYPE_WIDTH - 1)
      -#  define PRE_SWITCH_ADJUST       + 1
      -
      -#else /* CONFIG_MEMCPY_PRE_INC_PTRS */
      -
      -#  define START_VAL(x)
      -#  define INC_VAL(x)              *(x)++
      -#  define CAST_TO_U8(p, o)        ((uint8_t*)p + o)
      -#  define WHILE_DEST_BREAK        0
      -#  define PRE_LOOP_ADJUST
      -#  define PRE_SWITCH_ADJUST
      -
      -#endif /* CONFIG_MEMCPY_PRE_INC_PTRS */
      -
      -/* Definitions for endian-ness */
      -
      -#ifdef CONFIG_ENDIAN_BIG
      -
      -#  define SHL <<
      -#  define SHR >>
      -
      -#else /* CONFIG_ENDIAN_BIG */
      -
      -#  define SHL >>
      -#  define SHR <<
      -
      -#endif /* CONFIG_ENDIAN_BIG */
      -
      -/********************************************************************
      - * Macros for copying words of  different alignment.
      - * Uses incremening pointers.
      - *******************************************************************/
      -
      -#define CP_INCR()                         \
      -{                                         \
      -  INC_VAL(dstN) = INC_VAL(srcN);          \
      -}
      -
      -#define CP_INCR_SH(shl, shr)              \
      -{                                         \
      -  dstWord       = srcWord SHL shl;        \
      -  srcWord       = INC_VAL(srcN);          \
      -  dstWord      |= srcWord SHR shr;        \
      -  INC_VAL(dstN) = dstWord;                \
      -}
      -
      -/********************************************************************
      - * Macros for copying words of  different alignment.
      - * Uses array indexes.
      - *******************************************************************/
      -
      -#define CP_INDEX(idx)                     \
      -{                                         \
      -  dstN[idx] = srcN[idx];                  \
      -}
      -
      -#define CP_INDEX_SH(x, shl, shr)          \
      -{                                         \
      -  dstWord   = srcWord SHL shl;            \
      -  srcWord   = srcN[x];                    \
      -  dstWord  |= srcWord SHR shr;            \
      -  dstN[x]   = dstWord;                    \
      -}
      -
      -/********************************************************************
      - * Macros for copying words of different alignment.
      - * Uses incremening pointers or array indexes depending on
      - * configuration.
      - *******************************************************************/
      -
      -#if defined (CONFIG_MEMCPY_INDEXED_COPY)
      -
      -#  define CP(idx)               CP_INDEX(idx)
      -#  define CP_SH(idx, shl, shr)  CP_INDEX_SH(idx, shl, shr)
      -
      -#  define INC_INDEX(p, o)       ((p) += (o))
      -
      -#else /* CONFIG_MEMCPY_INDEXED_COPY */
      -
      -#  define CP(idx)               CP_INCR()
      -#  define CP_SH(idx, shl, shr)  CP_INCR_SH(shl, shr)
      -
      -#  define INC_INDEX(p, o)
      -
      -#endif /* CONFIG_MEMCPY_INDEXED_COPY */
      -
      -#define COPY_REMAINING(count)                                     \
      -{                                                                 \
      -  START_VAL(dst8);                                                \
      -  START_VAL(src8);                                                \
      -                                                                  \
      -  switch (count)                                                  \
      -    {                                                             \
      -    case 7: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 6: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 5: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 4: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 3: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 2: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 1: INC_VAL(dst8) = INC_VAL(src8);                        \
      -    case 0:                                                       \
      -    default: break;                                               \
      -    }                                                             \
      -}
      -
      -#define COPY_NO_SHIFT()                                           \
      -{                                                                 \
      -  UIntN* dstN = (UIntN*)(dst8 PRE_LOOP_ADJUST);                   \
      -  UIntN* srcN = (UIntN*)(src8 PRE_LOOP_ADJUST);                   \
      -  size_t length = count / TYPE_WIDTH;                             \
      -                                                                  \
      -  while (length & 7)                                              \
      -    {                                                             \
      -      CP_INCR();                                                  \
      -      length--;                                                   \
      -    }                                                             \
      -                                                                  \
      -  length /= 8;                                                    \
      -                                                                  \
      -  while (length--)                                                \
      -    {                                                             \
      -      CP(0);                                                      \
      -      CP(1);                                                      \
      -      CP(2);                                                      \
      -      CP(3);                                                      \
      -      CP(4);                                                      \
      -      CP(5);                                                      \
      -      CP(6);                                                      \
      -      CP(7);                                                      \
      -                                                                  \
      -      INC_INDEX(dstN, 8);                                         \
      -      INC_INDEX(srcN, 8);                                         \
      -    }                                                             \
      -                                                                  \
      -  src8 = CAST_TO_U8(srcN, 0);                                     \
      -  dst8 = CAST_TO_U8(dstN, 0);                                     \
      -                                                                  \
      -  COPY_REMAINING(count & (TYPE_WIDTH - 1));                       \
      -                                                                  \
      -  return dest;                                                    \
      -}
      -
      -#define COPY_SHIFT(shift)                                         \
      -{                                                                 \
      -  UIntN* dstN  = (UIntN*)((((UIntN)dst8) PRE_LOOP_ADJUST) &       \
      -                           ~(TYPE_WIDTH - 1));                    \
      -  UIntN* srcN  = (UIntN*)((((UIntN)src8) PRE_LOOP_ADJUST) &       \
      -                           ~(TYPE_WIDTH - 1));                    \
      -  size_t length  = count / TYPE_WIDTH;                            \
      -  UIntN srcWord = INC_VAL(srcN);                                  \
      -  UIntN dstWord;                                                  \
      -                                                                  \
      -  while (length & 7)                                              \
      -    {                                                             \
      -      CP_INCR_SH(8 * shift, 8 * (TYPE_WIDTH - shift));            \
      -      length--;                                                   \
      -    }                                                             \
      -                                                                  \
      -  length /= 8;                                                    \
      -                                                                  \
      -  while (length--)                                                \
      -    {                                                             \
      -      CP_SH(0, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(1, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(2, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(3, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(4, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(5, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(6, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -      CP_SH(7, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      -                                                                  \
      -      INC_INDEX(dstN, 8);                                         \
      -      INC_INDEX(srcN, 8);                                         \
      -    }                                                             \
      -                                                                  \
      -  src8 = CAST_TO_U8(srcN, (shift - TYPE_WIDTH));                  \
      -  dst8 = CAST_TO_U8(dstN, 0);                                     \
      -                                                                  \
      -  COPY_REMAINING(count & (TYPE_WIDTH - 1));                       \
      -                                                                  \
      -  return dest;                                                    \
      -}
      -
      -/********************************************************************
      - * Type Definitions
      - *******************************************************************/
      -
      -#ifdef CONFIG_MEMCPY_64BIT
      -typedef uint64_t            UIntN;
      -#  define TYPE_WIDTH        8L
      -#else
      -typedef uint32_t            UIntN;
      -#  define TYPE_WIDTH        4L
      -#endif
      -
      -/********************************************************************
      - * Public Functions
      - *******************************************************************/
      -/********************************************************************
      - * Name: memcpy
      - *
      - * Description:
      - *   Copies count bytes from src to dest. No overlap check is performed.
      - *
      - * Input Parameters:
      - *   dest        - pointer to destination buffer
      - *   src         - pointer to source buffer
      - *   count       - number of bytes to copy
      - *
      - * Returned Value:
      - *   A pointer to destination buffer
      - *
      - *******************************************************************/
      -
      -void *memcpy(void *dest, const void *src, size_t count) 
      -{
      -  uint8_t *dst8 = (uint8_t*)dest;
      -  uint8_t *src8 = (uint8_t*)src;
      -
      -  if (count < 8)
      -    {
      -      COPY_REMAINING(count);
      -      return dest;
      -    }
      -
      -  START_VAL(dst8);
      -  START_VAL(src8);
      -
      -  while (((UIntN)dst8 & (TYPE_WIDTH - 1)) != WHILE_DEST_BREAK)
      -    {
      -      INC_VAL(dst8) = INC_VAL(src8);
      -      count--;
      -    }
      -
      -  switch ((((UIntN)src8) PRE_SWITCH_ADJUST) & (TYPE_WIDTH - 1))
      -    {
      -    case 0: COPY_NO_SHIFT(); break;
      -    case 1: COPY_SHIFT(1);   break;
      -    case 2: COPY_SHIFT(2);   break;
      -    case 3: COPY_SHIFT(3);   break;
      -#if TYPE_WIDTH > 4
      -    case 4: COPY_SHIFT(4);   break;
      -    case 5: COPY_SHIFT(5);   break;
      -    case 6: COPY_SHIFT(6);   break;
      -    case 7: COPY_SHIFT(7);   break;
      -#endif
      -    }
      -
      -  return dest;
      -}
      +/****************************************************************************
      + * File: libc/string/lib_vikmemcpy.c
      + *
      + * This is version of the optimized memcpy by Daniel Vik, adapted to the
      + * NuttX environment.
      + *
      + *   Copyright (C) 1999-2010 Daniel Vik
      + *
      + * Adaptations include:
      + * - File name change
      + * - Use of types defined in stdint.h
      + * - Integration with the NuttX configuration system
      + * - Other cosmetic changes for consistency with NuttX coding standards
      + * 
      + * This software is provided 'as-is', without any express or implied
      + * warranty. In no event will the authors be held liable for any
      + * damages arising from the use of this software.
      + * Permission is granted to anyone to use this software for any
      + * purpose, including commercial applications, and to alter it and
      + * redistribute it freely, subject to the following restrictions:
      + * 
      + * 1. The origin of this software must not be misrepresented; you
      + *    must not claim that you wrote the original software. If you
      + *    use this software in a product, an acknowledgment in the
      + *    use this software in a product, an acknowledgment in the
      + *    product documentation would be appreciated but is not
      + *    required.
      + * 
      + * 2. Altered source versions must be plainly marked as such, and
      + *    must not be misrepresented as being the original software.
      + * 
      + * 3. This notice may not be removed or altered from any source
      + *    distribution.
      + * 
      + * Description: Implementation of the standard library function memcpy.
      + *              This implementation of memcpy() is ANSI-C89 compatible.
      + *
      + * The following configuration options can be set:
      + *
      + *   CONFIG_ENDIAN_BIG
      + *     Uses processor with big endian addressing. Default is little endian.
      + *
      + *   CONFIG_MEMCPY_PRE_INC_PTRS
      + *     Use pre increment of pointers. Default is post increment of pointers.
      + *
      + *   CONFIG_MEMCPY_INDEXED_COPY
      + *     Copying data using array indexing. Using this option, disables the
      + *     CONFIG_MEMCPY_PRE_INC_PTRS option.
      + *
      + *   CONFIG_MEMCPY_64BIT - Compiles memcpy for 64 bit architectures
      + *
      + ****************************************************************************/
      +
      +/****************************************************************************
      + * Configuration definitions.
      + ****************************************************************************/
      +
      +#define CONFIG_MEMCPY_INDEXED_COPY
      +
      +/********************************************************************
      + * Included Files
      + *******************************************************************/
      +
      +#include 
      +#include 
      +
      +#include 
      +#include 
      +#include 
      +
      +/********************************************************************
      + * Pre-processor Definitions
      + *******************************************************************/
      +
      +/* Can't support CONFIG_MEMCPY_64BIT if the platform does not have 64-bit
      + * integer types.
      + */
      +
      +#ifndef CONFIG_HAVE_LONG_LONG
      +#  undef CONFIG_MEMCPY_64BIT
      +#endif
      +
      +/* Remove definitions when CONFIG_MEMCPY_INDEXED_COPY is defined */
      +
      +#if defined (CONFIG_MEMCPY_INDEXED_COPY)
      +#  if defined (CONFIG_MEMCPY_PRE_INC_PTRS)
      +#    undef CONFIG_MEMCPY_PRE_INC_PTRS
      +#  endif /* CONFIG_MEMCPY_PRE_INC_PTRS */
      +#endif /* CONFIG_MEMCPY_INDEXED_COPY */
      +
      +/* Definitions for pre and post increment of pointers */
      +
      +#if defined (CONFIG_MEMCPY_PRE_INC_PTRS)
      +
      +#  define START_VAL(x)            (x)--
      +#  define INC_VAL(x)              *++(x)
      +#  define CAST_TO_U8(p, o)        ((uint8_t*)p + o + TYPE_WIDTH)
      +#  define WHILE_DEST_BREAK        (TYPE_WIDTH - 1)
      +#  define PRE_LOOP_ADJUST         - (TYPE_WIDTH - 1)
      +#  define PRE_SWITCH_ADJUST       + 1
      +
      +#else /* CONFIG_MEMCPY_PRE_INC_PTRS */
      +
      +#  define START_VAL(x)
      +#  define INC_VAL(x)              *(x)++
      +#  define CAST_TO_U8(p, o)        ((uint8_t*)p + o)
      +#  define WHILE_DEST_BREAK        0
      +#  define PRE_LOOP_ADJUST
      +#  define PRE_SWITCH_ADJUST
      +
      +#endif /* CONFIG_MEMCPY_PRE_INC_PTRS */
      +
      +/* Definitions for endian-ness */
      +
      +#ifdef CONFIG_ENDIAN_BIG
      +
      +#  define SHL <<
      +#  define SHR >>
      +
      +#else /* CONFIG_ENDIAN_BIG */
      +
      +#  define SHL >>
      +#  define SHR <<
      +
      +#endif /* CONFIG_ENDIAN_BIG */
      +
      +/********************************************************************
      + * Macros for copying words of  different alignment.
      + * Uses incremening pointers.
      + *******************************************************************/
      +
      +#define CP_INCR()                         \
      +{                                         \
      +  INC_VAL(dstN) = INC_VAL(srcN);          \
      +}
      +
      +#define CP_INCR_SH(shl, shr)              \
      +{                                         \
      +  dstWord       = srcWord SHL shl;        \
      +  srcWord       = INC_VAL(srcN);          \
      +  dstWord      |= srcWord SHR shr;        \
      +  INC_VAL(dstN) = dstWord;                \
      +}
      +
      +/********************************************************************
      + * Macros for copying words of  different alignment.
      + * Uses array indexes.
      + *******************************************************************/
      +
      +#define CP_INDEX(idx)                     \
      +{                                         \
      +  dstN[idx] = srcN[idx];                  \
      +}
      +
      +#define CP_INDEX_SH(x, shl, shr)          \
      +{                                         \
      +  dstWord   = srcWord SHL shl;            \
      +  srcWord   = srcN[x];                    \
      +  dstWord  |= srcWord SHR shr;            \
      +  dstN[x]   = dstWord;                    \
      +}
      +
      +/********************************************************************
      + * Macros for copying words of different alignment.
      + * Uses incremening pointers or array indexes depending on
      + * configuration.
      + *******************************************************************/
      +
      +#if defined (CONFIG_MEMCPY_INDEXED_COPY)
      +
      +#  define CP(idx)               CP_INDEX(idx)
      +#  define CP_SH(idx, shl, shr)  CP_INDEX_SH(idx, shl, shr)
      +
      +#  define INC_INDEX(p, o)       ((p) += (o))
      +
      +#else /* CONFIG_MEMCPY_INDEXED_COPY */
      +
      +#  define CP(idx)               CP_INCR()
      +#  define CP_SH(idx, shl, shr)  CP_INCR_SH(shl, shr)
      +
      +#  define INC_INDEX(p, o)
      +
      +#endif /* CONFIG_MEMCPY_INDEXED_COPY */
      +
      +#define COPY_REMAINING(count)                                     \
      +{                                                                 \
      +  START_VAL(dst8);                                                \
      +  START_VAL(src8);                                                \
      +                                                                  \
      +  switch (count)                                                  \
      +    {                                                             \
      +    case 7: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 6: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 5: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 4: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 3: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 2: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 1: INC_VAL(dst8) = INC_VAL(src8);                        \
      +    case 0:                                                       \
      +    default: break;                                               \
      +    }                                                             \
      +}
      +
      +#define COPY_NO_SHIFT()                                           \
      +{                                                                 \
      +  UIntN* dstN = (UIntN*)(dst8 PRE_LOOP_ADJUST);                   \
      +  UIntN* srcN = (UIntN*)(src8 PRE_LOOP_ADJUST);                   \
      +  size_t length = count / TYPE_WIDTH;                             \
      +                                                                  \
      +  while (length & 7)                                              \
      +    {                                                             \
      +      CP_INCR();                                                  \
      +      length--;                                                   \
      +    }                                                             \
      +                                                                  \
      +  length /= 8;                                                    \
      +                                                                  \
      +  while (length--)                                                \
      +    {                                                             \
      +      CP(0);                                                      \
      +      CP(1);                                                      \
      +      CP(2);                                                      \
      +      CP(3);                                                      \
      +      CP(4);                                                      \
      +      CP(5);                                                      \
      +      CP(6);                                                      \
      +      CP(7);                                                      \
      +                                                                  \
      +      INC_INDEX(dstN, 8);                                         \
      +      INC_INDEX(srcN, 8);                                         \
      +    }                                                             \
      +                                                                  \
      +  src8 = CAST_TO_U8(srcN, 0);                                     \
      +  dst8 = CAST_TO_U8(dstN, 0);                                     \
      +                                                                  \
      +  COPY_REMAINING(count & (TYPE_WIDTH - 1));                       \
      +                                                                  \
      +  return dest;                                                    \
      +}
      +
      +#define COPY_SHIFT(shift)                                         \
      +{                                                                 \
      +  UIntN* dstN  = (UIntN*)((((UIntN)dst8) PRE_LOOP_ADJUST) &       \
      +                           ~(TYPE_WIDTH - 1));                    \
      +  UIntN* srcN  = (UIntN*)((((UIntN)src8) PRE_LOOP_ADJUST) &       \
      +                           ~(TYPE_WIDTH - 1));                    \
      +  size_t length  = count / TYPE_WIDTH;                            \
      +  UIntN srcWord = INC_VAL(srcN);                                  \
      +  UIntN dstWord;                                                  \
      +                                                                  \
      +  while (length & 7)                                              \
      +    {                                                             \
      +      CP_INCR_SH(8 * shift, 8 * (TYPE_WIDTH - shift));            \
      +      length--;                                                   \
      +    }                                                             \
      +                                                                  \
      +  length /= 8;                                                    \
      +                                                                  \
      +  while (length--)                                                \
      +    {                                                             \
      +      CP_SH(0, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(1, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(2, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(3, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(4, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(5, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(6, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +      CP_SH(7, 8 * shift, 8 * (TYPE_WIDTH - shift));              \
      +                                                                  \
      +      INC_INDEX(dstN, 8);                                         \
      +      INC_INDEX(srcN, 8);                                         \
      +    }                                                             \
      +                                                                  \
      +  src8 = CAST_TO_U8(srcN, (shift - TYPE_WIDTH));                  \
      +  dst8 = CAST_TO_U8(dstN, 0);                                     \
      +                                                                  \
      +  COPY_REMAINING(count & (TYPE_WIDTH - 1));                       \
      +                                                                  \
      +  return dest;                                                    \
      +}
      +
      +/********************************************************************
      + * Type Definitions
      + *******************************************************************/
      +
      +#ifdef CONFIG_MEMCPY_64BIT
      +typedef uint64_t            UIntN;
      +#  define TYPE_WIDTH        8L
      +#else
      +typedef uint32_t            UIntN;
      +#  define TYPE_WIDTH        4L
      +#endif
      +
      +/********************************************************************
      + * Public Functions
      + *******************************************************************/
      +/********************************************************************
      + * Name: memcpy
      + *
      + * Description:
      + *   Copies count bytes from src to dest. No overlap check is performed.
      + *
      + * Input Parameters:
      + *   dest        - pointer to destination buffer
      + *   src         - pointer to source buffer
      + *   count       - number of bytes to copy
      + *
      + * Returned Value:
      + *   A pointer to destination buffer
      + *
      + *******************************************************************/
      +
      +void *memcpy(void *dest, const void *src, size_t count) 
      +{
      +  uint8_t *dst8 = (uint8_t*)dest;
      +  uint8_t *src8 = (uint8_t*)src;
      +
      +  if (count < 8)
      +    {
      +      COPY_REMAINING(count);
      +      return dest;
      +    }
      +
      +  START_VAL(dst8);
      +  START_VAL(src8);
      +
      +  while (((UIntN)dst8 & (TYPE_WIDTH - 1)) != WHILE_DEST_BREAK)
      +    {
      +      INC_VAL(dst8) = INC_VAL(src8);
      +      count--;
      +    }
      +
      +  switch ((((UIntN)src8) PRE_SWITCH_ADJUST) & (TYPE_WIDTH - 1))
      +    {
      +    case 0: COPY_NO_SHIFT(); break;
      +    case 1: COPY_SHIFT(1);   break;
      +    case 2: COPY_SHIFT(2);   break;
      +    case 3: COPY_SHIFT(3);   break;
      +#if TYPE_WIDTH > 4
      +    case 4: COPY_SHIFT(4);   break;
      +    case 5: COPY_SHIFT(5);   break;
      +    case 6: COPY_SHIFT(6);   break;
      +    case 7: COPY_SHIFT(7);   break;
      +#endif
      +    }
      +
      +  return dest;
      +}
      diff --git a/nuttx/libc/termios/Make.defs b/nuttx/libc/termios/Make.defs
      index a6bb77f835..d20a5f95c7 100644
      --- a/nuttx/libc/termios/Make.defs
      +++ b/nuttx/libc/termios/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/misc/Make.defs
      +# libc/misc/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/termios/lib_cfgetspeed.c b/nuttx/libc/termios/lib_cfgetspeed.c
      index d7f0dc4736..da10daac1e 100644
      --- a/nuttx/libc/termios/lib_cfgetspeed.c
      +++ b/nuttx/libc/termios/lib_cfgetspeed.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/termios/lib_cfgetspeed.c
      + * libc/termios/lib_cfgetspeed.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/termios/lib_cfsetspeed.c b/nuttx/libc/termios/lib_cfsetspeed.c
      index 714562ff50..a2a9475c4b 100644
      --- a/nuttx/libc/termios/lib_cfsetspeed.c
      +++ b/nuttx/libc/termios/lib_cfsetspeed.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/termios/lib_cfsetspeed.c
      + * libc/termios/lib_cfsetspeed.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/termios/lib_tcflush.c b/nuttx/libc/termios/lib_tcflush.c
      index 338524bdda..1a9710f6a0 100644
      --- a/nuttx/libc/termios/lib_tcflush.c
      +++ b/nuttx/libc/termios/lib_tcflush.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/termios/lib_tcflush.c
      + * libc/termios/lib_tcflush.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/termios/lib_tcgetattr.c b/nuttx/libc/termios/lib_tcgetattr.c
      index 500871d9ff..e8d3112603 100644
      --- a/nuttx/libc/termios/lib_tcgetattr.c
      +++ b/nuttx/libc/termios/lib_tcgetattr.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/termios/lib_tcgetattr.c
      + * libc/termios/lib_tcgetattr.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/termios/lib_tcsetattr.c b/nuttx/libc/termios/lib_tcsetattr.c
      index 791b519c85..901f2a1368 100644
      --- a/nuttx/libc/termios/lib_tcsetattr.c
      +++ b/nuttx/libc/termios/lib_tcsetattr.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/termios/lib_tcsetattr.c
      + * libc/termios/lib_tcsetattr.c
        *
        *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/time/Make.defs b/nuttx/libc/time/Make.defs
      index ab74142291..4848813d11 100644
      --- a/nuttx/libc/time/Make.defs
      +++ b/nuttx/libc/time/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/time/Make.defs
      +# libc/time/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/time/lib_calendar2utc.c b/nuttx/libc/time/lib_calendar2utc.c
      index e80c292fc6..1b8c40a9ea 100644
      --- a/nuttx/libc/time/lib_calendar2utc.c
      +++ b/nuttx/libc/time/lib_calendar2utc.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/time/lib_calendar2utc.c
      + * libc/time/lib_calendar2utc.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/time/lib_daysbeforemonth.c b/nuttx/libc/time/lib_daysbeforemonth.c
      index 8000b0e7a9..28f4d67a97 100644
      --- a/nuttx/libc/time/lib_daysbeforemonth.c
      +++ b/nuttx/libc/time/lib_daysbeforemonth.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/time/lib_daysbeforemonth.c
      + * libc/time/lib_daysbeforemonth.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/time/lib_gmtime.c b/nuttx/libc/time/lib_gmtime.c
      index 99afeded9e..7a4d0f5e14 100644
      --- a/nuttx/libc/time/lib_gmtime.c
      +++ b/nuttx/libc/time/lib_gmtime.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/time/lib_gmtime.c
      + * libc/time/lib_gmtime.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/time/lib_gmtimer.c b/nuttx/libc/time/lib_gmtimer.c
      index ba1c9724f1..d986205276 100644
      --- a/nuttx/libc/time/lib_gmtimer.c
      +++ b/nuttx/libc/time/lib_gmtimer.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/time/lib_gmtimer.c
      + * libc/time/lib_gmtimer.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/time/lib_isleapyear.c b/nuttx/libc/time/lib_isleapyear.c
      index 966c248e01..386e205b2e 100644
      --- a/nuttx/libc/time/lib_isleapyear.c
      +++ b/nuttx/libc/time/lib_isleapyear.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/time/lib_isleapyear.c
      + * libc/time/lib_isleapyear.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/time/lib_mktime.c b/nuttx/libc/time/lib_mktime.c
      index 8c17e7c0ab..25254d70e5 100644
      --- a/nuttx/libc/time/lib_mktime.c
      +++ b/nuttx/libc/time/lib_mktime.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/time/lib_mktime.c
      + * libc/time/lib_mktime.c
        *
        *   Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/time/lib_strftime.c b/nuttx/libc/time/lib_strftime.c
      index cd0804f55d..3b0c8dd8f3 100644
      --- a/nuttx/libc/time/lib_strftime.c
      +++ b/nuttx/libc/time/lib_strftime.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/time/lib_strftime.c
      + * libc/time/lib_strftime.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/time/lib_time.c b/nuttx/libc/time/lib_time.c
      index 106a04c366..673f6fdcdd 100644
      --- a/nuttx/libc/time/lib_time.c
      +++ b/nuttx/libc/time/lib_time.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/time/lib_time.c
      + * libc/time/lib_time.c
        *
        *   Copyright (C) 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/unistd/Make.defs b/nuttx/libc/unistd/Make.defs
      index e1441a48d3..67fce9b1d7 100644
      --- a/nuttx/libc/unistd/Make.defs
      +++ b/nuttx/libc/unistd/Make.defs
      @@ -1,5 +1,5 @@
       ############################################################################
      -# lib/unistd/Make.defs
      +# libc/unistd/Make.defs
       #
       #   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
      diff --git a/nuttx/libc/unistd/lib_chdir.c b/nuttx/libc/unistd/lib_chdir.c
      index 3dd1333cec..8953fb19b6 100644
      --- a/nuttx/libc/unistd/lib_chdir.c
      +++ b/nuttx/libc/unistd/lib_chdir.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/unistd/lib_chdir.c
      + * libc/unistd/lib_chdir.c
        *
        *   Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/unistd/lib_getcwd.c b/nuttx/libc/unistd/lib_getcwd.c
      index b94823300b..717ef29717 100644
      --- a/nuttx/libc/unistd/lib_getcwd.c
      +++ b/nuttx/libc/unistd/lib_getcwd.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/unistd/lib_getcwd.c
      + * libc/unistd/lib_getcwd.c
        *
        *   Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/unistd/lib_getopt.c b/nuttx/libc/unistd/lib_getopt.c
      index 832d287213..1a91909765 100644
      --- a/nuttx/libc/unistd/lib_getopt.c
      +++ b/nuttx/libc/unistd/lib_getopt.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/unistd/lib_getopt.c
      + * libc/unistd/lib_getopt.c
        *
        *   Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/unistd/lib_getoptargp.c b/nuttx/libc/unistd/lib_getoptargp.c
      index 98a4850169..5610342ca9 100644
      --- a/nuttx/libc/unistd/lib_getoptargp.c
      +++ b/nuttx/libc/unistd/lib_getoptargp.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/unistd/lib_getoptargp.c
      + * libc/unistd/lib_getoptargp.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/unistd/lib_getoptindp.c b/nuttx/libc/unistd/lib_getoptindp.c
      index 7714f8e708..94ea4d3fcd 100644
      --- a/nuttx/libc/unistd/lib_getoptindp.c
      +++ b/nuttx/libc/unistd/lib_getoptindp.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/unistd/lib_getoptindp.c
      + * libc/unistd/lib_getoptindp.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      diff --git a/nuttx/libc/unistd/lib_getoptoptp.c b/nuttx/libc/unistd/lib_getoptoptp.c
      index 4805b7ac3b..cd99b172f0 100644
      --- a/nuttx/libc/unistd/lib_getoptoptp.c
      +++ b/nuttx/libc/unistd/lib_getoptoptp.c
      @@ -1,5 +1,5 @@
       /****************************************************************************
      - * lib/unistd/lib_getoptoptp.c
      + * libc/unistd/lib_getoptoptp.c
        *
        *   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
        *   Author: Gregory Nutt 
      
      From 3bf4cd0abd093be0b3f2bac724aa952dc1b1bb60 Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sun, 11 Nov 2012 00:57:22 +0000
      Subject: [PATCH 101/206] Generated libraries are now installed in a new lib/
       directory
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5332 42af7a65-404d-4744-a932-0658087f49c3
      ---
       nuttx/ChangeLog                 |  7 +++
       nuttx/Documentation/README.html |  2 +
       nuttx/Makefile                  | 84 +++++++++++++++++++++++++--------
       nuttx/README.txt                |  2 +
       nuttx/lib/Makefile              | 45 ++++++++++++++++++
       nuttx/lib/README.txt            |  6 +++
       nuttx/libc/Makefile             |  2 +-
       7 files changed, 128 insertions(+), 20 deletions(-)
       create mode 100644 nuttx/lib/Makefile
       create mode 100644 nuttx/lib/README.txt
      
      diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
      index c63dbe62b2..d754bb72ce 100644
      --- a/nuttx/ChangeLog
      +++ b/nuttx/ChangeLog
      @@ -3595,3 +3595,10 @@
       	  directory that will be forthcoming.  Also rename libraries:  liblib.a -> libc.a,
       	  libulib.a -> libuc.a, libklib.a -> libkc.a, liblibxx.a ->libcxx.a.
       	  (I will probably, eventually rename libxx to libcxx for consistency)
      +	* Makefile, lib/: A new, empty directory that will hold generated libraries.
      +	  This simplifies the library patch calculations and lets me get rid of some
      +	  bash logic.  The change is functional, but only partially complete;
      +	  additional logic is needed in the arch/*/src/Makefile's as well.  Right
      +	  now that logic generate multiple library paths, all pointing to the lib/
      +	  directory.
      +
      diff --git a/nuttx/Documentation/README.html b/nuttx/Documentation/README.html
      index 0a4cc93b0c..771c605c7e 100644
      --- a/nuttx/Documentation/README.html
      +++ b/nuttx/Documentation/README.html
      @@ -236,6 +236,8 @@
        |   |       `- README.txt
        |   |- graphics/
        |   |   `- README.txt
      + |   |- lib/
      + |   |   `- README.txt
        |   |- libc/
        |   |   `- README.txt
        |   |- libxx/
      diff --git a/nuttx/Makefile b/nuttx/Makefile
      index c1060c34f7..bb8ee0a411 100644
      --- a/nuttx/Makefile
      +++ b/nuttx/Makefile
      @@ -35,7 +35,7 @@
       
       TOPDIR := ${shell pwd | sed -e 's/ /\\ /g'}
       -include ${TOPDIR}/.config
      --include ${TOPDIR}/tools/Config.mk
      +include ${TOPDIR}/tools/Config.mk
       -include ${TOPDIR}/Make.defs
       
       # Control build verbosity
      @@ -83,7 +83,7 @@ APPDIR := ${shell if [ -r $(CONFIG_APPS_DIR)/Makefile ]; then echo "$(CONFIG_APP
       # NUTTX_ADDONS is the list of directories built into the NuttX kernel.
       # USER_ADDONS is the list of directories that will be built into the user application
       
      -NUTTX_ADDONS := $(NX_DIR)
      +NUTTX_ADDONS :=
       USER_ADDONS :=
       
       ifeq ($(CONFIG_NUTTX_KERNEL),y)
      @@ -110,6 +110,7 @@ NONFSDIRS = sched $(ARCH_SRC) $(NUTTX_ADDONS)
       FSDIRS = fs drivers binfmt
       CONTEXTDIRS = $(APPDIR)
       USERDIRS =
      +OTHERDIRS = lib
       
       ifeq ($(CONFIG_NUTTX_KERNEL),y)
       
      @@ -189,7 +190,7 @@ endif
       # USERLIBS is the list of libraries used to build the final user-space
       #   application
       
      -NUTTXLIBS = sched/libsched$(LIBEXT) $(ARCH_SRC)/libarch$(LIBEXT)
      +NUTTXLIBS = lib/libsched$(LIBEXT) lib/libarch$(LIBEXT)
       USERLIBS =
       
       # Add libraries for syscall support.  The C library will be needed by
      @@ -197,10 +198,10 @@ USERLIBS =
       # is placed in user space (only).
       
       ifeq ($(CONFIG_NUTTX_KERNEL),y)
      -NUTTXLIBS += syscall/libstubs$(LIBEXT) libc/libkc$(LIBEXT)
      -USERLIBS += syscall/libproxies$(LIBEXT) libc/libuc$(LIBEXT) mm/libmm$(LIBEXT)
      +NUTTXLIBS += lib/libstubs$(LIBEXT) lib/libkc$(LIBEXT)
      +USERLIBS += lib/libproxies$(LIBEXT) lib/libuc$(LIBEXT) lib/libmm$(LIBEXT)
       else
      -NUTTXLIBS += mm/libmm$(LIBEXT) libc/libc$(LIBEXT)
      +NUTTXLIBS += lib/libmm$(LIBEXT) lib/libc$(LIBEXT)
       endif
       
       # Add libraries for C++ support.  CXX, CXXFLAGS, and COMPILEXX must
      @@ -208,9 +209,9 @@ endif
       
       ifeq ($(CONFIG_HAVE_CXX),y)
       ifeq ($(CONFIG_NUTTX_KERNEL),y)
      -USERLIBS += libxx/libcxx$(LIBEXT)
      +USERLIBS += lib/libcxx$(LIBEXT)
       else
      -NUTTXLIBS += libxx/libcxx$(LIBEXT)
      +NUTTXLIBS += lib/libcxx$(LIBEXT)
       endif
       endif
       
      @@ -218,40 +219,40 @@ endif
       
       ifneq ($(APPDIR),)
       ifeq ($(CONFIG_NUTTX_KERNEL),y)
      -USERLIBS += $(APPDIR)/libapps$(LIBEXT)
      +USERLIBS += lib/libapps$(LIBEXT)
       else
      -NUTTXLIBS += $(APPDIR)/libapps$(LIBEXT)
      +NUTTXLIBS += lib/libapps$(LIBEXT)
       endif
       endif
       
       # Add libraries for network support
       
       ifeq ($(CONFIG_NET),y)
      -NUTTXLIBS += net/libnet$(LIBEXT)
      +NUTTXLIBS += lib/libnet$(LIBEXT)
       endif
       
       # Add libraries for file system support
       
       ifeq ($(CONFIG_NFILE_DESCRIPTORS),0)
       ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0)
      -NUTTXLIBS += fs/libfs$(LIBEXT)
      +NUTTXLIBS += lib/libfs$(LIBEXT)
       endif
       ifeq ($(CONFIG_NET),y)
      -NUTTXLIBS += drivers/libdrivers$(LIBEXT)
      +NUTTXLIBS += lib/libdrivers$(LIBEXT)
       endif
       else
      -NUTTXLIBS += fs/libfs$(LIBEXT) drivers/libdrivers$(LIBEXT) binfmt/libbinfmt$(LIBEXT)
      +NUTTXLIBS += lib/libfs$(LIBEXT) lib/libdrivers$(LIBEXT) lib/libbinfmt$(LIBEXT)
       endif
       
       # Add libraries for the NX graphics sub-system
       
      -ifneq ($(NX_DIR),)
      -NUTTXLIBS += $(NX_DIR)/libnx$(LIBEXT)
      +ifeq ($(CONFIG_NX),y)
      +NUTTXLIBS += lib/libgraphics$(LIBEXT)
       endif
       
      -ifeq ($(CONFIG_NX),y)
      -NUTTXLIBS += graphics/libgraphics$(LIBEXT)
      -endif
      +# LINKLIBS derives from NUTTXLIBS and is simply the same list with the subdirectory removed
      +
      +LINKLIBS = $(patsubst lib/,,$(NUTTXLIBS))
       
       # This is the name of the final target (relative to the top level directorty)
       
      @@ -448,52 +449,97 @@ check_context:
       libc/libkc$(LIBEXT): context
       	$(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libkc$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
      +lib/libkc$(LIBEXT): libc/libkc$(LIBEXT)
      +	$(Q) install libc/libkc$(LIBEXT) lib/libkc$(LIBEXT)
      +
       sched/libsched$(LIBEXT): context
       	$(Q) $(MAKE) -C sched TOPDIR="$(TOPDIR)" libsched$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
      +lib/libsched$(LIBEXT): sched/libsched$(LIBEXT)
      +	$(Q) install sched/libsched$(LIBEXT) lib/libsched$(LIBEXT)
      +
       $(ARCH_SRC)/libarch$(LIBEXT): context
       	$(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" libarch$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
      +lib/libarch$(LIBEXT): $(ARCH_SRC)/libarch$(LIBEXT)
      +	$(Q) install $(ARCH_SRC)/libarch$(LIBEXT) lib/libarch$(LIBEXT)
      +
       net/libnet$(LIBEXT): context
       	$(Q) $(MAKE) -C net TOPDIR="$(TOPDIR)" libnet$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
      +lib/libnet$(LIBEXT): net/libnet$(LIBEXT)
      +	$(Q) install net/libnet$(LIBEXT) lib/libnet$(LIBEXT)
      +
       fs/libfs$(LIBEXT): context
       	$(Q) $(MAKE) -C fs TOPDIR="$(TOPDIR)" libfs$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
      +lib/libfs$(LIBEXT): fs/libfs$(LIBEXT)
      +	$(Q) install fs/libfs$(LIBEXT) lib/libfs$(LIBEXT)
      +
       drivers/libdrivers$(LIBEXT): context
       	$(Q) $(MAKE) -C drivers TOPDIR="$(TOPDIR)" libdrivers$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
      +lib/libdrivers$(LIBEXT): drivers/libdrivers$(LIBEXT)
      +	$(Q) install drivers/libdrivers$(LIBEXT) lib/libdrivers$(LIBEXT)
      +
       binfmt/libbinfmt$(LIBEXT): context
       	$(Q) $(MAKE) -C binfmt TOPDIR="$(TOPDIR)" libbinfmt$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
      +lib/libbinfmt$(LIBEXT): binfmt/libbinfmt$(LIBEXT)
      +	$(Q) install binfmt/libbinfmt$(LIBEXT) lib/libbinfmt$(LIBEXT)
      +
       graphics/libgraphics$(LIBEXT): context
       	$(Q) $(MAKE) -C graphics TOPDIR="$(TOPDIR)" libgraphics$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
      +lib/libgraphics$(LIBEXT): graphics/libgraphics$(LIBEXT)
      +	$(Q) install graphics/libgraphics$(LIBEXT) lib/libgraphics$(LIBEXT)
      +
       syscall/libstubs$(LIBEXT): context
       	$(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libstubs$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
      +lib/libstubs$(LIBEXT): syscall/libstubs$(LIBEXT)
      +	$(Q) install syscall/libstubs$(LIBEXT) lib/libstubs$(LIBEXT)
      +
       # Possible user-mode builds
       
       libc/libuc$(LIBEXT): context
       	$(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libuc$(LIBEXT)
       
      +lib/libuc$(LIBEXT): libc/libuc$(LIBEXT)
      +	$(Q) install libc/libuc$(LIBEXT) lib/libuc$(LIBEXT)
      +
       libxx/libcxx$(LIBEXT): context
       	$(Q) $(MAKE) -C libxx TOPDIR="$(TOPDIR)" libcxx$(LIBEXT)
       
      +lib/libcxx$(LIBEXT): libxx/libcxx$(LIBEXT)
      +	$(Q) install libxx/libcxx$(LIBEXT) lib/libcxx$(LIBEXT)
      +
       mm/libmm$(LIBEXT): context
       	$(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) EXTRADEFINES=$(KDEFINE)
       
      +lib/libmm$(LIBEXT): mm/libmm$(LIBEXT)
      +	$(Q) install mm/libmm$(LIBEXT) lib/libmm$(LIBEXT)
      +
       $(APPDIR)/libapps$(LIBEXT): context
       	$(Q) $(MAKE) -C $(APPDIR) TOPDIR="$(TOPDIR)" libapps$(LIBEXT)
       
      +lib/libapps$(LIBEXT): $(APPDIR)/libapps$(LIBEXT)
      +	$(Q) install $(APPDIR)/libapps$(LIBEXT) lib/libapps$(LIBEXT)
      +
       syscall/libproxies$(LIBEXT): context
       	$(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libproxies$(LIBEXT)
       
      +lib/libproxies$(LIBEXT): syscall/libproxies$(LIBEXT)
      +	$(Q) install syscall/libproxies$(LIBEXT) lib/libproxies$(LIBEXT)
      +
       # Possible non-kernel builds
       
       libc/libc$(LIBEXT): context
       	$(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libc$(LIBEXT)
       
      +lib/libc$(LIBEXT): libc/libc$(LIBEXT)
      +	$(Q) install libc/libc$(LIBEXT) lib/libc$(LIBEXT)
      +
       # pass1 and pass2
       #
       # If the 2 pass build option is selected, then this pass1 target is
      diff --git a/nuttx/README.txt b/nuttx/README.txt
      index c6138d1fdd..528b7897e5 100644
      --- a/nuttx/README.txt
      +++ b/nuttx/README.txt
      @@ -842,6 +842,8 @@ nuttx
        |       `- README.txt
        |- graphics/
        |   `- README.txt
      + |- lib/
      + |   `- README.txt
        |- libc/
        |   `- README.txt
        |- libxx/
      diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile
      new file mode 100644
      index 0000000000..d4e24124a0
      --- /dev/null
      +++ b/nuttx/lib/Makefile
      @@ -0,0 +1,45 @@
      +############################################################################
      +# lib/Makefile
      +#
      +#   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.
      +#
      +###########################################################################
      +
      +-include $(TOPDIR)/Make.defs
      +
      +all:
      +
      +depend:
      +
      +clean:
      +	@rm -f *$(LIBEXT)
      +
      +distclean: clean
      diff --git a/nuttx/lib/README.txt b/nuttx/lib/README.txt
      new file mode 100644
      index 0000000000..f742b9a243
      --- /dev/null
      +++ b/nuttx/lib/README.txt
      @@ -0,0 +1,6 @@
      +lib/ README File
      +================
      +
      +This directory is reserved for libraries generated during the NuttX build process
      +
      +
      diff --git a/nuttx/libc/Makefile b/nuttx/libc/Makefile
      index 318816ba71..da582cdae1 100644
      --- a/nuttx/libc/Makefile
      +++ b/nuttx/libc/Makefile
      @@ -78,7 +78,7 @@ $(AOBJS): %$(OBJEXT): %.S
       $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
      -$(BIN):	$(OBJS)
      +$(BIN): $(OBJS)
       	@( for obj in $(OBJS) ; do \
       		$(call ARCHIVE, $@, $${obj}); \
       	done ; )
      
      From 3ceb882b97a3080425f564a579a9f53a9422ee7c Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sun, 11 Nov 2012 13:52:31 +0000
      Subject: [PATCH 102/206] arch/../src/Makefiles now use only libraries in lib/
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5333 42af7a65-404d-4744-a932-0658087f49c3
      ---
       nuttx/ChangeLog                      |  1 +
       nuttx/Makefile                       |  6 +-
       nuttx/arch/8051/src/Makefile         | 84 ++++++++++++++--------------
       nuttx/arch/arm/src/Makefile          |  9 +--
       nuttx/arch/avr/src/Makefile          | 71 +++++++++++------------
       nuttx/arch/hc/src/Makefile           | 55 +++++++++---------
       nuttx/arch/mips/src/Makefile         | 57 +++++++++----------
       nuttx/arch/rgmp/src/Makefile         |  5 +-
       nuttx/arch/sh/src/Makefile           | 43 ++++++++------
       nuttx/arch/sim/src/Makefile          | 17 +++---
       nuttx/arch/x86/src/Makefile          | 63 +++++++++++----------
       nuttx/arch/z16/src/Makefile          | 44 +++++++--------
       nuttx/arch/z80/src/Makefile.sdcc     | 34 +++++------
       nuttx/configs/ea3131/locked/Makefile | 28 +++++-----
       14 files changed, 265 insertions(+), 252 deletions(-)
      
      diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
      index d754bb72ce..e4193db20c 100644
      --- a/nuttx/ChangeLog
      +++ b/nuttx/ChangeLog
      @@ -3601,4 +3601,5 @@
       	  additional logic is needed in the arch/*/src/Makefile's as well.  Right
       	  now that logic generate multiple library paths, all pointing to the lib/
       	  directory.
      +	* arch/*/src/Makefile:  Now uses only the libraries in lib/
       
      diff --git a/nuttx/Makefile b/nuttx/Makefile
      index bb8ee0a411..7263489c25 100644
      --- a/nuttx/Makefile
      +++ b/nuttx/Makefile
      @@ -252,7 +252,7 @@ endif
       
       # LINKLIBS derives from NUTTXLIBS and is simply the same list with the subdirectory removed
       
      -LINKLIBS = $(patsubst lib/,,$(NUTTXLIBS))
      +LINKLIBS = $(patsubst lib/%,%,$(NUTTXLIBS))
       
       # This is the name of the final target (relative to the top level directorty)
       
      @@ -566,13 +566,13 @@ ifeq ($(CONFIG_BUILD_2PASS),y)
       		echo "ERROR: No Makefile in CONFIG_PASS1_BUILDIR"; \
       		exit 1; \
       	fi
      -	$(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" LINKLIBS="$(NUTTXLIBS)" USERLIBS="$(USERLIBS)" "$(CONFIG_PASS1_TARGET)"
      +	$(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" LINKLIBS="$(LINKLIBS)" USERLIBS="$(USERLIBS)" "$(CONFIG_PASS1_TARGET)"
       endif
       
       pass2deps: context pass2dep $(NUTTXLIBS)
       
       pass2: pass2deps
      -	$(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(NUTTXLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN)
      +	$(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(LINKLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN)
       	$(Q) if [ -w /tftpboot ] ; then \
       		cp -f $(BIN) /tftpboot/$(BIN).${CONFIG_ARCH}; \
       	fi
      diff --git a/nuttx/arch/8051/src/Makefile b/nuttx/arch/8051/src/Makefile
      index 83c796119f..54a3ce79bc 100644
      --- a/nuttx/arch/8051/src/Makefile
      +++ b/nuttx/arch/8051/src/Makefile
      @@ -35,51 +35,51 @@
       
       -include $(TOPDIR)/Make.defs
       
      -CFLAGS		+= -I$(TOPDIR)/sched
      -ASFLAGS		= -x -j -g -l -s -p
      -CPPFLAGS	= $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -D__ASSEMBLY__
      +CFLAGS += -I$(TOPDIR)/sched
      +ASFLAGS = -x -j -g -l -s -p
      +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -D__ASSEMBLY__
       
      -SSRCS		= 
      -ASRCS		= $(SSRCS:.S=$(ASMEXT))
      -AOBJS		= $(ASRCS:$(ASMEXT)=$(OBJEXT))
      -CSRCS		= up_initialize.c up_idle.c up_interruptcontext.c \
      -		  up_initialstate.c up_unblocktask.c up_blocktask.c \
      -		  up_releasepending.c up_reprioritizertr.c \
      -		  up_exit.c up_assert.c up_allocateheap.c \
      -		  up_irq.c up_savecontext.c up_restorecontext.c \
      -		  up_timerisr.c up_putc.c up_debug.c up_delay.c
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      -SRCS		= $(SSRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      +SSRCS = 
      +ASRCS = $(SSRCS:.S=$(ASMEXT))
      +AOBJS = $(ASRCS:$(ASMEXT)=$(OBJEXT))
      +CSRCS = up_initialize.c up_idle.c up_interruptcontext.c \
      +		up_initialstate.c up_unblocktask.c up_blocktask.c \
      +		up_releasepending.c up_reprioritizertr.c \
      +		up_exit.c up_assert.c up_allocateheap.c \
      +		up_irq.c up_savecontext.c up_restorecontext.c \
      +		up_timerisr.c up_putc.c up_debug.c up_delay.c
      +COBJS = $(CSRCS:.c=$(OBJEXT))
      +SRCS = $(SSRCS) $(CSRCS)
      +OBJS = $(AOBJS) $(COBJS)
       
      -SDCCLIBDIR	= /usr/local/share/sdcc/lib/large-stack-auto
      -SDCCPATH	= -L$(SDCCLIBDIR)
      -SDCCLIBS	= -llibfloat.lib -llibint.lib -lliblong.lib -llibmysdcc.lib -lmcs51.lib
      +SDCCLIBDIR = /usr/local/share/sdcc/lib/large-stack-auto
      +SDCCPATH = -L$(SDCCLIBDIR)
      +SDCCLIBS = -llibfloat.lib -llibint.lib -lliblong.lib -llibmysdcc.lib -lmcs51.lib
       
      -LINKSSRCS	= up_head.S
      -LINKASRCS	= $(LINKSSRCS:.S=$(ASMEXT))
      -LINKOBJS	= $(LINKASRCS:$(ASMEXT)=$(OBJEXT))
      -LINKLIBS	=
      -LDPATHES	= $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
      -LDLIBS		= $(addprefix -l,$(notdir $(LINKLIBS)))
      +LINKSSRCS = up_head.S
      +LINKASRCS = $(LINKSSRCS:.S=$(ASMEXT))
      +LINKOBJS = $(LINKASRCS:$(ASMEXT)=$(OBJEXT))
      +LINKLIBS ?=
      +LDPATHS = -L"$(TOPDIR)/lib"
      +LDLIBS =  $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -TESTSRCS	= up_irqtest.c
      -TESTOBJS	= $(TESTSRCS:.c=$(OBJEXT))
      -TESTLINKOBJS	= up_head$(OBJEXT)
      -TESTEXTRAOBJS	= up_savecontext$(OBJEXT) up_restorecontext$(OBJEXT)
      +TESTSRCS = up_irqtest.c
      +TESTOBJS = $(TESTSRCS:.c=$(OBJEXT))
      +TESTLINKOBJS = up_head$(OBJEXT)
      +TESTEXTRAOBJS = up_savecontext$(OBJEXT) up_restorecontext$(OBJEXT)
       
      -BOARDDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      +BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
       
      -IRAM_SIZE	= 0x100
      -DEF_STACK_BASE	= 0x24
      -LDFLAGS		+= --model-large --nostdlib \
      -		  --data-loc $(DEF_STACK_BASE) --iram-size $(IRAM_SIZE) \
      -		  --code-loc 0x2100 --code-size 0x5f40 \
      -		  --xram-loc $(IRAM_SIZE) --xram-size 0x1f00
      +IRAM_SIZE = 0x100
      +DEF_STACK_BASE = 0x24
      +LDFLAGS += --model-large --nostdlib \
      +		--data-loc $(DEF_STACK_BASE) --iram-size $(IRAM_SIZE) \
      +		--code-loc 0x2100 --code-size 0x5f40 \
      +		--xram-loc $(IRAM_SIZE) --xram-size 0x1f00
       
      -DEPSRCS		= $(SRCS) $(LINKSSRCS)
      +DEPSRCS = $(SRCS) $(LINKSSRCS)
       
      -HEAP1_BASE	= ${shell \
      +HEAP1_BASE = ${shell \
       			if [ -e pass1.mem ]; then \
       				cat pass1.mem | grep "EXTERNAL RAM" | \
       				sed -e "s/[ ][ ]*/ /g" | cut -d' ' -f5 ; \
      @@ -87,8 +87,8 @@ HEAP1_BASE	= ${shell \
       				echo $(IRAM_SIZE) ; \
       			fi \
       		   }
      -DEF_HEAP2_BASE	= 0x6000
      -HEAP2_BASE	= ${shell \
      +DEF_HEAP2_BASE = 0x6000
      +HEAP2_BASE = ${shell \
       			if [ -e pass1.mem ]; then \
       				cat pass1.mem | grep "ROM/EPROM/FLASH" | \
       				sed -e "s/[ ][ ]*/ /g" | cut -d' ' -f4 ; \
      @@ -96,7 +96,7 @@ HEAP2_BASE	= ${shell \
       				echo $(DEF_HEAP2_BASE) ; \
       			fi \
       		   }
      -STACK_BASE	= ${shell \
      +STACK_BASE = ${shell \
       			if [ -e pass1.mem ]; then \
       				cat pass1.mem | grep "Stack starts" | \
       				cut -d' ' -f4 ; \
      @@ -173,7 +173,7 @@ board/libboard$(LIBEXT):
       
       pass1.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS) board/libboard$(LIBEXT)
       	@echo "LD:  $@"
      -	@$(CC) $(LDFLAGS) $(LDPATHES) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
      +	@$(CC) $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
       		$(LDLIBS) -llibboard$(LIBEXT) $(SDCCLIBS) -o $@
       	@rm -f up_mem.h
       	@rm -f up_allocateheap$(OBJEXT) libarch$(LIBEXT)
      @@ -181,7 +181,7 @@ pass1.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS) board/libboard$(LIBE
       
       nuttx.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS)
       	@echo "LD:  $@"
      -	@$(CC) $(LDFLAGS) $(LDPATHES) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
      +	@$(CC) $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
       		$(LDLIBS) -llibboard$(LIBEXT) $(SDCCLIBS) -o $@
       
       nuttx$(EXEEXT): pass1.hex nuttx.hex
      diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile
      index f356f4d02a..49fabb7087 100644
      --- a/nuttx/arch/arm/src/Makefile
      +++ b/nuttx/arch/arm/src/Makefile
      @@ -74,16 +74,17 @@ LDFLAGS += $(ARCHSCRIPT)
       
       EXTRA_LIBS ?=
       EXTRA_LIBPATHS ?=
      +LINKLIBS ?=
       
      -LINKLIBS =
       ifeq ($(WINTOOL),y)
      -  LIBPATHS = ${shell for path in $(LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done}
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
         LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
       else
      -  LIBPATHS = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
      +  LIBPATHS += -L"(TOPDIR)/lib"
         LIBPATHS += -L"$(BOARDDIR)"
       endif
      -LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
      +
      +LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
       BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
       
      diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile
      index bbfc4dd4f9..160ae63179 100644
      --- a/nuttx/arch/avr/src/Makefile
      +++ b/nuttx/arch/avr/src/Makefile
      @@ -37,61 +37,62 @@
       -include $(TOPDIR)/Make.defs
       -include chip/Make.defs
       
      -ARCH_SRCDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src
      +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
       ifeq ($(CONFIG_ARCH_AVR32),y)
      -ARCH_SUBDIR	= avr32
      +ARCH_SUBDIR = avr32
       else ifeq ($(CONFIG_ARCH_AVR),y)
      -ARCH_SUBDIR	= avr
      +ARCH_SUBDIR = avr
       endif
       
       ifeq ($(WINTOOL),y)
      -  NUTTX		= "${shell cygpath -w $(TOPDIR)/nuttx}"
      -  INCLUDES	+= -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}"
      -  INCLUDES	+= -I "${shell cygpath -w $(ARCH_SRCDIR)/common}"
      -  INCLUDES	+= -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}"
      -  INCLUDES	+= -I "${shell cygpath -w $(TOPDIR)/sched}"
      +  NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}"
      +  INCLUDES += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}"
      +  INCLUDES += -I "${shell cygpath -w $(ARCH_SRCDIR)/common}"
      +  INCLUDES += -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}"
      +  INCLUDES += -I "${shell cygpath -w $(TOPDIR)/sched}"
       else
      -  NUTTX		= "$(TOPDIR)/nuttx"
      -  INCLUDES	+= -I "$(ARCH_SRCDIR)/chip"
      -  INCLUDES	+= -I "$(ARCH_SRCDIR)/common"
      -  INCLUDES	+= -I "$(ARCH_SRCDIR)/$(ARCH_SUBDIR)"
      -  INCLUDES	+= -I "$(TOPDIR)/sched"
      +  NUTTX = "$(TOPDIR)/nuttx"
      +  INCLUDES += -I "$(ARCH_SRCDIR)/chip"
      +  INCLUDES += -I "$(ARCH_SRCDIR)/common"
      +  INCLUDES += -I "$(ARCH_SRCDIR)/$(ARCH_SUBDIR)"
      +  INCLUDES += -I "$(TOPDIR)/sched"
       endif
       
      -CPPFLAGS	+= $(INCLUDES)
      -CFLAGS		+= $(INCLUDES)
      -CXXFLAGS	+= $(INCLUDES)
      -AFLAGS		+= $(INCLUDES)
      +CPPFLAGS += $(INCLUDES)
      +CFLAGS += $(INCLUDES)
      +CXXFLAGS += $(INCLUDES)
      +AFLAGS += $(INCLUDES)
       
      -HEAD_OBJ	= $(HEAD_ASRC:.S=$(OBJEXT))
      +HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT))
       
      -ASRCS		= $(CHIP_ASRCS) $(CMN_ASRCS)
      -AOBJS		= $(ASRCS:.S=$(OBJEXT))
      +ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
      +AOBJS = $(ASRCS:.S=$(OBJEXT))
       
      -CSRCS		= $(CHIP_CSRCS) $(CMN_CSRCS)
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      +CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
      +COBJS = $(CSRCS:.c=$(OBJEXT))
       
      -SRCS		= $(ASRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      +SRCS = $(ASRCS) $(CSRCS)
      +OBJS = $(AOBJS) $(COBJS)
       
      -LDFLAGS		+= $(ARCHSCRIPT)
      -EXTRA_LIBS	?=
      +LDFLAGS += $(ARCHSCRIPT)
      +EXTRA_LIBS ?=
      +LINKLIBS ?=
       
      -LINKLIBS	=
       ifeq ($(WINTOOL),y)
      -  LIBPATHS	= ${shell for path in $(LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done}
      -  LIBPATHS	+= -L"${shell cygpath -w $(BOARDDIR)}"
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
       else
      -  LIBPATHS	= $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
      -  LIBPATHS	+= -L"$(BOARDDIR)"
      +  LIBPATHS += -L"(TOPDIR)/lib"
      +  LIBPATHS += -L"$(BOARDDIR)"
       endif
      -LDLIBS		= $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
       
      -BOARDDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      +LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -LIBGCC		= "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
       
      -VPATH		= chip:common:$(ARCH_SUBDIR)
      +LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +
      +VPATH = chip:common:$(ARCH_SUBDIR)
       
       all: $(HEAD_OBJ) libarch$(LIBEXT)
       
      diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile
      index ff19ce6fe6..b2058466ca 100644
      --- a/nuttx/arch/hc/src/Makefile
      +++ b/nuttx/arch/hc/src/Makefile
      @@ -36,55 +36,56 @@
       -include $(TOPDIR)/Make.defs
       -include chip/Make.defs
       
      -ARCH_SRCDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src
      +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
       ifeq ($(CONFIG_ARCH_HC12),y)
      -ARCH_SUBDIR	= hc12
      +ARCH_SUBDIR = hc12
       endif
       ifeq ($(CONFIG_ARCH_HCS12),y)
      -ARCH_SUBDIR	= hcs12
      +ARCH_SUBDIR = hcs12
       endif
       
       ifeq ($(WINTOOL),y)
      -  NUTTX		= "${shell cygpath -w $(TOPDIR)/nuttx}"
      -  CFLAGS	+= -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
      -  		   -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
      +  NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}"
      +  CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
      +		   -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
       		   -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \
       		   -I "${shell cygpath -w $(TOPDIR)/sched}"
       else
      -  NUTTX		= $(TOPDIR)/nuttx
      -  CFLAGS	+= -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \
      -		   -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched
      +  NUTTX = $(TOPDIR)/nuttx
      +  CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \
      +			-I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched
       endif
       
      -HEAD_OBJ	= $(HEAD_ASRC:.S=$(OBJEXT))
      +HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT))
       
      -ASRCS		= $(CHIP_ASRCS) $(CMN_ASRCS)
      -AOBJS		= $(ASRCS:.S=$(OBJEXT))
      +ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
      +AOBJS = $(ASRCS:.S=$(OBJEXT))
       
      -CSRCS		= $(CHIP_CSRCS) $(CMN_CSRCS)
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      +CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
      +COBJS = $(CSRCS:.c=$(OBJEXT))
       
      -SRCS		= $(ASRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      +SRCS = $(ASRCS) $(CSRCS)
      +OBJS = $(AOBJS) $(COBJS)
       
      -LDFLAGS		+= $(ARCHSCRIPT)
      -EXTRA_LIBS	?=
      +LDFLAGS += $(ARCHSCRIPT)
      +EXTRA_LIBS ?=
      +LINKLIBS ?=
       
      -LINKLIBS	=
       ifeq ($(WINTOOL),y)
      -  LIBPATHS	= ${shell for path in $(LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done}
      -  LIBPATHS	+= -L"${shell cygpath -w $(BOARDDIR)}"
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
       else
      -  LIBPATHS	= $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
      -  LIBPATHS	+= -L"$(BOARDDIR)"
      +  LIBPATHS += -L"(TOPDIR)/lib"
      +  LIBPATHS += -L"$(BOARDDIR)"
       endif
      -LDLIBS		= $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
       
      -BOARDDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      +LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -LIBGCC		= "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
       
      -VPATH		= chip:common:$(ARCH_SUBDIR)
      +LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +
      +VPATH = chip:common:$(ARCH_SUBDIR)
       
       all: $(HEAD_OBJ) libarch$(LIBEXT)
       .PHONY: board/libboard$(LIBEXT)
      diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile
      index 8769f35eca..c9019febdc 100644
      --- a/nuttx/arch/mips/src/Makefile
      +++ b/nuttx/arch/mips/src/Makefile
      @@ -36,52 +36,53 @@
       -include $(TOPDIR)/Make.defs
       -include chip/Make.defs
       
      -ARCH_SRCDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src
      +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
       ifeq ($(CONFIG_ARCH_MIPS),y)
      -ARCH_SUBDIR     = mips32
      +ARCH_SUBDIR = mips32
       endif
       
       ifeq ($(WINTOOL),y)
      -  NUTTX		= "${shell cygpath -w $(TOPDIR)/nuttx}"
      -  CFLAGS	+= -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
      -  		   -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
      -		   -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \
      -		   -I "${shell cygpath -w $(TOPDIR)/sched}"
      +  NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}"
      +  CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
      +			-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
      +			-I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \
      +			-I "${shell cygpath -w $(TOPDIR)/sched}"
       else
      -  NUTTX		= $(TOPDIR)/nuttx
      -  CFLAGS	+= -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \
      -		   -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched
      +  NUTTX = $(TOPDIR)/nuttx
      +  CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \
      +			-I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched
       endif
       
      -HEAD_OBJ	= $(HEAD_ASRC:.S=$(OBJEXT))
      +HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT))
       
      -ASRCS		= $(CHIP_ASRCS) $(CMN_ASRCS)
      -AOBJS		= $(ASRCS:.S=$(OBJEXT))
      +ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
      +AOBJS = $(ASRCS:.S=$(OBJEXT))
       
      -CSRCS		= $(CHIP_CSRCS) $(CMN_CSRCS)
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      +CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
      +COBJS = $(CSRCS:.c=$(OBJEXT))
       
      -SRCS		= $(ASRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      +SRCS = $(ASRCS) $(CSRCS)
      +OBJS = $(AOBJS) $(COBJS)
       
      -LDFLAGS		+= $(ARCHSCRIPT)
      -EXTRA_LIBS	?=
      +LDFLAGS += $(ARCHSCRIPT)
      +EXTRA_LIBS ?=
      +LINKLIBS ?=
       
      -LINKLIBS	=
       ifeq ($(WINTOOL),y)
      -  LIBPATHS	= ${shell for path in $(LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done}
      -  LIBPATHS	+= -L"${shell cygpath -w $(BOARDDIR)}"
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
       else
      -  LIBPATHS	= $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
      -  LIBPATHS	+= -L"$(BOARDDIR)"
      +  LIBPATHS += -L"(TOPDIR)/lib"
      +  LIBPATHS += -L"$(BOARDDIR)"
       endif
      -LDLIBS		= $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
       
      -BOARDDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      +LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -LIBGCC		= "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
       
      -VPATH		= chip:common:$(ARCH_SUBDIR)
      +LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +
      +VPATH = chip:common:$(ARCH_SUBDIR)
       
       all: $(HEAD_OBJ) libarch$(LIBEXT)
       
      diff --git a/nuttx/arch/rgmp/src/Makefile b/nuttx/arch/rgmp/src/Makefile
      index 80ad78b379..3989ab102c 100644
      --- a/nuttx/arch/rgmp/src/Makefile
      +++ b/nuttx/arch/rgmp/src/Makefile
      @@ -53,9 +53,8 @@ LINKSRCS    = rgmp.c bridge.c
       LINKOBJS    = $(LINKSRCS:.c=$(OBJEXT))
       
       LDFLAGS		+= -T$(RGMPLKSCPT)
      -LDPATHS		= $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
      -LDLIBS		= $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
      -LDPATHS		+= -L$(RGMPLIBDIR)
      +LDLIBS		= $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
      +LDPATHS		+= -L"$(TOPDIR)/lib -L$(RGMPLIBDIR)
       LDLIBS		+= -lrgmp $(shell $(CC) -print-libgcc-file-name)
       
       all: libarch$(LIBEXT)
      diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile
      index 3008983966..2cb22728ef 100644
      --- a/nuttx/arch/sh/src/Makefile
      +++ b/nuttx/arch/sh/src/Makefile
      @@ -36,32 +36,39 @@
       -include $(TOPDIR)/Make.defs
       -include chip/Make.defs
       
      -ARCH_SRCDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src
      -CFLAGS		+= -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched
      +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
      +CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched
       
      -HEAD_OBJ	= $(HEAD_ASRC:.S=$(OBJEXT))
      +HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT))
       
      -ASRCS		= $(CHIP_ASRCS) $(CMN_ASRCS)
      -AOBJS		= $(ASRCS:.S=$(OBJEXT))
      +ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
      +AOBJS = $(ASRCS:.S=$(OBJEXT))
       
      -CSRCS		= $(CHIP_CSRCS) $(CMN_CSRCS)
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      +CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
      +COBJS = $(CSRCS:.c=$(OBJEXT))
       
      -SRCS		= $(ASRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      +SRCS = $(ASRCS) $(CSRCS)
      +OBJS = $(AOBJS) $(COBJS)
       
      -LDFLAGS		+= $(ARCHSCRIPT)
      -EXTRA_LIBS	?=
      +LDFLAGS += $(ARCHSCRIPT)
      +EXTRA_LIBS ?=
      +LINKLIBS ?=
       
      -LINKLIBS	=
      -LDPATHES	= $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
      -LDLIBS		= $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
      +ifeq ($(WINTOOL),y)
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +else
      +  LIBPATHS += -L"(TOPDIR)/lib"
      +  LIBPATHS += -L"$(BOARDDIR)"
      +endif
       
      -BOARDDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      +LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -LIBGCC		= ${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}
      +BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
       
      -VPATH		= chip:common
      +LIBGCC = ${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}
      +
      +VPATH = chip:common
       
       all: $(HEAD_OBJ) libarch$(LIBEXT)
       
      @@ -83,7 +90,7 @@ board/libboard$(LIBEXT):
       
       nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx"
      -	@$(LD) --entry=__start $(LDFLAGS) $(LDPATHES) -L$(BOARDDIR) -o $(TOPDIR)/$@ $(HEAD_OBJ) \
      +	@$(LD) --entry=__start $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) -o $(TOPDIR)/$@ $(HEAD_OBJ) \
       		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
       	@$(NM) $(TOPDIR)/$@ | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
      diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile
      index 1e4d08736b..3719465b37 100644
      --- a/nuttx/arch/sim/src/Makefile
      +++ b/nuttx/arch/sim/src/Makefile
      @@ -40,11 +40,11 @@ CFLAGS += -I$(TOPDIR)/sched
       ASRCS = up_setjmp.S
       AOBJS = $(ASRCS:.S=$(OBJEXT))
       CSRCS = up_initialize.c up_idle.c up_interruptcontext.c \
      -		  up_initialstate.c up_createstack.c up_usestack.c \
      -		  up_releasestack.c  up_unblocktask.c up_blocktask.c \
      -		  up_releasepending.c up_reprioritizertr.c \
      -		  up_exit.c up_schedulesigaction.c up_allocateheap.c \
      -		  up_devconsole.c
      +		up_initialstate.c up_createstack.c up_usestack.c \
      +		up_releasestack.c  up_unblocktask.c up_blocktask.c \
      +		up_releasepending.c up_reprioritizertr.c \
      +		up_exit.c up_schedulesigaction.c up_allocateheap.c \
      +		up_devconsole.c
       HOSTSRCS = up_stdio.c up_hostusleep.c
       
       ifeq ($(CONFIG_NX_LCDDRIVER),y)
      @@ -126,9 +126,10 @@ endif
       # Determine which NuttX libraries will need to be linked in
       # Most are provided by LINKLIBS on the MAKE command line
       
      -LINKLIBS =
      -LDPATHS = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
      -LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
      +LINKLIBS ?=
      +LIBPATHS += -L"(TOPDIR)/lib"
      +LIBPATHS += -L"$(BOARDDIR)"
      +LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
       # Add the board-specific library and directory
       
      diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile
      index 7225f31cf0..b4aa02fb15 100644
      --- a/nuttx/arch/x86/src/Makefile
      +++ b/nuttx/arch/x86/src/Makefile
      @@ -36,60 +36,61 @@
       -include $(TOPDIR)/Make.defs
       -include chip/Make.defs
       
      -ARCH_SRCDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src
      +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
       ifeq ($(CONFIG_ARCH_I486),y)
      -ARCH_SUBDIR	= i486
      +ARCH_SUBDIR = i486
       endif
       
       ifeq ($(WINTOOL),y)
      -  NUTTX		= "${shell cygpath -w $(TOPDIR)/nuttx}"
      -  CFLAGS	+= -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
      -  		   -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
      -		   -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \
      -		   -I "${shell cygpath -w $(TOPDIR)/sched}"
      +  NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}"
      +  CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
      +		-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
      +		-I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \
      +		-I "${shell cygpath -w $(TOPDIR)/sched}"
       else
      -  NUTTX		= $(TOPDIR)/nuttx
      -  CFLAGS	+= -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \
      -		   -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched
      +  NUTTX = $(TOPDIR)/nuttx
      +  CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \
      +		-I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched
       endif
       
      -HEAD_OBJ	= $(HEAD_ASRC:.S=$(OBJEXT))
      +HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT))
       
      -ASRCS		= $(CHIP_ASRCS) $(CMN_ASRCS)
      -AOBJS		= $(ASRCS:.S=$(OBJEXT))
      +ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
      +AOBJS = $(ASRCS:.S=$(OBJEXT))
       
      -CSRCS		= $(CHIP_CSRCS) $(CMN_CSRCS)
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      +CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
      +COBJS = $(CSRCS:.c=$(OBJEXT))
       
      -SRCS		= $(ASRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      +SRCS = $(ASRCS) $(CSRCS)
      +OBJS = $(AOBJS) $(COBJS)
       
      -LDFLAGS		+= $(ARCHSCRIPT)
      -EXTRA_LIBS	?=
      +LDFLAGS += $(ARCHSCRIPT)
      +EXTRA_LIBS ?=
      +LINKLIBS ?=
       
      -LINKLIBS	=
       ifeq ($(WINTOOL),y)
      -  LIBPATHS	= ${shell for path in $(LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done}
      -  LIBPATHS	+= -L"${shell cygpath -w $(BOARDDIR)}"
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
       else
      -  LIBPATHS	= $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
      -  LIBPATHS	+= -L"$(BOARDDIR)"
      +  LIBPATHS += -L"(TOPDIR)/lib"
      +  LIBPATHS += -L"$(BOARDDIR)"
       endif
      -LDLIBS		= $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
       
      -BOARDDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      +LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -LIBGCC		= "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      +
      +LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
       ifeq ($(HOSTOS),FreeBSD)
      -  HOST_ARCH	= ${shell uname -m 2>/dev/null || echo "Other"}
      +  HOST_ARCH = ${shell uname -m 2>/dev/null || echo "Other"}
         ifeq ($(HOST_ARCH),amd64)
      -    LDFLAGS	+= -melf_i386
      -    LIBGCC	= "/usr/lib32/libgcc.a"
      +    LDFLAGS += -melf_i386
      +    LIBGCC = "/usr/lib32/libgcc.a"
         endif
       endif
       
      -VPATH		= chip:common:$(ARCH_SUBDIR)
      +VPATH = chip:common:$(ARCH_SUBDIR)
       
       all: $(HEAD_OBJ) libarch$(LIBEXT)
       
      diff --git a/nuttx/arch/z16/src/Makefile b/nuttx/arch/z16/src/Makefile
      index 088aeebd2e..3da8c2d676 100644
      --- a/nuttx/arch/z16/src/Makefile
      +++ b/nuttx/arch/z16/src/Makefile
      @@ -36,38 +36,38 @@
       -include $(TOPDIR)/Make.defs
       -include chip/Make.defs
       
      -COMPILER	= ${shell basename $(CC)}
      -ARCHSRCDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src
      +COMPILER = ${shell basename $(CC)}
      +ARCHSRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
       ifeq ($(COMPILER),zneocc.exe)
      -WARCHSRCDIR	:= ${shell cygpath -w $(ARCHSRCDIR)}
      -USRINCLUDES	= -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common'
      +WARCHSRCDIR := ${shell cygpath -w $(ARCHSRCDIR)}
      +USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common'
       else
      -WARCHSRCDIR	= $(ARCHSRCDIR)
      -USRINCLUDES	= -I$(TOPDIR)/sched -I$(ARCHSRCDIR) -I$(ARCHSRCDIR)/common
      +WARCHSRCDIR = $(ARCHSRCDIR)
      +USRINCLUDES = -I$(TOPDIR)/sched -I$(ARCHSRCDIR) -I$(ARCHSRCDIR)/common
       endif
      -INCLUDES	= $(ARCHSTDINCLUDES) $(USRINCLUDES)
      -CFLAGS		= $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
      -CPPFLAGS	+= -I$(ARCHSRCDIR)
      +INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES)
      +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
      +CPPFLAGS += -I$(ARCHSRCDIR)
       ifeq ($(COMPILER),zneocc.exe)
      -LDFLAGS 	+= @"${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}"
      +LDFLAGS  += @"${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}"
       endif
       
      -HEAD_ASRC	= $(HEAD_SSRC:.S=$(ASMEXT))
      -HEAD_OBJ	= $(HEAD_SSRC:.S=$(OBJEXT))
      +HEAD_ASRC = $(HEAD_SSRC:.S=$(ASMEXT))
      +HEAD_OBJ = $(HEAD_SSRC:.S=$(OBJEXT))
       
      -SSRCS		= $(CHIP_SSRCS) $(CMN_SSRCS)
      -ASRCS		= $(SSRCS:.S=$(ASMEXT))
      -AOBJS		= $(SSRCS:.S=$(OBJEXT))
      +SSRCS = $(CHIP_SSRCS) $(CMN_SSRCS)
      +ASRCS = $(SSRCS:.S=$(ASMEXT))
      +AOBJS = $(SSRCS:.S=$(OBJEXT))
       
      -CSRCS		= $(CHIP_CSRCS) $(CMN_CSRCS)
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      +CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
      +COBJS = $(CSRCS:.c=$(OBJEXT))
       
      -DEPSRCS 	= $(SSRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      +DEPSRCS = $(SSRCS) $(CSRCS)
      +OBJS = $(AOBJS) $(COBJS)
       
      -BOARDDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      +BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
       
      -VPATH		= chip:common
      +VPATH = chip:common
       
       all: $(HEAD_OBJ) libarch$(LIBEXT)
       
      @@ -103,7 +103,7 @@ nuttx.linkcmd: $(LINKCMDTEMPLATE)
       	@echo "\"${shell cygpath -w $(TOPDIR)/nuttx}\"= \\" >>nuttx.linkcmd
       	@echo "  \"${shell cygpath -w $(ARCHSRCDIR)/$(HEAD_OBJ)}\", \\" >>nuttx.linkcmd
       	@( for lib in $(LINKLIBS); do \
      -		echo "  \"`cygpath -w $(TOPDIR)/$${lib}`\", \\" >>nuttx.linkcmd; \
      +		echo "  \"`cygpath -w $(TOPDIR)/lib/$${lib}`\", \\" >>nuttx.linkcmd; \
       	done ; )
       	@echo "  \"${shell cygpath -w $(ARCHSRCDIR)/board/libboard$(LIBEXT)}\", \\"  >>nuttx.linkcmd
       	@echo "  \"${shell cygpath -w $(ZDSSTDLIBDIR)/chelpld$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      diff --git a/nuttx/arch/z80/src/Makefile.sdcc b/nuttx/arch/z80/src/Makefile.sdcc
      index 522c8d6f90..32169d4420 100644
      --- a/nuttx/arch/z80/src/Makefile.sdcc
      +++ b/nuttx/arch/z80/src/Makefile.sdcc
      @@ -37,49 +37,49 @@
       # Tools
       # CFLAGS, CPPFLAGS, ASFLAGS, LDFLAGS are set in $(TOPDIR)/Make.defs
       
      -CFLAGS		+= -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched
      -CPPFLAGS	+= -D__ASSEMBLY__
      +CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched
      +CPPFLAGS += -D__ASSEMBLY__
       
       ############################################################################
       # Files and directories
       
       # There should be one head source (.asm file)
       
      -HEAD_OBJ	= $(HEAD_ASRC:$(ASMEXT)=$(OBJEXT))
      +HEAD_OBJ = $(HEAD_ASRC:$(ASMEXT)=$(OBJEXT))
       
       # Assembly sources and objects
       
      -ASRCS		= $(CHIP_ASRCS) $(CMN_ASRCS)
      -AOBJS		= $(ASRCS:$(ASMEXT)=$(OBJEXT))
      +ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
      +AOBJS = $(ASRCS:$(ASMEXT)=$(OBJEXT))
       
       # C sources and objects
       
      -CSRCS		= $(CHIP_CSRCS) $(CMN_CSRCS)
      -COBJS		= $(CSRCS:.c=$(OBJEXT))
      +CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
      +COBJS = $(CSRCS:.c=$(OBJEXT))
       
       # All sources and objcts
       
      -SRCS		= $(ASRCS) $(CSRCS)
      -OBJS		= $(AOBJS) $(COBJS)
      +SRCS = $(ASRCS) $(CSRCS)
      +OBJS = $(AOBJS) $(COBJS)
       
       # Sources that can have dependencies (no .asm files)
       
      -DEPSRCS		= $(CSRCS)
      +DEPSRCS = $(CSRCS)
       
       # Directories
       
      -ARCH_SRCDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src
      -BOARDDIR	= $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
      +BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
       
      -VPATH		= chip:common:board
      +VPATH = chip:common:board
       
       # Libraries
       
      -LIBGCC		= ${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}
      +LIBGCC = ${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}
       
       # Supports dynamic sizing of HEAP.
       #
      -HEAP_BASE	= ${shell ./mkhpbase.sh}
      +HEAP_BASE = ${shell ./mkhpbase.sh}
       
       ############################################################################
       # Targets
      @@ -152,7 +152,7 @@ pass1.hex: up_mem.h asm_mem.h $(SDCCLIBDIR)/myz80.lib $(HEAD_OBJ) board/libboard
       	@echo "-k $(SDCCLIBDIR)" >>pass1.lnk		# Path to SDCC z80 library
       	@echo "-l libboard$(LIBEXT)" >>pass1.lnk	# Name of board library
       	@for LIB in $(LINKLIBS); do \
      -		echo "-l $(TOPDIR)/$$LIB" >> pass1.lnk ;\
      +		echo "-l $(TOPDIR)/lib/$$LIB" >> pass1.lnk ;\
       	done
       	@echo "-l myz80.lib" >>pass1.lnk		# Name of SDCC z80 library
       ifneq ($(CONFIG_LINKER_START_AREA),)
      @@ -185,7 +185,7 @@ nuttx.hex: up_mem.h asm_mem.h $(SDCCLIBDIR)/myz80.lib $(HEAD_OBJ) board/libboard
       	@echo "-k $(SDCCLIBDIR)" >>nuttx.lnk		# Path to SDCC z80 library
       	@echo "-l libboard$(LIBEXT)" >>nuttx.lnk	# Name of board library
       	@for LIB in $(LINKLIBS); do \
      -		echo "-l $(TOPDIR)/$$LIB" >> nuttx.lnk ;\
      +		echo "-l $(TOPDIR)/lib/$$LIB" >> nuttx.lnk ;\
       	done
       	@echo "-l myz80.lib" >>nuttx.lnk		# Name of SDCC z80 library
       ifneq ($(CONFIG_LINKER_START_AREA),)
      diff --git a/nuttx/configs/ea3131/locked/Makefile b/nuttx/configs/ea3131/locked/Makefile
      index 79fa82610c..163bebf252 100644
      --- a/nuttx/configs/ea3131/locked/Makefile
      +++ b/nuttx/configs/ea3131/locked/Makefile
      @@ -38,42 +38,42 @@
       
       # Board-specific directory, board library, and application library
       
      -PASS1_SRCDIR	= arch/$(CONFIG_ARCH)/src
      -PASS1_BOARDDIR	= $(PASS1_SRCDIR)/board
      -PASS1_LIBBOARD	= $(PASS1_BOARDDIR)/libboard$(LIBEXT)
      +PASS1_SRCDIR = arch/$(CONFIG_ARCH)/src
      +PASS1_BOARDDIR = $(PASS1_SRCDIR)/board
      +PASS1_LIBBOARD = $(PASS1_BOARDDIR)/libboard$(LIBEXT)
       
       # Where is the application library?
       
       ifneq ($(CONFIG_APPS_DIR),)
      -PASS1_LIBAPPS	= $(CONFIG_APPS_DIR)/libapps$(LIBEXT)
      +PASS1_LIBAPPS = $(CONFIG_APPS_DIR)/libapps$(LIBEXT)
       else
       ifneq ($(APPDIR),)
      -PASS1_LIBAPPS	= $(APPDIR)/libapps$(LIBEXT)
      +PASS1_LIBAPPS = $(APPDIR)/libapps$(LIBEXT)
       endif
       endif
       
       # Remove the application library (libapps) from the list of libraries.  Add
       # the boad library (liboard)
       
      -PASS1_LINKLIBS	= $(filter-out $(PASS1_LIBAPPS),$(LINKLIBS))
      -PASS1_LINKLIBS	+= $(PASS1_LIBBOARD)
      +PASS1_LINKLIBS = $(filter-out $(PASS1_LIBAPPS),$(LINKLIBS))
      +PASS1_LINKLIBS += $(PASS1_LIBBOARD)
       
       # Get the paths to the libraries and the links script path in format that
       # is appropriate for the host OS
       
       ifeq ($(WINTOOL),y)
         # Windows-native toolchains
      -  PASS1_LIBPATHS	= ${shell for path in $(PASS1_LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done}
      -  PASS1_LDSCRIPT	= -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/locked/ld-locked.inc}"
      +  PASS1_LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +  PASS1_LDSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/locked/ld-locked.inc}"
       else
         # Linux/Cygwin-native toolchain 
      -  PASS1_LIBPATHS	= $(addprefix -L$(TOPDIR)/,$(dir $(PASS1_LINKLIBS)))
      -  PASS1_LDSCRIPT	= -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/locked/ld-locked.inc
      +  PASS1_LIBPATHS += -L"(TOPDIR)/lib"
      +  PASS1_LDSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/locked/ld-locked.inc
       endif
       
      -PASS1_LDFLAGS	= -r $(PASS1_LDSCRIPT)
      -PASS1_LDLIBS	= $(patsubst lib%,-l%,$(basename $(notdir $(PASS1_LINKLIBS))))
      -PASS1_LIBGCC	= "${shell $(CC) -print-libgcc-file-name}"
      +PASS1_LDFLAGS = -r $(PASS1_LDSCRIPT)
      +PASS1_LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(PASS1_LINKLIBS)))
      +PASS1_LIBGCC = "${shell $(CC) -print-libgcc-file-name}"
       
       # Targets:
       
      
      From a2926f6d12baf162176b782e4559361c589f5844 Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sun, 11 Nov 2012 14:36:01 +0000
      Subject: [PATCH 103/206] Remove bash fragments that test for board/Makefile
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5334 42af7a65-404d-4744-a932-0658087f49c3
      ---
       nuttx/ChangeLog              |  1 +
       nuttx/arch/arm/src/Makefile  | 37 +++++++++++++++++-------
       nuttx/arch/avr/src/Makefile  | 53 ++++++++++++++++++++++------------
       nuttx/arch/hc/src/Makefile   | 56 ++++++++++++++++++++++--------------
       nuttx/arch/mips/src/Makefile | 54 +++++++++++++++++++++-------------
       nuttx/arch/sh/src/Makefile   | 54 +++++++++++++++++++++-------------
       nuttx/arch/x86/src/Makefile  | 54 +++++++++++++++++++++-------------
       7 files changed, 198 insertions(+), 111 deletions(-)
      
      diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
      index e4193db20c..b48fbfd962 100644
      --- a/nuttx/ChangeLog
      +++ b/nuttx/ChangeLog
      @@ -3602,4 +3602,5 @@
       	  now that logic generate multiple library paths, all pointing to the lib/
       	  directory.
       	* arch/*/src/Makefile:  Now uses only the libraries in lib/
      +	  Replace bash fragments that test for board/Makefile.
       
      diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile
      index 49fabb7087..8505ec2be0 100644
      --- a/nuttx/arch/arm/src/Makefile
      +++ b/nuttx/arch/arm/src/Makefile
      @@ -33,6 +33,7 @@
       #
       ############################################################################
       
      +-include $(TOPDIR)/.config
       -include $(TOPDIR)/Make.defs
       -include chip/Make.defs
       
      @@ -76,18 +77,32 @@ EXTRA_LIBS ?=
       EXTRA_LIBPATHS ?=
       LINKLIBS ?=
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      +ifneq ($(BOARDDIR),)
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
      +else
      +  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
       else
         LIBPATHS += -L"(TOPDIR)/lib"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"$(BOARDDIR)"
       endif
      +endif
      +endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      -
       LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       GCC_LIBDIR := ${shell dirname $(LIBGCC)}
       
      @@ -137,9 +152,9 @@ endif
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -	$(Q) if [ -e board/Makefile ]; then \
      -	$(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
      -	fi
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
      +endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
       	 $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
      @@ -147,16 +162,16 @@ endif
       depend: .depend
       
       clean:
      -	$(Q) if [ -e board/Makefile ]; then \
      -	$(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \
      -	fi
      +ifneq ($(BOARDDIR),)
      +	$(MAKE) -C board TOPDIR="$(TOPDIR)" clean
      +endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	$(Q) if [ -e board/Makefile ]; then \
      -	$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \
      -	fi
      +ifneq ($(BOARDDIR),)
      +	$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
      +endif
       	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile
      index 160ae63179..5504c71aa9 100644
      --- a/nuttx/arch/avr/src/Makefile
      +++ b/nuttx/arch/avr/src/Makefile
      @@ -78,17 +78,32 @@ LDFLAGS += $(ARCHSCRIPT)
       EXTRA_LIBS ?=
       LINKLIBS ?=
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      +ifneq ($(BOARDDIR),)
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
      +else
      +  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
       else
         LIBPATHS += -L"(TOPDIR)/lib"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"$(BOARDDIR)"
       endif
      +endif
      +endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
       
       LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
      @@ -105,25 +120,25 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      +	$(Q) ( for obj in $(OBJS) ; do \
       		$(call ARCHIVE, $@, $${obj}); \
       	done ; )
       
       board/libboard$(LIBEXT):
      -	@$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
       
       nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx"
      -	@$(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
      +	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
       		--start-group $(LDLIBS) -lboard  $(EXTRA_LIBS) $(LIBGCC) --end-group
      -	@$(NM) $(NUTTX)$(EXEEXT) | \
      +	$(Q) $(NM) $(NUTTX)$(EXEEXT) | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
       
       # This is part of the top-level export target
       
       export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
      -	@if [ -d "$(EXPORT_DIR)/startup" ]; then \
      +	$(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \
       		cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \
       	 else \
       		echo "$(EXPORT_DIR)/startup does not exist"; \
      @@ -133,27 +148,27 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
      -	fi
      -	@$(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
      +endif
      +	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
       	 $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \
      -	fi
      -	@rm -f libarch$(LIBEXT) *~ .*.swp
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
      +endif
      +	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \
      -	fi
      -	@rm -f Make.dep .depend
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
      +endif
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
       
      diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile
      index b2058466ca..b69f366a03 100644
      --- a/nuttx/arch/hc/src/Makefile
      +++ b/nuttx/arch/hc/src/Makefile
      @@ -71,18 +71,32 @@ LDFLAGS += $(ARCHSCRIPT)
       EXTRA_LIBS ?=
       LINKLIBS ?=
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      +ifneq ($(BOARDDIR),)
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
      +else
      +  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
       else
         LIBPATHS += -L"(TOPDIR)/lib"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"$(BOARDDIR)"
       endif
      +endif
      +endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      -
       LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
       VPATH = chip:common:$(ARCH_SUBDIR)
      @@ -97,25 +111,25 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      +	$(Q) ( for obj in $(OBJS) ; do \
       		$(call ARCHIVE, $@, $${obj}); \
       	done ; )
       
       board/libboard$(LIBEXT):
      -	@$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
       
       nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
      -	@echo "LD: nuttx"
      -	@$(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) \
      +	$(Q) echo "LD: nuttx"
      +	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) \
       		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
      -	@$(NM) $(NUTTX)$(EXEEXT) | \
      +	$(Q) $(NM) $(NUTTX)$(EXEEXT) | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
       
       # This is part of the top-level export target
       
       export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
      -	@if [ -d "$(EXPORT_DIR)/startup" ]; then \
      +	$(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \
       		cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \
       	 else \
       		echo "$(EXPORT_DIR)/startup does not exist"; \
      @@ -125,26 +139,26 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
      -	fi
      -	@$(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
      +endif
      +	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
       	 $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \
      -	fi
      -	@rm -f libarch$(LIBEXT) *~ .*.swp
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
      +endif
      +	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \
      -	fi
      -	@rm -f Make.dep .depend
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
      +endif
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile
      index c9019febdc..32e760b0f7 100644
      --- a/nuttx/arch/mips/src/Makefile
      +++ b/nuttx/arch/mips/src/Makefile
      @@ -68,18 +68,32 @@ LDFLAGS += $(ARCHSCRIPT)
       EXTRA_LIBS ?=
       LINKLIBS ?=
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      +ifneq ($(BOARDDIR),)
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
      +else
      +  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
       else
         LIBPATHS += -L"(TOPDIR)/lib"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"$(BOARDDIR)"
       endif
      +endif
      +endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      -
       LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
       VPATH = chip:common:$(ARCH_SUBDIR)
      @@ -95,25 +109,25 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      +	$(Q) ( for obj in $(OBJS) ; do \
       		$(call ARCHIVE, $@, $${obj}); \
       	done ; )
       
       board/libboard$(LIBEXT):
      -	@$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
       
       nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx"
      -	@$(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
      +	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
       		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
      -	@$(NM) $(NUTTX)$(EXEEXT) | \
      +	$(Q) $(NM) $(NUTTX)$(EXEEXT) | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
       
       # This is part of the top-level export target
       
       export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
      -	@if [ -d "$(EXPORT_DIR)/startup" ]; then \
      +	$(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \
       		cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \
       	 else \
       		echo "$(EXPORT_DIR)/startup does not exist"; \
      @@ -123,26 +137,26 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
      -	fi
      -	@$(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
      +endif
      +	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
       	 $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \
      -	fi
      -	@rm -f libarch$(LIBEXT) *~ .*.swp
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
      +endif
      +	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \
      -	fi
      -	@rm -f Make.dep .depend
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
      +endif
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile
      index 2cb22728ef..164b1fee42 100644
      --- a/nuttx/arch/sh/src/Makefile
      +++ b/nuttx/arch/sh/src/Makefile
      @@ -54,18 +54,32 @@ LDFLAGS += $(ARCHSCRIPT)
       EXTRA_LIBS ?=
       LINKLIBS ?=
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      +ifneq ($(BOARDDIR),)
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
      +else
      +  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
       else
         LIBPATHS += -L"(TOPDIR)/lib"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"$(BOARDDIR)"
       endif
      +endif
      +endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      -
       LIBGCC = ${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}
       
       VPATH = chip:common
      @@ -81,25 +95,25 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      +	$(Q) ( for obj in $(OBJS) ; do \
       		$(call ARCHIVE, $@, $${obj}); \
       	done ; )
       
       board/libboard$(LIBEXT):
      -	@$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
       
       nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx"
      -	@$(LD) --entry=__start $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) -o $(TOPDIR)/$@ $(HEAD_OBJ) \
      +	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) -o $(TOPDIR)/$@ $(HEAD_OBJ) \
       		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
      -	@$(NM) $(TOPDIR)/$@ | \
      +	$(Q) $(NM) $(TOPDIR)/$@ | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
       
       # This is part of the top-level export target
       
       export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
      -	@if [ -d "$(EXPORT_DIR)/startup" ]; then \
      +	$(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \
       		cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \
       	 else \
       		echo "$(EXPORT_DIR)/startup does not exist"; \
      @@ -109,25 +123,25 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
      -	fi
      -	@$(MKDEP) --dep-path chip --dep-path common $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
      +endif
      +	$(Q) $(MKDEP) --dep-path chip --dep-path common $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \
      -	fi
      -	@rm -f libarch$(LIBEXT) *~ .*.swp
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
      +endif
      +	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \
      -	fi
      -	@rm -f Make.dep .depend
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
      +endif
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile
      index b4aa02fb15..56ba0b257a 100644
      --- a/nuttx/arch/x86/src/Makefile
      +++ b/nuttx/arch/x86/src/Makefile
      @@ -68,18 +68,32 @@ LDFLAGS += $(ARCHSCRIPT)
       EXTRA_LIBS ?=
       LINKLIBS ?=
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      +ifneq ($(BOARDDIR),)
      +  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
      +else
      +  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +endif
      +
       else
         LIBPATHS += -L"(TOPDIR)/lib"
      +ifneq ($(BOARDDIR),)
         LIBPATHS += -L"$(BOARDDIR)"
       endif
      +endif
      +endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      -
       LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
       ifeq ($(HOSTOS),FreeBSD)
      @@ -103,25 +117,25 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      +	$(Q) ( for obj in $(OBJS) ; do \
       		$(call ARCHIVE, $@, $${obj}); \
       	done ; )
       
       board/libboard$(LIBEXT):
      -	@$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
       
       nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx$(EXEEXT)"
      -	@$(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
      +	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
       		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
      -	@$(NM) $(NUTTX)$(EXEEXT) | \
      +	$(Q) $(NM) $(NUTTX)$(EXEEXT) | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
       
       # This is part of the top-level export target
       
       export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
      -	@if [ -d "$(EXPORT_DIR)/startup" ]; then \
      +	$(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \
       		cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \
       	 else \
       		echo "$(EXPORT_DIR)/startup does not exist"; \
      @@ -131,26 +145,26 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
      -	fi
      -	@$(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
      +endif
      +	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
       	 $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \
      -	fi
      -	@rm -f libarch$(LIBEXT) *~ .*.swp
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
      +endif
      +	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@if [ -e board/Makefile ]; then \
      -		$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \
      -	fi
      -	@rm -f Make.dep .depend
      +ifneq ($(BOARDDIR),)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
      +endif
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      
      From a18d038b814eb0e7abb74ed2ea5a700304919240 Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sun, 11 Nov 2012 15:42:12 +0000
      Subject: [PATCH 104/206] Partial change: Removing bash ARCHIVE loop
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5335 42af7a65-404d-4744-a932-0658087f49c3
      ---
       nuttx/arch/8051/src/Makefile                   |  4 +---
       nuttx/arch/arm/src/Makefile                    |  4 +---
       nuttx/arch/avr/src/Makefile                    |  4 +---
       nuttx/arch/hc/src/Makefile                     |  4 +---
       nuttx/arch/mips/src/Makefile                   |  4 +---
       nuttx/arch/rgmp/src/Makefile                   |  5 ++---
       nuttx/arch/sh/src/Makefile                     |  4 +---
       nuttx/arch/sim/src/Makefile                    |  4 +---
       nuttx/arch/x86/src/Makefile                    |  4 +---
       nuttx/arch/z16/src/Makefile                    |  4 +---
       nuttx/arch/z80/src/Makefile.sdcc               |  4 +---
       nuttx/arch/z80/src/Makefile.zdsii              |  4 +---
       nuttx/binfmt/Makefile                          |  4 +---
       nuttx/configs/amber/src/Makefile               |  6 ++----
       nuttx/configs/avr32dev1/src/Makefile           |  4 +---
       nuttx/configs/c5471evm/src/Makefile            |  4 +---
       nuttx/configs/compal_e88/src/Makefile          |  4 +---
       nuttx/configs/compal_e99/src/Makefile          |  4 +---
       nuttx/configs/demo9s12ne64/src/Makefile        |  4 +---
       nuttx/configs/ea3131/src/Makefile              |  4 +---
       nuttx/configs/ea3152/src/Makefile              |  4 +---
       nuttx/configs/eagle100/src/Makefile            |  4 +---
       nuttx/configs/ekk-lm3s9b96/src/Makefile        |  4 +---
       nuttx/configs/ez80f910200kitg/src/Makefile     |  6 ++----
       nuttx/configs/ez80f910200zco/src/Makefile      |  4 +---
       nuttx/configs/fire-stm32v2/src/Makefile        |  4 +---
       nuttx/configs/hymini-stm32v/src/Makefile       |  4 +---
       nuttx/configs/kwikstik-k40/src/Makefile        |  6 ++----
       nuttx/configs/lincoln60/src/Makefile           |  6 ++----
       nuttx/configs/lm3s6432-s2e/src/Makefile        |  6 ++----
       nuttx/configs/lm3s6965-ek/src/Makefile         |  6 ++----
       nuttx/configs/lm3s8962-ek/src/Makefile         |  6 ++----
       nuttx/configs/lpc4330-xplorer/src/Makefile     |  4 +---
       nuttx/configs/lpcxpresso-lpc1768/src/Makefile  |  6 ++----
       nuttx/configs/m68332evb/src/Makefile           |  6 ++----
       nuttx/configs/mbed/src/Makefile                |  6 ++----
       nuttx/configs/mcu123-lpc214x/src/Makefile      |  4 +---
       nuttx/configs/micropendous3/src/Makefile       |  6 ++----
       nuttx/configs/mirtoo/src/Makefile              |  4 +---
       nuttx/configs/mx1ads/src/Makefile              |  8 +++-----
       nuttx/configs/ne64badge/src/Makefile           |  6 ++----
       nuttx/configs/ntosd-dm320/src/Makefile         |  4 +---
       nuttx/configs/nucleus2g/src/Makefile           |  6 ++----
       nuttx/configs/olimex-lpc1766stk/src/Makefile   |  4 +---
       nuttx/configs/olimex-lpc2378/src/Makefile      |  6 ++----
       nuttx/configs/olimex-stm32-p107/src/Makefile   |  4 +---
       nuttx/configs/olimex-strp711/src/Makefile      |  4 +---
       nuttx/configs/pcblogic-pic32mx/src/Makefile    |  6 ++----
       nuttx/configs/pic32-starterkit/src/Makefile    |  6 ++----
       nuttx/configs/pic32mx7mmb/src/Makefile         |  4 +---
       nuttx/configs/pjrc-8051/src/Makefile           |  6 ++----
       nuttx/configs/qemu-i486/src/Makefile           |  6 ++----
       nuttx/configs/sam3u-ek/src/Makefile            |  6 ++----
       nuttx/configs/shenzhou/src/Makefile            |  4 +---
       nuttx/configs/sim/src/Makefile                 |  6 ++----
       nuttx/configs/skp16c26/src/Makefile            |  6 ++----
       nuttx/configs/stm3210e-eval/src/Makefile       |  4 +---
       nuttx/configs/stm3220g-eval/src/Makefile       |  4 +---
       nuttx/configs/stm3240g-eval/src/Makefile       |  4 +---
       nuttx/configs/stm32f100rc_generic/src/Makefile |  4 +---
       nuttx/configs/stm32f4discovery/src/Makefile    |  4 +---
       nuttx/configs/sure-pic32mx/src/Makefile        |  4 +---
       nuttx/configs/teensy/src/Makefile              |  4 +---
       nuttx/configs/twr-k60n512/src/Makefile         |  6 ++----
       nuttx/configs/ubw32/src/Makefile               |  4 +---
       nuttx/configs/us7032evb1/src/Makefile          |  6 ++----
       nuttx/configs/vsn/src/Makefile                 |  6 ++----
       nuttx/configs/xtrs/src/Makefile                |  6 ++----
       nuttx/configs/z16f2800100zcog/src/Makefile     |  6 ++----
       nuttx/configs/z80sim/src/Makefile              |  6 ++----
       nuttx/configs/z8encore000zco/src/Makefile      |  6 ++----
       nuttx/configs/z8f64200100kit/src/Makefile      |  6 ++----
       nuttx/drivers/Makefile                         |  4 +---
       nuttx/fs/Makefile                              |  4 +---
       nuttx/graphics/Makefile                        |  4 +---
       nuttx/libc/Makefile                            |  4 +---
       nuttx/libxx/Makefile                           |  6 ++----
       nuttx/mm/Makefile                              |  4 +---
       nuttx/net/Makefile                             |  4 +---
       nuttx/sched/Makefile                           |  4 +---
       nuttx/syscall/Makefile                         | 10 +++-------
       81 files changed, 116 insertions(+), 279 deletions(-)
      
      diff --git a/nuttx/arch/8051/src/Makefile b/nuttx/arch/8051/src/Makefile
      index 54a3ce79bc..29204b1ee5 100644
      --- a/nuttx/arch/8051/src/Makefile
      +++ b/nuttx/arch/8051/src/Makefile
      @@ -148,9 +148,7 @@ up_mem.h: pass1.mem
       # Combine all objects in this directory into a library
       
       libarch$(LIBEXT): up_mem.h $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       # This is a kludge to work around some conflicting symbols in libsdcc.liXqueb
       
      diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile
      index 8505ec2be0..1f470a25d7 100644
      --- a/nuttx/arch/arm/src/Makefile
      +++ b/nuttx/arch/arm/src/Makefile
      @@ -119,9 +119,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	$(Q) ( for obj in $(OBJS) ; do \
      -	$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       board/libboard$(LIBEXT):
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile
      index 5504c71aa9..866d06e6fa 100644
      --- a/nuttx/arch/avr/src/Makefile
      +++ b/nuttx/arch/avr/src/Makefile
      @@ -120,9 +120,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	$(Q) ( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       board/libboard$(LIBEXT):
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile
      index b69f366a03..c6197f47cd 100644
      --- a/nuttx/arch/hc/src/Makefile
      +++ b/nuttx/arch/hc/src/Makefile
      @@ -111,9 +111,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	$(Q) ( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       board/libboard$(LIBEXT):
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile
      index 32e760b0f7..27c6780360 100644
      --- a/nuttx/arch/mips/src/Makefile
      +++ b/nuttx/arch/mips/src/Makefile
      @@ -109,9 +109,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	$(Q) ( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       board/libboard$(LIBEXT):
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      diff --git a/nuttx/arch/rgmp/src/Makefile b/nuttx/arch/rgmp/src/Makefile
      index 3989ab102c..e1bfb84c1b 100644
      --- a/nuttx/arch/rgmp/src/Makefile
      +++ b/nuttx/arch/rgmp/src/Makefile
      @@ -68,10 +68,9 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       # The architecture-specific library
      +
       libarch$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       # Generate the final NuttX binary by linking the host-specific objects with the NuttX
       # specific objects (with munged names)
      diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile
      index 164b1fee42..6e6ee5d640 100644
      --- a/nuttx/arch/sh/src/Makefile
      +++ b/nuttx/arch/sh/src/Makefile
      @@ -95,9 +95,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	$(Q) ( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       board/libboard$(LIBEXT):
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile
      index 3719465b37..8cccd0799f 100644
      --- a/nuttx/arch/sim/src/Makefile
      +++ b/nuttx/arch/sim/src/Makefile
      @@ -155,9 +155,7 @@ $(HOSTOBJS): %$(OBJEXT): %.c
       # The architecture-specific library
       
       libarch$(LIBEXT): $(NUTTXOBJS)
      -	$(Q) ( for obj in $(NUTTXOBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(NUTTXOBJS)")
       
       # The "board"-specific library. Of course, there really are no boards in
       # the simulation.  However, this is a good place to keep parts of the simulation
      diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile
      index 56ba0b257a..11bd3091dd 100644
      --- a/nuttx/arch/x86/src/Makefile
      +++ b/nuttx/arch/x86/src/Makefile
      @@ -117,9 +117,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	$(Q) ( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       board/libboard$(LIBEXT):
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      diff --git a/nuttx/arch/z16/src/Makefile b/nuttx/arch/z16/src/Makefile
      index 3da8c2d676..9223a0464e 100644
      --- a/nuttx/arch/z16/src/Makefile
      +++ b/nuttx/arch/z16/src/Makefile
      @@ -90,9 +90,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       board/libboard$(LIBEXT):
       	@$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      diff --git a/nuttx/arch/z80/src/Makefile.sdcc b/nuttx/arch/z80/src/Makefile.sdcc
      index 32169d4420..815c52a716 100644
      --- a/nuttx/arch/z80/src/Makefile.sdcc
      +++ b/nuttx/arch/z80/src/Makefile.sdcc
      @@ -134,9 +134,7 @@ endif
       # Combine all objects in this directory into a library
       
       libarch$(LIBEXT): up_mem.h asm_mem.h $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       # This builds the libboard library in the board/ subdirectory 
       
      diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii
      index e749bddd32..031d4fe3da 100644
      --- a/nuttx/arch/z80/src/Makefile.zdsii
      +++ b/nuttx/arch/z80/src/Makefile.zdsii
      @@ -86,9 +86,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libarch$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       board/libboard$(LIBEXT):
       	@$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile
      index 4724abeff0..caf57e62fe 100644
      --- a/nuttx/binfmt/Makefile
      +++ b/nuttx/binfmt/Makefile
      @@ -78,9 +78,7 @@ $(BINFMT_COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       $(BIN): $(BINFMT_OBJS)
      -	@( for obj in $(BINFMT_OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(BINFMT_OBJS)")
       
       .depend: Makefile $(BINFMT_SRCS)
       	@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep
      diff --git a/nuttx/configs/amber/src/Makefile b/nuttx/configs/amber/src/Makefile
      index 7b30e6ff6e..358e4dec33 100644
      --- a/nuttx/configs/amber/src/Makefile
      +++ b/nuttx/configs/amber/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/amber/src/Makefile
       #
      -#   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
      @@ -77,9 +77,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/avr32dev1/src/Makefile b/nuttx/configs/avr32dev1/src/Makefile
      index e49d457925..b997d7a444 100644
      --- a/nuttx/configs/avr32dev1/src/Makefile
      +++ b/nuttx/configs/avr32dev1/src/Makefile
      @@ -70,9 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/c5471evm/src/Makefile b/nuttx/configs/c5471evm/src/Makefile
      index 57f52b4fee..284bfb91d7 100644
      --- a/nuttx/configs/c5471evm/src/Makefile
      +++ b/nuttx/configs/c5471evm/src/Makefile
      @@ -57,9 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/compal_e88/src/Makefile b/nuttx/configs/compal_e88/src/Makefile
      index 13e1ae09f2..e60d599d9e 100644
      --- a/nuttx/configs/compal_e88/src/Makefile
      +++ b/nuttx/configs/compal_e88/src/Makefile
      @@ -60,9 +60,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/compal_e99/src/Makefile b/nuttx/configs/compal_e99/src/Makefile
      index 2a5ad6783e..adaf8b801d 100644
      --- a/nuttx/configs/compal_e99/src/Makefile
      +++ b/nuttx/configs/compal_e99/src/Makefile
      @@ -60,9 +60,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/demo9s12ne64/src/Makefile b/nuttx/configs/demo9s12ne64/src/Makefile
      index 7ab12080cc..e9fcd7f41f 100644
      --- a/nuttx/configs/demo9s12ne64/src/Makefile
      +++ b/nuttx/configs/demo9s12ne64/src/Makefile
      @@ -66,9 +66,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/ea3131/src/Makefile b/nuttx/configs/ea3131/src/Makefile
      index c3774db711..57011f08a7 100644
      --- a/nuttx/configs/ea3131/src/Makefile
      +++ b/nuttx/configs/ea3131/src/Makefile
      @@ -85,9 +85,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/ea3152/src/Makefile b/nuttx/configs/ea3152/src/Makefile
      index 91a7fe3792..088ce63d8f 100644
      --- a/nuttx/configs/ea3152/src/Makefile
      +++ b/nuttx/configs/ea3152/src/Makefile
      @@ -85,9 +85,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/eagle100/src/Makefile b/nuttx/configs/eagle100/src/Makefile
      index 123aa81398..c2b1437eee 100644
      --- a/nuttx/configs/eagle100/src/Makefile
      +++ b/nuttx/configs/eagle100/src/Makefile
      @@ -66,9 +66,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/ekk-lm3s9b96/src/Makefile b/nuttx/configs/ekk-lm3s9b96/src/Makefile
      index 3a364cd26f..a5e4f197f4 100644
      --- a/nuttx/configs/ekk-lm3s9b96/src/Makefile
      +++ b/nuttx/configs/ekk-lm3s9b96/src/Makefile
      @@ -68,9 +68,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/ez80f910200kitg/src/Makefile b/nuttx/configs/ez80f910200kitg/src/Makefile
      index a1f0f6035f..34ac4ba9cc 100644
      --- a/nuttx/configs/ez80f910200kitg/src/Makefile
      +++ b/nuttx/configs/ez80f910200kitg/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/ez80f910200kitg/Makefile
       #
      -#   Copyright (C) 2008 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -64,9 +64,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/ez80f910200zco/src/Makefile b/nuttx/configs/ez80f910200zco/src/Makefile
      index 994bb68a67..fcafd6177c 100644
      --- a/nuttx/configs/ez80f910200zco/src/Makefile
      +++ b/nuttx/configs/ez80f910200zco/src/Makefile
      @@ -71,9 +71,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/fire-stm32v2/src/Makefile b/nuttx/configs/fire-stm32v2/src/Makefile
      index d605a8f3bf..2045de7934 100644
      --- a/nuttx/configs/fire-stm32v2/src/Makefile
      +++ b/nuttx/configs/fire-stm32v2/src/Makefile
      @@ -107,9 +107,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/hymini-stm32v/src/Makefile b/nuttx/configs/hymini-stm32v/src/Makefile
      index fcfb670da8..54d0f9339e 100644
      --- a/nuttx/configs/hymini-stm32v/src/Makefile
      +++ b/nuttx/configs/hymini-stm32v/src/Makefile
      @@ -86,9 +86,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/kwikstik-k40/src/Makefile b/nuttx/configs/kwikstik-k40/src/Makefile
      index ae935f6d91..d8373e1ab1 100644
      --- a/nuttx/configs/kwikstik-k40/src/Makefile
      +++ b/nuttx/configs/kwikstik-k40/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/kwikstik-k40/src/Makefile
       #
      -#   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
      @@ -85,9 +85,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/lincoln60/src/Makefile b/nuttx/configs/lincoln60/src/Makefile
      index 1bc1f2fdf9..3820e5cd50 100644
      --- a/nuttx/configs/lincoln60/src/Makefile
      +++ b/nuttx/configs/lincoln60/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/lincoln60/src/Makefile
       #
      -#   Copyright (C) 20102Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -76,9 +76,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/lm3s6432-s2e/src/Makefile b/nuttx/configs/lm3s6432-s2e/src/Makefile
      index eefaa50394..c1290f6c24 100644
      --- a/nuttx/configs/lm3s6432-s2e/src/Makefile
      +++ b/nuttx/configs/lm3s6432-s2e/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/lm3s6432-s2e/src/Makefile
       #
      -#   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
      @@ -67,9 +67,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/lm3s6965-ek/src/Makefile b/nuttx/configs/lm3s6965-ek/src/Makefile
      index 90833fc319..2e560c0044 100644
      --- a/nuttx/configs/lm3s6965-ek/src/Makefile
      +++ b/nuttx/configs/lm3s6965-ek/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/lm3s6965-ek/src/Makefile
       #
      -#   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
      @@ -70,9 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/lm3s8962-ek/src/Makefile b/nuttx/configs/lm3s8962-ek/src/Makefile
      index 2d44db56c9..eaf5eeae19 100644
      --- a/nuttx/configs/lm3s8962-ek/src/Makefile
      +++ b/nuttx/configs/lm3s8962-ek/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/lm3s8962-ek/src/Makefile
       #
      -#   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
      @@ -70,9 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/lpc4330-xplorer/src/Makefile b/nuttx/configs/lpc4330-xplorer/src/Makefile
      index 30e429bceb..d4f4d6686a 100644
      --- a/nuttx/configs/lpc4330-xplorer/src/Makefile
      +++ b/nuttx/configs/lpc4330-xplorer/src/Makefile
      @@ -104,9 +104,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile
      index 7384b04d47..51aa1a7ca7 100644
      --- a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile
      +++ b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/lpcxpresso-lpc1768/src/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/m68332evb/src/Makefile b/nuttx/configs/m68332evb/src/Makefile
      index f510c22190..0644837339 100644
      --- a/nuttx/configs/m68332evb/src/Makefile
      +++ b/nuttx/configs/m68332evb/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/m68332evb/src/Makefile
       #
      -#   Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2007-2008, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -54,9 +54,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/mbed/src/Makefile b/nuttx/configs/mbed/src/Makefile
      index a29ddca868..9d2d489fec 100644
      --- a/nuttx/configs/mbed/src/Makefile
      +++ b/nuttx/configs/mbed/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/mbed/src/Makefile
       #
      -#   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
      @@ -70,9 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/mcu123-lpc214x/src/Makefile b/nuttx/configs/mcu123-lpc214x/src/Makefile
      index 21838bf39a..26c2c14483 100644
      --- a/nuttx/configs/mcu123-lpc214x/src/Makefile
      +++ b/nuttx/configs/mcu123-lpc214x/src/Makefile
      @@ -77,9 +77,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/micropendous3/src/Makefile b/nuttx/configs/micropendous3/src/Makefile
      index ff1c872f09..c926415f5e 100644
      --- a/nuttx/configs/micropendous3/src/Makefile
      +++ b/nuttx/configs/micropendous3/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/micropendous3/src/Makefile
       #
      -#   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
      @@ -77,9 +77,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/mirtoo/src/Makefile b/nuttx/configs/mirtoo/src/Makefile
      index bc2ca08053..29b91f4699 100644
      --- a/nuttx/configs/mirtoo/src/Makefile
      +++ b/nuttx/configs/mirtoo/src/Makefile
      @@ -76,9 +76,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/mx1ads/src/Makefile b/nuttx/configs/mx1ads/src/Makefile
      index 4a2c02ef1a..9e4d8c99a8 100644
      --- a/nuttx/configs/mx1ads/src/Makefile
      +++ b/nuttx/configs/mx1ads/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/mx1ads/src/Makefile
       #
      -#   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
      @@ -21,7 +21,7 @@
       # 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
      +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THEO
       # 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
      @@ -57,9 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/ne64badge/src/Makefile b/nuttx/configs/ne64badge/src/Makefile
      index 657fedddc1..bfd838bdf7 100644
      --- a/nuttx/configs/ne64badge/src/Makefile
      +++ b/nuttx/configs/ne64badge/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/ne64badge/src/Makefile
       #
      -#   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
      @@ -66,9 +66,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/ntosd-dm320/src/Makefile b/nuttx/configs/ntosd-dm320/src/Makefile
      index 1d0a1e614a..d57d94ce85 100644
      --- a/nuttx/configs/ntosd-dm320/src/Makefile
      +++ b/nuttx/configs/ntosd-dm320/src/Makefile
      @@ -57,9 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/nucleus2g/src/Makefile b/nuttx/configs/nucleus2g/src/Makefile
      index 6e3fc94d2d..bc21b12499 100644
      --- a/nuttx/configs/nucleus2g/src/Makefile
      +++ b/nuttx/configs/nucleus2g/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/nucleus2g/src/Makefile
       #
      -#   Copyright (C) 2010-2011 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
      @@ -70,9 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/olimex-lpc1766stk/src/Makefile b/nuttx/configs/olimex-lpc1766stk/src/Makefile
      index 1d7e049c6e..326fe52e41 100644
      --- a/nuttx/configs/olimex-lpc1766stk/src/Makefile
      +++ b/nuttx/configs/olimex-lpc1766stk/src/Makefile
      @@ -84,9 +84,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/olimex-lpc2378/src/Makefile b/nuttx/configs/olimex-lpc2378/src/Makefile
      index a9fa9fc70f..46ad0e45e5 100644
      --- a/nuttx/configs/olimex-lpc2378/src/Makefile
      +++ b/nuttx/configs/olimex-lpc2378/src/Makefile
      @@ -6,7 +6,7 @@
       #
       # This is part of the NuttX RTOS and based on the LPC2148 port:
       #
      -#   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
      @@ -73,9 +73,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/olimex-stm32-p107/src/Makefile b/nuttx/configs/olimex-stm32-p107/src/Makefile
      index 85a0722f36..7bf68b7613 100644
      --- a/nuttx/configs/olimex-stm32-p107/src/Makefile
      +++ b/nuttx/configs/olimex-stm32-p107/src/Makefile
      @@ -69,9 +69,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/olimex-strp711/src/Makefile b/nuttx/configs/olimex-strp711/src/Makefile
      index 95073eca15..ef6105a5f7 100644
      --- a/nuttx/configs/olimex-strp711/src/Makefile
      +++ b/nuttx/configs/olimex-strp711/src/Makefile
      @@ -70,9 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/pcblogic-pic32mx/src/Makefile b/nuttx/configs/pcblogic-pic32mx/src/Makefile
      index 9ca5c4f57d..d97e4cc26a 100644
      --- a/nuttx/configs/pcblogic-pic32mx/src/Makefile
      +++ b/nuttx/configs/pcblogic-pic32mx/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/pcblogic-pic32mx/src/Makefile
       #
      -#   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
      @@ -68,9 +68,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/pic32-starterkit/src/Makefile b/nuttx/configs/pic32-starterkit/src/Makefile
      index 4c086b2090..5e02f53315 100644
      --- a/nuttx/configs/pic32-starterkit/src/Makefile
      +++ b/nuttx/configs/pic32-starterkit/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/pic32-starterkit/src/Makefile
       #
      -#   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
      @@ -79,9 +79,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/pic32mx7mmb/src/Makefile b/nuttx/configs/pic32mx7mmb/src/Makefile
      index 029c39a494..3c31060fdf 100644
      --- a/nuttx/configs/pic32mx7mmb/src/Makefile
      +++ b/nuttx/configs/pic32mx7mmb/src/Makefile
      @@ -83,9 +83,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/pjrc-8051/src/Makefile b/nuttx/configs/pjrc-8051/src/Makefile
      index 7783ad1fbc..db95dc450f 100644
      --- a/nuttx/configs/pjrc-8051/src/Makefile
      +++ b/nuttx/configs/pjrc-8051/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/pjrc-8051/src/Makefile
       #
      -#   Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -56,9 +56,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/qemu-i486/src/Makefile b/nuttx/configs/qemu-i486/src/Makefile
      index 287e4e7285..1df02f58e3 100644
      --- a/nuttx/configs/qemu-i486/src/Makefile
      +++ b/nuttx/configs/qemu-i486/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/qemu-i486/src/Makefile
       #
      -#   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
      @@ -63,9 +63,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/sam3u-ek/src/Makefile b/nuttx/configs/sam3u-ek/src/Makefile
      index 193be03d02..7d4433e81d 100644
      --- a/nuttx/configs/sam3u-ek/src/Makefile
      +++ b/nuttx/configs/sam3u-ek/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/sam3u-ek/src/Makefile
       #
      -#   Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -76,9 +76,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile
      index 14dcd9fe68..1c1d000f9f 100644
      --- a/nuttx/configs/shenzhou/src/Makefile
      +++ b/nuttx/configs/shenzhou/src/Makefile
      @@ -127,9 +127,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/sim/src/Makefile b/nuttx/configs/sim/src/Makefile
      index 69e2ca9e71..b5c101d29f 100644
      --- a/nuttx/configs/sim/src/Makefile
      +++ b/nuttx/configs/sim/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/sim/src/Makefile
       #
      -#   Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2007, 2008, 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -62,9 +62,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       libboard$(LIBEXT): $(OBJS)
       	@$(AR) $@ # Create an empty archive
       ifneq ($(OBJS),)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       endif
       
       .depend: Makefile $(SRCS)
      diff --git a/nuttx/configs/skp16c26/src/Makefile b/nuttx/configs/skp16c26/src/Makefile
      index 483c244988..64a976ce8f 100644
      --- a/nuttx/configs/skp16c26/src/Makefile
      +++ b/nuttx/configs/skp16c26/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/skp16c26/src/Makefile
       #
      -#   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
      @@ -57,9 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/stm3210e-eval/src/Makefile b/nuttx/configs/stm3210e-eval/src/Makefile
      index 871d01ff15..70bf589be1 100644
      --- a/nuttx/configs/stm3210e-eval/src/Makefile
      +++ b/nuttx/configs/stm3210e-eval/src/Makefile
      @@ -111,9 +111,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/stm3220g-eval/src/Makefile b/nuttx/configs/stm3220g-eval/src/Makefile
      index 0aeb872d66..7fb3910441 100644
      --- a/nuttx/configs/stm3220g-eval/src/Makefile
      +++ b/nuttx/configs/stm3220g-eval/src/Makefile
      @@ -111,9 +111,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/stm3240g-eval/src/Makefile b/nuttx/configs/stm3240g-eval/src/Makefile
      index ffcf719aba..7174fb1bc9 100644
      --- a/nuttx/configs/stm3240g-eval/src/Makefile
      +++ b/nuttx/configs/stm3240g-eval/src/Makefile
      @@ -115,9 +115,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/stm32f100rc_generic/src/Makefile b/nuttx/configs/stm32f100rc_generic/src/Makefile
      index 1624a12239..16d72dd0d8 100644
      --- a/nuttx/configs/stm32f100rc_generic/src/Makefile
      +++ b/nuttx/configs/stm32f100rc_generic/src/Makefile
      @@ -63,9 +63,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/stm32f4discovery/src/Makefile b/nuttx/configs/stm32f4discovery/src/Makefile
      index 1803d30996..2f9a4baefb 100644
      --- a/nuttx/configs/stm32f4discovery/src/Makefile
      +++ b/nuttx/configs/stm32f4discovery/src/Makefile
      @@ -123,9 +123,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/sure-pic32mx/src/Makefile b/nuttx/configs/sure-pic32mx/src/Makefile
      index f5f9a89ea6..28ae67c63b 100644
      --- a/nuttx/configs/sure-pic32mx/src/Makefile
      +++ b/nuttx/configs/sure-pic32mx/src/Makefile
      @@ -88,9 +88,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/teensy/src/Makefile b/nuttx/configs/teensy/src/Makefile
      index 6b68e63bbe..11faf9491b 100644
      --- a/nuttx/configs/teensy/src/Makefile
      +++ b/nuttx/configs/teensy/src/Makefile
      @@ -83,9 +83,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/twr-k60n512/src/Makefile b/nuttx/configs/twr-k60n512/src/Makefile
      index 6e43aa69a4..4737686587 100644
      --- a/nuttx/configs/twr-k60n512/src/Makefile
      +++ b/nuttx/configs/twr-k60n512/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/twr-k60n512/src/Makefile
       #
      -#   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
      @@ -85,9 +85,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/ubw32/src/Makefile b/nuttx/configs/ubw32/src/Makefile
      index d9161f505c..a89ede256d 100644
      --- a/nuttx/configs/ubw32/src/Makefile
      +++ b/nuttx/configs/ubw32/src/Makefile
      @@ -79,9 +79,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/us7032evb1/src/Makefile b/nuttx/configs/us7032evb1/src/Makefile
      index 4ced0ac9ed..7bb51b9b28 100644
      --- a/nuttx/configs/us7032evb1/src/Makefile
      +++ b/nuttx/configs/us7032evb1/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/us7032evb1/src/Makefile
       #
      -#   Copyright (C) 2008 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -57,9 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/vsn/src/Makefile b/nuttx/configs/vsn/src/Makefile
      index fe40db2a71..657f016b25 100644
      --- a/nuttx/configs/vsn/src/Makefile
      +++ b/nuttx/configs/vsn/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/vsn/src/Makefile
       #
      -#   Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
       #   Copyright (c) 2011 Uros Platise. All rights reserved.
       #
       #   Authors: Gregory Nutt 
      @@ -81,9 +81,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       # Register application
       
      diff --git a/nuttx/configs/xtrs/src/Makefile b/nuttx/configs/xtrs/src/Makefile
      index 9b14cf4178..7715fbb0af 100644
      --- a/nuttx/configs/xtrs/src/Makefile
      +++ b/nuttx/configs/xtrs/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/xtrs/src/Makefile
       #
      -#   Copyright (C) 2008 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -57,9 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/z16f2800100zcog/src/Makefile b/nuttx/configs/z16f2800100zcog/src/Makefile
      index b8eedadd4a..2de29d8ce4 100644
      --- a/nuttx/configs/z16f2800100zcog/src/Makefile
      +++ b/nuttx/configs/z16f2800100zcog/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/z16f2800100zcog/Makefile
       #
      -#   Copyright (C) 2008 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -64,9 +64,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/z80sim/src/Makefile b/nuttx/configs/z80sim/src/Makefile
      index 0511d00fe6..65d9db9a48 100644
      --- a/nuttx/configs/z80sim/src/Makefile
      +++ b/nuttx/configs/z80sim/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/z80sim/src/Makefile
       #
      -#   Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -56,9 +56,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/z8encore000zco/src/Makefile b/nuttx/configs/z8encore000zco/src/Makefile
      index ca9de460cf..eee0728502 100644
      --- a/nuttx/configs/z8encore000zco/src/Makefile
      +++ b/nuttx/configs/z8encore000zco/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/z8encore000zco/Makefile
       #
      -#   Copyright (C) 2008 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -64,9 +64,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/configs/z8f64200100kit/src/Makefile b/nuttx/configs/z8f64200100kit/src/Makefile
      index c9c9b36e29..2cd0ed45f3 100644
      --- a/nuttx/configs/z8f64200100kit/src/Makefile
      +++ b/nuttx/configs/z8f64200100kit/src/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/z8f64200100kit/Makefile
       #
      -#   Copyright (C) 2008 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -64,9 +64,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       libboard$(LIBEXT): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
      index 26a2ea9923..53e9cb12c6 100644
      --- a/nuttx/drivers/Makefile
      +++ b/nuttx/drivers/Makefile
      @@ -102,9 +102,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       $(BIN):	$(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile
      index ce952e06f9..cb530cbec3 100644
      --- a/nuttx/fs/Makefile
      +++ b/nuttx/fs/Makefile
      @@ -120,9 +120,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       $(BIN):	$(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) --dep-path . $(MMAPDEPPATH) $(FATDEPPATH) $(ROMFSDEPPATH) $(NXFFSDEPPATH) $(NFSDEPPATH) \
      diff --git a/nuttx/graphics/Makefile b/nuttx/graphics/Makefile
      index 6e549c1dd7..27edbb411b 100644
      --- a/nuttx/graphics/Makefile
      +++ b/nuttx/graphics/Makefile
      @@ -186,9 +186,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       $(BIN): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       mklibgraphics: gensources $(BIN)
       
      diff --git a/nuttx/libc/Makefile b/nuttx/libc/Makefile
      index da582cdae1..9449915552 100644
      --- a/nuttx/libc/Makefile
      +++ b/nuttx/libc/Makefile
      @@ -79,9 +79,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       $(BIN): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       ifneq ($(BIN),$(UBIN))
       .userlib:
      diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile
      index db5675ce76..a69527c28e 100644
      --- a/nuttx/libxx/Makefile
      +++ b/nuttx/libxx/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # libxx/Makefile
       #
      -#   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
      @@ -96,9 +96,7 @@ $(CXXOBJS): %$(OBJEXT): %.cxx
       	$(call COMPILEXX, $<, $@)
       
       $(BIN):	$(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(DEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile
      index 0ccf5a09a9..d0c5048b42 100644
      --- a/nuttx/mm/Makefile
      +++ b/nuttx/mm/Makefile
      @@ -61,9 +61,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       $(BIN):	$(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
      index 506ef82138..42759e643e 100644
      --- a/nuttx/net/Makefile
      +++ b/nuttx/net/Makefile
      @@ -100,9 +100,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       $(BIN): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       ifeq ($(CONFIG_NET),y)
      diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
      index 1e0a55aeaf..cbce639e73 100644
      --- a/nuttx/sched/Makefile
      +++ b/nuttx/sched/Makefile
      @@ -196,9 +196,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       $(BIN): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/nuttx/syscall/Makefile b/nuttx/syscall/Makefile
      index 88365759d1..7d493665ad 100644
      --- a/nuttx/syscall/Makefile
      +++ b/nuttx/syscall/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # syscall/Makefile
       #
      -#   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
      @@ -72,14 +72,10 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       $(BIN1): $(PROXY_OBJS)
      -	@( for obj in $(PROXY_OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(PROXY_OBJS)")
       
       $(BIN2): $(STUB_OBJS)
      -	@( for obj in $(STUB_OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(STUB_OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(ROOTDEPPATH) $(PROXYDEPPATH) $(STUBDEPPATH) \
      
      From 24a0389152888e8d55f7b90850b7d0a09df53b2f Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sun, 11 Nov 2012 16:24:40 +0000
      Subject: [PATCH 105/206] Partial change: Removing bash ARCHIVE loop
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5336 42af7a65-404d-4744-a932-0658087f49c3
      ---
       apps/Makefile                      | 3 ---
       apps/examples/adc/Makefile         | 6 ++----
       apps/examples/buttons/Makefile     | 6 ++----
       apps/examples/can/Makefile         | 6 ++----
       apps/examples/cdcacm/Makefile      | 4 +---
       apps/examples/composite/Makefile   | 4 +---
       apps/examples/cxxtest/Makefile     | 6 ++----
       apps/examples/dhcpd/Makefile       | 6 ++----
       apps/examples/discover/Makefile    | 4 +---
       apps/examples/elf/Makefile         | 4 +---
       apps/examples/ftpc/Makefile        | 6 ++----
       apps/examples/ftpd/Makefile        | 4 +---
       apps/examples/hello/Makefile       | 4 +---
       apps/examples/helloxx/Makefile     | 6 ++----
       apps/examples/hidkbd/Makefile      | 6 ++----
       apps/examples/igmp/Makefile        | 6 ++----
       apps/examples/json/Makefile        | 4 +---
       apps/examples/lcdrw/Makefile       | 6 ++----
       apps/examples/mm/Makefile          | 6 ++----
       apps/examples/modbus/Makefile      | 4 +---
       apps/examples/mount/Makefile       | 6 ++----
       apps/examples/nettest/Makefile     | 6 ++----
       apps/examples/nsh/Makefile         | 6 ++----
       apps/examples/null/Makefile        | 6 ++----
       apps/examples/nx/Makefile          | 6 ++----
       apps/examples/nxconsole/Makefile   | 6 ++----
       apps/examples/nxffs/Makefile       | 6 ++----
       apps/examples/nxflat/Makefile      | 6 ++----
       apps/examples/nxhello/Makefile     | 6 ++----
       apps/examples/nximage/Makefile     | 6 ++----
       apps/examples/nxlines/Makefile     | 6 ++----
       apps/examples/nxtext/Makefile      | 6 ++----
       apps/examples/ostest/Makefile      | 4 +---
       apps/examples/pashello/Makefile    | 6 ++----
       apps/examples/pipe/Makefile        | 6 ++----
       apps/examples/poll/Makefile        | 6 ++----
       apps/examples/pwm/Makefile         | 6 ++----
       apps/examples/qencoder/Makefile    | 4 +---
       apps/examples/relays/Makefile      | 4 +---
       apps/examples/rgmp/Makefile        | 6 ++----
       apps/examples/romfs/Makefile       | 6 ++----
       apps/examples/sendmail/Makefile    | 6 ++----
       apps/examples/serloop/Makefile     | 6 ++----
       apps/examples/telnetd/Makefile     | 4 +---
       apps/examples/thttpd/Makefile      | 6 ++----
       apps/examples/tiff/Makefile        | 6 ++----
       apps/examples/touchscreen/Makefile | 6 ++----
       apps/examples/udp/Makefile         | 6 ++----
       apps/examples/uip/Makefile         | 4 +---
       apps/examples/usbserial/Makefile   | 6 ++----
       apps/examples/usbstorage/Makefile  | 4 +---
       apps/examples/usbterm/Makefile     | 4 +---
       apps/examples/watchdog/Makefile    | 4 +---
       apps/examples/wget/Makefile        | 6 ++----
       apps/examples/wgetjson/Makefile    | 4 +---
       apps/examples/wlan/Makefile        | 6 ++----
       apps/examples/xmlrpc/Makefile      | 4 +---
       apps/graphics/tiff/Makefile        | 6 ++----
       apps/interpreters/ficl/Makefile    | 6 ++----
       apps/modbus/Makefile               | 4 +---
       apps/namedapp/Makefile             | 6 ++----
       apps/netutils/codecs/Makefile      | 4 +---
       apps/netutils/dhcpc/Makefile       | 6 ++----
       apps/netutils/dhcpd/Makefile       | 6 ++----
       apps/netutils/discover/Makefile    | 4 +---
       apps/netutils/ftpc/Makefile        | 6 ++----
       apps/netutils/ftpd/Makefile        | 4 +---
       apps/netutils/json/Makefile        | 4 +---
       apps/netutils/resolv/Makefile      | 6 ++----
       apps/netutils/smtp/Makefile        | 6 ++----
       apps/netutils/telnetd/Makefile     | 4 +---
       apps/netutils/tftpc/Makefile       | 6 ++----
       apps/netutils/thttpd/Makefile      | 8 +++-----
       apps/netutils/uiplib/Makefile      | 6 ++----
       apps/netutils/webclient/Makefile   | 6 ++----
       apps/netutils/webserver/Makefile   | 4 +---
       apps/netutils/xmlrpc/Makefile      | 4 +---
       apps/nshlib/Makefile               | 4 +---
       apps/system/free/Makefile          | 6 ++----
       apps/system/i2c/Makefile           | 4 +---
       apps/system/install/Makefile       | 5 ++---
       apps/system/poweroff/Makefile      | 5 ++---
       apps/system/ramtron/Makefile       | 5 ++---
       apps/system/readline/Makefile      | 4 +---
       apps/system/sdcard/Makefile        | 5 ++---
       apps/system/sysinfo/Makefile       | 5 ++---
       86 files changed, 142 insertions(+), 310 deletions(-)
      
      diff --git a/apps/Makefile b/apps/Makefile
      index be98dbbfe2..9bdafb1819 100644
      --- a/apps/Makefile
      +++ b/apps/Makefile
      @@ -131,9 +131,6 @@ $(INSTALLED_APPS):
       	@$(MAKE) -C $@ TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)";
       
       $(BIN):	$(INSTALLED_APPS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
       
       .context:
       	@for dir in $(INSTALLED_APPS) ; do \
      diff --git a/apps/examples/adc/Makefile b/apps/examples/adc/Makefile
      index 6357dfc3db..7b5259716f 100644
      --- a/apps/examples/adc/Makefile
      +++ b/apps/examples/adc/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/adc/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/buttons/Makefile b/apps/examples/buttons/Makefile
      index 25d1ef2c2d..c050434803 100644
      --- a/apps/examples/buttons/Makefile
      +++ b/apps/examples/buttons/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/buttons/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/can/Makefile b/apps/examples/can/Makefile
      index c6dc5af84c..d5c7a04efb 100644
      --- a/apps/examples/can/Makefile
      +++ b/apps/examples/can/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/can/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/cdcacm/Makefile b/apps/examples/cdcacm/Makefile
      index 3fa886d561..71cd2f3afb 100644
      --- a/apps/examples/cdcacm/Makefile
      +++ b/apps/examples/cdcacm/Makefile
      @@ -80,9 +80,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/composite/Makefile b/apps/examples/composite/Makefile
      index 17c9f6d18d..80292dbfa2 100644
      --- a/apps/examples/composite/Makefile
      +++ b/apps/examples/composite/Makefile
      @@ -80,9 +80,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/cxxtest/Makefile b/apps/examples/cxxtest/Makefile
      index 803bffa73c..ac70a34f95 100644
      --- a/apps/examples/cxxtest/Makefile
      +++ b/apps/examples/cxxtest/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/cxxtest/Makefile
       #
      -#   Copyright (C) 2009-2011 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
      @@ -93,9 +93,7 @@ $(CXXOBJS): %$(OBJEXT): %.cxx
       	$(call COMPILEXX, $<, $@)
       
       .built: chkcxx $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/dhcpd/Makefile b/apps/examples/dhcpd/Makefile
      index 3254a98067..ceaa3b0224 100644
      --- a/apps/examples/dhcpd/Makefile
      +++ b/apps/examples/dhcpd/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/dhcpd/Makefile
       #
      -#   Copyright (C) 2009-2011 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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/discover/Makefile b/apps/examples/discover/Makefile
      index 3bb6b939eb..a3e90399c4 100644
      --- a/apps/examples/discover/Makefile
      +++ b/apps/examples/discover/Makefile
      @@ -77,9 +77,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/elf/Makefile b/apps/examples/elf/Makefile
      index ea483e7a14..ab49532c80 100644
      --- a/apps/examples/elf/Makefile
      +++ b/apps/examples/elf/Makefile
      @@ -75,9 +75,7 @@ $(COBJS): %$(OBJEXT): %.c
       # generating the source files.
       
       really_build: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .built:
      diff --git a/apps/examples/ftpc/Makefile b/apps/examples/ftpc/Makefile
      index cf32be0f0d..ca630c8143 100644
      --- a/apps/examples/ftpc/Makefile
      +++ b/apps/examples/ftpc/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/ftpc/Makefile
       #
      -#   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
      @@ -74,9 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       # Register application
      diff --git a/apps/examples/ftpd/Makefile b/apps/examples/ftpd/Makefile
      index 4eb25c9e91..bf0e435d7a 100644
      --- a/apps/examples/ftpd/Makefile
      +++ b/apps/examples/ftpd/Makefile
      @@ -71,9 +71,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/hello/Makefile b/apps/examples/hello/Makefile
      index 1d78d723ed..dc9c6c25c5 100644
      --- a/apps/examples/hello/Makefile
      +++ b/apps/examples/hello/Makefile
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/helloxx/Makefile b/apps/examples/helloxx/Makefile
      index 8e85eab23e..63da0bde39 100644
      --- a/apps/examples/helloxx/Makefile
      +++ b/apps/examples/helloxx/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/helloxx/Makefile
       #
      -#   Copyright (C) 2009-2011 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
      @@ -93,9 +93,7 @@ $(CXXOBJS): %$(OBJEXT): %.cxx
       	$(call COMPILEXX, $<, $@)
       
       .built: chkcxx $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/hidkbd/Makefile b/apps/examples/hidkbd/Makefile
      index 8dccb0475e..bd060d83a1 100644
      --- a/apps/examples/hidkbd/Makefile
      +++ b/apps/examples/hidkbd/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/hidkbd/Makefile
       #
      -#   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
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/igmp/Makefile b/apps/examples/igmp/Makefile
      index 1bab2c62ea..f6a171d495 100644
      --- a/apps/examples/igmp/Makefile
      +++ b/apps/examples/igmp/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/igmp/Makefile
       #
      -#   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
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/json/Makefile b/apps/examples/json/Makefile
      index c2fd26bff1..9c3ac61b64 100644
      --- a/apps/examples/json/Makefile
      +++ b/apps/examples/json/Makefile
      @@ -74,9 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/lcdrw/Makefile b/apps/examples/lcdrw/Makefile
      index cc23d3fe1c..c0b6efb8db 100644
      --- a/apps/examples/lcdrw/Makefile
      +++ b/apps/examples/lcdrw/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/lcdrw/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/mm/Makefile b/apps/examples/mm/Makefile
      index 24ed4926f7..e73cd9baa3 100644
      --- a/apps/examples/mm/Makefile
      +++ b/apps/examples/mm/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/mm/Makefile
       #
      -#   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
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/modbus/Makefile b/apps/examples/modbus/Makefile
      index 6dbc7e4245..78ea568d02 100644
      --- a/apps/examples/modbus/Makefile
      +++ b/apps/examples/modbus/Makefile
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/mount/Makefile b/apps/examples/mount/Makefile
      index 69cf970cf0..fd6a4b963a 100644
      --- a/apps/examples/mount/Makefile
      +++ b/apps/examples/mount/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/Makefile
       #
      -#   Copyright (C) 2007-2008, 2010-2010 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2007-2008, 2010-2010, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/nettest/Makefile b/apps/examples/nettest/Makefile
      index 9dd80e271b..09a7c42ddc 100644
      --- a/apps/examples/nettest/Makefile
      +++ b/apps/examples/nettest/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # examples/nettest/Makefile
       #
      -#   Copyright (C) 2007-2008, 2010-2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2007-2008, 2010-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -112,9 +112,7 @@ $(HOST_BIN): $(HOST_OBJS)
       	@$(HOSTCC) $(HOSTLDFLAGS) $(HOST_OBJS) -o $@
       
       .built: $(TARG_OBJS)
      -	@( for obj in $(TARG_OBJS) ; do \
      -		$(call ARCHIVE, $(TARG_BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(TARG_OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/nsh/Makefile b/apps/examples/nsh/Makefile
      index bad40fb2e2..b0efd9aa1b 100644
      --- a/apps/examples/nsh/Makefile
      +++ b/apps/examples/nsh/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/nsh/Makefile
       #
      -#   Copyright (C) 2007-2008, 2010-2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2007-2008, 2010-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/null/Makefile b/apps/examples/null/Makefile
      index 6341206007..6234f77ea6 100644
      --- a/apps/examples/null/Makefile
      +++ b/apps/examples/null/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # examples/null/Makefile
       #
      -#   Copyright (C) 2007-2008, 2010-2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2007-2008, 2010-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/nx/Makefile b/apps/examples/nx/Makefile
      index 748d67210b..6b670d83de 100644
      --- a/apps/examples/nx/Makefile
      +++ b/apps/examples/nx/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/nx/Makefile
       #
      -#   Copyright (C) 2009-2011 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
      @@ -79,9 +79,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/nxconsole/Makefile b/apps/examples/nxconsole/Makefile
      index 78a96a25d0..a478e6bded 100644
      --- a/apps/examples/nxconsole/Makefile
      +++ b/apps/examples/nxconsole/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/nxconsole/Makefile
       #
      -#   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
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/nxffs/Makefile b/apps/examples/nxffs/Makefile
      index b3d36e1634..28c869e16c 100644
      --- a/apps/examples/nxffs/Makefile
      +++ b/apps/examples/nxffs/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/nxffs/Makefile
       #
      -#   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
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/nxflat/Makefile b/apps/examples/nxflat/Makefile
      index a49177a332..e8a15a859c 100644
      --- a/apps/examples/nxflat/Makefile
      +++ b/apps/examples/nxflat/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/nxflat/Makefile
       #
      -#   Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2010-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -73,9 +73,7 @@ headers:
       	@$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/nxhello/Makefile b/apps/examples/nxhello/Makefile
      index 16e80e15e0..37d76b842a 100644
      --- a/apps/examples/nxhello/Makefile
      +++ b/apps/examples/nxhello/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/nxhello/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/nximage/Makefile b/apps/examples/nximage/Makefile
      index a59f05a798..f428009a2a 100644
      --- a/apps/examples/nximage/Makefile
      +++ b/apps/examples/nximage/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/nximage/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/nxlines/Makefile b/apps/examples/nxlines/Makefile
      index e69ce6c0db..2127f1b61e 100644
      --- a/apps/examples/nxlines/Makefile
      +++ b/apps/examples/nxlines/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/nxlines/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/nxtext/Makefile b/apps/examples/nxtext/Makefile
      index 8a9f349f44..ff8f1da694 100644
      --- a/apps/examples/nxtext/Makefile
      +++ b/apps/examples/nxtext/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/nxtext/Makefile
       #
      -#   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
      @@ -80,9 +80,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/ostest/Makefile b/apps/examples/ostest/Makefile
      index 374964b396..e73abfb47d 100644
      --- a/apps/examples/ostest/Makefile
      +++ b/apps/examples/ostest/Makefile
      @@ -120,9 +120,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/pashello/Makefile b/apps/examples/pashello/Makefile
      index f090a68eaf..c5103f2c6e 100644
      --- a/apps/examples/pashello/Makefile
      +++ b/apps/examples/pashello/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/pashello/Makefile
       #
      -#   Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/pipe/Makefile b/apps/examples/pipe/Makefile
      index 956c911b34..d484d9fd98 100644
      --- a/apps/examples/pipe/Makefile
      +++ b/apps/examples/pipe/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/pipe/Makefile
       #
      -#   Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2010-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/poll/Makefile b/apps/examples/poll/Makefile
      index aef61d199c..204acbb5e8 100644
      --- a/apps/examples/poll/Makefile
      +++ b/apps/examples/poll/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/poll/Makefile
       #
      -#   Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2010-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/pwm/Makefile b/apps/examples/pwm/Makefile
      index efbdb048e0..4a01293afe 100644
      --- a/apps/examples/pwm/Makefile
      +++ b/apps/examples/pwm/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/pwm/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/qencoder/Makefile b/apps/examples/qencoder/Makefile
      index 3f3fc9def8..5959d14a3f 100644
      --- a/apps/examples/qencoder/Makefile
      +++ b/apps/examples/qencoder/Makefile
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/relays/Makefile b/apps/examples/relays/Makefile
      index 4a65306935..72d2faa956 100644
      --- a/apps/examples/relays/Makefile
      +++ b/apps/examples/relays/Makefile
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/rgmp/Makefile b/apps/examples/rgmp/Makefile
      index 3590bb0f08..74b6c154b7 100644
      --- a/apps/examples/rgmp/Makefile
      +++ b/apps/examples/rgmp/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # examples/rgmp/Makefile
       #
      -#   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
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/romfs/Makefile b/apps/examples/romfs/Makefile
      index ba930b77d0..f82da8fe44 100644
      --- a/apps/examples/romfs/Makefile
      +++ b/apps/examples/romfs/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/romfs/Makefile
       #
      -#   Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2010-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -86,9 +86,7 @@ romfs_testdir.h : testdir.img
       	@xxd -i $< >$@ || { echo "xxd of $< failed" ; exit 1 ; }
       
       .built: romfs_testdir.h $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/sendmail/Makefile b/apps/examples/sendmail/Makefile
      index 6ee29d935e..0949c7f541 100644
      --- a/apps/examples/sendmail/Makefile
      +++ b/apps/examples/sendmail/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/sendmail/Makefile
       #
      -#   Copyright (C) 2009-2011 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
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/serloop/Makefile b/apps/examples/serloop/Makefile
      index e1c415cdd8..6c5d849e6f 100644
      --- a/apps/examples/serloop/Makefile
      +++ b/apps/examples/serloop/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/serloop/Makefile
       #
      -#   Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2010-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/telnetd/Makefile b/apps/examples/telnetd/Makefile
      index fe892670e1..960d221636 100644
      --- a/apps/examples/telnetd/Makefile
      +++ b/apps/examples/telnetd/Makefile
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/thttpd/Makefile b/apps/examples/thttpd/Makefile
      index 897f15b334..cfdd45a670 100644
      --- a/apps/examples/thttpd/Makefile
      +++ b/apps/examples/thttpd/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/thttpd/Makefile
       #
      -#   Copyright (C) 2009-2011 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
      @@ -73,9 +73,7 @@ headers:
       	@$(MAKE) -C content TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV)
       
       .built: headers $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/tiff/Makefile b/apps/examples/tiff/Makefile
      index 22611a400f..fb1fb7d342 100644
      --- a/apps/examples/tiff/Makefile
      +++ b/apps/examples/tiff/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/tiff/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/touchscreen/Makefile b/apps/examples/touchscreen/Makefile
      index bd32f9f607..d0bd2dbc70 100644
      --- a/apps/examples/touchscreen/Makefile
      +++ b/apps/examples/touchscreen/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/touchscreen/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/udp/Makefile b/apps/examples/udp/Makefile
      index 17438321c3..07f2ba80b2 100644
      --- a/apps/examples/udp/Makefile
      +++ b/apps/examples/udp/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/udp/Makefile
       #
      -#   Copyright (C) 2007-2008, 2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2007-2008, 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -92,9 +92,7 @@ $(TARG_COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       "$(TARG_BIN)": $(TARG_OBJS) $(HOST_BIN)
      -	@( for obj in $(TARG_OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(TARG_OBJS)")
       
       $(HOST_OBJS): %.o: %.c
       	$(HOSTCC) -c $(HOSTCFLAGS) $< -o $@
      diff --git a/apps/examples/uip/Makefile b/apps/examples/uip/Makefile
      index 218f6f3c60..316e01a163 100644
      --- a/apps/examples/uip/Makefile
      +++ b/apps/examples/uip/Makefile
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       httpd_fsdata.c: httpd-fs/*
      diff --git a/apps/examples/usbserial/Makefile b/apps/examples/usbserial/Makefile
      index 4b6bd89483..7bca964632 100644
      --- a/apps/examples/usbserial/Makefile
      +++ b/apps/examples/usbserial/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/usbserial/Makefile
       #
      -#   Copyright (C) 2008, 2010-2010 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2010-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/usbstorage/Makefile b/apps/examples/usbstorage/Makefile
      index d68a759e86..9ee03efc07 100644
      --- a/apps/examples/usbstorage/Makefile
      +++ b/apps/examples/usbstorage/Makefile
      @@ -80,9 +80,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/usbterm/Makefile b/apps/examples/usbterm/Makefile
      index 8db1f9897d..461a98fa36 100644
      --- a/apps/examples/usbterm/Makefile
      +++ b/apps/examples/usbterm/Makefile
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/watchdog/Makefile b/apps/examples/watchdog/Makefile
      index d2739dbb0a..22613aea2b 100644
      --- a/apps/examples/watchdog/Makefile
      +++ b/apps/examples/watchdog/Makefile
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/wget/Makefile b/apps/examples/wget/Makefile
      index 7771619a5b..ddb7b6bf29 100644
      --- a/apps/examples/wget/Makefile
      +++ b/apps/examples/wget/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/wget/Makefile
       #
      -#   Copyright (C) 2009-2011 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
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/wgetjson/Makefile b/apps/examples/wgetjson/Makefile
      index e8c3e50650..9687380e9b 100644
      --- a/apps/examples/wgetjson/Makefile
      +++ b/apps/examples/wgetjson/Makefile
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/examples/wlan/Makefile b/apps/examples/wlan/Makefile
      index 88b1e3e2a1..83fb94fc57 100644
      --- a/apps/examples/wlan/Makefile
      +++ b/apps/examples/wlan/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/examples/wlan/Makefile
       #
      -#   Copyright (C) 2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
       #   Authors: Gregory Nutt 
       #            Rafael Noronha 
       #
      @@ -71,9 +71,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/xmlrpc/Makefile b/apps/examples/xmlrpc/Makefile
      index 9fa03bf7ee..87eae9ed22 100644
      --- a/apps/examples/xmlrpc/Makefile
      +++ b/apps/examples/xmlrpc/Makefile
      @@ -77,9 +77,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/graphics/tiff/Makefile b/apps/graphics/tiff/Makefile
      index af487c1a9c..84e3a66bd6 100644
      --- a/apps/graphics/tiff/Makefile
      +++ b/apps/graphics/tiff/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/graphics/tiff/Makefile
       #
      -#   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
      @@ -70,9 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/interpreters/ficl/Makefile b/apps/interpreters/ficl/Makefile
      index fb953964e1..9a1fa7e719 100644
      --- a/apps/interpreters/ficl/Makefile
      +++ b/apps/interpreters/ficl/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/interpreters/ficl/Makefile
       #
      -#   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
      @@ -95,9 +95,7 @@ debug:
       	@#echo "CFLAGS: $(CFLAGS)"
       
       .built: debug $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/modbus/Makefile b/apps/modbus/Makefile
      index 3cee140171..01deedb542 100644
      --- a/apps/modbus/Makefile
      +++ b/apps/modbus/Makefile
      @@ -88,9 +88,7 @@ endif
       
       .built: $(OBJS)
       ifeq ($(CONFIG_MODBUS),y)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       endif
       
      diff --git a/apps/namedapp/Makefile b/apps/namedapp/Makefile
      index 6b0fd6a053..29ae343fbb 100644
      --- a/apps/namedapp/Makefile
      +++ b/apps/namedapp/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/nshlib/Makefile
       #
      -#   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
      @@ -75,9 +75,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/netutils/codecs/Makefile b/apps/netutils/codecs/Makefile
      index d1b84d4603..1b7a9aa5c0 100644
      --- a/apps/netutils/codecs/Makefile
      +++ b/apps/netutils/codecs/Makefile
      @@ -68,9 +68,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/dhcpc/Makefile b/apps/netutils/dhcpc/Makefile
      index 29e5bd4f2b..0207fff007 100644
      --- a/apps/netutils/dhcpc/Makefile
      +++ b/apps/netutils/dhcpc/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/netutils/dhcpc/Makefile
       #
      -#   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
      @@ -74,9 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/dhcpd/Makefile b/apps/netutils/dhcpd/Makefile
      index b05fe1c74d..cf91c2390c 100644
      --- a/apps/netutils/dhcpd/Makefile
      +++ b/apps/netutils/dhcpd/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/netutils/dhcpd/Makefile
       #
      -#   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
      @@ -74,9 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/discover/Makefile b/apps/netutils/discover/Makefile
      index 52099b439a..609365f637 100644
      --- a/apps/netutils/discover/Makefile
      +++ b/apps/netutils/discover/Makefile
      @@ -77,9 +77,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/ftpc/Makefile b/apps/netutils/ftpc/Makefile
      index 723179131d..0544ddb1a2 100644
      --- a/apps/netutils/ftpc/Makefile
      +++ b/apps/netutils/ftpc/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/netutils/ftpc/Makefile
       #
      -#   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
      @@ -90,9 +90,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/ftpd/Makefile b/apps/netutils/ftpd/Makefile
      index 84e4f79a77..158159f545 100644
      --- a/apps/netutils/ftpd/Makefile
      +++ b/apps/netutils/ftpd/Makefile
      @@ -74,9 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/json/Makefile b/apps/netutils/json/Makefile
      index 1426a1a51f..a0c99a4711 100644
      --- a/apps/netutils/json/Makefile
      +++ b/apps/netutils/json/Makefile
      @@ -68,9 +68,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/resolv/Makefile b/apps/netutils/resolv/Makefile
      index 89744e3233..423397f3f3 100644
      --- a/apps/netutils/resolv/Makefile
      +++ b/apps/netutils/resolv/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/netutils/resolv/Makefile
       #
      -#   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
      @@ -74,9 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/smtp/Makefile b/apps/netutils/smtp/Makefile
      index 5a43d1c9d6..01864da3bf 100644
      --- a/apps/netutils/smtp/Makefile
      +++ b/apps/netutils/smtp/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/netutils/smtp/Makefile
       #
      -#   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
      @@ -74,9 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/telnetd/Makefile b/apps/netutils/telnetd/Makefile
      index fac6df5719..a07a92b624 100644
      --- a/apps/netutils/telnetd/Makefile
      +++ b/apps/netutils/telnetd/Makefile
      @@ -74,9 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/tftpc/Makefile b/apps/netutils/tftpc/Makefile
      index 910046c11e..d8fb88ad99 100644
      --- a/apps/netutils/tftpc/Makefile
      +++ b/apps/netutils/tftpc/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/netutils/tftpc/Makefile
       #
      -#   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
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/thttpd/Makefile b/apps/netutils/thttpd/Makefile
      index f505125da7..38f6750434 100644
      --- a/apps/netutils/thttpd/Makefile
      +++ b/apps/netutils/thttpd/Makefile
      @@ -1,7 +1,7 @@
       #############################################################################
       # apps/netutils/thttpd/Makefile
       #
      -#   Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -106,11 +106,9 @@ cgi-bin/$(SUBDIR_BIN3): cgi-bin cgi-src/$(SUBDIR_BIN3)
       endif
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
      -	
      +
       context:
       
       .depend: Makefile $(SRCS)
      diff --git a/apps/netutils/uiplib/Makefile b/apps/netutils/uiplib/Makefile
      index c1b128c26d..29e569b011 100644
      --- a/apps/netutils/uiplib/Makefile
      +++ b/apps/netutils/uiplib/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/netutils/uiplib/Makefile
       #
      -#   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
      @@ -90,9 +90,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/webclient/Makefile b/apps/netutils/webclient/Makefile
      index d999d47af0..5fb6a2bb17 100644
      --- a/apps/netutils/webclient/Makefile
      +++ b/apps/netutils/webclient/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/netutils/webclient/Makefile
       #
      -#   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
      @@ -74,9 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/webserver/Makefile b/apps/netutils/webserver/Makefile
      index 4b1f2f9f3c..965de73b22 100644
      --- a/apps/netutils/webserver/Makefile
      +++ b/apps/netutils/webserver/Makefile
      @@ -81,9 +81,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/netutils/xmlrpc/Makefile b/apps/netutils/xmlrpc/Makefile
      index 903506f46a..3efdf0778d 100644
      --- a/apps/netutils/xmlrpc/Makefile
      +++ b/apps/netutils/xmlrpc/Makefile
      @@ -76,9 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile
      index 71f159b388..46dbdd0b11 100644
      --- a/apps/nshlib/Makefile
      +++ b/apps/nshlib/Makefile
      @@ -110,9 +110,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/system/free/Makefile b/apps/system/free/Makefile
      index 7f911d81cc..2fe5c455d6 100644
      --- a/apps/system/free/Makefile
      +++ b/apps/system/free/Makefile
      @@ -1,7 +1,7 @@
       ############################################################################
       # apps/system/free/Makefile
       #
      -#   Copyright (C) 2011 Uros Platise. All rights reserved.
      +#   Copyright (C) 2011-2012 Uros Platise. All rights reserved.
       #   Author: Uros Platise 
       #           Gregory Nutt 
       #
      @@ -83,9 +83,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       # Register application
      diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile
      index 00db91bb70..074906a6db 100644
      --- a/apps/system/i2c/Makefile
      +++ b/apps/system/i2c/Makefile
      @@ -73,9 +73,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       .context:
      diff --git a/apps/system/install/Makefile b/apps/system/install/Makefile
      index 71d82f34ce..6e85bba0c9 100644
      --- a/apps/system/install/Makefile
      +++ b/apps/system/install/Makefile
      @@ -2,6 +2,7 @@
       # apps/system/install/Makefile
       #
       #   Copyright (C) 2011 Uros Platise. All rights reserved.
      +#   Copyright (C) 2012 Gregory Nutt. All rights reserved.
       #   Author: Uros Platise 
       #           Gregory Nutt 
       #
      @@ -83,9 +84,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       # Register application
      diff --git a/apps/system/poweroff/Makefile b/apps/system/poweroff/Makefile
      index 40465e957d..92949d93c7 100644
      --- a/apps/system/poweroff/Makefile
      +++ b/apps/system/poweroff/Makefile
      @@ -2,6 +2,7 @@
       # apps/system/poweroff/Makefile
       #
       #   Copyright (C) 2011 Uros Platise. All rights reserved.
      +#   Copyright (C) 2012 Gregory Nutt. All rights reserved.
       #   Author: Uros Platise 
       #           Gregory Nutt 
       #
      @@ -83,9 +84,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       # Register application
      diff --git a/apps/system/ramtron/Makefile b/apps/system/ramtron/Makefile
      index 030ef6d5c4..cb771a9cc5 100644
      --- a/apps/system/ramtron/Makefile
      +++ b/apps/system/ramtron/Makefile
      @@ -2,6 +2,7 @@
       # apps/system/ramtron/Makefile
       #
       #   Copyright (C) 2011 Uros Platise. All rights reserved.
      +#   Copyright (C) 2012 Gregory Nutt. All rights reserved.
       #   Author: Uros Platise 
       #           Gregory Nutt 
       #
      @@ -83,9 +84,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       # Register application
      diff --git a/apps/system/readline/Makefile b/apps/system/readline/Makefile
      index 34fab7e810..d5db043cac 100644
      --- a/apps/system/readline/Makefile
      +++ b/apps/system/readline/Makefile
      @@ -74,9 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       # Context build phase target
      diff --git a/apps/system/sdcard/Makefile b/apps/system/sdcard/Makefile
      index fef049a59b..555ca151b3 100644
      --- a/apps/system/sdcard/Makefile
      +++ b/apps/system/sdcard/Makefile
      @@ -2,6 +2,7 @@
       # apps/system/sdcard/Makefile
       #
       #   Copyright (C) 2011 Uros Platise. All rights reserved.
      +#   Copyright (C) 2012 Gregory Nutt. All rights reserved.
       #   Author: Uros Platise 
       #           Gregory Nutt 
       #
      @@ -83,9 +84,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       # Register application
      diff --git a/apps/system/sysinfo/Makefile b/apps/system/sysinfo/Makefile
      index ead9742779..2b269deb59 100644
      --- a/apps/system/sysinfo/Makefile
      +++ b/apps/system/sysinfo/Makefile
      @@ -2,6 +2,7 @@
       # apps/system/sysinfo/Makefile
       #
       #   Copyright (C) 2011 Uros Platise. All rights reserved.
      +#   Copyright (C) 2012 Gregory Nutt. All rights reserved.
       #   Author: Uros Platise 
       #           Gregory Nutt 
       #
      @@ -83,9 +84,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       # Register application
      
      From 2e97e079981e4f8070ede6528f82c173b893fb62 Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sun, 11 Nov 2012 16:33:14 +0000
      Subject: [PATCH 106/206] Partial change: Removing bash ARCHIVE loop
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5337 42af7a65-404d-4744-a932-0658087f49c3
      ---
       NxWidgets/UnitTests/CButton/Makefile              | 4 +---
       NxWidgets/UnitTests/CButtonArray/Makefile         | 4 +---
       NxWidgets/UnitTests/CCheckBox/Makefile            | 4 +---
       NxWidgets/UnitTests/CGlyphButton/Makefile         | 4 +---
       NxWidgets/UnitTests/CImage/Makefile               | 4 +---
       NxWidgets/UnitTests/CKeypad/Makefile              | 4 +---
       NxWidgets/UnitTests/CLabel/Makefile               | 4 +---
       NxWidgets/UnitTests/CLatchButton/Makefile         | 4 +---
       NxWidgets/UnitTests/CLatchButtonArray/Makefile    | 4 +---
       NxWidgets/UnitTests/CListBox/Makefile             | 4 +---
       NxWidgets/UnitTests/CProgressBar/Makefile         | 4 +---
       NxWidgets/UnitTests/CRadioButton/Makefile         | 4 +---
       NxWidgets/UnitTests/CScrollbarHorizontal/Makefile | 4 +---
       NxWidgets/UnitTests/CScrollbarVertical/Makefile   | 4 +---
       NxWidgets/UnitTests/CSliderHorizonal/Makefile     | 4 +---
       NxWidgets/UnitTests/CSliderVertical/Makefile      | 4 +---
       NxWidgets/UnitTests/CTextBox/Makefile             | 4 +---
       NxWidgets/UnitTests/nxwm/Makefile                 | 4 +---
       NxWidgets/libnxwidgets/Makefile                   | 4 +---
       NxWidgets/nxwm/Makefile                           | 4 +---
       20 files changed, 20 insertions(+), 60 deletions(-)
      
      diff --git a/NxWidgets/UnitTests/CButton/Makefile b/NxWidgets/UnitTests/CButton/Makefile
      index 77ba7e9865..87649ac3c4 100644
      --- a/NxWidgets/UnitTests/CButton/Makefile
      +++ b/NxWidgets/UnitTests/CButton/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CButtonArray/Makefile b/NxWidgets/UnitTests/CButtonArray/Makefile
      index a5a33b3b01..03f7624f93 100644
      --- a/NxWidgets/UnitTests/CButtonArray/Makefile
      +++ b/NxWidgets/UnitTests/CButtonArray/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CCheckBox/Makefile b/NxWidgets/UnitTests/CCheckBox/Makefile
      index 9b46cef8d9..715fe4dad0 100644
      --- a/NxWidgets/UnitTests/CCheckBox/Makefile
      +++ b/NxWidgets/UnitTests/CCheckBox/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CGlyphButton/Makefile b/NxWidgets/UnitTests/CGlyphButton/Makefile
      index 5f2522e494..db91bdfbca 100644
      --- a/NxWidgets/UnitTests/CGlyphButton/Makefile
      +++ b/NxWidgets/UnitTests/CGlyphButton/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CImage/Makefile b/NxWidgets/UnitTests/CImage/Makefile
      index 46e69c495f..fb26404464 100644
      --- a/NxWidgets/UnitTests/CImage/Makefile
      +++ b/NxWidgets/UnitTests/CImage/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CKeypad/Makefile b/NxWidgets/UnitTests/CKeypad/Makefile
      index 3d37c26fe3..36ae2f5438 100644
      --- a/NxWidgets/UnitTests/CKeypad/Makefile
      +++ b/NxWidgets/UnitTests/CKeypad/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CLabel/Makefile b/NxWidgets/UnitTests/CLabel/Makefile
      index e04adc7de2..2ddfbbf427 100644
      --- a/NxWidgets/UnitTests/CLabel/Makefile
      +++ b/NxWidgets/UnitTests/CLabel/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CLatchButton/Makefile b/NxWidgets/UnitTests/CLatchButton/Makefile
      index 7444c50be3..a44e7e9549 100644
      --- a/NxWidgets/UnitTests/CLatchButton/Makefile
      +++ b/NxWidgets/UnitTests/CLatchButton/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CLatchButtonArray/Makefile b/NxWidgets/UnitTests/CLatchButtonArray/Makefile
      index a6ac9118bb..a11c9bfd64 100644
      --- a/NxWidgets/UnitTests/CLatchButtonArray/Makefile
      +++ b/NxWidgets/UnitTests/CLatchButtonArray/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CListBox/Makefile b/NxWidgets/UnitTests/CListBox/Makefile
      index f068738175..a396d4b01a 100644
      --- a/NxWidgets/UnitTests/CListBox/Makefile
      +++ b/NxWidgets/UnitTests/CListBox/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CProgressBar/Makefile b/NxWidgets/UnitTests/CProgressBar/Makefile
      index 5ee346b520..11b802f92e 100644
      --- a/NxWidgets/UnitTests/CProgressBar/Makefile
      +++ b/NxWidgets/UnitTests/CProgressBar/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CRadioButton/Makefile b/NxWidgets/UnitTests/CRadioButton/Makefile
      index 57190e8d30..b642ebaf31 100644
      --- a/NxWidgets/UnitTests/CRadioButton/Makefile
      +++ b/NxWidgets/UnitTests/CRadioButton/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile b/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile
      index 191324a96c..c952fd1e2e 100644
      --- a/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile
      +++ b/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CScrollbarVertical/Makefile b/NxWidgets/UnitTests/CScrollbarVertical/Makefile
      index a2777e7525..81b8ced265 100644
      --- a/NxWidgets/UnitTests/CScrollbarVertical/Makefile
      +++ b/NxWidgets/UnitTests/CScrollbarVertical/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CSliderHorizonal/Makefile b/NxWidgets/UnitTests/CSliderHorizonal/Makefile
      index 0578510d32..e31f1f0331 100644
      --- a/NxWidgets/UnitTests/CSliderHorizonal/Makefile
      +++ b/NxWidgets/UnitTests/CSliderHorizonal/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CSliderVertical/Makefile b/NxWidgets/UnitTests/CSliderVertical/Makefile
      index f37cc86191..3a86b57e97 100644
      --- a/NxWidgets/UnitTests/CSliderVertical/Makefile
      +++ b/NxWidgets/UnitTests/CSliderVertical/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/CTextBox/Makefile b/NxWidgets/UnitTests/CTextBox/Makefile
      index c368cc4970..b73ce8f4a1 100644
      --- a/NxWidgets/UnitTests/CTextBox/Makefile
      +++ b/NxWidgets/UnitTests/CTextBox/Makefile
      @@ -136,9 +136,7 @@ chklib:
       $(NXWIDGETS_LIB): # Just to keep make happy.  chklib does the work.
       
       .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       else
      diff --git a/NxWidgets/UnitTests/nxwm/Makefile b/NxWidgets/UnitTests/nxwm/Makefile
      index f84a78bcc4..cfcdef750f 100644
      --- a/NxWidgets/UnitTests/nxwm/Makefile
      +++ b/NxWidgets/UnitTests/nxwm/Makefile
      @@ -164,9 +164,7 @@ $(NXWIDGETS_LIB): # Just to keep make happy.  chklibnxwidgets does the work.
       $(NXWM_LIB): # Just to keep make happy.  chklibnxwm does the work.
       
       .built: $(OBJS) $(NXWIDGETS_LIB)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	   done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       ifeq ($(WINTOOL),y)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR)
       	@$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWM_DIR)
      diff --git a/NxWidgets/libnxwidgets/Makefile b/NxWidgets/libnxwidgets/Makefile
      index 92eb877517..4673c1f98e 100644
      --- a/NxWidgets/libnxwidgets/Makefile
      +++ b/NxWidgets/libnxwidgets/Makefile
      @@ -123,9 +123,7 @@ check_nuttx:
       	)
       
       $(BIN): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      diff --git a/NxWidgets/nxwm/Makefile b/NxWidgets/nxwm/Makefile
      index f26ae03bb8..372f3c186d 100644
      --- a/NxWidgets/nxwm/Makefile
      +++ b/NxWidgets/nxwm/Makefile
      @@ -128,9 +128,7 @@ check_nuttx:
       	)
       
       $(BIN): $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $@, $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
       	@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      
      From a42dcee79d5090c8df3a3a04cd1cf2b6d0347575 Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sun, 11 Nov 2012 18:36:28 +0000
      Subject: [PATCH 107/206] Completes removal bash ARCHIVE loop; Adds basic
       Makefile for native windows build
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5338 42af7a65-404d-4744-a932-0658087f49c3
      ---
       misc/pascal/nuttx/Makefile                    |   4 +-
       nuttx/ChangeLog                               |   6 +-
       nuttx/Makefile.win                            | 739 ++++++++++++++++++
       nuttx/README.txt                              |  30 +
       nuttx/binfmt/Makefile                         |  10 +-
       .../configs/ez80f910200kitg/ostest/Make.defs  |  13 +-
       nuttx/configs/ez80f910200zco/dhcpd/Make.defs  |  13 +-
       nuttx/configs/ez80f910200zco/httpd/Make.defs  |  13 +-
       .../configs/ez80f910200zco/nettest/Make.defs  |  13 +-
       nuttx/configs/ez80f910200zco/nsh/Make.defs    |  13 +-
       nuttx/configs/ez80f910200zco/ostest/Make.defs |  13 +-
       nuttx/configs/ez80f910200zco/poll/Make.defs   |  13 +-
       nuttx/configs/rgmp/x86/cxxtest/Make.defs      |  30 +-
       nuttx/configs/rgmp/x86/helloxx/Make.defs      |  30 +-
       nuttx/configs/stm32f4discovery/README.txt     |  34 +
       .../stm32f4discovery/winbuild/Make.defs       | 137 ++++
       .../stm32f4discovery/winbuild/defconfig       | 584 ++++++++++++++
       .../stm32f4discovery/winbuild/setenv.bat      |  48 ++
       .../configs/z16f2800100zcog/ostest/Make.defs  |  13 +-
       .../z16f2800100zcog/pashello/Make.defs        |  13 +-
       nuttx/configs/z8encore000zco/ostest/Make.defs |  13 +-
       nuttx/configs/z8f64200100kit/ostest/Make.defs |  13 +-
       nuttx/drivers/Makefile                        |   8 +-
       nuttx/fs/Makefile                             |  10 +-
       nuttx/graphics/Makefile                       |  78 +-
       nuttx/lib/Makefile                            |   2 +-
       nuttx/libc/Makefile                           |  24 +-
       nuttx/libxx/Makefile                          |   8 +-
       nuttx/mm/Makefile                             |  12 +-
       nuttx/net/Makefile                            |  10 +-
       nuttx/sched/Makefile                          |   8 +-
       nuttx/syscall/Makefile                        |  20 +-
       nuttx/tools/Config.mk                         |  12 +-
       nuttx/tools/Makefile.export                   |   4 +-
       nuttx/tools/Makefile.host                     |  18 +-
       35 files changed, 1817 insertions(+), 192 deletions(-)
       create mode 100644 nuttx/Makefile.win
       create mode 100644 nuttx/configs/stm32f4discovery/winbuild/Make.defs
       create mode 100644 nuttx/configs/stm32f4discovery/winbuild/defconfig
       create mode 100755 nuttx/configs/stm32f4discovery/winbuild/setenv.bat
      
      diff --git a/misc/pascal/nuttx/Makefile b/misc/pascal/nuttx/Makefile
      index eb82e48bd2..af4e4d412b 100644
      --- a/misc/pascal/nuttx/Makefile
      +++ b/misc/pascal/nuttx/Makefile
      @@ -112,9 +112,7 @@ $(APPDIR)/include/pcode/insn: $(APPDIR)/include/pcode insn/include
       	@$(DIRLINK) $(PCODEDIR)/insn/include $(APPDIR)/include/pcode/insn
       
       .built: $(APPDIR)/include/pcode $(APPDIR)/include/pcode/insn $(OBJS)
      -	@( for obj in $(OBJS) ; do \
      -		$(call ARCHIVE, $(BIN), $${obj}); \
      -	done ; )
      +	$(call ARCHIVE, $@, "$(OBJS)")
       	@touch .built
       
       context: $(APPDIR)/include/pcode $(APPDIR)/include/pcode/insn
      diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
      index b48fbfd962..eb4f4b4ed8 100644
      --- a/nuttx/ChangeLog
      +++ b/nuttx/ChangeLog
      @@ -3603,4 +3603,8 @@
       	  directory.
       	* arch/*/src/Makefile:  Now uses only the libraries in lib/
       	  Replace bash fragments that test for board/Makefile.
      -
      +	* Makefile.win:  The beginnings of a Windows-native build.  This is just
      +	  the begining and not yet ready for prime time use.
      +	* configs/stm32f4discovery/winbuild:  This is a version of the standard
      +	  NuttX OS test, but configured to build natively on Windows.  Its only
      +	  real purpose is to very the native Windows build logic.
      diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win
      new file mode 100644
      index 0000000000..d4157a3c49
      --- /dev/null
      +++ b/nuttx/Makefile.win
      @@ -0,0 +1,739 @@
      +############################################################################
      +# Makefile.win
      +#
      +#   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.
      +#
      +############################################################################
      +
      +TOPDIR := ${shell echo %CD%}
      +-include $(TOPDIR)\.config
      +-include $(TOPDIR)\tools\Config.mk
      +-include $(TOPDIR)\Make.defs
      +
      +# Control build verbosity
      +
      +ifeq ($(V),1)
      +export Q :=
      +else
      +export Q := @
      +endif
      +
      +# This define is passed as EXTRADEFINES for kernel-mode builds.  It is also passed
      +# during PASS1 (but not PASS2) context and depend targets.
      +
      +KDEFINE = -D__KERNEL__
      +
      +# Process architecture and board-specific directories
      +
      +ARCH_DIR = arch\$(CONFIG_ARCH)
      +ARCH_SRC = $(ARCH_DIR)\src
      +ARCH_INC = $(ARCH_DIR)\include
      +BOARD_DIR = configs\$(CONFIG_ARCH_BOARD)
      +
      +# Add-on directories.  These may or may not be in place in the
      +# NuttX source tree (they must be specifically installed)
      +#
      +# CONFIG_APPS_DIR can be over-ridden from the command line or in the .config file.
      +# The default value of CONFIG_APPS_DIR is ..\apps.  Ultimately, the application
      +# will be built if APPDIR is defined.  APPDIR will be defined if a directory containing
      +# a Makefile is found at the path provided by CONFIG_APPS_DIR
      +
      +ifeq ($(CONFIG_APPS_DIR),)
      +CONFIG_APPS_DIR = ..\apps
      +endif
      +APPDIR := ${shell if [ -r $(CONFIG_APPS_DIR)\Makefile ]; then echo "$(CONFIG_APPS_DIR)"; fi}
      +
      +# All add-on directories.
      +#
      +# NUTTX_ADDONS is the list of directories built into the NuttX kernel.
      +# USER_ADDONS is the list of directories that will be built into the user application
      +
      +NUTTX_ADDONS :=
      +USER_ADDONS :=
      +
      +ifeq ($(CONFIG_NUTTX_KERNEL),y)
      +USER_ADDONS += $(APPDIR)
      +else
      +NUTTX_ADDONS += $(APPDIR)
      +endif
      +
      +# Lists of build directories.
      +#
      +# FSDIRS depend on file descriptor support; NONFSDIRS do not (except for parts
      +#   of FSDIRS).  We will exclude FSDIRS from the build if file descriptor
      +#   support is disabled
      +# CONTEXTDIRS include directories that have special, one-time pre-build
      +#   requirements.  Normally this includes things like auto-generation of
      +#   configuration specific files or creation of configurable symbolic links
      +# USERDIRS - When NuttX is build is a monolithic kernel, this provides the
      +#   list of directories that must be built
      +# OTHERDIRS - These are directories that are not built but probably should
      +#   be cleaned to prevent garbarge from collecting in them when changing
      +#   configurations.
      +
      +NONFSDIRS = sched $(ARCH_SRC) $(NUTTX_ADDONS)
      +FSDIRS = fs drivers binfmt
      +CONTEXTDIRS = $(APPDIR)
      +USERDIRS =
      +OTHERDIRS = lib
      +
      +ifeq ($(CONFIG_NUTTX_KERNEL),y)
      +
      +NONFSDIRS += syscall
      +CONTEXTDIRS += syscall
      +USERDIRS += syscall libc mm $(USER_ADDONS)
      +ifeq ($(CONFIG_HAVE_CXX),y)
      +USERDIRS += libxx
      +endif
      +
      +else
      +
      +NONFSDIRS += libc mm
      +OTHERDIRS += syscall $(USER_ADDONS)
      +ifeq ($(CONFIG_HAVE_CXX),y)
      +NONFSDIRS += libxx
      +else
      +OTHERDIRS += libxx
      +endif
      +
      +endif
      +
      +ifeq ($(CONFIG_NX),y)
      +NONFSDIRS += graphics
      +CONTEXTDIRS += graphics
      +else
      +OTHERDIRS += graphics
      +endif
      +
      +# CLEANDIRS are the directories that will clean in.  These are
      +#   all directories that we know about.
      +# KERNDEPDIRS are the directories in which we will build target dependencies.
      +#   If NuttX and applications are built separately (CONFIG_NUTTX_KERNEL),
      +#   then this holds only the directories containing kernel files.
      +# USERDEPDIRS. If NuttX and applications are built separately (CONFIG_NUTTX_KERNEL),
      +#   then this holds only the directories containing user files.
      +
      +CLEANDIRS = $(NONFSDIRS) $(FSDIRS) $(USERDIRS) $(OTHERDIRS)
      +KERNDEPDIRS = $(NONFSDIRS)
      +USERDEPDIRS = $(USERDIRS)
      +
      +# Add file system directories to KERNDEPDIRS (they are already in CLEANDIRS)
      +
      +ifeq ($(CONFIG_NFILE_DESCRIPTORS),0)
      +ifeq ($(CONFIG_NET),y)
      +ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0)
      +KERNDEPDIRS += fs
      +endif
      +KERNDEPDIRS += drivers
      +endif
      +else
      +KERNDEPDIRS += $(FSDIRS)
      +endif
      +
      +# Add networking directories to KERNDEPDIRS and CLEANDIRS
      +
      +ifeq ($(CONFIG_NET),y)
      +KERNDEPDIRS += net
      +endif
      +CLEANDIRS += net
      +
      +#
      +# Extra objects used in the final link.
      +#
      +# Pass 1 1ncremental (relative) link objects should be put into the
      +# processor-specific source directory (where other link objects will
      +# be created).  If the pass1 obect is an archive, it could go anywhere.
      +
      +ifeq ($(CONFIG_BUILD_2PASS),y)
      +EXTRA_OBJS += $(CONFIG_PASS1_OBJECT)
      +endif
      +
      +# NUTTXLIBS is the list of NuttX libraries that is passed to the
      +#   processor-specific Makefile to build the final NuttX target.
      +#   Libraries in FSDIRS are excluded if file descriptor support
      +#   is disabled.
      +# USERLIBS is the list of libraries used to build the final user-space
      +#   application
      +
      +NUTTXLIBS = lib\libsched$(LIBEXT) lib\libarch$(LIBEXT)
      +USERLIBS =
      +
      +# Add libraries for syscall support.  The C library will be needed by
      +# both the kernel- and user-space builds.  For now, the memory manager (mm)
      +# is placed in user space (only).
      +
      +ifeq ($(CONFIG_NUTTX_KERNEL),y)
      +NUTTXLIBS += lib\libstubs$(LIBEXT) lib\libkc$(LIBEXT)
      +USERLIBS += lib\libproxies$(LIBEXT) lib\libuc$(LIBEXT) lib\libmm$(LIBEXT)
      +else
      +NUTTXLIBS += lib\libmm$(LIBEXT) lib\libc$(LIBEXT)
      +endif
      +
      +# Add libraries for C++ support.  CXX, CXXFLAGS, and COMPILEXX must
      +# be defined in Make.defs for this to work!
      +
      +ifeq ($(CONFIG_HAVE_CXX),y)
      +ifeq ($(CONFIG_NUTTX_KERNEL),y)
      +USERLIBS += lib\libcxx$(LIBEXT)
      +else
      +NUTTXLIBS += lib\libcxx$(LIBEXT)
      +endif
      +endif
      +
      +# Add library for application support.
      +
      +ifneq ($(APPDIR),)
      +ifeq ($(CONFIG_NUTTX_KERNEL),y)
      +USERLIBS += lib\libapps$(LIBEXT)
      +else
      +NUTTXLIBS += lib\libapps$(LIBEXT)
      +endif
      +endif
      +
      +# Add libraries for network support
      +
      +ifeq ($(CONFIG_NET),y)
      +NUTTXLIBS += lib\libnet$(LIBEXT)
      +endif
      +
      +# Add libraries for file system support
      +
      +ifeq ($(CONFIG_NFILE_DESCRIPTORS),0)
      +ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0)
      +NUTTXLIBS += lib\libfs$(LIBEXT)
      +endif
      +ifeq ($(CONFIG_NET),y)
      +NUTTXLIBS += lib\libdrivers$(LIBEXT)
      +endif
      +else
      +NUTTXLIBS += lib\libfs$(LIBEXT) lib\libdrivers$(LIBEXT) lib\libbinfmt$(LIBEXT)
      +endif
      +
      +# Add libraries for the NX graphics sub-system
      +
      +ifeq ($(CONFIG_NX),y)
      +NUTTXLIBS += lib\libgraphics$(LIBEXT)
      +endif
      +
      +# LINKLIBS derives from NUTTXLIBS and is simply the same list with the subdirectory removed
      +
      +LINKLIBS = $(patsubst lib\%,%,$(NUTTXLIBS))
      +
      +# This is the name of the final target (relative to the top level directorty)
      +
      +BIN = nuttx$(EXEEXT)
      +
      +all: $(BIN)
      +.PHONY: context clean_context check_context export subdir_clean clean subdir_distclean distclean apps_clean apps_distclean
      +
      +# Target used to copy include\nuttx\math.h.  If CONFIG_ARCH_MATH_H is
      +# defined, then there is an architecture specific math.h header file
      +# that will be included indirectly from include\math.h.  But first, we
      +# have to copy math.h from include\nuttx\. to include\.  Logic within
      +# include\nuttx\math.h will hand the redirection to the architecture-
      +# specific math.h header file.
      +#
      +# If the CONFIG_LIBM is defined, the Rhombus libm will be built at libc\math.
      +# Definitions and prototypes for the Rhombus libm are also contained in
      +# include\nuttx\math.h and so the file must also be copied in that case.
      +#
      +# If neither CONFIG_ARCH_MATH_H nor CONFIG_LIBM is defined, then no math.h
      +# header file will be provided.  You would want that behavior if (1) you
      +# don't use libm, or (2) you want to use the math.h and libm provided
      +# within your toolchain.
      +
      +ifeq ($(CONFIG_ARCH_MATH_H),y)
      +NEED_MATH_H = y
      +else
      +ifeq ($(CONFIG_LIBM),y)
      +NEED_MATH_H = y
      +endif
      +endif
      +
      +ifeq ($(NEED_MATH_H),y)
      +include\math.h: include\nuttx\math.h
      +	$(Q) cp -f include\nuttx\math.h include\math.h
      +else
      +include\math.h:
      +endif
      +
      +# The float.h header file defines the properties of your floating point
      +# implementation.  It would always be best to use your toolchain's float.h
      +# header file but if none is avaiable, a default float.h header file will
      +# provided if this option is selected.  However there is no assurance that
      +# the settings in this float.h are actually correct for your platform!
      +
      +ifeq ($(CONFIG_ARCH_FLOAT_H),y)
      +include\float.h: include\nuttx\float.h
      +	$(Q) cp -f include\nuttx\float.h include\float.h
      +else
      +include\float.h:
      +endif
      +
      +# Target used to copy include\nuttx\stdarg.h.  If CONFIG_ARCH_STDARG_H is
      +# defined, then there is an architecture specific stdarg.h header file
      +# that will be included indirectly from include\stdarg.h.  But first, we
      +# have to copy stdarg.h from include\nuttx\. to include\.
      +
      +ifeq ($(CONFIG_ARCH_STDARG_H),y)
      +include\stdarg.h: include\nuttx\stdarg.h
      +	$(Q) cp -f include\nuttx\stdarg.h include\stdarg.h
      +else
      +include\stdarg.h:
      +endif
      +
      +# Targets used to build include\nuttx\version.h.  Creation of version.h is
      +# part of the overall NuttX configuration sequence. Notice that the
      +# tools\mkversion tool is built and used to create include\nuttx\version.h
      +
      +tools\mkversion:
      +	$(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)"  mkversion
      +
      +$(TOPDIR)\.version:
      +	$(Q) if [ ! -f .version ]; then \
      +		echo "No .version file found, creating one"; \
      +		tools\version.sh -v 0.0 -b 0 .version; \
      +		chmod 755 .version; \
      +	fi
      +
      +include\nuttx\version.h: $(TOPDIR)\.version tools\mkversion
      +	$(Q) tools\mkversion $(TOPDIR) > include\nuttx\version.h
      +
      +# Targets used to build include\nuttx\config.h.  Creation of config.h is
      +# part of the overall NuttX configuration sequence. Notice that the
      +# tools\mkconfig tool is built and used to create include\nuttx\config.h
      +
      +tools\mkconfig:
      +	$(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)"  mkconfig
      +
      +include\nuttx\config.h: $(TOPDIR)\.config tools\mkconfig
      +	$(Q) tools\mkconfig $(TOPDIR) > include\nuttx\config.h
      +
      +# dirlinks, and helpers
      +#
      +# Directories links.  Most of establishing the NuttX configuration involves
      +# setting up symbolic links with 'generic' directory names to specific,
      +# configured directories.
      +#
      +# Link the apps/include directory to include\apps
      +
      +include\apps: Make.defs
      +ifneq ($(APPDIR),)
      +	@echo "LN: include\apps $(APPDIR)\include"
      +ifeq ($(CONFIG_WINDOWS_MKLINK),y)
      +	$(Q) /user:administrator mklink /d include\apps $(APPDIR)\include
      +else
      +	$(Q) xcopy $(APPDIR)\include include\apps /c /q /s /e /y /i
      +	$(Q) echo FAKELNK > include\apps\.fakelnk
      +endif
      +endif
      +
      +# Link the arch\\include directory to include\arch
      +
      +include\arch: Make.defs
      +	@echo "LN: include\arch -> $(TOPDIR)\$(ARCH_DIR)\include"
      +ifeq ($(CONFIG_WINDOWS_MKLINK),y)
      +	$(Q) /user:administrator mklink /d include\arch $(TOPDIR)\$(ARCH_DIR)\include
      +else
      +	$(Q) xcopy $(TOPDIR)\$(ARCH_DIR)\include include\arch /c /q /s /e /y /i
      +	$(Q) echo FAKELNK > include\arch\.fakelnk
      +endif
      +
      +# Link the configs\\include directory to include\arch\board
      +
      +include\arch\board: include\arch Make.defs include\arch
      +	@echo "LN: include\arch\board -> $(TOPDIR)\$(BOARD_DIR)\include"
      +ifeq ($(CONFIG_WINDOWS_MKLINK),y)
      +	$(Q) /user:administrator mklink /d include\arch\board $(TOPDIR)\$(BOARD_DIR)\include
      +else
      +	$(Q) xcopy $(TOPDIR)\$(BOARD_DIR)\include include\arch\board /c /q /s /e /y /i
      +	$(Q) echo FAKELNK > include\arch\board\.fakelnk
      +endif
      +
      +# Link the configs\\src dir to arch\\src\board
      +
      +$(ARCH_SRC)\board: Make.defs
      +	@echo "LN: $(ARCH_SRC)\board -> $(TOPDIR)\$(BOARD_DIR)\src"
      +ifeq ($(CONFIG_WINDOWS_MKLINK),y)
      +	$(Q) /user:administrator mklink /d $(ARCH_SRC)\board $(TOPDIR)\$(BOARD_DIR)\src
      +else
      +	$(Q) xcopy $(TOPDIR)\$(BOARD_DIR)\src $(ARCH_SRC)\board /c /q /s /e /y /i
      +	$(Q) echo FAKELNK > $(ARCH_SRC)\board\.fakelnk
      +endif
      +
      +# Link arch\\include\ to arch\\include\chip
      +
      +$(ARCH_SRC)\chip: Make.defs
      +ifneq ($(CONFIG_ARCH_CHIP),)
      +	@echo "LN: $(ARCH_SRC)\chip -> $(TOPDIR)\$(ARCH_SRC)\$(CONFIG_ARCH_CHIP)"
      +ifeq ($(CONFIG_WINDOWS_MKLINK),y)
      +	$(Q) /user:administrator mklink /d $(ARCH_SRC)\chip $(TOPDIR)\$(ARCH_SRC)\$(CONFIG_ARCH_CHIP)
      +else
      +	$(Q) xcopy $(TOPDIR)\$(ARCH_SRC)\$(CONFIG_ARCH_CHIP) $(ARCH_SRC)\chip /c /q /s /e /y /i
      +	$(Q) echo FAKELNK > $(ARCH_SRC)\chip\.fakelnk
      +endif
      +endif
      +
      +# Link arch\\src\ to arch\\src\chip
      +
      +include\arch\chip: include\arch Make.defs
      +ifneq ($(CONFIG_ARCH_CHIP),)
      +	@echo "LN: include\arch\chip -> $(TOPDIR)\$(ARCH_INC)\$(CONFIG_ARCH_CHIP)"
      +ifeq ($(CONFIG_WINDOWS_MKLINK),y)
      +	$(Q) /user:administrator mklink /d include\arch\chip $(TOPDIR)\$(ARCH_INC)\$(CONFIG_ARCH_CHIP)
      +else
      +	$(Q) xcopy $(TOPDIR)\$(ARCH_INC)\$(CONFIG_ARCH_CHIP) include\arch\chip /c /q /s /e /y /i
      +	$(Q) echo FAKELNK > include\arch\chip\.fakelnk
      +endif
      +endif
      +
      +dirlinks: include\arch include\arch\board include\arch\chip $(ARCH_SRC)\board $(ARCH_SRC)\chip include\apps
      +
      +# context
      +#
      +# The context target is invoked on each target build to assure that NuttX is
      +# properly configured.  The basic configuration steps include creation of the
      +# the config.h and version.h header files in the include\nuttx directory and
      +# the establishment of symbolic links to configured directories.
      +
      +context: check_context include\nuttx\config.h include\nuttx\version.h include\math.h include\float.h include\stdarg.h dirlinks
      +	$(Q) for %%G in ($(CONTEXTDIRS)) do ( $(MAKE) -C %%G TOPDIR="$(TOPDIR)" context )
      +
      +# clean_context
      +#
      +# This is part of the distclean target.  It removes all of the header files
      +# and symbolic links created by the context target.
      +
      +clean_context:
      +	$(Q) rm -f include\nuttx\config.h
      +	$(Q) rm -f include\nuttx\version.h
      +	$(Q) rm -f include\math.h
      +	$(Q) rm -f include\stdarg.h
      +	$(Q) $(DIRUNLINK) include\arch\board
      +	$(Q) $(DIRUNLINK) include\arch\chip
      +	$(Q) $(DIRUNLINK) include\arch
      +	$(Q) $(DIRUNLINK) $(ARCH_SRC)\board
      +	$(Q) $(DIRUNLINK) $(ARCH_SRC)\chip
      +	$(Q) $(DIRUNLINK) include\apps
      +
      +# check_context
      +#
      +# This target checks if NuttX has been configured.  NuttX is configured using
      +# the script tools\configure.sh.  That script will install certain files in
      +# the top-level NuttX build directory.  This target verifies that those
      +# configuration files have been installed and that NuttX is ready to be built.
      +
      +check_context:
      +	if not exist $(TOPDIR)\.config echo "$(TOPDIR)\.config does not exist"
      +	if not exist $(TOPDIR)\Make.defs echo "$(TOPDIR)\Make.defs does not exist"
      +
      +# Archive targets.  The target build sequency will first create a series of
      +# libraries, one per configured source file directory.  The final NuttX
      +# execution will then be built from those libraries.  The following targets
      +# built those libraries.
      +#
      +# Possible kernel-mode builds
      +
      +libc\libkc$(LIBEXT): context
      +	$(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libkc$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +
      +lib\libkc$(LIBEXT): libc\libkc$(LIBEXT)
      +	$(Q) install libc\libkc$(LIBEXT) lib\libkc$(LIBEXT)
      +
      +sched\libsched$(LIBEXT): context
      +	$(Q) $(MAKE) -C sched TOPDIR="$(TOPDIR)" libsched$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +
      +lib\libsched$(LIBEXT): sched\libsched$(LIBEXT)
      +	$(Q) install sched\libsched$(LIBEXT) lib\libsched$(LIBEXT)
      +
      +$(ARCH_SRC)\libarch$(LIBEXT): context
      +	$(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" libarch$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +
      +lib\libarch$(LIBEXT): $(ARCH_SRC)\libarch$(LIBEXT)
      +	$(Q) install $(ARCH_SRC)\libarch$(LIBEXT) lib\libarch$(LIBEXT)
      +
      +net\libnet$(LIBEXT): context
      +	$(Q) $(MAKE) -C net TOPDIR="$(TOPDIR)" libnet$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +
      +lib\libnet$(LIBEXT): net\libnet$(LIBEXT)
      +	$(Q) install net\libnet$(LIBEXT) lib\libnet$(LIBEXT)
      +
      +fs\libfs$(LIBEXT): context
      +	$(Q) $(MAKE) -C fs TOPDIR="$(TOPDIR)" libfs$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +
      +lib\libfs$(LIBEXT): fs\libfs$(LIBEXT)
      +	$(Q) install fs\libfs$(LIBEXT) lib\libfs$(LIBEXT)
      +
      +drivers\libdrivers$(LIBEXT): context
      +	$(Q) $(MAKE) -C drivers TOPDIR="$(TOPDIR)" libdrivers$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +
      +lib\libdrivers$(LIBEXT): drivers\libdrivers$(LIBEXT)
      +	$(Q) install drivers\libdrivers$(LIBEXT) lib\libdrivers$(LIBEXT)
      +
      +binfmt\libbinfmt$(LIBEXT): context
      +	$(Q) $(MAKE) -C binfmt TOPDIR="$(TOPDIR)" libbinfmt$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +
      +lib\libbinfmt$(LIBEXT): binfmt\libbinfmt$(LIBEXT)
      +	$(Q) install binfmt\libbinfmt$(LIBEXT) lib\libbinfmt$(LIBEXT)
      +
      +graphics\libgraphics$(LIBEXT): context
      +	$(Q) $(MAKE) -C graphics TOPDIR="$(TOPDIR)" libgraphics$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +
      +lib\libgraphics$(LIBEXT): graphics\libgraphics$(LIBEXT)
      +	$(Q) install graphics\libgraphics$(LIBEXT) lib\libgraphics$(LIBEXT)
      +
      +syscall\libstubs$(LIBEXT): context
      +	$(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libstubs$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +
      +lib\libstubs$(LIBEXT): syscall\libstubs$(LIBEXT)
      +	$(Q) install syscall\libstubs$(LIBEXT) lib\libstubs$(LIBEXT)
      +
      +# Possible user-mode builds
      +
      +libc\libuc$(LIBEXT): context
      +	$(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libuc$(LIBEXT)
      +
      +lib\libuc$(LIBEXT): libc\libuc$(LIBEXT)
      +	$(Q) install libc\libuc$(LIBEXT) lib\libuc$(LIBEXT)
      +
      +libxx\libcxx$(LIBEXT): context
      +	$(Q) $(MAKE) -C libxx TOPDIR="$(TOPDIR)" libcxx$(LIBEXT)
      +
      +lib\libcxx$(LIBEXT): libxx\libcxx$(LIBEXT)
      +	$(Q) install libxx\libcxx$(LIBEXT) lib\libcxx$(LIBEXT)
      +
      +mm\libmm$(LIBEXT): context
      +	$(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) EXTRADEFINES=$(KDEFINE)
      +
      +lib\libmm$(LIBEXT): mm\libmm$(LIBEXT)
      +	$(Q) install mm\libmm$(LIBEXT) lib\libmm$(LIBEXT)
      +
      +$(APPDIR)\libapps$(LIBEXT): context
      +	$(Q) $(MAKE) -C $(APPDIR) TOPDIR="$(TOPDIR)" libapps$(LIBEXT)
      +
      +lib\libapps$(LIBEXT): $(APPDIR)\libapps$(LIBEXT)
      +	$(Q) install $(APPDIR)\libapps$(LIBEXT) lib\libapps$(LIBEXT)
      +
      +syscall\libproxies$(LIBEXT): context
      +	$(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libproxies$(LIBEXT)
      +
      +lib\libproxies$(LIBEXT): syscall\libproxies$(LIBEXT)
      +	$(Q) install syscall\libproxies$(LIBEXT) lib\libproxies$(LIBEXT)
      +
      +# Possible non-kernel builds
      +
      +libc\libc$(LIBEXT): context
      +	$(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libc$(LIBEXT)
      +
      +lib\libc$(LIBEXT): libc\libc$(LIBEXT)
      +	$(Q) install libc\libc$(LIBEXT) lib\libc$(LIBEXT)
      +
      +# pass1 and pass2
      +#
      +# If the 2 pass build option is selected, then this pass1 target is
      +# configured to built before the pass2 target.  This pass1 target may, as an
      +# example, build an extra link object (CONFIG_PASS1_OBJECT) which may be an
      +# incremental (relative) link object, but could be a static library (archive);
      +# some modification to this Makefile would be required if CONFIG_PASS1_OBJECT
      +# is an archive.  Exactly what is performed during pass1 or what it generates
      +# is unknown to this makefule unless CONFIG_PASS1_OBJECT is defined.
      +
      +pass1deps: context pass1dep $(USERLIBS)
      +
      +pass1: pass1deps
      +ifeq ($(CONFIG_BUILD_2PASS),y)
      +	$(Q) if [ -z "$(CONFIG_PASS1_BUILDIR)" ]; then \
      +		echo "ERROR: CONFIG_PASS1_BUILDIR not defined"; \
      +		exit 1; \
      +	fi
      +	$(Q) if [ ! -d "$(CONFIG_PASS1_BUILDIR)" ]; then \
      +		echo "ERROR: CONFIG_PASS1_BUILDIR does not exist"; \
      +		exit 1; \
      +	fi
      +	$(Q) if [ ! -f "$(CONFIG_PASS1_BUILDIR)\Makefile" ]; then \
      +		echo "ERROR: No Makefile in CONFIG_PASS1_BUILDIR"; \
      +		exit 1; \
      +	fi
      +	$(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" LINKLIBS="$(LINKLIBS)" USERLIBS="$(USERLIBS)" "$(CONFIG_PASS1_TARGET)"
      +endif
      +
      +pass2deps: context pass2dep $(NUTTXLIBS)
      +
      +pass2: pass2deps
      +	$(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(LINKLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN)
      +	$(Q) if [ -w \tftpboot ] ; then \
      +		cp -f $(BIN) \tftpboot\$(BIN).${CONFIG_ARCH}; \
      +	fi
      +ifeq ($(CONFIG_RRLOAD_BINARY),y)
      +	@echo "MK: $(BIN).rr"
      +	$(Q) $(TOPDIR)\tools\mkimage.sh --Prefix $(CROSSDEV) $(BIN) $(BIN).rr
      +	$(Q) if [ -w \tftpboot ] ; then \
      +		cp -f $(BIN).rr \tftpboot\$\(BIN).rr.$(CONFIG_ARCH); \
      +	fi
      +endif
      +ifeq ($(CONFIG_INTELHEX_BINARY),y)
      +	@echo "CP: $(BIN).hex"
      +	$(Q) $(OBJCOPY) $(OBJCOPYARGS) -O ihex $(BIN) $(BIN).hex
      +endif
      +ifeq ($(CONFIG_MOTOROLA_SREC),y)
      +	@echo "CP: $(BIN).srec"
      +	$(Q) $(OBJCOPY) $(OBJCOPYARGS) -O srec $(BIN) $(BIN).srec
      +endif
      +ifeq ($(CONFIG_RAW_BINARY),y)
      +	@echo "CP: $(BIN).bin"
      +	$(Q) $(OBJCOPY) $(OBJCOPYARGS) -O binary $(BIN) $(BIN).bin
      +endif
      +
      +# $(BIN)
      +#
      +# Create the final NuttX executable in a two pass build process.  In the
      +# normal case, all pass1 and pass2 dependencies are created then pass1
      +# and pass2 targets are built.  However, in some cases, you may need to build
      +# pass1 depenencies and pass1 first, then build pass2 dependencies and pass2.
      +# in that case, execute 'make pass1 pass2' from the command line.
      +
      +$(BIN): pass1deps pass2deps pass1 pass2
      +
      +# download
      +#
      +# This is a helper target that will rebuild NuttX and download it to the target
      +# system in one step.  The operation of this target depends completely upon
      +# implementation of the DOWNLOAD command in the user Make.defs file.  It will
      +# generate an error an error if the DOWNLOAD command is not defined.
      +
      +download: $(BIN)
      +	$(call DOWNLOAD, $<)
      +
      +# pass1dep: Create pass1 build dependencies
      +# pass2dep: Create pass2 build dependencies
      +
      +pass1dep: context
      +	$(Q) for %%G in ($(USERDEPDIRS)) do ( $(MAKE) -C %%G TOPDIR="$(TOPDIR)" depend )
      +
      +pass2dep: context
      +	$(Q) for %%G in ($(KERNDEPDIRS)) do ( $(MAKE) -C %%G TOPDIR="$(TOPDIR)" EXTRADEFINES=$(KDEFINE) depend )
      +
      +# Configuration targets
      +#
      +# These targets depend on the kconfig-frontends packages.  To use these, you
      +# must first download and install the kconfig-frontends package from this
      +# location: http://ymorin.is-a-geek.org/projects/kconfig-frontends.  See
      +# misc\tools\README.txt for additional information.
      +
      +config:
      +	$(Q) APPSDIR=${CONFIG_APPS_DIR} conf Kconfig
      +
      +oldconfig:
      +	$(Q) APPSDIR=${CONFIG_APPS_DIR} conf --oldconfig Kconfig
      +
      +menuconfig:
      +	$(Q) APPSDIR=${CONFIG_APPS_DIR} mconf Kconfig
      +
      +# export
      +#
      +# The export target will package the NuttX libraries and header files into
      +# an exportable package.  Caveats: (1) These needs some extension for the KERNEL
      +# build; it needs to receive USERLIBS and create a libuser.a). (2) The logic
      +# in tools\mkexport.sh only supports GCC and, for example, explicitly assumes
      +# that the archiver is 'ar'
      +
      +export: pass2deps
      +	$(Q) tools\mkexport.sh -w$(WINTOOL) -t "$(TOPDIR)" -l "$(NUTTXLIBS)"
      +
      +# General housekeeping targets:  dependencies, cleaning, etc.
      +#
      +# depend:    Create both PASS1 and PASS2 dependencies
      +# clean:     Removes derived object files, archives, executables, and
      +#            temporary files, but retains the configuration and context
      +#            files and directories.
      +# distclean: Does 'clean' then also removes all configuration and context
      +#            files.  This essentially restores the directory structure
      +#            to its original, unconfigured stated.
      +
      +depend: pass1dep pass2dep
      +
      +subdir_clean:
      +	$(Q) for %%G in ($(CLEANDIRS)) do ( if exist %%G/Makefile $(MAKE) -C %%G TOPDIR="$(TOPDIR)" clean )
      +	$(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" clean
      +	$(Q) $(MAKE) -C mm -f Makefile.test TOPDIR="$(TOPDIR)" clean
      +ifeq ($(CONFIG_BUILD_2PASS),y)
      +	$(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" clean
      +endif
      +
      +clean: subdir_clean
      +	$(Q) rm -f $(BIN) nuttx.* mm_test *.map _SAVED_APPS_config *~
      +	$(Q) rm -f nuttx-export*
      +
      +subdir_distclean:
      +	$(Q) for %%G in ($(CLEANDIRS)) do ( if exist %%G/Makefile $(MAKE) -C %%G TOPDIR="$(TOPDIR)" distclean )
      +
      +distclean: clean subdir_distclean clean_context
      +ifeq ($(CONFIG_BUILD_2PASS),y)
      +	$(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean
      +endif
      +	$(Q) rm -f Make.defs setenv.sh setenv.bat .config .config.old
      +
      +# Application housekeeping targets.  The APPDIR variable refers to the user
      +# application directory.  A sample apps\ directory is included with NuttX,
      +# however, this is not treated as part of NuttX and may be replaced with a
      +# different application directory.  For the most part, the application
      +# directory is treated like any other build directory in this script.  However,
      +# as a convenience, the following targets are included to support housekeeping
      +# functions in the user application directory from the NuttX build directory.
      +#
      +# apps_clean:     Perform the clean operation only in the user application
      +#                 directory
      +# apps_distclean: Perform the distclean operation only in the user application
      +#                 directory.  Note that the apps\.config file (inf any) is
      +#                 preserved so that this is not a "full" distclean but more of a
      +#                 configuration "reset." (There willnot be an apps\.config
      +#                 file if the configuration was generated via make menuconfig).
      +
      +apps_clean:
      +ifneq ($(APPDIR),)
      +	$(Q) $(MAKE) -C "$(TOPDIR)\$(APPDIR)" TOPDIR="$(TOPDIR)" clean
      +endif
      +
      +apps_distclean:
      +ifneq ($(APPDIR),)
      +	$(Q) if [ -r "$(TOPDIR)\$(APPDIR)\.config" ]; then \
      +		cp "$(TOPDIR)\$(APPDIR)\.config" _SAVED_APPS_config || \
      +			{ echo "Copy of $(APPDIR)\.config failed" ; exit 1 ; } \
      +	else \
      +		rm -f _SAVED_APPS_config; \
      +	fi
      +	$(Q) $(MAKE) -C "$(TOPDIR)\$(APPDIR)" TOPDIR="$(TOPDIR)" distclean
      +	$(Q) if [ -r _SAVED_APPS_config ]; then \
      +		mv _SAVED_APPS_config "$(TOPDIR)\$(APPDIR)\.config" || \
      +			{ echo "Copy of _SAVED_APPS_config failed" ; exit 1 ; } \
      +	fi
      +endif
      +
      diff --git a/nuttx/README.txt b/nuttx/README.txt
      index 528b7897e5..737d4d4e29 100644
      --- a/nuttx/README.txt
      +++ b/nuttx/README.txt
      @@ -18,6 +18,7 @@ README
           - Building
           - Re-building 
           - Build Targets and Options
      +    - Native Windows Build
         o Cygwin Build Problems
           - Strange Path Problems
           - Window Native Toolchain Issues
      @@ -493,6 +494,35 @@ Build Targets and Options
           useful when adding new boards or tracking down compile time errors and
           warnings (Contributed by Richard Cochran).
       
      +Native Windows Build
      +--------------------
      +
      +  The beginnings of a Windows native build are in place but still not full
      +  usable as of this writing.  The windows native build logic is currently
      +  separate and must be started by:
      +
      +    make -f Makefile.win
      +
      +  This build:
      +
      +    - Uses all Windows style paths
      +    - Uses primarily Windows batch commands from cmd.exe, with
      +    - A few extensions from GNUWin32 (or MSYS is you prefer)
      +
      +  In this build, you cannot use a Cygwin or MSYS shell. Rather the build must
      +  be performed in a Windows CMD shell. Here is a better shell than than the
      +  standard issue, CMD shell:  ConEmu which can be downloaded from:
      +  http://code.google.com/p/conemu-maximus5/
      +
      +  Build Tools.  The build still relies on some Unix-like commands.  I use
      +  the GNUWin32 tools that can be downloaded from http://gnuwin32.sourceforge.net/.
      +  The MSYS tools are probably also a option but are likely lower performance
      +  since they are based on Cygwin 1.3.
      +
      +  Host Compiler:  I use the MingGW compiler which can be downloaded from
      +  http://www.mingw.org/.  If you are using GNUWin32, then it is recommended
      +  the you not install the optional MSYS components as there may be conflicts.
      +
       CYGWIN BUILD PROBLEMS
       ^^^^^^^^^^^^^^^^^^^^^
       
      diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile
      index caf57e62fe..68f671ce61 100644
      --- a/nuttx/binfmt/Makefile
      +++ b/nuttx/binfmt/Makefile
      @@ -81,19 +81,19 @@ $(BIN): $(BINFMT_OBJS)
       	$(call ARCHIVE, $@, "$(BINFMT_OBJS)")
       
       .depend: Makefile $(BINFMT_SRCS)
      -	@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep
      -	@touch $@
      +	$(Q) $(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@rm -f $(BIN) *~ .*.swp
      +	$(Q) rm -f $(BIN) *~ .*.swp
       	$(call CLEAN)
      -	@( for dir in $(SUBDIRS); do \
      +	$(Q) ( for dir in $(SUBDIRS); do \
       		rm -f $${dir}/*~ $${dir}/.*.swp; \
       	done ; )
       
       distclean: clean
      -	@rm -f Make.dep .depend
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/configs/ez80f910200kitg/ostest/Make.defs b/nuttx/configs/ez80f910200kitg/ostest/Make.defs
      index 2ec06aadd3..b7b4e23785 100644
      --- a/nuttx/configs/ez80f910200kitg/ostest/Make.defs
      +++ b/nuttx/configs/ez80f910200kitg/ostest/Make.defs
      @@ -153,10 +153,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      diff --git a/nuttx/configs/ez80f910200zco/dhcpd/Make.defs b/nuttx/configs/ez80f910200zco/dhcpd/Make.defs
      index 367f60ca7f..17ac71f07b 100644
      --- a/nuttx/configs/ez80f910200zco/dhcpd/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/dhcpd/Make.defs
      @@ -153,10 +153,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      diff --git a/nuttx/configs/ez80f910200zco/httpd/Make.defs b/nuttx/configs/ez80f910200zco/httpd/Make.defs
      index ec5a70ca69..399d3a4c25 100644
      --- a/nuttx/configs/ez80f910200zco/httpd/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/httpd/Make.defs
      @@ -153,10 +153,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      diff --git a/nuttx/configs/ez80f910200zco/nettest/Make.defs b/nuttx/configs/ez80f910200zco/nettest/Make.defs
      index 04074c1bf7..3044e8ffdb 100644
      --- a/nuttx/configs/ez80f910200zco/nettest/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/nettest/Make.defs
      @@ -153,10 +153,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      diff --git a/nuttx/configs/ez80f910200zco/nsh/Make.defs b/nuttx/configs/ez80f910200zco/nsh/Make.defs
      index 3f740ac34e..469baeb1aa 100644
      --- a/nuttx/configs/ez80f910200zco/nsh/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/nsh/Make.defs
      @@ -153,10 +153,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      diff --git a/nuttx/configs/ez80f910200zco/ostest/Make.defs b/nuttx/configs/ez80f910200zco/ostest/Make.defs
      index 7c738c4b31..c06dfdebe4 100644
      --- a/nuttx/configs/ez80f910200zco/ostest/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/ostest/Make.defs
      @@ -153,10 +153,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      diff --git a/nuttx/configs/ez80f910200zco/poll/Make.defs b/nuttx/configs/ez80f910200zco/poll/Make.defs
      index 65d3ca2f78..fa21c72065 100644
      --- a/nuttx/configs/ez80f910200zco/poll/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/poll/Make.defs
      @@ -153,10 +153,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      diff --git a/nuttx/configs/rgmp/x86/cxxtest/Make.defs b/nuttx/configs/rgmp/x86/cxxtest/Make.defs
      index 858ecbae1e..9c14dc783f 100644
      --- a/nuttx/configs/rgmp/x86/cxxtest/Make.defs
      +++ b/nuttx/configs/rgmp/x86/cxxtest/Make.defs
      @@ -36,6 +36,7 @@
       ############################################################################
       
       include ${TOPDIR}/.config
      +include ${TOPDIR}/tools/Config.mk
       
       RGMPLIBDIR := $(RGMP_INST_DIR)/lib
       RGMPINCDIR := $(RGMP_INST_DIR)/include
      @@ -96,35 +97,6 @@ LDFLAGS         += -nostdlib
       EXTRA_LIBS		= $(shell $(CC) -print-file-name=libsupc++.a) \
                         $(shell $(CC) -print-file-name=libgcc_eh.a)
       
      -define PREPROCESS
      -	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      -endef
      -
      -define COMPILE
      -	@echo "CC: $1"
      -	@$(CC) -c $(CFLAGS) $1 -o $2
      -endef
      -
      -define COMPILEXX
      -	@echo "CXX: $1"
      -	@$(CXX) -c $(CXXFLAGS) $1 -o $2
      -endef
      -
      -define ASSEMBLE
      -	@echo "AS: $1"
      -	@$(CC) -c $(AFLAGS) $1 -o $2
      -endef
      -
      -define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
      -endef
      -
      -define CLEAN
      -	@rm -f *.o *.a
      -endef
      -
       MKDEP			= $(TOPDIR)/tools/mkdeps.sh
       
       HOSTCC			= gcc
      diff --git a/nuttx/configs/rgmp/x86/helloxx/Make.defs b/nuttx/configs/rgmp/x86/helloxx/Make.defs
      index d2d0e83ea9..b40db563a0 100644
      --- a/nuttx/configs/rgmp/x86/helloxx/Make.defs
      +++ b/nuttx/configs/rgmp/x86/helloxx/Make.defs
      @@ -36,6 +36,7 @@
       ############################################################################
       
       include ${TOPDIR}/.config
      +include ${TOPDIR}/tools/Config.mk
       
       RGMPLIBDIR := $(RGMP_INST_DIR)/lib
       RGMPINCDIR := $(RGMP_INST_DIR)/include
      @@ -94,35 +95,6 @@ LDFLAGS         += -nostdlib
       EXTRA_LIBS		= $(shell $(CC) -print-file-name=libsupc++.a) \
                         $(shell $(CC) -print-file-name=libgcc_eh.a)
       
      -define PREPROCESS
      -	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      -endef
      -
      -define COMPILE
      -	@echo "CC: $1"
      -	@$(CC) -c $(CFLAGS) $1 -o $2
      -endef
      -
      -define COMPILEXX
      -	@echo "CXX: $1"
      -	@$(CXX) -c $(CXXFLAGS) $1 -o $2
      -endef
      -
      -define ASSEMBLE
      -	@echo "AS: $1"
      -	@$(CC) -c $(AFLAGS) $1 -o $2
      -endef
      -
      -define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
      -endef
      -
      -define CLEAN
      -	@rm -f *.o *.a
      -endef
      -
       MKDEP			= $(TOPDIR)/tools/mkdeps.sh
       
       HOSTCC			= gcc
      diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt
      index 216ce85cc6..a69f53b0f5 100644
      --- a/nuttx/configs/stm32f4discovery/README.txt
      +++ b/nuttx/configs/stm32f4discovery/README.txt
      @@ -1441,3 +1441,37 @@ Where  is one of the following:
           The RTC alarm is used to wake up from STOP mode and to transition to
           STANDBY mode.  This used of the RTC alarm could conflict with other uses of
           the RTC alarm in your application.
      +
      +  winbuild:
      +  --------
      +
      +    This is a version of the apps/example/ostest, but configure to build natively
      +    in the Windows CMD shell.
      +
      +    NOTES:
      +
      +    1. The beginnings of a Windows native build are in place but still not full
      +       usable as of this writing.  The windows native build logic is currently
      +       separate and must be started by:
      +
      +        make -f Makefile.win
      +
      +      This build:
      +
      +        - Uses all Windows style paths
      +        - Uses primarily Windows batch commands from cmd.exe, with
      +        - A few extensions from GNUWin32 (or MSYS is you prefer)
      +
      +      In this build, you cannot use a Cygwin or MSYS shell. Rather the build must
      +      be performed in a Windows CMD shell. Here is a better shell than than the
      +      standard issue, CMD shell:  ConEmu which can be downloaded from:
      +      http://code.google.com/p/conemu-maximus5/
      +
      +      Build Tools.  The build still relies on some Unix-like commands.  I use
      +      the GNUWin32 tools that can be downloaded from http://gnuwin32.sourceforge.net/.
      +      The MSYS tools are probably also a option but are likely lower performance
      +      since they are based on Cygwin 1.3.
      +
      +      Host Compiler:  I use the MingGW compiler which can be downloaded from
      +      http://www.mingw.org/.  If you are using GNUWin32, then it is recommended
      +      the you not install the optional MSYS components as there may be conflicts.
      diff --git a/nuttx/configs/stm32f4discovery/winbuild/Make.defs b/nuttx/configs/stm32f4discovery/winbuild/Make.defs
      new file mode 100644
      index 0000000000..0837044548
      --- /dev/null
      +++ b/nuttx/configs/stm32f4discovery/winbuild/Make.defs
      @@ -0,0 +1,137 @@
      +############################################################################
      +# configs/stm32f4discovery/winbuild/Make.defs
      +#
      +#   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
      +include ${TOPDIR}/tools/Config.mk
      +
      +# Setup for the selected toolchain
      +
      +ifeq ($(CONFIG_STM32_CODESOURCERYW),y)
      +  # CodeSourcery under Windows
      +  CROSSDEV = arm-none-eabi-
      +  ARCROSSDEV = arm-none-eabi-
      +  ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
      +endif
      +ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y)
      +  # Atollic toolchain under Windows
      +  CROSSDEV = arm-atollic-eabi-
      +  ARCROSSDEV =
      +ifeq ($(CONFIG_ARCH_FPU),y)
      +  ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
      +else
      +  ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
      +endif
      +endif
      +ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y)
      +  # Atollic toolchain under Windows
      +  CROSSDEV = arm-atollic-eabi-
      +  ARCROSSDEV = arm-atollic-eabi-
      +ifeq ($(CONFIG_ARCH_FPU),y)
      +  ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
      +else
      +  ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
      +endif
      +endif
      +ifeq ($(CONFIG_STM32_DEVKITARM),y)
      +  # devkitARM under Windows
      +  CROSSDEV = arm-eabi-
      +  ARCROSSDEV = arm-eabi-
      +  ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
      +endif
      +ifeq ($(CONFIG_STM32_RAISONANCE),y)
      +  # Raisonance RIDE7 under Windows
      +  CROSSDEV = arm-none-eabi-
      +  ARCROSSDEV = arm-none-eabi-
      +  ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
      +endif
      +
      +LDSCRIPT = ld.script
      +
      +# Windows-native toolchains
      +
      +MKDEP = $(TOPDIR)/tools/mknulldeps.sh
      +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
      +ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
      +ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
      +
      +CC = $(CROSSDEV)gcc.exe
      +CXX = $(CROSSDEV)g++.exe
      +CPP = $(CROSSDEV)gcc.exe -E
      +LD = $(CROSSDEV)ld.exe
      +AR = $(ARCROSSDEV)ar.exe rcs
      +NM = $(ARCROSSDEV)nm.exe
      +OBJCOPY = $(CROSSDEV)objcopy.exe
      +OBJDUMP = $(CROSSDEV)objdump.exe
      +
      +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 ("${CONFIG_DEBUG_SYMBOLS}","y")
      +  ARCHOPTIMIZATION = -g
      +else
      +  ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
      +endif
      +
      +ARCHCFLAGS = -fno-builtin
      +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
      +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
      +ARCHWARNINGSXX = -Wall -Wshadow
      +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__
      +
      +NXFLATLDFLAGS1 = -r -d -warn-common
      +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections
      +LDNXFLATFLAGS = -e main -s 2048
      +
      +OBJEXT = .o
      +LIBEXT = .a
      +EXEEXT = .exe
      +
      +LDFLAGS += -nostartfiles -nodefaultlibs
      +ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
      +  LDFLAGS += -g
      +endif
      +
      +HOSTCC = mingw-gcc.exe
      +HOSTINCLUDES = -I.
      +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
      +HOSTLDFLAGS =
      diff --git a/nuttx/configs/stm32f4discovery/winbuild/defconfig b/nuttx/configs/stm32f4discovery/winbuild/defconfig
      new file mode 100644
      index 0000000000..e52719f256
      --- /dev/null
      +++ b/nuttx/configs/stm32f4discovery/winbuild/defconfig
      @@ -0,0 +1,584 @@
      +#
      +# Automatically generated file; DO NOT EDIT.
      +# Nuttx/ Configuration
      +#
      +CONFIG_NUTTX_NEWCONFIG=y
      +
      +#
      +# Build Setup
      +#
      +# CONFIG_EXPERIMENTAL is not set
      +# CONFIG_HOST_LINUX is not set
      +# CONFIG_HOST_OSX is not set
      +CONFIG_HOST_WINDOWS=y
      +# CONFIG_HOST_OTHER is not set
      +CONFIG_WINDOWS_NATIVE=y
      +# CONFIG_WINDOWS_CYGWIN is not set
      +# CONFIG_WINDOWS_MSYS is not set
      +# CONFIG_WINDOWS_OTHER is not set
      +# CONFIG_WINDOWS_MKLINK is not set
      +
      +#
      +# Build Configuration
      +#
      +# CONFIG_APPS_DIR="../apps"
      +# CONFIG_BUILD_2PASS is not set
      +
      +#
      +# Binary Output Formats
      +#
      +# CONFIG_RRLOAD_BINARY is not set
      +CONFIG_INTELHEX_BINARY=y
      +# CONFIG_MOTOROLA_SREC is not set
      +CONFIG_RAW_BINARY=y
      +
      +#
      +# Customize Header Files
      +#
      +# CONFIG_ARCH_STDBOOL_H is not set
      +# CONFIG_ARCH_MATH_H is not set
      +# CONFIG_ARCH_FLOAT_H is not set
      +# CONFIG_ARCH_STDARG_H is not set
      +
      +#
      +# Debug Options
      +#
      +# CONFIG_DEBUG is not set
      +# CONFIG_DEBUG_SYMBOLS is not set
      +
      +#
      +# System Type
      +#
      +# CONFIG_ARCH_8051 is not set
      +CONFIG_ARCH_ARM=y
      +# CONFIG_ARCH_AVR is not set
      +# CONFIG_ARCH_HC is not set
      +# CONFIG_ARCH_MIPS is not set
      +# CONFIG_ARCH_RGMP is not set
      +# CONFIG_ARCH_SH is not set
      +# CONFIG_ARCH_SIM is not set
      +# CONFIG_ARCH_X86 is not set
      +# CONFIG_ARCH_Z16 is not set
      +# CONFIG_ARCH_Z80 is not set
      +CONFIG_ARCH="arm"
      +
      +#
      +# ARM Options
      +#
      +# CONFIG_ARCH_CHIP_C5471 is not set
      +# CONFIG_ARCH_CHIP_CALYPSO is not set
      +# CONFIG_ARCH_CHIP_DM320 is not set
      +# CONFIG_ARCH_CHIP_IMX is not set
      +# CONFIG_ARCH_CHIP_KINETIS is not set
      +# CONFIG_ARCH_CHIP_LM3S is not set
      +# CONFIG_ARCH_CHIP_LPC17XX is not set
      +# CONFIG_ARCH_CHIP_LPC214X is not set
      +# CONFIG_ARCH_CHIP_LPC2378 is not set
      +# CONFIG_ARCH_CHIP_LPC31XX is not set
      +# CONFIG_ARCH_CHIP_LPC43XX is not set
      +# CONFIG_ARCH_CHIP_SAM3U is not set
      +CONFIG_ARCH_CHIP_STM32=y
      +# CONFIG_ARCH_CHIP_STR71X is not set
      +CONFIG_ARCH_CORTEXM4=y
      +CONFIG_ARCH_FAMILY="armv7-m"
      +CONFIG_ARCH_CHIP="stm32"
      +CONFIG_ARCH_HAVE_CMNVECTOR=y
      +# CONFIG_ARMV7M_CMNVECTOR is not set
      +# CONFIG_ARCH_FPU is not set
      +CONFIG_ARCH_HAVE_MPU=y
      +# CONFIG_ARMV7M_MPU is not set
      +CONFIG_ARCH_IRQPRIO=y
      +CONFIG_BOARD_LOOPSPERMSEC=16717
      +# CONFIG_ARCH_CALIBRATION is not set
      +# CONFIG_SERIAL_TERMIOS is not set
      +
      +#
      +# STM32 Configuration Options
      +#
      +# CONFIG_ARCH_CHIP_STM32F100C8 is not set
      +# CONFIG_ARCH_CHIP_STM32F100CB is not set
      +# CONFIG_ARCH_CHIP_STM32F100R8 is not set
      +# CONFIG_ARCH_CHIP_STM32F100RB is not set
      +# CONFIG_ARCH_CHIP_STM32F100RC is not set
      +# CONFIG_ARCH_CHIP_STM32F100RD is not set
      +# CONFIG_ARCH_CHIP_STM32F100RE is not set
      +# CONFIG_ARCH_CHIP_STM32F100V8 is not set
      +# CONFIG_ARCH_CHIP_STM32F100VB is not set
      +# CONFIG_ARCH_CHIP_STM32F100VC is not set
      +# CONFIG_ARCH_CHIP_STM32F100VD is not set
      +# CONFIG_ARCH_CHIP_STM32F100VE is not set
      +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set
      +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
      +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set
      +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set
      +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set
      +# CONFIG_ARCH_CHIP_STM32F107VC is not set
      +# CONFIG_ARCH_CHIP_STM32F207IG is not set
      +# CONFIG_ARCH_CHIP_STM32F405RG is not set
      +# CONFIG_ARCH_CHIP_STM32F405VG is not set
      +# CONFIG_ARCH_CHIP_STM32F405ZG is not set
      +# CONFIG_ARCH_CHIP_STM32F407VE is not set
      +CONFIG_ARCH_CHIP_STM32F407VG=y
      +# CONFIG_ARCH_CHIP_STM32F407ZE is not set
      +# CONFIG_ARCH_CHIP_STM32F407ZG is not set
      +# CONFIG_ARCH_CHIP_STM32F407IE is not set
      +# CONFIG_ARCH_CHIP_STM32F407IG is not set
      +CONFIG_STM32_STM32F40XX=y
      +CONFIG_STM32_CODESOURCERYW=y
      +# CONFIG_STM32_CODESOURCERYL is not set
      +# CONFIG_STM32_ATOLLIC_LITE is not set
      +# CONFIG_STM32_ATOLLIC_PRO is not set
      +# CONFIG_STM32_DEVKITARM is not set
      +# CONFIG_STM32_RAISONANCE is not set
      +# CONFIG_STM32_BUILDROOT is not set
      +# CONFIG_STM32_DFU is not set
      +
      +#
      +# STM32 Peripheral Support
      +#
      +# CONFIG_STM32_ADC1 is not set
      +# CONFIG_STM32_ADC2 is not set
      +# CONFIG_STM32_ADC3 is not set
      +# CONFIG_STM32_BKPSRAM is not set
      +# CONFIG_STM32_CAN1 is not set
      +# CONFIG_STM32_CAN2 is not set
      +# CONFIG_STM32_CCMDATARAM is not set
      +# CONFIG_STM32_CRC is not set
      +# CONFIG_STM32_CRYP is not set
      +# CONFIG_STM32_DMA1 is not set
      +# CONFIG_STM32_DMA2 is not set
      +# CONFIG_STM32_DAC1 is not set
      +# CONFIG_STM32_DAC2 is not set
      +# CONFIG_STM32_DCMI is not set
      +# CONFIG_STM32_ETHMAC is not set
      +# CONFIG_STM32_FSMC is not set
      +# CONFIG_STM32_HASH is not set
      +# CONFIG_STM32_I2C1 is not set
      +# CONFIG_STM32_I2C2 is not set
      +# CONFIG_STM32_I2C3 is not set
      +# CONFIG_STM32_IWDG is not set
      +# CONFIG_STM32_OTGFS is not set
      +# CONFIG_STM32_OTGHS is not set
      +# CONFIG_STM32_PWR is not set
      +# CONFIG_STM32_RNG is not set
      +# CONFIG_STM32_SDIO is not set
      +# CONFIG_STM32_SPI1 is not set
      +# CONFIG_STM32_SPI2 is not set
      +# CONFIG_STM32_SPI3 is not set
      +CONFIG_STM32_SYSCFG=y
      +# CONFIG_STM32_TIM1 is not set
      +# CONFIG_STM32_TIM2 is not set
      +# CONFIG_STM32_TIM3 is not set
      +# CONFIG_STM32_TIM4 is not set
      +# CONFIG_STM32_TIM5 is not set
      +# CONFIG_STM32_TIM6 is not set
      +# CONFIG_STM32_TIM7 is not set
      +# CONFIG_STM32_TIM8 is not set
      +# CONFIG_STM32_TIM9 is not set
      +# CONFIG_STM32_TIM10 is not set
      +# CONFIG_STM32_TIM11 is not set
      +# CONFIG_STM32_TIM12 is not set
      +# CONFIG_STM32_TIM13 is not set
      +# CONFIG_STM32_TIM14 is not set
      +# CONFIG_STM32_USART1 is not set
      +CONFIG_STM32_USART2=y
      +# CONFIG_STM32_USART3 is not set
      +# CONFIG_STM32_UART4 is not set
      +# CONFIG_STM32_UART5 is not set
      +# CONFIG_STM32_USART6 is not set
      +# CONFIG_STM32_WWDG is not set
      +
      +#
      +# Alternate Pin Mapping
      +#
      +# CONFIG_STM32_JTAG_DISABLE is not set
      +# CONFIG_STM32_JTAG_FULL_ENABLE is not set
      +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
      +CONFIG_STM32_JTAG_SW_ENABLE=y
      +# CONFIG_STM32_FORCEPOWER is not set
      +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
      +# CONFIG_STM32_CCMEXCLUDE is not set
      +
      +#
      +# USB Host Configuration
      +#
      +
      +#
      +# Architecture Options
      +#
      +# CONFIG_ARCH_NOINTC is not set
      +# CONFIG_ARCH_DMA is not set
      +CONFIG_ARCH_STACKDUMP=y
      +
      +#
      +# Board Settings
      +#
      +CONFIG_DRAM_START=0x20000000
      +CONFIG_DRAM_SIZE=114688
      +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
      +CONFIG_ARCH_INTERRUPTSTACK=0
      +
      +#
      +# Boot options
      +#
      +# CONFIG_BOOT_RUNFROMEXTSRAM is not set
      +CONFIG_BOOT_RUNFROMFLASH=y
      +# CONFIG_BOOT_RUNFROMISRAM is not set
      +# CONFIG_BOOT_RUNFROMSDRAM is not set
      +# CONFIG_BOOT_COPYTORAM is not set
      +
      +#
      +# Board Selection
      +#
      +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y
      +# CONFIG_ARCH_BOARD_CUSTOM is not set
      +CONFIG_ARCH_BOARD="stm32f4discovery"
      +
      +#
      +# Common Board Options
      +#
      +CONFIG_ARCH_HAVE_LEDS=y
      +CONFIG_ARCH_LEDS=y
      +CONFIG_ARCH_HAVE_BUTTONS=y
      +# CONFIG_ARCH_BUTTONS is not set
      +CONFIG_ARCH_HAVE_IRQBUTTONS=y
      +
      +#
      +# Board-Specific Options
      +#
      +
      +#
      +# RTOS Features
      +#
      +CONFIG_MSEC_PER_TICK=10
      +CONFIG_RR_INTERVAL=200
      +# CONFIG_SCHED_INSTRUMENTATION is not set
      +CONFIG_TASK_NAME_SIZE=0
      +# CONFIG_JULIAN_TIME is not set
      +CONFIG_START_YEAR=2009
      +CONFIG_START_MONTH=9
      +CONFIG_START_DAY=21
      +CONFIG_DEV_CONSOLE=y
      +CONFIG_DEV_LOWCONSOLE=y
      +# CONFIG_MUTEX_TYPES is not set
      +# CONFIG_PRIORITY_INHERITANCE is not set
      +# CONFIG_FDCLONE_DISABLE is not set
      +# CONFIG_FDCLONE_STDIO is not set
      +CONFIG_SDCLONE_DISABLE=y
      +# CONFIG_SCHED_WORKQUEUE is not set
      +# CONFIG_SCHED_WAITPID is not set
      +# CONFIG_SCHED_ATEXIT is not set
      +# CONFIG_SCHED_ONEXIT is not set
      +CONFIG_USER_ENTRYPOINT="ostest_main"
      +CONFIG_DISABLE_OS_API=y
      +# CONFIG_DISABLE_CLOCK is not set
      +# CONFIG_DISABLE_POSIX_TIMERS is not set
      +# CONFIG_DISABLE_PTHREAD is not set
      +# CONFIG_DISABLE_SIGNALS is not set
      +# CONFIG_DISABLE_MQUEUE is not set
      +CONFIG_DISABLE_MOUNTPOINT=y
      +CONFIG_DISABLE_ENVIRON=y
      +CONFIG_DISABLE_POLL=y
      +
      +#
      +# Sizes of configurable things (0 disables)
      +#
      +CONFIG_MAX_TASKS=16
      +CONFIG_MAX_TASK_ARGS=4
      +CONFIG_NPTHREAD_KEYS=4
      +CONFIG_NFILE_DESCRIPTORS=8
      +CONFIG_NFILE_STREAMS=8
      +CONFIG_NAME_MAX=32
      +CONFIG_PREALLOC_MQ_MSGS=4
      +CONFIG_MQ_MAXMSGSIZE=32
      +CONFIG_MAX_WDOGPARMS=2
      +CONFIG_PREALLOC_WDOGS=4
      +CONFIG_PREALLOC_TIMERS=4
      +
      +#
      +# Stack and heap information
      +#
      +# CONFIG_CUSTOM_STACK is not set
      +CONFIG_IDLETHREAD_STACKSIZE=1024
      +CONFIG_USERMAIN_STACKSIZE=2048
      +CONFIG_PTHREAD_STACK_MIN=256
      +CONFIG_PTHREAD_STACK_DEFAULT=2048
      +
      +#
      +# Device Drivers
      +#
      +CONFIG_DEV_NULL=y
      +# CONFIG_DEV_ZERO is not set
      +# CONFIG_LOOP is not set
      +# CONFIG_RAMDISK is not set
      +# CONFIG_CAN is not set
      +# CONFIG_PWM is not set
      +# CONFIG_I2C is not set
      +CONFIG_ARCH_HAVE_I2CRESET=y
      +# CONFIG_SPI is not set
      +# CONFIG_RTC is not set
      +# CONFIG_WATCHDOG is not set
      +# CONFIG_ANALOG is not set
      +# CONFIG_BCH is not set
      +# CONFIG_INPUT is not set
      +# CONFIG_LCD is not set
      +# CONFIG_MMCSD is not set
      +# CONFIG_MTD is not set
      +# CONFIG_PIPES is not set
      +# CONFIG_PM is not set
      +# CONFIG_POWER is not set
      +# CONFIG_SENSORS is not set
      +# CONFIG_SERCOMM_CONSOLE is not set
      +CONFIG_SERIAL=y
      +# CONFIG_LOWLEVEL_CONSOLE is not set
      +# CONFIG_16550_UART is not set
      +CONFIG_ARCH_HAVE_USART2=y
      +CONFIG_MCU_SERIAL=y
      +CONFIG_STANDARD_SERIAL=y
      +CONFIG_USART2_SERIAL_CONSOLE=y
      +# CONFIG_NO_SERIAL_CONSOLE is not set
      +
      +#
      +# USART2 Configuration
      +#
      +CONFIG_USART2_RXBUFSIZE=128
      +CONFIG_USART2_TXBUFSIZE=128
      +CONFIG_USART2_BAUD=115200
      +CONFIG_USART2_BITS=8
      +CONFIG_USART2_PARITY=0
      +CONFIG_USART2_2STOP=0
      +# CONFIG_USBDEV is not set
      +# CONFIG_USBHOST is not set
      +# CONFIG_WIRELESS is not set
      +
      +#
      +# System Logging Device Options
      +#
      +
      +#
      +# System Logging
      +#
      +# CONFIG_RAMLOG is not set
      +
      +#
      +# Networking Support
      +#
      +# CONFIG_NET is not set
      +
      +#
      +# File Systems
      +#
      +
      +#
      +# File system configuration
      +#
      +# CONFIG_FS_RAMMAP is not set
      +
      +#
      +# System Logging
      +#
      +# CONFIG_SYSLOG is not set
      +
      +#
      +# Graphics Support
      +#
      +# CONFIG_NX is not set
      +
      +#
      +# Memory Management
      +#
      +# CONFIG_MM_SMALL is not set
      +CONFIG_MM_REGIONS=2
      +# CONFIG_GRAN is not set
      +
      +#
      +# Binary Formats
      +#
      +# CONFIG_BINFMT_DISABLE is not set
      +# CONFIG_NXFLAT is not set
      +# CONFIG_ELF is not set
      +CONFIG_SYMTAB_ORDEREDBYNAME=y
      +
      +#
      +# Library Routines
      +#
      +CONFIG_STDIO_BUFFER_SIZE=256
      +CONFIG_STDIO_LINEBUFFER=y
      +CONFIG_NUNGET_CHARS=2
      +# CONFIG_LIBM is not set
      +# CONFIG_NOPRINTF_FIELDWIDTH is not set
      +# CONFIG_LIBC_FLOATINGPOINT is not set
      +# CONFIG_EOL_IS_CR is not set
      +# CONFIG_EOL_IS_LF is not set
      +# CONFIG_EOL_IS_BOTH_CRLF is not set
      +CONFIG_EOL_IS_EITHER_CRLF=y
      +# CONFIG_LIBC_STRERROR is not set
      +# CONFIG_LIBC_PERROR_STDOUT is not set
      +CONFIG_ARCH_LOWPUTC=y
      +CONFIG_LIB_SENDFILE_BUFSIZE=512
      +# CONFIG_ARCH_ROMGETC is not set
      +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
      +
      +#
      +# Basic CXX Support
      +#
      +# CONFIG_HAVE_CXX is not set
      +
      +#
      +# Application Configuration
      +#
      +
      +#
      +# Named Applications
      +#
      +# CONFIG_NAMEDAPP is not set
      +
      +#
      +# Examples
      +#
      +# CONFIG_EXAMPLES_BUTTONS is not set
      +# CONFIG_EXAMPLES_CAN is not set
      +# CONFIG_EXAMPLES_CDCACM is not set
      +# CONFIG_EXAMPLES_COMPOSITE is not set
      +# CONFIG_EXAMPLES_DHCPD is not set
      +# CONFIG_EXAMPLES_ELF is not set
      +# CONFIG_EXAMPLES_FTPC is not set
      +# CONFIG_EXAMPLES_FTPD is not set
      +# CONFIG_EXAMPLES_HELLO is not set
      +# CONFIG_EXAMPLES_HELLOXX is not set
      +# CONFIG_EXAMPLES_JSON is not set
      +# CONFIG_EXAMPLES_HIDKBD is not set
      +# CONFIG_EXAMPLES_IGMP is not set
      +# CONFIG_EXAMPLES_LCDRW is not set
      +# CONFIG_EXAMPLES_MM is not set
      +# CONFIG_EXAMPLES_MOUNT is not set
      +# CONFIG_EXAMPLES_MODBUS is not set
      +# CONFIG_EXAMPLES_NETTEST is not set
      +# CONFIG_EXAMPLES_NSH is not set
      +# CONFIG_EXAMPLES_NULL is not set
      +# CONFIG_EXAMPLES_NX is not set
      +# CONFIG_EXAMPLES_NXCONSOLE is not set
      +# CONFIG_EXAMPLES_NXFFS is not set
      +# CONFIG_EXAMPLES_NXFLAT is not set
      +# CONFIG_EXAMPLES_NXHELLO is not set
      +# CONFIG_EXAMPLES_NXIMAGE is not set
      +# CONFIG_EXAMPLES_NXLINES is not set
      +# CONFIG_EXAMPLES_NXTEXT is not set
      +CONFIG_EXAMPLES_OSTEST=y
      +# CONFIG_EXAMPLES_OSTEST_BUILTIN is not set
      +CONFIG_EXAMPLES_OSTEST_LOOPS=1
      +CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048
      +CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3
      +CONFIG_EXAMPLES_OSTEST_RR_RANGE=10000
      +CONFIG_EXAMPLES_OSTEST_RR_RUNS=10
      +# CONFIG_EXAMPLES_PASHELLO is not set
      +# CONFIG_EXAMPLES_PIPE is not set
      +# CONFIG_EXAMPLES_POLL is not set
      +# CONFIG_EXAMPLES_QENCODER is not set
      +# CONFIG_EXAMPLES_RGMP is not set
      +# CONFIG_EXAMPLES_ROMFS is not set
      +# CONFIG_EXAMPLES_SENDMAIL is not set
      +# CONFIG_EXAMPLES_SERLOOP is not set
      +# CONFIG_EXAMPLES_TELNETD is not set
      +# CONFIG_EXAMPLES_THTTPD is not set
      +# CONFIG_EXAMPLES_TIFF is not set
      +# CONFIG_EXAMPLES_TOUCHSCREEN is not set
      +# CONFIG_EXAMPLES_UDP is not set
      +# CONFIG_EXAMPLES_UIP is not set
      +# CONFIG_EXAMPLES_USBSERIAL is not set
      +# CONFIG_EXAMPLES_USBMSC is not set
      +# CONFIG_EXAMPLES_USBTERM is not set
      +# CONFIG_EXAMPLES_WATCHDOG is not set
      +# CONFIG_EXAMPLES_WLAN is not set
      +
      +#
      +# Interpreters
      +#
      +
      +#
      +# Interpreters
      +#
      +# CONFIG_FICL is not set
      +# CONFIG_PCODE is not set
      +
      +#
      +# Network Utilities
      +#
      +
      +#
      +# Networking Utilities
      +#
      +# CONFIG_NETUTILS_CODECS is not set
      +# CONFIG_NETUTILS_DHCPC is not set
      +# CONFIG_NETUTILS_DHCPD is not set
      +# CONFIG_NETUTILS_FTPC is not set
      +# CONFIG_NETUTILS_FTPD is not set
      +# CONFIG_NETUTILS_JSON is not set
      +# CONFIG_NETUTILS_RESOLV is not set
      +# CONFIG_NETUTILS_SMTP is not set
      +# CONFIG_NETUTILS_TELNETD is not set
      +# CONFIG_NETUTILS_TFTPC is not set
      +# CONFIG_NETUTILS_THTTPD is not set
      +# CONFIG_NETUTILS_UIPLIB is not set
      +# CONFIG_NETUTILS_WEBCLIENT is not set
      +
      +#
      +# ModBus
      +#
      +
      +#
      +# FreeModbus
      +#
      +# CONFIG_MODBUS is not set
      +
      +#
      +# NSH Library
      +#
      +# CONFIG_NSH_LIBRARY is not set
      +
      +#
      +# NxWidgets/NxWM
      +#
      +
      +#
      +# System NSH Add-Ons
      +#
      +
      +#
      +# Custom Free Memory Command
      +#
      +# CONFIG_SYSTEM_FREE is not set
      +
      +#
      +# I2C tool
      +#
      +
      +#
      +# FLASH Program Installation
      +#
      +# CONFIG_SYSTEM_INSTALL is not set
      +
      +#
      +# readline()
      +#
      +# CONFIG_SYSTEM_READLINE is not set
      +
      +#
      +# Power Off
      +#
      +# CONFIG_SYSTEM_POWEROFF is not set
      +
      +#
      +# RAMTRON
      +#
      +# 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/stm32f4discovery/winbuild/setenv.bat b/nuttx/configs/stm32f4discovery/winbuild/setenv.bat
      new file mode 100755
      index 0000000000..e2196a90a0
      --- /dev/null
      +++ b/nuttx/configs/stm32f4discovery/winbuild/setenv.bat
      @@ -0,0 +1,48 @@
      +rem configs/stm32f4discovery/winbuild/setenv.sh
      +rem
      +rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
      +rem   Author: Gregory Nutt 
      +rem
      +rem Redistribution and use in source and binary forms, with or without
      +rem modification, are permitted provided that the following conditions
      +rem are met:
      +rem
      +rem 1. Redistributions of source code must retain the above copyright
      +rem    notice, this list of conditions and the following disclaimer.
      +rem 2. Redistributions in binary form must reproduce the above copyright
      +rem    notice, this list of conditions and the following disclaimer in
      +rem    the documentation and/or other materials provided with the
      +rem    distribution.
      +rem 3. Neither the name NuttX nor the names of its contributors may be
      +rem    used to endorse or promote products derived from this software
      +rem    without specific prior written permission.
      +rem
      +rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
      +rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
      +rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
      +rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
      +rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
      +rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
      +rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
      +rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
      +rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
      +rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
      +rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
      +rem POSSIBILITY OF SUCH DAMAGE.
      +
      +rem This is the location where I installed in the MinGW compiler. With
      +rem this configuration, it is recommended that you do NOT install the
      +rem MSYS tools; they conflict with the GNUWin32 tools.  See
      +rem http://www.mingw.org/ for further info.
      +
      +set PATH=C:\MinGW\bin;%PATH%
      +
      +rem This is the location where I installed the CodeSourcey toolchain.  See
      +rem http://www.mentor.com/embedded-software/codesourcery
      +
      +set PATH=C:\Program Files (x86)\CodeSourcery\Sourcery G++ Lite\bin;%PATH%
      +
      +rem This is the location where I installed the GNUWin32 tools.  See
      +rem http://gnuwin32.sourceforge.net/.
      +
      +set PATH=C:\gnuwin32\bin;%PATH%
      diff --git a/nuttx/configs/z16f2800100zcog/ostest/Make.defs b/nuttx/configs/z16f2800100zcog/ostest/Make.defs
      index 8440224cab..7f86dd29fa 100644
      --- a/nuttx/configs/z16f2800100zcog/ostest/Make.defs
      +++ b/nuttx/configs/z16f2800100zcog/ostest/Make.defs
      @@ -146,10 +146,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lst
      diff --git a/nuttx/configs/z16f2800100zcog/pashello/Make.defs b/nuttx/configs/z16f2800100zcog/pashello/Make.defs
      index 1c3e277ad9..92a67fa652 100644
      --- a/nuttx/configs/z16f2800100zcog/pashello/Make.defs
      +++ b/nuttx/configs/z16f2800100zcog/pashello/Make.defs
      @@ -146,10 +146,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lst
      diff --git a/nuttx/configs/z8encore000zco/ostest/Make.defs b/nuttx/configs/z8encore000zco/ostest/Make.defs
      index cf310e0ff4..23185e2dd0 100644
      --- a/nuttx/configs/z8encore000zco/ostest/Make.defs
      +++ b/nuttx/configs/z8encore000zco/ostest/Make.defs
      @@ -172,10 +172,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lst
      diff --git a/nuttx/configs/z8f64200100kit/ostest/Make.defs b/nuttx/configs/z8f64200100kit/ostest/Make.defs
      index 894df0855f..1ee00c72c0 100644
      --- a/nuttx/configs/z8f64200100kit/ostest/Make.defs
      +++ b/nuttx/configs/z8f64200100kit/ostest/Make.defs
      @@ -172,10 +172,19 @@ define ASSEMBLE
       	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $(ARFLAGS) $1=-+$2 || { echo "$(AR) $1=-+$2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2";
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
       endef
      +else
      +define ARCHIVE
      +	$(Q) for __obj in $(2); do \
      +		echo "AR: $(__obj)"; \
      +		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	done
      +endef
      +endif
       
       define CLEAN
       	@rm -f *.obj *.src *.lib *.hex *.lst
      diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
      index 53e9cb12c6..a57285505c 100644
      --- a/nuttx/drivers/Makefile
      +++ b/nuttx/drivers/Makefile
      @@ -105,16 +105,16 @@ $(BIN):	$(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) $(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@rm -f $(BIN) *~ .*.swp
      +	$(Q) rm -f $(BIN) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@rm -f Make.dep .depend
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile
      index cb530cbec3..643b322bb8 100644
      --- a/nuttx/fs/Makefile
      +++ b/nuttx/fs/Makefile
      @@ -123,20 +123,20 @@ $(BIN):	$(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) --dep-path . $(MMAPDEPPATH) $(FATDEPPATH) $(ROMFSDEPPATH) $(NXFFSDEPPATH) $(NFSDEPPATH) \
      +	$(Q) $(MKDEP) --dep-path . $(MMAPDEPPATH) $(FATDEPPATH) $(ROMFSDEPPATH) $(NXFFSDEPPATH) $(NFSDEPPATH) \
       		$(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@rm -f $(BIN) *~ .*.swp
      +	$(Q) rm -f $(BIN) *~ .*.swp
       	$(call CLEAN)
      -	@( for dir in $(SUBDIRS); do \
      +	$(Q) ( for dir in $(SUBDIRS); do \
       		rm -f $${dir}/*~ $${dir}/.*.swp; \
       	done ; )
       
       distclean: clean
      -	@rm -f Make.dep .depend
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/graphics/Makefile b/nuttx/graphics/Makefile
      index 27edbb411b..f3a768113a 100644
      --- a/nuttx/graphics/Makefile
      +++ b/nuttx/graphics/Makefile
      @@ -97,84 +97,84 @@ all:	mklibgraphics
       	 gen32bppsources genfontsources
       
       gen1bppsources:
      -	@$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=1 EXTRADEFINES=$(EXTRADEFINES)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=1 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=1 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=1 EXTRADEFINES=$(EXTRADEFINES)
       
       gen2bppsource:
      -	@$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=2 EXTRADEFINES=$(EXTRADEFINES)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=2 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=2 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=2 EXTRADEFINES=$(EXTRADEFINES)
       
       gen4bppsource:
      -	@$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=4 EXTRADEFINES=$(EXTRADEFINES)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=4 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=4 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=4 EXTRADEFINES=$(EXTRADEFINES)
       
       gen8bppsource:
      -	@$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=8 EXTRADEFINES=$(EXTRADEFINES)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=8 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=8 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=8 EXTRADEFINES=$(EXTRADEFINES)
       
       gen16bppsource:
      -	@$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=16 EXTRADEFINES=$(EXTRADEFINES)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=16 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=16 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=16 EXTRADEFINES=$(EXTRADEFINES)
       
       gen24bppsource:
      -	@$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=24 EXTRADEFINES=$(EXTRADEFINES)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=24 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=24 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=24 EXTRADEFINES=$(EXTRADEFINES)
       
       gen32bppsources:
      -	@$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=32 EXTRADEFINES=$(EXTRADEFINES)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=32 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=32 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=32 EXTRADEFINES=$(EXTRADEFINES)
       
       genfontsources:
       ifeq ($(CONFIG_NXFONT_SANS23X27),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=1 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=1 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SANS22X29),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=2 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=2 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SANS28X37),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=3 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=3 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SANS39X48),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=4 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=4 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SANS17X23B),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=16 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=16 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SANS20X27B),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=17 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=17 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SANS22X29B),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=5 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=5 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SANS28X37B),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=6 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=6 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SANS40X49B),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=7 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=7 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SERIF22X29),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=8 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=8 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SERIF29X37),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=9 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=9 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SERIF38X48),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=10 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=10 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SERIF22X28B),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=11 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=11 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SERIF27X38B),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=12 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=12 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SERIF38X49B),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=13 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=13 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SANS17X22),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=14 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=14 EXTRADEFINES=$(EXTRADEFINES)
       endif
       ifeq ($(CONFIG_NXFONT_SANS20X26),y)
      -	@$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=15 EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=15 EXTRADEFINES=$(EXTRADEFINES)
       endif
       
       gensources: gen1bppsources gen2bppsource gen4bppsource gen8bppsource gen16bppsource gen24bppsource gen32bppsources genfontsources
      @@ -191,23 +191,23 @@ $(BIN): $(OBJS)
       mklibgraphics: gensources $(BIN)
       
       .depend: gensources Makefile $(SRCS)
      -	@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) $(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) touch $@
       
       depend: .depend
       
       context: gensources
       
       clean:
      -	@$(MAKE) -C nxglib -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      -	@$(MAKE) -C nxfonts -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      -	@rm -f $(BIN) *~ .*.swp
      +	$(Q) $(MAKE) -C nxglib -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) rm -f $(BIN) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@$(MAKE) -C nxglib -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      -	@$(MAKE) -C nxfonts -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      -	@rm -f Make.dep .depend
      +	$(Q) $(MAKE) -C nxglib -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C nxfonts -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
       
      diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile
      index d4e24124a0..dca8ea035a 100644
      --- a/nuttx/lib/Makefile
      +++ b/nuttx/lib/Makefile
      @@ -40,6 +40,6 @@ all:
       depend:
       
       clean:
      -	@rm -f *$(LIBEXT)
      +	$(Q) rm -f *$(LIBEXT)
       
       distclean: clean
      diff --git a/nuttx/libc/Makefile b/nuttx/libc/Makefile
      index 9449915552..0e11c9bad2 100644
      --- a/nuttx/libc/Makefile
      +++ b/nuttx/libc/Makefile
      @@ -83,23 +83,23 @@ $(BIN): $(OBJS)
       
       ifneq ($(BIN),$(UBIN))
       .userlib:
      -	@$(MAKE) $(UBIN) BIN=$(UBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      -	@touch .userlib
      +	$(Q) $(MAKE) $(UBIN) BIN=$(UBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) touch .userlib
       
       $(UBIN): kclean .userlib
       endif
       
       ifneq ($(BIN),$(KBIN))
       .kernlib:
      -	@$(MAKE) $(KBIN) BIN=$(KBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      -	@touch .kernlib
      +	$(Q) $(MAKE) $(KBIN) BIN=$(KBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) touch .kernlib
       
       $(KBIN): uclean .kernlib
       endif
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) $(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) touch $@
       
       depend: .depend
       
      @@ -108,27 +108,27 @@ depend: .depend
       
       uclean:
       ifneq ($(OBJEXT),)
      -	@( if [ -f .userlib ]; then rm -f *$(OBJEXT); fi )
      +	$(Q) ( if [ -f .userlib ]; then rm -f *$(OBJEXT); fi )
       endif
      -	@rm -f .userlib *~ .*.swp
      +	$(Q) rm -f .userlib *~ .*.swp
       
       # Clean kernel-mode temporary files (retaining the KBIN binary)
       
       kclean:
       ifneq ($(OBJEXT),)
      -	@( if [ -f .kernlib ]; then rm -f *$(OBJEXT); fi )
      +	$(Q) ( if [ -f .kernlib ]; then rm -f *$(OBJEXT); fi )
       endif
      -	@rm -f .kernlib *~ .*.swp
      +	$(Q) rm -f .kernlib *~ .*.swp
       
       # Really clean everything
       
       clean: uclean kclean
      -	@rm -f $(BIN) $(UBIN) $(KBIN) *~ .*.swp
      +	$(Q) rm -f $(BIN) $(UBIN) $(KBIN) *~ .*.swp
       	$(call CLEAN)
       
       # Deep clean -- removes all traces of the configuration
       
       distclean: clean
      -	@rm -f Make.dep .depend
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile
      index a69527c28e..bdbc5da872 100644
      --- a/nuttx/libxx/Makefile
      +++ b/nuttx/libxx/Makefile
      @@ -99,16 +99,16 @@ $(BIN):	$(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(DEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) $(MKDEP) $(DEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@rm -f $(BIN) *~ .*.swp
      +	$(Q) rm -f $(BIN) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@rm -f Make.dep .depend
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile
      index d0c5048b42..b48d242ffd 100644
      --- a/nuttx/mm/Makefile
      +++ b/nuttx/mm/Makefile
      @@ -37,8 +37,8 @@
       
       ASRCS	= 
       CSRCS	= mm_initialize.c mm_sem.c  mm_addfreechunk.c mm_size2ndx.c mm_shrinkchunk.c \
      -	  mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c \
      -	  mm_memalign.c mm_free.c mm_mallinfo.c
      +		mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c \
      +		mm_memalign.c mm_free.c mm_mallinfo.c
       
       ifeq ($(CONFIG_GRAN),y)
       CSRCS	+= mm_graninit.c mm_granalloc.c mm_granfree.c mm_grancritical.c
      @@ -64,16 +64,16 @@ $(BIN):	$(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@rm -f $(BIN) *~ .*.swp
      +	$(Q) rm -f $(BIN) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@rm -f Make.dep .depend
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
      index 42759e643e..2a43914901 100644
      --- a/nuttx/net/Makefile
      +++ b/nuttx/net/Makefile
      @@ -104,18 +104,18 @@ $(BIN): $(OBJS)
       
       .depend: Makefile $(SRCS)
       ifeq ($(CONFIG_NET),y)
      -	@$(MKDEP) --dep-path . --dep-path uip $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) $(MKDEP) --dep-path . --dep-path uip $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
       endif
      -	@touch $@
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@rm -f $(BIN) *~ .*.swp
      -	@rm -f uip/*~ uip/.*.swp
      +	$(Q) rm -f $(BIN) *~ .*.swp
      +	$(Q) rm -f uip/*~ uip/.*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@rm -f Make.dep .depend
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
      index cbce639e73..6487c5701f 100644
      --- a/nuttx/sched/Makefile
      +++ b/nuttx/sched/Makefile
      @@ -199,16 +199,16 @@ $(BIN): $(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@rm -f $(BIN) *~ .*.swp
      +	$(Q) rm -f $(BIN) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@rm -f Make.dep .depend
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/syscall/Makefile b/nuttx/syscall/Makefile
      index 7d493665ad..e9370a7763 100644
      --- a/nuttx/syscall/Makefile
      +++ b/nuttx/syscall/Makefile
      @@ -78,32 +78,32 @@ $(BIN2): $(STUB_OBJS)
       	$(call ARCHIVE, $@, "$(STUB_OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(PROXYDEPPATH) $(STUBDEPPATH) \
      +	$(Q) $(MKDEP) $(ROOTDEPPATH) $(PROXYDEPPATH) $(STUBDEPPATH) \
       	  $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) touch $@
       
       depend: .depend
       
       $(MKSYSCALL):
      -	@$(MAKE) -C $(TOPDIR)/tools -f Makefile.host mksyscall
      +	$(Q) $(MAKE) -C $(TOPDIR)/tools -f Makefile.host mksyscall
       
       .context: syscall.csv
      -	@(cd proxies; $(MKSYSCALL) -p $(CSVFILE);)
      -	@(cd stubs; $(MKSYSCALL) -s $(CSVFILE);)
      -	@touch $@
      +	$(Q) (cd proxies; $(MKSYSCALL) -p $(CSVFILE);)
      +	$(Q) (cd stubs; $(MKSYSCALL) -s $(CSVFILE);)
      +	$(Q) touch $@
       
       context: $(MKSYSCALL) .context
       
       clean:
      -	@rm -f $(BIN1) $(BIN2) *~ .*.swp
      +	$(Q) rm -f $(BIN1) $(BIN2) *~ .*.swp
       ifneq ($(OBJEXT),)
      -	@rm -f proxies/*$(OBJEXT) stubs/*$(OBJEXT)
      +	$(Q) rm -f proxies/*$(OBJEXT) stubs/*$(OBJEXT)
       endif
       	$(call CLEAN)
       
       distclean: clean
      -	@rm -f Make.dep .depend .context
      -	@rm -f proxies/*.c stubs/*.c
      +	$(Q) rm -f Make.dep .depend .context
      +	$(Q) rm -f proxies/*.c stubs/*.c
       
       -include Make.dep
       
      diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk
      index 3a82a19377..47131b8007 100644
      --- a/nuttx/tools/Config.mk
      +++ b/nuttx/tools/Config.mk
      @@ -62,10 +62,18 @@ define ASSEMBLE
       	$(Q) $(CC) -c $(AFLAGS) $1 -o $2
       endef
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"; \
      -	$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
      +	echo "AR: $2"
      +	$(AR) $1
      +	$(AR) $1 $(subst ",,$(2))
       endef
      +else
      +define ARCHIVE
      +	echo "AR: $2"
      +	$(AR) $1 $(subst ",,$(2)) || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
      +endef
      +endif
       
       define CLEAN
       	$(Q) rm -f *.o *.a
      diff --git a/nuttx/tools/Makefile.export b/nuttx/tools/Makefile.export
      index ce4842187a..95a33b7796 100644
      --- a/nuttx/tools/Makefile.export
      +++ b/nuttx/tools/Makefile.export
      @@ -61,7 +61,7 @@ endif
       	@echo "ARCHCFLAGS=\"$(ARCHCFLAGS) $(ARCHCPUFLAGS)\"" >> $(EXPORTDIR)/makeinfo.sh
       	@echo "ARCHCXXFLAGS=\"$(ARCHCXXFLAGS) $(ARCHCPUFLAGS)\"" >> $(EXPORTDIR)/makeinfo.sh
       	@echo "CROSSDEV=\"$(CROSSDEV)\"" >> $(EXPORTDIR)/makeinfo.sh
      -	@chmod 755 $(EXPORTDIR)/makeinfo.sh
      +	$(Q) chmod 755 $(EXPORTDIR)/makeinfo.sh
       
       clean:
      -	@rm -f $(EXPORTDIR)/makeinfo.sh
      +	$(Q) rm -f $(EXPORTDIR)/makeinfo.sh
      diff --git a/nuttx/tools/Makefile.host b/nuttx/tools/Makefile.host
      index 33b7aaab2b..66bea9937b 100644
      --- a/nuttx/tools/Makefile.host
      +++ b/nuttx/tools/Makefile.host
      @@ -44,34 +44,34 @@ CFLAGS = -O2 -Wall -I.
       # mkconfig - Convert a .config file into a C config.h file
       
       mkconfig: mkconfig.c cfgparser.c
      -	@gcc $(CFLAGS) -o mkconfig mkconfig.c cfgparser.c
      +	$(Q) gcc $(CFLAGS) -o mkconfig mkconfig.c cfgparser.c
       
       # cmpconfig - Compare the contents of two configuration files
       
       cmpconfig: cmpconfig.c
      -	@gcc $(CFLAGS) -o cmpconfig cmpconfig.c
      +	$(Q) gcc $(CFLAGS) -o cmpconfig cmpconfig.c
       
       # mkversion - Convert a .version file into a C version.h file
       
       mkversion: mkconfig.c cfgparser.c
      -	@gcc $(CFLAGS) -o mkversion mkversion.c cfgparser.c
      +	$(Q) gcc $(CFLAGS) -o mkversion mkversion.c cfgparser.c
       
       # mksyscall - Convert a CSV file into syscall stubs and proxies
       
       mksyscall: mksyscall.c csvparser.c
      -	@gcc $(CFLAGS) -o mksyscall mksyscall.c csvparser.c
      +	$(Q) gcc $(CFLAGS) -o mksyscall mksyscall.c csvparser.c
       
       # mksymtab - Convert a CSV file into a symbol table
       
       mksymtab: mksymtab.c csvparser.c
      -	@gcc $(CFLAGS) -o mksymtab mksymtab.c csvparser.c
      +	$(Q) gcc $(CFLAGS) -o mksymtab mksymtab.c csvparser.c
       
       # bdf-converter - Converts a BDF font to the NuttX font format
       
       bdf-converter: bdf-converter.c
      -	@gcc $(CFLAGS) -o bdf-converter bdf-converter.c
      +	$(Q) gcc $(CFLAGS) -o bdf-converter bdf-converter.c
       
       clean:
      -	@rm -f *.o *.a *~ .*.swp
      -	@rm -f mkconfig mksyscall mkversion bdf-converter
      -	@rm -f mkconfig.exe mksyscall.exe mkversion.exe bdf-converter.exe
      +	$(Q) rm -f *.o *.a *~ .*.swp
      +	$(Q) rm -f mkconfig mksyscall mkversion bdf-converter
      +	$(Q) rm -f mkconfig.exe mksyscall.exe mkversion.exe bdf-converter.exe
      
      From 63e8e1bed383170be61d722348be7efcf1a33ec3 Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Sun, 11 Nov 2012 23:44:31 +0000
      Subject: [PATCH 108/206] Correct some issues with last check-in; ez80 still
       does not build
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5339 42af7a65-404d-4744-a932-0658087f49c3
      ---
       apps/examples/adc/Makefile                    |   4 +-
       apps/examples/buttons/Makefile                |   4 +-
       apps/examples/can/Makefile                    |   4 +-
       apps/examples/cdcacm/Makefile                 |   4 +-
       apps/examples/composite/Makefile              |   4 +-
       apps/examples/cxxtest/Makefile                |   4 +-
       apps/examples/dhcpd/Makefile                  |   4 +-
       apps/examples/discover/Makefile               |   4 +-
       apps/examples/elf/Makefile                    |   2 +-
       apps/examples/ftpc/Makefile                   |   4 +-
       apps/examples/ftpd/Makefile                   |   4 +-
       apps/examples/hello/Makefile                  |   4 +-
       apps/examples/helloxx/Makefile                |   4 +-
       apps/examples/hidkbd/Makefile                 |   4 +-
       apps/examples/igmp/Makefile                   |   4 +-
       apps/examples/json/Makefile                   |   4 +-
       apps/examples/lcdrw/Makefile                  |   4 +-
       apps/examples/mm/Makefile                     |   4 +-
       apps/examples/modbus/Makefile                 |   4 +-
       apps/examples/mount/Makefile                  |   4 +-
       apps/examples/nettest/Makefile                |   4 +-
       apps/examples/nsh/Makefile                    |   4 +-
       apps/examples/null/Makefile                   |   4 +-
       apps/examples/nx/Makefile                     |   4 +-
       apps/examples/nxconsole/Makefile              |   4 +-
       apps/examples/nxffs/Makefile                  |   4 +-
       apps/examples/nxflat/Makefile                 |   2 +-
       apps/examples/nxhello/Makefile                |   4 +-
       apps/examples/nximage/Makefile                |   4 +-
       apps/examples/nxlines/Makefile                |   4 +-
       apps/examples/nxtext/Makefile                 |   4 +-
       apps/examples/ostest/Makefile                 |   4 +-
       apps/examples/pashello/Makefile               |   4 +-
       apps/examples/pipe/Makefile                   |   4 +-
       apps/examples/poll/Makefile                   |   4 +-
       apps/examples/pwm/Makefile                    |   4 +-
       apps/examples/qencoder/Makefile               |   4 +-
       apps/examples/relays/Makefile                 |   4 +-
       apps/examples/rgmp/Makefile                   |   4 +-
       apps/examples/romfs/Makefile                  |   4 +-
       apps/examples/sendmail/Makefile               |   4 +-
       apps/examples/serloop/Makefile                |   4 +-
       apps/examples/telnetd/Makefile                |   4 +-
       apps/examples/thttpd/Makefile                 |   4 +-
       apps/examples/tiff/Makefile                   |   4 +-
       apps/examples/touchscreen/Makefile            |   4 +-
       apps/examples/udp/Makefile                    |   2 +-
       apps/examples/uip/Makefile                    |   4 +-
       apps/examples/usbserial/Makefile              |   4 +-
       apps/examples/usbstorage/Makefile             |   4 +-
       apps/examples/usbterm/Makefile                |   4 +-
       apps/examples/watchdog/Makefile               |   4 +-
       apps/examples/wget/Makefile                   |   4 +-
       apps/examples/wgetjson/Makefile               |   4 +-
       apps/examples/wlan/Makefile                   |   4 +-
       apps/examples/xmlrpc/Makefile                 |   4 +-
       apps/graphics/tiff/Makefile                   |   4 +-
       apps/interpreters/ficl/Makefile               |   4 +-
       apps/modbus/Makefile                          |   5 +-
       apps/namedapp/Makefile                        |  22 +--
       apps/netutils/codecs/Makefile                 |   4 +-
       apps/netutils/dhcpc/Makefile                  |   4 +-
       apps/netutils/dhcpd/Makefile                  |   4 +-
       apps/netutils/discover/Makefile               |   4 +-
       apps/netutils/ftpc/Makefile                   |   4 +-
       apps/netutils/ftpd/Makefile                   |   4 +-
       apps/netutils/json/Makefile                   |   4 +-
       apps/netutils/resolv/Makefile                 |   4 +-
       apps/netutils/smtp/Makefile                   |   4 +-
       apps/netutils/telnetd/Makefile                |   4 +-
       apps/netutils/tftpc/Makefile                  |   4 +-
       apps/netutils/thttpd/Makefile                 |   4 +-
       apps/netutils/uiplib/Makefile                 |   4 +-
       apps/netutils/webclient/Makefile              |   4 +-
       apps/netutils/webserver/Makefile              |   4 +-
       apps/netutils/xmlrpc/Makefile                 |   4 +-
       apps/nshlib/Makefile                          |   5 +-
       apps/system/free/Makefile                     |   4 +-
       apps/system/i2c/Makefile                      |   5 +-
       apps/system/install/Makefile                  |   4 +-
       apps/system/poweroff/Makefile                 |   4 +-
       apps/system/ramtron/Makefile                  |   4 +-
       apps/system/readline/Makefile                 |   4 +-
       apps/system/sdcard/Makefile                   |   4 +-
       apps/system/sysinfo/Makefile                  |   4 +-
       nuttx/Makefile                                |   2 +-
       nuttx/arch/8051/src/Makefile                  |   8 +-
       nuttx/arch/arm/src/Makefile                   |  28 ++--
       nuttx/arch/avr/src/Makefile                   |  28 ++--
       nuttx/arch/hc/src/Makefile                    |  28 ++--
       nuttx/arch/mips/src/Makefile                  |  28 ++--
       nuttx/arch/rgmp/src/Makefile                  |   4 +-
       nuttx/arch/sh/src/Makefile                    |  30 ++--
       nuttx/arch/sim/src/Makefile                   |  10 +-
       nuttx/arch/x86/src/Makefile                   |  28 ++--
       nuttx/arch/z16/src/Makefile                   |   6 +-
       nuttx/arch/z80/src/Makefile                   |   2 +-
       nuttx/arch/z80/src/Makefile.sdcc              |  46 ++---
       nuttx/arch/z80/src/Makefile.zdsii             |  34 ++--
       nuttx/binfmt/Makefile                         |   2 +-
       .../configs/ez80f910200kitg/ostest/Make.defs  |  52 +++---
       nuttx/configs/ez80f910200kitg/src/Makefile    |   2 +-
       nuttx/configs/ez80f910200zco/dhcpd/Make.defs  |  54 +++---
       nuttx/configs/ez80f910200zco/dhcpd/setenv.sh  |  14 +-
       nuttx/configs/ez80f910200zco/httpd/Make.defs  |  54 +++---
       nuttx/configs/ez80f910200zco/httpd/setenv.sh  |  14 +-
       .../configs/ez80f910200zco/nettest/Make.defs  |  54 +++---
       .../configs/ez80f910200zco/nettest/setenv.sh  |  14 +-
       nuttx/configs/ez80f910200zco/nsh/Make.defs    |  54 +++---
       nuttx/configs/ez80f910200zco/nsh/setenv.sh    |  14 +-
       nuttx/configs/ez80f910200zco/ostest/Make.defs | 158 ++++++++++--------
       nuttx/configs/ez80f910200zco/ostest/setenv.sh |  14 +-
       nuttx/configs/ez80f910200zco/poll/Make.defs   |  54 +++---
       nuttx/configs/ez80f910200zco/poll/setenv.sh   |  14 +-
       nuttx/configs/ez80f910200zco/src/Makefile     |   2 +-
       .../configs/z16f2800100zcog/ostest/Make.defs  |  49 +++---
       .../z16f2800100zcog/pashello/Make.defs        |  31 ++--
       nuttx/configs/z16f2800100zcog/src/Makefile    |   2 +-
       nuttx/configs/z8encore000zco/ostest/Make.defs |  62 ++++---
       nuttx/configs/z8encore000zco/src/Makefile     |   2 +-
       nuttx/configs/z8f64200100kit/ostest/Make.defs |  62 ++++---
       nuttx/configs/z8f64200100kit/src/Makefile     |   2 +-
       nuttx/drivers/Makefile                        |   2 +-
       nuttx/fs/Makefile                             |   2 +-
       nuttx/graphics/Makefile                       |   2 +-
       nuttx/libc/Makefile                           |   2 +-
       nuttx/libxx/Makefile                          |   2 +-
       nuttx/mm/Makefile                             |   2 +-
       nuttx/net/Makefile                            |   2 +-
       nuttx/sched/Makefile                          |   2 +-
       nuttx/syscall/Makefile                        |   2 +-
       nuttx/tools/Config.mk                         |   8 +-
       132 files changed, 779 insertions(+), 664 deletions(-)
      
      diff --git a/apps/examples/adc/Makefile b/apps/examples/adc/Makefile
      index 7b5259716f..fab1a91ab0 100644
      --- a/apps/examples/adc/Makefile
      +++ b/apps/examples/adc/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/buttons/Makefile b/apps/examples/buttons/Makefile
      index c050434803..780941562d 100644
      --- a/apps/examples/buttons/Makefile
      +++ b/apps/examples/buttons/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/can/Makefile b/apps/examples/can/Makefile
      index d5c7a04efb..35c7538f3b 100644
      --- a/apps/examples/can/Makefile
      +++ b/apps/examples/can/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/cdcacm/Makefile b/apps/examples/cdcacm/Makefile
      index 71cd2f3afb..3ffdf82b4e 100644
      --- a/apps/examples/cdcacm/Makefile
      +++ b/apps/examples/cdcacm/Makefile
      @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -91,7 +91,7 @@ $(COBJS): %$(OBJEXT): %.c
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/composite/Makefile b/apps/examples/composite/Makefile
      index 80292dbfa2..a8563ee61b 100644
      --- a/apps/examples/composite/Makefile
      +++ b/apps/examples/composite/Makefile
      @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -93,7 +93,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/cxxtest/Makefile b/apps/examples/cxxtest/Makefile
      index ac70a34f95..a2c29169f0 100644
      --- a/apps/examples/cxxtest/Makefile
      +++ b/apps/examples/cxxtest/Makefile
      @@ -93,7 +93,7 @@ $(CXXOBJS): %$(OBJEXT): %.cxx
       	$(call COMPILEXX, $<, $@)
       
       .built: chkcxx $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -105,7 +105,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CXX)" -- $(CXXFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/dhcpd/Makefile b/apps/examples/dhcpd/Makefile
      index ceaa3b0224..8b39c58d46 100644
      --- a/apps/examples/dhcpd/Makefile
      +++ b/apps/examples/dhcpd/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/discover/Makefile b/apps/examples/discover/Makefile
      index a3e90399c4..f4801c569d 100644
      --- a/apps/examples/discover/Makefile
      +++ b/apps/examples/discover/Makefile
      @@ -77,7 +77,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -89,7 +89,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/elf/Makefile b/apps/examples/elf/Makefile
      index ab49532c80..1c7ac4a238 100644
      --- a/apps/examples/elf/Makefile
      +++ b/apps/examples/elf/Makefile
      @@ -75,7 +75,7 @@ $(COBJS): %$(OBJEXT): %.c
       # generating the source files.
       
       really_build: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .built:
      diff --git a/apps/examples/ftpc/Makefile b/apps/examples/ftpc/Makefile
      index ca630c8143..96ed512e24 100644
      --- a/apps/examples/ftpc/Makefile
      +++ b/apps/examples/ftpc/Makefile
      @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       # Register application
      @@ -88,7 +88,7 @@ context: .context
       # Create dependencies
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/ftpd/Makefile b/apps/examples/ftpd/Makefile
      index bf0e435d7a..f6bab4f403 100644
      --- a/apps/examples/ftpd/Makefile
      +++ b/apps/examples/ftpd/Makefile
      @@ -71,7 +71,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -84,7 +84,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/hello/Makefile b/apps/examples/hello/Makefile
      index dc9c6c25c5..a556e6f0f3 100644
      --- a/apps/examples/hello/Makefile
      +++ b/apps/examples/hello/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/helloxx/Makefile b/apps/examples/helloxx/Makefile
      index 63da0bde39..de9b1cf9fe 100644
      --- a/apps/examples/helloxx/Makefile
      +++ b/apps/examples/helloxx/Makefile
      @@ -93,7 +93,7 @@ $(CXXOBJS): %$(OBJEXT): %.cxx
       	$(call COMPILEXX, $<, $@)
       
       .built: chkcxx $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -105,7 +105,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/hidkbd/Makefile b/apps/examples/hidkbd/Makefile
      index bd060d83a1..36762825c7 100644
      --- a/apps/examples/hidkbd/Makefile
      +++ b/apps/examples/hidkbd/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/igmp/Makefile b/apps/examples/igmp/Makefile
      index f6a171d495..cf65c41bd8 100644
      --- a/apps/examples/igmp/Makefile
      +++ b/apps/examples/igmp/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/json/Makefile b/apps/examples/json/Makefile
      index 9c3ac61b64..0880193ad6 100644
      --- a/apps/examples/json/Makefile
      +++ b/apps/examples/json/Makefile
      @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -86,7 +86,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/lcdrw/Makefile b/apps/examples/lcdrw/Makefile
      index c0b6efb8db..0de93c9e9a 100644
      --- a/apps/examples/lcdrw/Makefile
      +++ b/apps/examples/lcdrw/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/mm/Makefile b/apps/examples/mm/Makefile
      index e73cd9baa3..aff99d4609 100644
      --- a/apps/examples/mm/Makefile
      +++ b/apps/examples/mm/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/modbus/Makefile b/apps/examples/modbus/Makefile
      index 78ea568d02..10abd8780d 100644
      --- a/apps/examples/modbus/Makefile
      +++ b/apps/examples/modbus/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/mount/Makefile b/apps/examples/mount/Makefile
      index fd6a4b963a..d19f2894ae 100644
      --- a/apps/examples/mount/Makefile
      +++ b/apps/examples/mount/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/nettest/Makefile b/apps/examples/nettest/Makefile
      index 09a7c42ddc..979a2391ee 100644
      --- a/apps/examples/nettest/Makefile
      +++ b/apps/examples/nettest/Makefile
      @@ -112,7 +112,7 @@ $(HOST_BIN): $(HOST_OBJS)
       	@$(HOSTCC) $(HOSTLDFLAGS) $(HOST_OBJS) -o $@
       
       .built: $(TARG_OBJS)
      -	$(call ARCHIVE, $@, "$(TARG_OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(TARG_OBJS)")
       	@touch .built
       
       .context:
      @@ -124,7 +124,7 @@ endif
       context: .context
       
       .depend: Makefile $(TARG_SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(TARG_SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(TARG_SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/nsh/Makefile b/apps/examples/nsh/Makefile
      index b0efd9aa1b..600ea7090b 100644
      --- a/apps/examples/nsh/Makefile
      +++ b/apps/examples/nsh/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/null/Makefile b/apps/examples/null/Makefile
      index 6234f77ea6..baa9ac2c37 100644
      --- a/apps/examples/null/Makefile
      +++ b/apps/examples/null/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/nx/Makefile b/apps/examples/nx/Makefile
      index 6b670d83de..d8befe5580 100644
      --- a/apps/examples/nx/Makefile
      +++ b/apps/examples/nx/Makefile
      @@ -79,7 +79,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -91,7 +91,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/nxconsole/Makefile b/apps/examples/nxconsole/Makefile
      index a478e6bded..bbbf678128 100644
      --- a/apps/examples/nxconsole/Makefile
      +++ b/apps/examples/nxconsole/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/nxffs/Makefile b/apps/examples/nxffs/Makefile
      index 28c869e16c..2ae286cd07 100644
      --- a/apps/examples/nxffs/Makefile
      +++ b/apps/examples/nxffs/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/nxflat/Makefile b/apps/examples/nxflat/Makefile
      index e8a15a859c..3a34f1fa3a 100644
      --- a/apps/examples/nxflat/Makefile
      +++ b/apps/examples/nxflat/Makefile
      @@ -73,7 +73,7 @@ headers:
       	@$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
      diff --git a/apps/examples/nxhello/Makefile b/apps/examples/nxhello/Makefile
      index 37d76b842a..79b169a771 100644
      --- a/apps/examples/nxhello/Makefile
      +++ b/apps/examples/nxhello/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/nximage/Makefile b/apps/examples/nximage/Makefile
      index f428009a2a..0e8c3b0de6 100644
      --- a/apps/examples/nximage/Makefile
      +++ b/apps/examples/nximage/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/nxlines/Makefile b/apps/examples/nxlines/Makefile
      index 2127f1b61e..e12e310b87 100644
      --- a/apps/examples/nxlines/Makefile
      +++ b/apps/examples/nxlines/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/nxtext/Makefile b/apps/examples/nxtext/Makefile
      index ff8f1da694..0510992da0 100644
      --- a/apps/examples/nxtext/Makefile
      +++ b/apps/examples/nxtext/Makefile
      @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -92,7 +92,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/ostest/Makefile b/apps/examples/ostest/Makefile
      index e73abfb47d..7c4354b1d1 100644
      --- a/apps/examples/ostest/Makefile
      +++ b/apps/examples/ostest/Makefile
      @@ -120,7 +120,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -132,7 +132,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/pashello/Makefile b/apps/examples/pashello/Makefile
      index c5103f2c6e..2e2e428e91 100644
      --- a/apps/examples/pashello/Makefile
      +++ b/apps/examples/pashello/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/pipe/Makefile b/apps/examples/pipe/Makefile
      index d484d9fd98..8afb29188a 100644
      --- a/apps/examples/pipe/Makefile
      +++ b/apps/examples/pipe/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/poll/Makefile b/apps/examples/poll/Makefile
      index 204acbb5e8..1483f53421 100644
      --- a/apps/examples/poll/Makefile
      +++ b/apps/examples/poll/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       # Register application
      diff --git a/apps/examples/pwm/Makefile b/apps/examples/pwm/Makefile
      index 4a01293afe..beeb25e7cc 100644
      --- a/apps/examples/pwm/Makefile
      +++ b/apps/examples/pwm/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -86,7 +86,7 @@ $(COBJS): %$(OBJEXT): %.c
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/qencoder/Makefile b/apps/examples/qencoder/Makefile
      index 5959d14a3f..d6eaaf6cbb 100644
      --- a/apps/examples/qencoder/Makefile
      +++ b/apps/examples/qencoder/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/relays/Makefile b/apps/examples/relays/Makefile
      index 72d2faa956..fdb7927730 100644
      --- a/apps/examples/relays/Makefile
      +++ b/apps/examples/relays/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/rgmp/Makefile b/apps/examples/rgmp/Makefile
      index 74b6c154b7..04aab7bbe6 100644
      --- a/apps/examples/rgmp/Makefile
      +++ b/apps/examples/rgmp/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/romfs/Makefile b/apps/examples/romfs/Makefile
      index f82da8fe44..47b08134a9 100644
      --- a/apps/examples/romfs/Makefile
      +++ b/apps/examples/romfs/Makefile
      @@ -86,13 +86,13 @@ romfs_testdir.h : testdir.img
       	@xxd -i $< >$@ || { echo "xxd of $< failed" ; exit 1 ; }
       
       .built: romfs_testdir.h $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       # Register application
      diff --git a/apps/examples/sendmail/Makefile b/apps/examples/sendmail/Makefile
      index 0949c7f541..b7c4d32dcb 100644
      --- a/apps/examples/sendmail/Makefile
      +++ b/apps/examples/sendmail/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       # Register application
      diff --git a/apps/examples/serloop/Makefile b/apps/examples/serloop/Makefile
      index 6c5d849e6f..8ec7f07596 100644
      --- a/apps/examples/serloop/Makefile
      +++ b/apps/examples/serloop/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       # Register application
      diff --git a/apps/examples/telnetd/Makefile b/apps/examples/telnetd/Makefile
      index 960d221636..3371f90c22 100644
      --- a/apps/examples/telnetd/Makefile
      +++ b/apps/examples/telnetd/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/thttpd/Makefile b/apps/examples/thttpd/Makefile
      index cfdd45a670..4f303c9527 100644
      --- a/apps/examples/thttpd/Makefile
      +++ b/apps/examples/thttpd/Makefile
      @@ -73,13 +73,13 @@ headers:
       	@$(MAKE) -C content TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV)
       
       .built: headers $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/tiff/Makefile b/apps/examples/tiff/Makefile
      index fb1fb7d342..c86519fde4 100644
      --- a/apps/examples/tiff/Makefile
      +++ b/apps/examples/tiff/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/touchscreen/Makefile b/apps/examples/touchscreen/Makefile
      index d0bd2dbc70..c82a94b44a 100644
      --- a/apps/examples/touchscreen/Makefile
      +++ b/apps/examples/touchscreen/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/udp/Makefile b/apps/examples/udp/Makefile
      index 07f2ba80b2..0aa2aaa095 100644
      --- a/apps/examples/udp/Makefile
      +++ b/apps/examples/udp/Makefile
      @@ -106,7 +106,7 @@ $(HOST_BIN): $(HOST_OBJS)
       context:
       
       .depend: Makefile $(TARG_SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(TARG_SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(TARG_SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/uip/Makefile b/apps/examples/uip/Makefile
      index 316e01a163..4b4dfc9d9b 100644
      --- a/apps/examples/uip/Makefile
      +++ b/apps/examples/uip/Makefile
      @@ -70,7 +70,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       httpd_fsdata.c: httpd-fs/*
      @@ -79,7 +79,7 @@ httpd_fsdata.c: httpd-fs/*
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       epend: .depend
      diff --git a/apps/examples/usbserial/Makefile b/apps/examples/usbserial/Makefile
      index 7bca964632..06d4ab2981 100644
      --- a/apps/examples/usbserial/Makefile
      +++ b/apps/examples/usbserial/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/usbstorage/Makefile b/apps/examples/usbstorage/Makefile
      index 9ee03efc07..a5da68ef0a 100644
      --- a/apps/examples/usbstorage/Makefile
      +++ b/apps/examples/usbstorage/Makefile
      @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -93,7 +93,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/usbterm/Makefile b/apps/examples/usbterm/Makefile
      index 461a98fa36..16d5d4b53f 100644
      --- a/apps/examples/usbterm/Makefile
      +++ b/apps/examples/usbterm/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/watchdog/Makefile b/apps/examples/watchdog/Makefile
      index 22613aea2b..b55a372186 100644
      --- a/apps/examples/watchdog/Makefile
      +++ b/apps/examples/watchdog/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -86,7 +86,7 @@ $(COBJS): %$(OBJEXT): %.c
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/wget/Makefile b/apps/examples/wget/Makefile
      index ddb7b6bf29..f69ebe71ba 100644
      --- a/apps/examples/wget/Makefile
      +++ b/apps/examples/wget/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/wgetjson/Makefile b/apps/examples/wgetjson/Makefile
      index 9687380e9b..73e3ed8447 100644
      --- a/apps/examples/wgetjson/Makefile
      +++ b/apps/examples/wgetjson/Makefile
      @@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -88,7 +88,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/wlan/Makefile b/apps/examples/wlan/Makefile
      index 83fb94fc57..3d944b54a5 100644
      --- a/apps/examples/wlan/Makefile
      +++ b/apps/examples/wlan/Makefile
      @@ -71,13 +71,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/examples/xmlrpc/Makefile b/apps/examples/xmlrpc/Makefile
      index 87eae9ed22..6cde609ddd 100644
      --- a/apps/examples/xmlrpc/Makefile
      +++ b/apps/examples/xmlrpc/Makefile
      @@ -77,7 +77,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -89,7 +89,7 @@ endif
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/graphics/tiff/Makefile b/apps/graphics/tiff/Makefile
      index 84e3a66bd6..b98616bfce 100644
      --- a/apps/graphics/tiff/Makefile
      +++ b/apps/graphics/tiff/Makefile
      @@ -70,13 +70,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/interpreters/ficl/Makefile b/apps/interpreters/ficl/Makefile
      index 9a1fa7e719..c306f67faa 100644
      --- a/apps/interpreters/ficl/Makefile
      +++ b/apps/interpreters/ficl/Makefile
      @@ -95,13 +95,13 @@ debug:
       	@#echo "CFLAGS: $(CFLAGS)"
       
       .built: debug $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: debug Makefile $(SRCS)
      -	@$(MKDEP) $(ROOT_DEPPATH) $(SRC_DEPPATH) $(FICL_DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOT_DEPPATH) $(SRC_DEPPATH) $(FICL_DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/modbus/Makefile b/apps/modbus/Makefile
      index 01deedb542..321bf09b5b 100644
      --- a/apps/modbus/Makefile
      +++ b/apps/modbus/Makefile
      @@ -88,7 +88,7 @@ endif
       
       .built: $(OBJS)
       ifeq ($(CONFIG_MODBUS),y)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       endif
       
      @@ -96,8 +96,7 @@ context:
       
       .depend: Makefile $(SRCS)
       ifeq ($(CONFIG_MODBUS),y)
      -	@$(MKDEP) $(DEPPATH) \
      -	  $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       endif
       
      diff --git a/apps/namedapp/Makefile b/apps/namedapp/Makefile
      index 29ae343fbb..ce16376aed 100644
      --- a/apps/namedapp/Makefile
      +++ b/apps/namedapp/Makefile
      @@ -55,9 +55,9 @@ SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
       ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +  BIN		= ..\\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +  BIN		= ../libapps$(LIBEXT)
       endif
       
       ROOTDEPPATH	= --dep-path .
      @@ -75,30 +75,30 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      -	@touch .built
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
      +	$(Q) touch .built
       
       .context:
       	@echo "/* List of application requirements, generated during make context. */" > namedapp_list.h
       	@echo "/* List of application entry points, generated during make context. */" > namedapp_proto.h
      -	@touch $@
      +	$(Q) touch $@
       
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      -	@touch $@
      +	$(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@rm -f *.o *~ .*.swp .built
      +	$(Q) rm -f *.o *~ .*.swp .built
       	$(call CLEAN)
       
       distclean: clean
      -	@rm -f .context Make.dep .depend
      -	@rm -f namedapp_list.h
      -	@rm -f namedapp_proto.h
      +	$(Q) rm -f .context Make.dep .depend
      +	$(Q) rm -f namedapp_list.h
      +	$(Q) rm -f namedapp_proto.h
       
       -include Make.dep
       
      diff --git a/apps/netutils/codecs/Makefile b/apps/netutils/codecs/Makefile
      index 1b7a9aa5c0..7bab174dee 100644
      --- a/apps/netutils/codecs/Makefile
      +++ b/apps/netutils/codecs/Makefile
      @@ -68,13 +68,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/dhcpc/Makefile b/apps/netutils/dhcpc/Makefile
      index 0207fff007..161d8f68f4 100644
      --- a/apps/netutils/dhcpc/Makefile
      +++ b/apps/netutils/dhcpc/Makefile
      @@ -74,13 +74,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/dhcpd/Makefile b/apps/netutils/dhcpd/Makefile
      index cf91c2390c..8468153d47 100644
      --- a/apps/netutils/dhcpd/Makefile
      +++ b/apps/netutils/dhcpd/Makefile
      @@ -74,13 +74,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/discover/Makefile b/apps/netutils/discover/Makefile
      index 609365f637..b14d8040b3 100644
      --- a/apps/netutils/discover/Makefile
      +++ b/apps/netutils/discover/Makefile
      @@ -77,13 +77,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/ftpc/Makefile b/apps/netutils/ftpc/Makefile
      index 0544ddb1a2..33aee9d8e7 100644
      --- a/apps/netutils/ftpc/Makefile
      +++ b/apps/netutils/ftpc/Makefile
      @@ -90,13 +90,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/ftpd/Makefile b/apps/netutils/ftpd/Makefile
      index 158159f545..738eba226e 100644
      --- a/apps/netutils/ftpd/Makefile
      +++ b/apps/netutils/ftpd/Makefile
      @@ -74,13 +74,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/json/Makefile b/apps/netutils/json/Makefile
      index a0c99a4711..1fe14413b8 100644
      --- a/apps/netutils/json/Makefile
      +++ b/apps/netutils/json/Makefile
      @@ -68,13 +68,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/resolv/Makefile b/apps/netutils/resolv/Makefile
      index 423397f3f3..04ba2d17b9 100644
      --- a/apps/netutils/resolv/Makefile
      +++ b/apps/netutils/resolv/Makefile
      @@ -74,13 +74,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/smtp/Makefile b/apps/netutils/smtp/Makefile
      index 01864da3bf..27f8e323ab 100644
      --- a/apps/netutils/smtp/Makefile
      +++ b/apps/netutils/smtp/Makefile
      @@ -74,13 +74,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/telnetd/Makefile b/apps/netutils/telnetd/Makefile
      index a07a92b624..922fa638d0 100644
      --- a/apps/netutils/telnetd/Makefile
      +++ b/apps/netutils/telnetd/Makefile
      @@ -74,13 +74,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/tftpc/Makefile b/apps/netutils/tftpc/Makefile
      index d8fb88ad99..b544da8502 100644
      --- a/apps/netutils/tftpc/Makefile
      +++ b/apps/netutils/tftpc/Makefile
      @@ -76,13 +76,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/thttpd/Makefile b/apps/netutils/thttpd/Makefile
      index 38f6750434..2f6120f409 100644
      --- a/apps/netutils/thttpd/Makefile
      +++ b/apps/netutils/thttpd/Makefile
      @@ -106,13 +106,13 @@ cgi-bin/$(SUBDIR_BIN3): cgi-bin cgi-src/$(SUBDIR_BIN3)
       endif
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/uiplib/Makefile b/apps/netutils/uiplib/Makefile
      index 29e569b011..4242c3354f 100644
      --- a/apps/netutils/uiplib/Makefile
      +++ b/apps/netutils/uiplib/Makefile
      @@ -90,13 +90,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/webclient/Makefile b/apps/netutils/webclient/Makefile
      index 5fb6a2bb17..c6f9301bfc 100644
      --- a/apps/netutils/webclient/Makefile
      +++ b/apps/netutils/webclient/Makefile
      @@ -74,13 +74,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/webserver/Makefile b/apps/netutils/webserver/Makefile
      index 965de73b22..5fdd6b8d73 100644
      --- a/apps/netutils/webserver/Makefile
      +++ b/apps/netutils/webserver/Makefile
      @@ -81,13 +81,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/netutils/xmlrpc/Makefile b/apps/netutils/xmlrpc/Makefile
      index 3efdf0778d..e8118d7e29 100644
      --- a/apps/netutils/xmlrpc/Makefile
      +++ b/apps/netutils/xmlrpc/Makefile
      @@ -76,13 +76,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile
      index 46dbdd0b11..a16644c035 100644
      --- a/apps/nshlib/Makefile
      +++ b/apps/nshlib/Makefile
      @@ -110,14 +110,13 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       context:
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) \
      -	  $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/system/free/Makefile b/apps/system/free/Makefile
      index 2fe5c455d6..3a318a492c 100644
      --- a/apps/system/free/Makefile
      +++ b/apps/system/free/Makefile
      @@ -83,7 +83,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       # Register application
      @@ -97,7 +97,7 @@ context: .context
       # Create dependencies
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile
      index 074906a6db..3bad936755 100644
      --- a/apps/system/i2c/Makefile
      +++ b/apps/system/i2c/Makefile
      @@ -73,7 +73,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       .context:
      @@ -83,8 +83,7 @@ $(COBJS): %$(OBJEXT): %.c
       context: .context
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) \
      -	  $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/system/install/Makefile b/apps/system/install/Makefile
      index 6e85bba0c9..cf6371092a 100644
      --- a/apps/system/install/Makefile
      +++ b/apps/system/install/Makefile
      @@ -84,7 +84,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       # Register application
      @@ -98,7 +98,7 @@ context: .context
       # Create dependencies
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/system/poweroff/Makefile b/apps/system/poweroff/Makefile
      index 92949d93c7..6956755fcb 100644
      --- a/apps/system/poweroff/Makefile
      +++ b/apps/system/poweroff/Makefile
      @@ -84,7 +84,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       # Register application
      @@ -98,7 +98,7 @@ context: .context
       # Create dependencies
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/system/ramtron/Makefile b/apps/system/ramtron/Makefile
      index cb771a9cc5..339b99fa95 100644
      --- a/apps/system/ramtron/Makefile
      +++ b/apps/system/ramtron/Makefile
      @@ -84,7 +84,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       # Register application
      @@ -98,7 +98,7 @@ context: .context
       # Create dependencies
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/system/readline/Makefile b/apps/system/readline/Makefile
      index d5db043cac..471a811a31 100644
      --- a/apps/system/readline/Makefile
      +++ b/apps/system/readline/Makefile
      @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       # Context build phase target
      @@ -84,7 +84,7 @@ context:
       # Dependency build phase target
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/system/sdcard/Makefile b/apps/system/sdcard/Makefile
      index 555ca151b3..4600cdf685 100644
      --- a/apps/system/sdcard/Makefile
      +++ b/apps/system/sdcard/Makefile
      @@ -84,7 +84,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       # Register application
      @@ -98,7 +98,7 @@ context: .context
       # Create dependencies
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/apps/system/sysinfo/Makefile b/apps/system/sysinfo/Makefile
      index 2b269deb59..9f317e123a 100644
      --- a/apps/system/sysinfo/Makefile
      +++ b/apps/system/sysinfo/Makefile
      @@ -84,7 +84,7 @@ $(COBJS): %$(OBJEXT): %.c
       	$(call COMPILE, $<, $@)
       
       .built: $(OBJS)
      -	$(call ARCHIVE, $@, "$(OBJS)")
      +	$(call ARCHIVE, $(BIN), "$(OBJS)")
       	@touch .built
       
       # Register application
      @@ -98,7 +98,7 @@ context: .context
       # Create dependencies
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/nuttx/Makefile b/nuttx/Makefile
      index 7263489c25..5f7f519f0a 100644
      --- a/nuttx/Makefile
      +++ b/nuttx/Makefile
      @@ -56,7 +56,7 @@ endif
       # This define is passed as EXTRADEFINES for kernel-mode builds.  It is also passed
       # during PASS1 (but not PASS2) context and depend targets.
       
      -KDEFINE = ${shell $(TOPDIR)/tools/define.sh $(CC) __KERNEL__}
      +KDEFINE = ${shell $(TOPDIR)/tools/define.sh "$(CC)" __KERNEL__}
       
       # Process architecture and board-specific directories
       
      diff --git a/nuttx/arch/8051/src/Makefile b/nuttx/arch/8051/src/Makefile
      index 29204b1ee5..8a7aaa937d 100644
      --- a/nuttx/arch/8051/src/Makefile
      +++ b/nuttx/arch/8051/src/Makefile
      @@ -171,7 +171,7 @@ board/libboard$(LIBEXT):
       
       pass1.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS) board/libboard$(LIBEXT)
       	@echo "LD:  $@"
      -	@$(CC) $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
      +	@"$(CC)" $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
       		$(LDLIBS) -llibboard$(LIBEXT) $(SDCCLIBS) -o $@
       	@rm -f up_mem.h
       	@rm -f up_allocateheap$(OBJEXT) libarch$(LIBEXT)
      @@ -179,7 +179,7 @@ pass1.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS) board/libboard$(LIBE
       
       nuttx.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS)
       	@echo "LD:  $@"
      -	@$(CC) $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
      +	@"$(CC)" $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
       		$(LDLIBS) -llibboard$(LIBEXT) $(SDCCLIBS) -o $@
       
       nuttx$(EXEEXT): pass1.hex nuttx.hex
      @@ -201,7 +201,7 @@ export_head: board/libboard$(LIBEXT) p_head$(OBJEXT)
       # a PHONY target that just sets upt the up_irqtest build correctly
       
       up_irqtest.hex: $(TESTOBJS)
      -	$(CC) $(LDFLAGS) -L. $(SDCCPATH) $(TESTLINKOBJS) $(TESTOBJS) $(TESTEXTRAOBJS) $(SDCCLIBS) -o $@
      +	"$(CC)" $(LDFLAGS) -L. $(SDCCPATH) $(TESTLINKOBJS) $(TESTOBJS) $(TESTEXTRAOBJS) $(SDCCLIBS) -o $@
       
       irqtest:
       	@$(MAKE) TOPDIR=../../.. up_irqtest.hex
      @@ -212,7 +212,7 @@ irqtest:
       	@if [ -e board/Makefile ]; then \
       		$(MAKE) -C board TOPDIR=$(TOPDIR) depend ; \
       	fi	
      -	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile
      index 1f470a25d7..6a1dcd5d1a 100644
      --- a/nuttx/arch/arm/src/Makefile
      +++ b/nuttx/arch/arm/src/Makefile
      @@ -78,32 +78,32 @@ EXTRA_LIBPATHS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
      -  LIBPATHS += -L"(TOPDIR)/lib"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"$(BOARDDIR)"
      +  LIBPATHS += -L"$(TOPDIR)/lib"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       GCC_LIBDIR := ${shell dirname $(LIBGCC)}
       
       VPATH = chip:common:$(ARCH_SUBDIR)
      @@ -150,24 +150,24 @@ endif
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      -	 $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	 "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile
      index 866d06e6fa..8d9184a5db 100644
      --- a/nuttx/arch/avr/src/Makefile
      +++ b/nuttx/arch/avr/src/Makefile
      @@ -79,25 +79,25 @@ EXTRA_LIBS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
      -  LIBPATHS += -L"(TOPDIR)/lib"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"$(BOARDDIR)"
      +  LIBPATHS += -L"$(TOPDIR)/lib"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
      @@ -105,7 +105,7 @@ endif
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
       
      -LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
       VPATH = chip:common:$(ARCH_SUBDIR)
       
      @@ -146,24 +146,24 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      -	 $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	 "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile
      index c6197f47cd..e1675d2172 100644
      --- a/nuttx/arch/hc/src/Makefile
      +++ b/nuttx/arch/hc/src/Makefile
      @@ -72,32 +72,32 @@ EXTRA_LIBS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
      -  LIBPATHS += -L"(TOPDIR)/lib"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"$(BOARDDIR)"
      +  LIBPATHS += -L"$(TOPDIR)/lib"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
       VPATH = chip:common:$(ARCH_SUBDIR)
       
      @@ -137,24 +137,24 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      -	 $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	 "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile
      index 27c6780360..dd9aa3ed5e 100644
      --- a/nuttx/arch/mips/src/Makefile
      +++ b/nuttx/arch/mips/src/Makefile
      @@ -69,32 +69,32 @@ EXTRA_LIBS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
      -  LIBPATHS += -L"(TOPDIR)/lib"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"$(BOARDDIR)"
      +  LIBPATHS += -L"$(TOPDIR)/lib"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
       VPATH = chip:common:$(ARCH_SUBDIR)
       
      @@ -135,24 +135,24 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      -	 $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	 "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/rgmp/src/Makefile b/nuttx/arch/rgmp/src/Makefile
      index e1bfb84c1b..d638041566 100644
      --- a/nuttx/arch/rgmp/src/Makefile
      +++ b/nuttx/arch/rgmp/src/Makefile
      @@ -55,7 +55,7 @@ LINKOBJS    = $(LINKSRCS:.c=$(OBJEXT))
       LDFLAGS		+= -T$(RGMPLKSCPT)
       LDLIBS		= $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       LDPATHS		+= -L"$(TOPDIR)/lib -L$(RGMPLIBDIR)
      -LDLIBS		+= -lrgmp $(shell $(CC) -print-libgcc-file-name)
      +LDLIBS		+= -lrgmp $(shell "$(CC)" -print-libgcc-file-name)
       
       all: libarch$(LIBEXT)
       
      @@ -90,7 +90,7 @@ export_head:
       # Dependencies
       
       .depend: Makefile $(SRCS) $(LINKSRCS)
      -	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) $(LINKSRCS) >Make.dep
      +	@$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) $(LINKSRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile
      index 6e6ee5d640..9447606a15 100644
      --- a/nuttx/arch/sh/src/Makefile
      +++ b/nuttx/arch/sh/src/Makefile
      @@ -55,32 +55,32 @@ EXTRA_LIBS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
      -  LIBPATHS += -L"(TOPDIR)/lib"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"$(BOARDDIR)"
      +  LIBPATHS += -L"$(TOPDIR)/lib"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -LIBGCC = ${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}
      +LIBGCC = ${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}
       
       VPATH = chip:common
       
      @@ -102,7 +102,7 @@ board/libboard$(LIBEXT):
       
       nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx"
      -	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) -o $(TOPDIR)/$@ $(HEAD_OBJ) \
      +	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LDPATHS) -L$(BOARDMAKE) -o $(TOPDIR)/$@ $(HEAD_OBJ) \
       		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
       	$(Q) $(NM) $(TOPDIR)/$@ | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
      @@ -121,23 +121,23 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
      -	$(Q) $(MKDEP) --dep-path chip --dep-path common $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) $(MKDEP) --dep-path chip --dep-path common "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile
      index 8cccd0799f..4841abd50d 100644
      --- a/nuttx/arch/sim/src/Makefile
      +++ b/nuttx/arch/sim/src/Makefile
      @@ -127,8 +127,8 @@ endif
       # Most are provided by LINKLIBS on the MAKE command line
       
       LINKLIBS ?=
      -LIBPATHS += -L"(TOPDIR)/lib"
      -LIBPATHS += -L"$(BOARDDIR)"
      +LIBPATHS += -L"$(TOPDIR)/lib"
      +LIBPATHS += -Lboard
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
       # Add the board-specific library and directory
      @@ -150,7 +150,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
       
       $(HOSTOBJS): %$(OBJEXT): %.c
       	$(Q) echo "CC:  $<"
      -	$(Q) $(CC) -c $(HOSTCFLAGS) $< -o $@
      +	$(Q) "$(CC)" -c $(HOSTCFLAGS) $< -o $@
       
       # The architecture-specific library
       
      @@ -186,7 +186,7 @@ nuttx.rel : libarch$(LIBEXT) board/libboard$(LIBEXT) $(HOSTOS)-names.dat $(LINKO
       
       nuttx$(EXEEXT): cleanrel nuttx.rel $(HOSTOBJS)
       	$(Q) echo "LD:  nuttx$(EXEEXT)"
      -	$(Q) $(CC) $(CCLINKFLAGS) $(LDPATHS) -o $(TOPDIR)/$@ nuttx.rel $(HOSTOBJS) $(DRVLIB) $(STDLIBS)
      +	$(Q) "$(CC)" $(CCLINKFLAGS) $(LDPATHS) -o $(TOPDIR)/$@ nuttx.rel $(HOSTOBJS) $(DRVLIB) $(STDLIBS)
       	$(Q) $(NM) $(TOPDIR)/$@ | \
       		grep -v '\(compiled\)\|\(\.o$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       		sort > $(TOPDIR)/System.map
      @@ -202,7 +202,7 @@ export_head: board/libboard$(LIBEXT) up_head.o $(HOSTOBJS)
       # Dependencies
       
       .depend: Makefile $(SRCS)
      -	$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
      diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile
      index 11bd3091dd..a979593ee7 100644
      --- a/nuttx/arch/x86/src/Makefile
      +++ b/nuttx/arch/x86/src/Makefile
      @@ -69,32 +69,32 @@ EXTRA_LIBS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDDIR = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDDIR = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
      -  LIBPATHS += -L"(TOPDIR)/lib"
      -ifneq ($(BOARDDIR),)
      -  LIBPATHS += -L"$(BOARDDIR)"
      +  LIBPATHS += -L"$(TOPDIR)/lib"
      +ifdef BOARDMAKE
      +  LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
      -LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
      +LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
       ifeq ($(HOSTOS),FreeBSD)
         HOST_ARCH = ${shell uname -m 2>/dev/null || echo "Other"}
      @@ -143,24 +143,24 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      -	 $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	 "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifneq ($(BOARDDIR),)
      +ifdef BOARDMAKE
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/z16/src/Makefile b/nuttx/arch/z16/src/Makefile
      index 9223a0464e..f2d09e14fc 100644
      --- a/nuttx/arch/z16/src/Makefile
      +++ b/nuttx/arch/z16/src/Makefile
      @@ -36,7 +36,7 @@
       -include $(TOPDIR)/Make.defs
       -include chip/Make.defs
       
      -COMPILER = ${shell basename $(CC)}
      +COMPILER = ${shell basename "$(CC)"}
       ARCHSRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
       ifeq ($(COMPILER),zneocc.exe)
       WARCHSRCDIR := ${shell cygpath -w $(ARCHSRCDIR)}
      @@ -65,8 +65,6 @@ COBJS = $(CSRCS:.c=$(OBJEXT))
       DEPSRCS = $(SSRCS) $(CSRCS)
       OBJS = $(AOBJS) $(COBJS)
       
      -BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
      -
       VPATH = chip:common
       
       all: $(HEAD_OBJ) libarch$(LIBEXT)
      @@ -118,7 +116,7 @@ nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) nuttx.linkcmd
       	@if [ -e board/Makefile ]; then \
       		$(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
       	fi
      -	@$(MKDEP) --dep-path chip --dep-path common $(CC) -- $(CFLAGS) -- $(DEPSRCS) >Make.dep
      +	@$(MKDEP) --dep-path chip --dep-path common "$(CC)" -- $(CFLAGS) -- $(DEPSRCS) >Make.dep
       	@touch $@
       
       # This is part of the top-level export target
      diff --git a/nuttx/arch/z80/src/Makefile b/nuttx/arch/z80/src/Makefile
      index 92759de175..4b02b1f0b9 100644
      --- a/nuttx/arch/z80/src/Makefile
      +++ b/nuttx/arch/z80/src/Makefile
      @@ -42,7 +42,7 @@
       
       ############################################################################
       # Compiler-Dependent Make
      -COMPILER	= ${shell basename $(CC)}
      +COMPILER	= ${shell basename "$(CC)"}
       ifeq ($(COMPILER),sdcc)
       include Makefile.sdcc
       else
      diff --git a/nuttx/arch/z80/src/Makefile.sdcc b/nuttx/arch/z80/src/Makefile.sdcc
      index 815c52a716..5527bcb55c 100644
      --- a/nuttx/arch/z80/src/Makefile.sdcc
      +++ b/nuttx/arch/z80/src/Makefile.sdcc
      @@ -75,7 +75,7 @@ VPATH = chip:common:board
       
       # Libraries
       
      -LIBGCC = ${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}
      +LIBGCC = ${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}
       
       # Supports dynamic sizing of HEAP.
       #
      @@ -97,11 +97,11 @@ $(COBJS): %$(OBJEXT): %.c
       # This is a kludge to work around some conflicting symbols in libsdcc.lib
       
       $(SDCCLIBDIR)/myz80.lib: $(SDCCLIBDIR)/$(SDCCLIB)
      -	@cat $(SDCCLIBDIR)/$(SDCCLIB) | \
      +	$(Q) cat $(SDCCLIBDIR)/$(SDCCLIB) | \
       		grep -v alloc | grep -v free | grep -v printf | \
       		grep -v _str  | grep -v _mem | grep -v crt0\.o \
       		> myz80.lib
      -	@mv -f myz80.lib $(SDCCLIBDIR)/myz80.lib
      +	$(Q) mv -f myz80.lib $(SDCCLIBDIR)/myz80.lib
       
       # Create a header file that contains addressing information needed by the code
       
      @@ -139,7 +139,7 @@ libarch$(LIBEXT): up_mem.h asm_mem.h $(OBJS)
       # This builds the libboard library in the board/ subdirectory 
       
       board/libboard$(LIBEXT):
      -	@$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
       
       # This target builds the final executable
       
      @@ -149,7 +149,7 @@ pass1.hex: up_mem.h asm_mem.h $(SDCCLIBDIR)/myz80.lib $(HEAD_OBJ) board/libboard
       	@echo "-k $(BOARDDIR)" >>pass1.lnk		# Path to board library
       	@echo "-k $(SDCCLIBDIR)" >>pass1.lnk		# Path to SDCC z80 library
       	@echo "-l libboard$(LIBEXT)" >>pass1.lnk	# Name of board library
      -	@for LIB in $(LINKLIBS); do \
      +	$(Q) for LIB in $(LINKLIBS); do \
       		echo "-l $(TOPDIR)/lib/$$LIB" >> pass1.lnk ;\
       	done
       	@echo "-l myz80.lib" >>pass1.lnk		# Name of SDCC z80 library
      @@ -170,11 +170,11 @@ endif
       	@echo "pass1.hex" >>pass1.lnk			# Path to head object
       	@echo "$(HEAD_OBJ)" >>pass1.lnk		# Path to head object
       	@echo "-e" >>pass1.lnk				# End of script
      -	@$(LD) -f pass1.lnk
      -	@rm -f up_mem.h asm_mem.h
      -	@rm -f up_allocateheap$(OBJEXT) $(HEAD_OBJ) libarch$(LIBEXT)
      -	@$(MAKE) TOPDIR="$(TOPDIR)" libarch$(LIBEXT)
      -	@$(MAKE) TOPDIR="$(TOPDIR)" $(HEAD_OBJ)
      +	$(Q) $(LD) -f pass1.lnk
      +	$(Q) rm -f up_mem.h asm_mem.h
      +	$(Q) rm -f up_allocateheap$(OBJEXT) $(HEAD_OBJ) libarch$(LIBEXT)
      +	$(Q) $(MAKE) TOPDIR="$(TOPDIR)" libarch$(LIBEXT)
      +	$(Q) $(MAKE) TOPDIR="$(TOPDIR)" $(HEAD_OBJ)
       
       nuttx.hex: up_mem.h asm_mem.h $(SDCCLIBDIR)/myz80.lib $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx.hex"
      @@ -182,7 +182,7 @@ nuttx.hex: up_mem.h asm_mem.h $(SDCCLIBDIR)/myz80.lib $(HEAD_OBJ) board/libboard
       	@echo "-k $(BOARDDIR)" >>nuttx.lnk		# Path to board library
       	@echo "-k $(SDCCLIBDIR)" >>nuttx.lnk		# Path to SDCC z80 library
       	@echo "-l libboard$(LIBEXT)" >>nuttx.lnk	# Name of board library
      -	@for LIB in $(LINKLIBS); do \
      +	$(Q) for LIB in $(LINKLIBS); do \
       		echo "-l $(TOPDIR)/lib/$$LIB" >> nuttx.lnk ;\
       	done
       	@echo "-l myz80.lib" >>nuttx.lnk		# Name of SDCC z80 library
      @@ -203,22 +203,22 @@ endif
       	@echo "nuttx.hex" >>nuttx.lnk			# Path to head object
       	@echo "$(HEAD_OBJ)" >>nuttx.lnk		# Path to head object
       	@echo "-e" >>nuttx.lnk				# End of script
      -	@$(LD) -f nuttx.lnk
      +	$(Q) $(LD) -f nuttx.lnk
       
       nuttx$(EXEEXT): pass1.hex nuttx.hex
      -	@rm -f pass1.*
      -	@cp -f nuttx.map $(TOPDIR)/.
      +	$(Q) rm -f pass1.*
      +	$(Q) cp -f nuttx.map $(TOPDIR)/.
       ifeq ($(EXEEXT),.cmd)
       	sed s/:00000001FF/:00520001AD/ nuttx.hex | \
       	hex2cmd > $(TOPDIR)/nuttx.cmd
       else
      -	@packihx nuttx.hex > $(TOPDIR)/nuttx$(EXEEXT)
      +	$(Q) packihx nuttx.hex > $(TOPDIR)/nuttx$(EXEEXT)
       endif
       
       # This is part of the top-level export target
       
       export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
      -	@if [ -d "$(EXPORT_DIR)/startup" ]; then \
      +	$(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \
       		cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \
       	 else \
       		echo "$(EXPORT_DIR)/startup does not exist"; \
      @@ -228,25 +228,25 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Build dependencies
       
       .depend: Makefile up_mem.h asm_mem.h chip/Make.defs $(DEPSRCS)
      -	@if [ -e board/Makefile ]; then \
      +	$(Q) if [ -e board/Makefile ]; then \
       		$(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
       	fi
      -	@$(MKDEP) --dep-path chip --dep-path common $(CC) -- $(CFLAGS) -- $(DEPSRCS) >Make.dep
      -	@touch $@
      +	$(Q) $(MKDEP) --dep-path chip --dep-path common "$(CC)" -- $(CFLAGS) -- $(DEPSRCS) >Make.dep
      +	$(Q) touch $@
       
       depend: .depend
       
       clean:
      -	@if [ -e board/Makefile ]; then \
      +	$(Q) if [ -e board/Makefile ]; then \
       		$(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \
       	fi
      -	@rm -f libarch$(LIBEXT) up_mem.h asm_mem.h pass1.* nuttx.* *~ .*.swp
      +	$(Q) rm -f libarch$(LIBEXT) up_mem.h asm_mem.h pass1.* nuttx.* *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -	@if [ -e board/Makefile ]; then \
      +	$(Q) if [ -e board/Makefile ]; then \
       		$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \
       	fi
      -	@rm -f Make.dep .depend
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii
      index 031d4fe3da..4eaad3c325 100644
      --- a/nuttx/arch/z80/src/Makefile.zdsii
      +++ b/nuttx/arch/z80/src/Makefile.zdsii
      @@ -41,7 +41,7 @@ USRINCLUDES	= -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common'
       INCLUDES	= $(ARCHSTDINCLUDES) $(USRINCLUDES)
       CFLAGS		= $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
       CPPFLAGS	+= -I$(ARCHSRCDIR) -I$(ZDSSTDINCDIR) -I$(ZDSZILOGINCDIR)
      -LDFLAGS 	+= @"${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}"
      +LDFLAGS 	+= "${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}"
       
       ############################################################################
       # Files and directories
      @@ -75,9 +75,9 @@ all: $(HEAD_OBJ) libarch$(LIBEXT)
       .PHONY: board/libboard$(LIBEXT)
       
       $(HEAD_GENSRC) $(GENSRCS) : %$(ASMEXT): %.S
      -	@$(CPP) $(CPPFLAGS) $< -o $@.tmp
      -	@cat $@.tmp | sed -e "s/^#/;/g" > $@
      -	@rm $@.tmp
      +	$(Q) $(CPP) $(CPPFLAGS) $< -o $@.tmp
      +	$(Q) cat $@.tmp | sed -e "s/^#/;/g" > $@
      +	$(Q) rm $@.tmp
       
       $(AOBJS) $(HEAD_OBJ): %$(OBJEXT): %$(ASMEXT)
       	$(call ASSEMBLE, $<, $@)
      @@ -89,13 +89,13 @@ libarch$(LIBEXT): $(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       board/libboard$(LIBEXT):
      -	@$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
      +	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
       
       nuttx.linkcmd: $(LINKCMDTEMPLATE)
      -	@cp -f $(LINKCMDTEMPLATE) nuttx.linkcmd
      +	$(Q) cp -f $(LINKCMDTEMPLATE) nuttx.linkcmd
       	@echo "\"${shell cygpath -w $(TOPDIR)/nuttx}\"= \\" >>nuttx.linkcmd
       	@echo "  \"${shell cygpath -w $(ARCHSRCDIR)/$(HEAD_OBJ)}\", \\" >>nuttx.linkcmd
      -	@( for lib in $(LINKLIBS); do \
      +	$(Q) ( for lib in $(LINKLIBS); do \
       		echo "  \"`cygpath -w $(TOPDIR)/$${lib}`\", \\" >>nuttx.linkcmd; \
       	done ; )
       	@echo "  \"${shell cygpath -w $(ARCHSRCDIR)/board/libboard$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      @@ -123,19 +123,19 @@ endif
       
       nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) nuttx.linkcmd
       	@echo "LD:  nuttx.hex"
      -	@$(LD) $(LDFLAGS)
      +	$(Q) $(LD) $(LDFLAGS)
       
       .depend: Makefile chip/Make.defs $(DEPSRCS)
      -	@if [ -e board/Makefile ]; then \
      +	$(Q) if [ -e board/Makefile ]; then \
       		$(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
       	fi
      -	@$(MKDEP) --dep-path chip --dep-path common $(CC) -- $(CFLAGS) -- $(DEPSRCS) >Make.dep
      -	@touch $@
      +	$(Q) $(MKDEP) --dep-path chip --dep-path common "$(CC)" -- $(CFLAGS) -- $(DEPSRCS) >Make.dep
      +	$(Q) touch $@
       
       # This is part of the top-level export target
       
       export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
      -	@if [ -d "$(EXPORT_DIR)/startup" ]; then \
      +	$(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \
       		cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \
       	 else \
       		echo "$(EXPORT_DIR)/startup does not exist"; \
      @@ -147,17 +147,17 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       depend: .depend
       
       clean:
      -	@if [ -e board/Makefile ]; then \
      +	$(Q) if [ -e board/Makefile ]; then \
       		$(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \
       	fi
      -	@rm -f libarch$(LIBEXT) *~ .*.swp
      -	@rm -f nuttx.linkcmd *.asm *.tmp *.map
      +	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
      +	$(Q) rm -f nuttx.linkcmd *.asm *.tmp *.map
       	$(call CLEAN)
       
       distclean: clean
      -	@if [ -e board/Makefile ]; then \
      +	$(Q) if [ -e board/Makefile ]; then \
       		$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \
       	fi
      -	@rm -f Make.dep .depend
      +	$(Q) rm -f Make.dep .depend
       
       -include Make.dep
      diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile
      index 68f671ce61..365997be8b 100644
      --- a/nuttx/binfmt/Makefile
      +++ b/nuttx/binfmt/Makefile
      @@ -81,7 +81,7 @@ $(BIN): $(BINFMT_OBJS)
       	$(call ARCHIVE, $@, "$(BINFMT_OBJS)")
       
       .depend: Makefile $(BINFMT_SRCS)
      -	$(Q) $(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep
      +	$(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
      diff --git a/nuttx/configs/ez80f910200kitg/ostest/Make.defs b/nuttx/configs/ez80f910200kitg/ostest/Make.defs
      index b7b4e23785..0914bc17aa 100644
      --- a/nuttx/configs/ez80f910200kitg/ostest/Make.defs
      +++ b/nuttx/configs/ez80f910200kitg/ostest/Make.defs
      @@ -38,23 +38,33 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZDS-II toolchain is installed
       
      -ZDSVERSION		:= 4.11.1
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
      +ZDSVERSION := 5.1.1
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      +
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
      +endif
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZDS-II compiler
       
      -WINTOOL			:= y
      -WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
      -WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
      -WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      -WZDSSTDLIBDIR		:= ${shell cygpath -w $(ZDSSTDLIBDIR)}
      -WZDSZILOGLIBDIR 	:= ${shell cygpath -w $(ZDSZILOGLIBDIR)}
      +WTOPDIR := ${shell cygpath -w "$(TOPDIR)"}
      +WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"}
      +WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"}
      +WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"}
      +WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"}
       
       # Escaped versions
       
      @@ -140,35 +150,35 @@ HEXEXT			= .hex
       
       define PREPROCESS
       	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      +	$(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2
       endef
       
       define COMPILE
       	@#echo "CC: $1"
      -	@(wfile=`cygpath -w $1`; $(CC) $(CFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile)
       endef
       
       define ASSEMBLE
       	@#echo "AS: $1"
      -	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile)
       endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
       
       define CLEAN
      -	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      +	$(Q) rm -f *.obj *.src *.lib *.hex *.lod *.lst
       endef
       
       # This is the tool to use for dependencies (i.e., none)
      diff --git a/nuttx/configs/ez80f910200kitg/src/Makefile b/nuttx/configs/ez80f910200kitg/src/Makefile
      index 34ac4ba9cc..8a9d94e47a 100644
      --- a/nuttx/configs/ez80f910200kitg/src/Makefile
      +++ b/nuttx/configs/ez80f910200kitg/src/Makefile
      @@ -67,7 +67,7 @@ libboard$(LIBEXT): $(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/nuttx/configs/ez80f910200zco/dhcpd/Make.defs b/nuttx/configs/ez80f910200zco/dhcpd/Make.defs
      index 17ac71f07b..59f32fb457 100644
      --- a/nuttx/configs/ez80f910200zco/dhcpd/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/dhcpd/Make.defs
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/ez80f910200zco/dhcpd/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
      @@ -38,23 +38,33 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZDS-II toolchain is installed
       
      -ZDSVERSION		:= 4.11.1
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
      +ZDSVERSION := 5.1.1
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      +
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
      +endif
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZDS-II compiler
       
      -WINTOOL			:= y
      -WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
      -WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
      -WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      -WZDSSTDLIBDIR		:= ${shell cygpath -w $(ZDSSTDLIBDIR)}
      -WZDSZILOGLIBDIR 	:= ${shell cygpath -w $(ZDSZILOGLIBDIR)}
      +WTOPDIR := ${shell cygpath -w "$(TOPDIR)"}
      +WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"}
      +WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"}
      +WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"}
      +WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"}
       
       # Escaped versions
       
      @@ -140,35 +150,35 @@ HEXEXT			= .hex
       
       define PREPROCESS
       	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      +	$(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2
       endef
       
       define COMPILE
       	@#echo "CC: $1"
      -	@(wfile=`cygpath -w $1`; $(CC) $(CFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile)
       endef
       
       define ASSEMBLE
       	@#echo "AS: $1"
      -	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile)
       endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
       
       define CLEAN
      -	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      +	$(Q) rm -f *.obj *.src *.lib *.hex *.lod *.lst
       endef
       
       # This is the tool to use for dependencies (i.e., none)
      diff --git a/nuttx/configs/ez80f910200zco/dhcpd/setenv.sh b/nuttx/configs/ez80f910200zco/dhcpd/setenv.sh
      index 3d1c4aecbc..75e873a7fc 100755
      --- a/nuttx/configs/ez80f910200zco/dhcpd/setenv.sh
      +++ b/nuttx/configs/ez80f910200zco/dhcpd/setenv.sh
      @@ -1,7 +1,7 @@
       #!/bin/bash
       # configs/ez80f910200zco/dhcpd/setenv.sh
       #
      -#   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
      @@ -42,11 +42,11 @@ fi
       # The ZDS-II toolchain lies outside of the Cygwin "sandbox" and
       # attempts to set the PATH variable do not have the desired effect.
       # Instead, alias are provided for all of the ZDS-II command line tools.
      -# Version 4.10.1 installed in the default location is assumed here.
      +# Version 5.1.1 installed in the default location is assumed here.
       #
      -ZDSBINDIR="C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_4.11.1/bin"
      -alias ez8asm="${ZDSBINDIR}/ez8asm.exe"
      -alias ez8cc="${ZDSBINDIR}/ez8cc.exe"
      -alias ez8lib="${ZDSBINDIR}/ez8lib.exe"
      -alias ez8link="${ZDSBINDIR}/ez8link.exe"
      +ZDSBINDIR="C:/Program\ Files\ \(x86\)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1/bin"
      +alias ez80asm="${ZDSBINDIR}/ez80asm.exe"
      +alias ez80cc="${ZDSBINDIR}/ez80cc.exe"
      +alias ez80lib="${ZDSBINDIR}/ez80lib.exe"
      +alias ez80link="${ZDSBINDIR}/ez80link.exe"
       
      diff --git a/nuttx/configs/ez80f910200zco/httpd/Make.defs b/nuttx/configs/ez80f910200zco/httpd/Make.defs
      index 399d3a4c25..615939026c 100644
      --- a/nuttx/configs/ez80f910200zco/httpd/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/httpd/Make.defs
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/ez80f910200zco/httpd/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
      @@ -38,23 +38,33 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZDS-II toolchain is installed
       
      -ZDSVERSION		:= 4.11.1
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
      +ZDSVERSION := 5.1.1
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      +
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
      +endif
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZDS-II compiler
       
      -WINTOOL			:= y
      -WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
      -WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
      -WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      -WZDSSTDLIBDIR		:= ${shell cygpath -w $(ZDSSTDLIBDIR)}
      -WZDSZILOGLIBDIR 	:= ${shell cygpath -w $(ZDSZILOGLIBDIR)}
      +WTOPDIR := ${shell cygpath -w "$(TOPDIR)"}
      +WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"}
      +WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"}
      +WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"}
      +WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"}
       
       # Escaped versions
       
      @@ -140,35 +150,35 @@ HEXEXT			= .hex
       
       define PREPROCESS
       	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      +	$(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2
       endef
       
       define COMPILE
       	@#echo "CC: $1"
      -	@(wfile=`cygpath -w $1`; $(CC) $(CFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile)
       endef
       
       define ASSEMBLE
       	@#echo "AS: $1"
      -	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile)
       endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
       
       define CLEAN
      -	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      +	$(Q) rm -f *.obj *.src *.lib *.hex *.lod *.lst
       endef
       
       # This is the tool to use for dependencies (i.e., none)
      diff --git a/nuttx/configs/ez80f910200zco/httpd/setenv.sh b/nuttx/configs/ez80f910200zco/httpd/setenv.sh
      index 3d1c4aecbc..75e873a7fc 100755
      --- a/nuttx/configs/ez80f910200zco/httpd/setenv.sh
      +++ b/nuttx/configs/ez80f910200zco/httpd/setenv.sh
      @@ -1,7 +1,7 @@
       #!/bin/bash
       # configs/ez80f910200zco/dhcpd/setenv.sh
       #
      -#   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
      @@ -42,11 +42,11 @@ fi
       # The ZDS-II toolchain lies outside of the Cygwin "sandbox" and
       # attempts to set the PATH variable do not have the desired effect.
       # Instead, alias are provided for all of the ZDS-II command line tools.
      -# Version 4.10.1 installed in the default location is assumed here.
      +# Version 5.1.1 installed in the default location is assumed here.
       #
      -ZDSBINDIR="C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_4.11.1/bin"
      -alias ez8asm="${ZDSBINDIR}/ez8asm.exe"
      -alias ez8cc="${ZDSBINDIR}/ez8cc.exe"
      -alias ez8lib="${ZDSBINDIR}/ez8lib.exe"
      -alias ez8link="${ZDSBINDIR}/ez8link.exe"
      +ZDSBINDIR="C:/Program\ Files\ \(x86\)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1/bin"
      +alias ez80asm="${ZDSBINDIR}/ez80asm.exe"
      +alias ez80cc="${ZDSBINDIR}/ez80cc.exe"
      +alias ez80lib="${ZDSBINDIR}/ez80lib.exe"
      +alias ez80link="${ZDSBINDIR}/ez80link.exe"
       
      diff --git a/nuttx/configs/ez80f910200zco/nettest/Make.defs b/nuttx/configs/ez80f910200zco/nettest/Make.defs
      index 3044e8ffdb..ea309af75a 100644
      --- a/nuttx/configs/ez80f910200zco/nettest/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/nettest/Make.defs
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/ez80f910200zco/nettest/Make.defs
       #
      -#   Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2009, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -38,23 +38,33 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZDS-II toolchain is installed
       
      -ZDSVERSION		:= 4.11.1
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
      +ZDSVERSION := 5.1.1
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      +
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
      +endif
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZDS-II compiler
       
      -WINTOOL			:= y
      -WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
      -WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
      -WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      -WZDSSTDLIBDIR		:= ${shell cygpath -w $(ZDSSTDLIBDIR)}
      -WZDSZILOGLIBDIR 	:= ${shell cygpath -w $(ZDSZILOGLIBDIR)}
      +WTOPDIR := ${shell cygpath -w "$(TOPDIR)"}
      +WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"}
      +WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"}
      +WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"}
      +WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"}
       
       # Escaped versions
       
      @@ -140,35 +150,35 @@ HEXEXT			= .hex
       
       define PREPROCESS
       	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      +	$(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2
       endef
       
       define COMPILE
       	@#echo "CC: $1"
      -	@(wfile=`cygpath -w $1`; $(CC) $(CFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile)
       endef
       
       define ASSEMBLE
       	@#echo "AS: $1"
      -	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile)
       endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
       
       define CLEAN
      -	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      +	$(Q) rm -f *.obj *.src *.lib *.hex *.lod *.lst
       endef
       
       # This is the tool to use for dependencies (i.e., none)
      diff --git a/nuttx/configs/ez80f910200zco/nettest/setenv.sh b/nuttx/configs/ez80f910200zco/nettest/setenv.sh
      index 86823697cb..8a03824086 100755
      --- a/nuttx/configs/ez80f910200zco/nettest/setenv.sh
      +++ b/nuttx/configs/ez80f910200zco/nettest/setenv.sh
      @@ -1,7 +1,7 @@
       #!/bin/bash
       # configs/ez80f910200zco/nettest/setenv.sh
       #
      -#   Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2009, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -42,11 +42,11 @@ fi
       # The ZDS-II toolchain lies outside of the Cygwin "sandbox" and
       # attempts to set the PATH variable do not have the desired effect.
       # Instead, alias are provided for all of the ZDS-II command line tools.
      -# Version 4.10.1 installed in the default location is assumed here.
      +# Version 5.1.1 installed in the default location is assumed here.
       #
      -ZDSBINDIR="C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_4.11.1/bin"
      -alias ez8asm="${ZDSBINDIR}/ez8asm.exe"
      -alias ez8cc="${ZDSBINDIR}/ez8cc.exe"
      -alias ez8lib="${ZDSBINDIR}/ez8lib.exe"
      -alias ez8link="${ZDSBINDIR}/ez8link.exe"
      +ZDSBINDIR="C:/Program\ Files\ \(x86\)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1/bin"
      +alias ez80asm="${ZDSBINDIR}/ez80asm.exe"
      +alias ez80cc="${ZDSBINDIR}/ez80cc.exe"
      +alias ez80lib="${ZDSBINDIR}/ez80lib.exe"
      +alias ez80link="${ZDSBINDIR}/ez80link.exe"
       
      diff --git a/nuttx/configs/ez80f910200zco/nsh/Make.defs b/nuttx/configs/ez80f910200zco/nsh/Make.defs
      index 469baeb1aa..91c900b33f 100644
      --- a/nuttx/configs/ez80f910200zco/nsh/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/nsh/Make.defs
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/ez80f910200zco/nst/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
      @@ -38,23 +38,33 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZDS-II toolchain is installed
       
      -ZDSVERSION		:= 4.11.1
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
      +ZDSVERSION := 5.1.1
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      +
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
      +endif
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZDS-II compiler
       
      -WINTOOL			:= y
      -WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
      -WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
      -WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      -WZDSSTDLIBDIR		:= ${shell cygpath -w $(ZDSSTDLIBDIR)}
      -WZDSZILOGLIBDIR 	:= ${shell cygpath -w $(ZDSZILOGLIBDIR)}
      +WTOPDIR := ${shell cygpath -w "$(TOPDIR)"}
      +WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"}
      +WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"}
      +WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"}
      +WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"}
       
       # Escaped versions
       
      @@ -140,35 +150,35 @@ HEXEXT			= .hex
       
       define PREPROCESS
       	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      +	$(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2
       endef
       
       define COMPILE
       	@#echo "CC: $1"
      -	@(wfile=`cygpath -w $1`; $(CC) $(CFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile)
       endef
       
       define ASSEMBLE
       	@#echo "AS: $1"
      -	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile)
       endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
       
       define CLEAN
      -	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      +	$(Q) rm -f *.obj *.src *.lib *.hex *.lod *.lst
       endef
       
       # This is the tool to use for dependencies (i.e., none)
      diff --git a/nuttx/configs/ez80f910200zco/nsh/setenv.sh b/nuttx/configs/ez80f910200zco/nsh/setenv.sh
      index 37bc6e3aa7..8bfe02b2f4 100755
      --- a/nuttx/configs/ez80f910200zco/nsh/setenv.sh
      +++ b/nuttx/configs/ez80f910200zco/nsh/setenv.sh
      @@ -1,7 +1,7 @@
       #!/bin/bash
       # configs/ez80f910200zco/nst/setenv.sh
       #
      -#   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
      @@ -42,11 +42,11 @@ fi
       # The ZDS-II toolchain lies outside of the Cygwin "sandbox" and
       # attempts to set the PATH variable do not have the desired effect.
       # Instead, alias are provided for all of the ZDS-II command line tools.
      -# Version 4.10.1 installed in the default location is assumed here.
      +# Version 5.1.1 installed in the default location is assumed here.
       #
      -ZDSBINDIR="C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_4.11.1/bin"
      -alias ez8asm="${ZDSBINDIR}/ez8asm.exe"
      -alias ez8cc="${ZDSBINDIR}/ez8cc.exe"
      -alias ez8lib="${ZDSBINDIR}/ez8lib.exe"
      -alias ez8link="${ZDSBINDIR}/ez8link.exe"
      +ZDSBINDIR="C:/Program\ Files\ \(x86\)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1/bin"
      +alias ez80asm="${ZDSBINDIR}/ez80asm.exe"
      +alias ez80cc="${ZDSBINDIR}/ez80cc.exe"
      +alias ez80lib="${ZDSBINDIR}/ez80lib.exe"
      +alias ez80link="${ZDSBINDIR}/ez80link.exe"
       
      diff --git a/nuttx/configs/ez80f910200zco/ostest/Make.defs b/nuttx/configs/ez80f910200zco/ostest/Make.defs
      index c06dfdebe4..5cc8356129 100644
      --- a/nuttx/configs/ez80f910200zco/ostest/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/ostest/Make.defs
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/ez80f910200zco/ostest/Make.defs
       #
      -#   Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2009, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -38,101 +38,111 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZDS-II toolchain is installed
       
      -ZDSVERSION		:= 4.11.1
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
      +ZDSVERSION := 5.1.1
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      +
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
      +endif
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZDS-II compiler
       
      -WINTOOL			:= y
      -WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
      -WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
      -WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      -WZDSSTDLIBDIR		:= ${shell cygpath -w $(ZDSSTDLIBDIR)}
      -WZDSZILOGLIBDIR 	:= ${shell cygpath -w $(ZDSZILOGLIBDIR)}
      +WTOPDIR := ${shell cygpath -w "$(TOPDIR)"}
      +WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"}
      +WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"}
      +WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"}
      +WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"}
       
       # Escaped versions
       
      -ETOPDIR 		:= ${shell echo "$(WTOPDIR)" | sed -e "s/ /%20/g"}
      -EZDSSTDINCDIR		:= ${shell echo "$(WZDSSTDINCDIR)" | sed -e "s/ /%20/g"}
      -EZDSZILOGINCDIR 	:= ${shell echo "$(WZDSZILOGINCDIR)" | sed -e "s/ /%20/g"}
      +ETOPDIR := ${shell echo "$(WTOPDIR)" | sed -e "s/ /%20/g"}
      +EZDSSTDINCDIR := ${shell echo "$(WZDSSTDINCDIR)" | sed -e "s/ /%20/g"}
      +EZDSZILOGINCDIR := ${shell echo "$(WZDSZILOGINCDIR)" | sed -e "s/ /%20/g"}
       
       # Assembler definitions
       
       ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y)
      -ARCHCPU			= eZ80F91
      -ARCHCPUDEF		= _EZ80F91
      -ARCHFAMILY		= _EZ80ACCLAIM!
      +ARCHCPU = eZ80F91
      +ARCHCPUDEF = _EZ80F91
      +ARCHFAMILY = _EZ80ACCLAIM!
       endif
       
       ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
      -  ARCHASMOPTIMIZATION	= -debug -NOsdiopt
      +  ARCHASMOPTIMIZATION = -debug -NOsdiopt
       else
      -  ARCHASMOPTIMIZATION	= -nodebug -NOsdiopt
      +  ARCHASMOPTIMIZATION = -nodebug -NOsdiopt
       endif
       
      -ARCHASMCPUFLAGS 	= -cpu:$(ARCHCPU) -NOigcase
      -ARCHASMLIST		= -list -NOlistmac -name -pagelen:56 -pagewidth:80 -quiet
      -ARCHASMWARNINGS 	= -warn
      -ARCHASMDEFINES		= -define:$(ARCHCPUDEF)=1 -define:$(ARCHFAMILYDEF)=1 -define:__ASSEMBLY__
      -ARCHASMINCLUDES 	= -include:'$(WTOPDIR)\include;$(WZDSSTDINCDIR);$(WZDSZILOGINCDIR)'
      -EARCHASMINCLUDES 	= -include:'$(ETOPDIR)\include;$(EZDSSTDINCDIR);$(EZDSZILOGINCDIR)'
      -AFLAGS			= $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \
      -			  $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION)
      +ARCHASMCPUFLAGS = -cpu:$(ARCHCPU) -NOigcase
      +ARCHASMLIST = -list -NOlistmac -name -pagelen:56 -pagewidth:80 -quiet
      +ARCHASMWARNINGS = -warn
      +ARCHASMDEFINES = -define:$(ARCHCPUDEF)=1 -define:$(ARCHFAMILYDEF)=1 -define:__ASSEMBLY__
      +ARCHASMINCLUDES = -include:'$(WTOPDIR)\include;$(WZDSSTDINCDIR);$(WZDSZILOGINCDIR)'
      +EARCHASMINCLUDES = -include:'$(ETOPDIR)\include;$(EZDSSTDINCDIR);$(EZDSZILOGINCDIR)'
      +AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \
      +		 $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION)
       
       # Compiler definitions
       
       ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
      -  ARCHOPTIMIZATION	= -debug -reduceopt
      +  ARCHOPTIMIZATION = -debug -reduceopt
       else
      -  ARCHOPTIMIZATION	= -nodebug -optsize
      +  ARCHOPTIMIZATION = -nodebug -optsize
       endif
       
      -ARCHCPUFLAGS		= -chartype:S -promote -cpu:$(ARCHCPU) -NOgenprintf -NOmodsect \
      -			  -asmsw:" $(ARCHASMCPUFLAGS) $(EARCHASMINCLUDES) $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION)"
      -ARCHLIST		= -keeplst -NOlist -NOlistinc -keepasm
      -ARCHPICFLAGS		=
      -ARCHWARNINGS		= -warn
      -ARCHDEFINES		= -define:$(ARCHCPUDEF) -define:$(ARCHFAMILYDEF)
      -ARCHSTDINCLUDES 	= -stdinc:'$(WTOPDIR)\include;$(WZDSSTDINCDIR);$(WZDSZILOGINCDIR)'
      -ARCHUSRINCLUDES 	= -usrinc:'.'
      -ARCHINCLUDES		= $(ARCHSTDINCLUDES) $(ARCHUSRINCLUDES)
      -CFLAGS			= $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHLIST) \
      -			  $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
      +ARCHCPUFLAGS = -chartype:S -promote -cpu:$(ARCHCPU) -NOgenprintf -NOmodsect \
      +			   -asmsw:" $(ARCHASMCPUFLAGS) $(EARCHASMINCLUDES) $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION)"
      +ARCHLIST = -keeplst -NOlist -NOlistinc -keepasm
      +ARCHPICFLAGS =
      +ARCHWARNINGS = -warn
      +ARCHDEFINES = -define:$(ARCHCPUDEF) -define:$(ARCHFAMILYDEF)
      +ARCHSTDINCLUDES = -stdinc:'$(WTOPDIR)\include;$(WZDSSTDINCDIR);$(WZDSZILOGINCDIR)'
      +ARCHUSRINCLUDES = -usrinc:'.'
      +ARCHINCLUDES = $(ARCHSTDINCLUDES) $(ARCHUSRINCLUDES)
      +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHLIST) \
      +		  $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
       
      -CPPDEFINES              = -D$(ARCHFAMILYDEF) -D$(ARCHCPUDEF) -D__ASSEMBLY__
      -CPPINCLUDES             = -I$(TOPDIR)/include
      -CPPFLAGS                = $(CPPDEFINES) $(CPPINCLUDES)
      +CPPDEFINES = -D$(ARCHFAMILYDEF) -D$(ARCHCPUDEF) -D__ASSEMBLY__
      +CPPINCLUDES = -I$(TOPDIR)/include
      +CPPFLAGS = $(CPPDEFINES) $(CPPINCLUDES)
       
       # Librarian definitions
       
      -ARFLAGS 		= -quiet -warn
      +ARFLAGS = -quiet -warn
       
       # Linker definitions
       
      -LINKCMDTEMPLATE 	= $(TOPDIR)/configs/ez80f910200zco/ostest/ostest.linkcmd
      +LINKCMDTEMPLATE = $(TOPDIR)/configs/ez80f910200zco/ostest/ostest.linkcmd
       
       # Tool names/pathes
       
      -CROSSDEV		=
      -CC			= $(ZDSBINDIR)/ez80cc.exe
      -CPP			= gcc -E
      -LD			= $(ZDSBINDIR)/ez80link.exe
      -AS			= $(ZDSBINDIR)/ez80asm.exe
      -AR			= $(ZDSBINDIR)/ez80lib.exe
      +CROSSDEV =
      +CC = $(ZDSBINDIR)/ez80cc.exe
      +CPP = gcc -E
      +LD = $(ZDSBINDIR)/ez80link.exe
      +AS = $(ZDSBINDIR)/ez80asm.exe
      +AR = $(ZDSBINDIR)/ez80lib.exe
       
       # File extensions
       
      -ASMEXT			= .asm
      -OBJEXT			= .obj
      -LIBEXT			= .lib
      -EXEEXT			= .lod
      -HEXEXT			= .hex
      +ASMEXT = .asm
      +OBJEXT = .obj
      +LIBEXT = .lib
      +EXEEXT = .lod
      +HEXEXT = .hex
       
       # These are the macros that will be used in the NuttX make system
       # to compile and assembly source files and to insert the resulting
      @@ -140,49 +150,49 @@ HEXEXT			= .hex
       
       define PREPROCESS
       	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      +	$(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2
       endef
       
       define COMPILE
       	@#echo "CC: $1"
      -	@(wfile=`cygpath -w $1`; $(CC) $(CFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile)
       endef
       
       define ASSEMBLE
       	@#echo "AS: $1"
      -	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile)
       endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
       
       define CLEAN
      -	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      +	$(Q) rm -f *.obj *.src *.lib *.hex *.lod *.lst
       endef
       
       # This is the tool to use for dependencies (i.e., none)
       
      -MKDEP			= $(TOPDIR)/tools/mknulldeps.sh
      +MKDEP = $(TOPDIR)/tools/mknulldeps.sh
       
       # ZDS-II cannot follow Cygwin soft links, so we will have to use directory copies
       
      -DIRLINK 		= $(TOPDIR)/tools/winlink.sh
      -DIRUNLINK		= $(TOPDIR)/tools/unlink.sh
      +DIRLINK = $(TOPDIR)/tools/winlink.sh
      +DIRUNLINK = $(TOPDIR)/tools/unlink.sh
       
       # Linux/Cygwin host tool definitions
       
      -HOSTCC			= gcc
      -HOSTINCLUDES		= -I.
      -HOSTCFLAGS		= -Wall -wstrict-prototypes -Wshadow -g -pipe
      -HOSTLDFLAGS		=
      +HOSTCC = gcc
      +HOSTINCLUDES = -I.
      +HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
      +HOSTLDFLAGS =
      diff --git a/nuttx/configs/ez80f910200zco/ostest/setenv.sh b/nuttx/configs/ez80f910200zco/ostest/setenv.sh
      index 028eb6ad47..6150434efc 100755
      --- a/nuttx/configs/ez80f910200zco/ostest/setenv.sh
      +++ b/nuttx/configs/ez80f910200zco/ostest/setenv.sh
      @@ -1,7 +1,7 @@
       #!/bin/bash
       # configs/ez80f910200zco/ostest/setenv.sh
       #
      -#   Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved.
      +#   Copyright (C) 2008, 2009, 2012 Gregory Nutt. All rights reserved.
       #   Author: Gregory Nutt 
       #
       # Redistribution and use in source and binary forms, with or without
      @@ -42,11 +42,11 @@ fi
       # The ZDS-II toolchain lies outside of the Cygwin "sandbox" and
       # attempts to set the PATH variable do not have the desired effect.
       # Instead, alias are provided for all of the ZDS-II command line tools.
      -# Version 4.10.1 installed in the default location is assumed here.
      +# Version 5.1.1 installed in the default location is assumed here.
       #
      -ZDSBINDIR="C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_4.11.1/bin"
      -alias ez8asm="${ZDSBINDIR}/ez8asm.exe"
      -alias ez8cc="${ZDSBINDIR}/ez8cc.exe"
      -alias ez8lib="${ZDSBINDIR}/ez8lib.exe"
      -alias ez8link="${ZDSBINDIR}/ez8link.exe"
      +ZDSBINDIR="C:/Program\ Files\ \(x86\)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1/bin"
      +alias ez80asm="${ZDSBINDIR}/ez80asm.exe"
      +alias ez80cc="${ZDSBINDIR}/ez80cc.exe"
      +alias ez80lib="${ZDSBINDIR}/ez80lib.exe"
      +alias ez80link="${ZDSBINDIR}/ez80link.exe"
       
      diff --git a/nuttx/configs/ez80f910200zco/poll/Make.defs b/nuttx/configs/ez80f910200zco/poll/Make.defs
      index fa21c72065..2cd6fa5d38 100644
      --- a/nuttx/configs/ez80f910200zco/poll/Make.defs
      +++ b/nuttx/configs/ez80f910200zco/poll/Make.defs
      @@ -1,7 +1,7 @@
       ############################################################################
       # configs/ez80f910200zco/poll/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
      @@ -38,23 +38,33 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZDS-II toolchain is installed
       
      -ZDSVERSION		:= 4.11.1
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
      +ZDSVERSION := 5.1.1
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION)
      +
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
      +endif
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZDS-II compiler
       
      -WINTOOL			:= y
      -WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
      -WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
      -WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      -WZDSSTDLIBDIR		:= ${shell cygpath -w $(ZDSSTDLIBDIR)}
      -WZDSZILOGLIBDIR 	:= ${shell cygpath -w $(ZDSZILOGLIBDIR)}
      +WTOPDIR := ${shell cygpath -w "$(TOPDIR)"}
      +WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"}
      +WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"}
      +WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"}
      +WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"}
       
       # Escaped versions
       
      @@ -140,35 +150,35 @@ HEXEXT			= .hex
       
       define PREPROCESS
       	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      +	$(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2
       endef
       
       define COMPILE
       	@#echo "CC: $1"
      -	@(wfile=`cygpath -w $1`; $(CC) $(CFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile)
       endef
       
       define ASSEMBLE
       	@#echo "AS: $1"
      -	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile)
       endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
       
       define CLEAN
      -	@rm -f *.obj *.src *.lib *.hex *.lod *.lst
      +	$(Q) rm -f *.obj *.src *.lib *.hex *.lod *.lst
       endef
       
       # This is the tool to use for dependencies (i.e., none)
      diff --git a/nuttx/configs/ez80f910200zco/poll/setenv.sh b/nuttx/configs/ez80f910200zco/poll/setenv.sh
      index 38252f8f65..1628f105b3 100755
      --- a/nuttx/configs/ez80f910200zco/poll/setenv.sh
      +++ b/nuttx/configs/ez80f910200zco/poll/setenv.sh
      @@ -1,7 +1,7 @@
       #!/bin/bash
       # configs/ez80f910200zco/poll/setenv.sh
       #
      -#   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
      @@ -42,11 +42,11 @@ fi
       # The ZDS-II toolchain lies outside of the Cygwin "sandbox" and
       # attempts to set the PATH variable do not have the desired effect.
       # Instead, alias are provided for all of the ZDS-II command line tools.
      -# Version 4.10.1 installed in the default location is assumed here.
      +# Version 5.1.1 installed in the default location is assumed here.
       #
      -ZDSBINDIR="C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_4.11.1/bin"
      -alias ez8asm="${ZDSBINDIR}/ez8asm.exe"
      -alias ez8cc="${ZDSBINDIR}/ez8cc.exe"
      -alias ez8lib="${ZDSBINDIR}/ez8lib.exe"
      -alias ez8link="${ZDSBINDIR}/ez8link.exe"
      +ZDSBINDIR="C:/Program\ Files\ \(x86\)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1/bin"
      +alias ez80asm="${ZDSBINDIR}/ez80asm.exe"
      +alias ez80cc="${ZDSBINDIR}/ez80cc.exe"
      +alias ez80lib="${ZDSBINDIR}/ez80lib.exe"
      +alias ez80link="${ZDSBINDIR}/ez80link.exe"
       
      diff --git a/nuttx/configs/ez80f910200zco/src/Makefile b/nuttx/configs/ez80f910200zco/src/Makefile
      index fcafd6177c..85489fe91a 100644
      --- a/nuttx/configs/ez80f910200zco/src/Makefile
      +++ b/nuttx/configs/ez80f910200zco/src/Makefile
      @@ -74,7 +74,7 @@ libboard$(LIBEXT): $(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/nuttx/configs/z16f2800100zcog/ostest/Make.defs b/nuttx/configs/z16f2800100zcog/ostest/Make.defs
      index 7f86dd29fa..79fa655bb5 100644
      --- a/nuttx/configs/z16f2800100zcog/ostest/Make.defs
      +++ b/nuttx/configs/z16f2800100zcog/ostest/Make.defs
      @@ -38,23 +38,32 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZNeo-II toolchain is installed
       
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_ZNEO_4.11.1
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_ZNEO_4.11.1
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
      +endif
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZNeo-II compiler
       
      -WINTOOL			:= y
      -WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
      -WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
      -WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      -WZDSSTDLIBDIR		:= ${shell cygpath -w $(ZDSSTDLIBDIR)}
      -WZDSZILOGLIBDIR 	:= ${shell cygpath -w $(ZDSZILOGLIBDIR)}
      +WTOPDIR := ${shell cygpath -w "$(TOPDIR)"}
      +WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"}
      +WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"}
      +WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"}
      +WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"}
       
       # Escaped versions
       
      @@ -133,35 +142,35 @@ EXEEXT			= .hex
       
       define PREPROCESS
       	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      +	$(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2
       endef
       
       define COMPILE
       	@#echo "CC: $1"
      -	@(wfile=`cygpath -w $1`; $(CC) $(CFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile)
       endef
       
       define ASSEMBLE
       	@#echo "AS: $1"
      -	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile)
       endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
       
       define CLEAN
      -	@rm -f *.obj *.src *.lib *.hex *.lst
      +	$(Q) rm -f *.obj *.src *.lib *.hex *.lst
       endef
       
       # This is the tool to use for dependencies (i.e., none)
      diff --git a/nuttx/configs/z16f2800100zcog/pashello/Make.defs b/nuttx/configs/z16f2800100zcog/pashello/Make.defs
      index 92a67fa652..d7b93d659d 100644
      --- a/nuttx/configs/z16f2800100zcog/pashello/Make.defs
      +++ b/nuttx/configs/z16f2800100zcog/pashello/Make.defs
      @@ -38,18 +38,27 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZNeo-II toolchain is installed
       
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_ZNEO_4.11.1
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_ZNEO_4.11.1
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
      +endif
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZNeo-II compiler
       
      -WINTOOL			:= y
       WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
       WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
       WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      @@ -149,13 +158,13 @@ endef
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
      diff --git a/nuttx/configs/z16f2800100zcog/src/Makefile b/nuttx/configs/z16f2800100zcog/src/Makefile
      index 2de29d8ce4..43695f7482 100644
      --- a/nuttx/configs/z16f2800100zcog/src/Makefile
      +++ b/nuttx/configs/z16f2800100zcog/src/Makefile
      @@ -67,7 +67,7 @@ libboard$(LIBEXT): $(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/nuttx/configs/z8encore000zco/ostest/Make.defs b/nuttx/configs/z8encore000zco/ostest/Make.defs
      index 23185e2dd0..fba1018645 100644
      --- a/nuttx/configs/z8encore000zco/ostest/Make.defs
      +++ b/nuttx/configs/z8encore000zco/ostest/Make.defs
      @@ -38,29 +38,45 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZDS-II toolchain is installed
       
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_Z8Encore!_4.10.1
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_Z8Encore!_4.10.1
      +
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
       ifeq ($(CONFIG_ARCH_CHIP_Z8F642X),y)
      -ZDSDEVINCDIR		:= $(ZDSZILOGINCDIR)/Z8Encore_F642X
      +  ZDSDEVINCDIR := $(ZDSZILOGINCDIR)\Z8Encore_F642X
       endif
       ifeq ($(CONFIG_ARCH_CHIP_Z8F640X),y)
      -ZDSDEVINCDIR		:= $(ZDSZILOGINCDIR)/Z8Encore_F640X
      +  ZDSDEVINCDIR := $(ZDSZILOGINCDIR)\Z8Encore_F640X
      +endif
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +ifeq ($(CONFIG_ARCH_CHIP_Z8F642X),y)
      +  ZDSDEVINCDIR := $(ZDSZILOGINCDIR)/Z8Encore_F642X
      +endif
      +ifeq ($(CONFIG_ARCH_CHIP_Z8F640X),y)
      +  ZDSDEVINCDIR := $(ZDSZILOGINCDIR)/Z8Encore_F640X
      +endif
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
       endif
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZDS-II compiler
       
      -WINTOOL			:= y
      -WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
      -WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
      -WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      -WZDSDEVINCDIR		:= ${shell cygpath -w $(ZDSDEVINCDIR)}
      -WZDSSTDLIBDIR		:= ${shell cygpath -w $(ZDSSTDLIBDIR)}
      -WZDSZILOGLIBDIR 	:= ${shell cygpath -w $(ZDSZILOGLIBDIR)}
      +WTOPDIR := ${shell cygpath -w "$(TOPDIR)"}
      +WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"}
      +WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"}
      +WZDSDEVINCDIR := ${shell cygpath -w "$(ZDSDEVINCDIR)"}
      +WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"}
      +WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"}
       
       # Escaped versions
       
      @@ -159,35 +175,35 @@ EXEEXT			= .hex
       
       define PREPROCESS
       	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      +	$(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2
       endef
       
       define COMPILE
       	@#echo "CC: $1"
      -	@(wfile=`cygpath -w $1`; $(CC) $(CFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile)
       endef
       
       define ASSEMBLE
       	@#echo "AS: $1"
      -	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile)
       endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
       
       define CLEAN
      -	@rm -f *.obj *.src *.lib *.hex *.lst
      +	$(Q) rm -f *.obj *.src *.lib *.hex *.lst
       endef
       
       # This is the tool to use for dependencies (i.e., none)
      diff --git a/nuttx/configs/z8encore000zco/src/Makefile b/nuttx/configs/z8encore000zco/src/Makefile
      index eee0728502..a40b6f42c1 100644
      --- a/nuttx/configs/z8encore000zco/src/Makefile
      +++ b/nuttx/configs/z8encore000zco/src/Makefile
      @@ -67,7 +67,7 @@ libboard$(LIBEXT): $(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/nuttx/configs/z8f64200100kit/ostest/Make.defs b/nuttx/configs/z8f64200100kit/ostest/Make.defs
      index 1ee00c72c0..4fa6af2ec2 100644
      --- a/nuttx/configs/z8f64200100kit/ostest/Make.defs
      +++ b/nuttx/configs/z8f64200100kit/ostest/Make.defs
      @@ -38,29 +38,45 @@ include ${TOPDIR}/tools/Config.mk
       
       # These are the directories where the ZDS-II toolchain is installed
       
      -ZDSINSTALLDIR		:= C:/Program\ Files/ZiLOG/ZDSII_Z8Encore!_4.10.1
      -ZDSBINDIR		:= $(ZDSINSTALLDIR)/bin
      -ZDSSTDINCDIR		:= $(ZDSINSTALLDIR)/include/std
      -ZDSZILOGINCDIR		:= $(ZDSINSTALLDIR)/include/zilog
      +ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_Z8Encore!_4.10.1
      +
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  ZDSBINDIR := $(ZDSINSTALLDIR)\bin
      +  ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std
      +  ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog
       ifeq ($(CONFIG_ARCH_CHIP_Z8F642X),y)
      -ZDSDEVINCDIR		:= $(ZDSZILOGINCDIR)/Z8Encore_F642X
      +  ZDSDEVINCDIR := $(ZDSZILOGINCDIR)\Z8Encore_F642X
       endif
       ifeq ($(CONFIG_ARCH_CHIP_Z8F640X),y)
      -ZDSDEVINCDIR		:= $(ZDSZILOGINCDIR)/Z8Encore_F640X
      +  ZDSDEVINCDIR := $(ZDSZILOGINCDIR)\Z8Encore_F640X
      +endif
      +  ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std
      +  ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog
      +else
      +  WINTOOL := y
      +  INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"}
      +  ZDSBINDIR := $(INSTALLDIR)/bin
      +  ZDSSTDINCDIR := $(INSTALLDIR)/include/std
      +  ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog
      +ifeq ($(CONFIG_ARCH_CHIP_Z8F642X),y)
      +  ZDSDEVINCDIR := $(ZDSZILOGINCDIR)/Z8Encore_F642X
      +endif
      +ifeq ($(CONFIG_ARCH_CHIP_Z8F640X),y)
      +  ZDSDEVINCDIR := $(ZDSZILOGINCDIR)/Z8Encore_F640X
      +endif
      +  ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std
      +  ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog
       endif
      -ZDSSTDLIBDIR		:= $(ZDSINSTALLDIR)/lib/std
      -ZDSZILOGLIBDIR		:= $(ZDSINSTALLDIR)/lib/zilog
       
       # These are the same directories but with the directory separator
       # character swapped as needed by the ZDS-II compiler
       
      -WINTOOL			:= y
      -WTOPDIR 		:= ${shell cygpath -w $(TOPDIR)}
      -WZDSSTDINCDIR		:= ${shell cygpath -w $(ZDSSTDINCDIR)}
      -WZDSZILOGINCDIR 	:= ${shell cygpath -w $(ZDSZILOGINCDIR)}
      -WZDSDEVINCDIR		:= ${shell cygpath -w $(ZDSDEVINCDIR)}
      -WZDSSTDLIBDIR		:= ${shell cygpath -w $(ZDSSTDLIBDIR)}
      -WZDSZILOGLIBDIR 	:= ${shell cygpath -w $(ZDSZILOGLIBDIR)}
      +WTOPDIR := ${shell cygpath -w "$(TOPDIR)"}
      +WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"}
      +WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"}
      +WZDSDEVINCDIR := ${shell cygpath -w "$(ZDSDEVINCDIR)"}
      +WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"}
      +WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"}
       
       # Escaped versions
       
      @@ -159,35 +175,35 @@ EXEEXT			= .hex
       
       define PREPROCESS
       	@echo "CPP: $1->$2"
      -	@$(CPP) $(CPPFLAGS) $1 -o $2
      +	$(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2
       endef
       
       define COMPILE
       	@#echo "CC: $1"
      -	@(wfile=`cygpath -w $1`; $(CC) $(CFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile)
       endef
       
       define ASSEMBLE
       	@#echo "AS: $1"
      -	@(wfile=`cygpath -w $1`; $(AS) $(AFLAGS) $$wfile)
      +	$(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile)
       endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
       	echo "AR: $2";
      -	$(Q) for %%G in ($(subst ",,$(2))) do ( $(AR) $(ARFLAGS) $1=-+%%G )
      +	$(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G )
       endef
       else
       define ARCHIVE
      -	$(Q) for __obj in $(2); do \
      -		echo "AR: $(__obj)"; \
      -		$(AR) $(ARFLAGS) $1=-+$(__obj) || { echo "$(AR) $1=-+$(__obj) FAILED!" ; exit 1 ; } \
      +	$(Q) for __obj in $(subst ",,$(2)) ; do \
      +		echo "AR: $$__obj"; \
      +		"$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \
       	done
       endef
       endif
       
       define CLEAN
      -	@rm -f *.obj *.src *.lib *.hex *.lst
      +	$(Q) rm -f *.obj *.src *.lib *.hex *.lst
       endef
       
       # This is the tool to use for dependencies (i.e., none)
      diff --git a/nuttx/configs/z8f64200100kit/src/Makefile b/nuttx/configs/z8f64200100kit/src/Makefile
      index 2cd0ed45f3..a8b618b6f5 100644
      --- a/nuttx/configs/z8f64200100kit/src/Makefile
      +++ b/nuttx/configs/z8f64200100kit/src/Makefile
      @@ -67,7 +67,7 @@ libboard$(LIBEXT): $(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	@$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	@touch $@
       
       depend: .depend
      diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
      index a57285505c..3a6e340223 100644
      --- a/nuttx/drivers/Makefile
      +++ b/nuttx/drivers/Makefile
      @@ -105,7 +105,7 @@ $(BIN):	$(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	$(Q) $(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
      diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile
      index 643b322bb8..b79b1734d8 100644
      --- a/nuttx/fs/Makefile
      +++ b/nuttx/fs/Makefile
      @@ -124,7 +124,7 @@ $(BIN):	$(OBJS)
       
       .depend: Makefile $(SRCS)
       	$(Q) $(MKDEP) --dep-path . $(MMAPDEPPATH) $(FATDEPPATH) $(ROMFSDEPPATH) $(NXFFSDEPPATH) $(NFSDEPPATH) \
      -		$(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +		"$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
      diff --git a/nuttx/graphics/Makefile b/nuttx/graphics/Makefile
      index f3a768113a..f638587baf 100644
      --- a/nuttx/graphics/Makefile
      +++ b/nuttx/graphics/Makefile
      @@ -191,7 +191,7 @@ $(BIN): $(OBJS)
       mklibgraphics: gensources $(BIN)
       
       .depend: gensources Makefile $(SRCS)
      -	$(Q) $(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
      diff --git a/nuttx/libc/Makefile b/nuttx/libc/Makefile
      index 0e11c9bad2..ac8fe4bc7a 100644
      --- a/nuttx/libc/Makefile
      +++ b/nuttx/libc/Makefile
      @@ -98,7 +98,7 @@ $(KBIN): uclean .kernlib
       endif
       
       .depend: Makefile $(SRCS)
      -	$(Q) $(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
      diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile
      index bdbc5da872..e5fff1c479 100644
      --- a/nuttx/libxx/Makefile
      +++ b/nuttx/libxx/Makefile
      @@ -99,7 +99,7 @@ $(BIN):	$(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	$(Q) $(MKDEP) $(DEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) $(MKDEP) $(DEPPATH) "$(CXX)" -- $(CXXFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
      diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile
      index b48d242ffd..fef9cc9ddc 100644
      --- a/nuttx/mm/Makefile
      +++ b/nuttx/mm/Makefile
      @@ -64,7 +64,7 @@ $(BIN):	$(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
      diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
      index 2a43914901..5ce4de4ccb 100644
      --- a/nuttx/net/Makefile
      +++ b/nuttx/net/Makefile
      @@ -104,7 +104,7 @@ $(BIN): $(OBJS)
       
       .depend: Makefile $(SRCS)
       ifeq ($(CONFIG_NET),y)
      -	$(Q) $(MKDEP) --dep-path . --dep-path uip $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) $(MKDEP) --dep-path . --dep-path uip "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       endif
       	$(Q) touch $@
       
      diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
      index 6487c5701f..571393cb20 100644
      --- a/nuttx/sched/Makefile
      +++ b/nuttx/sched/Makefile
      @@ -199,7 +199,7 @@ $(BIN): $(OBJS)
       	$(call ARCHIVE, $@, "$(OBJS)")
       
       .depend: Makefile $(SRCS)
      -	$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	$(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
      diff --git a/nuttx/syscall/Makefile b/nuttx/syscall/Makefile
      index e9370a7763..0de895cde7 100644
      --- a/nuttx/syscall/Makefile
      +++ b/nuttx/syscall/Makefile
      @@ -79,7 +79,7 @@ $(BIN2): $(STUB_OBJS)
       
       .depend: Makefile $(SRCS)
       	$(Q) $(MKDEP) $(ROOTDEPPATH) $(PROXYDEPPATH) $(STUBDEPPATH) \
      -	  $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
      +	  "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
       	$(Q) touch $@
       
       depend: .depend
      diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk
      index 47131b8007..84643b8ccb 100644
      --- a/nuttx/tools/Config.mk
      +++ b/nuttx/tools/Config.mk
      @@ -64,14 +64,14 @@ endef
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
       define ARCHIVE
      -	echo "AR: $2"
      +	@echo "AR: $2"
       	$(AR) $1
      -	$(AR) $1 $(subst ",,$(2))
      +	$(Q) $(AR) $1 $(subst ",,$(2))
       endef
       else
       define ARCHIVE
      -	echo "AR: $2"
      -	$(AR) $1 $(subst ",,$(2)) || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
      +	@echo "AR: $2"
      +	$(Q) $(AR) $1 $(subst ",,$(2)) || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
       endef
       endif
       
      
      From fe19d5bea139e25e04c5260726ec300e49ffdf2b Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Mon, 12 Nov 2012 01:54:54 +0000
      Subject: [PATCH 109/206] A few more build fixes
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5340 42af7a65-404d-4744-a932-0658087f49c3
      ---
       apps/netutils/uiplib/uiplib.c |  5 ++++-
       nuttx/arch/8051/src/Makefile  |  6 +++---
       nuttx/arch/arm/src/Makefile   | 21 ++++++++++++---------
       nuttx/arch/avr/src/Makefile   | 22 ++++++++++++----------
       nuttx/arch/hc/src/Makefile    | 21 ++++++++++++---------
       nuttx/arch/mips/src/Makefile  | 21 ++++++++++++---------
       nuttx/arch/rgmp/src/Makefile  |  4 ++--
       nuttx/arch/sh/src/Makefile    | 23 +++++++++++++----------
       nuttx/arch/sim/src/Makefile   | 14 +++++++-------
       nuttx/arch/x86/src/Makefile   | 21 ++++++++++++---------
       nuttx/tools/Config.mk         |  2 +-
       11 files changed, 90 insertions(+), 70 deletions(-)
      
      diff --git a/apps/netutils/uiplib/uiplib.c b/apps/netutils/uiplib/uiplib.c
      index 32ffaeb06d..50182efe17 100644
      --- a/apps/netutils/uiplib/uiplib.c
      +++ b/apps/netutils/uiplib/uiplib.c
      @@ -45,6 +45,7 @@
       
       #include 
       #include 
      +#include 
       #include 
       
       #include 
      @@ -103,7 +104,7 @@ bool uiplib_hwmacconv(const char *hwstr, uint8_t *hw)
         unsigned char i;
         unsigned char j;
       
      -  if (strlen(hwstr)!=17)
      +  if (strlen(hwstr) != 17)
           {
             return false;
           }
      @@ -121,6 +122,7 @@ bool uiplib_hwmacconv(const char *hwstr, uint8_t *hw)
                  {
                    return false;
                  }
      +
                 if (c == ':' || c == 0)
                   {
                     *hw = tmp;
      @@ -144,6 +146,7 @@ bool uiplib_hwmacconv(const char *hwstr, uint8_t *hw)
                   {
                     return false;
                   }
      +
                 ++hwstr;
               }
             while(c != ':' && c != 0);
      diff --git a/nuttx/arch/8051/src/Makefile b/nuttx/arch/8051/src/Makefile
      index 8a7aaa937d..f228b46972 100644
      --- a/nuttx/arch/8051/src/Makefile
      +++ b/nuttx/arch/8051/src/Makefile
      @@ -60,7 +60,7 @@ LINKSSRCS = up_head.S
       LINKASRCS = $(LINKSSRCS:.S=$(ASMEXT))
       LINKOBJS = $(LINKASRCS:$(ASMEXT)=$(OBJEXT))
       LINKLIBS ?=
      -LDPATHS = -L"$(TOPDIR)/lib"
      +LIBPATHS = -L"$(TOPDIR)/lib"
       LDLIBS =  $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
       
       TESTSRCS = up_irqtest.c
      @@ -171,7 +171,7 @@ board/libboard$(LIBEXT):
       
       pass1.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS) board/libboard$(LIBEXT)
       	@echo "LD:  $@"
      -	@"$(CC)" $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
      +	@"$(CC)" $(LDFLAGS) $(LIBPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
       		$(LDLIBS) -llibboard$(LIBEXT) $(SDCCLIBS) -o $@
       	@rm -f up_mem.h
       	@rm -f up_allocateheap$(OBJEXT) libarch$(LIBEXT)
      @@ -179,7 +179,7 @@ pass1.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS) board/libboard$(LIBE
       
       nuttx.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS)
       	@echo "LD:  $@"
      -	@"$(CC)" $(LDFLAGS) $(LDPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
      +	@"$(CC)" $(LDFLAGS) $(LIBPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \
       		$(LDLIBS) -llibboard$(LIBEXT) $(SDCCLIBS) -o $@
       
       nuttx$(EXEEXT): pass1.hex nuttx.hex
      diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile
      index 6a1dcd5d1a..fb8d3932d6 100644
      --- a/nuttx/arch/arm/src/Makefile
      +++ b/nuttx/arch/arm/src/Makefile
      @@ -78,30 +78,33 @@ EXTRA_LIBPATHS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")}
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi}
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
         LIBPATHS += -L"$(TOPDIR)/lib"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
      +ifeq ($(BOARDMAKE),y)
      +  LDLIBS += -lboard
      +endif
       
       LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       GCC_LIBDIR := ${shell dirname $(LIBGCC)}
      @@ -128,7 +131,7 @@ nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
       	$(Q) echo "LD: nuttx"
       	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) $(EXTRA_LIBPATHS) \
       		-o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
      -		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
      +		--start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
       	$(Q) $(NM) $(NUTTX)$(EXEEXT) | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
      @@ -150,7 +153,7 @@ endif
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      @@ -160,14 +163,14 @@ endif
       depend: .depend
       
       clean:
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile
      index 8d9184a5db..cd4e9012db 100644
      --- a/nuttx/arch/avr/src/Makefile
      +++ b/nuttx/arch/avr/src/Makefile
      @@ -79,31 +79,33 @@ EXTRA_LIBS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")}
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi}
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
         LIBPATHS += -L"$(TOPDIR)/lib"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
      -
      +ifeq ($(BOARDMAKE),y)
      +  LDLIBS += -lboard
      +endif
       
       LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
      @@ -128,7 +130,7 @@ board/libboard$(LIBEXT):
       nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx"
       	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
      -		--start-group $(LDLIBS) -lboard  $(EXTRA_LIBS) $(LIBGCC) --end-group
      +		--start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
       	$(Q) $(NM) $(NUTTX)$(EXEEXT) | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
      @@ -146,7 +148,7 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      @@ -156,14 +158,14 @@ endif
       depend: .depend
       
       clean:
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile
      index e1675d2172..7a3e9d032a 100644
      --- a/nuttx/arch/hc/src/Makefile
      +++ b/nuttx/arch/hc/src/Makefile
      @@ -72,30 +72,33 @@ EXTRA_LIBS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")}
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi}
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
         LIBPATHS += -L"$(TOPDIR)/lib"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
      +ifeq ($(BOARDMAKE),y)
      +  LDLIBS += -lboard
      +endif
       
       LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
      @@ -119,7 +122,7 @@ board/libboard$(LIBEXT):
       nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
       	$(Q) echo "LD: nuttx"
       	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) \
      -		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
      +		--start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
       	$(Q) $(NM) $(NUTTX)$(EXEEXT) | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
      @@ -137,7 +140,7 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      @@ -147,14 +150,14 @@ endif
       depend: .depend
       
       clean:
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile
      index dd9aa3ed5e..8d02ac59c5 100644
      --- a/nuttx/arch/mips/src/Makefile
      +++ b/nuttx/arch/mips/src/Makefile
      @@ -69,30 +69,33 @@ EXTRA_LIBS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")}
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE := ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi}
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
         LIBPATHS += -L"$(TOPDIR)/lib"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
      +ifeq ($(BOARDMAKE),y)
      +  LDLIBS += -lboard
      +endif
       
       LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
      @@ -117,7 +120,7 @@ board/libboard$(LIBEXT):
       nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx"
       	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
      -		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
      +		--start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
       	$(Q) $(NM) $(NUTTX)$(EXEEXT) | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
      @@ -135,7 +138,7 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      @@ -145,14 +148,14 @@ endif
       depend: .depend
       
       clean:
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/rgmp/src/Makefile b/nuttx/arch/rgmp/src/Makefile
      index d638041566..4df7a9ce61 100644
      --- a/nuttx/arch/rgmp/src/Makefile
      +++ b/nuttx/arch/rgmp/src/Makefile
      @@ -54,7 +54,7 @@ LINKOBJS    = $(LINKSRCS:.c=$(OBJEXT))
       
       LDFLAGS		+= -T$(RGMPLKSCPT)
       LDLIBS		= $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
      -LDPATHS		+= -L"$(TOPDIR)/lib -L$(RGMPLIBDIR)
      +LIBPATHS		+= -L"$(TOPDIR)/lib" -L$(RGMPLIBDIR)
       LDLIBS		+= -lrgmp $(shell "$(CC)" -print-libgcc-file-name)
       
       all: libarch$(LIBEXT)
      @@ -77,7 +77,7 @@ libarch$(LIBEXT): $(OBJS)
       
       nuttx$(EXEEXT): $(LINKOBJS)
       	@echo "LD:  nuttx$(EXEEXT)"
      -	@$(LD) $(LDFLAGS) $(LDPATHS) $(LINKOBJS) --start-group $(LDLIBS) $(EXTRA_LIBS) --end-group -o $(TOPDIR)/$@
      +	@$(LD) $(LDFLAGS) $(LIBPATHS) $(LINKOBJS) --start-group $(LDLIBS) $(EXTRA_LIBS) --end-group -o $(TOPDIR)/$@
       	@$(OBJDUMP) -S $(TOPDIR)/$@ > $(TOPDIR)/nuttx.asm
       	@$(NM) -n $(TOPDIR)/$@ > $(TOPDIR)/nuttx.sym
       	@$(OBJCOPY) -S -O binary $(TOPDIR)/$@ nuttx.img
      diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile
      index 9447606a15..d6f3ed634e 100644
      --- a/nuttx/arch/sh/src/Makefile
      +++ b/nuttx/arch/sh/src/Makefile
      @@ -55,30 +55,33 @@ EXTRA_LIBS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")}
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi}
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
         LIBPATHS += -L"$(TOPDIR)/lib"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
      +ifeq ($(BOARDMAKE),y)
      +  LDLIBS += -lboard
      +endif
       
       LIBGCC = ${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}
       
      @@ -102,8 +105,8 @@ board/libboard$(LIBEXT):
       
       nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx"
      -	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LDPATHS) -L$(BOARDMAKE) -o $(TOPDIR)/$@ $(HEAD_OBJ) \
      -		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
      +	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(TOPDIR)/$@ $(HEAD_OBJ) \
      +		--start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
       	$(Q) $(NM) $(TOPDIR)/$@ | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
      @@ -121,7 +124,7 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
      @@ -130,14 +133,14 @@ endif
       depend: .depend
       
       clean:
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile
      index 4841abd50d..d46defe135 100644
      --- a/nuttx/arch/sim/src/Makefile
      +++ b/nuttx/arch/sim/src/Makefile
      @@ -127,14 +127,14 @@ endif
       # Most are provided by LINKLIBS on the MAKE command line
       
       LINKLIBS ?=
      -LIBPATHS += -L"$(TOPDIR)/lib"
      -LIBPATHS += -Lboard
      -LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
      +RELLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
      +RELPATHS += -L"$(TOPDIR)/lib"
       
       # Add the board-specific library and directory
       
      -LDPATHS += -L board 
      -LDLIBS += -lboard
      +LIBPATHS += -L board 
      +RELPATHS += -L board
      +RELLIBS += -lboard
       
       # Make targets begin here
       
      @@ -178,7 +178,7 @@ Cygwin-names.dat: nuttx-names.dat
       
       nuttx.rel : libarch$(LIBEXT) board/libboard$(LIBEXT) $(HOSTOS)-names.dat $(LINKOBJS)
       	$(Q) echo "LD:  nuttx.rel"
      -	$(Q) $(LD) -r $(LDLINKFLAGS) $(LDPATHS) $(EXTRA_LIBPATHS) -o $@ $(REQUIREDOBJS) --start-group $(LDLIBS) $(EXTRA_LIBS) --end-group
      +	$(Q) $(LD) -r $(LDLINKFLAGS) $(RELPATHS) $(EXTRA_LIBPATHS) -o $@ $(REQUIREDOBJS) --start-group $(RELLIBS) $(EXTRA_LIBS) --end-group
       	$(Q) $(OBJCOPY) --redefine-syms=$(HOSTOS)-names.dat $@
       
       # Generate the final NuttX binary by linking the host-specific objects with the NuttX
      @@ -186,7 +186,7 @@ nuttx.rel : libarch$(LIBEXT) board/libboard$(LIBEXT) $(HOSTOS)-names.dat $(LINKO
       
       nuttx$(EXEEXT): cleanrel nuttx.rel $(HOSTOBJS)
       	$(Q) echo "LD:  nuttx$(EXEEXT)"
      -	$(Q) "$(CC)" $(CCLINKFLAGS) $(LDPATHS) -o $(TOPDIR)/$@ nuttx.rel $(HOSTOBJS) $(DRVLIB) $(STDLIBS)
      +	$(Q) "$(CC)" $(CCLINKFLAGS) $(LIBPATHS) -o $(TOPDIR)/$@ nuttx.rel $(HOSTOBJS) $(DRVLIB) $(STDLIBS)
       	$(Q) $(NM) $(TOPDIR)/$@ | \
       		grep -v '\(compiled\)\|\(\.o$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       		sort > $(TOPDIR)/System.map
      diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile
      index a979593ee7..9e9abb9e2b 100644
      --- a/nuttx/arch/x86/src/Makefile
      +++ b/nuttx/arch/x86/src/Makefile
      @@ -69,30 +69,33 @@ EXTRA_LIBS ?=
       LINKLIBS ?=
       
       ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      -  BOARDMAKE = $(dir "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile")
      +  BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")}
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}"
       endif
       
       else
      -  BOARDMAKE = $(dir "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile")
      +  BOARDMAKE = ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi}
       
       ifeq ($(WINTOOL),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
       endif
       
       else
         LIBPATHS += -L"$(TOPDIR)/lib"
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
         LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
       endif
       endif
       endif
       
       LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
      +ifeq ($(BOARDMAKE),y)
      +  LDLIBS += -lboard
      +endif
       
       LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
       
      @@ -125,7 +128,7 @@ board/libboard$(LIBEXT):
       nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT)
       	@echo "LD: nuttx$(EXEEXT)"
       	$(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
      -		--start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
      +		--start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
       	$(Q) $(NM) $(NUTTX)$(EXEEXT) | \
       	grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
       	sort > $(TOPDIR)/System.map
      @@ -143,7 +146,7 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
       # Dependencies
       
       .depend: Makefile chip/Make.defs $(SRCS)
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
       endif
       	$(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
      @@ -153,14 +156,14 @@ endif
       depend: .depend
       
       clean:
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
       endif
       	$(Q) rm -f libarch$(LIBEXT) *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      -ifdef BOARDMAKE
      +ifeq ($(BOARDMAKE),y)
       	$(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
       endif
       	$(Q) rm -f Make.dep .depend
      diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk
      index 84643b8ccb..06a312fc50 100644
      --- a/nuttx/tools/Config.mk
      +++ b/nuttx/tools/Config.mk
      @@ -71,7 +71,7 @@ endef
       else
       define ARCHIVE
       	@echo "AR: $2"
      -	$(Q) $(AR) $1 $(subst ",,$(2)) || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
      +	$(Q) $(AR) $1 $(subst ",,$(2)) || { echo "$(AR) $1 FAILED!" ; exit 1 ; }
       endef
       endif
       
      
      From d3ac724c7b81fd155c046fbc68c8102ba6a58b92 Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Mon, 12 Nov 2012 15:22:27 +0000
      Subject: [PATCH 110/206] Changes to get a clean ez80 build using the ZDS 5.1.1
       toolchain
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5341 42af7a65-404d-4744-a932-0658087f49c3
      ---
       apps/examples/adc/Makefile               | 10 ++++--
       apps/examples/buttons/Makefile           | 10 ++++--
       apps/examples/can/Makefile               | 10 ++++--
       apps/examples/cdcacm/Makefile            | 10 ++++--
       apps/examples/composite/Makefile         | 10 ++++--
       apps/examples/cxxtest/Makefile           | 10 ++++--
       apps/examples/dhcpd/Makefile             | 10 ++++--
       apps/examples/discover/Makefile          | 10 ++++--
       apps/examples/elf/Makefile               | 10 ++++--
       apps/examples/ftpc/Makefile              | 10 ++++--
       apps/examples/ftpd/Makefile              | 10 ++++--
       apps/examples/hello/Makefile             | 10 ++++--
       apps/examples/helloxx/Makefile           | 10 ++++--
       apps/examples/hidkbd/Makefile            | 10 ++++--
       apps/examples/igmp/Makefile              | 10 ++++--
       apps/examples/json/Makefile              | 10 ++++--
       apps/examples/lcdrw/Makefile             | 10 ++++--
       apps/examples/mm/Makefile                | 10 ++++--
       apps/examples/modbus/Makefile            | 10 ++++--
       apps/examples/mount/Makefile             | 10 ++++--
       apps/examples/nettest/Makefile           | 15 +++++----
       apps/examples/nsh/Makefile               | 10 ++++--
       apps/examples/null/Makefile              | 10 ++++--
       apps/examples/nx/Makefile                | 10 ++++--
       apps/examples/nxconsole/Makefile         | 10 ++++--
       apps/examples/nxffs/Makefile             | 10 ++++--
       apps/examples/nxflat/Makefile            | 10 ++++--
       apps/examples/nxhello/Makefile           | 10 ++++--
       apps/examples/nximage/Makefile           | 10 ++++--
       apps/examples/nxlines/Makefile           | 10 ++++--
       apps/examples/nxtext/Makefile            | 10 ++++--
       apps/examples/ostest/Makefile            | 10 ++++--
       apps/examples/pashello/Makefile          | 10 ++++--
       apps/examples/pipe/Makefile              | 10 ++++--
       apps/examples/poll/Makefile              | 10 ++++--
       apps/examples/pwm/Makefile               | 10 ++++--
       apps/examples/qencoder/Makefile          | 10 ++++--
       apps/examples/relays/Makefile            | 10 ++++--
       apps/examples/rgmp/Makefile              | 10 ++++--
       apps/examples/romfs/Makefile             | 10 ++++--
       apps/examples/sendmail/Makefile          | 10 ++++--
       apps/examples/serloop/Makefile           | 10 ++++--
       apps/examples/telnetd/Makefile           | 10 ++++--
       apps/examples/thttpd/Makefile            | 10 ++++--
       apps/examples/tiff/Makefile              | 10 ++++--
       apps/examples/touchscreen/Makefile       | 10 ++++--
       apps/examples/udp/Makefile               | 10 ++++--
       apps/examples/uip/Makefile               | 10 ++++--
       apps/examples/usbserial/Makefile         | 10 ++++--
       apps/examples/usbstorage/Makefile        | 10 ++++--
       apps/examples/usbterm/Makefile           | 10 ++++--
       apps/examples/watchdog/Makefile          | 10 ++++--
       apps/examples/wget/Makefile              | 10 ++++--
       apps/examples/wgetjson/Makefile          | 10 ++++--
       apps/examples/wlan/Makefile              | 10 ++++--
       apps/examples/xmlrpc/Makefile            | 10 ++++--
       apps/graphics/tiff/Makefile              | 10 ++++--
       apps/interpreters/ficl/Makefile          | 10 ++++--
       apps/modbus/Makefile                     | 10 ++++--
       apps/namedapp/Makefile                   |  4 +++
       apps/netutils/codecs/Makefile            | 10 ++++--
       apps/netutils/dhcpc/Makefile             | 10 ++++--
       apps/netutils/dhcpd/Makefile             | 10 ++++--
       apps/netutils/discover/Makefile          | 10 ++++--
       apps/netutils/ftpc/Makefile              | 10 ++++--
       apps/netutils/ftpd/Makefile              | 10 ++++--
       apps/netutils/json/Makefile              | 10 ++++--
       apps/netutils/resolv/Makefile            | 10 ++++--
       apps/netutils/smtp/Makefile              | 10 ++++--
       apps/netutils/telnetd/Makefile           | 10 ++++--
       apps/netutils/tftpc/Makefile             | 10 ++++--
       apps/netutils/thttpd/Makefile            | 10 ++++--
       apps/netutils/uiplib/Makefile            | 10 ++++--
       apps/netutils/webclient/Makefile         | 10 ++++--
       apps/netutils/webserver/Makefile         | 10 ++++--
       apps/netutils/xmlrpc/Makefile            | 11 ++++---
       apps/nshlib/Makefile                     | 10 ++++--
       apps/nshlib/nsh_dbgcmds.c                |  5 +--
       apps/system/free/Makefile                | 10 ++++--
       apps/system/i2c/Makefile                 | 10 ++++--
       apps/system/install/Makefile             | 10 ++++--
       apps/system/poweroff/Makefile            | 10 ++++--
       apps/system/ramtron/Makefile             | 10 ++++--
       apps/system/readline/Makefile            | 10 ++++--
       apps/system/sdcard/Makefile              | 10 ++++--
       apps/system/sysinfo/Makefile             | 10 ++++--
       nuttx/arch/z80/src/Makefile.zdsii        | 42 ++++++++++++------------
       nuttx/configs/ez80f910200kitg/README.txt | 28 +++++++++-------
       nuttx/configs/ez80f910200zco/README.txt  | 30 +++++++++--------
       nuttx/include/nuttx/usb/usbdev_trace.h   |  4 ---
       nuttx/mm/mm_initialize.c                 |  6 ++--
       91 files changed, 654 insertions(+), 311 deletions(-)
      
      diff --git a/apps/examples/adc/Makefile b/apps/examples/adc/Makefile
      index fab1a91ab0..b2720d2404 100644
      --- a/apps/examples/adc/Makefile
      +++ b/apps/examples/adc/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/buttons/Makefile b/apps/examples/buttons/Makefile
      index 780941562d..34d928df86 100644
      --- a/apps/examples/buttons/Makefile
      +++ b/apps/examples/buttons/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/can/Makefile b/apps/examples/can/Makefile
      index 35c7538f3b..3e00083cd7 100644
      --- a/apps/examples/can/Makefile
      +++ b/apps/examples/can/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/cdcacm/Makefile b/apps/examples/cdcacm/Makefile
      index 3ffdf82b4e..3a6075df3e 100644
      --- a/apps/examples/cdcacm/Makefile
      +++ b/apps/examples/cdcacm/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/composite/Makefile b/apps/examples/composite/Makefile
      index a8563ee61b..c47be8726c 100644
      --- a/apps/examples/composite/Makefile
      +++ b/apps/examples/composite/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/cxxtest/Makefile b/apps/examples/cxxtest/Makefile
      index a2c29169f0..fdea675106 100644
      --- a/apps/examples/cxxtest/Makefile
      +++ b/apps/examples/cxxtest/Makefile
      @@ -50,10 +50,14 @@ CXXOBJS		= $(CXXSRCS:.cxx=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS) $(CXXSRCS)
       OBJS		= $(AOBJS) $(COBJS) $(CXXOBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/dhcpd/Makefile b/apps/examples/dhcpd/Makefile
      index 8b39c58d46..5be2a845f4 100644
      --- a/apps/examples/dhcpd/Makefile
      +++ b/apps/examples/dhcpd/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/discover/Makefile b/apps/examples/discover/Makefile
      index f4801c569d..5094bf6705 100644
      --- a/apps/examples/discover/Makefile
      +++ b/apps/examples/discover/Makefile
      @@ -55,10 +55,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/elf/Makefile b/apps/examples/elf/Makefile
      index 1c7ac4a238..d90c118d3e 100644
      --- a/apps/examples/elf/Makefile
      +++ b/apps/examples/elf/Makefile
      @@ -48,10 +48,14 @@ COBJS = $(CSRCS:.c=$(OBJEXT))
       SRCS = $(ASRCS) $(CSRCS)
       OBJS = $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN = "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN = "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path . --dep-path tests
      diff --git a/apps/examples/ftpc/Makefile b/apps/examples/ftpc/Makefile
      index 96ed512e24..93c7928a26 100644
      --- a/apps/examples/ftpc/Makefile
      +++ b/apps/examples/ftpc/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/ftpd/Makefile b/apps/examples/ftpd/Makefile
      index f6bab4f403..25a572db7c 100644
      --- a/apps/examples/ftpd/Makefile
      +++ b/apps/examples/ftpd/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/hello/Makefile b/apps/examples/hello/Makefile
      index a556e6f0f3..a3d245466e 100644
      --- a/apps/examples/hello/Makefile
      +++ b/apps/examples/hello/Makefile
      @@ -54,10 +54,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/helloxx/Makefile b/apps/examples/helloxx/Makefile
      index de9b1cf9fe..66669f1089 100644
      --- a/apps/examples/helloxx/Makefile
      +++ b/apps/examples/helloxx/Makefile
      @@ -50,10 +50,14 @@ CXXOBJS		= $(CXXSRCS:.cxx=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS) $(CXXSRCS)
       OBJS		= $(AOBJS) $(COBJS) $(CXXOBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/hidkbd/Makefile b/apps/examples/hidkbd/Makefile
      index 36762825c7..29746888c2 100644
      --- a/apps/examples/hidkbd/Makefile
      +++ b/apps/examples/hidkbd/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/igmp/Makefile b/apps/examples/igmp/Makefile
      index cf65c41bd8..361e3354a6 100644
      --- a/apps/examples/igmp/Makefile
      +++ b/apps/examples/igmp/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/json/Makefile b/apps/examples/json/Makefile
      index 0880193ad6..b2d7167762 100644
      --- a/apps/examples/json/Makefile
      +++ b/apps/examples/json/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/lcdrw/Makefile b/apps/examples/lcdrw/Makefile
      index 0de93c9e9a..32b074b58e 100644
      --- a/apps/examples/lcdrw/Makefile
      +++ b/apps/examples/lcdrw/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/mm/Makefile b/apps/examples/mm/Makefile
      index aff99d4609..95e2ec2472 100644
      --- a/apps/examples/mm/Makefile
      +++ b/apps/examples/mm/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/modbus/Makefile b/apps/examples/modbus/Makefile
      index 10abd8780d..015006773d 100644
      --- a/apps/examples/modbus/Makefile
      +++ b/apps/examples/modbus/Makefile
      @@ -54,10 +54,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/mount/Makefile b/apps/examples/mount/Makefile
      index d19f2894ae..2ed83d66bf 100644
      --- a/apps/examples/mount/Makefile
      +++ b/apps/examples/mount/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/nettest/Makefile b/apps/examples/nettest/Makefile
      index 979a2391ee..0e4f972ee1 100644
      --- a/apps/examples/nettest/Makefile
      +++ b/apps/examples/nettest/Makefile
      @@ -54,11 +54,14 @@ TARG_COBJS	= $(TARG_CSRCS:.c=$(OBJEXT))
       TARG_SRCS	= $(TARG_ASRCS) $(TARG_CSRCS)
       TARG_OBJS	= $(TARG_AOBJS) $(TARG_COBJS)
       
      -TARG_POSIX	= "$(APPDIR)/libapps$(LIBEXT)"
      -ifeq ($(WINTOOL),y)
      -  TARG_BIN	= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  TARG_BIN		= ..\..\libapps$(LIBEXT)
       else
      -  TARG_BIN	= "$(TARG_POSIX)"
      +ifeq ($(WINTOOL),y)
      +  TARG_BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  TARG_BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       HOSTCFLAGS	+= -DCONFIG_EXAMPLES_NETTEST_HOST=1
      @@ -70,8 +73,6 @@ ifeq ($(CONFIG_EXAMPLES_NETTEST_PERFORMANCE),y)
       HOSTCFLAGS	+= -DCONFIG_EXAMPLES_NETTEST_PERFORMANCE=1
       endif
       
      -
      -
       HOST_SRCS	= host.c
       ifeq ($(CONFIG_EXAMPLES_NETTEST_SERVER),y)
       HOST_SRCS	+= nettest_client.c
      @@ -130,7 +131,7 @@ context: .context
       depend: .depend
       
       clean:
      -	@rm -f $(TARG_POSIX) $(HOST_BIN) .built *.o *~ .*.swp
      +	@rm -f $(HOST_BIN) .built *.o *~ .*.swp
       	$(call CLEAN)
       
       distclean: clean
      diff --git a/apps/examples/nsh/Makefile b/apps/examples/nsh/Makefile
      index 600ea7090b..049b62e5dd 100644
      --- a/apps/examples/nsh/Makefile
      +++ b/apps/examples/nsh/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/null/Makefile b/apps/examples/null/Makefile
      index baa9ac2c37..76b3c0588a 100644
      --- a/apps/examples/null/Makefile
      +++ b/apps/examples/null/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/nx/Makefile b/apps/examples/nx/Makefile
      index d8befe5580..ddcc025a03 100644
      --- a/apps/examples/nx/Makefile
      +++ b/apps/examples/nx/Makefile
      @@ -51,10 +51,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/nxconsole/Makefile b/apps/examples/nxconsole/Makefile
      index bbbf678128..2c484dfdad 100644
      --- a/apps/examples/nxconsole/Makefile
      +++ b/apps/examples/nxconsole/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/nxffs/Makefile b/apps/examples/nxffs/Makefile
      index 2ae286cd07..210f40ea94 100644
      --- a/apps/examples/nxffs/Makefile
      +++ b/apps/examples/nxffs/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/nxflat/Makefile b/apps/examples/nxflat/Makefile
      index 3a34f1fa3a..9bf0b0c932 100644
      --- a/apps/examples/nxflat/Makefile
      +++ b/apps/examples/nxflat/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/nxhello/Makefile b/apps/examples/nxhello/Makefile
      index 79b169a771..48e982c32c 100644
      --- a/apps/examples/nxhello/Makefile
      +++ b/apps/examples/nxhello/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/nximage/Makefile b/apps/examples/nximage/Makefile
      index 0e8c3b0de6..0340e932d1 100644
      --- a/apps/examples/nximage/Makefile
      +++ b/apps/examples/nximage/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/nxlines/Makefile b/apps/examples/nxlines/Makefile
      index e12e310b87..5c185f038c 100644
      --- a/apps/examples/nxlines/Makefile
      +++ b/apps/examples/nxlines/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/nxtext/Makefile b/apps/examples/nxtext/Makefile
      index 0510992da0..62e7ac1e48 100644
      --- a/apps/examples/nxtext/Makefile
      +++ b/apps/examples/nxtext/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/ostest/Makefile b/apps/examples/ostest/Makefile
      index 7c4354b1d1..72582e510f 100644
      --- a/apps/examples/ostest/Makefile
      +++ b/apps/examples/ostest/Makefile
      @@ -98,10 +98,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/pashello/Makefile b/apps/examples/pashello/Makefile
      index 2e2e428e91..88c7bddec1 100644
      --- a/apps/examples/pashello/Makefile
      +++ b/apps/examples/pashello/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/pipe/Makefile b/apps/examples/pipe/Makefile
      index 8afb29188a..9596167fca 100644
      --- a/apps/examples/pipe/Makefile
      +++ b/apps/examples/pipe/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/poll/Makefile b/apps/examples/poll/Makefile
      index 1483f53421..cdb570fc7a 100644
      --- a/apps/examples/poll/Makefile
      +++ b/apps/examples/poll/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/pwm/Makefile b/apps/examples/pwm/Makefile
      index beeb25e7cc..e05c5cdbed 100644
      --- a/apps/examples/pwm/Makefile
      +++ b/apps/examples/pwm/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/qencoder/Makefile b/apps/examples/qencoder/Makefile
      index d6eaaf6cbb..499ae7475d 100644
      --- a/apps/examples/qencoder/Makefile
      +++ b/apps/examples/qencoder/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/relays/Makefile b/apps/examples/relays/Makefile
      index fdb7927730..efd15b61aa 100644
      --- a/apps/examples/relays/Makefile
      +++ b/apps/examples/relays/Makefile
      @@ -48,10 +48,14 @@ COBJS = $(CSRCS:.c=$(OBJEXT))
       SRCS = $(ASRCS) $(CSRCS)
       OBJS = $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN = "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH = --dep-path .
      diff --git a/apps/examples/rgmp/Makefile b/apps/examples/rgmp/Makefile
      index 04aab7bbe6..8207ee9702 100644
      --- a/apps/examples/rgmp/Makefile
      +++ b/apps/examples/rgmp/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/romfs/Makefile b/apps/examples/romfs/Makefile
      index 47b08134a9..2df77a0009 100644
      --- a/apps/examples/romfs/Makefile
      +++ b/apps/examples/romfs/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/sendmail/Makefile b/apps/examples/sendmail/Makefile
      index b7c4d32dcb..e7368e26dc 100644
      --- a/apps/examples/sendmail/Makefile
      +++ b/apps/examples/sendmail/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/serloop/Makefile b/apps/examples/serloop/Makefile
      index 8ec7f07596..740932b2f4 100644
      --- a/apps/examples/serloop/Makefile
      +++ b/apps/examples/serloop/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/telnetd/Makefile b/apps/examples/telnetd/Makefile
      index 3371f90c22..3df4026abf 100644
      --- a/apps/examples/telnetd/Makefile
      +++ b/apps/examples/telnetd/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/thttpd/Makefile b/apps/examples/thttpd/Makefile
      index 4f303c9527..4da7e79970 100644
      --- a/apps/examples/thttpd/Makefile
      +++ b/apps/examples/thttpd/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/tiff/Makefile b/apps/examples/tiff/Makefile
      index c86519fde4..1c44b48fad 100644
      --- a/apps/examples/tiff/Makefile
      +++ b/apps/examples/tiff/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/touchscreen/Makefile b/apps/examples/touchscreen/Makefile
      index c82a94b44a..88e88185a1 100644
      --- a/apps/examples/touchscreen/Makefile
      +++ b/apps/examples/touchscreen/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/udp/Makefile b/apps/examples/udp/Makefile
      index 0aa2aaa095..2f7d493224 100644
      --- a/apps/examples/udp/Makefile
      +++ b/apps/examples/udp/Makefile
      @@ -54,10 +54,14 @@ TARG_COBJS	= $(TARG_CSRCS:.c=$(OBJEXT))
       TARG_SRCS	= $(TARG_ASRCS) $(TARG_CSRCS)
       TARG_OBJS	= $(TARG_AOBJS) $(TARG_COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  TARG_BIN	= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  TARG_BIN	= ..\..\libapps$(LIBEXT)
       else
      -  TARG_BIN	= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  TARG_BIN	= ..\\..\\libapps$(LIBEXT)
      +else
      +  TARG_BIN	= ../../libapps$(LIBEXT)
      +endif
       endif
       
       HOSTCFLAGS	+= -DCONFIG_EXAMPLES_UDP_HOST=1
      diff --git a/apps/examples/uip/Makefile b/apps/examples/uip/Makefile
      index 4b4dfc9d9b..01e37dd72c 100644
      --- a/apps/examples/uip/Makefile
      +++ b/apps/examples/uip/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/usbserial/Makefile b/apps/examples/usbserial/Makefile
      index 06d4ab2981..26bbc1b1a7 100644
      --- a/apps/examples/usbserial/Makefile
      +++ b/apps/examples/usbserial/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/usbstorage/Makefile b/apps/examples/usbstorage/Makefile
      index a5da68ef0a..dfbdc8b47c 100644
      --- a/apps/examples/usbstorage/Makefile
      +++ b/apps/examples/usbstorage/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/usbterm/Makefile b/apps/examples/usbterm/Makefile
      index 16d5d4b53f..1dd30e8bef 100644
      --- a/apps/examples/usbterm/Makefile
      +++ b/apps/examples/usbterm/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/watchdog/Makefile b/apps/examples/watchdog/Makefile
      index b55a372186..87a7f82968 100644
      --- a/apps/examples/watchdog/Makefile
      +++ b/apps/examples/watchdog/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/wget/Makefile b/apps/examples/wget/Makefile
      index f69ebe71ba..19f16534b7 100644
      --- a/apps/examples/wget/Makefile
      +++ b/apps/examples/wget/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/wgetjson/Makefile b/apps/examples/wgetjson/Makefile
      index 73e3ed8447..f41464436f 100644
      --- a/apps/examples/wgetjson/Makefile
      +++ b/apps/examples/wgetjson/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/wlan/Makefile b/apps/examples/wlan/Makefile
      index 3d944b54a5..9268c74568 100644
      --- a/apps/examples/wlan/Makefile
      +++ b/apps/examples/wlan/Makefile
      @@ -49,10 +49,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/examples/xmlrpc/Makefile b/apps/examples/xmlrpc/Makefile
      index 6cde609ddd..061f8fc474 100644
      --- a/apps/examples/xmlrpc/Makefile
      +++ b/apps/examples/xmlrpc/Makefile
      @@ -55,10 +55,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/graphics/tiff/Makefile b/apps/graphics/tiff/Makefile
      index b98616bfce..ed445f132c 100644
      --- a/apps/graphics/tiff/Makefile
      +++ b/apps/graphics/tiff/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/interpreters/ficl/Makefile b/apps/interpreters/ficl/Makefile
      index c306f67faa..e905b9eff8 100644
      --- a/apps/interpreters/ficl/Makefile
      +++ b/apps/interpreters/ficl/Makefile
      @@ -69,10 +69,14 @@ COBJS = $(CSRCS:.c=$(OBJEXT))
       SRCS = $(ASRCS) $(CSRCS)
       OBJS = $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOT_DEPPATH = --dep-path .
      diff --git a/apps/modbus/Makefile b/apps/modbus/Makefile
      index 321bf09b5b..2b807dc48f 100644
      --- a/apps/modbus/Makefile
      +++ b/apps/modbus/Makefile
      @@ -66,10 +66,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../libapps$(LIBEXT)
      +endif
       endif
       
       # Build targets
      diff --git a/apps/namedapp/Makefile b/apps/namedapp/Makefile
      index ce16376aed..df80947d61 100644
      --- a/apps/namedapp/Makefile
      +++ b/apps/namedapp/Makefile
      @@ -54,11 +54,15 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\libapps$(LIBEXT)
      +else
       ifeq ($(WINTOOL),y)
         BIN		= ..\\libapps$(LIBEXT)
       else
         BIN		= ../libapps$(LIBEXT)
       endif
      +endif
       
       ROOTDEPPATH	= --dep-path .
       VPATH		= 
      diff --git a/apps/netutils/codecs/Makefile b/apps/netutils/codecs/Makefile
      index 7bab174dee..c3780756df 100644
      --- a/apps/netutils/codecs/Makefile
      +++ b/apps/netutils/codecs/Makefile
      @@ -46,10 +46,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/dhcpc/Makefile b/apps/netutils/dhcpc/Makefile
      index 161d8f68f4..7ab76b2191 100644
      --- a/apps/netutils/dhcpc/Makefile
      +++ b/apps/netutils/dhcpc/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/dhcpd/Makefile b/apps/netutils/dhcpd/Makefile
      index 8468153d47..11196bba1c 100644
      --- a/apps/netutils/dhcpd/Makefile
      +++ b/apps/netutils/dhcpd/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/discover/Makefile b/apps/netutils/discover/Makefile
      index b14d8040b3..86e429cd50 100644
      --- a/apps/netutils/discover/Makefile
      +++ b/apps/netutils/discover/Makefile
      @@ -55,10 +55,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/ftpc/Makefile b/apps/netutils/ftpc/Makefile
      index 33aee9d8e7..e024f3c534 100644
      --- a/apps/netutils/ftpc/Makefile
      +++ b/apps/netutils/ftpc/Makefile
      @@ -68,10 +68,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/ftpd/Makefile b/apps/netutils/ftpd/Makefile
      index 738eba226e..b2579a4166 100644
      --- a/apps/netutils/ftpd/Makefile
      +++ b/apps/netutils/ftpd/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/json/Makefile b/apps/netutils/json/Makefile
      index 1fe14413b8..99f2e81f65 100644
      --- a/apps/netutils/json/Makefile
      +++ b/apps/netutils/json/Makefile
      @@ -46,10 +46,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/resolv/Makefile b/apps/netutils/resolv/Makefile
      index 04ba2d17b9..ee9ee5dca9 100644
      --- a/apps/netutils/resolv/Makefile
      +++ b/apps/netutils/resolv/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/smtp/Makefile b/apps/netutils/smtp/Makefile
      index 27f8e323ab..f1762a0bc2 100644
      --- a/apps/netutils/smtp/Makefile
      +++ b/apps/netutils/smtp/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/telnetd/Makefile b/apps/netutils/telnetd/Makefile
      index 922fa638d0..8132aa1b16 100644
      --- a/apps/netutils/telnetd/Makefile
      +++ b/apps/netutils/telnetd/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/tftpc/Makefile b/apps/netutils/tftpc/Makefile
      index b544da8502..3e5c620b65 100644
      --- a/apps/netutils/tftpc/Makefile
      +++ b/apps/netutils/tftpc/Makefile
      @@ -54,10 +54,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/thttpd/Makefile b/apps/netutils/thttpd/Makefile
      index 2f6120f409..c7550a284e 100644
      --- a/apps/netutils/thttpd/Makefile
      +++ b/apps/netutils/thttpd/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/uiplib/Makefile b/apps/netutils/uiplib/Makefile
      index 4242c3354f..2d7a1925ae 100644
      --- a/apps/netutils/uiplib/Makefile
      +++ b/apps/netutils/uiplib/Makefile
      @@ -68,10 +68,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/webclient/Makefile b/apps/netutils/webclient/Makefile
      index c6f9301bfc..6c05abe315 100644
      --- a/apps/netutils/webclient/Makefile
      +++ b/apps/netutils/webclient/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/webserver/Makefile b/apps/netutils/webserver/Makefile
      index 5fdd6b8d73..13c8475bd5 100644
      --- a/apps/netutils/webserver/Makefile
      +++ b/apps/netutils/webserver/Makefile
      @@ -59,10 +59,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/netutils/xmlrpc/Makefile b/apps/netutils/xmlrpc/Makefile
      index e8118d7e29..b2e247b110 100644
      --- a/apps/netutils/xmlrpc/Makefile
      +++ b/apps/netutils/xmlrpc/Makefile
      @@ -40,7 +40,6 @@
       -include $(TOPDIR)/Make.defs
       include $(APPDIR)/Make.defs
       
      -
       ASRCS		=
       CSRCS		= 
       
      @@ -54,10 +53,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile
      index a16644c035..313a1f6cb6 100644
      --- a/apps/nshlib/Makefile
      +++ b/apps/nshlib/Makefile
      @@ -89,10 +89,14 @@ COBJS = $(CSRCS:.c=$(OBJEXT))
       SRCS = $(ASRCS) $(CSRCS)
       OBJS = $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN = "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\libapps$(LIBEXT)
       else
      -  BIN = "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH = --dep-path .
      diff --git a/apps/nshlib/nsh_dbgcmds.c b/apps/nshlib/nsh_dbgcmds.c
      index 627c56bcda..5463e0f5a2 100644
      --- a/apps/nshlib/nsh_dbgcmds.c
      +++ b/apps/nshlib/nsh_dbgcmds.c
      @@ -367,9 +367,10 @@ int cmd_xd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
       int cmd_hexdump(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
       {
         uint8_t buffer[IOBUFFERSIZE];
      +  char msg[32];
      +  int position;
         int fd;
         int ret = OK;
      -  char msg[32];
         
         /* Open the file for reading */
       
      @@ -380,7 +381,7 @@ int cmd_hexdump(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
             return ERROR;
           }
         
      -  int position = 0;
      +  position = 0;
         for (;;)
         {
           int nbytesread = read(fd, buffer, IOBUFFERSIZE);
      diff --git a/apps/system/free/Makefile b/apps/system/free/Makefile
      index 3a318a492c..9db10f790c 100644
      --- a/apps/system/free/Makefile
      +++ b/apps/system/free/Makefile
      @@ -61,10 +61,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile
      index 3bad936755..8e8130c134 100644
      --- a/apps/system/i2c/Makefile
      +++ b/apps/system/i2c/Makefile
      @@ -48,10 +48,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/system/install/Makefile b/apps/system/install/Makefile
      index cf6371092a..28858bf283 100644
      --- a/apps/system/install/Makefile
      +++ b/apps/system/install/Makefile
      @@ -62,10 +62,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/system/poweroff/Makefile b/apps/system/poweroff/Makefile
      index 6956755fcb..7a9ec2ebdf 100644
      --- a/apps/system/poweroff/Makefile
      +++ b/apps/system/poweroff/Makefile
      @@ -62,10 +62,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/system/ramtron/Makefile b/apps/system/ramtron/Makefile
      index 339b99fa95..41d1e7d45b 100644
      --- a/apps/system/ramtron/Makefile
      +++ b/apps/system/ramtron/Makefile
      @@ -62,10 +62,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/system/readline/Makefile b/apps/system/readline/Makefile
      index 471a811a31..08288fa952 100644
      --- a/apps/system/readline/Makefile
      +++ b/apps/system/readline/Makefile
      @@ -52,10 +52,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/system/sdcard/Makefile b/apps/system/sdcard/Makefile
      index 4600cdf685..0d7232c69a 100644
      --- a/apps/system/sdcard/Makefile
      +++ b/apps/system/sdcard/Makefile
      @@ -62,10 +62,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/apps/system/sysinfo/Makefile b/apps/system/sysinfo/Makefile
      index 9f317e123a..fafdb4e54a 100644
      --- a/apps/system/sysinfo/Makefile
      +++ b/apps/system/sysinfo/Makefile
      @@ -62,10 +62,14 @@ COBJS		= $(CSRCS:.c=$(OBJEXT))
       SRCS		= $(ASRCS) $(CSRCS)
       OBJS		= $(AOBJS) $(COBJS)
       
      -ifeq ($(WINTOOL),y)
      -  BIN		= "${shell cygpath -w  $(APPDIR)/libapps$(LIBEXT)}"
      +ifeq ($(CONFIG_WINDOWS_NATIVE),y)
      +  BIN		= ..\..\libapps$(LIBEXT)
       else
      -  BIN		= "$(APPDIR)/libapps$(LIBEXT)"
      +ifeq ($(WINTOOL),y)
      +  BIN		= ..\\..\\libapps$(LIBEXT)
      +else
      +  BIN		= ../../libapps$(LIBEXT)
      +endif
       endif
       
       ROOTDEPPATH	= --dep-path .
      diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii
      index 4eaad3c325..3a1727aef9 100644
      --- a/nuttx/arch/z80/src/Makefile.zdsii
      +++ b/nuttx/arch/z80/src/Makefile.zdsii
      @@ -41,7 +41,7 @@ USRINCLUDES	= -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common'
       INCLUDES	= $(ARCHSTDINCLUDES) $(USRINCLUDES)
       CFLAGS		= $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
       CPPFLAGS	+= -I$(ARCHSRCDIR) -I$(ZDSSTDINCDIR) -I$(ZDSZILOGINCDIR)
      -LDFLAGS 	+= "${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}"
      +LDFLAGS 	+= @nuttx.linkcmd
       
       ############################################################################
       # Files and directories
      @@ -93,37 +93,37 @@ board/libboard$(LIBEXT):
       
       nuttx.linkcmd: $(LINKCMDTEMPLATE)
       	$(Q) cp -f $(LINKCMDTEMPLATE) nuttx.linkcmd
      -	@echo "\"${shell cygpath -w $(TOPDIR)/nuttx}\"= \\" >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ARCHSRCDIR)/$(HEAD_OBJ)}\", \\" >>nuttx.linkcmd
      +	@echo "\"${shell cygpath -w "$(TOPDIR)/nuttx"}\"= \\" >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ARCHSRCDIR)/$(HEAD_OBJ)"}\", \\" >>nuttx.linkcmd
       	$(Q) ( for lib in $(LINKLIBS); do \
      -		echo "  \"`cygpath -w $(TOPDIR)/$${lib}`\", \\" >>nuttx.linkcmd; \
      +		echo "  \"`cygpath -w "$(TOPDIR)/lib/$${lib}"`\", \\" >>nuttx.linkcmd; \
       	done ; )
      -	@echo "  \"${shell cygpath -w $(ARCHSRCDIR)/board/libboard$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ARCHSRCDIR)/board/libboard$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
       ifeq ($(CONFIG_ARCH_CHIP_Z8F640X),y)
      -	@echo "  \"${shell cygpath -w $(ZDSSTDLIBDIR)/chelprevaaD$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSSTDLIBDIR)/crtrevaaLDD$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSSTDLIBDIR)/fprevaaLDD$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSZILOGLIBDIR)/csiorevaaLDD$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSZILOGLIBDIR)/zsldevinitdummy$(LIBEXT)}\""  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSSTDLIBDIR)/chelprevaaD$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSSTDLIBDIR)/crtrevaaLDD$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSSTDLIBDIR)/fprevaaLDD$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSZILOGLIBDIR)/csiorevaaLDD$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSZILOGLIBDIR)/zsldevinitdummy$(LIBEXT)"}\""  >>nuttx.linkcmd
       endif
       ifeq ($(CONFIG_ARCH_CHIP_Z8F642X),y)
      -	@echo "  \"${shell cygpath -w $(ZDSSTDLIBDIR)/chelpD$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSSTDLIBDIR)/crtLDD$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSSTDLIBDIR)/fpdumyLD$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSZILOGLIBDIR)/csioLDD$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSZILOGLIBDIR)/zsldevinitdummy$(LIBEXT)}\""  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSSTDLIBDIR)/chelpD$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSSTDLIBDIR)/crtLDD$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSSTDLIBDIR)/fpdumyLD$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSZILOGLIBDIR)/csioLDD$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSZILOGLIBDIR)/zsldevinitdummy$(LIBEXT)"}\""  >>nuttx.linkcmd
       endif
       ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y)
      -	@echo "  \"${shell cygpath -w $(ZDSSTDLIBDIR)/chelp$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSSTDLIBDIR)/crt$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSSTDLIBDIR)/fplib$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSZILOGLIBDIR)/gpio$(LIBEXT)}\", \\"  >>nuttx.linkcmd
      -	@echo "  \"${shell cygpath -w $(ZDSZILOGLIBDIR)/uartf91$(LIBEXT)}\""  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSSTDLIBDIR)/chelp$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSSTDLIBDIR)/crt$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSSTDLIBDIR)/fplib$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSZILOGLIBDIR)/gpio$(LIBEXT)"}\", \\"  >>nuttx.linkcmd
      +	@echo "  \"${shell cygpath -w "$(ZDSZILOGLIBDIR)/uartf91$(LIBEXT)"}\""  >>nuttx.linkcmd
       endif
       
       nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) nuttx.linkcmd
       	@echo "LD:  nuttx.hex"
      -	$(Q) $(LD) $(LDFLAGS)
      +	$(Q) "$(LD)" $(LDFLAGS)
       
       .depend: Makefile chip/Make.defs $(DEPSRCS)
       	$(Q) if [ -e board/Makefile ]; then \
      diff --git a/nuttx/configs/ez80f910200kitg/README.txt b/nuttx/configs/ez80f910200kitg/README.txt
      index 05f767c791..57520b88e6 100644
      --- a/nuttx/configs/ez80f910200kitg/README.txt
      +++ b/nuttx/configs/ez80f910200kitg/README.txt
      @@ -5,7 +5,7 @@ ZDS-II Compiler Versions
       ^^^^^^^^^^^^^^^^^^^^^^^^
       
       Different configurations have been build for this board using ZDS-11
      -Versions 4.11.0 and 4.11.1.  You have to check the files */Make.defs
      +Versions 4.11.0, 4.11.1, and 5.1.1  You have to check the files */Make.defs
       to see how the build is configured:  Check the definitions of
       ZDSVERSION (if present) and ZDSINSTALLDIR.
       
      @@ -14,8 +14,9 @@ different versions of .linkcmd and .zdsproj files as well.
       
       Version 4.11.0
       
      -  Although it compiles without error, the 4.11.0 compiler generates
      -  This is the only version that this code has been built against.
      +  The 5.1.1 version of the ZDS-II tools are currently configured for
      +  all ez80 boards.  However, it is the older version 4.11.0 that this code
      +  has been verified against.
         
         Although it compiles without error, the 4.11.0 compiler generates
         bad code on one of the files, mm/mm_initialize.c.  Below is a simple work-
      @@ -34,21 +35,26 @@ Version 4.11.0
        
          /* Set up global variables */
       
      +   UPDATE:  I don't know if 4.11.1 has this same problem (I bet not since
      +   I submitted the bug to ZiLOG), but I have permanently worked around the
      +   above problem for all ZiLOG compilers.
      +
       Version 5.1.1
       
         On June 22, 2011 I verified that these configurations build successfully
      -  with the 5.1.1 ZDS-II version.  All that is required to used ZDS-II is
      -  to modify the Make.defs file so that the correct version is used.  That
      -  version should also be changed in the (optional) setenv.sh file.
      +  with the 5.1.1 ZDS-II version.  On November 12, 2012, all of the configurations
      +  were converted to use 5.1.1, but have not been verified on a running target.
       
      -  The above kludge for 4.11.0 is not required.
      +  The above kludge for 4.11.0 is not required with 5.1.1.
       
      -  I had to make additional changes to the ZDS path in Make.defs (and also
      -  in setenv.sh) when the 32-bit ZDS-II tools are installed on my 64-bit
      -  Windows 7 system.
      +  Paths were also updated that are specific to a 32-bit toolchain running on
      +  a 64 bit windows platform.  Change to a different toolchain, you will need
      +  to modify the versioning in Make.defs and setenv.sh; if you want to build
      +  on a different platform, you will need to change the path in the ZDS binaries
      +  in those same files.
         
       Other Versions
      -  If you use any version of ZDS-II other than 4.11.0 or if you install ZDS-II
      +  If you use any version of ZDS-II other than 5.1.1 or if you install ZDS-II
         at any location other than the default location, you will have to modify
         two files:  (1) configs/ez80f910200kitg/*/setenv.sh and (2)
         configs/ez80f910200kitg/*/Make.defs.
      diff --git a/nuttx/configs/ez80f910200zco/README.txt b/nuttx/configs/ez80f910200zco/README.txt
      index 51b219493c..d39c419e01 100644
      --- a/nuttx/configs/ez80f910200zco/README.txt
      +++ b/nuttx/configs/ez80f910200zco/README.txt
      @@ -5,7 +5,7 @@ ZDS-II Compiler Versions
       ^^^^^^^^^^^^^^^^^^^^^^^^
       
       Different configurations have been build for this board using ZDS-11
      -Versions 4.11.0 and 4.11.1.  You have to check the files */Make.defs
      +Versions 4.11.0, 4.11.1, and 5.1.1  You have to check the files */Make.defs
       to see how the build is configured:  Check the definitions of
       ZDSVERSION (if present) and ZDSINSTALLDIR.
       
      @@ -14,6 +14,10 @@ different versions of .linkcmd and .zdsproj files as well.
       
       Version 4.11.0
       
      +  The 5.1.1 version of the ZDS-II tools are currently configured for
      +  all ez80 boards.  However, it is the older version 4.11.0 that this code
      +  has been verified against.
      +  
         Although it compiles without error, the 4.11.0 compiler generates
         bad code on one of the files, mm/mm_initialize.c.  Below is a simple work-
         around.
      @@ -33,27 +37,27 @@ Version 4.11.0
       
          UPDATE:  I don't know if 4.11.1 has this same problem (I bet not since
          I submitted the bug to ZiLOG), but I have permanently worked around the
      -   above problem for all ZiLOG compiler.
      +   above problem for all ZiLOG compilers.
       
       Version 5.1.1
       
         On June 22, 2011 I verified that these configurations build successfully
      -  with the 5.1.1 ZDS-II version.  All that is required to used ZDS-II is
      -  to modify the Make.defs file so that the correct version is used.  That
      -  version should also be changed in the (optional) setenv.sh file.
      +  with the 5.1.1 ZDS-II version.  On November 12, 2012, all of the configurations
      +  were converted to use 5.1.1, but have not been verified on a running target.
       
      -  The above kludge for 4.11.0 is not required.
      +  The above kludge for 4.11.0 is not required with 5.1.1.
       
      -  I had to make additional changes to the ZDS path in Make.defs (and also
      -  in setenv.sh) when the 32-bit ZDS-II tools are installed on my 64-bit
      -  Windows 7 system.
      +  Paths were also updated that are specific to a 32-bit toolchain running on
      +  a 64 bit windows platform.  Change to a different toolchain, you will need
      +  to modify the versioning in Make.defs and setenv.sh; if you want to build
      +  on a different platform, you will need to change the path in the ZDS binaries
      +  in those same files.
         
       Other Versions
      -
      -  If you use any version of ZDS-II other than 4.11.0 or if you install ZDS-II
      +  If you use any version of ZDS-II other than 5.1.1 or if you install ZDS-II
         at any location other than the default location, you will have to modify
      -  two files:  (1) configs/ez80f910200zco/*/setenv.sh and (2)
      -  configs/ez80f910200zco/*/Make.defs.
      +  two files:  (1) configs/ez80f910200kitg/*/setenv.sh and (2)
      +  configs/ez80f910200kitg/*/Make.defs.
       
       Configuration Subdirectories
       ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
      diff --git a/nuttx/include/nuttx/usb/usbdev_trace.h b/nuttx/include/nuttx/usb/usbdev_trace.h
      index ae8e13c3a4..ab3a5f4bea 100644
      --- a/nuttx/include/nuttx/usb/usbdev_trace.h
      +++ b/nuttx/include/nuttx/usb/usbdev_trace.h
      @@ -238,10 +238,6 @@
       #define USBCOMPOSITE_TRACEERR_ALLOCDEVSTRUCT         0x000a
       #define USBCOMPOSITE_TRACEERR_CLASSOBJECT            0x000b
       #define USBCOMPOSITE_TRACEERR_DEVREGISTER            0x000c
      -#define USBCOMPOSITE_TRACEERR_INVALIDARG             0x000d
      -#define USBCOMPOSITE_TRACEERR_INVALIDARG             0x000f
      -#define USBCOMPOSITE_TRACEERR_INVALIDARG             0x0010
      -#define USBCOMPOSITE_TRACEERR_INVALIDARG             0x0011
       
       /* USB Storage driver class events ******************************************/
       
      diff --git a/nuttx/mm/mm_initialize.c b/nuttx/mm/mm_initialize.c
      index 3a21d1759b..a7f64cfafd 100644
      --- a/nuttx/mm/mm_initialize.c
      +++ b/nuttx/mm/mm_initialize.c
      @@ -95,9 +95,9 @@ void mm_initialize(FAR void *heapstart, size_t heapsize)
       
         mlldbg("Heap: start=%p size=%u\n", heapstart, heapsize);
       
      -  /* The following two lines have cause problems for some ZiLog compilers
      -   * in the past.  Life is easier if we just the suppress them for those
      -   * tools.
      +  /* The following two lines have cause problems for some older ZiLog
      +   * compilers in the past (but not the more recent).  Life is easier if we
      +   * just the suppress them altogther for those tools.
          */
       
       #ifndef __ZILOG__
      
      From 923d1e49b56c1db79ca4ef5d33c828de4269bb33 Mon Sep 17 00:00:00 2001
      From: patacongo 
      Date: Tue, 13 Nov 2012 00:38:59 +0000
      Subject: [PATCH 111/206] Add tools/mkdeps.bat and tools/mkdeps.c
      
      git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5342 42af7a65-404d-4744-a932-0658087f49c3
      ---
       nuttx/ChangeLog                               |   5 +
       nuttx/Documentation/NuttX.html                |   2 -
       nuttx/README.txt                              |  16 +-
       nuttx/configs/amber/README.txt                |  10 +-
       nuttx/configs/ea3131/README.txt               |   6 +-
       nuttx/configs/ea3152/README.txt               |   9 +-
       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/mcu123-lpc214x/README.txt       |   6 +-
       nuttx/configs/micropendous3/README.txt        |   6 +-
       nuttx/configs/mirtoo/README.txt               |   6 +-
       nuttx/configs/ntosd-dm320/README.txt          |   6 +-
       nuttx/configs/nucleus2g/README.txt            |   6 +-
       nuttx/configs/olimex-lpc1766stk/README.txt    |   6 +-
       nuttx/configs/olimex-strp711/README.txt       |   6 +-
       nuttx/configs/pcblogic-pic32mx/README.txt     |   6 +-
       nuttx/configs/pic32-starterkit/README.txt     |   6 +-
       nuttx/configs/pic32mx7mmb/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        |   8 +-
       nuttx/configs/stm32f100rc_generic/README.txt  |   6 +-
       nuttx/configs/stm32f4discovery/README.txt     |   6 +-
       .../stm32f4discovery/winbuild/Make.defs       |   2 +-
       .../stm32f4discovery/winbuild/setenv.bat      |   2 +
       nuttx/configs/sure-pic32mx/README.txt         |   6 +-
       nuttx/configs/teensy/README.txt               |   6 +-
       nuttx/configs/twr-k60n512/README.txt          |   6 +-
       nuttx/configs/ubw32/README.txt                |   6 +-
       nuttx/configs/vsn/README.txt                  |   6 +-
       nuttx/tools/Makefile.host                     |  73 ++-
       nuttx/tools/README.txt                        |  20 +-
       nuttx/tools/mkdeps.bat                        | 173 +++++
       nuttx/tools/mkdeps.c                          | 599 ++++++++++++++++++
       nuttx/tools/mkdeps.sh                         |   2 +-
       47 files changed, 903 insertions(+), 222 deletions(-)
       create mode 100644 nuttx/tools/mkdeps.bat
       create mode 100644 nuttx/tools/mkdeps.c
      
      diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
      index eb4f4b4ed8..0f92fdf7af 100644
      --- a/nuttx/ChangeLog
      +++ b/nuttx/ChangeLog
      @@ -3608,3 +3608,8 @@
       	* configs/stm32f4discovery/winbuild:  This is a version of the standard
       	  NuttX OS test, but configured to build natively on Windows.  Its only
       	  real purpose is to very the native Windows build logic.
      +	* tools/mkdeps.bat and tools/mkdeps.c:  mkdeps.bat is a failed attempt
      +	  to leverage mkdeps.sh to CMD.exe.  It fails because the are certain
      +	  critical CFLAG values that cannot be passed on the CMD.exe command line
      +	  (line '=').  mkdeps.c is a work in progress that will, hopefully,
      +	  replace both mkdeps.sh and mkdeps.bat.
      diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
      index dd7b83cfc8..154e5aa2b8 100644
      --- a/nuttx/Documentation/NuttX.html
      +++ b/nuttx/Documentation/NuttX.html
      @@ -2971,8 +2971,6 @@ avr, m68k, m68hc11, m68hc12, m9s12, blackfin, m32c, h8, and SuperH ports.
               NOTE: dependencies are suppress by setting the make variable MKDEPS to point
               to the do-nothing dependency script, tools/mknulldeps.sh.
      -        Dependencies can be enabled for the Windows native GCC compilers by setting
      -        MKDEPS to point to $(TOPDIR)/tools/mkdeps.sh --winpaths $(TOPDIR).
             

    diff --git a/nuttx/README.txt b/nuttx/README.txt index 737d4d4e29..ae0a4a023d 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -578,18 +578,16 @@ Window Native Toolchain Issues is not a long as you might think because there is no dependency checking if you are using a native Windows toolchain. That bring us to #3: - 3. Dependencies are not made when using Windows versions of the GCC. This is - because the dependencies are generated using Windows pathes which do not - work with the Cygwin make. + 3. Dependencies are not made when using Windows versions of the GCC on a POSIX + platform (i.e., Cygwin). This is because the dependencies are generated + using Windows paths which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: + MKDEP = $(TOPDIR)/tools/mknulldeps.sh - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" + If you are building natively on Windows, then no such conflict exists + and the best selection is: - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mkdeps.exe General Pre-built Toolchain Issues diff --git a/nuttx/configs/amber/README.txt b/nuttx/configs/amber/README.txt index 9ef22917e3..63fa5d41f3 100644 --- a/nuttx/configs/amber/README.txt +++ b/nuttx/configs/amber/README.txt @@ -252,15 +252,7 @@ Windows Native Toolchains is because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native - toolchains. That support can be enabled by modifying your Make.defs - file as follows: - - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are - not building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh An additional issue with the WinAVR toolchain, in particular, is that it contains an incompatible version of the Cygwin DLL in its bin/ directory. diff --git a/nuttx/configs/ea3131/README.txt b/nuttx/configs/ea3131/README.txt index 4d01a4162a..29b68ce8d1 100644 --- a/nuttx/configs/ea3131/README.txt +++ b/nuttx/configs/ea3131/README.txt @@ -80,11 +80,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/ea3152/README.txt b/nuttx/configs/ea3152/README.txt index 5b513a620c..7aa57e3ae0 100644 --- a/nuttx/configs/ea3152/README.txt +++ b/nuttx/configs/ea3152/README.txt @@ -76,14 +76,7 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt index ce607c7647..79a4b96fdf 100644 --- a/nuttx/configs/eagle100/README.txt +++ b/nuttx/configs/eagle100/README.txt @@ -69,11 +69,7 @@ GNU Toolchain Options Support has been added for making dependencies with the CodeSourcery toolchain. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/ekk-lm3s9b96/README.txt b/nuttx/configs/ekk-lm3s9b96/README.txt index 78fe96ef55..fc9448aaf9 100644 --- a/nuttx/configs/ekk-lm3s9b96/README.txt +++ b/nuttx/configs/ekk-lm3s9b96/README.txt @@ -139,11 +139,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/fire-stm32v2/README.txt b/nuttx/configs/fire-stm32v2/README.txt index 0cf782a943..aa3225524b 100644 --- a/nuttx/configs/fire-stm32v2/README.txt +++ b/nuttx/configs/fire-stm32v2/README.txt @@ -229,11 +229,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) ----------------------------------- diff --git a/nuttx/configs/hymini-stm32v/README.txt b/nuttx/configs/hymini-stm32v/README.txt index 2c8f3a16af..4c55458061 100644 --- a/nuttx/configs/hymini-stm32v/README.txt +++ b/nuttx/configs/hymini-stm32v/README.txt @@ -83,11 +83,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/kwikstik-k40/README.txt b/nuttx/configs/kwikstik-k40/README.txt index 7a68fcffa8..1f3873cc9e 100644 --- a/nuttx/configs/kwikstik-k40/README.txt +++ b/nuttx/configs/kwikstik-k40/README.txt @@ -207,11 +207,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/lincoln60/README.txt b/nuttx/configs/lincoln60/README.txt index 068ca50dc7..87847cd8b7 100644 --- a/nuttx/configs/lincoln60/README.txt +++ b/nuttx/configs/lincoln60/README.txt @@ -107,11 +107,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/lm3s6432-s2e/README.txt b/nuttx/configs/lm3s6432-s2e/README.txt index 3630ccc5ec..df7e7029d3 100644 --- a/nuttx/configs/lm3s6432-s2e/README.txt +++ b/nuttx/configs/lm3s6432-s2e/README.txt @@ -134,11 +134,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/lm3s6965-ek/README.txt b/nuttx/configs/lm3s6965-ek/README.txt index f6c32ee82a..96e87bb272 100644 --- a/nuttx/configs/lm3s6965-ek/README.txt +++ b/nuttx/configs/lm3s6965-ek/README.txt @@ -163,11 +163,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/lm3s8962-ek/README.txt b/nuttx/configs/lm3s8962-ek/README.txt index 310edabc57..6de30047b0 100644 --- a/nuttx/configs/lm3s8962-ek/README.txt +++ b/nuttx/configs/lm3s8962-ek/README.txt @@ -163,11 +163,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/lpc4330-xplorer/README.txt b/nuttx/configs/lpc4330-xplorer/README.txt index 8c88b5758b..f7ec778eec 100644 --- a/nuttx/configs/lpc4330-xplorer/README.txt +++ b/nuttx/configs/lpc4330-xplorer/README.txt @@ -188,11 +188,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) ----------------------------------- diff --git a/nuttx/configs/lpcxpresso-lpc1768/README.txt b/nuttx/configs/lpcxpresso-lpc1768/README.txt index 9660e12fee..2fedefc588 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/README.txt +++ b/nuttx/configs/lpcxpresso-lpc1768/README.txt @@ -291,11 +291,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/mbed/README.txt b/nuttx/configs/mbed/README.txt index 958ae98184..09763086bd 100644 --- a/nuttx/configs/mbed/README.txt +++ b/nuttx/configs/mbed/README.txt @@ -77,11 +77,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/mcu123-lpc214x/README.txt b/nuttx/configs/mcu123-lpc214x/README.txt index 65d177cc1e..49a6d5c0f7 100644 --- a/nuttx/configs/mcu123-lpc214x/README.txt +++ b/nuttx/configs/mcu123-lpc214x/README.txt @@ -75,11 +75,7 @@ GNU Toolchain Options Support has been added for making dependencies with the CodeSourcery toolchain. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) may not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/micropendous3/README.txt b/nuttx/configs/micropendous3/README.txt index c05f1ddd5b..cc4a47ee3e 100644 --- a/nuttx/configs/micropendous3/README.txt +++ b/nuttx/configs/micropendous3/README.txt @@ -269,11 +269,7 @@ Windows Native Toolchains toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are - not building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh An additional issue with the WinAVR toolchain, in particular, is that it contains an incompatible version of the Cygwin DLL in its bin/ directory. diff --git a/nuttx/configs/mirtoo/README.txt b/nuttx/configs/mirtoo/README.txt index b2d0c5790d..7a58572bf8 100644 --- a/nuttx/configs/mirtoo/README.txt +++ b/nuttx/configs/mirtoo/README.txt @@ -451,11 +451,7 @@ Toolchains Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh Loading NuttX with ICD3 ======================== diff --git a/nuttx/configs/ntosd-dm320/README.txt b/nuttx/configs/ntosd-dm320/README.txt index 46f049e34c..ba6cc87ecb 100644 --- a/nuttx/configs/ntosd-dm320/README.txt +++ b/nuttx/configs/ntosd-dm320/README.txt @@ -99,11 +99,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/nucleus2g/README.txt b/nuttx/configs/nucleus2g/README.txt index 86a8944abe..0d1d2896b1 100644 --- a/nuttx/configs/nucleus2g/README.txt +++ b/nuttx/configs/nucleus2g/README.txt @@ -137,11 +137,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt index 0983ab1f52..6bb36f40ce 100644 --- a/nuttx/configs/olimex-lpc1766stk/README.txt +++ b/nuttx/configs/olimex-lpc1766stk/README.txt @@ -225,11 +225,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/olimex-strp711/README.txt b/nuttx/configs/olimex-strp711/README.txt index 74168dbfa9..7c3d3fe5b3 100644 --- a/nuttx/configs/olimex-strp711/README.txt +++ b/nuttx/configs/olimex-strp711/README.txt @@ -160,11 +160,7 @@ GNU Toolchain Options Support has been added for making dependencies with the CodeSourcery toolchain. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) may not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/pcblogic-pic32mx/README.txt b/nuttx/configs/pcblogic-pic32mx/README.txt index c15bd45a0e..9eea61fd87 100644 --- a/nuttx/configs/pcblogic-pic32mx/README.txt +++ b/nuttx/configs/pcblogic-pic32mx/README.txt @@ -279,11 +279,7 @@ Toolchains Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh Loading NuttX with PICkit2 ========================== diff --git a/nuttx/configs/pic32-starterkit/README.txt b/nuttx/configs/pic32-starterkit/README.txt index 31d84798c0..b21066b535 100644 --- a/nuttx/configs/pic32-starterkit/README.txt +++ b/nuttx/configs/pic32-starterkit/README.txt @@ -496,11 +496,7 @@ Toolchains Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh Powering the Board ================== diff --git a/nuttx/configs/pic32mx7mmb/README.txt b/nuttx/configs/pic32mx7mmb/README.txt index adf83e2f4d..cc8ea5573c 100644 --- a/nuttx/configs/pic32mx7mmb/README.txt +++ b/nuttx/configs/pic32mx7mmb/README.txt @@ -264,11 +264,7 @@ Toolchains Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh Powering the Board ================== diff --git a/nuttx/configs/sam3u-ek/README.txt b/nuttx/configs/sam3u-ek/README.txt index fa5d52b69c..bcb8b9ef62 100644 --- a/nuttx/configs/sam3u-ek/README.txt +++ b/nuttx/configs/sam3u-ek/README.txt @@ -78,11 +78,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index 48f183aee4..2f2833bbee 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -252,11 +252,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) ----------------------------------- diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt index 50e413b42c..9e63112016 100644 --- a/nuttx/configs/stm3210e-eval/README.txt +++ b/nuttx/configs/stm3210e-eval/README.txt @@ -86,11 +86,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/stm3220g-eval/README.txt b/nuttx/configs/stm3220g-eval/README.txt index 58a6f156c4..0e6a9a7dad 100644 --- a/nuttx/configs/stm3220g-eval/README.txt +++ b/nuttx/configs/stm3220g-eval/README.txt @@ -92,11 +92,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) ----------------------------------- diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index 8604f344a5..140cc7414d 100644 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -94,11 +94,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) ----------------------------------- @@ -1397,4 +1393,4 @@ Where is one of the following: 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. \ No newline at end of file + Contributed by Max Holtzberg. diff --git a/nuttx/configs/stm32f100rc_generic/README.txt b/nuttx/configs/stm32f100rc_generic/README.txt index e9959431c2..0c96d4fbc5 100644 --- a/nuttx/configs/stm32f100rc_generic/README.txt +++ b/nuttx/configs/stm32f100rc_generic/README.txt @@ -88,11 +88,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) ----------------------------------- diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index a69f53b0f5..68be0a8a67 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -92,11 +92,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) ----------------------------------- diff --git a/nuttx/configs/stm32f4discovery/winbuild/Make.defs b/nuttx/configs/stm32f4discovery/winbuild/Make.defs index 0837044548..426611f8e5 100644 --- a/nuttx/configs/stm32f4discovery/winbuild/Make.defs +++ b/nuttx/configs/stm32f4discovery/winbuild/Make.defs @@ -81,7 +81,7 @@ LDSCRIPT = ld.script # Windows-native toolchains -MKDEP = $(TOPDIR)/tools/mknulldeps.sh +MKDEP = $(TOPDIR)/tools/mkdeps.bat ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) diff --git a/nuttx/configs/stm32f4discovery/winbuild/setenv.bat b/nuttx/configs/stm32f4discovery/winbuild/setenv.bat index e2196a90a0..1d4a95f3a3 100755 --- a/nuttx/configs/stm32f4discovery/winbuild/setenv.bat +++ b/nuttx/configs/stm32f4discovery/winbuild/setenv.bat @@ -1,3 +1,5 @@ +@echo off + rem configs/stm32f4discovery/winbuild/setenv.sh rem rem Copyright (C) 2012 Gregory Nutt. All rights reserved. diff --git a/nuttx/configs/sure-pic32mx/README.txt b/nuttx/configs/sure-pic32mx/README.txt index ad98356980..68f0bd3365 100644 --- a/nuttx/configs/sure-pic32mx/README.txt +++ b/nuttx/configs/sure-pic32mx/README.txt @@ -345,11 +345,7 @@ Toolchains Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh Loading NuttX with PICkit2 ========================== diff --git a/nuttx/configs/teensy/README.txt b/nuttx/configs/teensy/README.txt index 979d8e0e78..454a42d054 100644 --- a/nuttx/configs/teensy/README.txt +++ b/nuttx/configs/teensy/README.txt @@ -272,11 +272,7 @@ Windows Native Toolchains toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are - not building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh An additional issue with the WinAVR toolchain, in particular, is that it contains an incompatible version of the Cygwin DLL in its bin/ directory. diff --git a/nuttx/configs/twr-k60n512/README.txt b/nuttx/configs/twr-k60n512/README.txt index 3b7b402d7e..cd567fd375 100644 --- a/nuttx/configs/twr-k60n512/README.txt +++ b/nuttx/configs/twr-k60n512/README.txt @@ -344,11 +344,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/configs/ubw32/README.txt b/nuttx/configs/ubw32/README.txt index f8afb88e4f..83ade7dae9 100644 --- a/nuttx/configs/ubw32/README.txt +++ b/nuttx/configs/ubw32/README.txt @@ -290,11 +290,7 @@ Toolchains Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh Loading NuttX with PICkit2 ========================== diff --git a/nuttx/configs/vsn/README.txt b/nuttx/configs/vsn/README.txt index 657cfdd899..a0b8e24193 100644 --- a/nuttx/configs/vsn/README.txt +++ b/nuttx/configs/vsn/README.txt @@ -83,11 +83,7 @@ GNU Toolchain Options Support has been added for making dependencies with the windows-native toolchains. That support can be enabled by modifying your Make.defs file as follows: - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with diff --git a/nuttx/tools/Makefile.host b/nuttx/tools/Makefile.host index 66bea9937b..d6a521272f 100644 --- a/nuttx/tools/Makefile.host +++ b/nuttx/tools/Makefile.host @@ -33,43 +33,86 @@ # ############################################################################ -all: mkconfig mkversion mksyscall bdf-converter -default: mkconfig mksyscall +TOPDIR ?= ${shell pwd}/.. +-include $(TOPDIR)/Make.defs +include ${TOPDIR}/tools/Config.mk + +all: mkconfig$(EXEEXT) mkversion$(EXEEXT) mksyscall$(EXEEXT) bdf-converter$(EXEEXT) mksymtab$(EXEEXT) mkdeps$(EXEEXT) +default: mkconfig$(EXEEXT) mksyscall$(EXEEXT) mkdeps$(EXEEXT) + +ifdef EXEEXT +.PHONY: clean mkconfig mkversion mksyscall bdf-converter mksymtab mkdeps +else .PHONY: clean +endif -# Add CFLAGS=-g on the make command line build debug versions +# Add HOSTCFLAGS=-g on the make command line build debug versions -CFLAGS = -O2 -Wall -I. +HOSTCFLAGS ?= -O2 -Wall -I. +HOSTCC ?= gcc # mkconfig - Convert a .config file into a C config.h file -mkconfig: mkconfig.c cfgparser.c - $(Q) gcc $(CFLAGS) -o mkconfig mkconfig.c cfgparser.c +mkconfig$(EXEEXT): mkconfig.c cfgparser.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkconfig$(EXEEXT) mkconfig.c cfgparser.c + +ifdef EXEEXT +mkconfig: mkconfig$(EXEEXT) +endif # cmpconfig - Compare the contents of two configuration files cmpconfig: cmpconfig.c - $(Q) gcc $(CFLAGS) -o cmpconfig cmpconfig.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o cmpconfig cmpconfig.c + +ifdef EXEEXT +cmpconfig: cmpconfig$(EXEEXT) +endif # mkversion - Convert a .version file into a C version.h file -mkversion: mkconfig.c cfgparser.c - $(Q) gcc $(CFLAGS) -o mkversion mkversion.c cfgparser.c +mkversion$(EXEEXT): mkconfig.c cfgparser.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkversion$(EXEEXT) mkversion.c cfgparser.c + +ifdef EXEEXT +mkversion: mkversion$(EXEEXT) +endif # mksyscall - Convert a CSV file into syscall stubs and proxies -mksyscall: mksyscall.c csvparser.c - $(Q) gcc $(CFLAGS) -o mksyscall mksyscall.c csvparser.c +mksyscall$(EXEEXT): mksyscall.c csvparser.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mksyscall$(EXEEXT) mksyscall.c csvparser.c + +ifdef EXEEXT +mksyscall: mksyscall$(EXEEXT) +endif # mksymtab - Convert a CSV file into a symbol table -mksymtab: mksymtab.c csvparser.c - $(Q) gcc $(CFLAGS) -o mksymtab mksymtab.c csvparser.c +mksymtab$(EXEEXT): mksymtab.c csvparser.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mksymtab$(EXEEXT) mksymtab.c csvparser.c + +ifdef EXEEXT +mksymtab: mksymtab$(EXEEXT) +endif # bdf-converter - Converts a BDF font to the NuttX font format -bdf-converter: bdf-converter.c - $(Q) gcc $(CFLAGS) -o bdf-converter bdf-converter.c +bdf-converter$(EXEEXT): bdf-converter.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o bdf-converter$(EXEEXT) bdf-converter.c + +ifdef EXEEXT +bdf-converter: bdf-converter$(EXEEXT) +endif + +# Create dependencies for a list of files + +mkdeps$(EXEEXT): mkdeps.c csvparser.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkdeps$(EXEEXT) mkdeps.c + +ifdef EXEEXT +mkdeps: mkdeps$(EXEEXT) +endif clean: $(Q) rm -f *.o *.a *~ .*.swp diff --git a/nuttx/tools/README.txt b/nuttx/tools/README.txt index 5d52eaefff..28fa664bda 100644 --- a/nuttx/tools/README.txt +++ b/nuttx/tools/README.txt @@ -271,6 +271,8 @@ mkromfsimg.sh may be mounted under /etc in the NuttX pseudo file system. mkdeps.sh +mkdeps.bat +mkdeps.c mknulldeps.sh NuttX uses the GCC compilers capabilities to create Makefile dependencies. @@ -278,7 +280,8 @@ mknulldeps.sh dependencies. If a NuttX configuration uses the GCC toolchain, its Make.defs file (see configs/README.txt) will include a line like: - MKDEP = $(TOPDIR)/tools/mkdeps.sh + MKDEP = $(TOPDIR)/tools/mkdeps.sh, or + MKDEP = $(TOPDIR)/tools/mkdeps[.exe] (See NOTE below) If the NuttX configuration does not use a GCC compatible toolchain, then it cannot use the dependencies and instead it uses mknulldeps.sh: @@ -287,6 +290,21 @@ mknulldeps.sh The mknulldeps.sh is a stub script that does essentially nothing. + NOTE: The mkdep.* files are undergoing change. mkdeps.sh is a bash + script that produces dependencies well for POSIX style hosts (e..g., + Linux and Cygwin). It does not work well for mixed environments with + a Windows toolchain running in a POSIX style environemnt (hence, the + mknulldeps.sh script). + + mkdeps.bat is a simple port of the bash script to run in a Windows + command shell. However, it does not work well either because some + of the common CFLAGS use characters like '=' which are transformed + by the CMD.exe shell. + + mkdeps.c generates mkdeps (on Linux) or mkdeps.exe (on Windows). + This C version should solve all of the issues. However, this verison + is still under-development. + define.sh Different compilers have different conventions for specifying pre- diff --git a/nuttx/tools/mkdeps.bat b/nuttx/tools/mkdeps.bat new file mode 100644 index 0000000000..23aab0b715 --- /dev/null +++ b/nuttx/tools/mkdeps.bat @@ -0,0 +1,173 @@ +@echo off + +rem tools/mkdeps.sh +rem +rem Copyright (C) 2012 Gregory Nutt. All rights reserved. +rem Author: Gregory Nutt +rem +rem Redistribution and use in source and binary forms, with or without +rem modification, are permitted provided that the following conditions +rem are met: +rem +rem 1. Redistributions of source code must retain the above copyright +rem notice, this list of conditions and the following disclaimer. +rem 2. Redistributions in binary form must reproduce the above copyright +rem notice, this list of conditions and the following disclaimer in +rem the documentation and/or other materials provided with the +rem distribution. +rem 3. Neither the name NuttX nor the names of its contributors may be +rem used to endorse or promote products derived from this software +rem without specific prior written permission. +rem +rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +rem POSSIBILITY OF SUCH DAMAGE. + +rem Accumulate CFLAGS up to "--" + +set cc= +set cflags= +set altpath= +set files= +set args= +set debug=n + +:Loop +if "%1"=="" goto Continue + +if "%1"=="--" ( + set cc=%cflags% + set cflags=%args% + set args= + goto NextParm +) + +if "%1"=="--dep-path" ( + if "%args%"=="" ( + set altpath=%altpath% %2 + ) else ( + set args=%args% %2 + ) + shift + goto NextParm +) + +if "%1"=="--dep-debug" ( +rem @echo on + set debug=y + goto NextParm +) + +if "%1"=="--help" goto Usage + +if "%args%"=="" ( + set args=%1 +) else ( + set args=%args% %1 +) + +:NextParm +shift +goto Loop +:Continue + +set files=%args% + +if "%debug%"=="y" ( + echo cc=%cc% + echo cflags=%cflags% + echo files=%files% + echo altpath=%altpath% +) + +rem Now check if we have everything + +if "%cc%"=="" ( + echo ERROR: No compiler specified + goto Usage +) + +if "%files%"=="" ( + rem Don't report an error -- this happens normally in some configurations + echo # No files specified for dependency generataion + goto End +) + +rem Then get the dependencies for each file + +if "%altpath%"=="" goto NoPaths +for %%G in (%files%) do ( + set fullpath= + set file=%%G + call :Checkpaths + if "%debug%"=="y" echo %file%: fullpath=%fullpath% + if "%fullpath%"=="" goto :NoFile + if "%debug%"=="y" echo CMD: %cc% -M %cflags% %fullpath% + %cc% -M %cflags% %fullpath% || goto DepFail +) +goto :End + +:NoPaths +for %%G in (%files%) do ( + set fullpath= + set file=%%G + call :CheckFile %%G +) +goto :End + +:CheckFile +if "%debug%"=="y" echo Checkfile: Checking %file% +if not exist %file% goto :NoFile +set fullpath=%file% + if "%debug%"=="y" echo CMD: %cc% -M %cflags% %fullpath% +%cc% -M %cflags% %fullpath% || goto DepFail +goto :EOF + +:CheckPaths +for %%H in (%altpath%) do ( + set tmppath=%%H\%file% + if "%debug%"=="y" echo Checkfile: Checking %tmppath% + if exist %tmppath% ( + set fullpath=%tmppath% + goto :EOF + ) +) +goto :EOF + +:NoFile +echo ERROR: No readable file at %file% +goto Usage + +:DepFail +echo ERROR: Failed to created dependencies for %file% + +:Usage +echo Usage: mkdeps [OPTIONS] CC -- CFLAGS -- file [file [file...]] +echo Where: +echo CC +echo A variable number of arguments that define how to execute the compiler +echo CFLAGS +echo The compiler compilation flags +echo file +echo One or more C files whose dependencies will be checked. Each file is expected +echo to reside in the current directory unless --dep-path is provided on the command line +echo And [OPTIONS] include: +echo --dep-debug +echo Enable script debug +echo --dep-path ^ +echo Do not look in the current directory for the file. Instead, look in to see +echo if the file resides there. --dep-path may be used multiple times to specify +echo multiple alternative location +echo --help +echo Shows this message and exits + +:End diff --git a/nuttx/tools/mkdeps.c b/nuttx/tools/mkdeps.c new file mode 100644 index 0000000000..1822dc9577 --- /dev/null +++ b/nuttx/tools/mkdeps.c @@ -0,0 +1,599 @@ +/**************************************************************************** + * tools/mkdeps.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define MAX_COMMAND 256 +#ifndef MAX_PATH +# define MAX_PATH 4096 +#endif +#define MAX_BUFFER (MAX_COMMAND + MAX_PATH + 2) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +enum slashmode_e +{ + MODE_FSLASH = 0, + MODE_BSLASH = 1, + MODE_DBLBACK = 2 +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static char *g_cc = NULL; +static char *g_cflags = NULL; +static char *g_files = NULL; +static char *g_altpath = NULL; +static int g_debug = 0; +static bool g_winnative = false; +#ifdef HAVE_WINPATH +static bool g_winpath = false; +static char *g_topdir = NULL; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static void append(char **base, char *str) +{ + char *oldbase; + char *newbase; + int alloclen; + + oldbase = *base; + if (!oldbase) + { + newbase = strdup(str); + if (!newbase) + { + fprintf(stderr, "ERROR: Failed to strdup %s\n", str); + exit(EXIT_FAILURE); + } + } + else + { + alloclen = strlen(newbase) + strlen(str) + 2; + newbase = (char *)malloc(alloclen); + if (!newbase) + { + fprintf(stderr, "ERROR: Failed to allocate %d bytes\n", alloclen); + exit(EXIT_FAILURE); + } + + snprintf(newbase, alloclen, "%s %s\n", oldbase, str); + free(oldbase); + } + + *base = newbase; +} + +static void show_usage(const char *progname, const char *msg, int exitcode) +{ + if (msg) + { + fprintf(stderr, "\n"); + fprintf(stderr, "%s:\n", msg); + } + + fprintf(stderr, "\n"); + fprintf(stderr, "%s [OPTIONS] CC -- CFLAGS -- file [file [file...]]\n", progname); + fprintf(stderr, "\n"); + fprintf(stderr, "Where:\n"); + fprintf(stderr, " CC\n"); + fprintf(stderr, " A variable number of arguments that define how to execute the compiler\n"); + fprintf(stderr, " CFLAGS\n"); + fprintf(stderr, " The compiler compilation flags\n"); + fprintf(stderr, " file\n"); + fprintf(stderr, " One or more C files whose dependencies will be checked. Each file is expected\n"); + fprintf(stderr, " to reside in the current directory unless --dep-path is provided on the command line\n"); + fprintf(stderr, "\n"); + fprintf(stderr, "And [OPTIONS] include:\n"); + fprintf(stderr, " --dep-debug\n"); + fprintf(stderr, " Enable script debug\n"); + fprintf(stderr, " --dep-path \n"); + fprintf(stderr, " Do not look in the current directory for the file. Instead, look in to see\n"); + fprintf(stderr, " if the file resides there. --dep-path may be used multiple times to specify\n"); + fprintf(stderr, " multiple alternative location\n"); + fprintf(stderr, " --winnative\n"); + fprintf(stderr, " By default, a POSIX-style environment is assumed (e.g., Linux, Cygwin, etc.) This option is\n"); + fprintf(stderr, " inform the tool that is working in a pure Windows native environment.\n"); +#ifdef HAVE_WINPATH + fprintf(stderr, " --winpaths \n"); + fprintf(stderr, " This option is useful when using a Windows native toolchain in a POSIX environment (such\n"); + fprintf(stderr, " such as Cygwin). In this case, will CC generates dependency lists using Windows paths\n"); + fprintf(stderr, " (e.g., C:\\blablah\\blabla). This switch instructs the script to use 'cygpath' to convert\n"); + fprintf(stderr, " the Windows paths to Cygwin POSIXE paths.\n"); +#endif + fprintf(stderr, " --help\n"); + fprintf(stderr, " Shows this message and exits\n"); + exit(exitcode); +} + +static void parse_args(int argc, char **argv) +{ + char *args = NULL; + int argidx; + + /* Accumulate CFLAGS up to "--" */ + + for (argidx = 1; argidx < argc; argidx++) + { + if (strcmp(argv[argidx], "--") == 0) + { + g_cc = g_cflags; + g_cflags = args; + args = NULL; + } + else if (strcmp(argv[argidx], "--dep-debug") == 0) + { + g_debug++; + } + else if (strcmp(argv[argidx], "--dep-path") == 0) + { + argidx++; + if (argidx >= argc) + { + show_usage(argv[0], "ERROR: Missing argument to --dep-path", EXIT_FAILURE); + } + + if (args) + { + append(&args, argv[argidx]); + } + else + { + append(&g_altpath, argv[argidx]); + } + } + else if (strcmp(argv[argidx], "--winnative") == 0) + { + g_winnative = true; + } +#ifdef HAVE_WINPATH + else if (strcmp(argv[argidx], "--winpath") == 0) + { + g_winpath = true; + if (g_topdir) + { + free(g_topdir); + } + + argidx++; + if (argidx >= argc) + { + show_usage(argv[0], "ERROR: Missing argument to --winpath", EXIT_FAILURE); + } + + g_topdir = strdup(argv[argidx]); + } +#endif + else if (strcmp(argv[argidx], "--help") == 0) + { + show_usage(argv[0], NULL, EXIT_SUCCESS); + } + else + { + append(&args, argv[argidx]); + } + } + + /* The final thing accumulated is the list of files */ + + g_files = args; + + /* If no paths were specified, then look in the current directory only */ + + if (!g_altpath) + { + g_altpath = strdup("."); + } + + if (g_debug) + { + fprintf(stderr, "SELECTIONS\n"); + fprintf(stderr, " CC : \"%s\"\n", g_cc ? g_cc : "(None)"); + fprintf(stderr, " CFLAGS : \"%s\"\n", g_cflags ? g_cflags : "(None)"); + fprintf(stderr, " FILES : \"%s\"\n", g_files ? g_files : "(None)"); + fprintf(stderr, " PATHS : \"%s\"\n", g_altpath ? g_altpath : "(None)"); +#ifdef HAVE_WINPATH + fprintf(stderr, " Windows Paths : \"%s\"\n", g_winpath ? "TRUE" : "FALSE"); + if (g_winpath) + { + fprintf(stderr, " TOPDIR : \"%s\"\n", g_topdir); + } +#endif + fprintf(stderr, " Windows Native : \"%s\"\n", g_winnative ? "TRUE" : "FALSE"); + } + + /* Check for required paramters */ + + if (!g_cc) + { + show_usage(argv[0], "ERROR: No compiler specified", EXIT_FAILURE); + } + + if (!g_files) + { + /* Don't report an error -- this happens normally in some configurations */ + + printf("# No files specified for dependency generataion\n"); + exit(EXIT_SUCCESS); + } + +#ifdef HAVE_WINPATH + if (g_winnative && g_winpath) + { + show_usage(argv[0], "ERROR: Both --winnative and --winpapth makes no sense", EXIT_FAILURE); + } +#endif +} + +static void do_dependency(const char *file, char separator) +{ + static const char moption[] = " -M "; + char command[MAX_BUFFER]; + struct stat buf; + char *altpath; + char *path; + char *bufptr; + int cmdlen; + int pathlen; + int filelen; + int totallen; + int ret; + + /* Copy the compiler into the command buffer */ + + cmdlen = strlen(g_cc); + if (cmdlen >= MAX_BUFFER) + { + fprintf(stderr, "ERROR: Compiler string is too long: %s\n", path); + exit(EXIT_FAILURE); + } + + strcpy(command, g_cc); + + /* Copy " -M " */ + + cmdlen += strlen(moption); + if (cmdlen >= MAX_BUFFER) + { + fprintf(stderr, "ERROR: Option string is too long: %s\n", moption); + exit(EXIT_FAILURE); + } + + strcat(command, moption); + + /* Copy the CFLAGS into the command buffer */ + + cmdlen += strlen(g_cflags); + if (cmdlen >= MAX_BUFFER) + { + fprintf(stderr, "ERROR: CFLAG string is too long: %s\n", g_cflags); + exit(EXIT_FAILURE); + } + + strcat(command, g_cflags); + + /* Add a space */ + + command[cmdlen] = ' '; + command[cmdlen+1] = '\0'; + cmdlen++; + + /* Try each path. This loop will continue until each path has been tried + * (failure) or until stat() finds the file + */ + + altpath = g_altpath; + while ((path = strtok(altpath, " ")) != NULL) + { + /* Create a full path to the file */ + + pathlen = strlen(path); + totallen = cmdlen + pathlen; + if (totallen >= MAX_BUFFER) + { + fprintf(stderr, "ERROR: Path is too long: %s\n", path); + exit(EXIT_FAILURE); + } + + strcpy(&command[cmdlen], path); + + if (command[totallen] != '\0') + { + fprintf(stderr, "ERROR: Missing NUL terminator\n", path); + exit(EXIT_FAILURE); + } + + if (command[totallen-1] != separator) + { + command[totallen] = separator; + command[totallen+1] = '\0'; + pathlen++; + totallen++; + } + + filelen = strlen(file); + totallen += filelen; + if (totallen >= MAX_BUFFER) + { + fprintf(stderr, "ERROR: Path+file is too long\n"); + exit(EXIT_FAILURE); + } + + strcat(command, file); + + /* Check that a file actually exists at this path */ + + ret = stat(command, &buf); + if (ret < 0) + { + altpath = NULL; + continue; + } + + if (!S_ISREG(buf.st_mode)) + { + fprintf(stderr, "ERROR: File %s exists but is not a regular file\n"); + exit(EXIT_FAILURE); + } + + /* Okay.. we have. Create the dependency */ + + ret = system(command); + if (ret != 0) + { + fprintf(stderr, "ERROR: ssystem(%s) failed\n"); + exit(EXIT_FAILURE); + } + + /* We don't really know that the command succeeded... Let's assume that it did */ + + return; + } + + printf("# ERROR: No readable file for \"%s\" found at any location\n", file); + exit(EXIT_FAILURE); +} + +/* Convert a Cygwin path to a Windows path */ + +#ifdef HAVE_WINPATH +static char *cywin2windows(const char *str, const char *append, enum slashmode_e mode) +{ + static const char cygdrive[] = "/cydrive"; + const char *src = src; + char *dest; + char *newpath; + char *allocpath = NULL; + int srclen = strlen(str); + int alloclen = 0; + int drive = 0; + int lastchar; + + /* Skip any leading whitespace */ + + while (isspace(*str)) str++; + + /* Were we asked to append something? */ + + if (append) + { + char *tmp; + + alloclen = sizeof(str) + sizeof(append) + 1; + allocpath = (char *)malloc(alloclen); + if (!allocpath) + { + fprintf(stderr, "ERROR: Failed to allocate %d bytes\n", alloclen); + exit(EXIT_FAILURE); + } + + snprintf(allocpath, alloclen, "%s/%s", str, append); + } + + /* Looking for path of the form /cygdrive/c/bla/bla/bla */ + + if (strcasecmp(src, cygdrive) == 0) + { + int cygsize = sizeof(cygdrive); + if (src[cygsize] == '/') + { + cygsize++; + srclen -= cygsize; + src += cygsize; + + if (srclen <= 0) + { + fprintf(stderr, "ERROR: Unhandled path: \"%s\"\n", str); + exit(EXIT_FAILURE); + } + + drive = toupper(*src); + if (drive < 'A' || drive > 'Z') + { + fprintf(stderr, "ERROR: Drive charager: \"%s\"\n", str); + exit(EXIT_FAILURE); + } + + srclen--; + src++; + alloclen = 2; + } + } + + /* Determine the size of the new path */ + + alloclen += sizeof(src) + 1; + if (mode == MODE_DBLBACK) + { + const char *tmpptr; + for (tmpptr = src; *tmpptr; tmpptr++) + { + if (*tmpptr == '/') alloclen++; + } + } + + /* Allocate memory for the new path */ + + newpath = (char *)malloc(alloclen); + if (!newpath) + { + fprintf(stderr, "ERROR: Failed to allocate %d bytes\n", alloclen); + exit(EXIT_FAILURE); + } + + dest = newpath; + + /* Copy the drive character */ + + if (drive) + { + *dest++ = drive; + *dest++ = ':'; + } + + /* Copy each character from the source, making modifications for foward slashes as required */ + + lastchar = '\0'; + for (; *src; src++) + { + if (mode != MODE_FSLASH && *src == '/') + { + if (lastchar != '/') + { + *dest++ = '\\'; + if (mode == MODE_DBLBACK) + { + *dest++ = '\\'; + } + } + } + else + { + *dest++ = *src; + } + + lastchar = *src; + } + + *dest++ = '\0'; + if (allocpath) + { + free(allocpath); + } + return dest; +} +#endif + +#ifdef HAVE_WINPATH +static void do_winpath(char *file) +{ + /* The file is in POSIX format. CC expects Windows format to generate the + * dependencies, but GNU make expect the resulting dependencies to be back + * in POSIX format. What a mess! + */ + + char *path = cywin2windows(g_topdir, file, MODE_FSLASH); + + /* Then get the dependency and perform conversions on it to make it + * palatable to the Cygwin make. + */ +#warning "Missing logic" + + free(path); +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int main(int argc, char **argv, char **envp) +{ + char *files; + char *file; + + /* Parse command line parameters */ + + parse_args(argc, argv); + + /* Then generate dependencies for each path on the command line */ + + files = g_files; + while ((file = strtok(files, " ")) != NULL) + { + /* Check if we need to do path conversions for a Windows-natvie tool + * being using in a POSIX/Cygwin environment. + */ + +#ifdef HAVE_WINPATH + if (g_winpath) + { + do_winpath(file); + } + else +#endif + { + do_dependency(file, g_winnative ? '\\' : '/'); + } + + files = NULL; + } + + return EXIT_SUCCESS; +} diff --git a/nuttx/tools/mkdeps.sh b/nuttx/tools/mkdeps.sh index acb6001509..028fd1d9f5 100755 --- a/nuttx/tools/mkdeps.sh +++ b/nuttx/tools/mkdeps.sh @@ -2,7 +2,7 @@ ############################################################################ # tools/mkdeps.sh # -# Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without From ccc5929f33e2867f61fbca1ccf3e04840e9166c1 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 13 Nov 2012 02:39:01 +0000 Subject: [PATCH 112/206] Fix some mkdeps.c issues; Incorporate mkdeps.c build in Makefiles git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5343 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Makefile | 25 ++++---- nuttx/Makefile.win | 29 ++++++---- .../stm32f4discovery/winbuild/Make.defs | 2 + nuttx/tools/Makefile.host | 58 +++++++++---------- nuttx/tools/mkdeps.c | 13 ++--- 5 files changed, 69 insertions(+), 58 deletions(-) diff --git a/nuttx/Makefile b/nuttx/Makefile index 5f7f519f0a..adf0d1017d 100644 --- a/nuttx/Makefile +++ b/nuttx/Makefile @@ -321,8 +321,8 @@ endif # part of the overall NuttX configuration sequence. Notice that the # tools/mkversion tool is built and used to create include/nuttx/version.h -tools/mkversion: - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkversion +tools/mkversion$(HOSTEXEEXT): + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkversion$(HOSTEXEEXT) $(TOPDIR)/.version: $(Q) if [ ! -f .version ]; then \ @@ -331,19 +331,24 @@ $(TOPDIR)/.version: chmod 755 .version; \ fi -include/nuttx/version.h: $(TOPDIR)/.version tools/mkversion +include/nuttx/version.h: $(TOPDIR)/.version tools/mkversion$(HOSTEXEEXT) $(Q) tools/mkversion $(TOPDIR) > include/nuttx/version.h # Targets used to build include/nuttx/config.h. Creation of config.h is # part of the overall NuttX configuration sequence. Notice that the # tools/mkconfig tool is built and used to create include/nuttx/config.h -tools/mkconfig: - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkconfig +tools/mkconfig$(HOSTEXEEXT): + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkconfig$(HOSTEXEEXT) -include/nuttx/config.h: $(TOPDIR)/.config tools/mkconfig +include/nuttx/config.h: $(TOPDIR)/.config tools/mkconfig$(HOSTEXEEXT) $(Q) tools/mkconfig $(TOPDIR) > include/nuttx/config.h +# Targets used to create dependencies + +tools/mkdeps$(HOSTEXEEXT): + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkdeps$(HOSTEXEEXT) + # dirlinks, and helpers # # Directories links. Most of establishing the NuttX configuration involves @@ -550,7 +555,7 @@ lib/libc$(LIBEXT): libc/libc$(LIBEXT) # is an archive. Exactly what is performed during pass1 or what it generates # is unknown to this makefule unless CONFIG_PASS1_OBJECT is defined. -pass1deps: context pass1dep $(USERLIBS) +pass1deps: pass1dep $(USERLIBS) pass1: pass1deps ifeq ($(CONFIG_BUILD_2PASS),y) @@ -569,7 +574,7 @@ ifeq ($(CONFIG_BUILD_2PASS),y) $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" LINKLIBS="$(LINKLIBS)" USERLIBS="$(USERLIBS)" "$(CONFIG_PASS1_TARGET)" endif -pass2deps: context pass2dep $(NUTTXLIBS) +pass2deps: pass2dep $(NUTTXLIBS) pass2: pass2deps $(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(LINKLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN) @@ -619,12 +624,12 @@ download: $(BIN) # pass1dep: Create pass1 build dependencies # pass2dep: Create pass2 build dependencies -pass1dep: context +pass1dep: context tools/mkdeps$(HOSTEXEEXT) $(Q) for dir in $(USERDEPDIRS) ; do \ $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" depend ; \ done -pass2dep: context +pass2dep: context tools/mkdeps$(HOSTEXEEXT) $(Q) for dir in $(KERNDEPDIRS) ; do \ $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" EXTRADEFINES=$(KDEFINE) depend; \ done diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win index d4157a3c49..5491851863 100644 --- a/nuttx/Makefile.win +++ b/nuttx/Makefile.win @@ -314,8 +314,8 @@ endif # part of the overall NuttX configuration sequence. Notice that the # tools\mkversion tool is built and used to create include\nuttx\version.h -tools\mkversion: - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkversion +tools\mkversion$(HOSTEXEEXT): + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkversion$(HOSTEXEEXT) $(TOPDIR)\.version: $(Q) if [ ! -f .version ]; then \ @@ -324,18 +324,23 @@ $(TOPDIR)\.version: chmod 755 .version; \ fi -include\nuttx\version.h: $(TOPDIR)\.version tools\mkversion - $(Q) tools\mkversion $(TOPDIR) > include\nuttx\version.h +include\nuttx\version.h: $(TOPDIR)\.version tools\mkversion$(HOSTEXEEXT) + $(Q) tools\mkversion$(HOSTEXEEXT) $(TOPDIR) > include\nuttx\version.h # Targets used to build include\nuttx\config.h. Creation of config.h is # part of the overall NuttX configuration sequence. Notice that the # tools\mkconfig tool is built and used to create include\nuttx\config.h -tools\mkconfig: - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkconfig +tools\mkconfig$(HOSTEXEEXT): + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkconfig$(HOSTEXEEXT) -include\nuttx\config.h: $(TOPDIR)\.config tools\mkconfig - $(Q) tools\mkconfig $(TOPDIR) > include\nuttx\config.h +include\nuttx\config.h: $(TOPDIR)\.config tools\mkconfig$(HOSTEXEEXT) + $(Q) tools\mkconfig$(HOSTEXEEXT) $(TOPDIR) > include\nuttx\config.h + +# Targets used to create dependencies + +tools/mkdeps$(HOSTEXEEXT): + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkdeps$(HOSTEXEEXT) # dirlinks, and helpers # @@ -566,7 +571,7 @@ lib\libc$(LIBEXT): libc\libc$(LIBEXT) # is an archive. Exactly what is performed during pass1 or what it generates # is unknown to this makefule unless CONFIG_PASS1_OBJECT is defined. -pass1deps: context pass1dep $(USERLIBS) +pass1deps: pass1dep $(USERLIBS) pass1: pass1deps ifeq ($(CONFIG_BUILD_2PASS),y) @@ -585,7 +590,7 @@ ifeq ($(CONFIG_BUILD_2PASS),y) $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" LINKLIBS="$(LINKLIBS)" USERLIBS="$(USERLIBS)" "$(CONFIG_PASS1_TARGET)" endif -pass2deps: context pass2dep $(NUTTXLIBS) +pass2deps: pass2dep $(NUTTXLIBS) pass2: pass2deps $(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(LINKLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN) @@ -635,10 +640,10 @@ download: $(BIN) # pass1dep: Create pass1 build dependencies # pass2dep: Create pass2 build dependencies -pass1dep: context +pass1dep: context tools/mkdeps$(HOSTEXEEXT) $(Q) for %%G in ($(USERDEPDIRS)) do ( $(MAKE) -C %%G TOPDIR="$(TOPDIR)" depend ) -pass2dep: context +pass2dep: context tools/mkdeps$(HOSTEXEEXT) $(Q) for %%G in ($(KERNDEPDIRS)) do ( $(MAKE) -C %%G TOPDIR="$(TOPDIR)" EXTRADEFINES=$(KDEFINE) depend ) # Configuration targets diff --git a/nuttx/configs/stm32f4discovery/winbuild/Make.defs b/nuttx/configs/stm32f4discovery/winbuild/Make.defs index 426611f8e5..bb78f35aa4 100644 --- a/nuttx/configs/stm32f4discovery/winbuild/Make.defs +++ b/nuttx/configs/stm32f4discovery/winbuild/Make.defs @@ -135,3 +135,5 @@ HOSTCC = mingw-gcc.exe HOSTINCLUDES = -I. HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe HOSTLDFLAGS = +HOSTEXEEXT = .exe + diff --git a/nuttx/tools/Makefile.host b/nuttx/tools/Makefile.host index d6a521272f..882a3c0ae9 100644 --- a/nuttx/tools/Makefile.host +++ b/nuttx/tools/Makefile.host @@ -37,10 +37,10 @@ TOPDIR ?= ${shell pwd}/.. -include $(TOPDIR)/Make.defs include ${TOPDIR}/tools/Config.mk -all: mkconfig$(EXEEXT) mkversion$(EXEEXT) mksyscall$(EXEEXT) bdf-converter$(EXEEXT) mksymtab$(EXEEXT) mkdeps$(EXEEXT) -default: mkconfig$(EXEEXT) mksyscall$(EXEEXT) mkdeps$(EXEEXT) +all: mkconfig$(HOSTEXEEXT) mkversion$(HOSTEXEEXT) mksyscall$(HOSTEXEEXT) bdf-converter$(HOSTEXEEXT) mksymtab$(HOSTEXEEXT) mkdeps$(HOSTEXEEXT) +default: mkconfig$(HOSTEXEEXT) mksyscall$(HOSTEXEEXT) mkdeps$(HOSTEXEEXT) -ifdef EXEEXT +ifdef HOSTEXEEXT .PHONY: clean mkconfig mkversion mksyscall bdf-converter mksymtab mkdeps else .PHONY: clean @@ -53,11 +53,11 @@ HOSTCC ?= gcc # mkconfig - Convert a .config file into a C config.h file -mkconfig$(EXEEXT): mkconfig.c cfgparser.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkconfig$(EXEEXT) mkconfig.c cfgparser.c +mkconfig$(HOSTEXEEXT): mkconfig.c cfgparser.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkconfig$(HOSTEXEEXT) mkconfig.c cfgparser.c -ifdef EXEEXT -mkconfig: mkconfig$(EXEEXT) +ifdef HOSTEXEEXT +mkconfig: mkconfig$(HOSTEXEEXT) endif # cmpconfig - Compare the contents of two configuration files @@ -65,53 +65,53 @@ endif cmpconfig: cmpconfig.c $(Q) $(HOSTCC) $(HOSTCFLAGS) -o cmpconfig cmpconfig.c -ifdef EXEEXT -cmpconfig: cmpconfig$(EXEEXT) +ifdef HOSTEXEEXT +cmpconfig: cmpconfig$(HOSTEXEEXT) endif # mkversion - Convert a .version file into a C version.h file -mkversion$(EXEEXT): mkconfig.c cfgparser.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkversion$(EXEEXT) mkversion.c cfgparser.c +mkversion$(HOSTEXEEXT): mkconfig.c cfgparser.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkversion$(HOSTEXEEXT) mkversion.c cfgparser.c -ifdef EXEEXT -mkversion: mkversion$(EXEEXT) +ifdef HOSTEXEEXT +mkversion: mkversion$(HOSTEXEEXT) endif # mksyscall - Convert a CSV file into syscall stubs and proxies -mksyscall$(EXEEXT): mksyscall.c csvparser.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mksyscall$(EXEEXT) mksyscall.c csvparser.c +mksyscall$(HOSTEXEEXT): mksyscall.c csvparser.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mksyscall$(HOSTEXEEXT) mksyscall.c csvparser.c -ifdef EXEEXT -mksyscall: mksyscall$(EXEEXT) +ifdef HOSTEXEEXT +mksyscall: mksyscall$(HOSTEXEEXT) endif # mksymtab - Convert a CSV file into a symbol table -mksymtab$(EXEEXT): mksymtab.c csvparser.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mksymtab$(EXEEXT) mksymtab.c csvparser.c +mksymtab$(HOSTEXEEXT): mksymtab.c csvparser.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mksymtab$(HOSTEXEEXT) mksymtab.c csvparser.c -ifdef EXEEXT -mksymtab: mksymtab$(EXEEXT) +ifdef HOSTEXEEXT +mksymtab: mksymtab$(HOSTEXEEXT) endif # bdf-converter - Converts a BDF font to the NuttX font format -bdf-converter$(EXEEXT): bdf-converter.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o bdf-converter$(EXEEXT) bdf-converter.c +bdf-converter$(HOSTEXEEXT): bdf-converter.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o bdf-converter$(HOSTEXEEXT) bdf-converter.c -ifdef EXEEXT -bdf-converter: bdf-converter$(EXEEXT) +ifdef HOSTEXEEXT +bdf-converter: bdf-converter$(HOSTEXEEXT) endif # Create dependencies for a list of files -mkdeps$(EXEEXT): mkdeps.c csvparser.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkdeps$(EXEEXT) mkdeps.c +mkdeps$(HOSTEXEEXT): mkdeps.c csvparser.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkdeps$(HOSTEXEEXT) mkdeps.c -ifdef EXEEXT -mkdeps: mkdeps$(EXEEXT) +ifdef HOSTEXEEXT +mkdeps: mkdeps$(HOSTEXEEXT) endif clean: diff --git a/nuttx/tools/mkdeps.c b/nuttx/tools/mkdeps.c index 1822dc9577..7850cee732 100644 --- a/nuttx/tools/mkdeps.c +++ b/nuttx/tools/mkdeps.c @@ -105,7 +105,7 @@ static void append(char **base, char *str) } else { - alloclen = strlen(newbase) + strlen(str) + 2; + alloclen = strlen(oldbase) + strlen(str) + 2; newbase = (char *)malloc(alloclen); if (!newbase) { @@ -288,7 +288,6 @@ static void do_dependency(const char *file, char separator) struct stat buf; char *altpath; char *path; - char *bufptr; int cmdlen; int pathlen; int filelen; @@ -300,7 +299,7 @@ static void do_dependency(const char *file, char separator) cmdlen = strlen(g_cc); if (cmdlen >= MAX_BUFFER) { - fprintf(stderr, "ERROR: Compiler string is too long: %s\n", path); + fprintf(stderr, "ERROR: Compiler string is too long: %s\n", g_cc); exit(EXIT_FAILURE); } @@ -355,7 +354,7 @@ static void do_dependency(const char *file, char separator) if (command[totallen] != '\0') { - fprintf(stderr, "ERROR: Missing NUL terminator\n", path); + fprintf(stderr, "ERROR: Missing NUL terminator\n"); exit(EXIT_FAILURE); } @@ -379,7 +378,7 @@ static void do_dependency(const char *file, char separator) /* Check that a file actually exists at this path */ - ret = stat(command, &buf); + ret = stat(&command[cmdlen], &buf); if (ret < 0) { altpath = NULL; @@ -388,7 +387,7 @@ static void do_dependency(const char *file, char separator) if (!S_ISREG(buf.st_mode)) { - fprintf(stderr, "ERROR: File %s exists but is not a regular file\n"); + fprintf(stderr, "ERROR: File %s exists but is not a regular file\n", &command[cmdlen]); exit(EXIT_FAILURE); } @@ -397,7 +396,7 @@ static void do_dependency(const char *file, char separator) ret = system(command); if (ret != 0) { - fprintf(stderr, "ERROR: ssystem(%s) failed\n"); + fprintf(stderr, "ERROR: ssystem(%s) failed\n", command); exit(EXIT_FAILURE); } From b74772ee54f0c70a68d4d5e967d3ef46be50251d Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 13 Nov 2012 15:50:38 +0000 Subject: [PATCH 113/206] Mostly cosmetic changes git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5344 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Kconfig | 12 ++++++++++-- nuttx/arch/arm/src/lm3s/Kconfig | 9 +++++++-- nuttx/arch/arm/src/lpc17xx/Kconfig | 17 ++++++++++++----- nuttx/arch/arm/src/lpc31xx/Kconfig | 15 ++++++++++----- nuttx/arch/arm/src/stm32/Kconfig | 18 +++++++++++++----- nuttx/configs/ea3131/README.txt | 3 --- nuttx/configs/eagle100/README.txt | 3 --- nuttx/configs/ekk-lm3s9b96/README.txt | 3 --- nuttx/configs/fire-stm32v2/README.txt | 3 --- nuttx/configs/hymini-stm32v/README.txt | 3 --- nuttx/configs/kwikstik-k40/README.txt | 3 --- nuttx/configs/lincoln60/README.txt | 3 --- nuttx/configs/lm3s6432-s2e/README.txt | 3 --- nuttx/configs/lm3s6965-ek/README.txt | 3 --- nuttx/configs/lm3s8962-ek/README.txt | 3 --- nuttx/configs/lpc4330-xplorer/README.txt | 3 --- nuttx/configs/lpcxpresso-lpc1768/README.txt | 3 --- nuttx/configs/mbed/README.txt | 3 --- nuttx/configs/mcu123-lpc214x/README.txt | 3 --- nuttx/configs/micropendous3/README.txt | 4 ---- nuttx/configs/mirtoo/README.txt | 3 --- nuttx/configs/ntosd-dm320/README.txt | 3 --- nuttx/configs/nucleus2g/README.txt | 3 --- nuttx/configs/olimex-lpc1766stk/README.txt | 3 --- nuttx/configs/olimex-strp711/README.txt | 3 --- nuttx/configs/pcblogic-pic32mx/README.txt | 3 --- nuttx/configs/pic32-starterkit/README.txt | 3 --- nuttx/configs/pic32mx7mmb/README.txt | 3 --- nuttx/configs/sam3u-ek/README.txt | 3 --- nuttx/configs/shenzhou/README.txt | 3 --- nuttx/configs/stm3210e-eval/README.txt | 3 --- nuttx/configs/stm3220g-eval/README.txt | 3 --- nuttx/configs/stm3240g-eval/README.txt | 3 --- nuttx/configs/stm32f100rc_generic/README.txt | 3 --- nuttx/configs/stm32f4discovery/README.txt | 3 --- .../configs/stm32f4discovery/ostest/Make.defs | 5 +++++ nuttx/configs/sure-pic32mx/README.txt | 3 --- nuttx/configs/teensy/README.txt | 4 ---- nuttx/configs/twr-k60n512/README.txt | 3 --- nuttx/configs/ubw32/README.txt | 3 --- nuttx/configs/vsn/README.txt | 3 --- nuttx/tools/README.txt | 19 +++++++++++++++---- nuttx/tools/mkdeps.c | 3 ++- 43 files changed, 74 insertions(+), 131 deletions(-) diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 13e92ebf2c..239a791fa2 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -45,22 +45,30 @@ choice config WINDOWS_NATIVE bool "Windows Native" + ---help--- + Build natively in a CMD.exe environment with Windows style paths (like C:\cgywin\home) config WINDOWS_CYGWIN bool "Cygwin" +- --help--- + Build natively in a Cygwin environment with POSIX style paths (like /cygdrive/c/cgywin/home) config WINDOWS_MSYS bool "MSYS" + ---help--- + Build natively in a Cygwin environment with POSIX style paths (like /cygdrive/c/cgywin/home) config WINDOWS_OTHER - bool "Other POSIX-like environment" + bool "Windows POSIX-like environment" + ---help--- + Build natively in another POSIX-like environment. Additional support may be necessary endchoice config WINDOWS_MKLINK bool "Use mklink" default y - depends on HOST_WINDOWS + depends on WINDOWS_NATIVE ---help--- Use the mklink command to set up symbolic links when NuttX is configured. Otherwise, configuration directories will be copied to diff --git a/nuttx/arch/arm/src/lm3s/Kconfig b/nuttx/arch/arm/src/lm3s/Kconfig index 03da5c458a..ef33655f55 100644 --- a/nuttx/arch/arm/src/lm3s/Kconfig +++ b/nuttx/arch/arm/src/lm3s/Kconfig @@ -28,20 +28,25 @@ config ARCH_CHIP_LM3S8962 endchoice choice - prompt "Toolchain" - default LM3S_BUILDROOT + prompt "Toolchain Selection" + default LM3S_BUILDROOT if !HOST_WINDOWS + default LM3S_CODESOURCERYW if HOST_WINDOWS config LM3S_CODESOURCERYW bool "CodeSourcery GNU toolchain under Windows" + depends on HOST_WINDOWS config LM3S_CODESOURCERYL bool "CodeSourcery GNU toolchain under Linux" + depends on HOST_LINUX config LM3S_DEVKITARM bool "devkitARM GNU toolchain" + depends on HOST_WINDOWS config LM3S_BUILDROOT bool "Buildroot" + depends on !WINDOWS_NATIVE endchoice diff --git a/nuttx/arch/arm/src/lpc17xx/Kconfig b/nuttx/arch/arm/src/lpc17xx/Kconfig index 2769fc231f..8a12ad9023 100644 --- a/nuttx/arch/arm/src/lpc17xx/Kconfig +++ b/nuttx/arch/arm/src/lpc17xx/Kconfig @@ -58,26 +58,33 @@ config ARCH_FAMILY_LPC176X choice prompt "Toolchain Selection" - default LPC17_CODESOURCERYW + default LPC17_BUILDROOT if !HOST_WINDOWS + default LPC17_CODESOURCERYW if HOST_WINDOWS depends on ARCH_CHIP_LPC17XX config LPC17_CODESOURCERYW - bool "CodeSourcery for Windows" + bool "CodeSourcery GNU toolchain under Windows" + depends on HOST_WINDOWS config LPC17_CODESOURCERYL - bool "CodeSourcery for Linux" + bool "CodeSourcery GNU toolchain under Linux" + depends on HOST_LINUX config LPC17_DEVKITARM - bool "DevkitARM (Windows)" + bool "devkitARM GNU toolchain" + depends on HOST_WINDOWS config LPC17_BUILDROOT - bool "NuttX buildroot (Cygwin or Linux)" + bool "Buildroot" + depends on !WINDOWS_NATIVE config LPC17_CODEREDW bool "CodeRed for Windows" + depends on HOST_WINDOWS config LPC17_CODEREDL bool "CodeRed for Windows" + depends on HOST_LINUX endchoice diff --git a/nuttx/arch/arm/src/lpc31xx/Kconfig b/nuttx/arch/arm/src/lpc31xx/Kconfig index 39b19b95d5..ad7bf3d4ed 100644 --- a/nuttx/arch/arm/src/lpc31xx/Kconfig +++ b/nuttx/arch/arm/src/lpc31xx/Kconfig @@ -26,20 +26,25 @@ endchoice choice prompt "Toolchain Selection" - default LPC31_CODESOURCERYW + default LPC31_BUILDROOT if !HOST_WINDOWS + default LPC31_CODESOURCERYW if HOST_WINDOWS depends on ARCH_CHIP_LPC31XX config LPC31_CODESOURCERYW - bool "CodeSourcery for Windows" + bool "CodeSourcery GNU toolchain under Windows" + depends on HOST_WINDOWS config LPC31_CODESOURCERYL - bool "CodeSourcery for Linux" + bool "CodeSourcery GNU toolchain under Linux" + depends on HOST_LINUX config LPC31_DEVKITARM - bool "DevkitARM (Windows)" + bool "devkitARM GNU toolchain" + depends on HOST_WINDOWS config LPC31_BUILDROOT - bool "NuttX buildroot (Cygwin or Linux)" + bool "Buildroot" + depends on !WINDOWS_NATIVE endchoice diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index a0e3fab0c6..81ba9e4a37 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -195,29 +195,37 @@ config STM32_STM32F40XX choice prompt "Toolchain Selection" - default STM32_CODESOURCERYW + default LPC31_BUILDROOT if !HOST_WINDOWS + default STM32_CODESOURCERYW if HOST_WINDOWS depends on ARCH_CHIP_STM32 config STM32_CODESOURCERYW - bool "CodeSourcery for Windows" + bool "CodeSourcery GNU toolchain under Windows" + depends on HOST_WINDOWS config STM32_CODESOURCERYL - bool "CodeSourcery for Linux" + bool "CodeSourcery GNU toolchain under Linux" + depends on HOST_LINUX config STM32_ATOLLIC_LITE bool "Atollic Lite for Windows" + depends on HOST_WINDOWS config STM32_ATOLLIC_PRO bool "Atollic Pro for Windows" + depends on HOST_WINDOWS config STM32_DEVKITARM - bool "DevkitARM (Windows)" + bool "devkitARM GNU toolchain" + depends on HOST_WINDOWS config STM32_RAISONANCE bool "STMicro Raisonance for Windows" + depends on HOST_WINDOWS config STM32_BUILDROOT - bool "NuttX buildroot (Cygwin or Linux)" + bool "Buildroot (Cygwin or Linux)" + depends on !WINDOWS_NATIVE endchoice diff --git a/nuttx/configs/ea3131/README.txt b/nuttx/configs/ea3131/README.txt index 29b68ce8d1..2912bf3187 100644 --- a/nuttx/configs/ea3131/README.txt +++ b/nuttx/configs/ea3131/README.txt @@ -77,9 +77,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt index 79a4b96fdf..a79ac2b2d7 100644 --- a/nuttx/configs/eagle100/README.txt +++ b/nuttx/configs/eagle100/README.txt @@ -66,9 +66,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the CodeSourcery toolchain. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/ekk-lm3s9b96/README.txt b/nuttx/configs/ekk-lm3s9b96/README.txt index fc9448aaf9..d331c1cd56 100644 --- a/nuttx/configs/ekk-lm3s9b96/README.txt +++ b/nuttx/configs/ekk-lm3s9b96/README.txt @@ -136,9 +136,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/fire-stm32v2/README.txt b/nuttx/configs/fire-stm32v2/README.txt index aa3225524b..88b5bf583b 100644 --- a/nuttx/configs/fire-stm32v2/README.txt +++ b/nuttx/configs/fire-stm32v2/README.txt @@ -226,9 +226,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) diff --git a/nuttx/configs/hymini-stm32v/README.txt b/nuttx/configs/hymini-stm32v/README.txt index 4c55458061..9b063d0ffa 100644 --- a/nuttx/configs/hymini-stm32v/README.txt +++ b/nuttx/configs/hymini-stm32v/README.txt @@ -80,9 +80,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/kwikstik-k40/README.txt b/nuttx/configs/kwikstik-k40/README.txt index 1f3873cc9e..98e738d803 100644 --- a/nuttx/configs/kwikstik-k40/README.txt +++ b/nuttx/configs/kwikstik-k40/README.txt @@ -204,9 +204,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/lincoln60/README.txt b/nuttx/configs/lincoln60/README.txt index 87847cd8b7..159753890e 100644 --- a/nuttx/configs/lincoln60/README.txt +++ b/nuttx/configs/lincoln60/README.txt @@ -104,9 +104,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/lm3s6432-s2e/README.txt b/nuttx/configs/lm3s6432-s2e/README.txt index df7e7029d3..296a10f054 100644 --- a/nuttx/configs/lm3s6432-s2e/README.txt +++ b/nuttx/configs/lm3s6432-s2e/README.txt @@ -131,9 +131,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/lm3s6965-ek/README.txt b/nuttx/configs/lm3s6965-ek/README.txt index 96e87bb272..1e3aed2d95 100644 --- a/nuttx/configs/lm3s6965-ek/README.txt +++ b/nuttx/configs/lm3s6965-ek/README.txt @@ -160,9 +160,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/lm3s8962-ek/README.txt b/nuttx/configs/lm3s8962-ek/README.txt index 6de30047b0..fdb7834660 100644 --- a/nuttx/configs/lm3s8962-ek/README.txt +++ b/nuttx/configs/lm3s8962-ek/README.txt @@ -160,9 +160,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/lpc4330-xplorer/README.txt b/nuttx/configs/lpc4330-xplorer/README.txt index f7ec778eec..65f3820099 100644 --- a/nuttx/configs/lpc4330-xplorer/README.txt +++ b/nuttx/configs/lpc4330-xplorer/README.txt @@ -185,9 +185,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) diff --git a/nuttx/configs/lpcxpresso-lpc1768/README.txt b/nuttx/configs/lpcxpresso-lpc1768/README.txt index 2fedefc588..ca0c0fdbd6 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/README.txt +++ b/nuttx/configs/lpcxpresso-lpc1768/README.txt @@ -288,9 +288,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/mbed/README.txt b/nuttx/configs/mbed/README.txt index 09763086bd..a5390a1d74 100644 --- a/nuttx/configs/mbed/README.txt +++ b/nuttx/configs/mbed/README.txt @@ -74,9 +74,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/mcu123-lpc214x/README.txt b/nuttx/configs/mcu123-lpc214x/README.txt index 49a6d5c0f7..435f8647d4 100644 --- a/nuttx/configs/mcu123-lpc214x/README.txt +++ b/nuttx/configs/mcu123-lpc214x/README.txt @@ -72,9 +72,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the CodeSourcery toolchain. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) may not work with default optimization diff --git a/nuttx/configs/micropendous3/README.txt b/nuttx/configs/micropendous3/README.txt index cc4a47ee3e..583f1d8d8a 100644 --- a/nuttx/configs/micropendous3/README.txt +++ b/nuttx/configs/micropendous3/README.txt @@ -265,10 +265,6 @@ Windows Native Toolchains is because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native - toolchains. That support can be enabled by modifying your Make.defs - file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh An additional issue with the WinAVR toolchain, in particular, is that it diff --git a/nuttx/configs/mirtoo/README.txt b/nuttx/configs/mirtoo/README.txt index 7a58572bf8..e0b7dc3bc8 100644 --- a/nuttx/configs/mirtoo/README.txt +++ b/nuttx/configs/mirtoo/README.txt @@ -448,9 +448,6 @@ Toolchains because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh Loading NuttX with ICD3 diff --git a/nuttx/configs/ntosd-dm320/README.txt b/nuttx/configs/ntosd-dm320/README.txt index ba6cc87ecb..1a6a38e7ca 100644 --- a/nuttx/configs/ntosd-dm320/README.txt +++ b/nuttx/configs/ntosd-dm320/README.txt @@ -96,9 +96,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/nucleus2g/README.txt b/nuttx/configs/nucleus2g/README.txt index 0d1d2896b1..e915e8bdd0 100644 --- a/nuttx/configs/nucleus2g/README.txt +++ b/nuttx/configs/nucleus2g/README.txt @@ -134,9 +134,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt index 6bb36f40ce..ec7ddd42db 100644 --- a/nuttx/configs/olimex-lpc1766stk/README.txt +++ b/nuttx/configs/olimex-lpc1766stk/README.txt @@ -222,9 +222,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/olimex-strp711/README.txt b/nuttx/configs/olimex-strp711/README.txt index 7c3d3fe5b3..17f24734a6 100644 --- a/nuttx/configs/olimex-strp711/README.txt +++ b/nuttx/configs/olimex-strp711/README.txt @@ -157,9 +157,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the CodeSourcery toolchain. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) may not work with default optimization diff --git a/nuttx/configs/pcblogic-pic32mx/README.txt b/nuttx/configs/pcblogic-pic32mx/README.txt index 9eea61fd87..bd81f0c423 100644 --- a/nuttx/configs/pcblogic-pic32mx/README.txt +++ b/nuttx/configs/pcblogic-pic32mx/README.txt @@ -276,9 +276,6 @@ Toolchains because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh Loading NuttX with PICkit2 diff --git a/nuttx/configs/pic32-starterkit/README.txt b/nuttx/configs/pic32-starterkit/README.txt index b21066b535..ea82a166b2 100644 --- a/nuttx/configs/pic32-starterkit/README.txt +++ b/nuttx/configs/pic32-starterkit/README.txt @@ -493,9 +493,6 @@ Toolchains because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh Powering the Board diff --git a/nuttx/configs/pic32mx7mmb/README.txt b/nuttx/configs/pic32mx7mmb/README.txt index cc8ea5573c..2112065255 100644 --- a/nuttx/configs/pic32mx7mmb/README.txt +++ b/nuttx/configs/pic32mx7mmb/README.txt @@ -261,9 +261,6 @@ Toolchains because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh Powering the Board diff --git a/nuttx/configs/sam3u-ek/README.txt b/nuttx/configs/sam3u-ek/README.txt index bcb8b9ef62..d8d1908046 100644 --- a/nuttx/configs/sam3u-ek/README.txt +++ b/nuttx/configs/sam3u-ek/README.txt @@ -75,9 +75,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt index 2f2833bbee..a15d2f9152 100644 --- a/nuttx/configs/shenzhou/README.txt +++ b/nuttx/configs/shenzhou/README.txt @@ -249,9 +249,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt index 9e63112016..f494e9e9ab 100644 --- a/nuttx/configs/stm3210e-eval/README.txt +++ b/nuttx/configs/stm3210e-eval/README.txt @@ -83,9 +83,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/stm3220g-eval/README.txt b/nuttx/configs/stm3220g-eval/README.txt index 0e6a9a7dad..1e3388e70d 100644 --- a/nuttx/configs/stm3220g-eval/README.txt +++ b/nuttx/configs/stm3220g-eval/README.txt @@ -89,9 +89,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index 140cc7414d..829f3a7773 100644 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -91,9 +91,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) diff --git a/nuttx/configs/stm32f100rc_generic/README.txt b/nuttx/configs/stm32f100rc_generic/README.txt index 0c96d4fbc5..951fb31305 100644 --- a/nuttx/configs/stm32f100rc_generic/README.txt +++ b/nuttx/configs/stm32f100rc_generic/README.txt @@ -85,9 +85,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index 68be0a8a67..eb43cad27e 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -89,9 +89,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh The CodeSourcery Toolchain (2009q1) diff --git a/nuttx/configs/stm32f4discovery/ostest/Make.defs b/nuttx/configs/stm32f4discovery/ostest/Make.defs index 6ed8530ad2..614e0c456f 100644 --- a/nuttx/configs/stm32f4discovery/ostest/Make.defs +++ b/nuttx/configs/stm32f4discovery/ostest/Make.defs @@ -172,4 +172,9 @@ HOSTCC = gcc HOSTINCLUDES = -I. HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe HOSTLDFLAGS = +ifeq ($(CONFIG_HOST_WINDOWS),y) + HOSTEXEEXT = .exe +else + HOSTEXEEXT = +endif diff --git a/nuttx/configs/sure-pic32mx/README.txt b/nuttx/configs/sure-pic32mx/README.txt index 68f0bd3365..403fe42baf 100644 --- a/nuttx/configs/sure-pic32mx/README.txt +++ b/nuttx/configs/sure-pic32mx/README.txt @@ -342,9 +342,6 @@ Toolchains because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh Loading NuttX with PICkit2 diff --git a/nuttx/configs/teensy/README.txt b/nuttx/configs/teensy/README.txt index 454a42d054..30349e1ff0 100644 --- a/nuttx/configs/teensy/README.txt +++ b/nuttx/configs/teensy/README.txt @@ -268,10 +268,6 @@ Windows Native Toolchains is because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native - toolchains. That support can be enabled by modifying your Make.defs - file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh An additional issue with the WinAVR toolchain, in particular, is that it diff --git a/nuttx/configs/twr-k60n512/README.txt b/nuttx/configs/twr-k60n512/README.txt index cd567fd375..a9db7a1f77 100644 --- a/nuttx/configs/twr-k60n512/README.txt +++ b/nuttx/configs/twr-k60n512/README.txt @@ -341,9 +341,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/configs/ubw32/README.txt b/nuttx/configs/ubw32/README.txt index 83ade7dae9..801be39a9a 100644 --- a/nuttx/configs/ubw32/README.txt +++ b/nuttx/configs/ubw32/README.txt @@ -287,9 +287,6 @@ Toolchains because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh Loading NuttX with PICkit2 diff --git a/nuttx/configs/vsn/README.txt b/nuttx/configs/vsn/README.txt index a0b8e24193..debc3e8ad4 100644 --- a/nuttx/configs/vsn/README.txt +++ b/nuttx/configs/vsn/README.txt @@ -80,9 +80,6 @@ GNU Toolchain Options because the dependencies are generated using Windows pathes which do not work with the Cygwin make. - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - MKDEP = $(TOPDIR)/tools/mknulldeps.sh NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization diff --git a/nuttx/tools/README.txt b/nuttx/tools/README.txt index 28fa664bda..3c9730d001 100644 --- a/nuttx/tools/README.txt +++ b/nuttx/tools/README.txt @@ -290,11 +290,17 @@ mknulldeps.sh The mknulldeps.sh is a stub script that does essentially nothing. - NOTE: The mkdep.* files are undergoing change. mkdeps.sh is a bash + NOTE: The mk*deps.* files are undergoing change. mkdeps.sh is a bash script that produces dependencies well for POSIX style hosts (e..g., Linux and Cygwin). It does not work well for mixed environments with a Windows toolchain running in a POSIX style environemnt (hence, the - mknulldeps.sh script). + mknulldeps.sh script). And, of course, cannot be used in a Windows + nativ environment. + + [mkdeps.sh does have an option, --winpath, that purports to convert + the dependencies generated by a Windows toolchain to POSIX format. + However, that is not being used and mostly likely does not cover + all of the conversion cases.] mkdeps.bat is a simple port of the bash script to run in a Windows command shell. However, it does not work well either because some @@ -302,8 +308,13 @@ mknulldeps.sh by the CMD.exe shell. mkdeps.c generates mkdeps (on Linux) or mkdeps.exe (on Windows). - This C version should solve all of the issues. However, this verison - is still under-development. + However, this verison is still under-development. It works well in + the all POSIX environment or in the all Windows environment but also + does not work well in mixed POSIX environment with a Windows toolchain. + In that case, there are still issues with the conversion of things like + 'c:\Program Files' to 'c:program files' by bash. Those issues may, + eventually be solvable but for now continue to use mknulldeps.sh in + that mixed environment. define.sh diff --git a/nuttx/tools/mkdeps.c b/nuttx/tools/mkdeps.c index 7850cee732..f2a1963878 100644 --- a/nuttx/tools/mkdeps.c +++ b/nuttx/tools/mkdeps.c @@ -396,7 +396,8 @@ static void do_dependency(const char *file, char separator) ret = system(command); if (ret != 0) { - fprintf(stderr, "ERROR: ssystem(%s) failed\n", command); + fprintf(stderr, "ERROR: system failed: %s\n", strerror(errno)); + fprintf(stderr, " command: %s\n", command); exit(EXIT_FAILURE); } From 93248471033bdf18d62cd3290129ec78dbb55dcf Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 13 Nov 2012 17:18:42 +0000 Subject: [PATCH 114/206] Oops.. nested strtok in mkdeps.c, need to use strtok_r git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5345 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/stm32f4discovery/README.txt | 8 +++++++- nuttx/configs/stm32f4discovery/ostest/Make.defs | 16 +++++++++++----- .../configs/stm32f4discovery/winbuild/Make.defs | 5 ++++- nuttx/tools/mkdeps.c | 8 +++++--- 4 files changed, 27 insertions(+), 10 deletions(-) diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index eb43cad27e..d824668cef 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -1084,8 +1084,10 @@ Where is one of the following: b. Execute 'make menuconfig' in nuttx/ in order to start the reconfiguration process. - 2. Default toolchain: + 2. Default platform/toolchain: + CONFIG_HOST_WINDOWS=y : Windows + CONFIG_WINDOWS_CYGWIN=y : Cygwin environment on Windows CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows 3. By default, this project assumes that you are *NOT* using the DFU @@ -1460,6 +1462,10 @@ Where is one of the following: standard issue, CMD shell: ConEmu which can be downloaded from: http://code.google.com/p/conemu-maximus5/ + CONFIG_HOST_WINDOWS=y : Windows + CONFIG_WINDOWS_NATIVE=y : Native Windows environment + CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + Build Tools. The build still relies on some Unix-like commands. I use the GNUWin32 tools that can be downloaded from http://gnuwin32.sourceforge.net/. The MSYS tools are probably also a option but are likely lower performance diff --git a/nuttx/configs/stm32f4discovery/ostest/Make.defs b/nuttx/configs/stm32f4discovery/ostest/Make.defs index 614e0c456f..3106143d6c 100644 --- a/nuttx/configs/stm32f4discovery/ostest/Make.defs +++ b/nuttx/configs/stm32f4discovery/ostest/Make.defs @@ -105,16 +105,12 @@ LDSCRIPT = ld.script ifeq ($(WINTOOL),y) # Windows-native toolchains - DIRLINK = $(TOPDIR)/tools/winlink.sh - DIRUNLINK = $(TOPDIR)/tools/unlink.sh - MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/scripts/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 else - # Linux/Cygwin-native toolchain - MKDEP = $(TOPDIR)/tools/mkdeps.sh + # Linux/Cygwin-native toolchain ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) @@ -178,3 +174,13 @@ else HOSTEXEEXT = endif +ifeq ($(WINTOOL),y) + # Windows-native host tools + DIRLINK = $(TOPDIR)/tools/winlink.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh +else + # Linux/Cygwin-native host tools + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) +endif + diff --git a/nuttx/configs/stm32f4discovery/winbuild/Make.defs b/nuttx/configs/stm32f4discovery/winbuild/Make.defs index bb78f35aa4..75051da515 100644 --- a/nuttx/configs/stm32f4discovery/winbuild/Make.defs +++ b/nuttx/configs/stm32f4discovery/winbuild/Make.defs @@ -81,7 +81,6 @@ LDSCRIPT = ld.script # Windows-native toolchains -MKDEP = $(TOPDIR)/tools/mkdeps.bat ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) @@ -137,3 +136,7 @@ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe HOSTLDFLAGS = HOSTEXEEXT = .exe +# Windows-native host tools + +MKDEP = $(TOPDIR)/tools/mkdeps.exe + diff --git a/nuttx/tools/mkdeps.c b/nuttx/tools/mkdeps.c index f2a1963878..a90595c980 100644 --- a/nuttx/tools/mkdeps.c +++ b/nuttx/tools/mkdeps.c @@ -288,6 +288,7 @@ static void do_dependency(const char *file, char separator) struct stat buf; char *altpath; char *path; + char *lasts; int cmdlen; int pathlen; int filelen; @@ -330,15 +331,15 @@ static void do_dependency(const char *file, char separator) /* Add a space */ command[cmdlen] = ' '; - command[cmdlen+1] = '\0'; cmdlen++; + command[cmdlen] = '\0'; /* Try each path. This loop will continue until each path has been tried * (failure) or until stat() finds the file */ altpath = g_altpath; - while ((path = strtok(altpath, " ")) != NULL) + while ((path = strtok_r(altpath, " ", &lasts)) != NULL) { /* Create a full path to the file */ @@ -565,6 +566,7 @@ static void do_winpath(char *file) int main(int argc, char **argv, char **envp) { + char *lasts; char *files; char *file; @@ -575,7 +577,7 @@ int main(int argc, char **argv, char **envp) /* Then generate dependencies for each path on the command line */ files = g_files; - while ((file = strtok(files, " ")) != NULL) + while ((file = strtok_r(files, " ", &lasts)) != NULL) { /* Check if we need to do path conversions for a Windows-natvie tool * being using in a POSIX/Cygwin environment. From c1e28f5f13beda2c3074e3c470293887d19d8071 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sun, 11 Nov 2012 19:10:26 +0100 Subject: [PATCH 115/206] first version of yaw control loop, needs testing --- .../fixedwing_att_control_att.c | 4 +- .../fixedwing_att_control_att.h | 2 + .../fixedwing_att_control_main.c | 46 ++++++++++++++++--- .../fixedwing_att_control_rate.c | 2 +- .../fixedwing_pos_control_main.c | 1 - apps/mavlink/mavlink_receiver.c | 23 +++++++++- 6 files changed, 67 insertions(+), 11 deletions(-) diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.c b/apps/fixedwing_att_control/fixedwing_att_control_att.c index 18b290f994..24142dece6 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_att.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_att.c @@ -113,6 +113,7 @@ static int parameters_update(const struct fw_pos_control_param_handles *h, struc int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, + const float speed_body[], struct vehicle_rates_setpoint_s *rates_sp) { static int counter = 0; @@ -150,7 +151,8 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att rates_sp->pitch = pid_calculate(&pitch_controller, pitch_sp_rollcompensation, att->pitch, 0, 0); /* Yaw (from coordinated turn constraint or lateral force) */ - //TODO + rates_sp->yaw = (att->rollspeed * rates_sp->roll + 9.81f * sinf(att->roll) * cosf(att->pitch) + speed_body[0] * rates_sp->pitch * sinf(att->roll)) + / (speed_body[0] * cosf(att->roll) * cosf(att->pitch) + speed_body[1] * sinf(att->pitch)); counter++; diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.h b/apps/fixedwing_att_control/fixedwing_att_control_att.h index ca7c14b43c..11c932800e 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_att.h +++ b/apps/fixedwing_att_control/fixedwing_att_control_att.h @@ -41,9 +41,11 @@ #include #include #include +#include int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, + const float speed_body[], struct vehicle_rates_setpoint_s *rates_sp); #endif /* FIXEDWING_ATT_CONTROL_ATT_H_ */ diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index ad0f201e1b..d2fbe31a60 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -58,6 +58,7 @@ #include #include #include +#include #include #include #include @@ -135,28 +136,33 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) memset(&att_sp, 0, sizeof(att_sp)); struct vehicle_rates_setpoint_s rates_sp; memset(&rates_sp, 0, sizeof(rates_sp)); -// static struct debug_key_value_s debug_output; -// memset(&debug_output, 0, sizeof(debug_output)); + struct vehicle_global_position_s global_pos; + memset(&global_pos, 0, sizeof(global_pos)); + /* output structs */ struct actuator_controls_s actuators; memset(&actuators, 0, sizeof(actuators)); + static struct debug_key_value_s debug_output; + memset(&debug_output, 0, sizeof(debug_output)); /* publish actuator controls */ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) actuators.control[i] = 0.0f; orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators); -// orb_advert_t debug_pub = orb_advertise(ORB_ID(debug_key_value), &debug_output); -// debug_output.key[0] = '1'; + orb_advert_t debug_pub = orb_advertise(ORB_ID(debug_key_value), &debug_output); + debug_output.key[0] = '1'; /* subscribe */ int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); + int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); /* Setup of loop */ float gyro[3] = {0.0f, 0.0f, 0.0f}; + float speed_body[3] = {0.0f, 0.0f, 0.0f}; struct pollfd fds = { .fd = att_sub, .events = POLLIN }; while(!thread_should_exit) @@ -164,10 +170,35 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) /* wait for a sensor update, check for exit condition every 500 ms */ poll(&fds, 1, 500); + /* Check if there is a new position measurement or attitude setpoint */ + bool pos_updated; + orb_check(global_pos_sub, &pos_updated); + bool att_sp_updated; + orb_check(att_sp_sub, &att_sp_updated); + /*Get Local Copies */ /* get a local copy of attitude */ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); - orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp); + if(att_sp_updated) + orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp); + if(pos_updated) + { + orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos); + if(att.R_valid) + { + speed_body[0] = att.R[0][0] * global_pos.vx + att.R[0][1] * global_pos.vy + att.R[0][2] * global_pos.vz; + speed_body[1] = att.R[1][0] * global_pos.vx + att.R[1][1] * global_pos.vy + att.R[1][2] * global_pos.vz; + speed_body[2] = att.R[2][0] * global_pos.vx + att.R[2][1] * global_pos.vy + att.R[2][2] * global_pos.vz; + } + else + { + speed_body[0] = 0; + speed_body[1] = 0; + speed_body[2] = 0; + + printf("FW ATT CONTROL: Did not get a valid R\n"); + } + } gyro[0] = att.rollspeed; gyro[1] = att.pitchspeed; @@ -178,6 +209,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) /* Attitude Control */ fixedwing_att_control_attitude(&att_sp, &att, + &speed_body, &rates_sp); /* Attitude Rate Control */ @@ -187,8 +219,8 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) actuators.control[3] = 0.7f; orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); -// debug_output.value = rates_sp.pitch; -// orb_publish(ORB_ID(debug_key_value), debug_pub, &debug_output); + debug_output.value = rates_sp.yaw; + orb_publish(ORB_ID(debug_key_value), debug_pub, &debug_output); } printf("[fixedwing_att_control] exiting, stopping all motors.\n"); diff --git a/apps/fixedwing_att_control/fixedwing_att_control_rate.c b/apps/fixedwing_att_control/fixedwing_att_control_rate.c index b81d50168b..6f3a7f6e8d 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_rate.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_rate.c @@ -172,7 +172,7 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp, actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT); //TODO: (-) sign comes from the elevator (positive --> deflection downwards), this has to be moved to the mixer... - actuators->control[2] = 0;//pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now + actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now counter++; diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c index 4430489130..4a1025109a 100644 --- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c +++ b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c @@ -248,7 +248,6 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) /* Control */ - /* Simple Horizontal Control */ if(global_sp_updated_set_once) { diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c index 3e485274eb..45fe1ccb57 100644 --- a/apps/mavlink/mavlink_receiver.c +++ b/apps/mavlink/mavlink_receiver.c @@ -292,6 +292,26 @@ handle_message(mavlink_message_t *msg) mavlink_hil_state_t hil_state; mavlink_msg_hil_state_decode(msg, &hil_state); + /* Calculate Rotation Matrix */ + //TODO: better clarification which app does this, atm we have a ekf for quadrotors which does this, but there is no such thing if fly in fixed wing mode + + if(mavlink_system.type == MAV_TYPE_FIXED_WING) { + //TODO: asuming low pitch and roll for now + hil_attitude.R[0][0] = cosf(hil_state.yaw); + hil_attitude.R[0][1] = sinf(hil_state.yaw); + hil_attitude.R[0][2] = 0.0f; + + hil_attitude.R[1][0] = -sinf(hil_state.yaw); + hil_attitude.R[1][1] = cosf(hil_state.yaw); + hil_attitude.R[1][2] = 0.0f; + + hil_attitude.R[2][0] = 0.0f; + hil_attitude.R[2][1] = 0.0f; + hil_attitude.R[2][2] = 1.0f; + + hil_attitude.R_valid = true; + } + hil_global_pos.lat = hil_state.lat; hil_global_pos.lon = hil_state.lon; hil_global_pos.alt = hil_state.alt / 1000.0f; @@ -299,6 +319,7 @@ handle_message(mavlink_message_t *msg) hil_global_pos.vy = hil_state.vy / 100.0f; hil_global_pos.vz = hil_state.vz / 100.0f; + /* set timestamp and notify processes (broadcast) */ hil_global_pos.timestamp = hrt_absolute_time(); orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos); @@ -418,4 +439,4 @@ receive_start(int uart) pthread_t thread; pthread_create(&thread, &receiveloop_attr, receive_thread, &uart); return thread; -} \ No newline at end of file +} From bcdd7936ce8a366e644f45fab42a48455b719546 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 13 Nov 2012 20:24:30 +0000 Subject: [PATCH 116/206] Centralized the definition of the INCDIR script in tools/Config.mk git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5346 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/UnitTests/CButton/Makefile | 2 - NxWidgets/UnitTests/CButtonArray/Makefile | 2 - NxWidgets/UnitTests/CCheckBox/Makefile | 2 - NxWidgets/UnitTests/CGlyphButton/Makefile | 2 - NxWidgets/UnitTests/CImage/Makefile | 2 - NxWidgets/UnitTests/CKeypad/Makefile | 2 - NxWidgets/UnitTests/CLabel/Makefile | 2 - NxWidgets/UnitTests/CLatchButton/Makefile | 2 - .../UnitTests/CLatchButtonArray/Makefile | 2 - NxWidgets/UnitTests/CListBox/Makefile | 2 - NxWidgets/UnitTests/CProgressBar/Makefile | 2 - NxWidgets/UnitTests/CRadioButton/Makefile | 2 - .../UnitTests/CScrollbarHorizontal/Makefile | 2 - .../UnitTests/CScrollbarVertical/Makefile | 2 - NxWidgets/UnitTests/CSliderHorizonal/Makefile | 2 - NxWidgets/UnitTests/CSliderVertical/Makefile | 2 - NxWidgets/UnitTests/CTextBox/Makefile | 2 - NxWidgets/UnitTests/nxwm/Makefile | 2 - NxWidgets/libnxwidgets/Makefile | 5 +- NxWidgets/nxwm/Makefile | 9 +-- apps/interpreters/ficl/Makefile | 3 - apps/modbus/ascii/Make.defs | 2 +- apps/modbus/functions/Make.defs | 2 +- apps/modbus/nuttx/Make.defs | 2 +- apps/modbus/rtu/Make.defs | 2 +- apps/modbus/tcp/Make.defs | 2 +- apps/netutils/thttpd/cgi-src/Makefile | 4 +- misc/pascal/nuttx/Makefile | 2 - nuttx/ChangeLog | 3 + nuttx/binfmt/Makefile | 2 +- .../stm32f4discovery/winbuild/Make.defs | 2 +- nuttx/drivers/analog/Make.defs | 6 +- nuttx/drivers/bch/Make.defs | 4 +- nuttx/drivers/input/Make.defs | 4 +- nuttx/drivers/lcd/Make.defs | 2 +- nuttx/drivers/mmcsd/Make.defs | 4 +- nuttx/drivers/power/Make.defs | 4 +- nuttx/drivers/sensors/Make.defs | 4 +- nuttx/drivers/usbdev/Make.defs | 2 +- nuttx/drivers/usbhost/Make.defs | 4 +- nuttx/drivers/wireless/Make.defs | 4 +- nuttx/graphics/Makefile | 14 ++-- nuttx/tools/Config.mk | 81 ++++++++++++++++++- nuttx/tools/Makefile.host | 7 ++ nuttx/tools/README.txt | 39 ++++++++- nuttx/tools/mkdeps.c | 69 ++++++++++++++++ 46 files changed, 236 insertions(+), 88 deletions(-) diff --git a/NxWidgets/UnitTests/CButton/Makefile b/NxWidgets/UnitTests/CButton/Makefile index 87649ac3c4..01bca12a57 100644 --- a/NxWidgets/UnitTests/CButton/Makefile +++ b/NxWidgets/UnitTests/CButton/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CButtonArray/Makefile b/NxWidgets/UnitTests/CButtonArray/Makefile index 03f7624f93..84d19277e0 100644 --- a/NxWidgets/UnitTests/CButtonArray/Makefile +++ b/NxWidgets/UnitTests/CButtonArray/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CCheckBox/Makefile b/NxWidgets/UnitTests/CCheckBox/Makefile index 715fe4dad0..5aa96e6185 100644 --- a/NxWidgets/UnitTests/CCheckBox/Makefile +++ b/NxWidgets/UnitTests/CCheckBox/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CGlyphButton/Makefile b/NxWidgets/UnitTests/CGlyphButton/Makefile index db91bdfbca..ec0c5d5d3c 100644 --- a/NxWidgets/UnitTests/CGlyphButton/Makefile +++ b/NxWidgets/UnitTests/CGlyphButton/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CImage/Makefile b/NxWidgets/UnitTests/CImage/Makefile index fb26404464..5970d59d19 100644 --- a/NxWidgets/UnitTests/CImage/Makefile +++ b/NxWidgets/UnitTests/CImage/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CKeypad/Makefile b/NxWidgets/UnitTests/CKeypad/Makefile index 36ae2f5438..b0aba9603f 100644 --- a/NxWidgets/UnitTests/CKeypad/Makefile +++ b/NxWidgets/UnitTests/CKeypad/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CLabel/Makefile b/NxWidgets/UnitTests/CLabel/Makefile index 2ddfbbf427..9a5fa13216 100644 --- a/NxWidgets/UnitTests/CLabel/Makefile +++ b/NxWidgets/UnitTests/CLabel/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CLatchButton/Makefile b/NxWidgets/UnitTests/CLatchButton/Makefile index a44e7e9549..e50db8914f 100644 --- a/NxWidgets/UnitTests/CLatchButton/Makefile +++ b/NxWidgets/UnitTests/CLatchButton/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CLatchButtonArray/Makefile b/NxWidgets/UnitTests/CLatchButtonArray/Makefile index a11c9bfd64..544167ec94 100644 --- a/NxWidgets/UnitTests/CLatchButtonArray/Makefile +++ b/NxWidgets/UnitTests/CLatchButtonArray/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CListBox/Makefile b/NxWidgets/UnitTests/CListBox/Makefile index a396d4b01a..1161460b44 100644 --- a/NxWidgets/UnitTests/CListBox/Makefile +++ b/NxWidgets/UnitTests/CListBox/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CProgressBar/Makefile b/NxWidgets/UnitTests/CProgressBar/Makefile index 11b802f92e..6fee2fac9b 100644 --- a/NxWidgets/UnitTests/CProgressBar/Makefile +++ b/NxWidgets/UnitTests/CProgressBar/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CRadioButton/Makefile b/NxWidgets/UnitTests/CRadioButton/Makefile index b642ebaf31..97e8a398ee 100644 --- a/NxWidgets/UnitTests/CRadioButton/Makefile +++ b/NxWidgets/UnitTests/CRadioButton/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile b/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile index c952fd1e2e..952ec4c6b4 100644 --- a/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile +++ b/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CScrollbarVertical/Makefile b/NxWidgets/UnitTests/CScrollbarVertical/Makefile index 81b8ced265..4e44699ee8 100644 --- a/NxWidgets/UnitTests/CScrollbarVertical/Makefile +++ b/NxWidgets/UnitTests/CScrollbarVertical/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CSliderHorizonal/Makefile b/NxWidgets/UnitTests/CSliderHorizonal/Makefile index e31f1f0331..5bc6c84c60 100644 --- a/NxWidgets/UnitTests/CSliderHorizonal/Makefile +++ b/NxWidgets/UnitTests/CSliderHorizonal/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CSliderVertical/Makefile b/NxWidgets/UnitTests/CSliderVertical/Makefile index 3a86b57e97..4c6a660f0c 100644 --- a/NxWidgets/UnitTests/CSliderVertical/Makefile +++ b/NxWidgets/UnitTests/CSliderVertical/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/CTextBox/Makefile b/NxWidgets/UnitTests/CTextBox/Makefile index b73ce8f4a1..8fde36bb08 100644 --- a/NxWidgets/UnitTests/CTextBox/Makefile +++ b/NxWidgets/UnitTests/CTextBox/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/UnitTests/nxwm/Makefile b/NxWidgets/UnitTests/nxwm/Makefile index cfcdef750f..73cb0b42a2 100644 --- a/NxWidgets/UnitTests/nxwm/Makefile +++ b/NxWidgets/UnitTests/nxwm/Makefile @@ -35,7 +35,6 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" -INCDIR=$(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} CXXFLAGS += ${shell $(INCDIR) -w "$(CXX)" "$(NXWIDGETS_INC)"} diff --git a/NxWidgets/libnxwidgets/Makefile b/NxWidgets/libnxwidgets/Makefile index 4673c1f98e..880117a247 100644 --- a/NxWidgets/libnxwidgets/Makefile +++ b/NxWidgets/libnxwidgets/Makefile @@ -33,7 +33,6 @@ # ################################################################################# --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs # Control build verbosity @@ -87,8 +86,8 @@ ifeq ($(WINTOOL),y) INCDIROPT = -w endif -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} -CXXFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} +CXXFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} DEPPATH = --dep-path src VPATH = src diff --git a/NxWidgets/nxwm/Makefile b/NxWidgets/nxwm/Makefile index 372f3c186d..81b9dcdeb8 100644 --- a/NxWidgets/nxwm/Makefile +++ b/NxWidgets/nxwm/Makefile @@ -33,7 +33,6 @@ # ################################################################################# --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs # Control build verbosity @@ -89,10 +88,10 @@ ifeq ($(WINTOOL),y) INCDIROPT = -w endif -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(NXWMDIR)/include} -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} -CXXFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(NXWMDIR)/include} -CXXFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWMDIR)/include} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} +CXXFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWMDIR)/include} +CXXFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} DEPPATH = --dep-path src VPATH = src diff --git a/apps/interpreters/ficl/Makefile b/apps/interpreters/ficl/Makefile index e905b9eff8..550c2fd2d7 100644 --- a/apps/interpreters/ficl/Makefile +++ b/apps/interpreters/ficl/Makefile @@ -35,14 +35,11 @@ BUILDDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs # Tools -INCDIR = $(TOPDIR)/tools/incdir.sh - ifeq ($(WINTOOL),y) INCDIROPT = -w endif diff --git a/apps/modbus/ascii/Make.defs b/apps/modbus/ascii/Make.defs index 3e99672831..d4cb38f976 100644 --- a/apps/modbus/ascii/Make.defs +++ b/apps/modbus/ascii/Make.defs @@ -39,6 +39,6 @@ CSRCS += mbascii.c DEPPATH += --dep-path ascii VPATH += :ascii -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(APPDIR)/modbus/ascii} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(APPDIR)/modbus/ascii} endif diff --git a/apps/modbus/functions/Make.defs b/apps/modbus/functions/Make.defs index 48f60d5060..ba4a243c14 100644 --- a/apps/modbus/functions/Make.defs +++ b/apps/modbus/functions/Make.defs @@ -38,4 +38,4 @@ CSRCS += mbfuncinput.c mbfuncother.c mbutils.c DEPPATH += --dep-path functions VPATH += :functions -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(APPDIR)/modbus/functions} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(APPDIR)/modbus/functions} diff --git a/apps/modbus/nuttx/Make.defs b/apps/modbus/nuttx/Make.defs index 96484217b3..3990ccd979 100644 --- a/apps/modbus/nuttx/Make.defs +++ b/apps/modbus/nuttx/Make.defs @@ -37,4 +37,4 @@ CSRCS += portevent.c portother.c portserial.c porttimer.c DEPPATH += --dep-path nuttx VPATH += :nuttx -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(APPDIR)/modbus/nuttx} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(APPDIR)/modbus/nuttx} diff --git a/apps/modbus/rtu/Make.defs b/apps/modbus/rtu/Make.defs index 8b9c68c770..d9e3b29c08 100644 --- a/apps/modbus/rtu/Make.defs +++ b/apps/modbus/rtu/Make.defs @@ -39,6 +39,6 @@ CSRCS += mbcrc.c mbrtu.c DEPPATH += --dep-path rtu VPATH += :rtu -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(APPDIR)/modbus/rtu} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(APPDIR)/modbus/rtu} endif diff --git a/apps/modbus/tcp/Make.defs b/apps/modbus/tcp/Make.defs index 30860be3a2..4cd2adb751 100644 --- a/apps/modbus/tcp/Make.defs +++ b/apps/modbus/tcp/Make.defs @@ -39,6 +39,6 @@ CSRCS += mbtcp.c DEPPATH += --dep-path tcp VPATH += :tcp -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(APPDIR)/modbus/tcp} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(APPDIR)/modbus/tcp} endif diff --git a/apps/netutils/thttpd/cgi-src/Makefile b/apps/netutils/thttpd/cgi-src/Makefile index 60efb08e7b..bb8e364573 100644 --- a/apps/netutils/thttpd/cgi-src/Makefile +++ b/apps/netutils/thttpd/cgi-src/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/netutils/cgi-src/Makefile # -# Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. +# Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -40,7 +40,7 @@ ifeq ($(WINTOOL),y) INCDIROPT = -w endif -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" "$(APPDIR)/netutils/thttpd" "$(APPDIR)/netutils/thttpd/cgi-src"} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" "$(APPDIR)/netutils/thttpd" "$(APPDIR)/netutils/thttpd/cgi-src"} CGIBINDIR = $(APPDIR)/netutils/thttpd/cgi-bin CLEANFILES = *.o redirect ssi phf diff --git a/misc/pascal/nuttx/Makefile b/misc/pascal/nuttx/Makefile index af4e4d412b..939c9322de 100644 --- a/misc/pascal/nuttx/Makefile +++ b/misc/pascal/nuttx/Makefile @@ -35,7 +35,6 @@ PCODEDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -45,7 +44,6 @@ ifeq ($(DIRLINK),) DIRLINK = $(TOPDIR)/tools/link.sh DIRUNLINK = $(TOPDIR)/tools/unlink.sh endif -INCDIR = $(TOPDIR)/tools/incdir.sh ifeq ($(WINTOOL),y) INCDIROPT = -w diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 0f92fdf7af..31700214f4 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3613,3 +3613,6 @@ critical CFLAG values that cannot be passed on the CMD.exe command line (line '='). mkdeps.c is a work in progress that will, hopefully, replace both mkdeps.sh and mkdeps.bat. + * tools/Config.mk: Centralize the definition of the scrpt that will be + used to generated header file include paths for the compiler. This + needs to be centralized in order to support the Windows native build. diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile index 365997be8b..378a737f60 100644 --- a/nuttx/binfmt/Makefile +++ b/nuttx/binfmt/Makefile @@ -38,7 +38,7 @@ ifeq ($(WINTOOL),y) INCDIROPT = -w endif -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/sched} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/sched} # Basic BINFMT source files diff --git a/nuttx/configs/stm32f4discovery/winbuild/Make.defs b/nuttx/configs/stm32f4discovery/winbuild/Make.defs index 75051da515..28cf8a5619 100644 --- a/nuttx/configs/stm32f4discovery/winbuild/Make.defs +++ b/nuttx/configs/stm32f4discovery/winbuild/Make.defs @@ -130,7 +130,7 @@ ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif -HOSTCC = mingw-gcc.exe +HOSTCC = mingw32-gcc.exe HOSTINCLUDES = -I. HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe HOSTLDFLAGS = diff --git a/nuttx/drivers/analog/Make.defs b/nuttx/drivers/analog/Make.defs index d94e397587..425193f7e5 100644 --- a/nuttx/drivers/analog/Make.defs +++ b/nuttx/drivers/analog/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/analog/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 @@ -76,12 +76,12 @@ endif ifeq ($(CONFIG_DAC),y) DEPPATH += --dep-path analog VPATH += :analog - CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/analog} + CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/analog} else ifeq ($(CONFIG_ADC),y) DEPPATH += --dep-path analog VPATH += :analog - CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/analog} + CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/analog} endif endif diff --git a/nuttx/drivers/bch/Make.defs b/nuttx/drivers/bch/Make.defs index bc22df8e26..2745fcfff0 100644 --- a/nuttx/drivers/bch/Make.defs +++ b/nuttx/drivers/bch/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/bch/Make.defs # -# Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved. +# Copyright (C) 2008, 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -46,7 +46,7 @@ CSRCS += bchlib_setup.c bchlib_teardown.c bchlib_read.c bchlib_write.c \ DEPPATH += --dep-path bch VPATH += :bch -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/bch} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/bch} endif endif diff --git a/nuttx/drivers/input/Make.defs b/nuttx/drivers/input/Make.defs index 8b009760c4..8afd76f89e 100644 --- a/nuttx/drivers/input/Make.defs +++ b/nuttx/drivers/input/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/input/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 @@ -71,6 +71,6 @@ endif DEPPATH += --dep-path input VPATH += :input -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/input} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/input} endif diff --git a/nuttx/drivers/lcd/Make.defs b/nuttx/drivers/lcd/Make.defs index 575751d393..8b6d300523 100644 --- a/nuttx/drivers/lcd/Make.defs +++ b/nuttx/drivers/lcd/Make.defs @@ -67,6 +67,6 @@ endif DEPPATH += --dep-path lcd VPATH += :lcd -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/lcd} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/lcd} endif diff --git a/nuttx/drivers/mmcsd/Make.defs b/nuttx/drivers/mmcsd/Make.defs index 410da741b6..0ba5efb7f1 100644 --- a/nuttx/drivers/mmcsd/Make.defs +++ b/nuttx/drivers/mmcsd/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/mmcsd/Make.defs # -# Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved. +# Copyright (C) 2008, 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -49,7 +49,7 @@ endif DEPPATH += --dep-path mmcsd VPATH += :mmcsd -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/mmcsd} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/mmcsd} endif diff --git a/nuttx/drivers/power/Make.defs b/nuttx/drivers/power/Make.defs index 45c6aebc32..9e6307ae21 100644 --- a/nuttx/drivers/power/Make.defs +++ b/nuttx/drivers/power/Make.defs @@ -47,7 +47,7 @@ CSRCS += pm_activity.c pm_changestate.c pm_checkstate.c pm_initialize.c pm_regis POWER_DEPPATH := --dep-path power POWER_VPATH := :power -POWER_CFLAGS := ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power} +POWER_CFLAGS := ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power} endif @@ -73,7 +73,7 @@ endif POWER_DEPPATH := --dep-path power POWER_VPATH := :power -POWER_CFLAGS := ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power} +POWER_CFLAGS := ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power} endif diff --git a/nuttx/drivers/sensors/Make.defs b/nuttx/drivers/sensors/Make.defs index 866ccb0536..17750831ec 100644 --- a/nuttx/drivers/sensors/Make.defs +++ b/nuttx/drivers/sensors/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/sensors/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 @@ -57,4 +57,4 @@ endif DEPPATH += --dep-path sensors VPATH += :sensors -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/sensors} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/sensors} diff --git a/nuttx/drivers/usbdev/Make.defs b/nuttx/drivers/usbdev/Make.defs index f1b3c405ae..782c185452 100644 --- a/nuttx/drivers/usbdev/Make.defs +++ b/nuttx/drivers/usbdev/Make.defs @@ -59,5 +59,5 @@ CSRCS += usbdev_trace.c usbdev_trprintf.c DEPPATH += --dep-path usbdev VPATH += :usbdev -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbdev} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbdev} endif diff --git a/nuttx/drivers/usbhost/Make.defs b/nuttx/drivers/usbhost/Make.defs index fd54ab53e7..91753ef318 100644 --- a/nuttx/drivers/usbhost/Make.defs +++ b/nuttx/drivers/usbhost/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/usbhost/Make.defs # -# Copyright (C) 2010-2011 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 @@ -54,4 +54,4 @@ endif DEPPATH += --dep-path usbhost VPATH += :usbhost -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbhost} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbhost} diff --git a/nuttx/drivers/wireless/Make.defs b/nuttx/drivers/wireless/Make.defs index f47f7666a5..86ea90e25e 100644 --- a/nuttx/drivers/wireless/Make.defs +++ b/nuttx/drivers/wireless/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/wireless/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 @@ -43,5 +43,5 @@ CSRCS += cc1101.c ISM1_868MHzGFSK100kbps.c ISM2_905MHzGFSK250kbps.c DEPPATH += --dep-path wireless/cc1101 VPATH += :wireless/cc1101 -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/wireless/cc1101} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/wireless/cc1101} endif diff --git a/nuttx/graphics/Makefile b/nuttx/graphics/Makefile index f638587baf..09d7cfa266 100644 --- a/nuttx/graphics/Makefile +++ b/nuttx/graphics/Makefile @@ -44,34 +44,34 @@ endif include nxglib/Make.defs DEPPATH += --dep-path nxglib -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxglib} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxglib} include nxbe/Make.defs DEPPATH += --dep-path nxbe -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxbe} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxbe} ifeq ($(CONFIG_NX_MULTIUSER),y) include nxmu/Make.defs DEPPATH += --dep-path nxmu -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxmu} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxmu} else include nxsu/Make.defs DEPPATH += --dep-path nxsu -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxsu} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxsu} endif include nxtk/Make.defs DEPPATH += --dep-path nxtk -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxtk} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxtk} include nxfonts/Make.defs DEPPATH += --dep-path nxfonts -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxfonts} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxfonts} ifeq ($(CONFIG_NXCONSOLE),y) include nxconsole/Make.defs DEPPATH += --dep-path nxconsole -CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxconsole} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxconsole} endif ASRCS = $(NXGLIB_ASRCS) $(NXBE_ASRCS) $(NX_ASRCS) $(NXTK_ASRCS) $(NXFONTS_ASRCS) $(NXCON_ASRCS) diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk index 06a312fc50..3a0714c10a 100644 --- a/nuttx/tools/Config.mk +++ b/nuttx/tools/Config.mk @@ -4,6 +4,9 @@ # # Author: Richard Cochran # +# This file (along with $(TOPDIR)/.config) must be included by every +# configuration-specific Make.defs file. +# # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: @@ -40,28 +43,104 @@ CONFIG_ARCH := $(patsubst "%",%,$(strip $(CONFIG_ARCH))) CONFIG_ARCH_CHIP := $(patsubst "%",%,$(strip $(CONFIG_ARCH_CHIP))) CONFIG_ARCH_BOARD := $(patsubst "%",%,$(strip $(CONFIG_ARCH_BOARD))) -# Default build rules. +# INCDIR - Convert a list of directory paths to a list of compiler include +# directirves +# Example: CFFLAGS += ${shell $(INCDIR) [options] "compiler" "dir1" "dir2" "dir2" ...} +# +# Note that the compiler string and each directory path string must quoted if +# they contain spaces or any other characters that might get mangled by the +# shell +# +# Depends on this setting passed as a make commaond line definition from the +# toplevel Makefile: +# +# TOPDIR - The path to the the top level NuttX directory in the form +# appropriate for the current build environment +# +# Depends on this settings defined in board-specific defconfig file installed +# at $(TOPDIR)/.config: +# +# CONFIG_WINDOWS_NATIVE - Defined for a Windows native build + +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + INCDIR = "$(TOPDIR)\tools\incdir.bat" +else + INCDIR = "$(TOPDIR)/tools/incdir.sh" +endif + +# PREPROCESS - Default macro to run the C pre-processor +# Example: $(call PREPROCESS, in-file, out-file) +# +# Depends on these settings defined in board-specific Make.defs file +# installed at $(TOPDIR)/Make.defs: +# +# CPP - The command to invoke the C pre-processor +# CPPFLAGS - Options to pass to the C pre-processor define PREPROCESS @echo "CPP: $1->$2" $(Q) $(CPP) $(CPPFLAGS) $1 -o $2 endef +# COMPILE - Default macro to compile one C file +# Example: $(call COMPILE, in-file, out-file) +# +# Depends on these settings defined in board-specific Make.defs file +# installed at $(TOPDIR)/Make.defs: +# +# CC - The command to invoke the C compiler +# CFLAGS - Options to pass to the C compiler + define COMPILE @echo "CC: $1" $(Q) $(CC) -c $(CFLAGS) $1 -o $2 endef +# COMPILEXX - Default macro to compile one C++ file +# Example: $(call COMPILEXX, in-file, out-file) +# +# Depends on these settings defined in board-specific Make.defs file +# installed at $(TOPDIR)/Make.defs: +# +# CXX - The command to invoke the C++ compiler +# CXXFLAGS - Options to pass to the C++ compiler + define COMPILEXX @echo "CXX: $1" $(Q) $(CXX) -c $(CXXFLAGS) $1 -o $2 endef +# ASSEMBLE - Default macro to assemble one assembly language file +# Example: $(call ASSEMBLE, in-file, out-file) +# +# Depends on these settings defined in board-specific Make.defs file +# installed at $(TOPDIR)/Make.defs: +# +# CC - By default, the C compiler is used to compile assembly lagnuage +# files +# AFLAGS - Options to pass to the C+compiler + define ASSEMBLE @echo "AS: $1" $(Q) $(CC) -c $(AFLAGS) $1 -o $2 endef +# ARCHIVE - Add a list of files to an archive +# Example: $(call ARCHIVE, archive-file, "file1 file2 file3 ...") +# +# Note: The fileN strings may not contain spaces or characters that may be +# interpreted strangely by the shell +# +# Depends on these settings defined in board-specific Make.defs file +# installed at $(TOPDIR)/Make.defs: +# +# AR - The command to invoke the archiver (includes any options) +# +# Depends on this settings defined in board-specific defconfig file installed +# at $(TOPDIR)/.config: +# +# CONFIG_WINDOWS_NATIVE - Defined for a Windows native build + ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE @echo "AR: $2" diff --git a/nuttx/tools/Makefile.host b/nuttx/tools/Makefile.host index 882a3c0ae9..4786250088 100644 --- a/nuttx/tools/Makefile.host +++ b/nuttx/tools/Makefile.host @@ -37,6 +37,13 @@ TOPDIR ?= ${shell pwd}/.. -include $(TOPDIR)/Make.defs include ${TOPDIR}/tools/Config.mk +# strtok_r is used in some tools, but does not seem to be available in +# the MinGW environment. + +ifneq ($(CONFIG_WINDOWS_NATIVE),y) + HOSTCFLAGS += -D HAVE_STRTOK_C +endif + all: mkconfig$(HOSTEXEEXT) mkversion$(HOSTEXEEXT) mksyscall$(HOSTEXEEXT) bdf-converter$(HOSTEXEEXT) mksymtab$(HOSTEXEEXT) mkdeps$(HOSTEXEEXT) default: mkconfig$(HOSTEXEEXT) mksyscall$(HOSTEXEEXT) mkdeps$(HOSTEXEEXT) diff --git a/nuttx/tools/README.txt b/nuttx/tools/README.txt index 3c9730d001..38efc7a3f2 100644 --- a/nuttx/tools/README.txt +++ b/nuttx/tools/README.txt @@ -1,5 +1,5 @@ tools/README.txt -^^^^^^^^^^^^^^^^ +================ This README file addresses the contents of the NuttX tools/ directory. @@ -8,22 +8,38 @@ that are necessary parts of the the NuttX build system. These files include: README.txt +---------- - This file + This file! + +Config.mk +--------- + + This file contains common definitions used by many configureation files. + This file (along with /.config) must be included at the top of + each configuration-specific Make.defs file like: + + -include $(TOPDIR)/.config + include $(TOPDIR)/tools/Config.mk + + Subsequent logic within the configuration-specific Make.defs file may then + override these default definitions as necessary. configure.sh +------------ This is a bash script that is used to configure NuttX for a given target board. See configs/README.txt or Documentation/NuttxPortingGuide.html for a description of how to configure NuttX with this script. discover.py +----------- Example script for discovering devices in the local network. It is the counter part to apps/netutils/discover - mkconfig.c, cfgparser.c, and cfgparser.h +---------------------------------------- These are Cs file that are used to build mkconfig program. The mkconfig program is used during the initial NuttX build. @@ -38,11 +54,13 @@ mkconfig.c, cfgparser.c, and cfgparser.h NuttX configuration that can be included by C files. cmdconfig.c +----------- This C file can be used to build a utility for comparing two NuttX configuration files. mkexport.sh and Makefile.export +------------------------------- These implement part of the top-level Makefile's 'export' target. That target will bundle up all of the NuttX libraries, header files, and the @@ -51,6 +69,7 @@ mkexport.sh and Makefile.export options from the top-level Make.defs file. mkfsdata.pl +----------- This perl script is used to build the "fake" file system and CGI support as needed for the apps/netutils/webserver. It is currently used only @@ -61,6 +80,7 @@ mkfsdata.pl by Adam Dunkels. uIP has a license that is compatible with NuttX. mkversion.c, cfgparser.c, and cfgparser.h +----------------------------------------- This is C file that is used to build mkversion program. The mkversion program is used during the initial NuttX build. @@ -74,6 +94,7 @@ mkversion.c, cfgparser.c, and cfgparser.h version.h provides version information that can be included by C files. mksyscall.c, cvsparser.c, and cvsparser.h +----------------------------------------- This is a C file that is used to build mksyscall program. The mksyscall program is used during the initial NuttX build by the logic in the top- @@ -96,6 +117,7 @@ mksyscall.c, cvsparser.c, and cvsparser.h stub files as output. See syscall/README.txt for additonal information. mksymtab.c, cvsparser.c, and cvsparser.h +---------------------------------------- This is a C file that is used to build symbol tables from common-separated value (CSV) files. This tool is not used during the NuttX build, but @@ -116,10 +138,12 @@ mksymtab.c, cvsparser.c, and cvsparser.h ./mksymtab.exe tmp.csv tmp.c pic32mx +------- This directory contains build tools used only for PIC32MX platforms bdf-convert.c +------------- This C file is used to build the bdf-converter program. The bdf-converter program be used to convert fonts in Bitmap Distribution Format (BDF) @@ -255,6 +279,7 @@ bdf-convert.c }; Makefile.host +------------- This is the makefile that is used to make the mkconfig program from the mkconfig.c C file, the cmpconfig program from cmpconfig.c C file @@ -265,6 +290,7 @@ Makefile.host make -f Makefile.host mkromfsimg.sh +------------- This script may be used to automate the generate of a ROMFS file system image. It accepts an rcS script "template" and generates and image that @@ -274,6 +300,7 @@ mkdeps.sh mkdeps.bat mkdeps.c mknulldeps.sh +------------- NuttX uses the GCC compilers capabilities to create Makefile dependencies. The bash script mkdeps.sh is used to run GCC in order to create the @@ -317,6 +344,7 @@ mknulldeps.sh that mixed environment. define.sh +--------- Different compilers have different conventions for specifying pre- processor definitions on the compiler command line. This bash @@ -324,6 +352,7 @@ define.sh without concern for the particular compiler in use. incdir.sh +--------- Different compilers have different conventions for specifying lists of include file paths on the the compiler command line. This bash @@ -333,6 +362,7 @@ incdir.sh link.sh winlink.sh unlink.sh +---------- Different file system have different capabilities for symbolic links. Some windows file systems have no native support for symbolic links. @@ -365,16 +395,19 @@ unlink.sh tried that mkimage.sh +---------- The creates a downloadable image as needed with the rrload bootloader. indent.sh +--------- This script can be used to indent .c and .h files in a manner similar to my coding NuttX coding style. It doesn't do a really good job, however (see the comments at the top of the indent.sh file). zipme.sh +-------- I use this script to create the nuttx-xx.yy.tar.gz tarballs for release on SourceForge. It is handy because it also does the diff --git a/nuttx/tools/mkdeps.c b/nuttx/tools/mkdeps.c index a90595c980..c688b2b75f 100644 --- a/nuttx/tools/mkdeps.c +++ b/nuttx/tools/mkdeps.c @@ -87,6 +87,75 @@ static char *g_topdir = NULL; * Private Functions ****************************************************************************/ + /* MinGW does not seem to provide strtok_r */ + +#ifndef HAVE_STRTOK_R +static char *strtok_r(char *str, const char *delim, char **saveptr) +{ + char *pbegin; + char *pend = NULL; + + /* Decide if we are starting a new string or continuing from + * the point we left off. + */ + + if (str) + { + pbegin = str; + } + else if (saveptr && *saveptr) + { + pbegin = *saveptr; + } + else + { + return NULL; + } + + /* Find the beginning of the next token */ + + for (; + *pbegin && strchr(delim, *pbegin) != NULL; + pbegin++); + + /* If we are at the end of the string with nothing + * but delimiters found, then return NULL. + */ + + if (!*pbegin) + { + return NULL; + } + + /* Find the end of the token */ + + for (pend = pbegin + 1; + *pend && strchr(delim, *pend) == NULL; + pend++); + + /* pend either points to the end of the string or to + * the first delimiter after the string. + */ + + if (*pend) + { + /* Turn the delimiter into a null terminator */ + + *pend++ = '\0'; + } + + /* Save the pointer where we left off and return the + * beginning of the token. + */ + + if (saveptr) + { + *saveptr = pend; + } + return pbegin; +} +#endif + static void append(char **base, char *str) { char *oldbase; From 50d55efc797f123dd98c2775292beab2b4374fd7 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 13 Nov 2012 21:10:50 +0000 Subject: [PATCH 117/206] Add tools/incdir.bat; Rename top-level Makefile to Makefile.unix git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5347 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 7 ++ nuttx/{Makefile => Makefile.unix} | 2 +- nuttx/tools/README.txt | 9 ++- nuttx/tools/incdir.bat | 102 ++++++++++++++++++++++++++++++ nuttx/tools/incdir.sh | 2 + 5 files changed, 119 insertions(+), 3 deletions(-) rename nuttx/{Makefile => Makefile.unix} (99%) create mode 100755 nuttx/tools/incdir.bat diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 31700214f4..ce2db55b5f 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3616,3 +3616,10 @@ * tools/Config.mk: Centralize the definition of the scrpt that will be used to generated header file include paths for the compiler. This needs to be centralized in order to support the Windows native build. + * tools/incdir.bat: A replaced for tools/incdir.sh for use with the + the Windows native build. + * Makefile.unix: The existing top-level Makefile has been renamed + Makefile.unix. + * Makefile: This is a new top-level Makefile that just includes + either Makefile.unix or Makefile.win + diff --git a/nuttx/Makefile b/nuttx/Makefile.unix similarity index 99% rename from nuttx/Makefile rename to nuttx/Makefile.unix index adf0d1017d..ba0005771c 100644 --- a/nuttx/Makefile +++ b/nuttx/Makefile.unix @@ -1,5 +1,5 @@ ############################################################################ -# Makefile +# Makefile.unix # # Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt diff --git a/nuttx/tools/README.txt b/nuttx/tools/README.txt index 38efc7a3f2..dd971fadc5 100644 --- a/nuttx/tools/README.txt +++ b/nuttx/tools/README.txt @@ -352,13 +352,18 @@ define.sh without concern for the particular compiler in use. incdir.sh +incdir.bat --------- Different compilers have different conventions for specifying lists - of include file paths on the the compiler command line. This bash - script allows the build system to create include file paths without + of include file paths on the the compiler command line. This incdir.sh + bash script allows the build system to create include file paths without concern for the particular compiler in use. + The incdir.bat script is a counterpart for use in the native Windows + build. However, their is currently only one compiler supported in + that context: MinGW-GCC. + link.sh winlink.sh unlink.sh diff --git a/nuttx/tools/incdir.bat b/nuttx/tools/incdir.bat new file mode 100755 index 0000000000..a53afdd475 --- /dev/null +++ b/nuttx/tools/incdir.bat @@ -0,0 +1,102 @@ +@echo off + +rem tools/incdir.sh +rem +rem Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved. +rem Author: Gregory Nutt +rem +rem Redistribution and use in source and binary forms, with or without +rem modification, are permitted provided that the following conditions +rem are met: +rem +rem 1. Redistributions of source code must retain the above copyright +rem notice, this list of conditions and the following disclaimer. +rem 2. Redistributions in binary form must reproduce the above copyright +rem notice, this list of conditions and the following disclaimer in +rem the documentation and/or other materials provided with the +rem distribution. +rem 3. Neither the name NuttX nor the names of its contributors may be +rem used to endorse or promote products derived from this software +rem without specific prior written permission. +rem +rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +rem POSSIBILITY OF SUCH DAMAGE. +rem + +rem Handle command line options + +set progname=%0 + +:ArgLoop + +rem [-d] [-w] [-h]. [-w] and [-d] Ignored for compatibility with incdir.sh + +if "%1"=="-d" goto :NextArg +if "%1"=="-w" goto :NextArg +if "%1"=="-h" goto :Usage +goto :CheckCompiler + +:NextArg +shift +goto :ArgLoop + +:CheckCompiler +if "%1"=="" ( + echo ERROR: Missing compiler name + goto :Usage +) +shift + +rem Generate the compiler include path directives. Easy since only MinGW is +rem supported + +if "%1"=="" ( + echo ERROR: Missing directory paths + goto :Usage +) + +set response= + +:DirLoop +if "%1" == "" ( + echo %response% + goto :End +) + +if not exist %1 ( + echo ERROR: Path %1 does not exist + goto :Usage +) + +if "%response"=="" ( + set response=-I "%1" +) else ( + set response=%response% -I "%1" +) +shift +goto :DirLoop + +:Usage +echo %progname% is a tool for flexible generation of include path arguments for a +echo variety of different compilers in a variety of compilation environments +echo USAGE: %progname% [-w] [-d] [-h] ^ ^ [^ [^ ...]] +echo Where: +echo ^ +echo The full path to your compiler +echo ^ [^ [^ ...]] +echo A list of include directories +echo -w, -d +echo For compatibility with incdir.sh (ignored) +echo -h +echo Shows this help text and exits. +:End diff --git a/nuttx/tools/incdir.sh b/nuttx/tools/incdir.sh index be6a1d07a7..181fb1fa29 100755 --- a/nuttx/tools/incdir.sh +++ b/nuttx/tools/incdir.sh @@ -63,6 +63,8 @@ while [ ! -z "$1" ]; do echo " style pathnames like C:\\Program Files" echo " -d" echo " Enable script debug" + echo " -h" + echo " Shows this help text and exits." ;; * ) break; From 2e8ca5cb32832814aee9440b66d806568a07e6c3 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 13 Nov 2012 21:19:19 +0000 Subject: [PATCH 118/206] This is the new, top-level, redirecting Makefile git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5348 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Makefile | 49 +++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 49 insertions(+) create mode 100644 nuttx/Makefile diff --git a/nuttx/Makefile b/nuttx/Makefile new file mode 100644 index 0000000000..cf7a57c83d --- /dev/null +++ b/nuttx/Makefile @@ -0,0 +1,49 @@ +############################################################################ +# Makefile +# +# 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. +# +############################################################################ + +# This is a top-level "kludge" Makefile that just includes the correct +# Makefile. If you already know the Makefile that you want, you can skip +# this nonsense using: +# +# make -f Makefile.unix, OR +# make -f Makefile.win +# + +-include .config +ifeq ($(CONFIG_WINDOWS_NATIVE),y) +include Makefile.win +else +include Makefile.unix +endif From 693a7083aeb1f2b91ac046843f02017a18592d61 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 13 Nov 2012 22:47:44 +0000 Subject: [PATCH 119/206] mkdeps.c: Fix some strtok logic; fix some system() return value check git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5349 42af7a65-404d-4744-a932-0658087f49c3 --- .../stm32f4discovery/winbuild/Make.defs | 2 +- nuttx/tools/mkdeps.c | 112 ++++++++++++------ 2 files changed, 78 insertions(+), 36 deletions(-) diff --git a/nuttx/configs/stm32f4discovery/winbuild/Make.defs b/nuttx/configs/stm32f4discovery/winbuild/Make.defs index 28cf8a5619..54b6c03ea6 100644 --- a/nuttx/configs/stm32f4discovery/winbuild/Make.defs +++ b/nuttx/configs/stm32f4discovery/winbuild/Make.defs @@ -138,5 +138,5 @@ HOSTEXEEXT = .exe # Windows-native host tools -MKDEP = $(TOPDIR)/tools/mkdeps.exe +MKDEP = $(TOPDIR)/tools/mkdeps.exe --winnative diff --git a/nuttx/tools/mkdeps.c b/nuttx/tools/mkdeps.c index c688b2b75f..5bf8932e72 100644 --- a/nuttx/tools/mkdeps.c +++ b/nuttx/tools/mkdeps.c @@ -51,11 +51,7 @@ * Pre-processor Definitions ****************************************************************************/ -#define MAX_COMMAND 256 -#ifndef MAX_PATH -# define MAX_PATH 4096 -#endif -#define MAX_BUFFER (MAX_COMMAND + MAX_PATH + 2) +#define MAX_BUFFER (4096) /**************************************************************************** * Private Types @@ -83,6 +79,8 @@ static bool g_winpath = false; static char *g_topdir = NULL; #endif +static char g_command[MAX_BUFFER]; + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -90,7 +88,7 @@ static char *g_topdir = NULL; /* MinGW does not seem to provide strtok_r */ #ifndef HAVE_STRTOK_R -static char *strtok_r(char *str, const char *delim, char **saveptr) +static char *MY_strtok_r(char *str, const char *delim, char **saveptr) { char *pbegin; char *pend = NULL; @@ -154,6 +152,8 @@ static char *strtok_r(char *str, const char *delim, char **saveptr) } return pbegin; } + +#define strtok_r MY_strtok_r #endif static void append(char **base, char *str) @@ -198,7 +198,8 @@ static void show_usage(const char *progname, const char *msg, int exitcode) } fprintf(stderr, "\n"); - fprintf(stderr, "%s [OPTIONS] CC -- CFLAGS -- file [file [file...]]\n", progname); + fprintf(stderr, "%s [OPTIONS] CC -- CFLAGS -- file [file [file...]]\n", + progname); fprintf(stderr, "\n"); fprintf(stderr, "Where:\n"); fprintf(stderr, " CC\n"); @@ -353,8 +354,8 @@ static void parse_args(int argc, char **argv) static void do_dependency(const char *file, char separator) { static const char moption[] = " -M "; - char command[MAX_BUFFER]; struct stat buf; + char *alloc; char *altpath; char *path; char *lasts; @@ -369,45 +370,60 @@ static void do_dependency(const char *file, char separator) cmdlen = strlen(g_cc); if (cmdlen >= MAX_BUFFER) { - fprintf(stderr, "ERROR: Compiler string is too long: %s\n", g_cc); + fprintf(stderr, "ERROR: Compiler string is too long [%d/%d]: %s\n", + cmdlen, MAX_BUFFER, g_cc); exit(EXIT_FAILURE); } - strcpy(command, g_cc); + strcpy(g_command, g_cc); /* Copy " -M " */ cmdlen += strlen(moption); if (cmdlen >= MAX_BUFFER) { - fprintf(stderr, "ERROR: Option string is too long: %s\n", moption); + fprintf(stderr, "ERROR: Option string is too long [%d/%d]: %s\n", + cmdlen, MAX_BUFFER, moption); exit(EXIT_FAILURE); } - strcat(command, moption); + strcat(g_command, moption); /* Copy the CFLAGS into the command buffer */ cmdlen += strlen(g_cflags); if (cmdlen >= MAX_BUFFER) { - fprintf(stderr, "ERROR: CFLAG string is too long: %s\n", g_cflags); + fprintf(stderr, "ERROR: CFLAG string is too long [%d/%d]: %s\n", + cmdlen, MAX_BUFFER, g_cflags); exit(EXIT_FAILURE); } - strcat(command, g_cflags); + strcat(g_command, g_cflags); /* Add a space */ - command[cmdlen] = ' '; + g_command[cmdlen] = ' '; cmdlen++; - command[cmdlen] = '\0'; + g_command[cmdlen] = '\0'; + + /* Make a copy of g_altpath. We need to do this because at least the version + * of strtok_r above does modifie it. + */ + + alloc = strdup(g_altpath); + if (!alloc) + { + fprintf(stderr, "ERROR: Failed to strdup paths\n"); + exit(EXIT_FAILURE); + } + + altpath = alloc; /* Try each path. This loop will continue until each path has been tried * (failure) or until stat() finds the file */ - altpath = g_altpath; while ((path = strtok_r(altpath, " ", &lasts)) != NULL) { /* Create a full path to the file */ @@ -416,22 +432,23 @@ static void do_dependency(const char *file, char separator) totallen = cmdlen + pathlen; if (totallen >= MAX_BUFFER) { - fprintf(stderr, "ERROR: Path is too long: %s\n", path); + fprintf(stderr, "ERROR: Path is too long [%d/%d]: %s\n", + totallen, MAX_BUFFER, path); exit(EXIT_FAILURE); } - strcpy(&command[cmdlen], path); + strcpy(&g_command[cmdlen], path); - if (command[totallen] != '\0') + if (g_command[totallen] != '\0') { fprintf(stderr, "ERROR: Missing NUL terminator\n"); exit(EXIT_FAILURE); } - if (command[totallen-1] != separator) + if (g_command[totallen-1] != separator) { - command[totallen] = separator; - command[totallen+1] = '\0'; + g_command[totallen] = separator; + g_command[totallen+1] = '\0'; pathlen++; totallen++; } @@ -440,15 +457,22 @@ static void do_dependency(const char *file, char separator) totallen += filelen; if (totallen >= MAX_BUFFER) { - fprintf(stderr, "ERROR: Path+file is too long\n"); + fprintf(stderr, "ERROR: Path+file is too long [%d/%d]\n", + totallen, MAX_BUFFER); exit(EXIT_FAILURE); } - strcat(command, file); + strcat(g_command, file); /* Check that a file actually exists at this path */ - ret = stat(&command[cmdlen], &buf); + if (g_debug) + { + fprintf(stderr, "Trying path=%s file=%s fullpath=%s\n", + path, file, &g_command[cmdlen]); + } + + ret = stat(&g_command[cmdlen], &buf); if (ret < 0) { altpath = NULL; @@ -457,26 +481,39 @@ static void do_dependency(const char *file, char separator) if (!S_ISREG(buf.st_mode)) { - fprintf(stderr, "ERROR: File %s exists but is not a regular file\n", &command[cmdlen]); + fprintf(stderr, "ERROR: File %s exists but is not a regular file\n", + &g_command[cmdlen]); exit(EXIT_FAILURE); } - /* Okay.. we have. Create the dependency */ + /* Okay.. we have. Create the dependency. One a failure to start the + * compiler, system() will return -1; Otherwise, the returned value + * from the compiler is in WEXITSTATUS(ret). + */ - ret = system(command); - if (ret != 0) + ret = system(g_command); + if (ret < 0 || WEXITSTATUS(ret) != 0) { - fprintf(stderr, "ERROR: system failed: %s\n", strerror(errno)); - fprintf(stderr, " command: %s\n", command); + if (ret < 0) + { + fprintf(stderr, "ERROR: system failed: %s\n", strerror(errno)); + } + else + { + fprintf(stderr, "ERROR: %s failed: %s\n", g_cc, WEXITSTATUS(ret)); + } + + fprintf(stderr, " command: %s\n", g_command); exit(EXIT_FAILURE); } /* We don't really know that the command succeeded... Let's assume that it did */ + free(alloc); return; } - printf("# ERROR: No readable file for \"%s\" found at any location\n", file); + printf("# ERROR: File \"%s\" not found at any location\n", file); exit(EXIT_FAILURE); } @@ -577,7 +614,9 @@ static char *cywin2windows(const char *str, const char *append, enum slashmode_e *dest++ = ':'; } - /* Copy each character from the source, making modifications for foward slashes as required */ + /* Copy each character from the source, making modifications for foward + * slashes as required. + */ lastchar = '\0'; for (; *src; src++) @@ -643,7 +682,10 @@ int main(int argc, char **argv, char **envp) parse_args(argc, argv); - /* Then generate dependencies for each path on the command line */ + /* Then generate dependencies for each path on the command line. NOTE + * strtok_r will clobber the files list. But that is okay because we are + * only going to traverse it once. + */ files = g_files; while ((file = strtok_r(files, " ", &lasts)) != NULL) From 372c7ce012a663ed30cfcc7c6920691c42f4aa14 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 13 Nov 2012 23:05:48 +0000 Subject: [PATCH 120/206] mkdeps.c: Oops MinGW does not have WEXITSTATUS; Now all of NuttX on native Windows WITH dependencies (still some link time problems). git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5350 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/README.txt | 67 ++++++++++++++++++++++++++++++++++++++++++++ nuttx/tools/mkdeps.c | 9 ++++++ 2 files changed, 76 insertions(+) diff --git a/nuttx/README.txt b/nuttx/README.txt index ae0a4a023d..a133f209a6 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -19,6 +19,7 @@ README - Re-building - Build Targets and Options - Native Windows Build + - Installing GNUWin32 o Cygwin Build Problems - Strange Path Problems - Window Native Toolchain Issues @@ -523,6 +524,72 @@ Native Windows Build http://www.mingw.org/. If you are using GNUWin32, then it is recommended the you not install the optional MSYS components as there may be conflicts. +Installing GNUWin32 +------------------- + +The Windows native build will depend upon a few Unix-like tools that can be +provided either by MSYS or GNUWin32. The GNUWin32 are available from +http://gnuwin32.sourceforge.net/. GNUWin32 provides ports of tools with a +GPL or similar open source license to modern MS-Windows (Microsoft Windows +2000 / XP / 2003 / Vista / 2008 / 7). See +http://gnuwin32.sourceforge.net/packages.html for a list of all of the tools +available in the GNUWin32 package. + +The SourceForge project is located here: +http://sourceforge.net/projects/gnuwin32/. The project is still being +actively supported (although some of the Windows ports have gotten very old). + +Some commercial toolchains include a subset of the GNUWin32 tools in the +installation. My recommendation is that you download the GNUWin32 tools +directly from the sourceforge.net website so that you will know what you are +using and can reproduce your build environment. + +GNUWin32 Installation Steps: + +The following steps will download and execute the GNUWin32 installer. + +1. Download GetGNUWin32-x.x.x.exe from + http://sourceforge.net/projects/getgnuwin32/files/. This is the + installer. The current version as of this writing is 0.6.3. + +2. Run the installer. + +3. Accept the license. + +4. Select the installation directory. My recommendation is the + directory that contains this README file (). + +5. After running GetGNUWin32-0.x.x.exe, you will have a new directory + /GetGNUWin32 + +Note the the GNUWin32 installer didn't install GNUWin32. Instead, it +installed another, smarter downloader. That downloader is the GNUWin32 +package management tool developed by the Open SSL project. + +The following steps probably should be performed from inside a DOS shell. + +6. Change to the directory created by GetGNUWin32-x.x.x.exe + + cd GetGNUWin32 + +7. Execute the download.bat script. The download.bat script will download + about 446 packages! Enough to have a very complete Linux-like environment + under the DOS shell. This will take awhile. This step only downloads + the packages and the next step will install the packages. + + download + +8. This step will install the downloaded packages. The argument of the + install.bat script is the installation location. C:\gnuwin32 is the + standard install location: + + install C:\gnuwin32 + +NOTE: This installation step will install *all* GNUWin32 packages... far +more than you will ever need. If disc space is a problem for you, you might +need to perform a manual installation of the individual ZIP files that you +will find in the /GetGNUWin32/packages directory. + CYGWIN BUILD PROBLEMS ^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/tools/mkdeps.c b/nuttx/tools/mkdeps.c index 5bf8932e72..97934a2493 100644 --- a/nuttx/tools/mkdeps.c +++ b/nuttx/tools/mkdeps.c @@ -492,6 +492,7 @@ static void do_dependency(const char *file, char separator) */ ret = system(g_command); +#ifdef WEXITSTATUS if (ret < 0 || WEXITSTATUS(ret) != 0) { if (ret < 0) @@ -506,6 +507,14 @@ static void do_dependency(const char *file, char separator) fprintf(stderr, " command: %s\n", g_command); exit(EXIT_FAILURE); } +#else + if (ret < 0) + { + fprintf(stderr, "ERROR: system failed: %s\n", strerror(errno)); + fprintf(stderr, " command: %s\n", g_command); + exit(EXIT_FAILURE); + } +#endif /* We don't really know that the command succeeded... Let's assume that it did */ From 81caf90b8d140d580a969a07f0659a9a32f8624f Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 14 Nov 2012 14:29:01 +0000 Subject: [PATCH 121/206] ModBus fixes from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5351 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/Make.defs | 4 ++++ apps/modbus/mb.c | 4 +++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index 1c61513844..3d95ccb16d 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -106,6 +106,10 @@ ifeq ($(CONFIG_EXAMPLES_MM),y) CONFIGURED_APPS += examples/mm endif +ifeq ($(CONFIG_EXAMPLES_MODBUS),y) +CONFIGURED_APPS += examples/modbus +endif + ifeq ($(CONFIG_EXAMPLES_MOUNT),y) CONFIGURED_APPS += examples/mount endif diff --git a/apps/modbus/mb.c b/apps/modbus/mb.c index 209b1274ca..8417d12749 100644 --- a/apps/modbus/mb.c +++ b/apps/modbus/mb.c @@ -399,10 +399,12 @@ eMBPoll( void ) ucMBFrame[usLength++] = ( uint8_t )( ucFunctionCode | MB_FUNC_ERROR ); ucMBFrame[usLength++] = eException; } +#ifdef CONFIG_MB_ASCII_ENABLED if( ( eMBCurrentMode == MB_ASCII ) && CONFIG_MB_ASCII_TIMEOUT_WAIT_BEFORE_SEND_MS ) { vMBPortTimersDelay( CONFIG_MB_ASCII_TIMEOUT_WAIT_BEFORE_SEND_MS ); - } + } +#endif eStatus = peMBFrameSendCur( ucMBAddress, ucMBFrame, usLength ); } break; From 7213ccf4de665ee7f1cd215ebee3f85787b6cd5f Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 14 Nov 2012 15:55:07 +0000 Subject: [PATCH 122/206] More native build fixes -- still problems in apps/ directory git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5352 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Makefile.win | 16 ++++---- nuttx/arch/arm/src/Makefile | 41 ++++++++++++------- nuttx/arch/avr/src/Makefile | 25 +++++++---- nuttx/arch/hc/src/Makefile | 41 ++++++++++++------- nuttx/arch/mips/src/Makefile | 41 ++++++++++++------- nuttx/arch/sh/src/Makefile | 35 +++++++++++++--- nuttx/arch/x86/src/Makefile | 39 +++++++++++------- nuttx/arch/z16/src/Makefile | 2 +- nuttx/arch/z80/src/Makefile.zdsii | 2 +- .../stm32f4discovery/winbuild/Make.defs | 16 ++++---- 10 files changed, 167 insertions(+), 91 deletions(-) diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win index 5491851863..7da6e8e9ce 100644 --- a/nuttx/Makefile.win +++ b/nuttx/Makefile.win @@ -69,7 +69,7 @@ BOARD_DIR = configs\$(CONFIG_ARCH_BOARD) ifeq ($(CONFIG_APPS_DIR),) CONFIG_APPS_DIR = ..\apps endif -APPDIR := ${shell if [ -r $(CONFIG_APPS_DIR)\Makefile ]; then echo "$(CONFIG_APPS_DIR)"; fi} +APPDIR := ${shell if exist "$(CONFIG_APPS_DIR)\Makefile" echo "$(CONFIG_APPS_DIR)"} # All add-on directories. # @@ -245,7 +245,7 @@ endif # LINKLIBS derives from NUTTXLIBS and is simply the same list with the subdirectory removed -LINKLIBS = $(patsubst lib\%,%,$(NUTTXLIBS)) +LINKLIBS = $(patsubst lib\\%,%,$(NUTTXLIBS)) # This is the name of the final target (relative to the top level directorty) @@ -339,7 +339,7 @@ include\nuttx\config.h: $(TOPDIR)\.config tools\mkconfig$(HOSTEXEEXT) # Targets used to create dependencies -tools/mkdeps$(HOSTEXEEXT): +tools\mkdeps$(HOSTEXEEXT): $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkdeps$(HOSTEXEEXT) # dirlinks, and helpers @@ -348,7 +348,7 @@ tools/mkdeps$(HOSTEXEEXT): # setting up symbolic links with 'generic' directory names to specific, # configured directories. # -# Link the apps/include directory to include\apps +# Link the apps\include directory to include\apps include\apps: Make.defs ifneq ($(APPDIR),) @@ -640,10 +640,10 @@ download: $(BIN) # pass1dep: Create pass1 build dependencies # pass2dep: Create pass2 build dependencies -pass1dep: context tools/mkdeps$(HOSTEXEEXT) +pass1dep: context tools\mkdeps$(HOSTEXEEXT) $(Q) for %%G in ($(USERDEPDIRS)) do ( $(MAKE) -C %%G TOPDIR="$(TOPDIR)" depend ) -pass2dep: context tools/mkdeps$(HOSTEXEEXT) +pass2dep: context tools\mkdeps$(HOSTEXEEXT) $(Q) for %%G in ($(KERNDEPDIRS)) do ( $(MAKE) -C %%G TOPDIR="$(TOPDIR)" EXTRADEFINES=$(KDEFINE) depend ) # Configuration targets @@ -686,7 +686,7 @@ export: pass2deps depend: pass1dep pass2dep subdir_clean: - $(Q) for %%G in ($(CLEANDIRS)) do ( if exist %%G/Makefile $(MAKE) -C %%G TOPDIR="$(TOPDIR)" clean ) + $(Q) for %%G in ($(CLEANDIRS)) do ( if exist %%G\Makefile $(MAKE) -C %%G TOPDIR="$(TOPDIR)" clean ) $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" clean $(Q) $(MAKE) -C mm -f Makefile.test TOPDIR="$(TOPDIR)" clean ifeq ($(CONFIG_BUILD_2PASS),y) @@ -698,7 +698,7 @@ clean: subdir_clean $(Q) rm -f nuttx-export* subdir_distclean: - $(Q) for %%G in ($(CLEANDIRS)) do ( if exist %%G/Makefile $(MAKE) -C %%G TOPDIR="$(TOPDIR)" distclean ) + $(Q) for %%G in ($(CLEANDIRS)) do ( if exist %%G\Makefile $(MAKE) -C %%G TOPDIR="$(TOPDIR)" distclean ) distclean: clean subdir_distclean clean_context ifeq ($(CONFIG_BUILD_2PASS),y) diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index fb8d3932d6..17e30411e9 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -37,7 +37,6 @@ -include $(TOPDIR)/Make.defs -include chip/Make.defs -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(CONFIG_ARCH_CORTEXM3),y) # Cortex-M3 is ARMv7-M ARCH_SUBDIR = armv7-m else @@ -48,16 +47,28 @@ ARCH_SUBDIR = arm endif endif -ifeq ($(WINTOOL),y) - NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}" - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \ - -I "${shell cygpath -w $(TOPDIR)/sched}" +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + ARCH_SRCDIR = $(TOPDIR)\arch\$(CONFIG_ARCH)\src + NUTTX = "$(TOPDIR)\nuttx$(EXEEXT)" + CFLAGS += -I$(ARCH_SRCDIR)\chip + CFLAGS += -I$(ARCH_SRCDIR)\common + CFLAGS += -I$(ARCH_SRCDIR)\$(ARCH_SUBDIR) + CFLAGS += -I$(TOPDIR)\sched else - NUTTX = $(TOPDIR)/nuttx - CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \ - -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched + ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx$(EXEEXT)}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" + CFLAGS += -I "${shell cygpath -w $(TOPDIR)/sched}" +else + NUTTX = "$(TOPDIR)/nuttx$(EXEEXT)" + CFLAGS += -I$(ARCH_SRCDIR)/chip + CFLAGS += -I$(ARCH_SRCDIR)/common + CFLAGS += -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) + CFLAGS += -I$(TOPDIR)/sched +endif endif HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT)) @@ -78,14 +89,14 @@ EXTRA_LIBPATHS ?= LINKLIBS ?= ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")} - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}" + BOARDMAKE = $(if $(wildcard .\board\Makefile),y,) + LIBPATHS += -L"$(TOPDIR)\lib" ifeq ($(BOARDMAKE),y) - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}" + LIBPATHS += -L"$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board" endif else - BOARDMAKE = ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi} + BOARDMAKE = $(if $(wildcard ./board/Makefile),y,) ifeq ($(WINTOOL),y) LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}" @@ -127,7 +138,7 @@ libarch$(LIBEXT): $(OBJS) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) -nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT) +nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) $(Q) echo "LD: nuttx" $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) $(EXTRA_LIBPATHS) \ -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile index cd4e9012db..1d4fed3816 100644 --- a/nuttx/arch/avr/src/Makefile +++ b/nuttx/arch/avr/src/Makefile @@ -37,26 +37,35 @@ -include $(TOPDIR)/Make.defs -include chip/Make.defs -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(CONFIG_ARCH_AVR32),y) ARCH_SUBDIR = avr32 else ifeq ($(CONFIG_ARCH_AVR),y) ARCH_SUBDIR = avr endif +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + ARCH_SRCDIR = $(TOPDIR)\arch\$(CONFIG_ARCH)\src + NUTTX = "$(TOPDIR)\nuttx$(EXEEXT)" + INCLUDES += -I "$(ARCH_SRCDIR)\chip" + INCLUDES += -I "$(ARCH_SRCDIR)\common" + INCLUDES += -I "$(ARCH_SRCDIR)\$(ARCH_SUBDIR)" + INCLUDES += -I "$(TOPDIR)\sched" +else + ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(WINTOOL),y) - NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}" + NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx$(EXEEXT)}" INCLUDES += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" INCLUDES += -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" INCLUDES += -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" INCLUDES += -I "${shell cygpath -w $(TOPDIR)/sched}" else - NUTTX = "$(TOPDIR)/nuttx" + NUTTX = "$(TOPDIR)/nuttx$(EXEEXT)" INCLUDES += -I "$(ARCH_SRCDIR)/chip" INCLUDES += -I "$(ARCH_SRCDIR)/common" INCLUDES += -I "$(ARCH_SRCDIR)/$(ARCH_SUBDIR)" INCLUDES += -I "$(TOPDIR)/sched" endif +endif CPPFLAGS += $(INCLUDES) CFLAGS += $(INCLUDES) @@ -79,14 +88,14 @@ EXTRA_LIBS ?= LINKLIBS ?= ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")} - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}" + BOARDMAKE = $(if $(wildcard .\board\Makefile),y,) + LIBPATHS += -L"$(TOPDIR)\lib" ifeq ($(BOARDMAKE),y) - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}" + LIBPATHS += -L"$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board" endif else - BOARDMAKE = ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi} + BOARDMAKE = $(if $(wildcard ./board/Makefile),y,) ifeq ($(WINTOOL),y) LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}" @@ -127,7 +136,7 @@ libarch$(LIBEXT): $(OBJS) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) -nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT) +nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) @echo "LD: nuttx" $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile index 7a3e9d032a..60e6a863b2 100644 --- a/nuttx/arch/hc/src/Makefile +++ b/nuttx/arch/hc/src/Makefile @@ -36,7 +36,6 @@ -include $(TOPDIR)/Make.defs -include chip/Make.defs -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(CONFIG_ARCH_HC12),y) ARCH_SUBDIR = hc12 endif @@ -44,16 +43,28 @@ ifeq ($(CONFIG_ARCH_HCS12),y) ARCH_SUBDIR = hcs12 endif -ifeq ($(WINTOOL),y) - NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}" - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \ - -I "${shell cygpath -w $(TOPDIR)/sched}" +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + ARCH_SRCDIR = $(TOPDIR)\arch\$(CONFIG_ARCH)\src + NUTTX = "$(TOPDIR)\nuttx$(EXEEXT)" + CFLAGS += -I$(ARCH_SRCDIR)\chip + CFLAGS += -I$(ARCH_SRCDIR)\common + CFLAGS += -I$(ARCH_SRCDIR)\$(ARCH_SUBDIR) + CFLAGS += -I$(TOPDIR)\sched else - NUTTX = $(TOPDIR)/nuttx - CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \ - -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched + ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx$(EXEEXT)}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" + CFLAGS += -I "${shell cygpath -w $(TOPDIR)/sched}" +else + NUTTX = "$(TOPDIR)/nuttx$(EXEEXT)" + CFLAGS += -I$(ARCH_SRCDIR)/chip + CFLAGS += -I$(ARCH_SRCDIR)/common + CFLAGS += -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) + CFLAGS += -I$(TOPDIR)/sched +endif endif HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT)) @@ -72,14 +83,14 @@ EXTRA_LIBS ?= LINKLIBS ?= ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")} - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}" + BOARDMAKE = $(if $(wildcard .\board\Makefile),y,) + LIBPATHS += -L"$(TOPDIR)\lib" ifeq ($(BOARDMAKE),y) - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}" + LIBPATHS += -L"$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board" endif else - BOARDMAKE = ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi} + BOARDMAKE = $(if $(wildcard ./board/Makefile),y,) ifeq ($(WINTOOL),y) LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}" @@ -119,7 +130,7 @@ libarch$(LIBEXT): $(OBJS) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) -nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT) +nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) $(Q) echo "LD: nuttx" $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) \ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile index 8d02ac59c5..14388a90db 100644 --- a/nuttx/arch/mips/src/Makefile +++ b/nuttx/arch/mips/src/Makefile @@ -36,21 +36,32 @@ -include $(TOPDIR)/Make.defs -include chip/Make.defs -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(CONFIG_ARCH_MIPS),y) ARCH_SUBDIR = mips32 endif -ifeq ($(WINTOOL),y) - NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}" - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \ - -I "${shell cygpath -w $(TOPDIR)/sched}" +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + ARCH_SRCDIR = $(TOPDIR)\arch\$(CONFIG_ARCH)\src + NUTTX = $(TOPDIR)\nuttx$(EXEEXT) + CFLAGS += -I$(ARCH_SRCDIR)\chip + CFLAGS += -I$(ARCH_SRCDIR)\common + CFLAGS += -I$(ARCH_SRCDIR)\$(ARCH_SUBDIR) + CFLAGS += -I$(TOPDIR)\sched else - NUTTX = $(TOPDIR)/nuttx - CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \ - -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched + ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx$(EXEEXT)}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" + CFLAGS += -I "${shell cygpath -w $(TOPDIR)/sched}" +else + NUTTX = $(TOPDIR)/nuttx$(EXEEXT) + CFLAGS += -I$(ARCH_SRCDIR)/chip + CFLAGS += -I$(ARCH_SRCDIR)/common + CFLAGS += -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) + CFLAGS += -I$(TOPDIR)/sched +endif endif HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT)) @@ -69,14 +80,14 @@ EXTRA_LIBS ?= LINKLIBS ?= ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")} - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}" + BOARDMAKE = $(if $(wildcard .\board\Makefile),y,) + LIBPATHS += -L"$(TOPDIR)\lib" ifeq ($(BOARDMAKE),y) - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}" + LIBPATHS += -L"$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board" endif else - BOARDMAKE := ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi} + BOARDMAKE = $(if $(wildcard ./board/Makefile),y,) ifeq ($(WINTOOL),y) LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}" @@ -117,7 +128,7 @@ libarch$(LIBEXT): $(OBJS) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) -nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT) +nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) @echo "LD: nuttx" $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile index d6f3ed634e..9fa8ea4472 100644 --- a/nuttx/arch/sh/src/Makefile +++ b/nuttx/arch/sh/src/Makefile @@ -36,7 +36,30 @@ -include $(TOPDIR)/Make.defs -include chip/Make.defs -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + ARCH_SRCDIR = $(TOPDIR)\arch\$(CONFIG_ARCH)\src + NUTTX = $(TOPDIR)\nuttx$(EXEEXT) + CFLAGS += -I$(ARCH_SRCDIR)\chip + CFLAGS += -I$(ARCH_SRCDIR)\common + CFLAGS += -I$(ARCH_SRCDIR)\$(ARCH_SUBDIR) + CFLAGS += -I$(TOPDIR)\sched +else + ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx$(EXEEXT)}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" + CFLAGS += -I "${shell cygpath -w $(TOPDIR)/sched}" +else + NUTTX = $(TOPDIR)/nuttx$(EXEEXT) + CFLAGS += -I$(ARCH_SRCDIR)/chip + CFLAGS += -I$(ARCH_SRCDIR)/common + CFLAGS += -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) + CFLAGS += -I$(TOPDIR)/sched +endif +endif + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT)) @@ -55,14 +78,14 @@ EXTRA_LIBS ?= LINKLIBS ?= ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")} - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}" + BOARDMAKE = $(if $(wildcard .\board\Makefile),y,) + LIBPATHS += -L"$(TOPDIR)\lib" ifeq ($(BOARDMAKE),y) - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}" + LIBPATHS += -L"$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board" endif else - BOARDMAKE = ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi} + BOARDMAKE = $(if $(wildcard ./board/Makefile),y,) ifeq ($(WINTOOL),y) LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}" @@ -103,7 +126,7 @@ libarch$(LIBEXT): $(OBJS) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) -nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT) +nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) @echo "LD: nuttx" $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(TOPDIR)/$@ $(HEAD_OBJ) \ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile index 9e9abb9e2b..dc35d0db3d 100644 --- a/nuttx/arch/x86/src/Makefile +++ b/nuttx/arch/x86/src/Makefile @@ -36,21 +36,32 @@ -include $(TOPDIR)/Make.defs -include chip/Make.defs -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(CONFIG_ARCH_I486),y) ARCH_SUBDIR = i486 endif -ifeq ($(WINTOOL),y) - NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}" - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \ - -I "${shell cygpath -w $(TOPDIR)/sched}" +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + ARCH_SRCDIR = $(TOPDIR)\arch\$(CONFIG_ARCH)\src + NUTTX = $(TOPDIR)\nuttx$(EXEEXT) + CFLAGS += -I$(ARCH_SRCDIR)\chip + CFLAGS += -I$(ARCH_SRCDIR)\common + CFLAGS += -I$(ARCH_SRCDIR)\$(ARCH_SUBDIR) + CFLAGS += -I$(TOPDIR)\sched else - NUTTX = $(TOPDIR)/nuttx - CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \ - -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched + ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx$(EXEEXT)}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" + CFLAGS += -I "${shell cygpath -w $(TOPDIR)/sched}" +else + NUTTX = $(TOPDIR)/nuttx$(EXEEXT) + CFLAGS += -I$(ARCH_SRCDIR)/chip + CFLAGS += -I$(ARCH_SRCDIR)/common + CFLAGS += -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) + CFLAGS += -I$(TOPDIR)/sched +endif endif HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT)) @@ -69,14 +80,14 @@ EXTRA_LIBS ?= LINKLIBS ?= ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BOARDMAKE = ${shell if exist "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board\Makefile" (echo "y")} - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\lib"}" + BOARDMAKE = $(if $(wildcard .\board\Makefile),y,) + LIBPATHS += -L"$(TOPDIR)\lib" ifeq ($(BOARDMAKE),y) - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"}" + LIBPATHS += -L"$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board" endif else - BOARDMAKE = ${shell if [ -r "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board/Makefile" ]; then echo "y"; fi} + BOARDMAKE = $(if $(wildcard ./board/Makefile),y,) ifeq ($(WINTOOL),y) LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}" diff --git a/nuttx/arch/z16/src/Makefile b/nuttx/arch/z16/src/Makefile index f2d09e14fc..3e2f487ffa 100644 --- a/nuttx/arch/z16/src/Makefile +++ b/nuttx/arch/z16/src/Makefile @@ -109,7 +109,7 @@ nuttx.linkcmd: endif nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) nuttx.linkcmd - @echo "LD: nuttx.hex" + @echo "LD: nuttx$(EXEEXT)" @$(LD) $(LDFLAGS) .depend: Makefile chip/Make.defs $(DEPSRCS) diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii index 3a1727aef9..93d80d2ddb 100644 --- a/nuttx/arch/z80/src/Makefile.zdsii +++ b/nuttx/arch/z80/src/Makefile.zdsii @@ -122,7 +122,7 @@ ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y) endif nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) nuttx.linkcmd - @echo "LD: nuttx.hex" + @echo "LD: nuttx$(EXEEXT)" $(Q) "$(LD)" $(LDFLAGS) .depend: Makefile chip/Make.defs $(DEPSRCS) diff --git a/nuttx/configs/stm32f4discovery/winbuild/Make.defs b/nuttx/configs/stm32f4discovery/winbuild/Make.defs index 54b6c03ea6..6110b7bbd2 100644 --- a/nuttx/configs/stm32f4discovery/winbuild/Make.defs +++ b/nuttx/configs/stm32f4discovery/winbuild/Make.defs @@ -33,8 +33,8 @@ # ############################################################################ -include ${TOPDIR}/.config -include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}\.config +include ${TOPDIR}\tools\Config.mk # Setup for the selected toolchain @@ -81,9 +81,9 @@ LDSCRIPT = ld.script # Windows-native toolchains -ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx -ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +ARCHINCLUDES = -I. -isystem $(TOPDIR)\include +ARCHXXINCLUDES = -I. -isystem $(TOPDIR)\include -isystem $(TOPDIR)\include\cxx +ARCHSCRIPT = -T$(TOPDIR)\configs\$(CONFIG_ARCH_BOARD)\scripts\$(LDSCRIPT) CC = $(CROSSDEV)gcc.exe CXX = $(CROSSDEV)g++.exe @@ -118,12 +118,12 @@ 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-pcrel.ld -no-check-sections LDNXFLATFLAGS = -e main -s 2048 OBJEXT = .o LIBEXT = .a -EXEEXT = .exe +EXEEXT = LDFLAGS += -nostartfiles -nodefaultlibs ifeq ($(CONFIG_DEBUG_SYMBOLS),y) @@ -138,5 +138,5 @@ HOSTEXEEXT = .exe # Windows-native host tools -MKDEP = $(TOPDIR)/tools/mkdeps.exe --winnative +MKDEP = $(TOPDIR)\tools\mkdeps.exe --winnative From 21f348544f4fd3a9d51a8bfce08d2736eeb15d26 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 14 Nov 2012 17:04:03 +0000 Subject: [PATCH 123/206] Kconfig updates from Freddie Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5353 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/modbus/Kconfig | 40 ++++++++++++++++++++++++++++++++++++ nuttx/Kconfig | 3 ++- nuttx/arch/arm/src/Makefile | 1 - nuttx/arch/avr/src/Makefile | 1 - 4 files changed, 42 insertions(+), 3 deletions(-) diff --git a/apps/examples/modbus/Kconfig b/apps/examples/modbus/Kconfig index 4519ed2e37..7bc38bf9c3 100644 --- a/apps/examples/modbus/Kconfig +++ b/apps/examples/modbus/Kconfig @@ -10,4 +10,44 @@ config EXAMPLES_MODBUS Enable the FreeModBus example if EXAMPLES_MODBUS + +config EXAMPLES_MODBUS_PORT + int "Port used for MODBUS transmissions" + default 0 + ---help--- + Port used for MODBUS transmissions, default = 0 (i.e., /dev/ttyS0) + +config EXAMPLES_MODBUS_BAUD + int "MODBUS baudrate" + default 38400 + range 50 3000000 + ---help--- + MODBUS baudrate, allowed values {50, 75, 110, 134, 150, 200, 300, 600, + 1200, 1800, 2400, 4800, 9600, 19200, 38400, 57600, 115200, 128000, + 230400, 256000, 460800, 500000, 576000, 921600, 1000000, 1152000, + 1500000, 2000000, 2500000, 3000000} + +config EXAMPLES_MODBUS_PARITY + int "MODBUS parity" + default 2 + range 0 2 + ---help--- + MODBUS parity, 0 - none, 1 - odd, 2 - even + +config EXAMPLES_MODBUS_REG_INPUT_START + int "Input registers start address" + default 1000 + +config EXAMPLES_MODBUS_REG_INPUT_NREGS + int "Number of input registers" + default 4 + +config EXAMPLES_MODBUS_REG_HOLDING_START + int "Holding registers start address" + default 2000 + +config EXAMPLES_MODBUS_REG_HOLDING_NREGS + int "Number of holding registers" + default 130 + endif diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 239a791fa2..129a503673 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -87,7 +87,8 @@ menu "Build Configuration" config APPS_DIR string "Application directory" - default "../apps" + default "../apps" if !WINDOWS_NATIVE + default "..\apps" if WINDOWS_NATIVE ---help--- Identifies the directory that builds the application to link with NuttX. Default: ../apps This symbol must be assigned diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index 17e30411e9..be6b10af6b 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs -include chip/Make.defs diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile index 1d4fed3816..9b44c36976 100644 --- a/nuttx/arch/avr/src/Makefile +++ b/nuttx/arch/avr/src/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs -include chip/Make.defs From 2afceac48734c888931e4b824a62fcfd0e4f5ad8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 14 Nov 2012 19:26:13 +0000 Subject: [PATCH 124/206] Qencoder fixes from Ryan Sundberg git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5354 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 3 +++ nuttx/ChangeLog | 3 +++ nuttx/arch/arm/src/stm32/stm32_qencoder.c | 1 + nuttx/configs/stm3240g-eval/src/Makefile | 4 ++++ nuttx/tools/mkromfsimg.sh | 2 +- 5 files changed, 12 insertions(+), 1 deletion(-) diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 99f0ebc532..9040a7ec8d 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -414,4 +414,7 @@ * apps/nshlib/nsh_dbgcmds.c: Add hexdump command to dump the contents of a file (or character device) to the console Contributed by Petteri Aimonen. + * apps/examples/modbus: Fixes from Freddie Chopin + * apps/examples/modbus/Kconfig: Kconfig logic for FreeModBus contributed + by Freddie Chopin. diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index ce2db55b5f..5fa67d3fe7 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3622,4 +3622,7 @@ Makefile.unix. * Makefile: This is a new top-level Makefile that just includes either Makefile.unix or Makefile.win + * configs/stm3240g-eval/src: Qencoder fixes from Ryan Sundberg. + * arch/arm/src/stm32/stm32_qencoder.c: TIM3 bug fix from Ryan Sundberg. + * tools/mkromfsimg.sh: Correct typo in an error message (Ryan Sundberg) diff --git a/nuttx/arch/arm/src/stm32/stm32_qencoder.c b/nuttx/arch/arm/src/stm32/stm32_qencoder.c index 8553296f93..d37614c03c 100644 --- a/nuttx/arch/arm/src/stm32/stm32_qencoder.c +++ b/nuttx/arch/arm/src/stm32/stm32_qencoder.c @@ -607,6 +607,7 @@ static FAR struct stm32_lowerhalf_s *stm32_tim2lower(int tim) #endif #ifdef CONFIG_STM32_TIM3_QE case 3: + return &g_tim3lower; #endif #ifdef CONFIG_STM32_TIM4_QE case 4: diff --git a/nuttx/configs/stm3240g-eval/src/Makefile b/nuttx/configs/stm3240g-eval/src/Makefile index 7174fb1bc9..40c3b8769b 100644 --- a/nuttx/configs/stm3240g-eval/src/Makefile +++ b/nuttx/configs/stm3240g-eval/src/Makefile @@ -92,6 +92,10 @@ ifeq ($(CONFIG_INPUT_STMPE811),y) CSRCS += up_stmpe811.c endif +ifeq ($(CONFIG_QENCODER),y) +CSRCS += up_qencoder.c +endif + COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) diff --git a/nuttx/tools/mkromfsimg.sh b/nuttx/tools/mkromfsimg.sh index b774119800..8811f19536 100755 --- a/nuttx/tools/mkromfsimg.sh +++ b/nuttx/tools/mkromfsimg.sh @@ -233,7 +233,7 @@ mkdir -p $workingdir || { echo "Failed to created the new $workingdir"; exit 1; # Create the rcS file from the rcS.template if [ ! -r $rcstemplate ]; then - echo "$rcstemplete does not exist" + echo "$rcstemplate does not exist" rmdir $workingdir exit 1 fi From 5bba2c1508aa4e318de64cbaee58a12876745a97 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 14 Nov 2012 20:59:36 +0000 Subject: [PATCH 125/206] Simple window natives OS test build now works; Probabaly more to do for other configs; clean targets still have problems git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5355 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 3 +- apps/Makefile | 59 ++++++++++++++++++++++++++++-------- apps/examples/Makefile | 30 +++++++++--------- apps/graphics/Makefile | 30 +++++++++--------- apps/interpreters/Makefile | 24 +++++++-------- apps/netutils/Makefile | 24 +++++++-------- apps/system/Makefile | 25 ++++++++------- nuttx/ChangeLog | 3 ++ nuttx/Makefile.win | 10 ++---- nuttx/arch/arm/src/Makefile | 2 ++ nuttx/arch/avr/src/Makefile | 2 ++ nuttx/arch/hc/src/Makefile | 2 ++ nuttx/arch/mips/src/Makefile | 2 ++ nuttx/arch/sh/src/Makefile | 2 ++ nuttx/arch/x86/src/Makefile | 2 ++ 15 files changed, 129 insertions(+), 91 deletions(-) diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 9040a7ec8d..1a88900bed 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -417,4 +417,5 @@ * apps/examples/modbus: Fixes from Freddie Chopin * apps/examples/modbus/Kconfig: Kconfig logic for FreeModBus contributed by Freddie Chopin. - + * Makefile, */Makefile: Various fixes for Windows native build. Now uses + make foreach loops instead of shell loops. diff --git a/apps/Makefile b/apps/Makefile index 9bdafb1819..826694dad4 100644 --- a/apps/Makefile +++ b/apps/Makefile @@ -104,7 +104,7 @@ endif # Create the list of available applications (INSTALLED_APPS) define ADD_BUILTIN -INSTALLED_APPS += ${shell if [ -r $1/Makefile ]; then echo "$1"; fi} +INSTALLED_APPS += $(if $(wildcard $1\Makefile),$1,) endef $(foreach BUILTIN, $(CONFIGURED_APPS), $(eval $(call ADD_BUILTIN,$(BUILTIN)))) @@ -128,45 +128,78 @@ all: $(BIN) .PHONY: $(INSTALLED_APPS) context depend clean distclean $(INSTALLED_APPS): - @$(MAKE) -C $@ TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; + $(Q) $(MAKE) -C $@ TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" $(BIN): $(INSTALLED_APPS) .context: - @for dir in $(INSTALLED_APPS) ; do \ +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + $(Q) for %%G in ($(INSTALLED_APPS)) do ( \ + if exist %%G\.context del /f /q %%G\.context \ + $(MAKE) -C %%G TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" context \ + ) +else + $(Q) for dir in $(INSTALLED_APPS) ; do \ rm -f $$dir/.context ; \ - $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" context ; \ + $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" context ; \ done - @touch $@ +endif + $(Q) touch $@ context: .context .depend: context Makefile $(SRCS) - @for dir in $(INSTALLED_APPS) ; do \ +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + $(Q) for %%G in ($(INSTALLED_APPS)) do ( \ + if exist %%G\.depend del /f /q %%G\.depend \ + $(MAKE) -C %%G TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" depend \ + ) +else + $(Q) for dir in $(INSTALLED_APPS) ; do \ rm -f $$dir/.depend ; \ - $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" depend ; \ + $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" depend ; \ done - @touch $@ +endif + $(Q) touch $@ depend: .depend clean: - @for dir in $(SUBDIRS) ; do \ +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + $(Q) for %%G in ($(SUBDIRS)) do ( \ + $(MAKE) -C %%G clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" \ + ) + $(Q) rm -f $(BIN) *~ .*.swp *.o +else + $(Q) for dir in $(SUBDIRS) ; do \ $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ done - @rm -f $(BIN) *~ .*.swp *.o + $(Q) rm -f $(BIN) *~ .*.swp *.o +endif $(call CLEAN) distclean: # clean - @for dir in $(SUBDIRS) ; do \ +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + $(Q) for %%G in ($(SUBDIRS)) do ( \ + $(MAKE) -C %%G distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" \ + ) + $(Q) rm -f .config .context .depend + $(Q) ( if exist external ( \ + echo ********************************************************" \ + echo * The external directory/link must be removed manually *" \ + echo ********************************************************" \ + ) +else + $(Q) for dir in $(SUBDIRS) ; do \ $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ done - @rm -f .config .context .depend - @( if [ -e external ]; then \ + $(Q) rm -f .config .context .depend + $(Q) ( if [ -e external ]; then \ echo "********************************************************"; \ echo "* The external directory/link must be removed manually *"; \ echo "********************************************************"; \ fi; \ ) +endif diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 2ab3cf05c9..269d2b4643 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -102,27 +102,25 @@ all: nothing .PHONY: nothing context depend clean distclean +define SDIR_template +$(1)_$(2): + $(MAKE) -C $(1) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" +endef + +$(foreach SDIR, $(CNTXTDIRS), $(eval $(call SDIR_template,$(SDIR),context))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),depend))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),clean))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),disclean))) + nothing: -context: - @for dir in $(CNTXTDIRS) ; do \ - $(MAKE) -C $$dir context TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +context: $(foreach SDIR, $(CNTXTDIRS), $(SDIR)_context) -depend: - @for dir in $(SUBDIRS) ; do \ - $(MAKE) -C $$dir depend TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +depend: $(foreach SDIR, $(SUBDIRS), $(SDIR)_depend) -clean: - @for dir in $(SUBDIRS) ; do \ - $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +clean: $(foreach SDIR, $(SUBDIRS), $(SDIR)_clean) -distclean: clean - @for dir in $(SUBDIRS) ; do \ - $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +distclean: clean $(foreach SDIR, $(SUBDIRS), $(SDIR)_distclean) -include Make.dep diff --git a/apps/graphics/Makefile b/apps/graphics/Makefile index ddd26e5367..bebb31b5a6 100644 --- a/apps/graphics/Makefile +++ b/apps/graphics/Makefile @@ -46,27 +46,25 @@ CNTXTDIRS = all: nothing .PHONY: nothing context depend clean distclean +define SDIR_template +$(1)_$(2): + $(MAKE) -C $(1) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" +endef + +$(foreach SDIR, $(CNTXTDIRS), $(eval $(call SDIR_template,$(SDIR),context))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),depend))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),clean))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),disclean))) + nothing: -context: - @for dir in $(CNTXTDIRS) ; do \ - $(MAKE) -C $$dir context TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +context: $(foreach SDIR, $(CNTXTDIRS), $(SDIR)_context) -depend: - @for dir in $(SUBDIRS) ; do \ - $(MAKE) -C $$dir depend TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +depend: $(foreach SDIR, $(SUBDIRS), $(SDIR)_depend) -clean: - @for dir in $(SUBDIRS) ; do \ - $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +clean: $(foreach SDIR, $(SUBDIRS), $(SDIR)_clean) -distclean: clean - @for dir in $(SUBDIRS) ; do \ - $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +distclean: clean $(foreach SDIR, $(SUBDIRS), $(SDIR)_distclean) -include Make.dep diff --git a/apps/interpreters/Makefile b/apps/interpreters/Makefile index 5901fc8309..1eeab585e0 100644 --- a/apps/interpreters/Makefile +++ b/apps/interpreters/Makefile @@ -50,21 +50,21 @@ $(foreach DIR, $(SUBDIRS), $(eval $(call ADD_DIRECTORY,$(DIR)))) all: nothing .PHONY: nothing context depend clean distclean +define SDIR_template +$(1)_$(2): + $(MAKE) -C $(1) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" +endef + +$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),depend))) +$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),clean))) +$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),disclean))) + nothing: context: -depend: - @for dir in $(INSTALLED_DIRS) ; do \ - $(MAKE) -C $$dir depend TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +depend: $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_depend) -clean: - @for dir in $(INSTALLED_DIRS) ; do \ - $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +clean: $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_clean) -distclean: clean - @for dir in $(INSTALLED_DIRS) ; do \ - $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +distclean: clean $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_distclean) diff --git a/apps/netutils/Makefile b/apps/netutils/Makefile index e03369e303..303b804b6c 100644 --- a/apps/netutils/Makefile +++ b/apps/netutils/Makefile @@ -47,21 +47,21 @@ all: nothing .PHONY: nothing context depend clean distclean +define SDIR_template +$(1)_$(2): + $(MAKE) -C $(1) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" +endef + +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),depend))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),clean))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),disclean))) + nothing: context: -depend: - @for dir in $(SUBDIRS) ; do \ - $(MAKE) -C $$dir depend TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +depend: $(foreach SDIR, $(SUBDIRS), $(SDIR)_depend) -clean: - @for dir in $(SUBDIRS) ; do \ - $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +clean: $(foreach SDIR, $(SUBDIRS), $(SDIR)_clean) -distclean: clean - @for dir in $(SUBDIRS) ; do \ - $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +distclean: clean $(foreach SDIR, $(SUBDIRS), $(SDIR)_distclean) diff --git a/apps/system/Makefile b/apps/system/Makefile index d64bb54c6e..572598e398 100644 --- a/apps/system/Makefile +++ b/apps/system/Makefile @@ -50,22 +50,21 @@ $(foreach DIR, $(SUBDIRS), $(eval $(call ADD_DIRECTORY,$(DIR)))) all: nothing .PHONY: nothing context depend clean distclean +define SDIR_template +$(1)_$(2): + $(MAKE) -C $(1) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" +endef + +$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),depend))) +$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),clean))) +$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),disclean))) + nothing: context: -depend: - @for dir in $(INSTALLED_DIRS) ; do \ - $(MAKE) -C $$dir depend TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +depend: $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_depend) -clean: - @for dir in $(INSTALLED_DIRS) ; do \ - $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done - -distclean: clean - @for dir in $(INSTALLED_DIRS) ; do \ - $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ - done +clean: $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_clean) +distclean: clean $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_distclean) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 5fa67d3fe7..f907cbfcd1 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3625,4 +3625,7 @@ * configs/stm3240g-eval/src: Qencoder fixes from Ryan Sundberg. * arch/arm/src/stm32/stm32_qencoder.c: TIM3 bug fix from Ryan Sundberg. * tools/mkromfsimg.sh: Correct typo in an error message (Ryan Sundberg) + * arch/*/src/Makefile: Remove tftboot install and creation of System.map + for Windows native build. The fist is necessary, the second just needs + re-implemented. diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win index 7da6e8e9ce..c3c80cd105 100644 --- a/nuttx/Makefile.win +++ b/nuttx/Makefile.win @@ -457,8 +457,8 @@ clean_context: # configuration files have been installed and that NuttX is ready to be built. check_context: - if not exist $(TOPDIR)\.config echo "$(TOPDIR)\.config does not exist" - if not exist $(TOPDIR)\Make.defs echo "$(TOPDIR)\Make.defs does not exist" + $(Q) if not exist $(TOPDIR)\.config echo "$(TOPDIR)\.config does not exist" + $(Q) if not exist $(TOPDIR)\Make.defs echo "$(TOPDIR)\Make.defs does not exist" # Archive targets. The target build sequency will first create a series of # libraries, one per configured source file directory. The final NuttX @@ -594,15 +594,9 @@ pass2deps: pass2dep $(NUTTXLIBS) pass2: pass2deps $(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(LINKLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN) - $(Q) if [ -w \tftpboot ] ; then \ - cp -f $(BIN) \tftpboot\$(BIN).${CONFIG_ARCH}; \ - fi ifeq ($(CONFIG_RRLOAD_BINARY),y) @echo "MK: $(BIN).rr" $(Q) $(TOPDIR)\tools\mkimage.sh --Prefix $(CROSSDEV) $(BIN) $(BIN).rr - $(Q) if [ -w \tftpboot ] ; then \ - cp -f $(BIN).rr \tftpboot\$\(BIN).rr.$(CONFIG_ARCH); \ - fi endif ifeq ($(CONFIG_INTELHEX_BINARY),y) @echo "CP: $(BIN).hex" diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index be6b10af6b..243b5761ea 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -142,9 +142,11 @@ nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) $(EXTRA_LIBPATHS) \ -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group +ifneq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) $(NM) $(NUTTX)$(EXEEXT) | \ grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \ sort > $(TOPDIR)/System.map +endif # This is part of the top-level export target # Note that there may not be a head object if layout is handled diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile index 9b44c36976..067a99c372 100644 --- a/nuttx/arch/avr/src/Makefile +++ b/nuttx/arch/avr/src/Makefile @@ -139,9 +139,11 @@ nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) @echo "LD: nuttx" $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group +ifneq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) $(NM) $(NUTTX)$(EXEEXT) | \ grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \ sort > $(TOPDIR)/System.map +endif # This is part of the top-level export target diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile index 60e6a863b2..13788b71df 100644 --- a/nuttx/arch/hc/src/Makefile +++ b/nuttx/arch/hc/src/Makefile @@ -134,9 +134,11 @@ nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) $(Q) echo "LD: nuttx" $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) \ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group +ifneq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) $(NM) $(NUTTX)$(EXEEXT) | \ grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \ sort > $(TOPDIR)/System.map +endif # This is part of the top-level export target diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile index 14388a90db..c4a73e3923 100644 --- a/nuttx/arch/mips/src/Makefile +++ b/nuttx/arch/mips/src/Makefile @@ -132,9 +132,11 @@ nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) @echo "LD: nuttx" $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group +ifneq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) $(NM) $(NUTTX)$(EXEEXT) | \ grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \ sort > $(TOPDIR)/System.map +endif # This is part of the top-level export target diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile index 9fa8ea4472..c096bb0da4 100644 --- a/nuttx/arch/sh/src/Makefile +++ b/nuttx/arch/sh/src/Makefile @@ -130,9 +130,11 @@ nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) @echo "LD: nuttx" $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(TOPDIR)/$@ $(HEAD_OBJ) \ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group +ifneq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) $(NM) $(TOPDIR)/$@ | \ grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \ sort > $(TOPDIR)/System.map +endif # This is part of the top-level export target diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile index dc35d0db3d..7ee92e8384 100644 --- a/nuttx/arch/x86/src/Makefile +++ b/nuttx/arch/x86/src/Makefile @@ -140,9 +140,11 @@ nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) @echo "LD: nuttx$(EXEEXT)" $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group +ifneq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) $(NM) $(NUTTX)$(EXEEXT) | \ grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \ sort > $(TOPDIR)/System.map +endif # This is part of the top-level export target From f0e39397fe5d9b301ad887ad430736397f6403fd Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 14 Nov 2012 22:41:50 +0100 Subject: [PATCH 126/206] fw control: work in progress, heading rate control loop --- .../fixedwing_pos_control_main.c | 46 ++++++++++++++----- 1 file changed, 35 insertions(+), 11 deletions(-) diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c index 4a1025109a..8fc272eb64 100644 --- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c +++ b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c @@ -75,6 +75,8 @@ PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); // Pitch angle limit in radians struct fw_pos_control_params { float heading_p; + float headingr_p; + float headingr_i; float xtrack_p; float altitude_p; float roll_lim; @@ -83,6 +85,8 @@ struct fw_pos_control_params { struct fw_pos_control_param_handles { param_t heading_p; + param_t headingr_p; + param_t headingr_i; param_t xtrack_p; param_t altitude_p; param_t roll_lim; @@ -124,6 +128,8 @@ static int parameters_init(struct fw_pos_control_param_handles *h) { /* PID parameters */ h->heading_p = param_find("FW_HEADING_P"); + h->headingr_p = param_find("FW_HEADINGR_P"); + h->headingr_i = param_find("FW_HEADINGR_I"); h->xtrack_p = param_find("FW_XTRACK_P"); h->altitude_p = param_find("FW_ALT_P"); h->roll_lim = param_find("FW_ROLL_LIM"); @@ -136,6 +142,8 @@ static int parameters_init(struct fw_pos_control_param_handles *h) static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_pos_control_params *p) { param_get(h->heading_p, &(p->heading_p)); + param_get(h->headingr_p, &(p->headingr_p)); + param_get(h->headingr_i, &(p->headingr_i)); param_get(h->xtrack_p, &(p->xtrack_p)); param_get(h->altitude_p, &(p->altitude_p)); param_get(h->roll_lim, &(p->roll_lim)); @@ -205,14 +213,22 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) static struct fw_pos_control_param_handles h; PID_t heading_controller; + PID_t heading_rate_controller; + PID_t offtrack_controller; PID_t altitude_controller; + static uint64_t last_run = 0; + const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f; + last_run = hrt_absolute_time(); + if(!initialized) { parameters_init(&h); parameters_update(&h, &p); - pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f,p.roll_lim,PID_MODE_DERIVATIV_NONE); - pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f,p.pitch_lim,PID_MODE_DERIVATIV_NONE); + pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f, 10000.0f, PID_MODE_DERIVATIV_NONE); //arbitrary high limit + pid_init(&heading_rate_controller, p.headingr_p, p.headingr_i, 0.0f, 0.0f, p.roll_lim, PID_MODE_DERIVATIV_NONE); + pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f, p.pitch_lim, PID_MODE_DERIVATIV_NONE); + pid_init(&offtrack_controller, p.xtrack_p, 0.0f, 0.0f, 0.0f , 60.0f*M_DEG_TO_RAD, PID_MODE_DERIVATIV_NONE); //TODO: remove hardcoded value initialized = true; } @@ -220,8 +236,10 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) if (counter % 100 == 0) { /* update parameters from storage */ parameters_update(&h, &p); - pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, p.roll_lim); + pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, 10000.0f); //arbitrary high limit + pid_set_parameters(&heading_rate_controller, p.headingr_p, p.headingr_i, 0, 0, p.roll_lim); pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_lim); + pid_set_parameters(&offtrack_controller, p.xtrack_p, 0, 0, 0, 60.0f*M_DEG_TO_RAD); //TODO: remove hardcoded value } @@ -262,13 +280,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) if(!(distance_res != OK || xtrack_err.past_end)) { - float delta_psi_c = -p.xtrack_p * xtrack_err.distance; //(-) because z axis points downwards - - if(delta_psi_c > 60.0f*M_DEG_TO_RAD) - delta_psi_c = 60.0f*M_DEG_TO_RAD; - - if(delta_psi_c < -60.0f*M_DEG_TO_RAD) - delta_psi_c = -60.0f*M_DEG_TO_RAD; + float delta_psi_c = -pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance; //(-) because z axis points downwards float psi_c = psi_track + delta_psi_c; @@ -278,7 +290,19 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) psi_e = _wrapPI(psi_e); /* calculate roll setpoint, do this artificially around zero */ - attitude_setpoint.roll_tait_bryan = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f); + //TODO: psi rate loop incomplete + float delta_psi_rate_c = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f); + float psi_rate_track = 0; //=V_gr/r_track , this will be needed for implementation of arc following + float psi_rate_c = delta_psi_rate_c + psi_rate_track; + + //TODO limit turn rate + + float psi_rate_e = psi_rate_c - att.yawspeed; + + float psi_rate_e_scaled = psi_rate_e * sqrtf(pow(global_pos.vx,2) + pow(global_pos.vy,2)) / 9.81f; //* V_gr / g + + attitude_setpoint.roll_tait_bryan = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT); + // if (counter % 100 == 0) // printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c); From 2581506dfb1861f909fb99c790f2d5b9b7132141 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 15 Nov 2012 17:43:29 +0000 Subject: [PATCH 127/206] Move some (hopefully) un-necessary quotes in Makefiles for Mike git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5356 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/UnitTests/CButton/Makefile | 2 +- NxWidgets/UnitTests/CButtonArray/Makefile | 2 +- NxWidgets/UnitTests/CCheckBox/Makefile | 2 +- NxWidgets/UnitTests/CGlyphButton/Makefile | 2 +- NxWidgets/UnitTests/CImage/Makefile | 2 +- NxWidgets/UnitTests/CKeypad/Makefile | 2 +- NxWidgets/UnitTests/CLabel/Makefile | 2 +- NxWidgets/UnitTests/CLatchButton/Makefile | 2 +- .../UnitTests/CLatchButtonArray/Makefile | 2 +- NxWidgets/UnitTests/CListBox/Makefile | 2 +- NxWidgets/UnitTests/CProgressBar/Makefile | 2 +- NxWidgets/UnitTests/CRadioButton/Makefile | 2 +- .../UnitTests/CScrollbarHorizontal/Makefile | 2 +- .../UnitTests/CScrollbarVertical/Makefile | 2 +- NxWidgets/UnitTests/CSliderHorizonal/Makefile | 2 +- NxWidgets/UnitTests/CSliderVertical/Makefile | 2 +- NxWidgets/UnitTests/CTextBox/Makefile | 2 +- NxWidgets/UnitTests/nxwm/Makefile | 2 +- NxWidgets/libnxwidgets/Makefile | 2 +- NxWidgets/nxwm/Makefile | 2 +- apps/examples/adc/Makefile | 2 +- apps/examples/buttons/Makefile | 2 +- apps/examples/can/Makefile | 2 +- apps/examples/cdcacm/Makefile | 2 +- apps/examples/composite/Makefile | 2 +- apps/examples/cxxtest/Makefile | 2 +- apps/examples/dhcpd/Makefile | 2 +- apps/examples/discover/Makefile | 2 +- apps/examples/elf/Makefile | 2 +- apps/examples/ftpc/Makefile | 2 +- apps/examples/ftpd/Makefile | 2 +- apps/examples/hello/Makefile | 2 +- apps/examples/helloxx/Makefile | 2 +- apps/examples/hidkbd/Makefile | 2 +- apps/examples/igmp/Makefile | 2 +- apps/examples/json/Makefile | 2 +- apps/examples/lcdrw/Makefile | 2 +- apps/examples/mm/Makefile | 2 +- apps/examples/modbus/Makefile | 2 +- apps/examples/mount/Makefile | 2 +- apps/examples/nettest/Makefile | 2 +- apps/examples/nsh/Makefile | 2 +- apps/examples/null/Makefile | 2 +- apps/examples/nx/Makefile | 2 +- apps/examples/nxconsole/Makefile | 2 +- apps/examples/nxffs/Makefile | 2 +- apps/examples/nxflat/Makefile | 2 +- apps/examples/nxhello/Makefile | 2 +- apps/examples/nximage/Makefile | 2 +- apps/examples/nxlines/Makefile | 2 +- apps/examples/nxtext/Makefile | 2 +- apps/examples/ostest/Makefile | 2 +- apps/examples/pashello/Makefile | 2 +- apps/examples/pipe/Makefile | 2 +- apps/examples/poll/Makefile | 2 +- apps/examples/pwm/Makefile | 2 +- apps/examples/qencoder/Makefile | 2 +- apps/examples/relays/Makefile | 2 +- apps/examples/rgmp/Makefile | 2 +- apps/examples/romfs/Makefile | 2 +- apps/examples/sendmail/Makefile | 2 +- apps/examples/serloop/Makefile | 2 +- apps/examples/telnetd/Makefile | 2 +- apps/examples/thttpd/Makefile | 2 +- apps/examples/tiff/Makefile | 2 +- apps/examples/touchscreen/Makefile | 2 +- apps/examples/udp/Makefile | 2 +- apps/examples/uip/Makefile | 2 +- apps/examples/usbserial/Makefile | 2 +- apps/examples/usbstorage/Makefile | 2 +- apps/examples/usbterm/Makefile | 2 +- apps/examples/watchdog/Makefile | 2 +- apps/examples/wget/Makefile | 2 +- apps/examples/wgetjson/Makefile | 2 +- apps/examples/wlan/Makefile | 2 +- apps/examples/xmlrpc/Makefile | 2 +- apps/graphics/tiff/Makefile | 2 +- apps/interpreters/ficl/Makefile | 2 +- apps/modbus/Makefile | 2 +- apps/namedapp/Makefile | 2 +- apps/netutils/codecs/Makefile | 2 +- apps/netutils/dhcpc/Makefile | 2 +- apps/netutils/dhcpd/Makefile | 2 +- apps/netutils/discover/Makefile | 2 +- apps/netutils/ftpc/Makefile | 2 +- apps/netutils/ftpd/Makefile | 2 +- apps/netutils/json/Makefile | 2 +- apps/netutils/resolv/Makefile | 2 +- apps/netutils/smtp/Makefile | 2 +- apps/netutils/telnetd/Makefile | 2 +- apps/netutils/tftpc/Makefile | 2 +- apps/netutils/thttpd/Makefile | 2 +- apps/netutils/uiplib/Makefile | 2 +- apps/netutils/webclient/Makefile | 2 +- apps/netutils/webserver/Makefile | 2 +- apps/netutils/xmlrpc/Makefile | 2 +- apps/nshlib/Makefile | 2 +- apps/system/free/Makefile | 2 +- apps/system/i2c/Makefile | 2 +- apps/system/install/Makefile | 2 +- apps/system/poweroff/Makefile | 2 +- apps/system/ramtron/Makefile | 2 +- apps/system/readline/Makefile | 2 +- apps/system/sdcard/Makefile | 2 +- apps/system/sysinfo/Makefile | 2 +- misc/pascal/nuttx/Makefile | 2 +- nuttx/Documentation/NuttxPortingGuide.html | 27 ++++++++++++++----- nuttx/arch/8051/src/Makefile | 2 +- nuttx/arch/arm/src/Makefile | 2 +- nuttx/arch/avr/src/Makefile | 2 +- nuttx/arch/hc/src/Makefile | 2 +- nuttx/arch/mips/src/Makefile | 2 +- nuttx/arch/rgmp/src/Makefile | 2 +- nuttx/arch/sh/src/Makefile | 2 +- nuttx/arch/sim/src/Makefile | 2 +- nuttx/arch/x86/src/Makefile | 2 +- nuttx/arch/z16/src/Makefile | 2 +- nuttx/arch/z80/src/Makefile.sdcc | 2 +- nuttx/arch/z80/src/Makefile.zdsii | 2 +- nuttx/binfmt/Makefile | 2 +- nuttx/configs/README.txt | 15 ++++++++--- nuttx/configs/amber/src/Makefile | 2 +- nuttx/configs/avr32dev1/src/Makefile | 2 +- nuttx/configs/c5471evm/src/Makefile | 2 +- nuttx/configs/compal_e88/src/Makefile | 2 +- nuttx/configs/compal_e99/src/Makefile | 2 +- nuttx/configs/demo9s12ne64/src/Makefile | 2 +- nuttx/configs/ea3131/src/Makefile | 2 +- nuttx/configs/ea3152/src/Makefile | 2 +- nuttx/configs/eagle100/src/Makefile | 2 +- nuttx/configs/ekk-lm3s9b96/src/Makefile | 2 +- .../configs/ez80f910200kitg/ostest/Make.defs | 4 +-- nuttx/configs/ez80f910200kitg/src/Makefile | 2 +- nuttx/configs/ez80f910200zco/dhcpd/Make.defs | 5 ++-- nuttx/configs/ez80f910200zco/httpd/Make.defs | 4 +-- .../configs/ez80f910200zco/nettest/Make.defs | 4 +-- nuttx/configs/ez80f910200zco/nsh/Make.defs | 4 +-- nuttx/configs/ez80f910200zco/ostest/Make.defs | 4 +-- nuttx/configs/ez80f910200zco/poll/Make.defs | 4 +-- nuttx/configs/ez80f910200zco/src/Makefile | 2 +- nuttx/configs/fire-stm32v2/src/Makefile | 2 +- nuttx/configs/hymini-stm32v/src/Makefile | 2 +- nuttx/configs/kwikstik-k40/src/Makefile | 2 +- nuttx/configs/lincoln60/src/Makefile | 2 +- nuttx/configs/lm3s6432-s2e/src/Makefile | 2 +- nuttx/configs/lm3s6965-ek/src/Makefile | 2 +- nuttx/configs/lm3s8962-ek/src/Makefile | 2 +- nuttx/configs/lpc4330-xplorer/src/Makefile | 2 +- nuttx/configs/lpcxpresso-lpc1768/src/Makefile | 2 +- nuttx/configs/m68332evb/src/Makefile | 2 +- nuttx/configs/mbed/src/Makefile | 2 +- nuttx/configs/mcu123-lpc214x/src/Makefile | 2 +- nuttx/configs/micropendous3/src/Makefile | 2 +- nuttx/configs/mirtoo/src/Makefile | 2 +- nuttx/configs/mx1ads/src/Makefile | 2 +- nuttx/configs/ne64badge/src/Makefile | 2 +- nuttx/configs/ntosd-dm320/src/Makefile | 2 +- nuttx/configs/nucleus2g/src/Makefile | 2 +- nuttx/configs/olimex-lpc1766stk/src/Makefile | 2 +- nuttx/configs/olimex-lpc2378/src/Makefile | 2 +- nuttx/configs/olimex-stm32-p107/src/Makefile | 2 +- nuttx/configs/olimex-strp711/src/Makefile | 2 +- nuttx/configs/pcblogic-pic32mx/src/Makefile | 2 +- nuttx/configs/pic32-starterkit/src/Makefile | 2 +- nuttx/configs/pic32mx7mmb/src/Makefile | 2 +- nuttx/configs/pjrc-8051/src/Makefile | 2 +- nuttx/configs/qemu-i486/src/Makefile | 2 +- nuttx/configs/sam3u-ek/src/Makefile | 2 +- nuttx/configs/shenzhou/src/Makefile | 2 +- nuttx/configs/sim/src/Makefile | 2 +- nuttx/configs/skp16c26/src/Makefile | 2 +- nuttx/configs/stm3210e-eval/src/Makefile | 2 +- nuttx/configs/stm3220g-eval/src/Makefile | 2 +- nuttx/configs/stm3240g-eval/src/Makefile | 2 +- .../configs/stm32f100rc_generic/src/Makefile | 2 +- nuttx/configs/stm32f4discovery/src/Makefile | 2 +- nuttx/configs/sure-pic32mx/src/Makefile | 2 +- nuttx/configs/teensy/src/Makefile | 2 +- nuttx/configs/twr-k60n512/src/Makefile | 2 +- nuttx/configs/ubw32/src/Makefile | 2 +- nuttx/configs/us7032evb1/src/Makefile | 2 +- nuttx/configs/vsn/src/Makefile | 2 +- nuttx/configs/xtrs/src/Makefile | 2 +- .../configs/z16f2800100zcog/ostest/Make.defs | 4 +-- .../z16f2800100zcog/pashello/Make.defs | 4 +-- nuttx/configs/z16f2800100zcog/src/Makefile | 2 +- nuttx/configs/z80sim/src/Makefile | 2 +- nuttx/configs/z8encore000zco/ostest/Make.defs | 4 +-- nuttx/configs/z8encore000zco/src/Makefile | 2 +- nuttx/configs/z8f64200100kit/ostest/Make.defs | 4 +-- nuttx/configs/z8f64200100kit/src/Makefile | 2 +- nuttx/drivers/Makefile | 2 +- nuttx/fs/Makefile | 2 +- nuttx/graphics/Makefile | 2 +- nuttx/libc/Makefile | 10 ++++++- nuttx/libxx/Makefile | 2 +- nuttx/mm/Makefile | 2 +- nuttx/net/Makefile | 2 +- nuttx/sched/Makefile | 4 +-- nuttx/syscall/Makefile | 2 +- nuttx/tools/Config.mk | 8 ++++-- 201 files changed, 257 insertions(+), 222 deletions(-) diff --git a/NxWidgets/UnitTests/CButton/Makefile b/NxWidgets/UnitTests/CButton/Makefile index 01bca12a57..c2dcfcb5dd 100644 --- a/NxWidgets/UnitTests/CButton/Makefile +++ b/NxWidgets/UnitTests/CButton/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CButtonArray/Makefile b/NxWidgets/UnitTests/CButtonArray/Makefile index 84d19277e0..8df0b42135 100644 --- a/NxWidgets/UnitTests/CButtonArray/Makefile +++ b/NxWidgets/UnitTests/CButtonArray/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CCheckBox/Makefile b/NxWidgets/UnitTests/CCheckBox/Makefile index 5aa96e6185..e363aed44c 100644 --- a/NxWidgets/UnitTests/CCheckBox/Makefile +++ b/NxWidgets/UnitTests/CCheckBox/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CGlyphButton/Makefile b/NxWidgets/UnitTests/CGlyphButton/Makefile index ec0c5d5d3c..9b529faee2 100644 --- a/NxWidgets/UnitTests/CGlyphButton/Makefile +++ b/NxWidgets/UnitTests/CGlyphButton/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CImage/Makefile b/NxWidgets/UnitTests/CImage/Makefile index 5970d59d19..b35fb2f7ca 100644 --- a/NxWidgets/UnitTests/CImage/Makefile +++ b/NxWidgets/UnitTests/CImage/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CKeypad/Makefile b/NxWidgets/UnitTests/CKeypad/Makefile index b0aba9603f..2003e13f99 100644 --- a/NxWidgets/UnitTests/CKeypad/Makefile +++ b/NxWidgets/UnitTests/CKeypad/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CLabel/Makefile b/NxWidgets/UnitTests/CLabel/Makefile index 9a5fa13216..dacfa6274b 100644 --- a/NxWidgets/UnitTests/CLabel/Makefile +++ b/NxWidgets/UnitTests/CLabel/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CLatchButton/Makefile b/NxWidgets/UnitTests/CLatchButton/Makefile index e50db8914f..6730a6eb57 100644 --- a/NxWidgets/UnitTests/CLatchButton/Makefile +++ b/NxWidgets/UnitTests/CLatchButton/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CLatchButtonArray/Makefile b/NxWidgets/UnitTests/CLatchButtonArray/Makefile index 544167ec94..715ab3e2ac 100644 --- a/NxWidgets/UnitTests/CLatchButtonArray/Makefile +++ b/NxWidgets/UnitTests/CLatchButtonArray/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CListBox/Makefile b/NxWidgets/UnitTests/CListBox/Makefile index 1161460b44..52f3ca038b 100644 --- a/NxWidgets/UnitTests/CListBox/Makefile +++ b/NxWidgets/UnitTests/CListBox/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CProgressBar/Makefile b/NxWidgets/UnitTests/CProgressBar/Makefile index 6fee2fac9b..49eddf1885 100644 --- a/NxWidgets/UnitTests/CProgressBar/Makefile +++ b/NxWidgets/UnitTests/CProgressBar/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CRadioButton/Makefile b/NxWidgets/UnitTests/CRadioButton/Makefile index 97e8a398ee..17b58a7c9c 100644 --- a/NxWidgets/UnitTests/CRadioButton/Makefile +++ b/NxWidgets/UnitTests/CRadioButton/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile b/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile index 952ec4c6b4..9efc5d4018 100644 --- a/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile +++ b/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CScrollbarVertical/Makefile b/NxWidgets/UnitTests/CScrollbarVertical/Makefile index 4e44699ee8..3f69266281 100644 --- a/NxWidgets/UnitTests/CScrollbarVertical/Makefile +++ b/NxWidgets/UnitTests/CScrollbarVertical/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CSliderHorizonal/Makefile b/NxWidgets/UnitTests/CSliderHorizonal/Makefile index 5bc6c84c60..97be73810d 100644 --- a/NxWidgets/UnitTests/CSliderHorizonal/Makefile +++ b/NxWidgets/UnitTests/CSliderHorizonal/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CSliderVertical/Makefile b/NxWidgets/UnitTests/CSliderVertical/Makefile index 4c6a660f0c..1c37913932 100644 --- a/NxWidgets/UnitTests/CSliderVertical/Makefile +++ b/NxWidgets/UnitTests/CSliderVertical/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/CTextBox/Makefile b/NxWidgets/UnitTests/CTextBox/Makefile index 8fde36bb08..8a44caee29 100644 --- a/NxWidgets/UnitTests/CTextBox/Makefile +++ b/NxWidgets/UnitTests/CTextBox/Makefile @@ -134,7 +134,7 @@ chklib: $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else diff --git a/NxWidgets/UnitTests/nxwm/Makefile b/NxWidgets/UnitTests/nxwm/Makefile index 73cb0b42a2..3dd666b113 100644 --- a/NxWidgets/UnitTests/nxwm/Makefile +++ b/NxWidgets/UnitTests/nxwm/Makefile @@ -162,7 +162,7 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklibnxwidgets does the work. $(NXWM_LIB): # Just to keep make happy. chklibnxwm does the work. .built: $(OBJS) $(NXWIDGETS_LIB) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWM_DIR) diff --git a/NxWidgets/libnxwidgets/Makefile b/NxWidgets/libnxwidgets/Makefile index 880117a247..222f008b74 100644 --- a/NxWidgets/libnxwidgets/Makefile +++ b/NxWidgets/libnxwidgets/Makefile @@ -122,7 +122,7 @@ check_nuttx: ) $(BIN): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/NxWidgets/nxwm/Makefile b/NxWidgets/nxwm/Makefile index 81b9dcdeb8..d272a83848 100644 --- a/NxWidgets/nxwm/Makefile +++ b/NxWidgets/nxwm/Makefile @@ -127,7 +127,7 @@ check_nuttx: ) $(BIN): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/apps/examples/adc/Makefile b/apps/examples/adc/Makefile index b2720d2404..8f37169c5f 100644 --- a/apps/examples/adc/Makefile +++ b/apps/examples/adc/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/buttons/Makefile b/apps/examples/buttons/Makefile index 34d928df86..1f209b7608 100644 --- a/apps/examples/buttons/Makefile +++ b/apps/examples/buttons/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/can/Makefile b/apps/examples/can/Makefile index 3e00083cd7..20fb173f0f 100644 --- a/apps/examples/can/Makefile +++ b/apps/examples/can/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/cdcacm/Makefile b/apps/examples/cdcacm/Makefile index 3a6075df3e..1ebbc6e1e9 100644 --- a/apps/examples/cdcacm/Makefile +++ b/apps/examples/cdcacm/Makefile @@ -84,7 +84,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/composite/Makefile b/apps/examples/composite/Makefile index c47be8726c..6fe34a1e99 100644 --- a/apps/examples/composite/Makefile +++ b/apps/examples/composite/Makefile @@ -84,7 +84,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/cxxtest/Makefile b/apps/examples/cxxtest/Makefile index fdea675106..e6bdd34fc3 100644 --- a/apps/examples/cxxtest/Makefile +++ b/apps/examples/cxxtest/Makefile @@ -97,7 +97,7 @@ $(CXXOBJS): %$(OBJEXT): %.cxx $(call COMPILEXX, $<, $@) .built: chkcxx $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/dhcpd/Makefile b/apps/examples/dhcpd/Makefile index 5be2a845f4..6a96281cfb 100644 --- a/apps/examples/dhcpd/Makefile +++ b/apps/examples/dhcpd/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/discover/Makefile b/apps/examples/discover/Makefile index 5094bf6705..722ad3d9bc 100644 --- a/apps/examples/discover/Makefile +++ b/apps/examples/discover/Makefile @@ -81,7 +81,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/elf/Makefile b/apps/examples/elf/Makefile index d90c118d3e..24472139fb 100644 --- a/apps/examples/elf/Makefile +++ b/apps/examples/elf/Makefile @@ -79,7 +79,7 @@ $(COBJS): %$(OBJEXT): %.c # generating the source files. really_build: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .built: diff --git a/apps/examples/ftpc/Makefile b/apps/examples/ftpc/Makefile index 93c7928a26..9f9f689db5 100644 --- a/apps/examples/ftpc/Makefile +++ b/apps/examples/ftpc/Makefile @@ -78,7 +78,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built # Register application diff --git a/apps/examples/ftpd/Makefile b/apps/examples/ftpd/Makefile index 25a572db7c..cae8a282ec 100644 --- a/apps/examples/ftpd/Makefile +++ b/apps/examples/ftpd/Makefile @@ -75,7 +75,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/hello/Makefile b/apps/examples/hello/Makefile index a3d245466e..53fbead98c 100644 --- a/apps/examples/hello/Makefile +++ b/apps/examples/hello/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/helloxx/Makefile b/apps/examples/helloxx/Makefile index 66669f1089..fd126d345f 100644 --- a/apps/examples/helloxx/Makefile +++ b/apps/examples/helloxx/Makefile @@ -97,7 +97,7 @@ $(CXXOBJS): %$(OBJEXT): %.cxx $(call COMPILEXX, $<, $@) .built: chkcxx $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/hidkbd/Makefile b/apps/examples/hidkbd/Makefile index 29746888c2..cb0f32c606 100644 --- a/apps/examples/hidkbd/Makefile +++ b/apps/examples/hidkbd/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/igmp/Makefile b/apps/examples/igmp/Makefile index 361e3354a6..5f9d4aa98a 100644 --- a/apps/examples/igmp/Makefile +++ b/apps/examples/igmp/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/json/Makefile b/apps/examples/json/Makefile index b2d7167762..0551eccfe3 100644 --- a/apps/examples/json/Makefile +++ b/apps/examples/json/Makefile @@ -78,7 +78,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/lcdrw/Makefile b/apps/examples/lcdrw/Makefile index 32b074b58e..fab2a6939c 100644 --- a/apps/examples/lcdrw/Makefile +++ b/apps/examples/lcdrw/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/mm/Makefile b/apps/examples/mm/Makefile index 95e2ec2472..5d29c6d905 100644 --- a/apps/examples/mm/Makefile +++ b/apps/examples/mm/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/modbus/Makefile b/apps/examples/modbus/Makefile index 015006773d..937212f723 100644 --- a/apps/examples/modbus/Makefile +++ b/apps/examples/modbus/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/mount/Makefile b/apps/examples/mount/Makefile index 2ed83d66bf..d244852d0c 100644 --- a/apps/examples/mount/Makefile +++ b/apps/examples/mount/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/nettest/Makefile b/apps/examples/nettest/Makefile index 0e4f972ee1..75e4cf0bea 100644 --- a/apps/examples/nettest/Makefile +++ b/apps/examples/nettest/Makefile @@ -113,7 +113,7 @@ $(HOST_BIN): $(HOST_OBJS) @$(HOSTCC) $(HOSTLDFLAGS) $(HOST_OBJS) -o $@ .built: $(TARG_OBJS) - $(call ARCHIVE, $(BIN), "$(TARG_OBJS)") + $(call ARCHIVE, $(BIN), $(TARG_OBJS)) @touch .built .context: diff --git a/apps/examples/nsh/Makefile b/apps/examples/nsh/Makefile index 049b62e5dd..fdf5a2a908 100644 --- a/apps/examples/nsh/Makefile +++ b/apps/examples/nsh/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/null/Makefile b/apps/examples/null/Makefile index 76b3c0588a..fa3b83d2af 100644 --- a/apps/examples/null/Makefile +++ b/apps/examples/null/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/nx/Makefile b/apps/examples/nx/Makefile index ddcc025a03..7bc861bbd1 100644 --- a/apps/examples/nx/Makefile +++ b/apps/examples/nx/Makefile @@ -83,7 +83,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/nxconsole/Makefile b/apps/examples/nxconsole/Makefile index 2c484dfdad..eb72c87b9a 100644 --- a/apps/examples/nxconsole/Makefile +++ b/apps/examples/nxconsole/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/nxffs/Makefile b/apps/examples/nxffs/Makefile index 210f40ea94..c66a0ec33b 100644 --- a/apps/examples/nxffs/Makefile +++ b/apps/examples/nxffs/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/nxflat/Makefile b/apps/examples/nxflat/Makefile index 9bf0b0c932..07c163347d 100644 --- a/apps/examples/nxflat/Makefile +++ b/apps/examples/nxflat/Makefile @@ -77,7 +77,7 @@ headers: @$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/nxhello/Makefile b/apps/examples/nxhello/Makefile index 48e982c32c..6ab65c53d8 100644 --- a/apps/examples/nxhello/Makefile +++ b/apps/examples/nxhello/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/nximage/Makefile b/apps/examples/nximage/Makefile index 0340e932d1..b552c0bf69 100644 --- a/apps/examples/nximage/Makefile +++ b/apps/examples/nximage/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/nxlines/Makefile b/apps/examples/nxlines/Makefile index 5c185f038c..b52da37d2b 100644 --- a/apps/examples/nxlines/Makefile +++ b/apps/examples/nxlines/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/nxtext/Makefile b/apps/examples/nxtext/Makefile index 62e7ac1e48..5067d2af78 100644 --- a/apps/examples/nxtext/Makefile +++ b/apps/examples/nxtext/Makefile @@ -84,7 +84,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/ostest/Makefile b/apps/examples/ostest/Makefile index 72582e510f..e490139187 100644 --- a/apps/examples/ostest/Makefile +++ b/apps/examples/ostest/Makefile @@ -124,7 +124,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/pashello/Makefile b/apps/examples/pashello/Makefile index 88c7bddec1..af33975d0e 100644 --- a/apps/examples/pashello/Makefile +++ b/apps/examples/pashello/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/pipe/Makefile b/apps/examples/pipe/Makefile index 9596167fca..e0168ed0af 100644 --- a/apps/examples/pipe/Makefile +++ b/apps/examples/pipe/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/poll/Makefile b/apps/examples/poll/Makefile index cdb570fc7a..89b3145117 100644 --- a/apps/examples/poll/Makefile +++ b/apps/examples/poll/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/pwm/Makefile b/apps/examples/pwm/Makefile index e05c5cdbed..6aeb385948 100644 --- a/apps/examples/pwm/Makefile +++ b/apps/examples/pwm/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/qencoder/Makefile b/apps/examples/qencoder/Makefile index 499ae7475d..483043c46c 100644 --- a/apps/examples/qencoder/Makefile +++ b/apps/examples/qencoder/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/relays/Makefile b/apps/examples/relays/Makefile index efd15b61aa..bb988f7756 100644 --- a/apps/examples/relays/Makefile +++ b/apps/examples/relays/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/rgmp/Makefile b/apps/examples/rgmp/Makefile index 8207ee9702..c7e2c59797 100644 --- a/apps/examples/rgmp/Makefile +++ b/apps/examples/rgmp/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/romfs/Makefile b/apps/examples/romfs/Makefile index 2df77a0009..b247db6f62 100644 --- a/apps/examples/romfs/Makefile +++ b/apps/examples/romfs/Makefile @@ -90,7 +90,7 @@ romfs_testdir.h : testdir.img @xxd -i $< >$@ || { echo "xxd of $< failed" ; exit 1 ; } .built: romfs_testdir.h $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/sendmail/Makefile b/apps/examples/sendmail/Makefile index e7368e26dc..e8d05ceabd 100644 --- a/apps/examples/sendmail/Makefile +++ b/apps/examples/sendmail/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/serloop/Makefile b/apps/examples/serloop/Makefile index 740932b2f4..ecf7984e53 100644 --- a/apps/examples/serloop/Makefile +++ b/apps/examples/serloop/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/telnetd/Makefile b/apps/examples/telnetd/Makefile index 3df4026abf..7c541cba98 100644 --- a/apps/examples/telnetd/Makefile +++ b/apps/examples/telnetd/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/thttpd/Makefile b/apps/examples/thttpd/Makefile index 4da7e79970..10bcb9af07 100644 --- a/apps/examples/thttpd/Makefile +++ b/apps/examples/thttpd/Makefile @@ -77,7 +77,7 @@ headers: @$(MAKE) -C content TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) .built: headers $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/tiff/Makefile b/apps/examples/tiff/Makefile index 1c44b48fad..73a687c253 100644 --- a/apps/examples/tiff/Makefile +++ b/apps/examples/tiff/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/touchscreen/Makefile b/apps/examples/touchscreen/Makefile index 88e88185a1..ad10363161 100644 --- a/apps/examples/touchscreen/Makefile +++ b/apps/examples/touchscreen/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/udp/Makefile b/apps/examples/udp/Makefile index 2f7d493224..6bfdce9cc1 100644 --- a/apps/examples/udp/Makefile +++ b/apps/examples/udp/Makefile @@ -96,7 +96,7 @@ $(TARG_COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) "$(TARG_BIN)": $(TARG_OBJS) $(HOST_BIN) - $(call ARCHIVE, $@, "$(TARG_OBJS)") + $(call ARCHIVE, $@, $(TARG_OBJS)) $(HOST_OBJS): %.o: %.c $(HOSTCC) -c $(HOSTCFLAGS) $< -o $@ diff --git a/apps/examples/uip/Makefile b/apps/examples/uip/Makefile index 01e37dd72c..487512072e 100644 --- a/apps/examples/uip/Makefile +++ b/apps/examples/uip/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built httpd_fsdata.c: httpd-fs/* diff --git a/apps/examples/usbserial/Makefile b/apps/examples/usbserial/Makefile index 26bbc1b1a7..0761dd48c7 100644 --- a/apps/examples/usbserial/Makefile +++ b/apps/examples/usbserial/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/usbstorage/Makefile b/apps/examples/usbstorage/Makefile index dfbdc8b47c..8c142e0c63 100644 --- a/apps/examples/usbstorage/Makefile +++ b/apps/examples/usbstorage/Makefile @@ -84,7 +84,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/usbterm/Makefile b/apps/examples/usbterm/Makefile index 1dd30e8bef..6622759f6d 100644 --- a/apps/examples/usbterm/Makefile +++ b/apps/examples/usbterm/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/watchdog/Makefile b/apps/examples/watchdog/Makefile index 87a7f82968..f3c9a8bf93 100644 --- a/apps/examples/watchdog/Makefile +++ b/apps/examples/watchdog/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/wget/Makefile b/apps/examples/wget/Makefile index 19f16534b7..859ae999d8 100644 --- a/apps/examples/wget/Makefile +++ b/apps/examples/wget/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/wgetjson/Makefile b/apps/examples/wgetjson/Makefile index f41464436f..c03715ad5e 100644 --- a/apps/examples/wgetjson/Makefile +++ b/apps/examples/wgetjson/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/examples/wlan/Makefile b/apps/examples/wlan/Makefile index 9268c74568..c50b132278 100644 --- a/apps/examples/wlan/Makefile +++ b/apps/examples/wlan/Makefile @@ -75,7 +75,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/examples/xmlrpc/Makefile b/apps/examples/xmlrpc/Makefile index 061f8fc474..84d3ed4be5 100644 --- a/apps/examples/xmlrpc/Makefile +++ b/apps/examples/xmlrpc/Makefile @@ -81,7 +81,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/graphics/tiff/Makefile b/apps/graphics/tiff/Makefile index ed445f132c..1ce2813c83 100644 --- a/apps/graphics/tiff/Makefile +++ b/apps/graphics/tiff/Makefile @@ -74,7 +74,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/interpreters/ficl/Makefile b/apps/interpreters/ficl/Makefile index 550c2fd2d7..cbea9163a8 100644 --- a/apps/interpreters/ficl/Makefile +++ b/apps/interpreters/ficl/Makefile @@ -96,7 +96,7 @@ debug: @#echo "CFLAGS: $(CFLAGS)" .built: debug $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/modbus/Makefile b/apps/modbus/Makefile index 2b807dc48f..59e2e2526c 100644 --- a/apps/modbus/Makefile +++ b/apps/modbus/Makefile @@ -92,7 +92,7 @@ endif .built: $(OBJS) ifeq ($(CONFIG_MODBUS),y) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built endif diff --git a/apps/namedapp/Makefile b/apps/namedapp/Makefile index df80947d61..8f653a2082 100644 --- a/apps/namedapp/Makefile +++ b/apps/namedapp/Makefile @@ -79,7 +79,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) $(Q) touch .built .context: diff --git a/apps/netutils/codecs/Makefile b/apps/netutils/codecs/Makefile index c3780756df..6dcd94e9bb 100644 --- a/apps/netutils/codecs/Makefile +++ b/apps/netutils/codecs/Makefile @@ -72,7 +72,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/dhcpc/Makefile b/apps/netutils/dhcpc/Makefile index 7ab76b2191..67cad42146 100644 --- a/apps/netutils/dhcpc/Makefile +++ b/apps/netutils/dhcpc/Makefile @@ -78,7 +78,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/dhcpd/Makefile b/apps/netutils/dhcpd/Makefile index 11196bba1c..13f1215117 100644 --- a/apps/netutils/dhcpd/Makefile +++ b/apps/netutils/dhcpd/Makefile @@ -78,7 +78,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/discover/Makefile b/apps/netutils/discover/Makefile index 86e429cd50..3f5c1f71f2 100644 --- a/apps/netutils/discover/Makefile +++ b/apps/netutils/discover/Makefile @@ -81,7 +81,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/ftpc/Makefile b/apps/netutils/ftpc/Makefile index e024f3c534..65c2d59c57 100644 --- a/apps/netutils/ftpc/Makefile +++ b/apps/netutils/ftpc/Makefile @@ -94,7 +94,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/ftpd/Makefile b/apps/netutils/ftpd/Makefile index b2579a4166..9956bf97f9 100644 --- a/apps/netutils/ftpd/Makefile +++ b/apps/netutils/ftpd/Makefile @@ -78,7 +78,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/json/Makefile b/apps/netutils/json/Makefile index 99f2e81f65..4a54ab5f70 100644 --- a/apps/netutils/json/Makefile +++ b/apps/netutils/json/Makefile @@ -72,7 +72,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/resolv/Makefile b/apps/netutils/resolv/Makefile index ee9ee5dca9..d9a74989b3 100644 --- a/apps/netutils/resolv/Makefile +++ b/apps/netutils/resolv/Makefile @@ -78,7 +78,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/smtp/Makefile b/apps/netutils/smtp/Makefile index f1762a0bc2..d9e6e5c0e6 100644 --- a/apps/netutils/smtp/Makefile +++ b/apps/netutils/smtp/Makefile @@ -78,7 +78,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/telnetd/Makefile b/apps/netutils/telnetd/Makefile index 8132aa1b16..e024134ffb 100644 --- a/apps/netutils/telnetd/Makefile +++ b/apps/netutils/telnetd/Makefile @@ -78,7 +78,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/tftpc/Makefile b/apps/netutils/tftpc/Makefile index 3e5c620b65..050da06d0b 100644 --- a/apps/netutils/tftpc/Makefile +++ b/apps/netutils/tftpc/Makefile @@ -80,7 +80,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/thttpd/Makefile b/apps/netutils/thttpd/Makefile index c7550a284e..a0d5b0ea27 100644 --- a/apps/netutils/thttpd/Makefile +++ b/apps/netutils/thttpd/Makefile @@ -110,7 +110,7 @@ cgi-bin/$(SUBDIR_BIN3): cgi-bin cgi-src/$(SUBDIR_BIN3) endif .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/uiplib/Makefile b/apps/netutils/uiplib/Makefile index 2d7a1925ae..fa9296c0a6 100644 --- a/apps/netutils/uiplib/Makefile +++ b/apps/netutils/uiplib/Makefile @@ -94,7 +94,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/webclient/Makefile b/apps/netutils/webclient/Makefile index 6c05abe315..ef9dbd78be 100644 --- a/apps/netutils/webclient/Makefile +++ b/apps/netutils/webclient/Makefile @@ -78,7 +78,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/webserver/Makefile b/apps/netutils/webserver/Makefile index 13c8475bd5..26362be5d5 100644 --- a/apps/netutils/webserver/Makefile +++ b/apps/netutils/webserver/Makefile @@ -85,7 +85,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/netutils/xmlrpc/Makefile b/apps/netutils/xmlrpc/Makefile index b2e247b110..1eb3919878 100644 --- a/apps/netutils/xmlrpc/Makefile +++ b/apps/netutils/xmlrpc/Makefile @@ -79,7 +79,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile index 313a1f6cb6..afe0014195 100644 --- a/apps/nshlib/Makefile +++ b/apps/nshlib/Makefile @@ -114,7 +114,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built context: diff --git a/apps/system/free/Makefile b/apps/system/free/Makefile index 9db10f790c..a4cd506870 100644 --- a/apps/system/free/Makefile +++ b/apps/system/free/Makefile @@ -87,7 +87,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built # Register application diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile index 8e8130c134..8dd4bc5630 100644 --- a/apps/system/i2c/Makefile +++ b/apps/system/i2c/Makefile @@ -77,7 +77,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built .context: diff --git a/apps/system/install/Makefile b/apps/system/install/Makefile index 28858bf283..99de400c97 100644 --- a/apps/system/install/Makefile +++ b/apps/system/install/Makefile @@ -88,7 +88,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built # Register application diff --git a/apps/system/poweroff/Makefile b/apps/system/poweroff/Makefile index 7a9ec2ebdf..a96a600336 100644 --- a/apps/system/poweroff/Makefile +++ b/apps/system/poweroff/Makefile @@ -88,7 +88,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built # Register application diff --git a/apps/system/ramtron/Makefile b/apps/system/ramtron/Makefile index 41d1e7d45b..b300a3711a 100644 --- a/apps/system/ramtron/Makefile +++ b/apps/system/ramtron/Makefile @@ -88,7 +88,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built # Register application diff --git a/apps/system/readline/Makefile b/apps/system/readline/Makefile index 08288fa952..fb60b6fc46 100644 --- a/apps/system/readline/Makefile +++ b/apps/system/readline/Makefile @@ -78,7 +78,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built # Context build phase target diff --git a/apps/system/sdcard/Makefile b/apps/system/sdcard/Makefile index 0d7232c69a..50bf0eeb11 100644 --- a/apps/system/sdcard/Makefile +++ b/apps/system/sdcard/Makefile @@ -88,7 +88,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built # Register application diff --git a/apps/system/sysinfo/Makefile b/apps/system/sysinfo/Makefile index fafdb4e54a..a8821c7de1 100644 --- a/apps/system/sysinfo/Makefile +++ b/apps/system/sysinfo/Makefile @@ -88,7 +88,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), "$(OBJS)") + $(call ARCHIVE, $(BIN), $(OBJS)) @touch .built # Register application diff --git a/misc/pascal/nuttx/Makefile b/misc/pascal/nuttx/Makefile index 939c9322de..fc9be25e3a 100644 --- a/misc/pascal/nuttx/Makefile +++ b/misc/pascal/nuttx/Makefile @@ -110,7 +110,7 @@ $(APPDIR)/include/pcode/insn: $(APPDIR)/include/pcode insn/include @$(DIRLINK) $(PCODEDIR)/insn/include $(APPDIR)/include/pcode/insn .built: $(APPDIR)/include/pcode $(APPDIR)/include/pcode/insn $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) @touch .built context: $(APPDIR)/include/pcode $(APPDIR)/include/pcode/insn diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index e602d2cd37..50cc0ace56 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -701,17 +701,30 @@ makefiles in the build (once it is installed). This make fragment should define:

      -
    • Tools: CC, LD, AR, NM, OBJCOPY, OBJDUMP
    • -
    • Tool options: CFLAGS, LDFLAGS
    • -
    • COMPILE, ASSEMBLE, ARCHIVE, CLEAN, and MKDEP macros
    • +
    • Tools: CC, LD, AR, NM, OBJCOPY, OBJDUMP
    • +
    • Tool options: CFLAGS, LDFLAGS

    - When this makefile fragment runs, it will be passed TOPDIR which + When this makefile fragment runs, it will be passed TOPDIR which is the path to the root directory of the build. This makefile - fragment may include ${TOPDIR}/.config to perform configuration - specific settings. For example, the CFLAGS will most likely be - different if CONFIG_DEBUG=y. + fragment should include:

    +
      +
    • $(TOPDIR)/.config : Nuttx configuration
    • +
    • $(TOPDIR)/tools/Config.mk : Common definitions
    • +
    +

    + Definitions in the Make.defs file probably depend on some of the + settings in the .config file. For example, the CFLAGS will most likely be + different if CONFIG_DEBUG=y. +

    +

    + The included tools/Config.mk file contains additional definitions that may + be overriden in the architecture-specific Make.defs file as necessary: +

    +
      +
    • COMPILE, ASSEMBLE, ARCHIVE, CLEAN, and MKDEP macros
    • +
  • diff --git a/nuttx/arch/8051/src/Makefile b/nuttx/arch/8051/src/Makefile index f228b46972..0f1b1b8577 100644 --- a/nuttx/arch/8051/src/Makefile +++ b/nuttx/arch/8051/src/Makefile @@ -148,7 +148,7 @@ up_mem.h: pass1.mem # Combine all objects in this directory into a library libarch$(LIBEXT): up_mem.h $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) # This is a kludge to work around some conflicting symbols in libsdcc.liXqueb diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index 243b5761ea..ba506d4da1 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -132,7 +132,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libarch$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile index 067a99c372..462968ed53 100644 --- a/nuttx/arch/avr/src/Makefile +++ b/nuttx/arch/avr/src/Makefile @@ -130,7 +130,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libarch$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile index 13788b71df..0ada6c4c2c 100644 --- a/nuttx/arch/hc/src/Makefile +++ b/nuttx/arch/hc/src/Makefile @@ -125,7 +125,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libarch$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile index c4a73e3923..057b95d220 100644 --- a/nuttx/arch/mips/src/Makefile +++ b/nuttx/arch/mips/src/Makefile @@ -123,7 +123,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libarch$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) diff --git a/nuttx/arch/rgmp/src/Makefile b/nuttx/arch/rgmp/src/Makefile index 4df7a9ce61..7650a0a942 100644 --- a/nuttx/arch/rgmp/src/Makefile +++ b/nuttx/arch/rgmp/src/Makefile @@ -70,7 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c # The architecture-specific library libarch$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) # Generate the final NuttX binary by linking the host-specific objects with the NuttX # specific objects (with munged names) diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile index c096bb0da4..132ca4610e 100644 --- a/nuttx/arch/sh/src/Makefile +++ b/nuttx/arch/sh/src/Makefile @@ -121,7 +121,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libarch$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile index d46defe135..a5d6100a3f 100644 --- a/nuttx/arch/sim/src/Makefile +++ b/nuttx/arch/sim/src/Makefile @@ -155,7 +155,7 @@ $(HOSTOBJS): %$(OBJEXT): %.c # The architecture-specific library libarch$(LIBEXT): $(NUTTXOBJS) - $(call ARCHIVE, $@, "$(NUTTXOBJS)") + $(call ARCHIVE, $@, $(NUTTXOBJS)) # The "board"-specific library. Of course, there really are no boards in # the simulation. However, this is a good place to keep parts of the simulation diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile index 7ee92e8384..19193709cc 100644 --- a/nuttx/arch/x86/src/Makefile +++ b/nuttx/arch/x86/src/Makefile @@ -131,7 +131,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libarch$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) diff --git a/nuttx/arch/z16/src/Makefile b/nuttx/arch/z16/src/Makefile index 3e2f487ffa..a2a441f742 100644 --- a/nuttx/arch/z16/src/Makefile +++ b/nuttx/arch/z16/src/Makefile @@ -88,7 +88,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libarch$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) board/libboard$(LIBEXT): @$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) diff --git a/nuttx/arch/z80/src/Makefile.sdcc b/nuttx/arch/z80/src/Makefile.sdcc index 5527bcb55c..7c9f45a6c7 100644 --- a/nuttx/arch/z80/src/Makefile.sdcc +++ b/nuttx/arch/z80/src/Makefile.sdcc @@ -134,7 +134,7 @@ endif # Combine all objects in this directory into a library libarch$(LIBEXT): up_mem.h asm_mem.h $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) # This builds the libboard library in the board/ subdirectory diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii index 93d80d2ddb..666af89452 100644 --- a/nuttx/arch/z80/src/Makefile.zdsii +++ b/nuttx/arch/z80/src/Makefile.zdsii @@ -86,7 +86,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libarch$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) board/libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile index 378a737f60..06def551f1 100644 --- a/nuttx/binfmt/Makefile +++ b/nuttx/binfmt/Makefile @@ -78,7 +78,7 @@ $(BINFMT_COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(BINFMT_OBJS) - $(call ARCHIVE, $@, "$(BINFMT_OBJS)") + $(call ARCHIVE, $@, $(BINFMT_OBJS)) .depend: Makefile $(BINFMT_SRCS) $(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 81749f29fc..575eb690ab 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -103,14 +103,23 @@ Make.defs -- This makefile fragment provides architecture and Tools: CC, LD, AR, NM, OBJCOPY, OBJDUMP Tool options: CFLAGS, LDFLAGS - COMPILE, ASSEMBLE, ARCHIVE, CLEAN, and MKDEP macros When this makefile fragment runs, it will be passed TOPDIR which is the path to the root directory of the build. This makefile - fragment may include ${TOPDIR}/.config to perform configuration - specific settings. For example, the CFLAGS will most likely be + fragment should include: + + $(TOPDIR)/.config : Nuttx configuration + $(TOPDIR)/tools/Config.mk : Common definitions + + Definitions in the Make.defs file probably depend on some of the + settings in the .config file. For example, the CFLAGS will most likely be different if CONFIG_DEBUG=y. + The included tools/Config.mk file contains additional definitions that may + be overriden in the architecture-specific Make.defs file as necessary: + + COMPILE, ASSEMBLE, ARCHIVE, CLEAN, and MKDEP macros + defconfig -- This is a configuration file similar to the Linux configuration file. In contains variable/value pairs like: diff --git a/nuttx/configs/amber/src/Makefile b/nuttx/configs/amber/src/Makefile index 358e4dec33..befcee2134 100644 --- a/nuttx/configs/amber/src/Makefile +++ b/nuttx/configs/amber/src/Makefile @@ -77,7 +77,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/avr32dev1/src/Makefile b/nuttx/configs/avr32dev1/src/Makefile index b997d7a444..1abc7c7b92 100644 --- a/nuttx/configs/avr32dev1/src/Makefile +++ b/nuttx/configs/avr32dev1/src/Makefile @@ -70,7 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/c5471evm/src/Makefile b/nuttx/configs/c5471evm/src/Makefile index 284bfb91d7..42c87ccab9 100644 --- a/nuttx/configs/c5471evm/src/Makefile +++ b/nuttx/configs/c5471evm/src/Makefile @@ -57,7 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/compal_e88/src/Makefile b/nuttx/configs/compal_e88/src/Makefile index e60d599d9e..8394fd47d2 100644 --- a/nuttx/configs/compal_e88/src/Makefile +++ b/nuttx/configs/compal_e88/src/Makefile @@ -60,7 +60,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/compal_e99/src/Makefile b/nuttx/configs/compal_e99/src/Makefile index adaf8b801d..915786222d 100644 --- a/nuttx/configs/compal_e99/src/Makefile +++ b/nuttx/configs/compal_e99/src/Makefile @@ -60,7 +60,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/demo9s12ne64/src/Makefile b/nuttx/configs/demo9s12ne64/src/Makefile index e9fcd7f41f..fc33ef32c9 100644 --- a/nuttx/configs/demo9s12ne64/src/Makefile +++ b/nuttx/configs/demo9s12ne64/src/Makefile @@ -66,7 +66,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/ea3131/src/Makefile b/nuttx/configs/ea3131/src/Makefile index 57011f08a7..8b628a0ebc 100644 --- a/nuttx/configs/ea3131/src/Makefile +++ b/nuttx/configs/ea3131/src/Makefile @@ -85,7 +85,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/ea3152/src/Makefile b/nuttx/configs/ea3152/src/Makefile index 088ce63d8f..c360856475 100644 --- a/nuttx/configs/ea3152/src/Makefile +++ b/nuttx/configs/ea3152/src/Makefile @@ -85,7 +85,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/eagle100/src/Makefile b/nuttx/configs/eagle100/src/Makefile index c2b1437eee..3bb71aa89e 100644 --- a/nuttx/configs/eagle100/src/Makefile +++ b/nuttx/configs/eagle100/src/Makefile @@ -66,7 +66,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/ekk-lm3s9b96/src/Makefile b/nuttx/configs/ekk-lm3s9b96/src/Makefile index a5e4f197f4..a012fcc255 100644 --- a/nuttx/configs/ekk-lm3s9b96/src/Makefile +++ b/nuttx/configs/ekk-lm3s9b96/src/Makefile @@ -68,7 +68,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/ez80f910200kitg/ostest/Make.defs b/nuttx/configs/ez80f910200kitg/ostest/Make.defs index 0914bc17aa..4eaf34fe01 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/Make.defs +++ b/nuttx/configs/ez80f910200kitg/ostest/Make.defs @@ -166,11 +166,11 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done diff --git a/nuttx/configs/ez80f910200kitg/src/Makefile b/nuttx/configs/ez80f910200kitg/src/Makefile index 8a9d94e47a..a5515d855b 100644 --- a/nuttx/configs/ez80f910200kitg/src/Makefile +++ b/nuttx/configs/ez80f910200kitg/src/Makefile @@ -64,7 +64,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/ez80f910200zco/dhcpd/Make.defs b/nuttx/configs/ez80f910200zco/dhcpd/Make.defs index 59f32fb457..326ea137b2 100644 --- a/nuttx/configs/ez80f910200zco/dhcpd/Make.defs +++ b/nuttx/configs/ez80f910200zco/dhcpd/Make.defs @@ -166,16 +166,17 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done endef endif +endif define CLEAN $(Q) rm -f *.obj *.src *.lib *.hex *.lod *.lst diff --git a/nuttx/configs/ez80f910200zco/httpd/Make.defs b/nuttx/configs/ez80f910200zco/httpd/Make.defs index 615939026c..6a30c70004 100644 --- a/nuttx/configs/ez80f910200zco/httpd/Make.defs +++ b/nuttx/configs/ez80f910200zco/httpd/Make.defs @@ -166,11 +166,11 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done diff --git a/nuttx/configs/ez80f910200zco/nettest/Make.defs b/nuttx/configs/ez80f910200zco/nettest/Make.defs index ea309af75a..ce32366643 100644 --- a/nuttx/configs/ez80f910200zco/nettest/Make.defs +++ b/nuttx/configs/ez80f910200zco/nettest/Make.defs @@ -166,11 +166,11 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done diff --git a/nuttx/configs/ez80f910200zco/nsh/Make.defs b/nuttx/configs/ez80f910200zco/nsh/Make.defs index 91c900b33f..9dbaceb645 100644 --- a/nuttx/configs/ez80f910200zco/nsh/Make.defs +++ b/nuttx/configs/ez80f910200zco/nsh/Make.defs @@ -166,11 +166,11 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done diff --git a/nuttx/configs/ez80f910200zco/ostest/Make.defs b/nuttx/configs/ez80f910200zco/ostest/Make.defs index 5cc8356129..6a49cbc573 100644 --- a/nuttx/configs/ez80f910200zco/ostest/Make.defs +++ b/nuttx/configs/ez80f910200zco/ostest/Make.defs @@ -166,11 +166,11 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done diff --git a/nuttx/configs/ez80f910200zco/poll/Make.defs b/nuttx/configs/ez80f910200zco/poll/Make.defs index 2cd6fa5d38..fd32a6df63 100644 --- a/nuttx/configs/ez80f910200zco/poll/Make.defs +++ b/nuttx/configs/ez80f910200zco/poll/Make.defs @@ -166,11 +166,11 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done diff --git a/nuttx/configs/ez80f910200zco/src/Makefile b/nuttx/configs/ez80f910200zco/src/Makefile index 85489fe91a..faaec39ef7 100644 --- a/nuttx/configs/ez80f910200zco/src/Makefile +++ b/nuttx/configs/ez80f910200zco/src/Makefile @@ -71,7 +71,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/fire-stm32v2/src/Makefile b/nuttx/configs/fire-stm32v2/src/Makefile index 2045de7934..2fa9039ce0 100644 --- a/nuttx/configs/fire-stm32v2/src/Makefile +++ b/nuttx/configs/fire-stm32v2/src/Makefile @@ -107,7 +107,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/hymini-stm32v/src/Makefile b/nuttx/configs/hymini-stm32v/src/Makefile index 54d0f9339e..42b16287ca 100644 --- a/nuttx/configs/hymini-stm32v/src/Makefile +++ b/nuttx/configs/hymini-stm32v/src/Makefile @@ -86,7 +86,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/kwikstik-k40/src/Makefile b/nuttx/configs/kwikstik-k40/src/Makefile index d8373e1ab1..dda93719d0 100644 --- a/nuttx/configs/kwikstik-k40/src/Makefile +++ b/nuttx/configs/kwikstik-k40/src/Makefile @@ -85,7 +85,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/lincoln60/src/Makefile b/nuttx/configs/lincoln60/src/Makefile index 3820e5cd50..b31f42ba41 100644 --- a/nuttx/configs/lincoln60/src/Makefile +++ b/nuttx/configs/lincoln60/src/Makefile @@ -76,7 +76,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/lm3s6432-s2e/src/Makefile b/nuttx/configs/lm3s6432-s2e/src/Makefile index c1290f6c24..64faf3a778 100644 --- a/nuttx/configs/lm3s6432-s2e/src/Makefile +++ b/nuttx/configs/lm3s6432-s2e/src/Makefile @@ -67,7 +67,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/lm3s6965-ek/src/Makefile b/nuttx/configs/lm3s6965-ek/src/Makefile index 2e560c0044..12750d192a 100644 --- a/nuttx/configs/lm3s6965-ek/src/Makefile +++ b/nuttx/configs/lm3s6965-ek/src/Makefile @@ -70,7 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/lm3s8962-ek/src/Makefile b/nuttx/configs/lm3s8962-ek/src/Makefile index eaf5eeae19..8b1400ea0d 100644 --- a/nuttx/configs/lm3s8962-ek/src/Makefile +++ b/nuttx/configs/lm3s8962-ek/src/Makefile @@ -70,7 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/lpc4330-xplorer/src/Makefile b/nuttx/configs/lpc4330-xplorer/src/Makefile index d4f4d6686a..9698f78fc6 100644 --- a/nuttx/configs/lpc4330-xplorer/src/Makefile +++ b/nuttx/configs/lpc4330-xplorer/src/Makefile @@ -104,7 +104,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile index 51aa1a7ca7..d1012b8a90 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile +++ b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile @@ -76,7 +76,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/m68332evb/src/Makefile b/nuttx/configs/m68332evb/src/Makefile index 0644837339..46a06c71ab 100644 --- a/nuttx/configs/m68332evb/src/Makefile +++ b/nuttx/configs/m68332evb/src/Makefile @@ -54,7 +54,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/mbed/src/Makefile b/nuttx/configs/mbed/src/Makefile index 9d2d489fec..31b5df171d 100644 --- a/nuttx/configs/mbed/src/Makefile +++ b/nuttx/configs/mbed/src/Makefile @@ -70,7 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/mcu123-lpc214x/src/Makefile b/nuttx/configs/mcu123-lpc214x/src/Makefile index 26c2c14483..62ff003a16 100644 --- a/nuttx/configs/mcu123-lpc214x/src/Makefile +++ b/nuttx/configs/mcu123-lpc214x/src/Makefile @@ -77,7 +77,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/micropendous3/src/Makefile b/nuttx/configs/micropendous3/src/Makefile index c926415f5e..3041fb282d 100644 --- a/nuttx/configs/micropendous3/src/Makefile +++ b/nuttx/configs/micropendous3/src/Makefile @@ -77,7 +77,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/mirtoo/src/Makefile b/nuttx/configs/mirtoo/src/Makefile index 29b91f4699..9bda8246df 100644 --- a/nuttx/configs/mirtoo/src/Makefile +++ b/nuttx/configs/mirtoo/src/Makefile @@ -76,7 +76,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/mx1ads/src/Makefile b/nuttx/configs/mx1ads/src/Makefile index 9e4d8c99a8..e55195649a 100644 --- a/nuttx/configs/mx1ads/src/Makefile +++ b/nuttx/configs/mx1ads/src/Makefile @@ -57,7 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/ne64badge/src/Makefile b/nuttx/configs/ne64badge/src/Makefile index bfd838bdf7..52cd7897b1 100644 --- a/nuttx/configs/ne64badge/src/Makefile +++ b/nuttx/configs/ne64badge/src/Makefile @@ -66,7 +66,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/ntosd-dm320/src/Makefile b/nuttx/configs/ntosd-dm320/src/Makefile index d57d94ce85..114e5bf997 100644 --- a/nuttx/configs/ntosd-dm320/src/Makefile +++ b/nuttx/configs/ntosd-dm320/src/Makefile @@ -57,7 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/nucleus2g/src/Makefile b/nuttx/configs/nucleus2g/src/Makefile index bc21b12499..1f2c02fd1e 100644 --- a/nuttx/configs/nucleus2g/src/Makefile +++ b/nuttx/configs/nucleus2g/src/Makefile @@ -70,7 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/olimex-lpc1766stk/src/Makefile b/nuttx/configs/olimex-lpc1766stk/src/Makefile index 326fe52e41..955c80937e 100644 --- a/nuttx/configs/olimex-lpc1766stk/src/Makefile +++ b/nuttx/configs/olimex-lpc1766stk/src/Makefile @@ -84,7 +84,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/olimex-lpc2378/src/Makefile b/nuttx/configs/olimex-lpc2378/src/Makefile index 46ad0e45e5..12cddf95be 100644 --- a/nuttx/configs/olimex-lpc2378/src/Makefile +++ b/nuttx/configs/olimex-lpc2378/src/Makefile @@ -73,7 +73,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/olimex-stm32-p107/src/Makefile b/nuttx/configs/olimex-stm32-p107/src/Makefile index 7bf68b7613..a0d6fc5ff1 100644 --- a/nuttx/configs/olimex-stm32-p107/src/Makefile +++ b/nuttx/configs/olimex-stm32-p107/src/Makefile @@ -69,7 +69,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/olimex-strp711/src/Makefile b/nuttx/configs/olimex-strp711/src/Makefile index ef6105a5f7..766305c03b 100644 --- a/nuttx/configs/olimex-strp711/src/Makefile +++ b/nuttx/configs/olimex-strp711/src/Makefile @@ -70,7 +70,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/pcblogic-pic32mx/src/Makefile b/nuttx/configs/pcblogic-pic32mx/src/Makefile index d97e4cc26a..6eda3248bb 100644 --- a/nuttx/configs/pcblogic-pic32mx/src/Makefile +++ b/nuttx/configs/pcblogic-pic32mx/src/Makefile @@ -68,7 +68,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/pic32-starterkit/src/Makefile b/nuttx/configs/pic32-starterkit/src/Makefile index 5e02f53315..a1ee69b929 100644 --- a/nuttx/configs/pic32-starterkit/src/Makefile +++ b/nuttx/configs/pic32-starterkit/src/Makefile @@ -79,7 +79,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/pic32mx7mmb/src/Makefile b/nuttx/configs/pic32mx7mmb/src/Makefile index 3c31060fdf..92445604ed 100644 --- a/nuttx/configs/pic32mx7mmb/src/Makefile +++ b/nuttx/configs/pic32mx7mmb/src/Makefile @@ -83,7 +83,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/pjrc-8051/src/Makefile b/nuttx/configs/pjrc-8051/src/Makefile index db95dc450f..5d9b553692 100644 --- a/nuttx/configs/pjrc-8051/src/Makefile +++ b/nuttx/configs/pjrc-8051/src/Makefile @@ -56,7 +56,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/qemu-i486/src/Makefile b/nuttx/configs/qemu-i486/src/Makefile index 1df02f58e3..785b78be7a 100644 --- a/nuttx/configs/qemu-i486/src/Makefile +++ b/nuttx/configs/qemu-i486/src/Makefile @@ -63,7 +63,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/sam3u-ek/src/Makefile b/nuttx/configs/sam3u-ek/src/Makefile index 7d4433e81d..97227b40a4 100644 --- a/nuttx/configs/sam3u-ek/src/Makefile +++ b/nuttx/configs/sam3u-ek/src/Makefile @@ -76,7 +76,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile index 1c1d000f9f..ad4c1d7718 100644 --- a/nuttx/configs/shenzhou/src/Makefile +++ b/nuttx/configs/shenzhou/src/Makefile @@ -127,7 +127,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/sim/src/Makefile b/nuttx/configs/sim/src/Makefile index b5c101d29f..9b924486d0 100644 --- a/nuttx/configs/sim/src/Makefile +++ b/nuttx/configs/sim/src/Makefile @@ -62,7 +62,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c libboard$(LIBEXT): $(OBJS) @$(AR) $@ # Create an empty archive ifneq ($(OBJS),) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) endif .depend: Makefile $(SRCS) diff --git a/nuttx/configs/skp16c26/src/Makefile b/nuttx/configs/skp16c26/src/Makefile index 64a976ce8f..21a528c04c 100644 --- a/nuttx/configs/skp16c26/src/Makefile +++ b/nuttx/configs/skp16c26/src/Makefile @@ -57,7 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/stm3210e-eval/src/Makefile b/nuttx/configs/stm3210e-eval/src/Makefile index 70bf589be1..e9af34f213 100644 --- a/nuttx/configs/stm3210e-eval/src/Makefile +++ b/nuttx/configs/stm3210e-eval/src/Makefile @@ -111,7 +111,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/stm3220g-eval/src/Makefile b/nuttx/configs/stm3220g-eval/src/Makefile index 7fb3910441..1a670588f8 100644 --- a/nuttx/configs/stm3220g-eval/src/Makefile +++ b/nuttx/configs/stm3220g-eval/src/Makefile @@ -111,7 +111,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/stm3240g-eval/src/Makefile b/nuttx/configs/stm3240g-eval/src/Makefile index 40c3b8769b..8ea4690c55 100644 --- a/nuttx/configs/stm3240g-eval/src/Makefile +++ b/nuttx/configs/stm3240g-eval/src/Makefile @@ -119,7 +119,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/stm32f100rc_generic/src/Makefile b/nuttx/configs/stm32f100rc_generic/src/Makefile index 16d72dd0d8..c0916f40cb 100644 --- a/nuttx/configs/stm32f100rc_generic/src/Makefile +++ b/nuttx/configs/stm32f100rc_generic/src/Makefile @@ -63,7 +63,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/stm32f4discovery/src/Makefile b/nuttx/configs/stm32f4discovery/src/Makefile index 2f9a4baefb..b6d0f6226d 100644 --- a/nuttx/configs/stm32f4discovery/src/Makefile +++ b/nuttx/configs/stm32f4discovery/src/Makefile @@ -123,7 +123,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/sure-pic32mx/src/Makefile b/nuttx/configs/sure-pic32mx/src/Makefile index 28ae67c63b..3c8e5277bd 100644 --- a/nuttx/configs/sure-pic32mx/src/Makefile +++ b/nuttx/configs/sure-pic32mx/src/Makefile @@ -88,7 +88,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/teensy/src/Makefile b/nuttx/configs/teensy/src/Makefile index 11faf9491b..a1e6a6e05c 100644 --- a/nuttx/configs/teensy/src/Makefile +++ b/nuttx/configs/teensy/src/Makefile @@ -83,7 +83,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/twr-k60n512/src/Makefile b/nuttx/configs/twr-k60n512/src/Makefile index 4737686587..3c036b0886 100644 --- a/nuttx/configs/twr-k60n512/src/Makefile +++ b/nuttx/configs/twr-k60n512/src/Makefile @@ -85,7 +85,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/ubw32/src/Makefile b/nuttx/configs/ubw32/src/Makefile index a89ede256d..49243ab83a 100644 --- a/nuttx/configs/ubw32/src/Makefile +++ b/nuttx/configs/ubw32/src/Makefile @@ -79,7 +79,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/us7032evb1/src/Makefile b/nuttx/configs/us7032evb1/src/Makefile index 7bb51b9b28..cd4fc1b746 100644 --- a/nuttx/configs/us7032evb1/src/Makefile +++ b/nuttx/configs/us7032evb1/src/Makefile @@ -57,7 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/vsn/src/Makefile b/nuttx/configs/vsn/src/Makefile index 657f016b25..917dcbd7a9 100644 --- a/nuttx/configs/vsn/src/Makefile +++ b/nuttx/configs/vsn/src/Makefile @@ -81,7 +81,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) # Register application diff --git a/nuttx/configs/xtrs/src/Makefile b/nuttx/configs/xtrs/src/Makefile index 7715fbb0af..0662e145e3 100644 --- a/nuttx/configs/xtrs/src/Makefile +++ b/nuttx/configs/xtrs/src/Makefile @@ -57,7 +57,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/z16f2800100zcog/ostest/Make.defs b/nuttx/configs/z16f2800100zcog/ostest/Make.defs index 79fa655bb5..8589b5566a 100644 --- a/nuttx/configs/z16f2800100zcog/ostest/Make.defs +++ b/nuttx/configs/z16f2800100zcog/ostest/Make.defs @@ -158,11 +158,11 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done diff --git a/nuttx/configs/z16f2800100zcog/pashello/Make.defs b/nuttx/configs/z16f2800100zcog/pashello/Make.defs index d7b93d659d..3620ffcbe7 100644 --- a/nuttx/configs/z16f2800100zcog/pashello/Make.defs +++ b/nuttx/configs/z16f2800100zcog/pashello/Make.defs @@ -158,11 +158,11 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done diff --git a/nuttx/configs/z16f2800100zcog/src/Makefile b/nuttx/configs/z16f2800100zcog/src/Makefile index 43695f7482..8c5bfd1e85 100644 --- a/nuttx/configs/z16f2800100zcog/src/Makefile +++ b/nuttx/configs/z16f2800100zcog/src/Makefile @@ -64,7 +64,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/z80sim/src/Makefile b/nuttx/configs/z80sim/src/Makefile index 65d9db9a48..2dc3a785ca 100644 --- a/nuttx/configs/z80sim/src/Makefile +++ b/nuttx/configs/z80sim/src/Makefile @@ -56,7 +56,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/z8encore000zco/ostest/Make.defs b/nuttx/configs/z8encore000zco/ostest/Make.defs index fba1018645..9e89220f8c 100644 --- a/nuttx/configs/z8encore000zco/ostest/Make.defs +++ b/nuttx/configs/z8encore000zco/ostest/Make.defs @@ -191,11 +191,11 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done diff --git a/nuttx/configs/z8encore000zco/src/Makefile b/nuttx/configs/z8encore000zco/src/Makefile index a40b6f42c1..e274e7b83f 100644 --- a/nuttx/configs/z8encore000zco/src/Makefile +++ b/nuttx/configs/z8encore000zco/src/Makefile @@ -64,7 +64,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/configs/z8f64200100kit/ostest/Make.defs b/nuttx/configs/z8f64200100kit/ostest/Make.defs index 4fa6af2ec2..899f3955c7 100644 --- a/nuttx/configs/z8f64200100kit/ostest/Make.defs +++ b/nuttx/configs/z8f64200100kit/ostest/Make.defs @@ -191,11 +191,11 @@ endef ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE echo "AR: $2"; - $(Q) for %%G in ($(subst ",,$(2))) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) endef else define ARCHIVE - $(Q) for __obj in $(subst ",,$(2)) ; do \ + $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done diff --git a/nuttx/configs/z8f64200100kit/src/Makefile b/nuttx/configs/z8f64200100kit/src/Makefile index a8b618b6f5..da104cedf2 100644 --- a/nuttx/configs/z8f64200100kit/src/Makefile +++ b/nuttx/configs/z8f64200100kit/src/Makefile @@ -64,7 +64,7 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile index 3a6e340223..98bb8a7d0f 100644 --- a/nuttx/drivers/Makefile +++ b/nuttx/drivers/Makefile @@ -102,7 +102,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) $(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile index b79b1734d8..b55ec6218b 100644 --- a/nuttx/fs/Makefile +++ b/nuttx/fs/Makefile @@ -120,7 +120,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) $(Q) $(MKDEP) --dep-path . $(MMAPDEPPATH) $(FATDEPPATH) $(ROMFSDEPPATH) $(NXFFSDEPPATH) $(NFSDEPPATH) \ diff --git a/nuttx/graphics/Makefile b/nuttx/graphics/Makefile index 09d7cfa266..d0fdb647dd 100644 --- a/nuttx/graphics/Makefile +++ b/nuttx/graphics/Makefile @@ -186,7 +186,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) mklibgraphics: gensources $(BIN) diff --git a/nuttx/libc/Makefile b/nuttx/libc/Makefile index ac8fe4bc7a..313629f2b8 100644 --- a/nuttx/libc/Makefile +++ b/nuttx/libc/Makefile @@ -79,7 +79,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) ifneq ($(BIN),$(UBIN)) .userlib: @@ -108,7 +108,11 @@ depend: .depend uclean: ifneq ($(OBJEXT),) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + $(Q) if exist .userlib ]; then del *$(OBJEXT) +else $(Q) ( if [ -f .userlib ]; then rm -f *$(OBJEXT); fi ) +endif endif $(Q) rm -f .userlib *~ .*.swp @@ -116,7 +120,11 @@ endif kclean: ifneq ($(OBJEXT),) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + $(Q) if exist .kernlib ]; then del *$(OBJEXT) +else $(Q) ( if [ -f .kernlib ]; then rm -f *$(OBJEXT); fi ) +endif endif $(Q) rm -f .kernlib *~ .*.swp diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile index e5fff1c479..6093ad4902 100644 --- a/nuttx/libxx/Makefile +++ b/nuttx/libxx/Makefile @@ -96,7 +96,7 @@ $(CXXOBJS): %$(OBJEXT): %.cxx $(call COMPILEXX, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) $(Q) $(MKDEP) $(DEPPATH) "$(CXX)" -- $(CXXFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile index fef9cc9ddc..8cdfb4d279 100644 --- a/nuttx/mm/Makefile +++ b/nuttx/mm/Makefile @@ -61,7 +61,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) $(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile index 5ce4de4ccb..aed5734dfc 100644 --- a/nuttx/net/Makefile +++ b/nuttx/net/Makefile @@ -100,7 +100,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) ifeq ($(CONFIG_NET),y) diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 571393cb20..601ba58193 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -196,7 +196,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, "$(OBJS)") + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) $(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep @@ -205,7 +205,7 @@ $(BIN): $(OBJS) depend: .depend clean: - $(Q) rm -f $(BIN) *~ .*.swp + $(Q) rm -f $(BIN) $(call CLEAN) distclean: clean diff --git a/nuttx/syscall/Makefile b/nuttx/syscall/Makefile index 0de895cde7..a21eb04ee7 100644 --- a/nuttx/syscall/Makefile +++ b/nuttx/syscall/Makefile @@ -72,7 +72,7 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN1): $(PROXY_OBJS) - $(call ARCHIVE, $@, "$(PROXY_OBJS)") + $(call ARCHIVE, $@, $(PROXY_OBJS)) $(BIN2): $(STUB_OBJS) $(call ARCHIVE, $@, "$(STUB_OBJS)") diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk index 3a0714c10a..b7f8d9bbe0 100644 --- a/nuttx/tools/Config.mk +++ b/nuttx/tools/Config.mk @@ -145,15 +145,19 @@ ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE @echo "AR: $2" $(AR) $1 - $(Q) $(AR) $1 $(subst ",,$(2)) + $(Q) $(AR) $1 $(2) endef else define ARCHIVE @echo "AR: $2" - $(Q) $(AR) $1 $(subst ",,$(2)) || { echo "$(AR) $1 FAILED!" ; exit 1 ; } + $(Q) $(AR) $1 $(2) || { echo "$(AR) $1 FAILED!" ; exit 1 ; } endef endif define CLEAN +ifeq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) rm -f *.o *.a +else + $(Q) rm -f *.o *.a *~ .*.swp +endif endef From 98c0270edecaaca7d0f4ad387cce7c91a4ddbbd9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 15 Nov 2012 18:33:18 +0000 Subject: [PATCH 128/206] More changes for Mike git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5357 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/amber/hello/Make.defs | 2 +- nuttx/configs/avr32dev1/nsh/Make.defs | 3 +-- nuttx/configs/avr32dev1/ostest/Make.defs | 3 +-- nuttx/configs/c5471evm/httpd/Make.defs | 5 ++--- nuttx/configs/c5471evm/nettest/Make.defs | 5 ++--- nuttx/configs/c5471evm/nsh/Make.defs | 5 ++--- nuttx/configs/c5471evm/ostest/Make.defs | 5 ++--- nuttx/configs/compal_e88/nsh_highram/Make.defs | 4 ++-- nuttx/configs/compal_e99/nsh_compalram/Make.defs | 4 ++-- nuttx/configs/compal_e99/nsh_highram/Make.defs | 4 ++-- 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/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/nsh/Make.defs | 2 +- nuttx/configs/ekk-lm3s9b96/ostest/Make.defs | 2 +- nuttx/configs/ez80f910200kitg/ostest/Make.defs | 4 ++-- nuttx/configs/ez80f910200zco/dhcpd/Make.defs | 4 ++-- nuttx/configs/ez80f910200zco/httpd/Make.defs | 4 ++-- nuttx/configs/ez80f910200zco/nettest/Make.defs | 4 ++-- nuttx/configs/ez80f910200zco/nsh/Make.defs | 4 ++-- nuttx/configs/ez80f910200zco/ostest/Make.defs | 4 ++-- nuttx/configs/ez80f910200zco/poll/Make.defs | 4 ++-- nuttx/configs/fire-stm32v2/nsh/Make.defs | 2 +- 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/ostest/Make.defs | 2 +- nuttx/configs/lincoln60/nsh/Make.defs | 2 +- nuttx/configs/lincoln60/ostest/Make.defs | 2 +- nuttx/configs/lm3s6432-s2e/nsh/Make.defs | 2 +- nuttx/configs/lm3s6432-s2e/ostest/Make.defs | 2 +- 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/nsh/Make.defs | 2 +- nuttx/configs/lm3s8962-ek/nx/Make.defs | 2 +- nuttx/configs/lm3s8962-ek/ostest/Make.defs | 2 +- nuttx/configs/lpc4330-xplorer/nsh/Make.defs | 2 +- nuttx/configs/lpc4330-xplorer/ostest/Make.defs | 2 +- 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 | 2 +- nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs | 2 +- nuttx/configs/m68332evb/Make.defs | 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 | 4 ++-- 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 | 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/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 +- nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs | 2 +- nuttx/configs/olimex-lpc1766stk/wlan/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/pjrc-8051/Make.defs | 2 +- nuttx/configs/qemu-i486/nsh/Make.defs | 2 +- nuttx/configs/qemu-i486/ostest/Make.defs | 2 +- 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/nsh/Make.defs | 2 +- nuttx/configs/shenzhou/nxwm/Make.defs | 2 +- nuttx/configs/shenzhou/thttpd/Make.defs | 2 +- nuttx/configs/skp16c26/ostest/Make.defs | 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/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/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/stm32f100rc_generic/nsh/Make.defs | 2 +- nuttx/configs/stm32f100rc_generic/ostest/Make.defs | 2 +- nuttx/configs/stm32f4discovery/cxxtest/Make.defs | 2 +- nuttx/configs/stm32f4discovery/elf/Make.defs | 2 +- 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/stm32f4discovery/winbuild/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/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/us7032evb1/nsh/Make.defs | 4 ++-- nuttx/configs/us7032evb1/ostest/Make.defs | 4 ++-- nuttx/configs/vsn/nsh/Make.defs | 2 +- nuttx/configs/z16f2800100zcog/ostest/Make.defs | 4 ++-- nuttx/configs/z16f2800100zcog/pashello/Make.defs | 4 ++-- nuttx/configs/z8encore000zco/ostest/Make.defs | 4 ++-- nuttx/configs/z8f64200100kit/ostest/Make.defs | 4 ++-- 176 files changed, 199 insertions(+), 205 deletions(-) diff --git a/nuttx/configs/amber/hello/Make.defs b/nuttx/configs/amber/hello/Make.defs index 1c2d8b89e1..15c31f1923 100644 --- a/nuttx/configs/amber/hello/Make.defs +++ b/nuttx/configs/amber/hello/Make.defs @@ -88,7 +88,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/avr32dev1/nsh/Make.defs b/nuttx/configs/avr32dev1/nsh/Make.defs index 46fef6ec1e..aa84884d06 100644 --- a/nuttx/configs/avr32dev1/nsh/Make.defs +++ b/nuttx/configs/avr32dev1/nsh/Make.defs @@ -78,7 +78,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -ffunction-sections -fdata-sections -fno-strict-aliasing @@ -110,7 +110,6 @@ ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif - HOSTCC = gcc HOSTINCLUDES = -I. HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe diff --git a/nuttx/configs/avr32dev1/ostest/Make.defs b/nuttx/configs/avr32dev1/ostest/Make.defs index ad74d889cc..ab8c9cd36c 100644 --- a/nuttx/configs/avr32dev1/ostest/Make.defs +++ b/nuttx/configs/avr32dev1/ostest/Make.defs @@ -78,7 +78,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -ffunction-sections -fdata-sections -fno-strict-aliasing @@ -110,7 +110,6 @@ ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif - HOSTCC = gcc HOSTINCLUDES = -I. HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe diff --git a/nuttx/configs/c5471evm/httpd/Make.defs b/nuttx/configs/c5471evm/httpd/Make.defs index 4d94d83427..45a567ec43 100644 --- a/nuttx/configs/c5471evm/httpd/Make.defs +++ b/nuttx/configs/c5471evm/httpd/Make.defs @@ -48,7 +48,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -82,11 +82,10 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif - MKDEP = $(TOPDIR)/tools/mkdeps.sh HOSTCC = gcc diff --git a/nuttx/configs/c5471evm/nettest/Make.defs b/nuttx/configs/c5471evm/nettest/Make.defs index 1f8b7afa17..0db0a8dc9c 100644 --- a/nuttx/configs/c5471evm/nettest/Make.defs +++ b/nuttx/configs/c5471evm/nettest/Make.defs @@ -48,7 +48,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -82,11 +82,10 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif - MKDEP = $(TOPDIR)/tools/mkdeps.sh HOSTCC = gcc diff --git a/nuttx/configs/c5471evm/nsh/Make.defs b/nuttx/configs/c5471evm/nsh/Make.defs index 68a15703e3..8d3a3adc1c 100644 --- a/nuttx/configs/c5471evm/nsh/Make.defs +++ b/nuttx/configs/c5471evm/nsh/Make.defs @@ -48,7 +48,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -82,11 +82,10 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif - MKDEP = $(TOPDIR)/tools/mkdeps.sh HOSTCC = gcc diff --git a/nuttx/configs/c5471evm/ostest/Make.defs b/nuttx/configs/c5471evm/ostest/Make.defs index 8a0f8c812f..c834591732 100644 --- a/nuttx/configs/c5471evm/ostest/Make.defs +++ b/nuttx/configs/c5471evm/ostest/Make.defs @@ -48,7 +48,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -82,11 +82,10 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif - MKDEP = $(TOPDIR)/tools/mkdeps.sh HOSTCC = gcc diff --git a/nuttx/configs/compal_e88/nsh_highram/Make.defs b/nuttx/configs/compal_e88/nsh_highram/Make.defs index c5890828f8..2d65c2782f 100644 --- a/nuttx/configs/compal_e88/nsh_highram/Make.defs +++ b/nuttx/configs/compal_e88/nsh_highram/Make.defs @@ -57,7 +57,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -91,7 +91,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif diff --git a/nuttx/configs/compal_e99/nsh_compalram/Make.defs b/nuttx/configs/compal_e99/nsh_compalram/Make.defs index 16e38b666b..f93a01f04c 100644 --- a/nuttx/configs/compal_e99/nsh_compalram/Make.defs +++ b/nuttx/configs/compal_e99/nsh_compalram/Make.defs @@ -57,7 +57,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -91,7 +91,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif diff --git a/nuttx/configs/compal_e99/nsh_highram/Make.defs b/nuttx/configs/compal_e99/nsh_highram/Make.defs index c5890828f8..2d65c2782f 100644 --- a/nuttx/configs/compal_e99/nsh_highram/Make.defs +++ b/nuttx/configs/compal_e99/nsh_highram/Make.defs @@ -57,7 +57,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -91,7 +91,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif diff --git a/nuttx/configs/demo9s12ne64/ostest/Make.defs b/nuttx/configs/demo9s12ne64/ostest/Make.defs index 9edf5adf9c..e6fdb9952f 100644 --- a/nuttx/configs/demo9s12ne64/ostest/Make.defs +++ b/nuttx/configs/demo9s12ne64/ostest/Make.defs @@ -84,7 +84,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ea3131/nsh/Make.defs b/nuttx/configs/ea3131/nsh/Make.defs index 28e881ccb4..a061eb22cf 100644 --- a/nuttx/configs/ea3131/nsh/Make.defs +++ b/nuttx/configs/ea3131/nsh/Make.defs @@ -88,7 +88,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ea3131/ostest/Make.defs b/nuttx/configs/ea3131/ostest/Make.defs index ed7eb92903..ba750e2122 100644 --- a/nuttx/configs/ea3131/ostest/Make.defs +++ b/nuttx/configs/ea3131/ostest/Make.defs @@ -88,7 +88,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ea3131/pgnsh/Make.defs b/nuttx/configs/ea3131/pgnsh/Make.defs index 7b09759ead..c142319dea 100644 --- a/nuttx/configs/ea3131/pgnsh/Make.defs +++ b/nuttx/configs/ea3131/pgnsh/Make.defs @@ -88,7 +88,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ea3131/usbserial/Make.defs b/nuttx/configs/ea3131/usbserial/Make.defs index 614221fb37..ef64e26157 100644 --- a/nuttx/configs/ea3131/usbserial/Make.defs +++ b/nuttx/configs/ea3131/usbserial/Make.defs @@ -88,7 +88,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ea3131/usbstorage/Make.defs b/nuttx/configs/ea3131/usbstorage/Make.defs index 4aa007069e..7393606158 100644 --- a/nuttx/configs/ea3131/usbstorage/Make.defs +++ b/nuttx/configs/ea3131/usbstorage/Make.defs @@ -88,7 +88,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ea3152/ostest/Make.defs b/nuttx/configs/ea3152/ostest/Make.defs index 8ca8f6e6a9..f69eb5e957 100644 --- a/nuttx/configs/ea3152/ostest/Make.defs +++ b/nuttx/configs/ea3152/ostest/Make.defs @@ -88,7 +88,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/eagle100/httpd/Make.defs b/nuttx/configs/eagle100/httpd/Make.defs index 4d5024d247..ef5b28ede5 100644 --- a/nuttx/configs/eagle100/httpd/Make.defs +++ b/nuttx/configs/eagle100/httpd/Make.defs @@ -74,7 +74,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/eagle100/nettest/Make.defs b/nuttx/configs/eagle100/nettest/Make.defs index 98b544ed9b..ac9e7853b3 100644 --- a/nuttx/configs/eagle100/nettest/Make.defs +++ b/nuttx/configs/eagle100/nettest/Make.defs @@ -74,7 +74,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/eagle100/nsh/Make.defs b/nuttx/configs/eagle100/nsh/Make.defs index efd473f7ab..3bc31ce777 100644 --- a/nuttx/configs/eagle100/nsh/Make.defs +++ b/nuttx/configs/eagle100/nsh/Make.defs @@ -74,7 +74,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/eagle100/nxflat/Make.defs b/nuttx/configs/eagle100/nxflat/Make.defs index 6c6965d202..2c8aa9c44d 100644 --- a/nuttx/configs/eagle100/nxflat/Make.defs +++ b/nuttx/configs/eagle100/nxflat/Make.defs @@ -77,7 +77,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/eagle100/ostest/Make.defs b/nuttx/configs/eagle100/ostest/Make.defs index f28f6d90be..4eb37853b0 100644 --- a/nuttx/configs/eagle100/ostest/Make.defs +++ b/nuttx/configs/eagle100/ostest/Make.defs @@ -74,7 +74,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/eagle100/thttpd/Make.defs b/nuttx/configs/eagle100/thttpd/Make.defs index 83abbe411a..dbdfddf1b5 100644 --- a/nuttx/configs/eagle100/thttpd/Make.defs +++ b/nuttx/configs/eagle100/thttpd/Make.defs @@ -77,7 +77,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs b/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs index c14dccbb91..1563e73a97 100644 --- a/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs +++ b/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs @@ -97,7 +97,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs b/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs index 4068b73fd4..b052c86aeb 100644 --- a/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs +++ b/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs @@ -97,7 +97,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ez80f910200kitg/ostest/Make.defs b/nuttx/configs/ez80f910200kitg/ostest/Make.defs index 4eaf34fe01..88280d8ecb 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/Make.defs +++ b/nuttx/configs/ez80f910200kitg/ostest/Make.defs @@ -80,7 +80,7 @@ ARCHCPUDEF = _EZ80F91 ARCHFAMILY = _EZ80ACCLAIM! endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug -NOsdiopt else ARCHASMOPTIMIZATION = -nodebug -NOsdiopt @@ -97,7 +97,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -reduceopt else ARCHOPTIMIZATION = -nodebug -optsize diff --git a/nuttx/configs/ez80f910200zco/dhcpd/Make.defs b/nuttx/configs/ez80f910200zco/dhcpd/Make.defs index 326ea137b2..d8e7d33fe4 100644 --- a/nuttx/configs/ez80f910200zco/dhcpd/Make.defs +++ b/nuttx/configs/ez80f910200zco/dhcpd/Make.defs @@ -80,7 +80,7 @@ ARCHCPUDEF = _EZ80F91 ARCHFAMILY = _EZ80ACCLAIM! endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug -NOsdiopt else ARCHASMOPTIMIZATION = -nodebug -NOsdiopt @@ -97,7 +97,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -reduceopt else ARCHOPTIMIZATION = -nodebug -optsize diff --git a/nuttx/configs/ez80f910200zco/httpd/Make.defs b/nuttx/configs/ez80f910200zco/httpd/Make.defs index 6a30c70004..2a8ffb04f1 100644 --- a/nuttx/configs/ez80f910200zco/httpd/Make.defs +++ b/nuttx/configs/ez80f910200zco/httpd/Make.defs @@ -80,7 +80,7 @@ ARCHCPUDEF = _EZ80F91 ARCHFAMILY = _EZ80ACCLAIM! endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug -NOsdiopt else ARCHASMOPTIMIZATION = -nodebug -NOsdiopt @@ -97,7 +97,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -reduceopt else ARCHOPTIMIZATION = -nodebug -optsize diff --git a/nuttx/configs/ez80f910200zco/nettest/Make.defs b/nuttx/configs/ez80f910200zco/nettest/Make.defs index ce32366643..95a5b4201b 100644 --- a/nuttx/configs/ez80f910200zco/nettest/Make.defs +++ b/nuttx/configs/ez80f910200zco/nettest/Make.defs @@ -80,7 +80,7 @@ ARCHCPUDEF = _EZ80F91 ARCHFAMILY = _EZ80ACCLAIM! endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug -NOsdiopt else ARCHASMOPTIMIZATION = -nodebug -NOsdiopt @@ -97,7 +97,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -reduceopt else ARCHOPTIMIZATION = -nodebug -optsize diff --git a/nuttx/configs/ez80f910200zco/nsh/Make.defs b/nuttx/configs/ez80f910200zco/nsh/Make.defs index 9dbaceb645..978e406b78 100644 --- a/nuttx/configs/ez80f910200zco/nsh/Make.defs +++ b/nuttx/configs/ez80f910200zco/nsh/Make.defs @@ -80,7 +80,7 @@ ARCHCPUDEF = _EZ80F91 ARCHFAMILY = _EZ80ACCLAIM! endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug -NOsdiopt else ARCHASMOPTIMIZATION = -nodebug -NOsdiopt @@ -97,7 +97,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -reduceopt else ARCHOPTIMIZATION = -nodebug -optsize diff --git a/nuttx/configs/ez80f910200zco/ostest/Make.defs b/nuttx/configs/ez80f910200zco/ostest/Make.defs index 6a49cbc573..1a2759cff3 100644 --- a/nuttx/configs/ez80f910200zco/ostest/Make.defs +++ b/nuttx/configs/ez80f910200zco/ostest/Make.defs @@ -80,7 +80,7 @@ ARCHCPUDEF = _EZ80F91 ARCHFAMILY = _EZ80ACCLAIM! endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug -NOsdiopt else ARCHASMOPTIMIZATION = -nodebug -NOsdiopt @@ -97,7 +97,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -reduceopt else ARCHOPTIMIZATION = -nodebug -optsize diff --git a/nuttx/configs/ez80f910200zco/poll/Make.defs b/nuttx/configs/ez80f910200zco/poll/Make.defs index fd32a6df63..c9a9a83ea0 100644 --- a/nuttx/configs/ez80f910200zco/poll/Make.defs +++ b/nuttx/configs/ez80f910200zco/poll/Make.defs @@ -80,7 +80,7 @@ ARCHCPUDEF = _EZ80F91 ARCHFAMILY = _EZ80ACCLAIM! endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug -NOsdiopt else ARCHASMOPTIMIZATION = -nodebug -NOsdiopt @@ -97,7 +97,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -reduceopt else ARCHOPTIMIZATION = -nodebug -optsize diff --git a/nuttx/configs/fire-stm32v2/nsh/Make.defs b/nuttx/configs/fire-stm32v2/nsh/Make.defs index bd63f7c6be..271d4ab17c 100644 --- a/nuttx/configs/fire-stm32v2/nsh/Make.defs +++ b/nuttx/configs/fire-stm32v2/nsh/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/hymini-stm32v/buttons/Make.defs b/nuttx/configs/hymini-stm32v/buttons/Make.defs index 565729c1a1..fde36e025b 100644 --- a/nuttx/configs/hymini-stm32v/buttons/Make.defs +++ b/nuttx/configs/hymini-stm32v/buttons/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/hymini-stm32v/nsh/Make.defs b/nuttx/configs/hymini-stm32v/nsh/Make.defs index 285bbe40ab..f819679f29 100644 --- a/nuttx/configs/hymini-stm32v/nsh/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/hymini-stm32v/nsh2/Make.defs b/nuttx/configs/hymini-stm32v/nsh2/Make.defs index 9ad8c2774a..c1c55a1f70 100644 --- a/nuttx/configs/hymini-stm32v/nsh2/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh2/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/hymini-stm32v/nx/Make.defs b/nuttx/configs/hymini-stm32v/nx/Make.defs index 84700e0828..2d26b881b1 100644 --- a/nuttx/configs/hymini-stm32v/nx/Make.defs +++ b/nuttx/configs/hymini-stm32v/nx/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/hymini-stm32v/nxlines/Make.defs b/nuttx/configs/hymini-stm32v/nxlines/Make.defs index b9e8841f0a..1970020f1b 100644 --- a/nuttx/configs/hymini-stm32v/nxlines/Make.defs +++ b/nuttx/configs/hymini-stm32v/nxlines/Make.defs @@ -110,7 +110,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/hymini-stm32v/usbserial/Make.defs b/nuttx/configs/hymini-stm32v/usbserial/Make.defs index 559af81de5..68a0618b0a 100644 --- a/nuttx/configs/hymini-stm32v/usbserial/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbserial/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs index 5fef4f705d..b59091c5e5 100644 --- a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/kwikstik-k40/ostest/Make.defs b/nuttx/configs/kwikstik-k40/ostest/Make.defs index f239d872d4..7f260d2671 100644 --- a/nuttx/configs/kwikstik-k40/ostest/Make.defs +++ b/nuttx/configs/kwikstik-k40/ostest/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lincoln60/nsh/Make.defs b/nuttx/configs/lincoln60/nsh/Make.defs index cf76f97f28..8d17270240 100644 --- a/nuttx/configs/lincoln60/nsh/Make.defs +++ b/nuttx/configs/lincoln60/nsh/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lincoln60/ostest/Make.defs b/nuttx/configs/lincoln60/ostest/Make.defs index 044b27dc43..e8a4ec3ea5 100644 --- a/nuttx/configs/lincoln60/ostest/Make.defs +++ b/nuttx/configs/lincoln60/ostest/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs index 795d928d2e..6597c42838 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs index 8a0fc03175..3ac4c12ac4 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lm3s6965-ek/nsh/Make.defs b/nuttx/configs/lm3s6965-ek/nsh/Make.defs index 72ea6b151e..d8c4978bda 100644 --- a/nuttx/configs/lm3s6965-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nsh/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lm3s6965-ek/nx/Make.defs b/nuttx/configs/lm3s6965-ek/nx/Make.defs index 2a409101bb..eccfcde079 100644 --- a/nuttx/configs/lm3s6965-ek/nx/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nx/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lm3s6965-ek/ostest/Make.defs b/nuttx/configs/lm3s6965-ek/ostest/Make.defs index ae376da0c5..fe15153db3 100644 --- a/nuttx/configs/lm3s6965-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s6965-ek/ostest/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lm3s8962-ek/nsh/Make.defs b/nuttx/configs/lm3s8962-ek/nsh/Make.defs index b0b57559c0..3269059c9b 100644 --- a/nuttx/configs/lm3s8962-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nsh/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lm3s8962-ek/nx/Make.defs b/nuttx/configs/lm3s8962-ek/nx/Make.defs index 7d0d0aa55b..5c2bab9154 100644 --- a/nuttx/configs/lm3s8962-ek/nx/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nx/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lm3s8962-ek/ostest/Make.defs b/nuttx/configs/lm3s8962-ek/ostest/Make.defs index 50368f34f2..19b7fef1d1 100644 --- a/nuttx/configs/lm3s8962-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s8962-ek/ostest/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lpc4330-xplorer/nsh/Make.defs b/nuttx/configs/lpc4330-xplorer/nsh/Make.defs index 51439ac227..49fc903aa1 100644 --- a/nuttx/configs/lpc4330-xplorer/nsh/Make.defs +++ b/nuttx/configs/lpc4330-xplorer/nsh/Make.defs @@ -153,7 +153,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lpc4330-xplorer/ostest/Make.defs b/nuttx/configs/lpc4330-xplorer/ostest/Make.defs index 51439ac227..49fc903aa1 100644 --- a/nuttx/configs/lpc4330-xplorer/ostest/Make.defs +++ b/nuttx/configs/lpc4330-xplorer/ostest/Make.defs @@ -153,7 +153,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs index eebe11c22a..5c7bd715eb 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs index c8fb0e9aec..020006de32 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs index b0334ba46d..79390242bb 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs index 1e1f2d9795..5a99725c07 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs index 93bcfa376e..9fe82fe83a 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs @@ -113,7 +113,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs index e546666e75..a42b8e84a6 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/m68332evb/Make.defs b/nuttx/configs/m68332evb/Make.defs index fb85cf8272..6f6ae7ad07 100644 --- a/nuttx/configs/m68332evb/Make.defs +++ b/nuttx/configs/m68332evb/Make.defs @@ -36,7 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -68,7 +68,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif diff --git a/nuttx/configs/mbed/hidkbd/Make.defs b/nuttx/configs/mbed/hidkbd/Make.defs index 92c6c7ceaa..b11b33d6d3 100644 --- a/nuttx/configs/mbed/hidkbd/Make.defs +++ b/nuttx/configs/mbed/hidkbd/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/mbed/nsh/Make.defs b/nuttx/configs/mbed/nsh/Make.defs index 9a72736d26..a7bc14423f 100644 --- a/nuttx/configs/mbed/nsh/Make.defs +++ b/nuttx/configs/mbed/nsh/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/mcu123-lpc214x/composite/Make.defs b/nuttx/configs/mcu123-lpc214x/composite/Make.defs index 7b9b8f22ff..28dbf31579 100644 --- a/nuttx/configs/mcu123-lpc214x/composite/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/composite/Make.defs @@ -80,7 +80,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/mcu123-lpc214x/nsh/Make.defs b/nuttx/configs/mcu123-lpc214x/nsh/Make.defs index ddccbb4734..d9ae7e305a 100644 --- a/nuttx/configs/mcu123-lpc214x/nsh/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/nsh/Make.defs @@ -80,7 +80,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/mcu123-lpc214x/ostest/Make.defs b/nuttx/configs/mcu123-lpc214x/ostest/Make.defs index 255515a42e..76b9e7abb0 100644 --- a/nuttx/configs/mcu123-lpc214x/ostest/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/ostest/Make.defs @@ -80,7 +80,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs b/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs index 6f05d79f73..5490d690f8 100644 --- a/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/usbserial/Make.defs @@ -80,7 +80,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs b/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs index 35ea7af7ab..408d19c234 100644 --- a/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/usbstorage/Make.defs @@ -80,7 +80,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/micropendous3/hello/Make.defs b/nuttx/configs/micropendous3/hello/Make.defs index bd48d79c9e..69073bb438 100644 --- a/nuttx/configs/micropendous3/hello/Make.defs +++ b/nuttx/configs/micropendous3/hello/Make.defs @@ -88,7 +88,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/mirtoo/nsh/Make.defs b/nuttx/configs/mirtoo/nsh/Make.defs index de0a190f66..28ea99ab04 100644 --- a/nuttx/configs/mirtoo/nsh/Make.defs +++ b/nuttx/configs/mirtoo/nsh/Make.defs @@ -134,7 +134,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/mirtoo/nxffs/Make.defs b/nuttx/configs/mirtoo/nxffs/Make.defs index a6992ee533..09989324e5 100644 --- a/nuttx/configs/mirtoo/nxffs/Make.defs +++ b/nuttx/configs/mirtoo/nxffs/Make.defs @@ -134,7 +134,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/mirtoo/ostest/Make.defs b/nuttx/configs/mirtoo/ostest/Make.defs index 71bd9d5baa..7a087665b9 100644 --- a/nuttx/configs/mirtoo/ostest/Make.defs +++ b/nuttx/configs/mirtoo/ostest/Make.defs @@ -134,7 +134,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/mx1ads/ostest/Make.defs b/nuttx/configs/mx1ads/ostest/Make.defs index 9b9c61df8f..0e261775f4 100644 --- a/nuttx/configs/mx1ads/ostest/Make.defs +++ b/nuttx/configs/mx1ads/ostest/Make.defs @@ -54,7 +54,7 @@ ARCHCXXFLAGS = -fno-builtin -fno-exceptions ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow ARCHWARNINGSXX = -Wall -Wshadow -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -92,7 +92,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif diff --git a/nuttx/configs/ne64badge/ostest/Make.defs b/nuttx/configs/ne64badge/ostest/Make.defs index 2858d30f1d..870313d73f 100644 --- a/nuttx/configs/ne64badge/ostest/Make.defs +++ b/nuttx/configs/ne64badge/ostest/Make.defs @@ -84,7 +84,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ntosd-dm320/nettest/Make.defs b/nuttx/configs/ntosd-dm320/nettest/Make.defs index e28c1a3609..8c5b7e93b9 100644 --- a/nuttx/configs/ntosd-dm320/nettest/Make.defs +++ b/nuttx/configs/ntosd-dm320/nettest/Make.defs @@ -90,7 +90,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ntosd-dm320/nsh/Make.defs b/nuttx/configs/ntosd-dm320/nsh/Make.defs index aff7f4240b..fa61494062 100644 --- a/nuttx/configs/ntosd-dm320/nsh/Make.defs +++ b/nuttx/configs/ntosd-dm320/nsh/Make.defs @@ -90,7 +90,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ntosd-dm320/ostest/Make.defs b/nuttx/configs/ntosd-dm320/ostest/Make.defs index 6766b49153..9b2ab9e5e2 100644 --- a/nuttx/configs/ntosd-dm320/ostest/Make.defs +++ b/nuttx/configs/ntosd-dm320/ostest/Make.defs @@ -90,7 +90,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ntosd-dm320/poll/Make.defs b/nuttx/configs/ntosd-dm320/poll/Make.defs index a111fed657..69c20da944 100644 --- a/nuttx/configs/ntosd-dm320/poll/Make.defs +++ b/nuttx/configs/ntosd-dm320/poll/Make.defs @@ -90,7 +90,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ntosd-dm320/thttpd/Make.defs b/nuttx/configs/ntosd-dm320/thttpd/Make.defs index a0e501376e..252416f6bf 100644 --- a/nuttx/configs/ntosd-dm320/thttpd/Make.defs +++ b/nuttx/configs/ntosd-dm320/thttpd/Make.defs @@ -90,7 +90,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ntosd-dm320/udp/Make.defs b/nuttx/configs/ntosd-dm320/udp/Make.defs index 16ed8ecebf..0cdb9f05dc 100644 --- a/nuttx/configs/ntosd-dm320/udp/Make.defs +++ b/nuttx/configs/ntosd-dm320/udp/Make.defs @@ -90,7 +90,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ntosd-dm320/uip/Make.defs b/nuttx/configs/ntosd-dm320/uip/Make.defs index d9425c05eb..64bb4494b4 100644 --- a/nuttx/configs/ntosd-dm320/uip/Make.defs +++ b/nuttx/configs/ntosd-dm320/uip/Make.defs @@ -90,7 +90,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/nucleus2g/nsh/Make.defs b/nuttx/configs/nucleus2g/nsh/Make.defs index aed194e104..7b82800bfd 100644 --- a/nuttx/configs/nucleus2g/nsh/Make.defs +++ b/nuttx/configs/nucleus2g/nsh/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/nucleus2g/ostest/Make.defs b/nuttx/configs/nucleus2g/ostest/Make.defs index 239424083b..b0ec211649 100644 --- a/nuttx/configs/nucleus2g/ostest/Make.defs +++ b/nuttx/configs/nucleus2g/ostest/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/nucleus2g/usbserial/Make.defs b/nuttx/configs/nucleus2g/usbserial/Make.defs index 81f17e86d2..04e94eda90 100644 --- a/nuttx/configs/nucleus2g/usbserial/Make.defs +++ b/nuttx/configs/nucleus2g/usbserial/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/nucleus2g/usbstorage/Make.defs b/nuttx/configs/nucleus2g/usbstorage/Make.defs index 06af74d397..3e15c52d04 100644 --- a/nuttx/configs/nucleus2g/usbstorage/Make.defs +++ b/nuttx/configs/nucleus2g/usbstorage/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs index 674ad76929..91bd0e27cb 100644 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs @@ -99,7 +99,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs index 3c68d370d0..c785dc7b7c 100644 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs index 57f2b7a558..119acc0f69 100644 --- a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs index c9ecf51db7..ea6ad5670b 100644 --- a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs index 64c9814925..67d74dcde1 100644 --- a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs index 2f33642bfc..78618bddbe 100644 --- a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs index fc49b69814..4f217561ff 100644 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs @@ -99,7 +99,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs index bb4df618b2..e7095d9379 100644 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs @@ -99,7 +99,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs index b4716971df..0ff4bb94af 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs index ed338c8b26..c7f954ff9a 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs index 08f55feab7..31f4023e6a 100644 --- a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-stm32-p107/nsh/Make.defs b/nuttx/configs/olimex-stm32-p107/nsh/Make.defs index 3314a82bef..f88fb67312 100644 --- a/nuttx/configs/olimex-stm32-p107/nsh/Make.defs +++ b/nuttx/configs/olimex-stm32-p107/nsh/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-stm32-p107/ostest/Make.defs b/nuttx/configs/olimex-stm32-p107/ostest/Make.defs index fdceac03ba..2a1bc6d9cd 100644 --- a/nuttx/configs/olimex-stm32-p107/ostest/Make.defs +++ b/nuttx/configs/olimex-stm32-p107/ostest/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-strp711/nettest/Make.defs b/nuttx/configs/olimex-strp711/nettest/Make.defs index 64259e9199..f14c078941 100644 --- a/nuttx/configs/olimex-strp711/nettest/Make.defs +++ b/nuttx/configs/olimex-strp711/nettest/Make.defs @@ -80,7 +80,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-strp711/nsh/Make.defs b/nuttx/configs/olimex-strp711/nsh/Make.defs index 69c6b4c277..a16447aec3 100644 --- a/nuttx/configs/olimex-strp711/nsh/Make.defs +++ b/nuttx/configs/olimex-strp711/nsh/Make.defs @@ -80,7 +80,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/olimex-strp711/ostest/Make.defs b/nuttx/configs/olimex-strp711/ostest/Make.defs index 722a45951e..a4fe11a027 100644 --- a/nuttx/configs/olimex-strp711/ostest/Make.defs +++ b/nuttx/configs/olimex-strp711/ostest/Make.defs @@ -80,7 +80,7 @@ else MAXOPTIMIZATION = -O2 endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs b/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs index 9608ce0ee4..166378988e 100644 --- a/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs +++ b/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs b/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs index 0376ee339f..834a8ed53e 100644 --- a/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs +++ b/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/pic32-starterkit/nsh/Make.defs b/nuttx/configs/pic32-starterkit/nsh/Make.defs index 962801567f..1063e57bec 100644 --- a/nuttx/configs/pic32-starterkit/nsh/Make.defs +++ b/nuttx/configs/pic32-starterkit/nsh/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/pic32-starterkit/nsh2/Make.defs b/nuttx/configs/pic32-starterkit/nsh2/Make.defs index 2068db849d..730ec22b6f 100644 --- a/nuttx/configs/pic32-starterkit/nsh2/Make.defs +++ b/nuttx/configs/pic32-starterkit/nsh2/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/pic32-starterkit/ostest/Make.defs b/nuttx/configs/pic32-starterkit/ostest/Make.defs index 370ac7f1fb..d5eb4fb7f0 100644 --- a/nuttx/configs/pic32-starterkit/ostest/Make.defs +++ b/nuttx/configs/pic32-starterkit/ostest/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/pic32mx7mmb/nsh/Make.defs b/nuttx/configs/pic32mx7mmb/nsh/Make.defs index ed776bc191..249c359d4d 100644 --- a/nuttx/configs/pic32mx7mmb/nsh/Make.defs +++ b/nuttx/configs/pic32mx7mmb/nsh/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/pic32mx7mmb/ostest/Make.defs b/nuttx/configs/pic32mx7mmb/ostest/Make.defs index 54806fb95a..4196872a7f 100644 --- a/nuttx/configs/pic32mx7mmb/ostest/Make.defs +++ b/nuttx/configs/pic32mx7mmb/ostest/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/pjrc-8051/Make.defs b/nuttx/configs/pjrc-8051/Make.defs index 5d25945479..5cf9fadf13 100644 --- a/nuttx/configs/pjrc-8051/Make.defs +++ b/nuttx/configs/pjrc-8051/Make.defs @@ -36,7 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = --debug else ARCHOPTIMIZATION = diff --git a/nuttx/configs/qemu-i486/nsh/Make.defs b/nuttx/configs/qemu-i486/nsh/Make.defs index 8b5fe61f65..dd518a5afc 100644 --- a/nuttx/configs/qemu-i486/nsh/Make.defs +++ b/nuttx/configs/qemu-i486/nsh/Make.defs @@ -99,7 +99,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = .elf -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif diff --git a/nuttx/configs/qemu-i486/ostest/Make.defs b/nuttx/configs/qemu-i486/ostest/Make.defs index 0a2423456e..7bec9327bd 100644 --- a/nuttx/configs/qemu-i486/ostest/Make.defs +++ b/nuttx/configs/qemu-i486/ostest/Make.defs @@ -99,7 +99,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = .elf -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif diff --git a/nuttx/configs/sam3u-ek/knsh/Make.defs b/nuttx/configs/sam3u-ek/knsh/Make.defs index a402a4d512..b6275f283f 100644 --- a/nuttx/configs/sam3u-ek/knsh/Make.defs +++ b/nuttx/configs/sam3u-ek/knsh/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/sam3u-ek/nsh/Make.defs b/nuttx/configs/sam3u-ek/nsh/Make.defs index 337b98df84..f314f6765c 100644 --- a/nuttx/configs/sam3u-ek/nsh/Make.defs +++ b/nuttx/configs/sam3u-ek/nsh/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/sam3u-ek/nx/Make.defs b/nuttx/configs/sam3u-ek/nx/Make.defs index 86a1c5c38e..10ef94ff3f 100644 --- a/nuttx/configs/sam3u-ek/nx/Make.defs +++ b/nuttx/configs/sam3u-ek/nx/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/sam3u-ek/ostest/Make.defs b/nuttx/configs/sam3u-ek/ostest/Make.defs index 25f386df75..167b9217bf 100644 --- a/nuttx/configs/sam3u-ek/ostest/Make.defs +++ b/nuttx/configs/sam3u-ek/ostest/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/sam3u-ek/touchscreen/Make.defs b/nuttx/configs/sam3u-ek/touchscreen/Make.defs index fce80ec256..a1f1e71514 100644 --- a/nuttx/configs/sam3u-ek/touchscreen/Make.defs +++ b/nuttx/configs/sam3u-ek/touchscreen/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/shenzhou/nsh/Make.defs b/nuttx/configs/shenzhou/nsh/Make.defs index 81dedb8bba..ef2bf35fb0 100644 --- a/nuttx/configs/shenzhou/nsh/Make.defs +++ b/nuttx/configs/shenzhou/nsh/Make.defs @@ -130,7 +130,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/shenzhou/nxwm/Make.defs b/nuttx/configs/shenzhou/nxwm/Make.defs index 84e0df782d..66e4945b12 100644 --- a/nuttx/configs/shenzhou/nxwm/Make.defs +++ b/nuttx/configs/shenzhou/nxwm/Make.defs @@ -130,7 +130,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/shenzhou/thttpd/Make.defs b/nuttx/configs/shenzhou/thttpd/Make.defs index 99aed6a514..8773aee1b3 100644 --- a/nuttx/configs/shenzhou/thttpd/Make.defs +++ b/nuttx/configs/shenzhou/thttpd/Make.defs @@ -133,7 +133,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/skp16c26/ostest/Make.defs b/nuttx/configs/skp16c26/ostest/Make.defs index a7444daae3..7f1ab651a9 100644 --- a/nuttx/configs/skp16c26/ostest/Make.defs +++ b/nuttx/configs/skp16c26/ostest/Make.defs @@ -48,7 +48,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer @@ -70,7 +70,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif diff --git a/nuttx/configs/stm3210e-eval/RIDE/Make.defs b/nuttx/configs/stm3210e-eval/RIDE/Make.defs index 6e69590c7a..33c95f4cf3 100644 --- a/nuttx/configs/stm3210e-eval/RIDE/Make.defs +++ b/nuttx/configs/stm3210e-eval/RIDE/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/buttons/Make.defs b/nuttx/configs/stm3210e-eval/buttons/Make.defs index 860d81c1fb..0ff9bef0cd 100644 --- a/nuttx/configs/stm3210e-eval/buttons/Make.defs +++ b/nuttx/configs/stm3210e-eval/buttons/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/composite/Make.defs b/nuttx/configs/stm3210e-eval/composite/Make.defs index c0d85bf227..5c22eb8e43 100644 --- a/nuttx/configs/stm3210e-eval/composite/Make.defs +++ b/nuttx/configs/stm3210e-eval/composite/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/nsh/Make.defs b/nuttx/configs/stm3210e-eval/nsh/Make.defs index 03d19fbc80..348c721d13 100644 --- a/nuttx/configs/stm3210e-eval/nsh/Make.defs +++ b/nuttx/configs/stm3210e-eval/nsh/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/nsh2/Make.defs b/nuttx/configs/stm3210e-eval/nsh2/Make.defs index f84c115529..9cea646855 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3210e-eval/nsh2/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/nx/Make.defs b/nuttx/configs/stm3210e-eval/nx/Make.defs index 7f253873a1..b4f210369f 100644 --- a/nuttx/configs/stm3210e-eval/nx/Make.defs +++ b/nuttx/configs/stm3210e-eval/nx/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/nxconsole/Make.defs b/nuttx/configs/stm3210e-eval/nxconsole/Make.defs index 8993a53aab..bb51b10f91 100644 --- a/nuttx/configs/stm3210e-eval/nxconsole/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxconsole/Make.defs @@ -110,7 +110,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/nxlines/Make.defs b/nuttx/configs/stm3210e-eval/nxlines/Make.defs index 190ed098f8..9f1de2f93b 100644 --- a/nuttx/configs/stm3210e-eval/nxlines/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxlines/Make.defs @@ -110,7 +110,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/nxtext/Make.defs b/nuttx/configs/stm3210e-eval/nxtext/Make.defs index d4f8ec2fe3..d977538864 100644 --- a/nuttx/configs/stm3210e-eval/nxtext/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxtext/Make.defs @@ -110,7 +110,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/ostest/Make.defs b/nuttx/configs/stm3210e-eval/ostest/Make.defs index ef1a3d4234..ccb90fe273 100644 --- a/nuttx/configs/stm3210e-eval/ostest/Make.defs +++ b/nuttx/configs/stm3210e-eval/ostest/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/pm/Make.defs b/nuttx/configs/stm3210e-eval/pm/Make.defs index a60e4a7745..b5e08c9a08 100644 --- a/nuttx/configs/stm3210e-eval/pm/Make.defs +++ b/nuttx/configs/stm3210e-eval/pm/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/usbserial/Make.defs b/nuttx/configs/stm3210e-eval/usbserial/Make.defs index f08d5b68c4..9219e6099e 100644 --- a/nuttx/configs/stm3210e-eval/usbserial/Make.defs +++ b/nuttx/configs/stm3210e-eval/usbserial/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3210e-eval/usbstorage/Make.defs b/nuttx/configs/stm3210e-eval/usbstorage/Make.defs index 7f2cb73b66..2c9e2a9e1b 100644 --- a/nuttx/configs/stm3210e-eval/usbstorage/Make.defs +++ b/nuttx/configs/stm3210e-eval/usbstorage/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs index e5a0e7b06a..71cb52eea6 100644 --- a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3220g-eval/nettest/Make.defs b/nuttx/configs/stm3220g-eval/nettest/Make.defs index 2a8976d089..de62c90567 100644 --- a/nuttx/configs/stm3220g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3220g-eval/nettest/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3220g-eval/nsh/Make.defs b/nuttx/configs/stm3220g-eval/nsh/Make.defs index 23a57ab800..fcb4bf93f7 100644 --- a/nuttx/configs/stm3220g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3220g-eval/nsh2/Make.defs b/nuttx/configs/stm3220g-eval/nsh2/Make.defs index 38335c1709..af4359dd8b 100644 --- a/nuttx/configs/stm3220g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh2/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3220g-eval/nxwm/Make.defs b/nuttx/configs/stm3220g-eval/nxwm/Make.defs index c4846c0c31..bb46adff7c 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3220g-eval/nxwm/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3220g-eval/ostest/Make.defs b/nuttx/configs/stm3220g-eval/ostest/Make.defs index e2de89cf74..8e72558f94 100644 --- a/nuttx/configs/stm3220g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3220g-eval/ostest/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3220g-eval/telnetd/Make.defs b/nuttx/configs/stm3220g-eval/telnetd/Make.defs index 4004508d50..c82a2715a2 100644 --- a/nuttx/configs/stm3220g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3220g-eval/telnetd/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/dhcpd/Make.defs b/nuttx/configs/stm3240g-eval/dhcpd/Make.defs index 5b1334a073..599ad69ec7 100644 --- a/nuttx/configs/stm3240g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3240g-eval/dhcpd/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/discover/Make.defs b/nuttx/configs/stm3240g-eval/discover/Make.defs index 58afd39038..37280e89b0 100644 --- a/nuttx/configs/stm3240g-eval/discover/Make.defs +++ b/nuttx/configs/stm3240g-eval/discover/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/nettest/Make.defs b/nuttx/configs/stm3240g-eval/nettest/Make.defs index a7e4f9e077..b03eb2a3d4 100644 --- a/nuttx/configs/stm3240g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3240g-eval/nettest/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/nsh/Make.defs b/nuttx/configs/stm3240g-eval/nsh/Make.defs index d63876e754..a1587e4828 100644 --- a/nuttx/configs/stm3240g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3240g-eval/nsh/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/nsh2/Make.defs b/nuttx/configs/stm3240g-eval/nsh2/Make.defs index 16fef33447..9a2f75e73d 100644 --- a/nuttx/configs/stm3240g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3240g-eval/nsh2/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/nxconsole/Make.defs b/nuttx/configs/stm3240g-eval/nxconsole/Make.defs index 20fabfc9d2..c822180f56 100644 --- a/nuttx/configs/stm3240g-eval/nxconsole/Make.defs +++ b/nuttx/configs/stm3240g-eval/nxconsole/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/nxwm/Make.defs b/nuttx/configs/stm3240g-eval/nxwm/Make.defs index bf2da32464..edb007bd61 100644 --- a/nuttx/configs/stm3240g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3240g-eval/nxwm/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/ostest/Make.defs b/nuttx/configs/stm3240g-eval/ostest/Make.defs index c984a7e85c..19c1c22640 100644 --- a/nuttx/configs/stm3240g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3240g-eval/ostest/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/telnetd/Make.defs b/nuttx/configs/stm3240g-eval/telnetd/Make.defs index 498ee33861..325d0fd97e 100644 --- a/nuttx/configs/stm3240g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3240g-eval/telnetd/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/webserver/Make.defs b/nuttx/configs/stm3240g-eval/webserver/Make.defs index fb47d40050..d303a06fb0 100644 --- a/nuttx/configs/stm3240g-eval/webserver/Make.defs +++ b/nuttx/configs/stm3240g-eval/webserver/Make.defs @@ -131,7 +131,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs b/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs index 8f7fe96dc1..09e4b985b7 100644 --- a/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs +++ b/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm32f100rc_generic/nsh/Make.defs b/nuttx/configs/stm32f100rc_generic/nsh/Make.defs index 7d016a674e..76ab1751f8 100644 --- a/nuttx/configs/stm32f100rc_generic/nsh/Make.defs +++ b/nuttx/configs/stm32f100rc_generic/nsh/Make.defs @@ -105,7 +105,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm32f100rc_generic/ostest/Make.defs b/nuttx/configs/stm32f100rc_generic/ostest/Make.defs index 68d5410b34..2742e18cdf 100644 --- a/nuttx/configs/stm32f100rc_generic/ostest/Make.defs +++ b/nuttx/configs/stm32f100rc_generic/ostest/Make.defs @@ -105,7 +105,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm32f4discovery/cxxtest/Make.defs b/nuttx/configs/stm32f4discovery/cxxtest/Make.defs index 004643950b..57254cc4af 100644 --- a/nuttx/configs/stm32f4discovery/cxxtest/Make.defs +++ b/nuttx/configs/stm32f4discovery/cxxtest/Make.defs @@ -138,7 +138,7 @@ else ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm32f4discovery/elf/Make.defs b/nuttx/configs/stm32f4discovery/elf/Make.defs index 035a03e71a..e65571c68a 100644 --- a/nuttx/configs/stm32f4discovery/elf/Make.defs +++ b/nuttx/configs/stm32f4discovery/elf/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm32f4discovery/nsh/Make.defs b/nuttx/configs/stm32f4discovery/nsh/Make.defs index ed1662af5d..b3ccbbcc18 100644 --- a/nuttx/configs/stm32f4discovery/nsh/Make.defs +++ b/nuttx/configs/stm32f4discovery/nsh/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm32f4discovery/nxlines/Make.defs b/nuttx/configs/stm32f4discovery/nxlines/Make.defs index cfdb79a74a..b3d9337791 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/Make.defs +++ b/nuttx/configs/stm32f4discovery/nxlines/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm32f4discovery/ostest/Make.defs b/nuttx/configs/stm32f4discovery/ostest/Make.defs index 3106143d6c..4527a9b223 100644 --- a/nuttx/configs/stm32f4discovery/ostest/Make.defs +++ b/nuttx/configs/stm32f4discovery/ostest/Make.defs @@ -128,7 +128,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm32f4discovery/pm/Make.defs b/nuttx/configs/stm32f4discovery/pm/Make.defs index 3643548d47..e7276aa2ff 100644 --- a/nuttx/configs/stm32f4discovery/pm/Make.defs +++ b/nuttx/configs/stm32f4discovery/pm/Make.defs @@ -132,7 +132,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/stm32f4discovery/winbuild/Make.defs b/nuttx/configs/stm32f4discovery/winbuild/Make.defs index 6110b7bbd2..2d9e4f1e2a 100644 --- a/nuttx/configs/stm32f4discovery/winbuild/Make.defs +++ b/nuttx/configs/stm32f4discovery/winbuild/Make.defs @@ -97,7 +97,7 @@ OBJDUMP = $(CROSSDEV)objdump.exe 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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/sure-pic32mx/nsh/Make.defs b/nuttx/configs/sure-pic32mx/nsh/Make.defs index debf622d28..4aaf906ed8 100644 --- a/nuttx/configs/sure-pic32mx/nsh/Make.defs +++ b/nuttx/configs/sure-pic32mx/nsh/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/sure-pic32mx/ostest/Make.defs b/nuttx/configs/sure-pic32mx/ostest/Make.defs index 0c8d4346a5..cc25177391 100644 --- a/nuttx/configs/sure-pic32mx/ostest/Make.defs +++ b/nuttx/configs/sure-pic32mx/ostest/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/sure-pic32mx/usbnsh/Make.defs b/nuttx/configs/sure-pic32mx/usbnsh/Make.defs index fa8d3700fa..fbb58949ba 100644 --- a/nuttx/configs/sure-pic32mx/usbnsh/Make.defs +++ b/nuttx/configs/sure-pic32mx/usbnsh/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/teensy/hello/Make.defs b/nuttx/configs/teensy/hello/Make.defs index b79a52ed91..9c7cb8268f 100644 --- a/nuttx/configs/teensy/hello/Make.defs +++ b/nuttx/configs/teensy/hello/Make.defs @@ -88,7 +88,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/teensy/nsh/Make.defs b/nuttx/configs/teensy/nsh/Make.defs index 65838649cb..63c9db51f2 100644 --- a/nuttx/configs/teensy/nsh/Make.defs +++ b/nuttx/configs/teensy/nsh/Make.defs @@ -88,7 +88,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/teensy/usbstorage/Make.defs b/nuttx/configs/teensy/usbstorage/Make.defs index fa2997fb06..6474a772e1 100644 --- a/nuttx/configs/teensy/usbstorage/Make.defs +++ b/nuttx/configs/teensy/usbstorage/Make.defs @@ -88,7 +88,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/twr-k60n512/nsh/Make.defs b/nuttx/configs/twr-k60n512/nsh/Make.defs index a558cc0109..bb4a3f941c 100644 --- a/nuttx/configs/twr-k60n512/nsh/Make.defs +++ b/nuttx/configs/twr-k60n512/nsh/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/twr-k60n512/ostest/Make.defs b/nuttx/configs/twr-k60n512/ostest/Make.defs index 6d49455215..cb7d962baa 100644 --- a/nuttx/configs/twr-k60n512/ostest/Make.defs +++ b/nuttx/configs/twr-k60n512/ostest/Make.defs @@ -96,7 +96,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ubw32/nsh/Make.defs b/nuttx/configs/ubw32/nsh/Make.defs index 07a966446f..0f034825a9 100644 --- a/nuttx/configs/ubw32/nsh/Make.defs +++ b/nuttx/configs/ubw32/nsh/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/ubw32/ostest/Make.defs b/nuttx/configs/ubw32/ostest/Make.defs index 4f2971768d..143ab7b9c9 100644 --- a/nuttx/configs/ubw32/ostest/Make.defs +++ b/nuttx/configs/ubw32/ostest/Make.defs @@ -98,7 +98,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/us7032evb1/nsh/Make.defs b/nuttx/configs/us7032evb1/nsh/Make.defs index 9cbc41f5b9..fcda184774 100644 --- a/nuttx/configs/us7032evb1/nsh/Make.defs +++ b/nuttx/configs/us7032evb1/nsh/Make.defs @@ -36,7 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -68,7 +68,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif diff --git a/nuttx/configs/us7032evb1/ostest/Make.defs b/nuttx/configs/us7032evb1/ostest/Make.defs index 32f45eddab..379342a5d2 100644 --- a/nuttx/configs/us7032evb1/ostest/Make.defs +++ b/nuttx/configs/us7032evb1/ostest/Make.defs @@ -36,7 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \ @@ -68,7 +68,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) LDFLAGS += -g endif diff --git a/nuttx/configs/vsn/nsh/Make.defs b/nuttx/configs/vsn/nsh/Make.defs index c6ab376dec..98ef2d94c4 100644 --- a/nuttx/configs/vsn/nsh/Make.defs +++ b/nuttx/configs/vsn/nsh/Make.defs @@ -108,7 +108,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 ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer diff --git a/nuttx/configs/z16f2800100zcog/ostest/Make.defs b/nuttx/configs/z16f2800100zcog/ostest/Make.defs index 8589b5566a..e6b5ab4c69 100644 --- a/nuttx/configs/z16f2800100zcog/ostest/Make.defs +++ b/nuttx/configs/z16f2800100zcog/ostest/Make.defs @@ -73,7 +73,7 @@ EZDSZILOGINCDIR := ${shell echo "$(WZDSZILOGINCDIR)" | sed -e "s/ /%20/g"} # Assembler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug else ARCHASMOPTIMIZATION = -nodebug @@ -89,7 +89,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -NOregvar -reduceopt else ARCHOPTIMIZATION = -nodebug -regvar diff --git a/nuttx/configs/z16f2800100zcog/pashello/Make.defs b/nuttx/configs/z16f2800100zcog/pashello/Make.defs index 3620ffcbe7..e06d1dc0bf 100644 --- a/nuttx/configs/z16f2800100zcog/pashello/Make.defs +++ b/nuttx/configs/z16f2800100zcog/pashello/Make.defs @@ -73,7 +73,7 @@ EZDSZILOGINCDIR := ${shell echo "$(WZDSZILOGINCDIR)" | sed -e "s/ /%20/g"} # Assembler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug else ARCHASMOPTIMIZATION = -nodebug @@ -89,7 +89,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -NOregvar -reduceopt else ARCHOPTIMIZATION = -nodebug -regvar diff --git a/nuttx/configs/z8encore000zco/ostest/Make.defs b/nuttx/configs/z8encore000zco/ostest/Make.defs index 9e89220f8c..3991f68675 100644 --- a/nuttx/configs/z8encore000zco/ostest/Make.defs +++ b/nuttx/configs/z8encore000zco/ostest/Make.defs @@ -106,7 +106,7 @@ ARCHCPUDEF = _Z8F6403 endif endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug -sdiopt else ARCHASMOPTIMIZATION = -nodebug -sdiopt @@ -123,7 +123,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -NOregvar -reduceopt else ARCHOPTIMIZATION = -nodebug -regvar diff --git a/nuttx/configs/z8f64200100kit/ostest/Make.defs b/nuttx/configs/z8f64200100kit/ostest/Make.defs index 899f3955c7..5987934c3c 100644 --- a/nuttx/configs/z8f64200100kit/ostest/Make.defs +++ b/nuttx/configs/z8f64200100kit/ostest/Make.defs @@ -106,7 +106,7 @@ ARCHCPUDEF = _Z8F6403 endif endif -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHASMOPTIMIZATION = -debug -sdiopt else ARCHASMOPTIMIZATION = -nodebug -sdiopt @@ -123,7 +123,7 @@ AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ # Compiler definitions -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) ARCHOPTIMIZATION = -debug -NOregvar -reduceopt else ARCHOPTIMIZATION = -nodebug -regvar From afda7763683b2b6accbdf4b721b6a5b118d386ac Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 15 Nov 2012 19:22:47 +0000 Subject: [PATCH 129/206] Fix various build-related typos git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5358 42af7a65-404d-4744-a932-0658087f49c3 --- apps/Makefile | 1 - apps/examples/Makefile | 4 ++-- apps/examples/cxxtest/Makefile | 2 +- apps/examples/elf/Makefile | 2 +- apps/examples/helloxx/Makefile | 2 +- apps/examples/nettest/Makefile | 2 +- apps/examples/nxflat/Makefile | 2 +- apps/examples/romfs/Makefile | 2 +- apps/examples/udp/Makefile | 2 +- apps/graphics/Makefile | 4 ++-- apps/interpreters/Makefile | 4 ++-- apps/netutils/Makefile | 4 ++-- apps/system/Makefile | 12 +++++++++--- nuttx/tools/Config.mk | 10 ++++++---- 14 files changed, 30 insertions(+), 23 deletions(-) diff --git a/apps/Makefile b/apps/Makefile index 826694dad4..77f2012ef8 100644 --- a/apps/Makefile +++ b/apps/Makefile @@ -35,7 +35,6 @@ ############################################################################ -include $(TOPDIR)/Make.defs --include $(TOPDIR)/.config APPDIR = ${shell pwd} diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 269d2b4643..2bff9934e6 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -104,13 +104,13 @@ all: nothing define SDIR_template $(1)_$(2): - $(MAKE) -C $(1) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef $(foreach SDIR, $(CNTXTDIRS), $(eval $(call SDIR_template,$(SDIR),context))) $(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),depend))) $(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),clean))) -$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),disclean))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),distclean))) nothing: diff --git a/apps/examples/cxxtest/Makefile b/apps/examples/cxxtest/Makefile index e6bdd34fc3..b0f0befbf0 100644 --- a/apps/examples/cxxtest/Makefile +++ b/apps/examples/cxxtest/Makefile @@ -73,7 +73,7 @@ STACKSIZE = 4096 VPATH = all: .built -.PHONY: clean depend disclean chkcxx +.PHONY: clean depend distclean chkcxx chkcxx: ifneq ($(CONFIG_HAVE_CXX),y) diff --git a/apps/examples/elf/Makefile b/apps/examples/elf/Makefile index 24472139fb..8831a9336e 100644 --- a/apps/examples/elf/Makefile +++ b/apps/examples/elf/Makefile @@ -65,7 +65,7 @@ ROOTDEPPATH = --dep-path . --dep-path tests VPATH = tests all: .built -.PHONY: really_build clean_tests clean depend disclean +.PHONY: really_build clean_tests clean depend distclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) diff --git a/apps/examples/helloxx/Makefile b/apps/examples/helloxx/Makefile index fd126d345f..295d0116e7 100644 --- a/apps/examples/helloxx/Makefile +++ b/apps/examples/helloxx/Makefile @@ -73,7 +73,7 @@ STACKSIZE = 2048 VPATH = all: .built -.PHONY: clean depend disclean chkcxx +.PHONY: clean depend distclean chkcxx chkcxx: ifneq ($(CONFIG_HAVE_CXX),y) diff --git a/apps/examples/nettest/Makefile b/apps/examples/nettest/Makefile index 75e4cf0bea..c1c50bbb8f 100644 --- a/apps/examples/nettest/Makefile +++ b/apps/examples/nettest/Makefile @@ -96,7 +96,7 @@ STACKSIZE = 2048 VPATH = all: .built $(HOST_BIN) -.PHONY: clean depend disclean +.PHONY: clean depend distclean $(TARG_AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) diff --git a/apps/examples/nxflat/Makefile b/apps/examples/nxflat/Makefile index 07c163347d..4fc315592c 100644 --- a/apps/examples/nxflat/Makefile +++ b/apps/examples/nxflat/Makefile @@ -65,7 +65,7 @@ ROOTDEPPATH = --dep-path . VPATH = all: .built -.PHONY: headers clean depend disclean +.PHONY: headers clean depend distclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) diff --git a/apps/examples/romfs/Makefile b/apps/examples/romfs/Makefile index b247db6f62..3701412762 100644 --- a/apps/examples/romfs/Makefile +++ b/apps/examples/romfs/Makefile @@ -65,7 +65,7 @@ ROOTDEPPATH = --dep-path . VPATH = all: .built -.PHONY: checkgenromfs clean depend disclean +.PHONY: checkgenromfs clean depend distclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) diff --git a/apps/examples/udp/Makefile b/apps/examples/udp/Makefile index 6bfdce9cc1..d6c89cac44 100644 --- a/apps/examples/udp/Makefile +++ b/apps/examples/udp/Makefile @@ -87,7 +87,7 @@ ROOTDEPPATH = --dep-path . VPATH = all: .built -.PHONY: clean depend disclean +.PHONY: clean depend distclean $(TARG_AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) diff --git a/apps/graphics/Makefile b/apps/graphics/Makefile index bebb31b5a6..474118450b 100644 --- a/apps/graphics/Makefile +++ b/apps/graphics/Makefile @@ -48,13 +48,13 @@ all: nothing define SDIR_template $(1)_$(2): - $(MAKE) -C $(1) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef $(foreach SDIR, $(CNTXTDIRS), $(eval $(call SDIR_template,$(SDIR),context))) $(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),depend))) $(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),clean))) -$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),disclean))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),distclean))) nothing: diff --git a/apps/interpreters/Makefile b/apps/interpreters/Makefile index 1eeab585e0..3569a0044a 100644 --- a/apps/interpreters/Makefile +++ b/apps/interpreters/Makefile @@ -52,12 +52,12 @@ all: nothing define SDIR_template $(1)_$(2): - $(MAKE) -C $(1) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef $(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),depend))) $(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),clean))) -$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),disclean))) +$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),distclean))) nothing: diff --git a/apps/netutils/Makefile b/apps/netutils/Makefile index 303b804b6c..b557c73cc8 100644 --- a/apps/netutils/Makefile +++ b/apps/netutils/Makefile @@ -49,12 +49,12 @@ all: nothing define SDIR_template $(1)_$(2): - $(MAKE) -C $(1) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef $(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),depend))) $(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),clean))) -$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),disclean))) +$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),distclean))) nothing: diff --git a/apps/system/Makefile b/apps/system/Makefile index 572598e398..c59059d811 100644 --- a/apps/system/Makefile +++ b/apps/system/Makefile @@ -41,9 +41,15 @@ SUBDIRS = free i2c install readline poweroff ramtron sdcard sysinfo # Create the list of installed runtime modules (INSTALLED_DIRS) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ADD_DIRECTORY -INSTALLED_DIRS += ${shell if [ -r $1/Makefile ]; then echo "$1"; fi} + INSTALLED_DIRS += $(if $(wildcard .\$1\Makefile),$1,) endef +else +define ADD_DIRECTORY + INSTALLED_DIRS += $(if $(wildcard ./$1/Makefile),$1,) +endef +endif $(foreach DIR, $(SUBDIRS), $(eval $(call ADD_DIRECTORY,$(DIR)))) @@ -52,12 +58,12 @@ all: nothing define SDIR_template $(1)_$(2): - $(MAKE) -C $(1) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef $(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),depend))) $(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),clean))) -$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),disclean))) +$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),distclean))) nothing: diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk index b7f8d9bbe0..f05933f1ab 100644 --- a/nuttx/tools/Config.mk +++ b/nuttx/tools/Config.mk @@ -154,10 +154,12 @@ define ARCHIVE endef endif -define CLEAN ifeq ($(CONFIG_WINDOWS_NATIVE),y) +define CLEAN $(Q) rm -f *.o *.a -else - $(Q) rm -f *.o *.a *~ .*.swp -endif endef +else +define CLEAN + $(Q) rm -f *.o *.a *~ .*.swp +endef +endif From 9129fb715b69c0d2ffec2f963f57346bf89bc355 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 15 Nov 2012 19:35:15 +0000 Subject: [PATCH 130/206] Fix a place that had a '\' but needed a '/' git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5359 42af7a65-404d-4744-a932-0658087f49c3 --- apps/Makefile | 8 +++++++- apps/netutils/resolv/resolv.c | 2 ++ 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/apps/Makefile b/apps/Makefile index 77f2012ef8..c172135eca 100644 --- a/apps/Makefile +++ b/apps/Makefile @@ -102,9 +102,15 @@ endif # Create the list of available applications (INSTALLED_APPS) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ADD_BUILTIN -INSTALLED_APPS += $(if $(wildcard $1\Makefile),$1,) + INSTALLED_APPS += $(if $(wildcard $1\Makefile),$1,) endef +else +define ADD_BUILTIN + INSTALLED_APPS += $(if $(wildcard $1/Makefile),$1,) +endef +endif $(foreach BUILTIN, $(CONFIGURED_APPS), $(eval $(call ADD_BUILTIN,$(BUILTIN)))) diff --git a/apps/netutils/resolv/resolv.c b/apps/netutils/resolv/resolv.c index 346cbe175f..627c40aec9 100644 --- a/apps/netutils/resolv/resolv.c +++ b/apps/netutils/resolv/resolv.c @@ -250,6 +250,7 @@ static int send_query_socket(int sockfd, const char *name, struct sockaddr_in *a return sendto(sockfd, buffer, query + 5 - buffer, 0, (struct sockaddr*)addr, ADDRLEN); } +#if 0 /* Not used */ #ifdef CONFIG_NET_IPv6 static int send_query(const char *name, struct sockaddr_in6 *addr) #else @@ -258,6 +259,7 @@ static int send_query(const char *name, struct sockaddr_in *addr) { return send_query_socket(g_sockfd, name, addr); } +#endif /* Called when new UDP data arrives */ From e24f4089720b27bc926d778eff89297ab944e457 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 15 Nov 2012 21:35:18 +0000 Subject: [PATCH 131/206] Mirtoo differences from Konstantin; File system fix from Lorenz Meier git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5360 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 +++++ nuttx/configs/mirtoo/Kconfig | 5 +++++ nuttx/configs/mirtoo/README.txt | 6 +++--- nuttx/configs/mirtoo/src/up_spi2.c | 11 ++++++++--- nuttx/fs/fs_files.c | 1 + 5 files changed, 22 insertions(+), 6 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f907cbfcd1..9c62db68fe 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3628,4 +3628,9 @@ * arch/*/src/Makefile: Remove tftboot install and creation of System.map for Windows native build. The fist is necessary, the second just needs re-implemented. + * configs/mirtoo: Update Mirtoo pin definitions for Release 2. Provided + by Konstantin Dimitrov. + * Fixed an uninitialized variable in the file system that can cause + assertions if DEBUG on (contributed by Lorenz Meier). + diff --git a/nuttx/configs/mirtoo/Kconfig b/nuttx/configs/mirtoo/Kconfig index fe15952f31..1ff7e4246b 100644 --- a/nuttx/configs/mirtoo/Kconfig +++ b/nuttx/configs/mirtoo/Kconfig @@ -10,4 +10,9 @@ config ARCH_LEDS ---help--- "Support control of board LEDs by NuttX to indicate system state" +config MIRTOO_RELEASE + int "Mirtoo Release 1 (R1)" + default 2 + ---help--- + Select the Mirtoo release number endif diff --git a/nuttx/configs/mirtoo/README.txt b/nuttx/configs/mirtoo/README.txt index e0b7dc3bc8..488884ba58 100644 --- a/nuttx/configs/mirtoo/README.txt +++ b/nuttx/configs/mirtoo/README.txt @@ -199,19 +199,19 @@ PIN PIC32 SIGNAL(s) BOARD SIGNAL/USAGE --- ------------------------------------------------ ---------------------------------- ---------------------------------- 29 VSS VSS Not available off module --- ------------------------------------------------ ---------------------------------- ---------------------------------- -30 OSC1/CLKI/RPA2/RA2 SO Not available off module +30 OSC1/CLKI/RPA2/RA2 SO (R1) DIN0 (R2) Not available off module OSC1 Oscillator crystal input Not available CLKI External clock source input Not available RPRA2 Peripheral Selection PORTA, Pin 2 Used for SO RA2 PORTA, Pin 2 Not available --- ------------------------------------------------ ---------------------------------- ---------------------------------- -31 OSC2/CLKO/RPA3/RA3 DIN0 PORT0, to X1, pin 2 +31 OSC2/CLKO/RPA3/RA3 DIN0 (R1) DIN3 (R2) PORT0, to X1, pin 2 OSC2 Oscillator crystal output Not available (also X13, pin1) CLKO Oscillator crystal output Not available RPA3 Peripheral Selection for PORTA, Pin 3 May be used for peripheral input RA3 PORTA, Pin 3 May be used for GPIO input --- ------------------------------------------------ ---------------------------------- ---------------------------------- -32 TDO/RPA8/PMA8/RA8 DIN3 PORT3, to X5, pin 2 +32 TDO/RPA8/PMA8/RA8 DIN3 (R1) S0 (R2) PORT3, to X5, pin 2 TDO JTAG test data output pin Not available (also X13, pin7) RPA8 PORTA, Pin 8 May be used for peripheral input PMA8 Parallel Master Port Address bit 8 Not available diff --git a/nuttx/configs/mirtoo/src/up_spi2.c b/nuttx/configs/mirtoo/src/up_spi2.c index 3b43497d7d..0565707106 100644 --- a/nuttx/configs/mirtoo/src/up_spi2.c +++ b/nuttx/configs/mirtoo/src/up_spi2.c @@ -74,7 +74,8 @@ * PIN SIGNAL BOARD CONNECTION NOTES * ------ -------- ------------------------- -------------------------------- * RPA1 SI PGA117 and SST25VF032B SPI2 data OUT (SDO2) - * RPA2 SO PGA117 and SST25VF032B SPI2 data IN (SDI2) + * RPA2 SO PGA117 and SST25VF032B R1, SPI2 data IN (SDI2) + * RPA3 SO PGA117 and SST25VF032B R0, SPI2 data IN (SDI2) * SCK2 SCK PGA117 and SST25VF032B SPI2 clock * * RB7 ~CSAI PGA117 PGA117 chip select (active low) @@ -82,8 +83,12 @@ */ #define GPIO_SI (GPIO_OUTPUT|GPIO_PORTA|GPIO_PIN1) -#define GPIO_SO (GPIO_INPUT|GPIO_PORTA|GPIO_PIN1) -#define GPIO_SCK (GPIO_OUTPUT|GPIO_PORTA|GPIO_PIN1) +#ifdef CONFIG_MIRTOO_RELEASE == 1 +# define GPIO_SO (GPIO_INPUT|GPIO_PORTA|GPIO_PIN2) +#else +# define GPIO_SO (GPIO_INPUT|GPIO_PORTA|GPIO_PIN3) +#endif +#define GPIO_SCK (GPIO_OUTPUT|GPIO_PORTB|GPIO_PIN15) #define GPIO_PGA117_CS (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTB|GPIO_PIN7) #define GPIO_SST25VF032B_CS (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTB|GPIO_PIN13) diff --git a/nuttx/fs/fs_files.c b/nuttx/fs/fs_files.c index 425e7c73f8..4da2d28a52 100644 --- a/nuttx/fs/fs_files.c +++ b/nuttx/fs/fs_files.c @@ -400,6 +400,7 @@ int files_allocate(FAR struct inode *inode, int oflags, off_t pos, int minfd) list->fl_files[i].f_oflags = oflags; list->fl_files[i].f_pos = pos; list->fl_files[i].f_inode = inode; + list->fl_files[i].f_priv = NULL; _files_semgive(list); return i; } From da3dd04ea56562e2a50606be907fe99d11822d9d Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 16 Nov 2012 12:41:58 +0000 Subject: [PATCH 132/206] Changes from Mike git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5361 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 3 +++ apps/Makefile | 11 +++-------- apps/examples/elf/tests/errno/Makefile | 3 ++- apps/examples/elf/tests/hello/Makefile | 3 ++- apps/examples/elf/tests/helloxx/Makefile | 9 +++++---- apps/examples/elf/tests/longjmp/Makefile | 3 ++- apps/examples/elf/tests/mutex/Makefile | 3 ++- apps/examples/elf/tests/pthread/Makefile | 3 ++- apps/examples/elf/tests/signal/Makefile | 3 ++- apps/examples/elf/tests/struct/Makefile | 3 ++- apps/examples/elf/tests/task/Makefile | 3 ++- misc/tools/README.txt | 10 ++++++++-- nuttx/ChangeLog | 4 +++- nuttx/tools/Config.mk | 13 +++++++++++++ nuttx/tools/Makefile.host | 6 ++++-- 15 files changed, 55 insertions(+), 25 deletions(-) diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 1a88900bed..c1c5189c43 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -419,3 +419,6 @@ by Freddie Chopin. * Makefile, */Makefile: Various fixes for Windows native build. Now uses make foreach loops instead of shell loops. + * apps/examples/elf/test/*/Makefile: OSX doesn't support install -D, use + mkdir -p then install without the -D. From Mike Smith. + diff --git a/apps/Makefile b/apps/Makefile index c172135eca..7e7d52a405 100644 --- a/apps/Makefile +++ b/apps/Makefile @@ -102,15 +102,9 @@ endif # Create the list of available applications (INSTALLED_APPS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ADD_BUILTIN - INSTALLED_APPS += $(if $(wildcard $1\Makefile),$1,) + INSTALLED_APPS += $(if $(wildcard $1$(DELIM)Makefile),$1,) endef -else -define ADD_BUILTIN - INSTALLED_APPS += $(if $(wildcard $1/Makefile),$1,) -endef -endif $(foreach BUILTIN, $(CONFIGURED_APPS), $(eval $(call ADD_BUILTIN,$(BUILTIN)))) @@ -119,7 +113,8 @@ $(foreach BUILTIN, $(CONFIGURED_APPS), $(eval $(call ADD_BUILTIN,$(BUILTIN)))) # provided by the user (possibly as a symbolic link) to add libraries and # applications to the standard build from the repository. -EXTERNAL_DIR := $(dir $(wildcard external/Makefile)) +EXTERNAL_DIR := $(dir $(wildcard external$(DELIM)Makefile)) + INSTALLED_APPS += $(EXTERNAL_DIR) SUBDIRS += $(EXTERNAL_DIR) diff --git a/apps/examples/elf/tests/errno/Makefile b/apps/examples/elf/tests/errno/Makefile index 92cff9e12f..09d469f9b4 100644 --- a/apps/examples/elf/tests/errno/Makefile +++ b/apps/examples/elf/tests/errno/Makefile @@ -55,5 +55,6 @@ clean: @rm -f $(BIN) *.o *~ .*.swp core install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + @mkdir -p $(ROMFS_DIR) + @install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/hello/Makefile b/apps/examples/elf/tests/hello/Makefile index e1c396c3c7..88770276b3 100644 --- a/apps/examples/elf/tests/hello/Makefile +++ b/apps/examples/elf/tests/hello/Makefile @@ -55,4 +55,5 @@ clean: @rm -f $(BIN) *.o *~ .*.swp core install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + @mkdir -p $(ROMFS_DIR) + @install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/helloxx/Makefile b/apps/examples/elf/tests/helloxx/Makefile index d115fbeaf4..45b4b8868e 100644 --- a/apps/examples/elf/tests/helloxx/Makefile +++ b/apps/examples/elf/tests/helloxx/Makefile @@ -109,12 +109,13 @@ clean: @rm -f $(ALL_BIN) *.o *~ .*.swp core install: $(ALL_BIN) - @install -D $(BIN1) $(ROMFS_DIR)/$(BIN1) - @install -D $(BIN2) $(ROMFS_DIR)/$(BIN2) + @mkdir -p $(ROMFS_DIR) + @install $(BIN1) $(ROMFS_DIR)/$(BIN1) + @install $(BIN2) $(ROMFS_DIR)/$(BIN2) ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) - @install -D $(BIN3) $(ROMFS_DIR)/$(BIN3) + @install $(BIN3) $(ROMFS_DIR)/$(BIN3) endif -# @install -D $(BIN4) $(ROMFS_DIR)/$(BIN4) +# @install $(BIN4) $(ROMFS_DIR)/$(BIN4) diff --git a/apps/examples/elf/tests/longjmp/Makefile b/apps/examples/elf/tests/longjmp/Makefile index 0cafe05e37..04da6ee819 100644 --- a/apps/examples/elf/tests/longjmp/Makefile +++ b/apps/examples/elf/tests/longjmp/Makefile @@ -55,4 +55,5 @@ clean: @rm -f $(BIN) *.o *~ .*.swp core install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + @mkdir -p $(ROMFS_DIR) + @install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/mutex/Makefile b/apps/examples/elf/tests/mutex/Makefile index efce216d87..756ada2c09 100644 --- a/apps/examples/elf/tests/mutex/Makefile +++ b/apps/examples/elf/tests/mutex/Makefile @@ -55,4 +55,5 @@ clean: @rm -f $(BIN) *.o *~ .*.swp core install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + @mkdir -p $(ROMFS_DIR) + @install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/pthread/Makefile b/apps/examples/elf/tests/pthread/Makefile index 134fabe01a..4bea4515b0 100644 --- a/apps/examples/elf/tests/pthread/Makefile +++ b/apps/examples/elf/tests/pthread/Makefile @@ -55,4 +55,5 @@ clean: @rm -f $(BIN) *.o *~ .*.swp core install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + @mkdir -p $(ROMFS_DIR) + @install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/signal/Makefile b/apps/examples/elf/tests/signal/Makefile index 08710aeaa5..9eaaf86096 100644 --- a/apps/examples/elf/tests/signal/Makefile +++ b/apps/examples/elf/tests/signal/Makefile @@ -55,4 +55,5 @@ clean: @rm -f $(BIN) *.o *~ .*.swp core install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + @mkdir -p $(ROMFS_DIR) + @install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/struct/Makefile b/apps/examples/elf/tests/struct/Makefile index 3aa0e4a572..2ddd80b893 100644 --- a/apps/examples/elf/tests/struct/Makefile +++ b/apps/examples/elf/tests/struct/Makefile @@ -56,4 +56,5 @@ clean: @rm -f $(BIN) *.o *~ .*.swp core install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + @mkdir -p $(ROMFS_DIR) + @install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/task/Makefile b/apps/examples/elf/tests/task/Makefile index 63a2eb211c..accac987f2 100644 --- a/apps/examples/elf/tests/task/Makefile +++ b/apps/examples/elf/tests/task/Makefile @@ -55,4 +55,5 @@ clean: @rm -f $(BIN) *.o *~ .*.swp core install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + @mkdir -p $(ROMFS_DIR) + @install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/misc/tools/README.txt b/misc/tools/README.txt index fff94cd3f5..47c966921a 100644 --- a/misc/tools/README.txt +++ b/misc/tools/README.txt @@ -50,11 +50,17 @@ kconfig-frontends-3.3.0-1-libintl.patch http://ymorin.is-a-geek.org/download/kconfig-frontends/ -kconfig-macos.path ------------------- +kconfig-macos.patch +------------------- This is a patch to make the kconfig-frontends-3.3.0 build on Mac OS X. + To build the conf and mconf frontends, use the following commands: + + ./configure --disable-shared --enable-static --disable-gconf --disable-qconf --disable-nconf --disable-utils + make + make install + kconfig-frontends for Windows ============================= diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 9c62db68fe..72fab8a711 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3632,5 +3632,7 @@ by Konstantin Dimitrov. * Fixed an uninitialized variable in the file system that can cause assertions if DEBUG on (contributed by Lorenz Meier). - + * Config.mk: Defined DELIM to be either / or \, depending upon + CONFIG_WINDOWS_NATIVE. This will allow me to eliminate a lot of + conditional logic elsewhere. diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk index f05933f1ab..4cdda113c7 100644 --- a/nuttx/tools/Config.mk +++ b/nuttx/tools/Config.mk @@ -43,6 +43,19 @@ CONFIG_ARCH := $(patsubst "%",%,$(strip $(CONFIG_ARCH))) CONFIG_ARCH_CHIP := $(patsubst "%",%,$(strip $(CONFIG_ARCH_CHIP))) CONFIG_ARCH_BOARD := $(patsubst "%",%,$(strip $(CONFIG_ARCH_BOARD))) +# DELIM - Path segment delimiter character +# +# Depends on this settings defined in board-specific defconfig file installed +# at $(TOPDIR)/.config: +# +# CONFIG_WINDOWS_NATIVE - Defined for a Windows native build + +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + DELIM = $(strip \) +else + DELIM = $(strip /) +endif + # INCDIR - Convert a list of directory paths to a list of compiler include # directirves # Example: CFFLAGS += ${shell $(INCDIR) [options] "compiler" "dir1" "dir2" "dir2" ...} diff --git a/nuttx/tools/Makefile.host b/nuttx/tools/Makefile.host index 4786250088..16975a42a3 100644 --- a/nuttx/tools/Makefile.host +++ b/nuttx/tools/Makefile.host @@ -123,5 +123,7 @@ endif clean: $(Q) rm -f *.o *.a *~ .*.swp - $(Q) rm -f mkconfig mksyscall mkversion bdf-converter - $(Q) rm -f mkconfig.exe mksyscall.exe mkversion.exe bdf-converter.exe + $(Q) rm -f mkdeps mkconfig mksyscall mkversion bdf-converter + $(Q) rm -f mkdeps.exe mkconfig.exe mksyscall.exe mkversion.exe bdf-converter.exe + $(Q) rm -rf *.dSYM + From 8b823f6beeae9c0dcc75cbc92bb7d977533e0b7d Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 16 Nov 2012 14:13:04 +0000 Subject: [PATCH 133/206] Mostly cosmetic build changes git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5362 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/Makefile | 2 +- apps/graphics/Makefile | 2 +- apps/interpreters/Makefile | 2 +- apps/netutils/Makefile | 2 +- apps/system/Makefile | 2 +- nuttx/Makefile.unix | 10 ++++----- nuttx/Makefile.win | 12 +++++------ nuttx/arch/8051/src/Makefile | 40 ++++++++++++++++++------------------ nuttx/arch/arm/src/Makefile | 10 ++++----- nuttx/arch/z16/src/Makefile | 34 +++++++++++++++--------------- 10 files changed, 58 insertions(+), 58 deletions(-) diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 2bff9934e6..9d20e9312d 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -104,7 +104,7 @@ all: nothing define SDIR_template $(1)_$(2): - $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + $(Q) $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef $(foreach SDIR, $(CNTXTDIRS), $(eval $(call SDIR_template,$(SDIR),context))) diff --git a/apps/graphics/Makefile b/apps/graphics/Makefile index 474118450b..94d2ff5c0f 100644 --- a/apps/graphics/Makefile +++ b/apps/graphics/Makefile @@ -48,7 +48,7 @@ all: nothing define SDIR_template $(1)_$(2): - $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + $(Q) $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef $(foreach SDIR, $(CNTXTDIRS), $(eval $(call SDIR_template,$(SDIR),context))) diff --git a/apps/interpreters/Makefile b/apps/interpreters/Makefile index 3569a0044a..08385433aa 100644 --- a/apps/interpreters/Makefile +++ b/apps/interpreters/Makefile @@ -52,7 +52,7 @@ all: nothing define SDIR_template $(1)_$(2): - $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + $(Q) $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef $(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),depend))) diff --git a/apps/netutils/Makefile b/apps/netutils/Makefile index b557c73cc8..0879ada4e7 100644 --- a/apps/netutils/Makefile +++ b/apps/netutils/Makefile @@ -49,7 +49,7 @@ all: nothing define SDIR_template $(1)_$(2): - $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + $(Q) $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef $(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),depend))) diff --git a/apps/system/Makefile b/apps/system/Makefile index c59059d811..9955a6b2ce 100644 --- a/apps/system/Makefile +++ b/apps/system/Makefile @@ -58,7 +58,7 @@ all: nothing define SDIR_template $(1)_$(2): - $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + $(Q) $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef $(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),depend))) diff --git a/nuttx/Makefile.unix b/nuttx/Makefile.unix index ba0005771c..439aa2d4bd 100644 --- a/nuttx/Makefile.unix +++ b/nuttx/Makefile.unix @@ -368,26 +368,26 @@ endif # Link the arch//include directory to include/arch include/arch: Make.defs - @echo "LN: include/arch -> $(TOPDIR)/$(ARCH_DIR)/include" + @echo "LN: include/arch -> $(ARCH_DIR)/include" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_DIR)/include include/arch # Link the configs//include directory to include/arch/board include/arch/board: include/arch Make.defs include/arch - @echo "LN: include/arch/board -> $(TOPDIR)/$(BOARD_DIR)/include" + @echo "LN: include/arch/board -> $(BOARD_DIR)/include" $(Q) $(DIRLINK) $(TOPDIR)/$(BOARD_DIR)/include include/arch/board # Link the configs//src dir to arch//src/board $(ARCH_SRC)/board: Make.defs - @echo "LN: $(ARCH_SRC)/board -> $(TOPDIR)/$(BOARD_DIR)/src" + @echo "LN: $(ARCH_SRC)/board -> $(BOARD_DIR)/src" $(Q) $(DIRLINK) $(TOPDIR)/$(BOARD_DIR)/src $(ARCH_SRC)/board # Link arch//include/ to arch//include/chip $(ARCH_SRC)/chip: Make.defs ifneq ($(CONFIG_ARCH_CHIP),) - @echo "LN: $(ARCH_SRC)/chip -> $(TOPDIR)\$(ARCH_SRC)/$(CONFIG_ARCH_CHIP)" + @echo "LN: $(ARCH_SRC)/chip -> $(ARCH_SRC)/$(CONFIG_ARCH_CHIP)" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_SRC)/$(CONFIG_ARCH_CHIP) $(ARCH_SRC)/chip endif @@ -395,7 +395,7 @@ endif include/arch/chip: include/arch Make.defs ifneq ($(CONFIG_ARCH_CHIP),) - @echo "LN: include/arch/chip -> $(TOPDIR)/$(ARCH_INC)/$(CONFIG_ARCH_CHIP)" + @echo "LN: include/arch/chip -> $(ARCH_INC)/$(CONFIG_ARCH_CHIP)" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_INC)/$(CONFIG_ARCH_CHIP) include/arch/chip endif diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win index c3c80cd105..f43f14f0da 100644 --- a/nuttx/Makefile.win +++ b/nuttx/Makefile.win @@ -69,7 +69,7 @@ BOARD_DIR = configs\$(CONFIG_ARCH_BOARD) ifeq ($(CONFIG_APPS_DIR),) CONFIG_APPS_DIR = ..\apps endif -APPDIR := ${shell if exist "$(CONFIG_APPS_DIR)\Makefile" echo "$(CONFIG_APPS_DIR)"} +APPDIR := ${shell if exist "$(CONFIG_APPS_DIR)\Makefile" echo $(CONFIG_APPS_DIR)} # All add-on directories. # @@ -364,7 +364,7 @@ endif # Link the arch\\include directory to include\arch include\arch: Make.defs - @echo "LN: include\arch -> $(TOPDIR)\$(ARCH_DIR)\include" + @echo "LN: include\arch -> $(ARCH_DIR)\include" ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d include\arch $(TOPDIR)\$(ARCH_DIR)\include else @@ -375,7 +375,7 @@ endif # Link the configs\\include directory to include\arch\board include\arch\board: include\arch Make.defs include\arch - @echo "LN: include\arch\board -> $(TOPDIR)\$(BOARD_DIR)\include" + @echo "LN: include\arch\board -> $(BOARD_DIR)\include" ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d include\arch\board $(TOPDIR)\$(BOARD_DIR)\include else @@ -386,7 +386,7 @@ endif # Link the configs\\src dir to arch\\src\board $(ARCH_SRC)\board: Make.defs - @echo "LN: $(ARCH_SRC)\board -> $(TOPDIR)\$(BOARD_DIR)\src" + @echo "LN: $(ARCH_SRC)\board -> $(BOARD_DIR)\src" ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d $(ARCH_SRC)\board $(TOPDIR)\$(BOARD_DIR)\src else @@ -398,7 +398,7 @@ endif $(ARCH_SRC)\chip: Make.defs ifneq ($(CONFIG_ARCH_CHIP),) - @echo "LN: $(ARCH_SRC)\chip -> $(TOPDIR)\$(ARCH_SRC)\$(CONFIG_ARCH_CHIP)" + @echo "LN: $(ARCH_SRC)\chip -> $(ARCH_SRC)\$(CONFIG_ARCH_CHIP)" ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d $(ARCH_SRC)\chip $(TOPDIR)\$(ARCH_SRC)\$(CONFIG_ARCH_CHIP) else @@ -411,7 +411,7 @@ endif include\arch\chip: include\arch Make.defs ifneq ($(CONFIG_ARCH_CHIP),) - @echo "LN: include\arch\chip -> $(TOPDIR)\$(ARCH_INC)\$(CONFIG_ARCH_CHIP)" + @echo "LN: include\arch\chip -> $(ARCH_INC)\$(CONFIG_ARCH_CHIP)" ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d include\arch\chip $(TOPDIR)\$(ARCH_INC)\$(CONFIG_ARCH_CHIP) else diff --git a/nuttx/arch/8051/src/Makefile b/nuttx/arch/8051/src/Makefile index 0f1b1b8577..4772834d9c 100644 --- a/nuttx/arch/8051/src/Makefile +++ b/nuttx/arch/8051/src/Makefile @@ -153,44 +153,44 @@ libarch$(LIBEXT): up_mem.h $(OBJS) # This is a kludge to work around some conflicting symbols in libsdcc.liXqueb $(SDCCLIBDIR)/libmysdcc.lib: $(SDCCLIBDIR)/libsdcc.lib - @cat $(SDCCLIBDIR)/libsdcc.lib | \ + $(Q) cat $(SDCCLIBDIR)/libsdcc.lib | \ grep -v calloc | grep -v malloc | grep -v realloc | \ grep -v free | grep -v vprintf | grep -v _strncpy | \ grep -v _strchr | grep -v _strlen | grep -v _strcmp | \ grep -v _strcpy | grep -v _memcmp | grep -v _memcpy | \ grep -v _memset \ > libmysdcc.lib - @mv -f libmysdcc.lib $(SDCCLIBDIR)/libmysdcc.lib + $(Q) mv -f libmysdcc.lib $(SDCCLIBDIR)/libmysdcc.lib # This builds the libboard library in the board/ subdirectory board/libboard$(LIBEXT): - $(MAKE) -C board TOPDIR=$(TOPDIR) libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) + $(Q) $(MAKE) -C board TOPDIR=$(TOPDIR) libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) # This target builds the final executable pass1.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS) board/libboard$(LIBEXT) @echo "LD: $@" - @"$(CC)" $(LDFLAGS) $(LIBPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \ + $(Q) "$(CC)" $(LDFLAGS) $(LIBPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \ $(LDLIBS) -llibboard$(LIBEXT) $(SDCCLIBS) -o $@ - @rm -f up_mem.h - @rm -f up_allocateheap$(OBJEXT) libarch$(LIBEXT) - @$(MAKE) TOPDIR=$(TOPDIR) libarch$(LIBEXT) + $(Q) rm -f up_mem.h + $(Q) rm -f up_allocateheap$(OBJEXT) libarch$(LIBEXT) + $(Q) $(MAKE) TOPDIR=$(TOPDIR) libarch$(LIBEXT) nuttx.hex: up_mem.h $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS) @echo "LD: $@" - @"$(CC)" $(LDFLAGS) $(LIBPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \ + $(Q) "$(CC)" $(LDFLAGS) $(LIBPATHS) -L$(BOARDDIR) $(SDCCPATH) $(LINKOBJS) \ $(LDLIBS) -llibboard$(LIBEXT) $(SDCCLIBS) -o $@ nuttx$(EXEEXT): pass1.hex nuttx.hex - @rm -f pass1.* - @packihx nuttx.hex > $(TOPDIR)/nuttx$(EXEEXT) - @cp -f nuttx.map $(TOPDIR)/. + $(Q) rm -f pass1.* + $(Q) packihx nuttx.hex > $(TOPDIR)/nuttx$(EXEEXT) + $(Q) cp -f nuttx.map $(TOPDIR)/. # This is part of the top-level export target export_head: board/libboard$(LIBEXT) p_head$(OBJEXT) - @if [ -d "$(EXPORT_DIR)/startup" ]; then \ + $(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \ cp -f up_head$(OBJEXT) "$(EXPORT_DIR)/startup"; \ else \ echo "$(EXPORT_DIR)/startup does not exist"; \ @@ -201,31 +201,31 @@ export_head: board/libboard$(LIBEXT) p_head$(OBJEXT) # a PHONY target that just sets upt the up_irqtest build correctly up_irqtest.hex: $(TESTOBJS) - "$(CC)" $(LDFLAGS) -L. $(SDCCPATH) $(TESTLINKOBJS) $(TESTOBJS) $(TESTEXTRAOBJS) $(SDCCLIBS) -o $@ + $(Q) "$(CC)" $(LDFLAGS) -L. $(SDCCPATH) $(TESTLINKOBJS) $(TESTOBJS) $(TESTEXTRAOBJS) $(SDCCLIBS) -o $@ irqtest: - @$(MAKE) TOPDIR=../../.. up_irqtest.hex + $(Q) $(MAKE) TOPDIR=../../.. up_irqtest.hex # Build dependencies .depend: Makefile up_mem.h $(DEPSRCS) - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR=$(TOPDIR) depend ; \ fi - @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR=$(TOPDIR) clean ; \ fi - @rm -f libarch$(LIBEXT) up_mem.h *~ .*.swp + $(Q) rm -f libarch$(LIBEXT) up_mem.h *~ .*.swp $(call CLEAN) distclean: clean - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR=$(TOPDIR) distclean ; \ fi rm -f Make.dep .depend diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index ba506d4da1..a48d18799b 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -155,11 +155,11 @@ endif export_head: board/libboard$(LIBEXT) $(HEAD_OBJ) ifneq ($(HEAD_OBJ),) $(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \ - cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \ + cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \ else \ - echo "$(EXPORT_DIR)/startup does not exist"; \ + echo "$(EXPORT_DIR)/startup does not exist"; \ exit 1; \ - fi + fi endif # Dependencies @@ -176,14 +176,14 @@ depend: .depend clean: ifeq ($(BOARDMAKE),y) - $(MAKE) -C board TOPDIR="$(TOPDIR)" clean + $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif $(Q) rm -f libarch$(LIBEXT) *~ .*.swp $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) - $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean + $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif $(Q) rm -f Make.dep .depend diff --git a/nuttx/arch/z16/src/Makefile b/nuttx/arch/z16/src/Makefile index a2a441f742..44f96d03d4 100644 --- a/nuttx/arch/z16/src/Makefile +++ b/nuttx/arch/z16/src/Makefile @@ -49,7 +49,7 @@ INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) CPPFLAGS += -I$(ARCHSRCDIR) ifeq ($(COMPILER),zneocc.exe) -LDFLAGS += @"${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}" +LDFLAGS += "${shell cygpath -w $(ARCHSRCDIR)/nuttx.linkcmd}" endif HEAD_ASRC = $(HEAD_SSRC:.S=$(ASMEXT)) @@ -73,9 +73,9 @@ all: $(HEAD_OBJ) libarch$(LIBEXT) ifeq ($(COMPILER),zneocc.exe) $(ASRCS) $(HEAD_ASRC): %$(ASMEXT): %.S - @$(CPP) $(CPPFLAGS) $< -o $@.tmp - @cat $@.tmp | sed -e "s/^#/;/g" > $@ - @rm $@.tmp + $(Q) $(CPP) $(CPPFLAGS) $< -o $@.tmp + $(Q) cat $@.tmp | sed -e "s/^#/;/g" > $@ + $(Q) rm $@.tmp $(AOBJS) $(HEAD_OBJ): %$(OBJEXT): %$(ASMEXT) $(call ASSEMBLE, $<, $@) @@ -91,14 +91,14 @@ libarch$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) board/libboard$(LIBEXT): - @$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) + $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) ifeq ($(COMPILER),zneocc.exe) nuttx.linkcmd: $(LINKCMDTEMPLATE) - @cp -f $(LINKCMDTEMPLATE) nuttx.linkcmd + $(Q) cp -f $(LINKCMDTEMPLATE) nuttx.linkcmd @echo "\"${shell cygpath -w $(TOPDIR)/nuttx}\"= \\" >>nuttx.linkcmd @echo " \"${shell cygpath -w $(ARCHSRCDIR)/$(HEAD_OBJ)}\", \\" >>nuttx.linkcmd - @( for lib in $(LINKLIBS); do \ + $(Q) ( for lib in $(LINKLIBS); do \ echo " \"`cygpath -w $(TOPDIR)/lib/$${lib}`\", \\" >>nuttx.linkcmd; \ done ; ) @echo " \"${shell cygpath -w $(ARCHSRCDIR)/board/libboard$(LIBEXT)}\", \\" >>nuttx.linkcmd @@ -110,19 +110,19 @@ endif nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) nuttx.linkcmd @echo "LD: nuttx$(EXEEXT)" - @$(LD) $(LDFLAGS) + $(Q) $(LD) $(LDFLAGS) .depend: Makefile chip/Make.defs $(DEPSRCS) - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \ fi - @$(MKDEP) --dep-path chip --dep-path common "$(CC)" -- $(CFLAGS) -- $(DEPSRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) --dep-path chip --dep-path common "$(CC)" -- $(CFLAGS) -- $(DEPSRCS) >Make.dep + $(Q) touch $@ # This is part of the top-level export target export_head: board/libboard$(LIBEXT) $(HEAD_OBJ) - @if [ -d "$(EXPORT_DIR)/startup" ]; then \ + $(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \ cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \ else \ echo "$(EXPORT_DIR)/startup does not exist"; \ @@ -134,19 +134,19 @@ export_head: board/libboard$(LIBEXT) $(HEAD_OBJ) depend: .depend clean: - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi - @rm -f libarch$(LIBEXT) *~ .*.swp + $(Q) rm -f libarch$(LIBEXT) *~ .*.swp ifeq ($(COMPILER),zneocc.exe) - @rm -f nuttx.linkcmd *.asm *.tmp *.map + $(Q) rm -f nuttx.linkcmd *.asm *.tmp *.map endif $(call CLEAN) distclean: clean - @if [ -e board/Makefile ]; then \ + $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - @rm -f Make.dep .depend + $(Q) rm -f Make.dep .depend -include Make.dep From 48247aa52fa3d5d88f01db31d82f941526876d6e Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 16 Nov 2012 15:53:16 +0000 Subject: [PATCH 134/206] Fixes for CCycleButton unit test; Add CNumericEdit. Both from Petteri Aimonen git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5363 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/ChangeLog.txt | 4 + NxWidgets/libnxwidgets/Makefile | 1 + .../libnxwidgets/include/ccyclebutton.hxx | 12 +- .../libnxwidgets/include/cnumericedit.hxx | 213 ++++++++++++++ NxWidgets/libnxwidgets/src/cnumericedit.cxx | 262 ++++++++++++++++++ NxWidgets/libnxwidgets/src/glyph_cycle.cxx | 4 +- 6 files changed, 488 insertions(+), 8 deletions(-) create mode 100644 NxWidgets/libnxwidgets/include/cnumericedit.hxx create mode 100644 NxWidgets/libnxwidgets/src/cnumericedit.cxx diff --git a/NxWidgets/ChangeLog.txt b/NxWidgets/ChangeLog.txt index 113945f2f4..dca1f856dd 100644 --- a/NxWidgets/ChangeLog.txt +++ b/NxWidgets/ChangeLog.txt @@ -200,3 +200,7 @@ Contributed by Petteri Aimonen. * NxWidgets/nxwm/src/ctaskbar.cxx: Highlight the current window in the task bar. Contributed by Petteri Aimonen. +* NxWidgets/libnxwidgets/src/glyph_cycle.cxx: Width of glyph_cycle was wrong; + Desctructor needs to by public. From Petteri Aimonen. +* CNumericEdit. This is basically a label with plus and minus buttons. + Contributed by Petteri, Aimonen. diff --git a/NxWidgets/libnxwidgets/Makefile b/NxWidgets/libnxwidgets/Makefile index 222f008b74..654f1d2fc6 100644 --- a/NxWidgets/libnxwidgets/Makefile +++ b/NxWidgets/libnxwidgets/Makefile @@ -58,6 +58,7 @@ CXXSRCS += cwindoweventhandlerlist.cxx singletons.cxx CXXSRCS += cbutton.cxx cbuttonarray.cxx ccheckbox.cxx ccyclebutton.cxx CXXSRCS += cglyphbutton.cxx cimage.cxx ckeypad.cxx clabel.cxx clatchbutton.cxx CXXSRCS += clatchbuttonarray.cxx clistbox.cxx clistboxdataitem.cxx cmultilinetextbox.cxx +CXXSRCS += cnumericedit.cxx CXXSRCS += cprogressbar.cxx cradiobutton.cxx cradiobuttongroup.cxx cscrollbarhorizontal.cxx CXXSRCS += cscrollbarpanel.cxx cscrollbarvertical.cxx cscrollinglistbox.cxx CXXSRCS += cscrollingpanel.cxx cscrollingtextbox.cxx csliderhorizontal.cxx diff --git a/NxWidgets/libnxwidgets/include/ccyclebutton.hxx b/NxWidgets/libnxwidgets/include/ccyclebutton.hxx index 5fd9405d8a..f7f9659332 100644 --- a/NxWidgets/libnxwidgets/include/ccyclebutton.hxx +++ b/NxWidgets/libnxwidgets/include/ccyclebutton.hxx @@ -179,12 +179,6 @@ namespace NXWidgets virtual inline void calculateTextPosition(void) { } - /** - * Destructor. - */ - - virtual ~CCycleButton(void) { } - /** * Copy constructor is protected to prevent usage. */ @@ -212,6 +206,12 @@ namespace NXWidgets nxgl_coord_t width, nxgl_coord_t height, CWidgetStyle *style = (CWidgetStyle *)NULL); + /** + * Destructor. + */ + + virtual ~CCycleButton(void) { } + /** * Add a new option to the widget. * diff --git a/NxWidgets/libnxwidgets/include/cnumericedit.hxx b/NxWidgets/libnxwidgets/include/cnumericedit.hxx new file mode 100644 index 0000000000..3de01a4c13 --- /dev/null +++ b/NxWidgets/libnxwidgets/include/cnumericedit.hxx @@ -0,0 +1,213 @@ +/**************************************************************************** + * NxWidgets/libnxwidgets/include/cnumericedit.hxx + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Petteri Aimonen + * + * 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, NxWidgets, nor the names of its contributors + * me 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. + * + **************************************************************************** + * + * Portions of this package derive from Woopsi (http://woopsi.org/) and + * portions are original efforts. It is difficult to determine at this + * point what parts are original efforts and which parts derive from Woopsi. + * However, in any event, the work of Antony Dzeryn will be acknowledged + * in all NxWidget files. Thanks Antony! + * + * Copyright (c) 2007-2011, Antony Dzeryn + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * 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. + * * Neither the names "Woopsi", "Simian Zombie" 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 Antony Dzeryn ``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 Antony Dzeryn 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 __INCLUDE_CNUMERICEDIT_HXX +#define __INCLUDE_CNUMERICEDIT_HXX + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#include "cnxwidget.hxx" +#include "cwidgetstyle.hxx" +#include "cnxstring.hxx" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Implementation Classes + ****************************************************************************/ + +#if defined(__cplusplus) + +namespace NXWidgets +{ + /** + * Forward references + */ + + class CWidgetControl; + class CRect; + class CLabel; + class CButton; + class CNxTimer; + + /** + * Numeric edit control, with plus and minus buttons. + */ + + class CNumericEdit : public CNxWidget, public CWidgetEventHandler + { + protected: + CLabel *m_label; + CButton *m_button_minus; + CButton *m_button_plus; + CNxTimer *m_timer; + int m_value; + int m_minimum; + int m_maximum; + int m_increment; + int m_timercount; + + /** + * Resize the widget to the new dimensions. + * + * @param width The new width. + * @param height The new height. + */ + + virtual void onResize(nxgl_coord_t width, nxgl_coord_t height); + + virtual void handleClickEvent(const CWidgetEventArgs &e); + + virtual void handleReleaseEvent(const CWidgetEventArgs &e); + + virtual void handleReleaseOutsideEvent(const CWidgetEventArgs &e); + + virtual void handleActionEvent(const CWidgetEventArgs &e); + + virtual void handleDragEvent(const CWidgetEventArgs &e); + + /** + * Copy constructor is protected to prevent usage. + */ + + inline CNumericEdit(const CNumericEdit &num) : CNxWidget(num) { }; + + public: + + /** + * Constructor for a numeric edit control. + * + * @param pWidgetControl The controlling widget for the display + * @param x The x coordinate of the text box, relative to its parent. + * @param y The y coordinate of the text box, relative to its parent. + * @param width The width of the textbox. + * @param height The height of the textbox. + * @param style The style that the button should use. If this is not + * specified, the button will use the global default widget + * style. + */ + + CNumericEdit(CWidgetControl *pWidgetControl, nxgl_coord_t x, nxgl_coord_t y, + nxgl_coord_t width, nxgl_coord_t height, + CWidgetStyle *style = (CWidgetStyle *)NULL); + + /** + * Destructor. + */ + + virtual ~CNumericEdit(); + + /** + * Insert the dimensions that this widget wants to have into the rect + * passed in as a parameter. All coordinates are relative to the + * widget's parent. + * + * @param rect Reference to a rect to populate with data. + */ + + virtual void getPreferredDimensions(CRect &rect) const; + + /** + * Sets the font. + * + * @param font A pointer to the font to use. + */ + + virtual void setFont(CNxFont *font); + + inline int getValue() const { return m_value; } + void setValue(int value); + + inline int getMaximum() const { return m_maximum; } + inline void setMaximum(int value) { m_maximum = value; setValue(m_value); } + + inline int getMinimum() const { return m_minimum; } + inline void setMinimum(int value) { m_minimum = value; setValue(m_value); } + + inline int getIncrement() const { return m_increment; } + inline void setIncrement(int value) { m_increment = value; setValue(m_value); } + + }; +} + +#endif // __cplusplus + +#endif // __INCLUDE_CLABEL_HXX diff --git a/NxWidgets/libnxwidgets/src/cnumericedit.cxx b/NxWidgets/libnxwidgets/src/cnumericedit.cxx new file mode 100644 index 0000000000..e0df014c5e --- /dev/null +++ b/NxWidgets/libnxwidgets/src/cnumericedit.cxx @@ -0,0 +1,262 @@ +/**************************************************************************** + * NxWidgets/libnxwidgets/include/cnumericedit.cxx + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Petteri Aimonen + * + * 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, NxWidgets, nor the names of its contributors + * me 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. + * + **************************************************************************** + * + * Portions of this package derive from Woopsi (http://woopsi.org/) and + * portions are original efforts. It is difficult to determine at this + * point what parts are original efforts and which parts derive from Woopsi. + * However, in any event, the work of Antony Dzeryn will be acknowledged + * in all NxWidget files. Thanks Antony! + * + * Copyright (c) 2007-2011, Antony Dzeryn + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * 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. + * * Neither the names "Woopsi", "Simian Zombie" 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 Antony Dzeryn ``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 Antony Dzeryn 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 "cnumericedit.hxx" +#include "cbutton.hxx" +#include "clabel.hxx" +#include "cnxtimer.hxx" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * CNumericEdit Method Implementations + ****************************************************************************/ + +using namespace NXWidgets; + +// Label that passes drag events + +class CDraggableLabel: public CLabel +{ +public: + CDraggableLabel(CWidgetControl *pWidgetControl, nxgl_coord_t x, nxgl_coord_t y, + nxgl_coord_t width, nxgl_coord_t height, const CNxString &text, + CWidgetStyle *style = (CWidgetStyle *)NULL): + CLabel(pWidgetControl, x, y, width, height, text, style) + { + setDraggable(true); + } + + virtual void onClick(nxgl_coord_t x, nxgl_coord_t y) + { + startDragging(x, y); + } +}; + +/** + * Constructor for a numeric edit control. + * + * @param pWidgetControl The controlling widget for the display + * @param x The x coordinate of the text box, relative to its parent. + * @param y The y coordinate of the text box, relative to its parent. + * @param width The width of the textbox. + * @param height The height of the textbox. + * @param style The style that the button should use. If this is not + * specified, the button will use the global default widget + * style. + */ + +CNumericEdit::CNumericEdit(CWidgetControl *pWidgetControl, nxgl_coord_t x, nxgl_coord_t y, + nxgl_coord_t width, nxgl_coord_t height, + CWidgetStyle *style) +: CNxWidget(pWidgetControl, x, y, width, height, 0, style) +{ + m_label = new CDraggableLabel(pWidgetControl, height, 0, width - 2 * height, height, CNxString("0"), style); + m_label->addWidgetEventHandler(this); + addWidget(m_label); + + m_button_minus = new CButton(pWidgetControl, 0, 0, height, height, CNxString("-")); + m_button_minus->addWidgetEventHandler(this); + addWidget(m_button_minus); + + m_button_plus = new CButton(pWidgetControl, width - height, 0, height, height, CNxString("+")); + m_button_plus->addWidgetEventHandler(this); + addWidget(m_button_plus); + + m_timer = new CNxTimer(pWidgetControl, 100, true); + m_timer->addWidgetEventHandler(this); + addWidget(m_timer); + + m_minimum = INT_MIN; + m_maximum = INT_MAX; + m_increment = 1; + setValue(0); +} + +CNumericEdit::~CNumericEdit() +{ + delete m_label; + delete m_button_minus; + delete m_button_plus; +} + +void CNumericEdit::getPreferredDimensions(CRect &rect) const +{ +} + +void CNumericEdit::setFont(CNxFont *font) +{ + m_label->setFont(font); +} + +void CNumericEdit::onResize(nxgl_coord_t width, nxgl_coord_t height) +{ +} + +void CNumericEdit::handleClickEvent(const CWidgetEventArgs &e) +{ + if (e.getSource() == m_button_plus) + { + setValue(m_value + m_increment); + m_timercount = 0; + m_timer->start(); + } + else if (e.getSource() == m_button_minus) + { + setValue(m_value - m_increment); + m_timercount = 0; + m_timer->start(); + } +} + +void CNumericEdit::handleReleaseEvent(const CWidgetEventArgs &e) +{ + if (e.getSource() == m_button_plus || e.getSource() == m_button_minus) + { + m_timer->stop(); + } +} + +void CNumericEdit::handleReleaseOutsideEvent(const CWidgetEventArgs &e) +{ + if (e.getSource() == m_button_plus || e.getSource() == m_button_minus) + { + m_timer->stop(); + } +} + +void CNumericEdit::handleActionEvent(const CWidgetEventArgs &e) +{ + if (e.getSource() == m_timer) + { + m_timercount++; + + int increment = m_increment; + if (m_timercount > 50) + { + increment = m_increment * 100; + } + else if (m_timercount > 10) + { + increment = m_increment * 10; + } + + if (m_button_minus->isClicked()) + { + setValue(m_value - increment); + } + else if (m_button_plus->isClicked()) + { + setValue(m_value + increment); + } + } +} + +void CNumericEdit::handleDragEvent(const CWidgetEventArgs &e) +{ + int x = e.getX() - m_label->getX(); + int width = m_label->getWidth(); + int value = m_minimum + (m_maximum - m_minimum) * x / width; + setValue(value / m_increment * m_increment); +} + +void CNumericEdit::setValue(int value) +{ + if (value < m_minimum) value = m_minimum; + if (value > m_maximum) value = m_maximum; + + m_value = value; + + char buf[10]; + snprintf(buf, sizeof(buf), "%d", m_value); + CNxString text(buf); + + m_label->setText(text); + + m_widgetEventHandlers->raiseValueChangeEvent(); + + redraw(); +} diff --git a/NxWidgets/libnxwidgets/src/glyph_cycle.cxx b/NxWidgets/libnxwidgets/src/glyph_cycle.cxx index 5c98b8b900..d706adddb1 100644 --- a/NxWidgets/libnxwidgets/src/glyph_cycle.cxx +++ b/NxWidgets/libnxwidgets/src/glyph_cycle.cxx @@ -145,9 +145,9 @@ const struct SBitmap NXWidgets::g_cycle = { CONFIG_NXWIDGETS_BPP, // bpp - Bits per pixel COLOR_FMT, // fmt - Color format - 7, // width - Width in pixels + 8, // width - Width in pixels 10, // height - Height in rows - (7*CONFIG_NXWIDGETS_BPP + 7) / 8, // stride - Width in bytes + (8*CONFIG_NXWIDGETS_BPP + 7) / 8, // stride - Width in bytes g_cycleGlyph // data - Pointer to the beginning of pixel data }; From 0ac67b46fba7412d7bfaf999108af5a9c409f1f5 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 16 Nov 2012 16:49:21 +0000 Subject: [PATCH 135/206] Patches 4-6 from Petteri Aimonen git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5364 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/ChangeLog.txt | 9 ++++-- NxWidgets/nxwm/src/cstartwindow.cxx | 7 ++++- nuttx/ChangeLog | 6 ++++ nuttx/graphics/nxmu/nx_block.c | 2 +- nuttx/graphics/nxmu/nxmu_mouse.c | 44 +++++++++++++++++++++-------- nuttx/graphics/nxsu/nx_mousein.c | 30 ++++++++++++++++---- nuttx/graphics/nxtk/nxtk_events.c | 15 ++++++++-- nuttx/graphics/nxtk/nxtk_internal.h | 5 ++++ 8 files changed, 93 insertions(+), 25 deletions(-) diff --git a/NxWidgets/ChangeLog.txt b/NxWidgets/ChangeLog.txt index dca1f856dd..ece08e4fd6 100644 --- a/NxWidgets/ChangeLog.txt +++ b/NxWidgets/ChangeLog.txt @@ -198,9 +198,12 @@ This commit adds a simple forward declaration to the relevant files, based on the configured icon. If the icon does not exist, linker will give an error about it. Contributed by Petteri Aimonen. -* NxWidgets/nxwm/src/ctaskbar.cxx: Highlight the current window in the task bar. +* NxWidgets::CTaskBar: Highlight the current window in the task bar. Contributed by Petteri Aimonen. * NxWidgets/libnxwidgets/src/glyph_cycle.cxx: Width of glyph_cycle was wrong; - Desctructor needs to by public. From Petteri Aimonen. -* CNumericEdit. This is basically a label with plus and minus buttons. + Destructor needs to by public. From Petteri Aimonen. +* NxWidgets::CNumericEdit. This is basically a label with plus and minus buttons. Contributed by Petteri, Aimonen. +* NxWM::CStartWindow: Fix mq_receive error handling with signal is recieved. + From Petteri Aimonen. + diff --git a/NxWidgets/nxwm/src/cstartwindow.cxx b/NxWidgets/nxwm/src/cstartwindow.cxx index a99e81d88b..cc8802b7c6 100644 --- a/NxWidgets/nxwm/src/cstartwindow.cxx +++ b/NxWidgets/nxwm/src/cstartwindow.cxx @@ -654,8 +654,13 @@ int CStartWindow::startWindow(int argc, char *argv[]) { gdbg("ERROR: mq_receive failed: %d\n", errval); } + else + { + gdbg("mq_receive interrupted by signal\n"); + } + + continue; } - while (nbytes < 0); gvdbg("Received msgid=%d nbytes=%d\n", msg.msgId, nbytes); DEBUGASSERT(nbytes = sizeof(struct SStartWindowMessage) && msg.instance); diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 72fab8a711..c53f9c891e 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3635,4 +3635,10 @@ * Config.mk: Defined DELIM to be either / or \, depending upon CONFIG_WINDOWS_NATIVE. This will allow me to eliminate a lot of conditional logic elsewhere. + * nuttx/graphics: One a mouse button is pressed, continue to report all + mouse button events to the first window that received the the initial + button down event, even if the mouse attempts to dray outside the + window. From Petteri Aimonen. + * nuttx/graphics/nxmu/nx_block.c: One more fixe to the NX block message + logic from Petteri Aimonen. diff --git a/nuttx/graphics/nxmu/nx_block.c b/nuttx/graphics/nxmu/nx_block.c index 3a051f9d7d..7b198613c6 100644 --- a/nuttx/graphics/nxmu/nx_block.c +++ b/nuttx/graphics/nxmu/nx_block.c @@ -140,7 +140,7 @@ int nx_block(NXWINDOW hwnd, FAR void *arg) * that it will not be blocked. */ - ret = nxmu_sendserver(wnd->conn, &outmsg, sizeof(struct nxbe_window_s)); + ret = nxmu_sendserver(wnd->conn, &outmsg, sizeof(struct nxsvrmsg_blocked_s)); } return ret; diff --git a/nuttx/graphics/nxmu/nxmu_mouse.c b/nuttx/graphics/nxmu/nxmu_mouse.c index 3ebe062d29..93441cc01f 100644 --- a/nuttx/graphics/nxmu/nxmu_mouse.c +++ b/nuttx/graphics/nxmu/nxmu_mouse.c @@ -61,9 +61,10 @@ * Private Data ****************************************************************************/ -static struct nxgl_point_s g_mpos; -static struct nxgl_point_s g_mrange; -static uint8_t g_mbutton; +static struct nxgl_point_s g_mpos; +static struct nxgl_point_s g_mrange; +static uint8_t g_mbutton; +static struct nxbe_window_s *g_mwnd; /**************************************************************************** * Public Data @@ -154,6 +155,7 @@ int nxmu_mousein(FAR struct nxfe_state_s *fe, struct nxbe_window_s *wnd; nxgl_coord_t x = pos->x; nxgl_coord_t y = pos->y; + uint8_t oldbuttons; int ret; /* Clip x and y to within the bounding rectangle */ @@ -182,20 +184,36 @@ int nxmu_mousein(FAR struct nxfe_state_s *fe, { /* Update the mouse value */ - g_mpos.x = x; - g_mpos.y = y; - g_mbutton = buttons; + oldbuttons = g_mbutton; + g_mpos.x = x; + g_mpos.y = y; + g_mbutton = buttons; - /* Pick the window to receive the mouse event. Start with - * the top window and go down. Stop with the first window - * that gets the mouse report + /* If a button is already down, regard this as part of a mouse drag + * event. Pass all the following events to the window where the drag + * started in. + */ + + if (oldbuttons && g_mwnd && g_mwnd->cb->mousein) + { + struct nxclimsg_mousein_s outmsg; + outmsg.msgid = NX_CLIMSG_MOUSEIN; + outmsg.wnd = g_mwnd; + outmsg.buttons = g_mbutton; + nxgl_vectsubtract(&outmsg.pos, &g_mpos, &g_mwnd->bounds.pt1); + + return nxmu_sendclient(g_mwnd->conn, &outmsg, sizeof(struct nxclimsg_mousein_s)); + } + + /* Pick the window to receive the mouse event. Start with the top + * window and go down. Stop with the first window that gets the mouse + * report */ for (wnd = fe->be.topwnd; wnd; wnd = wnd->below) { - /* The background window normally has no callback structure - * (unless a client has taken control of the background via - * nx_requestbkgd()). + /* The background window normally has no callback structure (unless + * a client has taken control of the background via nx_requestbkgd()). */ if (wnd->cb) @@ -207,6 +225,8 @@ int nxmu_mousein(FAR struct nxfe_state_s *fe, } } } + + g_mwnd = wnd; } return OK; diff --git a/nuttx/graphics/nxsu/nx_mousein.c b/nuttx/graphics/nxsu/nx_mousein.c index bee4a22650..5b268358bf 100644 --- a/nuttx/graphics/nxsu/nx_mousein.c +++ b/nuttx/graphics/nxsu/nx_mousein.c @@ -62,9 +62,10 @@ * Private Data ****************************************************************************/ -static struct nxgl_point_s g_mpos; -static struct nxgl_point_s g_mrange; -static uint8_t g_mbutton; +static struct nxgl_point_s g_mpos; +static struct nxgl_point_s g_mrange; +static uint8_t g_mbutton; +static struct nxbe_window_s *g_mwnd; /**************************************************************************** * Public Data @@ -148,6 +149,7 @@ int nx_mousein(NXHANDLE handle, nxgl_coord_t x, nxgl_coord_t y, uint8_t buttons) { FAR struct nxfe_state_s *fe = (FAR struct nxfe_state_s *)handle; struct nxbe_window_s *wnd; + uint8_t oldbuttons; int ret; /* Clip x and y to within the bounding rectangle */ @@ -176,13 +178,27 @@ int nx_mousein(NXHANDLE handle, nxgl_coord_t x, nxgl_coord_t y, uint8_t buttons) { /* Update the mouse value */ + oldbuttons = g_mbutton; g_mpos.x = x; g_mpos.y = y; g_mbutton = buttons; - /* Pick the window to receive the mouse event. Start with - * the top window and go down. Step with the first window - * that gets the mouse report + /* If a button is already down, regard this as part of a mouse drag + * event. Pass all the following events to the window where the drag + * started in. + */ + + if (oldbuttons && g_mwnd && g_mwnd->cb->mousein) + { + struct nxgl_point_s relpos; + nxgl_vectsubtract(&relpos, &g_mpos, &g_mwnd->bounds.pt1); + g_mwnd->cb->mousein((NXWINDOW)g_mwnd, &relpos, g_mbutton, g_mwnd->arg); + return OK; + } + + /* Pick the window to receive the mouse event. Start with the top + * window and go down. Step with the first window that gets the mouse + * report */ for (wnd = fe->be.topwnd; wnd; wnd = wnd->below) @@ -193,6 +209,8 @@ int nx_mousein(NXHANDLE handle, nxgl_coord_t x, nxgl_coord_t y, uint8_t buttons) break; } } + + g_mwnd = wnd; } return OK; } diff --git a/nuttx/graphics/nxtk/nxtk_events.c b/nuttx/graphics/nxtk/nxtk_events.c index aaec16b5af..facf921762 100644 --- a/nuttx/graphics/nxtk/nxtk_events.c +++ b/nuttx/graphics/nxtk/nxtk_events.c @@ -261,9 +261,20 @@ static void nxtk_mousein(NXWINDOW hwnd, FAR const struct nxgl_point_s *pos, nxgl_vectoradd(&abspos, pos, &fwnd->wnd.bounds.pt1); + /* In order to deliver mouse release events to the same window where the + * mouse down event happened, we store the initial mouse down location. + */ + + if (fwnd->mbutton == 0 && buttons != 0) + { + fwnd->mpos = abspos; + } + + fwnd->mbutton = buttons; + /* Is the mouse position inside of the client window region? */ - if (fwnd->fwcb->mousein && nxgl_rectinside(&fwnd->fwrect, &abspos)) + if (fwnd->fwcb->mousein && nxgl_rectinside(&fwnd->fwrect, &fwnd->mpos)) { nxgl_vectsubtract(&relpos, &abspos, &fwnd->fwrect.pt1); fwnd->fwcb->mousein((NXTKWINDOW)fwnd, &relpos, buttons, fwnd->fwarg); @@ -271,7 +282,7 @@ static void nxtk_mousein(NXWINDOW hwnd, FAR const struct nxgl_point_s *pos, /* If the mouse position inside the toobar region? */ - else if (fwnd->tbcb->mousein && nxgl_rectinside(&fwnd->tbrect, &abspos)) + else if (fwnd->tbcb->mousein && nxgl_rectinside(&fwnd->tbrect, &fwnd->mpos)) { nxgl_vectsubtract(&relpos, &abspos, &fwnd->tbrect.pt1); fwnd->tbcb->mousein((NXTKWINDOW)fwnd, &relpos, buttons, fwnd->tbarg); diff --git a/nuttx/graphics/nxtk/nxtk_internal.h b/nuttx/graphics/nxtk/nxtk_internal.h index 87a098845a..3a31215d83 100644 --- a/nuttx/graphics/nxtk/nxtk_internal.h +++ b/nuttx/graphics/nxtk/nxtk_internal.h @@ -72,6 +72,11 @@ struct nxtk_framedwindow_s struct nxgl_rect_s fwrect; FAR const struct nx_callback_s *fwcb; FAR void *fwarg; + + /* Initial mouse down location */ + + uint8_t mbutton; + struct nxgl_point_s mpos; }; /**************************************************************************** From e74eed618541f7f8f21428ea953c6edc78eaf389 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 17 Nov 2012 13:50:02 +0000 Subject: [PATCH 136/206] Patches 7-9 from Petteri Aimonen git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5365 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/ChangeLog.txt | 6 + NxWidgets/libnxwidgets/include/cimage.hxx | 16 +- NxWidgets/libnxwidgets/include/cnxtimer.hxx | 55 ++--- NxWidgets/libnxwidgets/src/cnxtimer.cxx | 224 +++----------------- NxWidgets/libnxwidgets/src/cnxtkwindow.cxx | 14 +- NxWidgets/nxwm/src/ctaskbar.cxx | 35 +-- 6 files changed, 86 insertions(+), 264 deletions(-) diff --git a/NxWidgets/ChangeLog.txt b/NxWidgets/ChangeLog.txt index ece08e4fd6..65022ea150 100644 --- a/NxWidgets/ChangeLog.txt +++ b/NxWidgets/ChangeLog.txt @@ -206,4 +206,10 @@ Contributed by Petteri, Aimonen. * NxWM::CStartWindow: Fix mq_receive error handling with signal is recieved. From Petteri Aimonen. +* NxWidgets:CNxTimer: Replace the original (apparently non-functional) signal- + based solution with a work queue-based solution. This raises some isses about + using the internal work queues from user space. I have decided to implemented + user-space work queues (someday) in order to accomplish that functionaliy. + Submitted by Petteri Aimonen. + solutions diff --git a/NxWidgets/libnxwidgets/include/cimage.hxx b/NxWidgets/libnxwidgets/include/cimage.hxx index 0fe2756244..6093c5f334 100644 --- a/NxWidgets/libnxwidgets/include/cimage.hxx +++ b/NxWidgets/libnxwidgets/include/cimage.hxx @@ -73,7 +73,7 @@ /**************************************************************************** * Included Files ****************************************************************************/ - + #include #include @@ -86,11 +86,11 @@ /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ - + /**************************************************************************** * Implementation Classes ****************************************************************************/ - + #if defined(__cplusplus) namespace NXWidgets @@ -120,7 +120,7 @@ namespace NXWidgets * @param port The CGraphicsPort to draw to. * @see redraw() */ - + virtual void drawContents(CGraphicsPort *port); /** @@ -150,7 +150,7 @@ namespace NXWidgets */ virtual void onPreRelease(nxgl_coord_t x, nxgl_coord_t y); - + /** * Redraws the image. * @@ -201,6 +201,12 @@ namespace NXWidgets virtual inline ~CImage() { } + /** + * Get pointer to the bitmap that this image contains. + */ + + inline FAR IBitmap *getBitmap() const { return m_bitmap; } + /** * Insert the dimensions that this widget wants to have into the rect * passed in as a parameter. All coordinates are relative to the diff --git a/NxWidgets/libnxwidgets/include/cnxtimer.hxx b/NxWidgets/libnxwidgets/include/cnxtimer.hxx index be6038dacc..d4715b3788 100644 --- a/NxWidgets/libnxwidgets/include/cnxtimer.hxx +++ b/NxWidgets/libnxwidgets/include/cnxtimer.hxx @@ -80,6 +80,8 @@ #include #include +#include + #include "cnxwidget.hxx" /**************************************************************************** @@ -108,42 +110,18 @@ namespace NXWidgets class CNxTimer : public CNxWidget { protected: - FAR timer_t m_timerid; /**< POSIX timer */ + struct work_s m_work; /**< Work queue entry */ uint32_t m_timeout; /**< The timeout value in milliseconds */ bool m_isRunning; /**< Indicates whether or not the timer is running */ bool m_isRepeater; /**< Indicates whether or not the timer repeats */ /** - * The SIGALM signal handler that will be called when the timer goes off + * Static function called from work queue when the timeout expires. * - * @param signo The signal number call caused the handler to run (SIGALM) + * @param arg Pointer to the CNxTimer instance. */ - static void signalHandler(int signo); - - /** - * Handle an expired timer - */ - - void handleTimerExpiration(void); - - /** - * Convert a timespec to milliseconds - * - * @param tp The pointer to the timespec to convert - * @return The corresponding time in milliseconds - */ - - uint32_t timespecToMilliseconds(FAR const struct timespec *tp); - - /** - * Convert milliseconds to a timespec - * - * @param milliseconds The milliseconds to be converted - * @param tp The pointer to the location to store the converted timespec - */ - - void millisecondsToTimespec(uint32_t milliseconds, FAR struct timespec *tp); + static void workQueueCallback(FAR void *arg); /** * Copy constructor is protected to prevent usage. @@ -171,15 +149,6 @@ namespace NXWidgets ~CNxTimer(void); - /** - * Return the time remaining on this timer. - * - * @return The number of milliseconds that this timer runs before - * firing an event. Zero is returned if the timer is not running. - */ - - const uint32_t getTimeout(void); - /** * Resets the (running) timer to its initial timeout value. This * call does nothing if the timer is not running. @@ -212,6 +181,18 @@ namespace NXWidgets { m_timeout = timeout; } + + /** + * Return the timeout of this timer. + * + * @return The number of milliseconds that this timer will run before + * firing an event. + */ + + inline uint32_t getTimeout(void) const + { + return m_timeout; + } }; } diff --git a/NxWidgets/libnxwidgets/src/cnxtimer.cxx b/NxWidgets/libnxwidgets/src/cnxtimer.cxx index e351d2357d..d663df036f 100644 --- a/NxWidgets/libnxwidgets/src/cnxtimer.cxx +++ b/NxWidgets/libnxwidgets/src/cnxtimer.cxx @@ -70,18 +70,20 @@ /**************************************************************************** * Included Files ****************************************************************************/ - + #include #include #include #include #include -#include #include +#include + +#include +#include #include "cnxtimer.hxx" -#include "singletons.hxx" /**************************************************************************** * Pre-Processor Definitions @@ -116,44 +118,9 @@ CNxTimer::CNxTimer(CWidgetControl *pWidgetControl, uint32_t timeout, bool repeat m_isRepeater = repeat; m_isRunning = false; - // Create a POSIX timer (We can't do anything about failures here) + // Reset the work structure - int ret = timer_create(CLOCK_REALTIME, (FAR struct sigevent *)NULL, &m_timerid); - if (ret < 0) - { - gdbg("timer_create() failed\n"); - return; - } - - // If we are the first timer created in the whole system, then create - // the timer list and attach the SIGALRM timer handler. - - if (!g_nxTimers) - { - if (!g_nxTimers) - { - gdbg("Failed to create the timer list\n"); - return; - } - - // Attach the SIGALM signal handler (no harm if this is done multiple times) - - struct sigaction sigact; - sigact.sa_handler = signalHandler; - sigact.sa_flags = 0; - sigemptyset(&sigact.sa_mask); - - ret = sigaction(SIGALRM, &sigact, (FAR struct sigaction *)NULL); - if (ret < 0) - { - gdbg("sigaction() failed\n"); - return; - } - } - - // Add ourself onto the array of timers -#warning "Need to disable SIGALRM here" - g_nxTimers->push_back(this); + memset(&m_work, 0, sizeof(m_work)); } /** @@ -162,54 +129,6 @@ CNxTimer::CNxTimer(CWidgetControl *pWidgetControl, uint32_t timeout, bool repeat CNxTimer::~CNxTimer(void) { - // Locate ourself in the list of timers and remove ourselves - -#warning "Need to disable SIGALRM here" - for (int i = 0; i < g_nxTimers->size(); i++) - { - CNxTimer *timer = g_nxTimers->at(i); - if (timer == this) - { - g_nxTimers->erase(i); - break; - } - } - - // Destroy the timer - - (void)timer_delete(m_timerid); -} - -/** - * Return the timeout of this timer. - * - * @return The number of milliseconds that this timer will run before firing - * an event. - */ - -const uint32_t CNxTimer::getTimeout(void) -{ - // If the timer is not running, then just return the timeout value - - if (!m_isRunning) - { - return m_timeout; - } - else - { - // Get the time remaining on the POSIX timer. Of course, there - // are race conditions here.. the timer could expire at anytime - - struct itimerspec remaining; - int ret = timer_gettime(m_timerid, &remaining); - if (ret < 0) - { - gdbg("timer_gettime() failed\n"); - return 0; - } - - return timespecToMilliseconds(&remaining.it_value); - } } /** @@ -222,11 +141,7 @@ void CNxTimer::reset(void) if (m_isRunning) { - // If the specified timer was already armed when timer_settime() is - // called, this call will reset the time until next expiration to the - // value specified. - - m_isRunning = false; + stop(); start(); } } @@ -241,24 +156,14 @@ void CNxTimer::start(void) if (!m_isRunning) { - // If the specified timer was already armed when timer_settime() is - // called, this call will reset the time until next expiration to the - // value specified. - - struct itimerspec timerspec; - millisecondsToTimespec(m_timeout, &timerspec.it_value); - timerspec.it_interval.tv_sec = 0; - timerspec.it_interval.tv_nsec = 0; + uint32_t ticks = m_timeout / MSEC_PER_TICK; + int ret = work_queue(USRWORK, &m_work, workQueueCallback, this, ticks); - int ret = timer_settime(m_timerid, 0, &timerspec, - (FAR struct itimerspec *)NULL); if (ret < 0) { - gdbg("timer_settime() failed\n"); + gdbg("work_queue failed: %d\n", ret); } - // The timer is now running - m_isRunning = true; } } @@ -271,112 +176,33 @@ void CNxTimer::stop(void) { if (m_isRunning) { - // If the it_value member of value is zero, the timer will be disarmed. - // The effect of disarming or resetting a timer with pending expiration - // notifications is unspecified. + int ret = work_cancel(USRWORK, &m_work); - struct itimerspec nullTime; - memset(&nullTime, 0, sizeof(struct itimerspec)); - - int ret = timer_settime(m_timerid, 0, &nullTime, - (FAR struct itimerspec *)NULL); if (ret < 0) { - gdbg("timer_settime failed\n"); + gdbg("work_cancel failed: %d\n", ret); } - // The time is no longer running - m_isRunning = false; } } -/** - * The SIGALM signal handler that will be called when the timer goes off - * - * @param signo The signal number call caused the handler to run (SIGALM) - */ - -void CNxTimer::signalHandler(int signo) +void CNxTimer::workQueueCallback(FAR void *arg) { - // Call handlerTimerExpiration on every timer instance + CNxTimer* This = (CNxTimer*)arg; - for (int i = 0; i < g_nxTimers->size(); i++) + This->m_isRunning = false; + + // Raise the action event. + + This->m_widgetEventHandlers->raiseActionEvent(); + + // Restart the timer if this is a repeating timer + + if (This->m_isRepeater) { - CNxTimer *timer = g_nxTimers->at(i); - timer->handleTimerExpiration(); + This->start(); } } -/** - * Handle an expired timer - */ - -void CNxTimer::handleTimerExpiration(void) -{ - // Do we think our timer is running? - - if (m_isRunning) - { - // Is it running? It the timer is not running, it will return an - // it_value of zero. - - struct itimerspec status; - int ret = timer_gettime(m_timerid, &status); - if (ret < 0) - { - gdbg("timer_gettime() failed\n"); - return; - } - - // it_value == 0 means that timer is not running - - if (status.it_value.tv_sec == 0 && status.it_value.tv_nsec == 0) - { - // It has expired - - m_isRunning = false; - - // Raise the action event. Hmmm.. are there any issues with - // doing this from a signal handler? We'll find out - - m_widgetEventHandlers->raiseActionEvent(); - - // Restart the timer if this is a repeating timer - - if (m_isRepeater) - { - start(); - } - } - } -} - -/** - * Convert a timespec to milliseconds - * - * @param tp The pointer to the timespec to convert - * @return The corresponding time in milliseconds - */ - -uint32_t CNxTimer::timespecToMilliseconds(FAR const struct timespec *tp) -{ - return (uint32_t)tp->tv_sec * 1000 + (uint32_t)tp->tv_nsec / 10000000; -} - -/** - * Convert milliseconds to a timespec - * - * @param milliseconds The milliseconds to be converted - * @param tp The pointer to the location to store the converted timespec - */ - - void CNxTimer::millisecondsToTimespec(uint32_t milliseconds, - FAR struct timespec *tp) - { - tp->tv_sec = milliseconds / 1000; - uint32_t remainder = milliseconds - (uint32_t)tp->tv_sec * 1000; - tp->tv_nsec = remainder * 1000000; - } - diff --git a/NxWidgets/libnxwidgets/src/cnxtkwindow.cxx b/NxWidgets/libnxwidgets/src/cnxtkwindow.cxx index 05241817cc..57ca5eb2b6 100644 --- a/NxWidgets/libnxwidgets/src/cnxtkwindow.cxx +++ b/NxWidgets/libnxwidgets/src/cnxtkwindow.cxx @@ -65,7 +65,7 @@ using namespace NXWidgets; * @param hNxServer Handle to the NX server. * @param widgetControl Controlling widget for this window. */ - + CNxTkWindow::CNxTkWindow(NXHANDLE hNxServer, CWidgetControl *widgetControl) : CCallback(widgetControl) { @@ -101,6 +101,8 @@ CNxTkWindow::~CNxTkWindow(void) // constructed-us. (void)nxtk_closewindow(m_hNxTkWindow); + + delete m_widgetControl; } /** @@ -137,7 +139,7 @@ CWidgetControl *CNxTkWindow::getWidgetControl(void) const /** * Open a toolbar on the framed window. This method both instantiates - * the toolbar object AND calls the INxWindow::open() method to + * the toolbar object AND calls the INxWindow::open() method to * create the toolbar. The toolbar is ready for use upon return. * * @param height. The height in rows of the tool bar @@ -184,7 +186,7 @@ CNxToolbar *CNxTkWindow::openToolbar(nxgl_coord_t height, CWidgetControl *widget widgetControl->setWidgetStyle(&style); // And create the toolbar - + m_toolbar = new CNxToolbar(this, m_hNxTkWindow, widgetControl, height); if (!m_toolbar) @@ -218,7 +220,7 @@ CNxToolbar *CNxTkWindow::openToolbar(nxgl_coord_t height, CWidgetControl *widget // Provide parent widget control information to new widget control instance. // This information is reported by an NX callback for "normal" windows. But - // the toolbar widget control does not get NX callbacks and has to get the + // the toolbar widget control does not get NX callbacks and has to get the // window size through the setWindowBounds method. // Disable preemption so that we can be assured that all of the following @@ -309,7 +311,7 @@ bool CNxTkWindow::getSize(FAR struct nxgl_size_s *size) * @param pos The new position of the window. * @return True on success, false on any failure. */ - + bool CNxTkWindow::setPosition(FAR const struct nxgl_point_s *pos) { // Set the window size and position @@ -323,7 +325,7 @@ bool CNxTkWindow::setPosition(FAR const struct nxgl_point_s *pos) * @param size The new size of the window. * @return True on success, false on any failure. */ - + bool CNxTkWindow::setSize(FAR const struct nxgl_size_s *size) { // Set the window size diff --git a/NxWidgets/nxwm/src/ctaskbar.cxx b/NxWidgets/nxwm/src/ctaskbar.cxx index 23d2d23b50..031edbf3a8 100644 --- a/NxWidgets/nxwm/src/ctaskbar.cxx +++ b/NxWidgets/nxwm/src/ctaskbar.cxx @@ -90,7 +90,7 @@ CTaskbar::~CTaskbar(void) /** * Connect to the server */ - + bool CTaskbar::connect(void) { // Connect to the server @@ -116,7 +116,7 @@ bool CTaskbar::connect(void) void CTaskbar::disconnect(void) { - // Stop all applications and remove them from the task bar. Clearly, there + // Stop all applications and remove them from the task bar. Clearly, there // are some ordering issues here... On an orderly system shutdown, disconnection // should really occur priority to deleting instances @@ -279,7 +279,7 @@ bool CTaskbar::startWindowManager(void) for (int i = 0; i < m_slots.size(); ) { - IApplication *app = m_slots.at(i).app; + IApplication *app = m_slots.at(i).app; gvdbg("Starting app[%d]\n", i); if (!app->run()) @@ -294,7 +294,7 @@ bool CTaskbar::startWindowManager(void) // Then continue with the next application. Notice that i is // not incremented in this case and we will continue with the // next application which will not be at this same index - + continue; } @@ -631,7 +631,7 @@ bool CTaskbar::stopApplication(IApplication *app) app->setTopApplication(false); m_topApp = (IApplication *)0; } - + // Hide the application window. That will move the application to the // bottom of the hiearachy. @@ -655,6 +655,7 @@ bool CTaskbar::stopApplication(IApplication *app) // Yes.. found it. Delete the icon image and remove the entry // from the list of applications + delete m_slots.at(i).image->getBitmap(); delete m_slots.at(i).image; m_slots.erase(i); break; @@ -743,7 +744,7 @@ void CTaskbar::clickIcon(int index, bool click) #endif /** - * Create a raw window. + * Create a raw window. * * 1) Create a dumb CWigetControl instance (see note below) * 2) Pass the dumb CWidgetControl instance to the window constructor @@ -796,7 +797,7 @@ NXWidgets::CNxWindow *CTaskbar::openRawWindow(void) * * @return A partially initialized application window instance. */ - + NXWidgets::CNxTkWindow *CTaskbar::openFramedWindow(void) { // Create the widget control (with the window messenger) using the default style @@ -892,13 +893,13 @@ void CTaskbar::setApplicationGeometry(NXWidgets::INxWindow *window, bool fullscr * @param pPos The new position of the window. * @return True on success, false on failure. */ - + window->setPosition(&pos); window->setSize(&size); } /** - * Create the task bar window. + * Create the task bar window. * * @return true on success */ @@ -962,7 +963,7 @@ bool CTaskbar::createTaskbarWindow(void) } /** - * Create the background window. + * Create the background window. * * @return true on success */ @@ -984,7 +985,7 @@ bool CTaskbar::createBackgroundWindow(void) } /** - * Create the background image. + * Create the background image. * * @return true on success */ @@ -1056,7 +1057,7 @@ bool CTaskbar::createBackgroundImage(void) m_backImage->setBorderless(true); m_backImage->setRaisesEvents(false); #endif - + return true; } @@ -1132,9 +1133,9 @@ bool CTaskbar::redrawTaskbarWindow(void) image->setRaisesEvents(false); // Highlight the icon for the top-most window - + image->highlight(m_slots.at(i).app == m_topApp); - + // Get the size of the icon image NXWidgets::CRect rect; @@ -1295,7 +1296,7 @@ bool CTaskbar::redrawBackgroundWindow(void) // Raise the background window to the top of the hierarchy m_background->raise(); - + // Fill the entire window with the background color port->drawFilledRect(0, 0, windowSize.w, windowSize.h, @@ -1314,7 +1315,7 @@ bool CTaskbar::redrawBackgroundWindow(void) m_backImage->enableDrawing(); m_backImage->redraw(); } - + return true; } @@ -1344,7 +1345,7 @@ bool CTaskbar::redrawApplicationWindow(IApplication *app) // Redraw taskbar redrawTaskbarWindow(); - + // Every application provides a method to obtain its application window IApplicationWindow *appWindow = app->getWindow(); From cc099195b8a4baa726810a7811e341f383d442eb Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 17 Nov 2012 13:50:59 +0000 Subject: [PATCH 137/206] Patches 7-9 from Petteri Aimonen git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5366 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 7 ++++ nuttx/graphics/nxmu/nx_bitmap.c | 29 ++++++++++++++- nuttx/graphics/nxmu/nx_getrectangle.c | 30 ++++++++++++++-- nuttx/graphics/nxmu/nxfe.h | 21 +++++++++++ nuttx/graphics/nxmu/nxmu_kbdin.c | 2 +- nuttx/graphics/nxmu/nxmu_mouse.c | 4 +-- nuttx/graphics/nxmu/nxmu_redrawreq.c | 2 +- nuttx/graphics/nxmu/nxmu_reportposition.c | 2 +- nuttx/graphics/nxmu/nxmu_sendwindow.c | 44 +++++++++++++++++++++++ nuttx/graphics/nxmu/nxmu_server.c | 10 ++++++ nuttx/include/nuttx/wqueue.h | 24 +++++++++++-- 11 files changed, 164 insertions(+), 11 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index c53f9c891e..551e5c0fcf 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3641,4 +3641,11 @@ window. From Petteri Aimonen. * nuttx/graphics/nxmu/nx_block.c: One more fixe to the NX block message logic from Petteri Aimonen. + * include/nuttx/wqueue.h: Some basic definitions to support a user- + space work queue (someday in the future). + * graphics/nxmu: Add semaphores so buffers messages that send buffers + will block until the buffer data has been acted upon. + * graphics/nxmw: Extended the blocked messages to cover mouse movement + and redraw events. These will also cause problems if sent to a window + while it is closing. diff --git a/nuttx/graphics/nxmu/nx_bitmap.c b/nuttx/graphics/nxmu/nx_bitmap.c index a86eda96ac..a0bd748b09 100644 --- a/nuttx/graphics/nxmu/nx_bitmap.c +++ b/nuttx/graphics/nxmu/nx_bitmap.c @@ -100,6 +100,8 @@ int nx_bitmap(NXWINDOW hwnd, FAR const struct nxgl_rect_s *dest, FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; struct nxsvrmsg_bitmap_s outmsg; int i; + int ret; + sem_t sem_done; #ifdef CONFIG_DEBUG if (!wnd || !dest || !src || !origin) @@ -124,7 +126,32 @@ int nx_bitmap(NXWINDOW hwnd, FAR const struct nxgl_rect_s *dest, outmsg.origin.y = origin->y; nxgl_rectcopy(&outmsg.dest, dest); + + /* Create a semaphore for tracking command completion */ + + outmsg.sem_done = &sem_done; + ret = sem_init(&sem_done, 0, 0); + + if (ret != OK) + { + gdbg("sem_init failed: %d\n", errno); + return ret; + } + /* Forward the fill command to the server */ - return nxmu_sendwindow(wnd, &outmsg, sizeof(struct nxsvrmsg_bitmap_s)); + ret = nxmu_sendwindow(wnd, &outmsg, sizeof(struct nxsvrmsg_bitmap_s)); + + /* Wait that the command is completed, so that caller can release the buffer. */ + + if (ret == OK) + { + ret = sem_wait(&sem_done); + } + + /* Destroy the semaphore and return. */ + + sem_destroy(&sem_done); + + return ret; } diff --git a/nuttx/graphics/nxmu/nx_getrectangle.c b/nuttx/graphics/nxmu/nx_getrectangle.c index f32065129c..9b7d3679c4 100644 --- a/nuttx/graphics/nxmu/nx_getrectangle.c +++ b/nuttx/graphics/nxmu/nx_getrectangle.c @@ -98,7 +98,9 @@ int nx_getrectangle(NXWINDOW hwnd, FAR const struct nxgl_rect_s *rect, { FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; struct nxsvrmsg_getrectangle_s outmsg; - + int ret; + sem_t sem_done; + #ifdef CONFIG_DEBUG if (!hwnd || !rect || !dest) { @@ -118,7 +120,31 @@ int nx_getrectangle(NXWINDOW hwnd, FAR const struct nxgl_rect_s *rect, nxgl_rectcopy(&outmsg.rect, rect); + /* Create a semaphore for tracking command completion */ + + outmsg.sem_done = &sem_done; + ret = sem_init(&sem_done, 0, 0); + + if (ret != OK) + { + gdbg("sem_init failed: %d\n", errno); + return ret; + } + /* Forward the fill command to the server */ - return nxmu_sendwindow(wnd, &outmsg, sizeof(struct nxsvrmsg_getrectangle_s)); + ret = nxmu_sendwindow(wnd, &outmsg, sizeof(struct nxsvrmsg_getrectangle_s)); + + /* Wait that the command is completed, so that caller can release the buffer. */ + + if (ret == OK) + { + ret = sem_wait(&sem_done); + } + + /* Destroy the semaphore and return. */ + + sem_destroy(&sem_done); + + return ret; } diff --git a/nuttx/graphics/nxmu/nxfe.h b/nuttx/graphics/nxmu/nxfe.h index 8b6a21ef48..b9e02616ce 100644 --- a/nuttx/graphics/nxmu/nxfe.h +++ b/nuttx/graphics/nxmu/nxfe.h @@ -392,6 +392,7 @@ struct nxsvrmsg_getrectangle_s unsigned int plane; /* The plane number to read */ FAR uint8_t *dest; /* Memory location in which to store the graphics data */ unsigned int deststride; /* Width of the destination memory in bytes */ + sem_t *sem_done; /* Semaphore to report when command is done. */ }; /* Fill a trapezoidal region in the window with a color */ @@ -425,6 +426,7 @@ struct nxsvrmsg_bitmap_s FAR const void *src[CONFIG_NX_NPLANES]; /* The start of the source image. */ struct nxgl_point_s origin; /* Offset into the source image data */ unsigned int stride; /* The width of the full source image in pixels. */ + sem_t *sem_done; /* Semaphore to report when command is done. */ }; /* Set the color of the background */ @@ -586,6 +588,25 @@ EXTERN int nxmu_sendwindow(FAR struct nxbe_window_s *wnd, FAR const void *msg, EXTERN int nxmu_sendclient(FAR struct nxfe_conn_s *conn, FAR const void *msg, size_t msglen); +/**************************************************************************** + * Name: nxmu_sendclientwindow + * + * Description: + * Send a message to the client at NX_CLIMSG_PRIO priority + * + * Input Parameters: + * wnd - A pointer to the back-end window structure + * msg - A pointer to the message to send + * msglen - The length of the message in bytes. + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nxmu_sendclientwindow(FAR struct nxbe_window_s *wnd, FAR const void *msg, + size_t msglen); + /**************************************************************************** * Name: nxmu_openwindow * diff --git a/nuttx/graphics/nxmu/nxmu_kbdin.c b/nuttx/graphics/nxmu/nxmu_kbdin.c index 2c658009bc..0308c2bfa8 100644 --- a/nuttx/graphics/nxmu/nxmu_kbdin.c +++ b/nuttx/graphics/nxmu/nxmu_kbdin.c @@ -108,7 +108,7 @@ void nxmu_kbdin(FAR struct nxfe_state_s *fe, uint8_t nch, FAR uint8_t *ch) outmsg->ch[i] = ch[i]; } - (void)nxmu_sendclient(fe->be.topwnd->conn, outmsg, size); + (void)nxmu_sendclientwindow(fe->be.topwnd, outmsg, size); free(outmsg); } } diff --git a/nuttx/graphics/nxmu/nxmu_mouse.c b/nuttx/graphics/nxmu/nxmu_mouse.c index 93441cc01f..1b8f4a5921 100644 --- a/nuttx/graphics/nxmu/nxmu_mouse.c +++ b/nuttx/graphics/nxmu/nxmu_mouse.c @@ -130,7 +130,7 @@ int nxmu_mousereport(struct nxbe_window_s *wnd) outmsg.buttons = g_mbutton; nxgl_vectsubtract(&outmsg.pos, &g_mpos, &wnd->bounds.pt1); - return nxmu_sendclient(wnd->conn, &outmsg, sizeof(struct nxclimsg_mousein_s)); + return nxmu_sendclientwindow(wnd, &outmsg, sizeof(struct nxclimsg_mousein_s)); } } @@ -202,7 +202,7 @@ int nxmu_mousein(FAR struct nxfe_state_s *fe, outmsg.buttons = g_mbutton; nxgl_vectsubtract(&outmsg.pos, &g_mpos, &g_mwnd->bounds.pt1); - return nxmu_sendclient(g_mwnd->conn, &outmsg, sizeof(struct nxclimsg_mousein_s)); + return nxmu_sendclientwindow(g_mwnd, &outmsg, sizeof(struct nxclimsg_mousein_s)); } /* Pick the window to receive the mouse event. Start with the top diff --git a/nuttx/graphics/nxmu/nxmu_redrawreq.c b/nuttx/graphics/nxmu/nxmu_redrawreq.c index 32ca477a26..f54aa85a7e 100644 --- a/nuttx/graphics/nxmu/nxmu_redrawreq.c +++ b/nuttx/graphics/nxmu/nxmu_redrawreq.c @@ -87,7 +87,7 @@ void nxfe_redrawreq(FAR struct nxbe_window_s *wnd, FAR const struct nxgl_rect_s outmsg.more = false; nxgl_rectoffset(&outmsg.rect, rect, -wnd->bounds.pt1.x, -wnd->bounds.pt1.y); - (void)nxmu_sendclient(wnd->conn, &outmsg, sizeof(struct nxclimsg_redraw_s)); + (void)nxmu_sendclientwindow(wnd, &outmsg, sizeof(struct nxclimsg_redraw_s)); } diff --git a/nuttx/graphics/nxmu/nxmu_reportposition.c b/nuttx/graphics/nxmu/nxmu_reportposition.c index f9b5f9dafa..6ffb3f4ee7 100644 --- a/nuttx/graphics/nxmu/nxmu_reportposition.c +++ b/nuttx/graphics/nxmu/nxmu_reportposition.c @@ -100,7 +100,7 @@ void nxfe_reportposition(FAR struct nxbe_window_s *wnd) /* And provide this to the client */ - ret = nxmu_sendclient(wnd->conn, &outmsg, sizeof(struct nxclimsg_newposition_s)); + ret = nxmu_sendclientwindow(wnd, &outmsg, sizeof(struct nxclimsg_newposition_s)); if (ret < 0) { gdbg("nxmu_sendclient failed: %d\n", errno); diff --git a/nuttx/graphics/nxmu/nxmu_sendwindow.c b/nuttx/graphics/nxmu/nxmu_sendwindow.c index 6f64ffff2c..0826a45bc9 100644 --- a/nuttx/graphics/nxmu/nxmu_sendwindow.c +++ b/nuttx/graphics/nxmu/nxmu_sendwindow.c @@ -112,3 +112,47 @@ int nxmu_sendwindow(FAR struct nxbe_window_s *wnd, FAR const void *msg, return ret; } + +/**************************************************************************** + * Name: nxmu_sendclientwindow + * + * Description: + * Send a message to the client at NX_CLIMSG_PRIO priority + * + * Input Parameters: + * wnd - A pointer to the back-end window structure + * msg - A pointer to the message to send + * msglen - The length of the message in bytes. + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nxmu_sendclientwindow(FAR struct nxbe_window_s *wnd, FAR const void *msg, + size_t msglen) +{ + int ret = OK; + + /* Sanity checking */ + +#ifdef CONFIG_DEBUG + if (!wnd || !wnd->conn) + { + errno = EINVAL; + return ERROR; + } +#endif + + /* Ignore messages destined to a blocked window (no errors reported) */ + + if (!NXBE_ISBLOCKED(wnd)) + { + /* Send the message to the server */ + + ret = nxmu_sendclient(wnd->conn, msg, msglen); + } + + return ret; +} + diff --git a/nuttx/graphics/nxmu/nxmu_server.c b/nuttx/graphics/nxmu/nxmu_server.c index 2730e0ea28..cfaa5bbf5d 100644 --- a/nuttx/graphics/nxmu/nxmu_server.c +++ b/nuttx/graphics/nxmu/nxmu_server.c @@ -451,6 +451,11 @@ int nx_runinstance(FAR const char *mqname, FAR NX_DRIVERTYPE *dev) { FAR struct nxsvrmsg_getrectangle_s *getmsg = (FAR struct nxsvrmsg_getrectangle_s *)buffer; nxbe_getrectangle(getmsg->wnd, &getmsg->rect, getmsg->plane, getmsg->dest, getmsg->deststride); + + if (getmsg->sem_done) + { + sem_post(getmsg->sem_done); + } } break; @@ -471,6 +476,11 @@ int nx_runinstance(FAR const char *mqname, FAR NX_DRIVERTYPE *dev) { FAR struct nxsvrmsg_bitmap_s *bmpmsg = (FAR struct nxsvrmsg_bitmap_s *)buffer; nxbe_bitmap(bmpmsg->wnd, &bmpmsg->dest, bmpmsg->src, &bmpmsg->origin, bmpmsg->stride); + + if (bmpmsg->sem_done) + { + sem_post(bmpmsg->sem_done); + } } break; diff --git a/nuttx/include/nuttx/wqueue.h b/nuttx/include/nuttx/wqueue.h index 644585c56f..c509bf197b 100644 --- a/nuttx/include/nuttx/wqueue.h +++ b/nuttx/include/nuttx/wqueue.h @@ -109,17 +109,35 @@ # endif #endif -/* Work queue IDs (indices). These are both zero if there is only one work - * queue. +/* Work queue IDs (indices): + * + * Kernel Work Queues: + * HPWORK: This ID of the high priority work queue that should only be used for + * hi-priority, time-critical, driver bottom-half functions. + * + * LPWORK: This is the ID of the low priority work queue that can be used for any + * purpose. if CONFIG_SCHED_LPWORK is not defined, then there is only one kernel + * work queue and LPWORK == HPWORK. + * + * User Work Queue: + * USRWORK: CONFIG_NUTTX_KERNEL and CONFIG_SCHED_USRWORK are defined, then NuttX + * will also support a user-accessible work queue. Otherwise, USRWORK == LPWORK. */ #define HPWORK 0 #ifdef CONFIG_SCHED_LPWORK -# define LPWORK 1 +# define LPWORK (HPWORK+1) #else # define LPWORK HPWORK #endif +#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_SCHED_USRWORK) +# warning "Feature not implemented" +# define USRWORK (LPWORK+1) +#else +# define USRWORK LPWORK +#endif + /**************************************************************************** * Public Types ****************************************************************************/ From d4dca58d933cf2c713ee8ccead6fce329e199320 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 17 Nov 2012 18:54:53 +0000 Subject: [PATCH 138/206] Most of the changes needed to support Windows native clean; distclean is has a problem git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5367 42af7a65-404d-4744-a932-0658087f49c3 --- apps/Makefile | 11 ++-- apps/examples/adc/Makefile | 5 +- apps/examples/buttons/Makefile | 5 +- apps/examples/can/Makefile | 5 +- apps/examples/cdcacm/Makefile | 5 +- apps/examples/composite/Makefile | 5 +- apps/examples/cxxtest/Makefile | 5 +- apps/examples/dhcpd/Makefile | 5 +- apps/examples/discover/Makefile | 5 +- apps/examples/elf/Makefile | 5 +- apps/examples/elf/tests/errno/Makefile | 14 ++--- apps/examples/elf/tests/hello/Makefile | 12 ++--- apps/examples/elf/tests/helloxx/Makefile | 29 +++++----- apps/examples/elf/tests/longjmp/Makefile | 12 ++--- apps/examples/elf/tests/mutex/Makefile | 12 ++--- apps/examples/elf/tests/pthread/Makefile | 12 ++--- apps/examples/elf/tests/signal/Makefile | 12 ++--- apps/examples/elf/tests/struct/Makefile | 12 ++--- apps/examples/elf/tests/task/Makefile | 14 ++--- apps/examples/ftpc/Makefile | 6 ++- apps/examples/ftpd/Makefile | 5 +- apps/examples/hello/Makefile | 5 +- apps/examples/helloxx/Makefile | 5 +- apps/examples/hidkbd/Makefile | 5 +- apps/examples/igmp/Makefile | 5 +- apps/examples/json/Makefile | 5 +- apps/examples/lcdrw/Makefile | 5 +- apps/examples/mm/Makefile | 5 +- apps/examples/modbus/Makefile | 5 +- apps/examples/mount/Makefile | 5 +- apps/examples/nettest/Makefile | 6 ++- apps/examples/nsh/Makefile | 5 +- apps/examples/null/Makefile | 5 +- apps/examples/nx/Makefile | 5 +- apps/examples/nxconsole/Makefile | 5 +- apps/examples/nxffs/Makefile | 5 +- apps/examples/nxflat/Makefile | 5 +- apps/examples/nxflat/tests/errno/Makefile | 23 ++++---- apps/examples/nxflat/tests/hello++/Makefile | 53 +++++++++++-------- apps/examples/nxflat/tests/hello/Makefile | 23 ++++---- apps/examples/nxflat/tests/longjmp/Makefile | 23 ++++---- apps/examples/nxflat/tests/mutex/Makefile | 23 ++++---- apps/examples/nxflat/tests/pthread/Makefile | 20 ++++--- apps/examples/nxflat/tests/signal/Makefile | 23 ++++---- apps/examples/nxflat/tests/struct/Makefile | 23 ++++---- apps/examples/nxflat/tests/task/Makefile | 23 ++++---- apps/examples/nxhello/Makefile | 5 +- apps/examples/nximage/Makefile | 5 +- apps/examples/nxlines/Makefile | 5 +- apps/examples/nxtext/Makefile | 5 +- apps/examples/ostest/Makefile | 5 +- apps/examples/pashello/Makefile | 5 +- apps/examples/pipe/Makefile | 5 +- apps/examples/poll/Makefile | 6 ++- apps/examples/pwm/Makefile | 5 +- apps/examples/qencoder/Makefile | 5 +- apps/examples/relays/Makefile | 5 +- apps/examples/rgmp/Makefile | 5 +- apps/examples/romfs/Makefile | 6 ++- apps/examples/sendmail/Makefile | 5 +- apps/examples/sendmail/Makefile.host | 4 +- apps/examples/serloop/Makefile | 5 +- apps/examples/telnetd/Makefile | 5 +- apps/examples/thttpd/Makefile | 5 +- apps/examples/thttpd/content/Makefile | 6 ++- apps/examples/thttpd/content/hello/Makefile | 23 ++++---- apps/examples/thttpd/content/netstat/Makefile | 23 ++++---- apps/examples/thttpd/content/tasks/Makefile | 23 ++++---- apps/examples/tiff/Makefile | 9 ++-- apps/examples/touchscreen/Makefile | 5 +- apps/examples/udp/Makefile | 7 ++- apps/examples/uip/Makefile | 7 +-- apps/examples/usbserial/Makefile | 6 +-- apps/examples/usbserial/Makefile.host | 5 +- apps/examples/usbstorage/Makefile | 5 +- apps/examples/usbterm/Makefile | 5 +- apps/examples/watchdog/Makefile | 5 +- apps/examples/wget/Makefile | 5 +- apps/examples/wget/Makefile.host | 4 +- apps/examples/wgetjson/Makefile | 5 +- apps/examples/wlan/Makefile | 5 +- apps/examples/xmlrpc/Makefile | 5 +- apps/graphics/tiff/Makefile | 12 +++-- apps/interpreters/ficl/Makefile | 12 +++-- apps/modbus/Makefile | 13 +++-- apps/namedapp/Makefile | 10 ++-- apps/netutils/codecs/Makefile | 11 ++-- apps/netutils/dhcpc/Makefile | 11 ++-- apps/netutils/dhcpd/Makefile | 11 ++-- apps/netutils/discover/Makefile | 11 ++-- apps/netutils/ftpc/Makefile | 11 ++-- apps/netutils/ftpd/Makefile | 11 ++-- apps/netutils/json/Makefile | 11 ++-- apps/netutils/resolv/Makefile | 11 ++-- apps/netutils/smtp/Makefile | 11 ++-- apps/netutils/telnetd/Makefile | 11 ++-- apps/netutils/tftpc/Makefile | 11 ++-- apps/netutils/thttpd/Makefile | 25 ++++----- apps/netutils/uiplib/Makefile | 11 ++-- apps/netutils/webclient/Makefile | 11 ++-- apps/netutils/webserver/Makefile | 11 ++-- apps/netutils/xmlrpc/Makefile | 11 ++-- apps/nshlib/Makefile | 6 ++- apps/system/free/Makefile | 14 ++--- apps/system/i2c/Makefile | 14 ++--- apps/system/install/Makefile | 14 ++--- apps/system/poweroff/Makefile | 14 ++--- apps/system/ramtron/Makefile | 14 ++--- apps/system/readline/Makefile | 12 +++-- apps/system/sdcard/Makefile | 14 ++--- apps/system/sysinfo/Makefile | 14 ++--- nuttx/Makefile.unix | 23 +++++--- nuttx/Makefile.win | 36 +++++++------ nuttx/arch/8051/src/Makefile | 6 ++- nuttx/arch/arm/src/Makefile | 5 +- nuttx/arch/avr/src/Makefile | 5 +- nuttx/arch/hc/src/Makefile | 5 +- nuttx/arch/mips/src/Makefile | 5 +- nuttx/arch/rgmp/src/Makefile | 10 ++-- nuttx/arch/sh/src/Makefile | 5 +- nuttx/arch/sim/src/Makefile | 6 ++- nuttx/arch/x86/src/Makefile | 5 +- nuttx/arch/z16/src/Makefile | 10 ++-- nuttx/arch/z80/src/Makefile.sdcc | 10 +++- nuttx/arch/z80/src/Makefile.zdsii | 10 ++-- nuttx/binfmt/Makefile | 8 ++- nuttx/configs/stm32f4discovery/src/Makefile | 9 ++-- nuttx/drivers/Makefile | 5 +- nuttx/fs/Makefile | 8 ++- nuttx/graphics/Makefile | 6 +-- nuttx/graphics/nxfonts/Makefile.sources | 14 ++--- nuttx/graphics/nxglib/Makefile.sources | 52 +++++++++--------- nuttx/lib/Makefile | 2 +- nuttx/libc/Makefile | 11 ++-- nuttx/libxx/Makefile | 5 +- nuttx/mm/Makefile | 5 +- nuttx/mm/Makefile.test | 18 ++++--- nuttx/net/Makefile | 6 +-- nuttx/sched/Makefile | 6 ++- nuttx/syscall/Makefile | 23 ++++---- nuttx/tools/Config.mk | 32 +++++++++-- nuttx/tools/Makefile.host | 18 +++++-- 142 files changed, 861 insertions(+), 616 deletions(-) diff --git a/apps/Makefile b/apps/Makefile index 7e7d52a405..522731722d 100644 --- a/apps/Makefile +++ b/apps/Makefile @@ -169,13 +169,12 @@ ifeq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) for %%G in ($(SUBDIRS)) do ( \ $(MAKE) -C %%G clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" \ ) - $(Q) rm -f $(BIN) *~ .*.swp *.o else $(Q) for dir in $(SUBDIRS) ; do \ $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ done - $(Q) rm -f $(BIN) *~ .*.swp *.o endif + $(call DELFILE $(BIN)) $(call CLEAN) distclean: # clean @@ -183,7 +182,9 @@ ifeq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) for %%G in ($(SUBDIRS)) do ( \ $(MAKE) -C %%G distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" \ ) - $(Q) rm -f .config .context .depend + $(call DELFILE .config) + $(call DELFILE .context) + $(call DELFILE .depend) $(Q) ( if exist external ( \ echo ********************************************************" \ echo * The external directory/link must be removed manually *" \ @@ -193,7 +194,9 @@ else $(Q) for dir in $(SUBDIRS) ; do \ $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ done - $(Q) rm -f .config .context .depend + $(call DELFILE .config) + $(call DELFILE .context) + $(call DELFILE .depend) $(Q) ( if [ -e external ]; then \ echo "********************************************************"; \ echo "* The external directory/link must be removed manually *"; \ diff --git a/apps/examples/adc/Makefile b/apps/examples/adc/Makefile index 8f37169c5f..e9f3980b13 100644 --- a/apps/examples/adc/Makefile +++ b/apps/examples/adc/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/buttons/Makefile b/apps/examples/buttons/Makefile index 1f209b7608..01d0719a91 100644 --- a/apps/examples/buttons/Makefile +++ b/apps/examples/buttons/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/can/Makefile b/apps/examples/can/Makefile index 20fb173f0f..824cea3603 100644 --- a/apps/examples/can/Makefile +++ b/apps/examples/can/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/cdcacm/Makefile b/apps/examples/cdcacm/Makefile index 1ebbc6e1e9..336f572442 100644 --- a/apps/examples/cdcacm/Makefile +++ b/apps/examples/cdcacm/Makefile @@ -101,11 +101,12 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/composite/Makefile b/apps/examples/composite/Makefile index 6fe34a1e99..da528b54bf 100644 --- a/apps/examples/composite/Makefile +++ b/apps/examples/composite/Makefile @@ -103,11 +103,12 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/cxxtest/Makefile b/apps/examples/cxxtest/Makefile index b0f0befbf0..f1ab33744c 100644 --- a/apps/examples/cxxtest/Makefile +++ b/apps/examples/cxxtest/Makefile @@ -115,10 +115,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/dhcpd/Makefile b/apps/examples/dhcpd/Makefile index 6a96281cfb..34575f802d 100644 --- a/apps/examples/dhcpd/Makefile +++ b/apps/examples/dhcpd/Makefile @@ -98,11 +98,12 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/discover/Makefile b/apps/examples/discover/Makefile index 722ad3d9bc..6fa70d0929 100644 --- a/apps/examples/discover/Makefile +++ b/apps/examples/discover/Makefile @@ -99,10 +99,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/elf/Makefile b/apps/examples/elf/Makefile index 8831a9336e..ee34130316 100644 --- a/apps/examples/elf/Makefile +++ b/apps/examples/elf/Makefile @@ -100,10 +100,11 @@ clean_tests: @$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) clean clean: clean_tests - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/elf/tests/errno/Makefile b/apps/examples/elf/tests/errno/Makefile index 09d469f9b4..08bffc7dd5 100644 --- a/apps/examples/elf/tests/errno/Makefile +++ b/apps/examples/elf/tests/errno/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs BIN = errno @@ -45,16 +44,17 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CELFFLAGS) $< -o $@ + $(Q) $(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ -clean: - @rm -f $(BIN) *.o *~ .*.swp core +clean: + $(call DELFILE $(BIN)) + $(call CLEAN) install: - @mkdir -p $(ROMFS_DIR) - @install $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) mkdir -p $(ROMFS_DIR) + $(Q) install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/hello/Makefile b/apps/examples/elf/tests/hello/Makefile index 88770276b3..d4af19e02c 100644 --- a/apps/examples/elf/tests/hello/Makefile +++ b/apps/examples/elf/tests/hello/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs BIN = hello @@ -45,15 +44,16 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CELFFLAGS) $< -o $@ + $(Q) $(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - @rm -f $(BIN) *.o *~ .*.swp core + $(call DELFILE $(BIN)) + $(call CLEAN) install: - @mkdir -p $(ROMFS_DIR) - @install $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) mkdir -p $(ROMFS_DIR) + $(Q) install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/helloxx/Makefile b/apps/examples/elf/tests/helloxx/Makefile index 45b4b8868e..e1c9cfc5be 100644 --- a/apps/examples/elf/tests/helloxx/Makefile +++ b/apps/examples/elf/tests/helloxx/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs BIN1 = hello++1 @@ -68,13 +67,13 @@ all: $(BIN1) $(BIN2) $(BIN3) $(BIN4) $(OBJS): %.o: %.cpp @echo "CC: $<" - @$(CXX) -c $(CXXELFFLAGS) $< -o $@ + $(Q) $(CXX) -c $(CXXELFFLAGS) $< -o $@ # This contains libstdc++ stubs to that you can build C++ code # without actually having libstdc++ $(LIBSTDC_STUBS_LIB): - @$(MAKE) -C $(LIBSTDC_STUBS_DIR) TOPDIR=$(TOPDIR) + $(Q) $(MAKE) -C $(LIBSTDC_STUBS_DIR) TOPDIR=$(TOPDIR) # BIN1 and BIN2 link just like C code because they contain no # static constructors. BIN1 is equivalent to a C hello world; @@ -83,18 +82,18 @@ $(LIBSTDC_STUBS_LIB): $(BIN1): $(OBJS1) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ $(BIN2): $(OBJS2) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ # BIN3 is equivalent to BIN2 except that is uses static initializers ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) $(BIN3): $(OBJS3) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ endif # BIN4 is similar to BIN3 except that it uses the streams code from libstdc++ @@ -103,19 +102,23 @@ endif # #$(BIN4): $(OBJS4) # @echo "LD: $<" -# @$(LD) $(LDELFFLAGS) -o $@ $^ +# $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - @rm -f $(ALL_BIN) *.o *~ .*.swp core + $(call DELFILE $(BIN1)) + $(call DELFILE $(BIN2)) + $(call DELFILE $(BIN3)) + $(call DELFILE $(BIN4)) + $(call CLEAN) install: $(ALL_BIN) - @mkdir -p $(ROMFS_DIR) - @install $(BIN1) $(ROMFS_DIR)/$(BIN1) - @install $(BIN2) $(ROMFS_DIR)/$(BIN2) + $(Q) mkdir -p $(ROMFS_DIR) + $(Q) install $(BIN1) $(ROMFS_DIR)/$(BIN1) + $(Q) install $(BIN2) $(ROMFS_DIR)/$(BIN2) ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) - @install $(BIN3) $(ROMFS_DIR)/$(BIN3) + $(Q) install $(BIN3) $(ROMFS_DIR)/$(BIN3) endif -# @install $(BIN4) $(ROMFS_DIR)/$(BIN4) +# $(Q) install $(BIN4) $(ROMFS_DIR)/$(BIN4) diff --git a/apps/examples/elf/tests/longjmp/Makefile b/apps/examples/elf/tests/longjmp/Makefile index 04da6ee819..e7a54fc002 100644 --- a/apps/examples/elf/tests/longjmp/Makefile +++ b/apps/examples/elf/tests/longjmp/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs BIN = longjmp @@ -45,15 +44,16 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CELFFLAGS) $< -o $@ + $(Q) $(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - @rm -f $(BIN) *.o *~ .*.swp core + $(call DELFILE $(BIN)) + $(call CLEAN) install: - @mkdir -p $(ROMFS_DIR) - @install $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) mkdir -p $(ROMFS_DIR) + $(Q) install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/mutex/Makefile b/apps/examples/elf/tests/mutex/Makefile index 756ada2c09..958c0c38e6 100644 --- a/apps/examples/elf/tests/mutex/Makefile +++ b/apps/examples/elf/tests/mutex/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs BIN = mutex @@ -45,15 +44,16 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CELFFLAGS) $< -o $@ + $(Q) $(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - @rm -f $(BIN) *.o *~ .*.swp core + $(call DELFILE $(BIN)) + $(call CLEAN) install: - @mkdir -p $(ROMFS_DIR) - @install $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) mkdir -p $(ROMFS_DIR) + $(Q) install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/pthread/Makefile b/apps/examples/elf/tests/pthread/Makefile index 4bea4515b0..a491b98741 100644 --- a/apps/examples/elf/tests/pthread/Makefile +++ b/apps/examples/elf/tests/pthread/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs BIN = pthread @@ -45,15 +44,16 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CELFFLAGS) $< -o $@ + $(Q) $(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - @rm -f $(BIN) *.o *~ .*.swp core + $(call DELFILE $(BIN)) + $(call CLEAN) install: - @mkdir -p $(ROMFS_DIR) - @install $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) mkdir -p $(ROMFS_DIR) + $(Q) install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/signal/Makefile b/apps/examples/elf/tests/signal/Makefile index 9eaaf86096..227f995211 100644 --- a/apps/examples/elf/tests/signal/Makefile +++ b/apps/examples/elf/tests/signal/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs BIN = signal @@ -45,15 +44,16 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CELFFLAGS) $< -o $@ + $(Q) $(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - @rm -f $(BIN) *.o *~ .*.swp core + $(call DELFILE $(BIN)) + $(call CLEAN) install: - @mkdir -p $(ROMFS_DIR) - @install $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) mkdir -p $(ROMFS_DIR) + $(Q) install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/struct/Makefile b/apps/examples/elf/tests/struct/Makefile index 2ddd80b893..3224c655e7 100644 --- a/apps/examples/elf/tests/struct/Makefile +++ b/apps/examples/elf/tests/struct/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs CELFFLAGS += -I. @@ -46,15 +45,16 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CELFFLAGS) $< -o $@ + $(Q) $(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - @rm -f $(BIN) *.o *~ .*.swp core + $(call DELFILE $(BIN)) + $(call CLEAN) install: - @mkdir -p $(ROMFS_DIR) - @install $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) mkdir -p $(ROMFS_DIR) + $(Q) install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/elf/tests/task/Makefile b/apps/examples/elf/tests/task/Makefile index accac987f2..cf56b1287f 100644 --- a/apps/examples/elf/tests/task/Makefile +++ b/apps/examples/elf/tests/task/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs BIN = task @@ -45,15 +44,16 @@ all: $(BIN) $(OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CELFFLAGS) $< -o $@ + $(Q) $(CC) -c $(CELFFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "LD: $<" - @$(LD) $(LDELFFLAGS) -o $@ $^ + $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ -clean: - @rm -f $(BIN) *.o *~ .*.swp core +clean: + $(call DELFILE $(BIN)) + $(call CLEAN) install: - @mkdir -p $(ROMFS_DIR) - @install $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) mkdir -p $(ROMFS_DIR) + $(Q) install $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/ftpc/Makefile b/apps/examples/ftpc/Makefile index 9f9f689db5..3cdc93060c 100644 --- a/apps/examples/ftpc/Makefile +++ b/apps/examples/ftpc/Makefile @@ -98,10 +98,12 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f .context Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/ftpd/Makefile b/apps/examples/ftpd/Makefile index cae8a282ec..071784b8e2 100644 --- a/apps/examples/ftpd/Makefile +++ b/apps/examples/ftpd/Makefile @@ -94,10 +94,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/hello/Makefile b/apps/examples/hello/Makefile index 53fbead98c..b35b97eb0d 100644 --- a/apps/examples/hello/Makefile +++ b/apps/examples/hello/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/helloxx/Makefile b/apps/examples/helloxx/Makefile index 295d0116e7..739f262526 100644 --- a/apps/examples/helloxx/Makefile +++ b/apps/examples/helloxx/Makefile @@ -115,10 +115,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/hidkbd/Makefile b/apps/examples/hidkbd/Makefile index cb0f32c606..0dbfbdb778 100644 --- a/apps/examples/hidkbd/Makefile +++ b/apps/examples/hidkbd/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/igmp/Makefile b/apps/examples/igmp/Makefile index 5f9d4aa98a..a94a97cf73 100644 --- a/apps/examples/igmp/Makefile +++ b/apps/examples/igmp/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/json/Makefile b/apps/examples/json/Makefile index 0551eccfe3..bdd93fd178 100644 --- a/apps/examples/json/Makefile +++ b/apps/examples/json/Makefile @@ -96,10 +96,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/lcdrw/Makefile b/apps/examples/lcdrw/Makefile index fab2a6939c..bbe46025dd 100644 --- a/apps/examples/lcdrw/Makefile +++ b/apps/examples/lcdrw/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/mm/Makefile b/apps/examples/mm/Makefile index 5d29c6d905..bb14a2e4ef 100644 --- a/apps/examples/mm/Makefile +++ b/apps/examples/mm/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/modbus/Makefile b/apps/examples/modbus/Makefile index 937212f723..f6e964f51f 100644 --- a/apps/examples/modbus/Makefile +++ b/apps/examples/modbus/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/mount/Makefile b/apps/examples/mount/Makefile index d244852d0c..becc6670b8 100644 --- a/apps/examples/mount/Makefile +++ b/apps/examples/mount/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/nettest/Makefile b/apps/examples/nettest/Makefile index c1c50bbb8f..76ad94d6fb 100644 --- a/apps/examples/nettest/Makefile +++ b/apps/examples/nettest/Makefile @@ -131,11 +131,13 @@ context: .context depend: .depend clean: - @rm -f $(HOST_BIN) .built *.o *~ .*.swp + $(call DELFILE $(HOST_BIN)) + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/nsh/Makefile b/apps/examples/nsh/Makefile index fdf5a2a908..0c0ebe8b9f 100644 --- a/apps/examples/nsh/Makefile +++ b/apps/examples/nsh/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/null/Makefile b/apps/examples/null/Makefile index fa3b83d2af..d37d9e6371 100644 --- a/apps/examples/null/Makefile +++ b/apps/examples/null/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/nx/Makefile b/apps/examples/nx/Makefile index 7bc861bbd1..a77ad792a2 100644 --- a/apps/examples/nx/Makefile +++ b/apps/examples/nx/Makefile @@ -101,10 +101,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/nxconsole/Makefile b/apps/examples/nxconsole/Makefile index eb72c87b9a..555511882b 100644 --- a/apps/examples/nxconsole/Makefile +++ b/apps/examples/nxconsole/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/nxffs/Makefile b/apps/examples/nxffs/Makefile index c66a0ec33b..be2a34eae7 100644 --- a/apps/examples/nxffs/Makefile +++ b/apps/examples/nxffs/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/nxflat/Makefile b/apps/examples/nxflat/Makefile index 4fc315592c..5f5a302c34 100644 --- a/apps/examples/nxflat/Makefile +++ b/apps/examples/nxflat/Makefile @@ -91,10 +91,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/nxflat/tests/errno/Makefile b/apps/examples/nxflat/tests/errno/Makefile index df3ea1e3eb..d05154525a 100644 --- a/apps/examples/nxflat/tests/errno/Makefile +++ b/apps/examples/nxflat/tests/errno/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs BIN = errno @@ -48,31 +47,35 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/nxflat/tests/hello++/Makefile b/apps/examples/nxflat/tests/hello++/Makefile index 3433145dc3..445049e94d 100644 --- a/apps/examples/nxflat/tests/hello++/Makefile +++ b/apps/examples/nxflat/tests/hello++/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs BIN1 = hello++1 BIN2 = hello++2 @@ -74,17 +73,17 @@ all: $(BIN1) $(BIN2) $(BIN3) # $(BIN4) $(R1CXXOBJS): %.o: %.cpp @echo "CC: $<" - @$(CXX) -c $(CXXPICFLAGS) $< -o $@ + $(Q) $(CXX) -c $(CXXPICFLAGS) $< -o $@ $(R2AOBJS): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ # This contains libstdc++ stubs to that you can build C++ code # without actually having libstdc++ $(LIBSTDC_STUBS_LIB): - @$(MAKE) -C $(LIBSTDC_STUBS_DIR) TOPDIR=$(TOPDIR) + $(Q) $(MAKE) -C $(LIBSTDC_STUBS_DIR) TOPDIR=$(TOPDIR) # BIN1 and BIN2 link just like C code because they contain no # static constructors. BIN1 is equivalent to a C hello world; @@ -93,34 +92,34 @@ $(LIBSTDC_STUBS_LIB): $(BIN1).r1: $(R1OBJS1) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC1): $(BIN1).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN1).r2: $(R2OBJ1) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS1) $(R2OBJ1) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS1) $(R2OBJ1) $(BIN1): $(BIN1).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ $(BIN2).r1: $(R1OBJS2) $(LIBSTDC_STUBS_LIB) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC2): $(BIN2).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN2).r2: $(R2OBJ2) - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS2) $(R2OBJ2) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS2) $(R2OBJ2) $(BIN2): $(BIN2).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ # BIN3 and BIN4 require that we include --cxx in the xflat-ld command. # This will instruct xflat-ld that we want it to put together the correct @@ -130,19 +129,19 @@ $(BIN2): $(BIN2).r2 $(BIN3).r1: $(R1OBJS3) $(LIBSTDC_STUBS_LIB) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC3): $(BIN3).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN3).r2: $(R2OBJ3) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS3) $(R2OBJ3) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS3) $(R2OBJ3) $(BIN3): $(BIN3).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ # BIN4 is similar to BIN3 except that it uses the streams code from libstdc++ # @@ -164,13 +163,23 @@ $(BIN3): $(BIN3).r2 # $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(ALL_BIN) $(DERIVED) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN1)) + $(call DELFILE $(BIN2)) + $(call DELFILE $(BIN3)) + $(call DELFILE $(BIN4)) + $(call DELFILE $(R2SRC1)) + $(call DELFILE $(R2SRC2)) + $(call DELFILE $(R2SRC3)) + $(call DELFILE $(R2SRC4)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: $(ALL_BIN) - @install -D $(BIN1) $(ROMFS_DIR)/$(BIN1) - @install -D $(BIN2) $(ROMFS_DIR)/$(BIN2) - @install -D $(BIN3) $(ROMFS_DIR)/$(BIN3) -# @install -D $(BIN4) $(ROMFS_DIR)/$(BIN4) + $(Q) install -D $(BIN1) $(ROMFS_DIR)/$(BIN1) + $(Q) install -D $(BIN2) $(ROMFS_DIR)/$(BIN2) + $(Q) install -D $(BIN3) $(ROMFS_DIR)/$(BIN3) +# $(Q) install -D $(BIN4) $(ROMFS_DIR)/$(BIN4) diff --git a/apps/examples/nxflat/tests/hello/Makefile b/apps/examples/nxflat/tests/hello/Makefile index e7e66c628c..cf1a4eb80c 100644 --- a/apps/examples/nxflat/tests/hello/Makefile +++ b/apps/examples/nxflat/tests/hello/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs BIN = hello @@ -48,31 +47,35 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/nxflat/tests/longjmp/Makefile b/apps/examples/nxflat/tests/longjmp/Makefile index 47a1c4905c..55deadbb73 100644 --- a/apps/examples/nxflat/tests/longjmp/Makefile +++ b/apps/examples/nxflat/tests/longjmp/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs BIN = longjmp @@ -48,31 +47,35 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/nxflat/tests/mutex/Makefile b/apps/examples/nxflat/tests/mutex/Makefile index fe66848568..97e5c356e6 100644 --- a/apps/examples/nxflat/tests/mutex/Makefile +++ b/apps/examples/nxflat/tests/mutex/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs BIN = mutex @@ -48,31 +47,35 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/nxflat/tests/pthread/Makefile b/apps/examples/nxflat/tests/pthread/Makefile index f645441ade..5dd6a2a10d 100644 --- a/apps/examples/nxflat/tests/pthread/Makefile +++ b/apps/examples/nxflat/tests/pthread/Makefile @@ -48,31 +48,35 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/nxflat/tests/signal/Makefile b/apps/examples/nxflat/tests/signal/Makefile index 222c57dbe4..e39f3a8d49 100644 --- a/apps/examples/nxflat/tests/signal/Makefile +++ b/apps/examples/nxflat/tests/signal/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs BIN = signal @@ -48,31 +47,35 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/nxflat/tests/struct/Makefile b/apps/examples/nxflat/tests/struct/Makefile index 69f9dd2f3e..ac789f3f40 100644 --- a/apps/examples/nxflat/tests/struct/Makefile +++ b/apps/examples/nxflat/tests/struct/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs CFLAGS += -I. @@ -50,31 +49,35 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/nxflat/tests/task/Makefile b/apps/examples/nxflat/tests/task/Makefile index 8b17ec822e..d27213817b 100644 --- a/apps/examples/nxflat/tests/task/Makefile +++ b/apps/examples/nxflat/tests/task/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs BIN = task @@ -48,32 +47,36 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -D $(BIN) $(ROMFS_DIR)/$(BIN) + $(Q) install -D $(BIN) $(ROMFS_DIR)/$(BIN) diff --git a/apps/examples/nxhello/Makefile b/apps/examples/nxhello/Makefile index 6ab65c53d8..be52882c36 100644 --- a/apps/examples/nxhello/Makefile +++ b/apps/examples/nxhello/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/nximage/Makefile b/apps/examples/nximage/Makefile index b552c0bf69..b20e463509 100644 --- a/apps/examples/nximage/Makefile +++ b/apps/examples/nximage/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/nxlines/Makefile b/apps/examples/nxlines/Makefile index b52da37d2b..cd5753ef9b 100644 --- a/apps/examples/nxlines/Makefile +++ b/apps/examples/nxlines/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/nxtext/Makefile b/apps/examples/nxtext/Makefile index 5067d2af78..68c4a026f8 100644 --- a/apps/examples/nxtext/Makefile +++ b/apps/examples/nxtext/Makefile @@ -102,10 +102,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/ostest/Makefile b/apps/examples/ostest/Makefile index e490139187..2d93126ad8 100644 --- a/apps/examples/ostest/Makefile +++ b/apps/examples/ostest/Makefile @@ -142,10 +142,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/pashello/Makefile b/apps/examples/pashello/Makefile index af33975d0e..df86e7d626 100644 --- a/apps/examples/pashello/Makefile +++ b/apps/examples/pashello/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/pipe/Makefile b/apps/examples/pipe/Makefile index e0168ed0af..e6cefbcdbd 100644 --- a/apps/examples/pipe/Makefile +++ b/apps/examples/pipe/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/poll/Makefile b/apps/examples/poll/Makefile index 89b3145117..dc33d6b491 100644 --- a/apps/examples/poll/Makefile +++ b/apps/examples/poll/Makefile @@ -87,10 +87,12 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend host + $(call DELFILE Make.dep) + $(call DELFILE .depend) + $(call DELFILE host$(HOSTEXEEXT)) -include Make.dep diff --git a/apps/examples/pwm/Makefile b/apps/examples/pwm/Makefile index 6aeb385948..c7cc700bdc 100644 --- a/apps/examples/pwm/Makefile +++ b/apps/examples/pwm/Makefile @@ -96,10 +96,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/qencoder/Makefile b/apps/examples/qencoder/Makefile index 483043c46c..817ba17cc0 100644 --- a/apps/examples/qencoder/Makefile +++ b/apps/examples/qencoder/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/relays/Makefile b/apps/examples/relays/Makefile index bb988f7756..385bc85203 100644 --- a/apps/examples/relays/Makefile +++ b/apps/examples/relays/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/rgmp/Makefile b/apps/examples/rgmp/Makefile index c7e2c59797..72d5e660a0 100644 --- a/apps/examples/rgmp/Makefile +++ b/apps/examples/rgmp/Makefile @@ -86,10 +86,11 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/romfs/Makefile b/apps/examples/romfs/Makefile index 3701412762..5190a7a6e8 100644 --- a/apps/examples/romfs/Makefile +++ b/apps/examples/romfs/Makefile @@ -103,11 +103,13 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend testdir.img + $(call DELFILE Make.dep) + $(call DELFILE .depend) + $(call DELFILE testdir.img) -include Make.dep diff --git a/apps/examples/sendmail/Makefile b/apps/examples/sendmail/Makefile index e8d05ceabd..049321b524 100644 --- a/apps/examples/sendmail/Makefile +++ b/apps/examples/sendmail/Makefile @@ -87,12 +87,13 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) @$(MAKE) -f Makefile.host clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/sendmail/Makefile.host b/apps/examples/sendmail/Makefile.host index bef7eebbfc..e6ff39540d 100644 --- a/apps/examples/sendmail/Makefile.host +++ b/apps/examples/sendmail/Makefile.host @@ -71,7 +71,9 @@ $(BIN): headers $(OBJS) $(HOSTCC) $(HOSTLDFLAGS) $(OBJS) -o $@ clean: - @rm -f $(BIN).* *.o1 *~ + $(call DELFILE $(BIN).*) + $(call DELFILE *.o1) + $(call CLEAN) @rm -rf include diff --git a/apps/examples/serloop/Makefile b/apps/examples/serloop/Makefile index ecf7984e53..01d2c60fef 100644 --- a/apps/examples/serloop/Makefile +++ b/apps/examples/serloop/Makefile @@ -87,11 +87,12 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/telnetd/Makefile b/apps/examples/telnetd/Makefile index 7c541cba98..a1f0f7c63e 100644 --- a/apps/examples/telnetd/Makefile +++ b/apps/examples/telnetd/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/thttpd/Makefile b/apps/examples/thttpd/Makefile index 10bcb9af07..5320a0a131 100644 --- a/apps/examples/thttpd/Makefile +++ b/apps/examples/thttpd/Makefile @@ -89,12 +89,13 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) @$(MAKE) -C content clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/thttpd/content/Makefile b/apps/examples/thttpd/content/Makefile index 1f5ce42469..8a74201b5a 100644 --- a/apps/examples/thttpd/content/Makefile +++ b/apps/examples/thttpd/content/Makefile @@ -97,8 +97,10 @@ $(SYMTAB): build # Clean each subdirectory clean: $(foreach DIR, $(SUBDIRS), $(DIR)_clean) - @rm -f $(ROMFS_HDR) $(ROMFS_IMG) $(SYMTAB) + $(call DELFILE$(ROMFS_HDR)) + $(call DELFILE $(ROMFS_IMG)) + $(call DELFILE $(SYMTAB)) @rm -rf $(ROMFS_DIR) - @rm -f *~ .*.swp + $(call CLEAN) diff --git a/apps/examples/thttpd/content/hello/Makefile b/apps/examples/thttpd/content/hello/Makefile index 76d4e67c89..74ff2116af 100644 --- a/apps/examples/thttpd/content/hello/Makefile +++ b/apps/examples/thttpd/content/hello/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs BIN = hello @@ -48,31 +47,35 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -m 0755 -D $(BIN) $(CGI_DIR)/$(BIN) + $(Q) install -m 0755 -D $(BIN) $(CGI_DIR)/$(BIN) diff --git a/apps/examples/thttpd/content/netstat/Makefile b/apps/examples/thttpd/content/netstat/Makefile index 9769c92070..d9953547af 100644 --- a/apps/examples/thttpd/content/netstat/Makefile +++ b/apps/examples/thttpd/content/netstat/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs BIN = netstat @@ -48,31 +47,35 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -m 0755 -D $(BIN) $(CGI_DIR)/$(BIN) + $(Q) install -m 0755 -D $(BIN) $(CGI_DIR)/$(BIN) diff --git a/apps/examples/thttpd/content/tasks/Makefile b/apps/examples/thttpd/content/tasks/Makefile index b76c3f22a0..c668285d8b 100644 --- a/apps/examples/thttpd/content/tasks/Makefile +++ b/apps/examples/thttpd/content/tasks/Makefile @@ -33,8 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration --include $(TOPDIR)/Make.defs # Basic make info +-include $(TOPDIR)/Make.defs BIN = tasks @@ -48,31 +47,35 @@ all: $(BIN) $(R1OBJS): %.o: %.c @echo "CC: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(R2OBJ): %.o: %.S @echo "AS: $<" - @$(CC) -c $(CPICFLAGS) $< -o $@ + $(Q) $(CC) -c $(CPICFLAGS) $< -o $@ $(BIN).r1: $(R1OBJS) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS1) -o $@ $^ + $(Q) $(LD) $(NXFLATLDFLAGS1) -o $@ $^ $(R2SRC): $(BIN).r1 @echo "MK: $<" - @$(MKNXFLAT) -o $@ $^ + $(Q) $(MKNXFLAT) -o $@ $^ $(BIN).r2: $(R2OBJ) @echo "LD: $<" - @$(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) + $(Q) $(LD) $(NXFLATLDFLAGS2) -o $@ $(R1OBJS) $(R2OBJ) $(BIN): $(BIN).r2 @echo "LD: $<" - @$(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ + $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - @rm -f $(BIN) $(R2SRC) *.o *.r1 *.r2 *~ .*.swp core + $(call DELFILE $(BIN)) + $(call DELFILE $(R2SRC)) + $(call DELFILE *.r1) + $(call DELFILE *.r2) + $(call CLEAN) install: - @install -m 0755 -D $(BIN) $(CGI_DIR)/$(BIN) + $(Q) install -m 0755 -D $(BIN) $(CGI_DIR)/$(BIN) diff --git a/apps/examples/tiff/Makefile b/apps/examples/tiff/Makefile index 73a687c253..373c07ca7c 100644 --- a/apps/examples/tiff/Makefile +++ b/apps/examples/tiff/Makefile @@ -98,11 +98,14 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built - @rm -f result.tif tmpfile1.dat tmpfile2.dat + $(call DELFILE .built) + $(call DELFILE result.tif) + $(call DELFILE tmpfile1.dat) + $(call DELFILE tmpfile2.dat) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/touchscreen/Makefile b/apps/examples/touchscreen/Makefile index ad10363161..f252966201 100644 --- a/apps/examples/touchscreen/Makefile +++ b/apps/examples/touchscreen/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/udp/Makefile b/apps/examples/udp/Makefile index d6c89cac44..79606c69b3 100644 --- a/apps/examples/udp/Makefile +++ b/apps/examples/udp/Makefile @@ -116,11 +116,14 @@ context: depend: .depend clean: - @rm -f $(TARG_BIN) $(HOST_BIN) *.o *~ .*.swp .built + $(call DELFILE .built) + $(call DELFILE $(TARG_BIN)) + $(call DELFILE $(HOST_BIN)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/uip/Makefile b/apps/examples/uip/Makefile index 487512072e..99e140f043 100644 --- a/apps/examples/uip/Makefile +++ b/apps/examples/uip/Makefile @@ -89,12 +89,13 @@ context: epend: .depend clean: - @rm -f *.o *~ .*.swp .built - @rm -f httpd_fsdata.c + $(call DELFILE .built) + $(call DELFILE httpd_fsdata.c) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/usbserial/Makefile b/apps/examples/usbserial/Makefile index 0761dd48c7..2c34fa2757 100644 --- a/apps/examples/usbserial/Makefile +++ b/apps/examples/usbserial/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs @@ -86,12 +85,13 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) @$(MAKE) -f Makefile.host clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/usbserial/Makefile.host b/apps/examples/usbserial/Makefile.host index 628304cd4e..9fb43269d5 100644 --- a/apps/examples/usbserial/Makefile.host +++ b/apps/examples/usbserial/Makefile.host @@ -35,7 +35,6 @@ # TOPDIR must be defined on the make command line --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs SRC = host.c @@ -61,7 +60,5 @@ $(BIN): $(SRC) @$(HOSTCC) $(HOSTCFLAGS) $(DEFINES) $^ -o $@ clean: - @rm -f $(BIN) *~ .*.swp *.o + $(call DELFILE $(BIN)) $(call CLEAN) - - diff --git a/apps/examples/usbstorage/Makefile b/apps/examples/usbstorage/Makefile index 8c142e0c63..4c8323e005 100644 --- a/apps/examples/usbstorage/Makefile +++ b/apps/examples/usbstorage/Makefile @@ -103,11 +103,12 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/usbterm/Makefile b/apps/examples/usbterm/Makefile index 6622759f6d..acf9812bd6 100644 --- a/apps/examples/usbterm/Makefile +++ b/apps/examples/usbterm/Makefile @@ -98,11 +98,12 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/watchdog/Makefile b/apps/examples/watchdog/Makefile index f3c9a8bf93..8bbdbfea61 100644 --- a/apps/examples/watchdog/Makefile +++ b/apps/examples/watchdog/Makefile @@ -96,10 +96,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/wget/Makefile b/apps/examples/wget/Makefile index 859ae999d8..d74c248e91 100644 --- a/apps/examples/wget/Makefile +++ b/apps/examples/wget/Makefile @@ -86,12 +86,13 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) @$(MAKE) -f Makefile.host clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/wget/Makefile.host b/apps/examples/wget/Makefile.host index 5d746441a8..14da45c7e9 100644 --- a/apps/examples/wget/Makefile.host +++ b/apps/examples/wget/Makefile.host @@ -71,7 +71,9 @@ $(BIN): headers $(OBJS) $(HOSTCC) $(HOSTLDFLAGS) $(OBJS) -o $@ clean: - @rm -f $(BIN).* *.o1 *~ + $(call DELFILE $(BIN).*) + $(call DELFILE *.o1) + $(call CLEAN) @rm -rf net nuttx diff --git a/apps/examples/wgetjson/Makefile b/apps/examples/wgetjson/Makefile index c03715ad5e..96748defb5 100644 --- a/apps/examples/wgetjson/Makefile +++ b/apps/examples/wgetjson/Makefile @@ -98,10 +98,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/wlan/Makefile b/apps/examples/wlan/Makefile index c50b132278..be2dbea7af 100644 --- a/apps/examples/wlan/Makefile +++ b/apps/examples/wlan/Makefile @@ -87,11 +87,12 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/examples/xmlrpc/Makefile b/apps/examples/xmlrpc/Makefile index 84d3ed4be5..5ab60a0dd5 100644 --- a/apps/examples/xmlrpc/Makefile +++ b/apps/examples/xmlrpc/Makefile @@ -99,10 +99,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/graphics/tiff/Makefile b/apps/graphics/tiff/Makefile index 1ce2813c83..996f518940 100644 --- a/apps/graphics/tiff/Makefile +++ b/apps/graphics/tiff/Makefile @@ -75,21 +75,23 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/interpreters/ficl/Makefile b/apps/interpreters/ficl/Makefile index cbea9163a8..97cc9d6386 100644 --- a/apps/interpreters/ficl/Makefile +++ b/apps/interpreters/ficl/Makefile @@ -97,21 +97,23 @@ debug: .built: debug $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: debug Makefile $(SRCS) - @$(MKDEP) $(ROOT_DEPPATH) $(SRC_DEPPATH) $(FICL_DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOT_DEPPATH) $(SRC_DEPPATH) $(FICL_DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .context) + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/modbus/Makefile b/apps/modbus/Makefile index 59e2e2526c..c0f01bc94d 100644 --- a/apps/modbus/Makefile +++ b/apps/modbus/Makefile @@ -93,25 +93,28 @@ endif .built: $(OBJS) ifeq ($(CONFIG_MODBUS),y) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built endif context: .depend: Makefile $(SRCS) ifeq ($(CONFIG_MODBUS),y) - @$(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ endif depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) + -include Make.dep diff --git a/apps/namedapp/Makefile b/apps/namedapp/Makefile index 8f653a2082..f52e8a9d57 100644 --- a/apps/namedapp/Makefile +++ b/apps/namedapp/Makefile @@ -96,13 +96,15 @@ context: .context depend: .depend clean: - $(Q) rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - $(Q) rm -f .context Make.dep .depend - $(Q) rm -f namedapp_list.h - $(Q) rm -f namedapp_proto.h + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) + $(call DELFILE namedapp_list.h) + $(call DELFILE namedapp_proto.h) -include Make.dep diff --git a/apps/netutils/codecs/Makefile b/apps/netutils/codecs/Makefile index 6dcd94e9bb..644a07dece 100644 --- a/apps/netutils/codecs/Makefile +++ b/apps/netutils/codecs/Makefile @@ -73,21 +73,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/dhcpc/Makefile b/apps/netutils/dhcpc/Makefile index 67cad42146..0fe9681011 100644 --- a/apps/netutils/dhcpc/Makefile +++ b/apps/netutils/dhcpc/Makefile @@ -79,21 +79,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/dhcpd/Makefile b/apps/netutils/dhcpd/Makefile index 13f1215117..3592313987 100644 --- a/apps/netutils/dhcpd/Makefile +++ b/apps/netutils/dhcpd/Makefile @@ -79,21 +79,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/discover/Makefile b/apps/netutils/discover/Makefile index 3f5c1f71f2..22c06b4721 100644 --- a/apps/netutils/discover/Makefile +++ b/apps/netutils/discover/Makefile @@ -82,21 +82,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/ftpc/Makefile b/apps/netutils/ftpc/Makefile index 65c2d59c57..9524895501 100644 --- a/apps/netutils/ftpc/Makefile +++ b/apps/netutils/ftpc/Makefile @@ -95,21 +95,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/ftpd/Makefile b/apps/netutils/ftpd/Makefile index 9956bf97f9..cccdf548af 100644 --- a/apps/netutils/ftpd/Makefile +++ b/apps/netutils/ftpd/Makefile @@ -79,21 +79,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/json/Makefile b/apps/netutils/json/Makefile index 4a54ab5f70..d8f492aed3 100644 --- a/apps/netutils/json/Makefile +++ b/apps/netutils/json/Makefile @@ -73,21 +73,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/resolv/Makefile b/apps/netutils/resolv/Makefile index d9a74989b3..c5ec8fff13 100644 --- a/apps/netutils/resolv/Makefile +++ b/apps/netutils/resolv/Makefile @@ -79,21 +79,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/smtp/Makefile b/apps/netutils/smtp/Makefile index d9e6e5c0e6..ec3e513b86 100644 --- a/apps/netutils/smtp/Makefile +++ b/apps/netutils/smtp/Makefile @@ -79,21 +79,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/telnetd/Makefile b/apps/netutils/telnetd/Makefile index e024134ffb..f614719d5b 100644 --- a/apps/netutils/telnetd/Makefile +++ b/apps/netutils/telnetd/Makefile @@ -79,21 +79,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/tftpc/Makefile b/apps/netutils/tftpc/Makefile index 050da06d0b..56d3ded125 100644 --- a/apps/netutils/tftpc/Makefile +++ b/apps/netutils/tftpc/Makefile @@ -81,21 +81,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/thttpd/Makefile b/apps/netutils/thttpd/Makefile index a0d5b0ea27..aa053b709f 100644 --- a/apps/netutils/thttpd/Makefile +++ b/apps/netutils/thttpd/Makefile @@ -88,44 +88,45 @@ $(COBJS): %$(OBJEXT): %.c ifeq ($(CONFIG_NXFLAT),y) cgi-bin: - @mkdir cgi-bin + $(Q) mkdir cgi-bin cgi-src/$(SUBDIR_BIN1): - @$(MAKE) -C cgi-src $(SUBDIR_BIN1) + $(Q) $(MAKE) -C cgi-src $(SUBDIR_BIN1) cgi-bin/$(SUBDIR_BIN1): cgi-bin cgi-src/$(SUBDIR_BIN1) - @cp -a cgi-src/$(SUBDIR_BIN1) $@ + $(Q) cp -a cgi-src/$(SUBDIR_BIN1) $@ cgi-src/$(SUBDIR_BIN2): - @$(MAKE) -C cgi-src $(SUBDIR_BIN2) + $(Q) $(MAKE) -C cgi-src $(SUBDIR_BIN2) cgi-bin/$(SUBDIR_BIN2): cgi-bin cgi-src/$(SUBDIR_BIN2) - @cp -a cgi-src/$(SUBDIR_BIN2) $@ + $(Q) cp -a cgi-src/$(SUBDIR_BIN2) $@ cgi-src/$(SUBDIR_BIN3): - @$(MAKE) -C cgi-src $(SUBDIR_BIN3) + $(Q) $(MAKE) -C cgi-src $(SUBDIR_BIN3) cgi-bin/$(SUBDIR_BIN3): cgi-bin cgi-src/$(SUBDIR_BIN3) - @cp -a cgi-src/$(SUBDIR_BIN3) $@ + $(Q) cp -a cgi-src/$(SUBDIR_BIN3) $@ endif .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/uiplib/Makefile b/apps/netutils/uiplib/Makefile index fa9296c0a6..d4f73fb835 100644 --- a/apps/netutils/uiplib/Makefile +++ b/apps/netutils/uiplib/Makefile @@ -95,21 +95,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/webclient/Makefile b/apps/netutils/webclient/Makefile index ef9dbd78be..7ade03cb9c 100644 --- a/apps/netutils/webclient/Makefile +++ b/apps/netutils/webclient/Makefile @@ -79,21 +79,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/webserver/Makefile b/apps/netutils/webserver/Makefile index 26362be5d5..6c5e3d286f 100644 --- a/apps/netutils/webserver/Makefile +++ b/apps/netutils/webserver/Makefile @@ -86,21 +86,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/netutils/xmlrpc/Makefile b/apps/netutils/xmlrpc/Makefile index 1eb3919878..bf78153604 100644 --- a/apps/netutils/xmlrpc/Makefile +++ b/apps/netutils/xmlrpc/Makefile @@ -80,21 +80,22 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile index afe0014195..16efe99cc4 100644 --- a/apps/nshlib/Makefile +++ b/apps/nshlib/Makefile @@ -126,11 +126,13 @@ context: depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/system/free/Makefile b/apps/system/free/Makefile index a4cd506870..9637fa772e 100644 --- a/apps/system/free/Makefile +++ b/apps/system/free/Makefile @@ -88,29 +88,31 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built # Register application .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - @touch $@ + $(Q) touch $@ context: .context # Create dependencies .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f .context Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile index 8dd4bc5630..7cdbcdf593 100644 --- a/apps/system/i2c/Makefile +++ b/apps/system/i2c/Makefile @@ -78,26 +78,28 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/system/install/Makefile b/apps/system/install/Makefile index 99de400c97..951917a77c 100644 --- a/apps/system/install/Makefile +++ b/apps/system/install/Makefile @@ -89,29 +89,31 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built # Register application .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - @touch $@ + $(Q) touch $@ context: .context # Create dependencies .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f .context Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/system/poweroff/Makefile b/apps/system/poweroff/Makefile index a96a600336..46b595e843 100644 --- a/apps/system/poweroff/Makefile +++ b/apps/system/poweroff/Makefile @@ -89,29 +89,31 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built # Register application .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - @touch $@ + $(Q) touch $@ context: .context # Create dependencies .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f .context Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/system/ramtron/Makefile b/apps/system/ramtron/Makefile index b300a3711a..60a2be66a7 100644 --- a/apps/system/ramtron/Makefile +++ b/apps/system/ramtron/Makefile @@ -89,29 +89,31 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built # Register application .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - @touch $@ + $(Q) touch $@ context: .context # Create dependencies .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f .context Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/system/readline/Makefile b/apps/system/readline/Makefile index fb60b6fc46..f67dc85f6e 100644 --- a/apps/system/readline/Makefile +++ b/apps/system/readline/Makefile @@ -79,7 +79,7 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built # Context build phase target @@ -88,18 +88,20 @@ context: # Dependency build phase target .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend # Housekeeping targets clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f .context Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/system/sdcard/Makefile b/apps/system/sdcard/Makefile index 50bf0eeb11..ee95505a20 100644 --- a/apps/system/sdcard/Makefile +++ b/apps/system/sdcard/Makefile @@ -89,29 +89,31 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built # Register application .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - @touch $@ + $(Q) touch $@ context: .context # Create dependencies .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f .context Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/apps/system/sysinfo/Makefile b/apps/system/sysinfo/Makefile index a8821c7de1..06c27a8be7 100644 --- a/apps/system/sysinfo/Makefile +++ b/apps/system/sysinfo/Makefile @@ -89,29 +89,31 @@ $(COBJS): %$(OBJEXT): %.c .built: $(OBJS) $(call ARCHIVE, $(BIN), $(OBJS)) - @touch .built + $(Q) touch .built # Register application .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - @touch $@ + $(Q) touch $@ context: .context # Create dependencies .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f .context Make.dep .depend + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/Makefile.unix b/nuttx/Makefile.unix index 439aa2d4bd..3b641e8b26 100644 --- a/nuttx/Makefile.unix +++ b/nuttx/Makefile.unix @@ -419,10 +419,10 @@ context: check_context include/nuttx/config.h include/nuttx/version.h include/ma # and symbolic links created by the context target. clean_context: - $(Q) rm -f include/nuttx/config.h - $(Q) rm -f include/nuttx/version.h - $(Q) rm -f include/math.h - $(Q) rm -f include/stdarg.h + $(call DELFILE include/nuttx/config.h) + $(call DELFILE include/nuttx/version.h) + $(call DELFILE include/math.h) + $(call DELFILE include/stdarg.h) $(Q) $(DIRUNLINK) include/arch/board $(Q) $(DIRUNLINK) include/arch/chip $(Q) $(DIRUNLINK) include/arch @@ -686,8 +686,13 @@ ifeq ($(CONFIG_BUILD_2PASS),y) endif clean: subdir_clean - $(Q) rm -f $(BIN) nuttx.* mm_test *.map _SAVED_APPS_config *~ - $(Q) rm -f nuttx-export* + $(call DELFILE $(BIN)) + $(call DELFILE nuttx.*) + $(call DELFILE mm_test) + $(call DELFILE *.map) + $(call DELFILE _SAVED_APPS_config) + $(call DELFILE nuttx-export*) + $(call CLEAN) subdir_distclean: $(Q) for dir in $(CLEANDIRS) ; do \ @@ -700,7 +705,11 @@ distclean: clean subdir_distclean clean_context ifeq ($(CONFIG_BUILD_2PASS),y) $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean endif - $(Q) rm -f Make.defs setenv.sh setenv.bat .config .config.old + $(call DELFILE Make.defs) + $(call DELFILE setenv.sh) + $(call DELFILE setenv.bat) + $(call DELFILE .config) + $(call DELFILE .config.old) # Application housekeeping targets. The APPDIR variable refers to the user # application directory. A sample apps/ directory is included with NuttX, diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win index f43f14f0da..f98c5e6d83 100644 --- a/nuttx/Makefile.win +++ b/nuttx/Makefile.win @@ -438,10 +438,10 @@ context: check_context include\nuttx\config.h include\nuttx\version.h include\ma # and symbolic links created by the context target. clean_context: - $(Q) rm -f include\nuttx\config.h - $(Q) rm -f include\nuttx\version.h - $(Q) rm -f include\math.h - $(Q) rm -f include\stdarg.h + $(call DELFILE include\nuttx\config.h) + $(call DELFILE include\nuttx\version.h) + $(call DELFILE include\math.h) + $(call DELFILE include\stdarg.h) $(Q) $(DIRUNLINK) include\arch\board $(Q) $(DIRUNLINK) include\arch\chip $(Q) $(DIRUNLINK) include\arch @@ -688,8 +688,13 @@ ifeq ($(CONFIG_BUILD_2PASS),y) endif clean: subdir_clean - $(Q) rm -f $(BIN) nuttx.* mm_test *.map _SAVED_APPS_config *~ - $(Q) rm -f nuttx-export* + $(call DELFILE $(BIN)) + $(call DELFILE nuttx.*) + $(call DELFILE mm_test) + $(call DELFILE *.map) + $(call DELFILE _SAVED_APPS_config) + $(call DELFILE nuttx-export*) + $(call CLEAN) subdir_distclean: $(Q) for %%G in ($(CLEANDIRS)) do ( if exist %%G\Makefile $(MAKE) -C %%G TOPDIR="$(TOPDIR)" distclean ) @@ -698,7 +703,11 @@ distclean: clean subdir_distclean clean_context ifeq ($(CONFIG_BUILD_2PASS),y) $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean endif - $(Q) rm -f Make.defs setenv.sh setenv.bat .config .config.old + $(call DELFILE Make.defs) + $(call DELFILE setenv.sh) + $(call DELFILE setenv.bat) + $(call DELFILE .config) + $(call DELFILE .config.old) # Application housekeeping targets. The APPDIR variable refers to the user # application directory. A sample apps\ directory is included with NuttX, @@ -723,16 +732,9 @@ endif apps_distclean: ifneq ($(APPDIR),) - $(Q) if [ -r "$(TOPDIR)\$(APPDIR)\.config" ]; then \ - cp "$(TOPDIR)\$(APPDIR)\.config" _SAVED_APPS_config || \ - { echo "Copy of $(APPDIR)\.config failed" ; exit 1 ; } \ - else \ - rm -f _SAVED_APPS_config; \ - fi + $(call DELFILE _SAVED_APPS_config + $(Q) if exist "$(TOPDIR)\$(APPDIR)\.config" ( cp "$(TOPDIR)\$(APPDIR)\.config" _SAVED_APPS_config ) $(Q) $(MAKE) -C "$(TOPDIR)\$(APPDIR)" TOPDIR="$(TOPDIR)" distclean - $(Q) if [ -r _SAVED_APPS_config ]; then \ - mv _SAVED_APPS_config "$(TOPDIR)\$(APPDIR)\.config" || \ - { echo "Copy of _SAVED_APPS_config failed" ; exit 1 ; } \ - fi + $(Q) if exist _SAVED_APPS_config ( mv _SAVED_APPS_config "$(TOPDIR)\$(APPDIR)\.config" ) endif diff --git a/nuttx/arch/8051/src/Makefile b/nuttx/arch/8051/src/Makefile index 4772834d9c..6c87b8bc96 100644 --- a/nuttx/arch/8051/src/Makefile +++ b/nuttx/arch/8051/src/Makefile @@ -221,13 +221,15 @@ clean: $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR=$(TOPDIR) clean ; \ fi - $(Q) rm -f libarch$(LIBEXT) up_mem.h *~ .*.swp + $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE up_mem.h) $(call CLEAN) distclean: clean $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR=$(TOPDIR) distclean ; \ fi - rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index a48d18799b..a6d5fa4f46 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -178,13 +178,14 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(Q) rm -f libarch$(LIBEXT) *~ .*.swp + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile index 462968ed53..69d3a0fc04 100644 --- a/nuttx/arch/avr/src/Makefile +++ b/nuttx/arch/avr/src/Makefile @@ -171,14 +171,15 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(Q) rm -f libarch$(LIBEXT) *~ .*.swp + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile index 0ada6c4c2c..7353b44ea5 100644 --- a/nuttx/arch/hc/src/Makefile +++ b/nuttx/arch/hc/src/Makefile @@ -166,13 +166,14 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(Q) rm -f libarch$(LIBEXT) *~ .*.swp + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile index 057b95d220..b27fe8730a 100644 --- a/nuttx/arch/mips/src/Makefile +++ b/nuttx/arch/mips/src/Makefile @@ -164,13 +164,14 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(Q) rm -f libarch$(LIBEXT) *~ .*.swp + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/arch/rgmp/src/Makefile b/nuttx/arch/rgmp/src/Makefile index 7650a0a942..019dca4658 100644 --- a/nuttx/arch/rgmp/src/Makefile +++ b/nuttx/arch/rgmp/src/Makefile @@ -96,12 +96,14 @@ export_head: depend: .depend clean: - @rm -f $(TOPDIR)/arch/rgmp/src/x86/*.o - @rm -f $(TOPDIR)/kernel.img nuttx.img - @rm -f libarch$(LIBEXT) *~ .*.swp + $(call DELFILE "$(TOPDIR)/arch/rgmp/src/x86/*.o") + $(call DELFILE "$(TOPDIR)/kernel.img") + $(call DELFILE nuttx.img) + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile index 132ca4610e..af7c481a90 100644 --- a/nuttx/arch/sh/src/Makefile +++ b/nuttx/arch/sh/src/Makefile @@ -161,13 +161,14 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(Q) rm -f libarch$(LIBEXT) *~ .*.swp + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile index a5d6100a3f..5abd6ce4f0 100644 --- a/nuttx/arch/sim/src/Makefile +++ b/nuttx/arch/sim/src/Makefile @@ -214,14 +214,16 @@ clean: cleanrel $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi - $(Q) rm -f nuttx.rel libarch$(LIBEXT) *~ .*.swp + $(call DELFILE nuttx.rel) + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) distclean: clean $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) $(Q) rm -rf GNU -include Make.dep diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile index 19193709cc..e93dc2657c 100644 --- a/nuttx/arch/x86/src/Makefile +++ b/nuttx/arch/x86/src/Makefile @@ -172,13 +172,14 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(Q) rm -f libarch$(LIBEXT) *~ .*.swp + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/arch/z16/src/Makefile b/nuttx/arch/z16/src/Makefile index 44f96d03d4..d3f5819989 100644 --- a/nuttx/arch/z16/src/Makefile +++ b/nuttx/arch/z16/src/Makefile @@ -137,16 +137,20 @@ clean: $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi - $(Q) rm -f libarch$(LIBEXT) *~ .*.swp ifeq ($(COMPILER),zneocc.exe) - $(Q) rm -f nuttx.linkcmd *.asm *.tmp *.map + $(call DELFILE nuttx.linkcmd) + $(call DELFILE *.asm) + $(call DELFILE *.tmp) + $(call DELFILE *.map) endif + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) distclean: clean $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/arch/z80/src/Makefile.sdcc b/nuttx/arch/z80/src/Makefile.sdcc index 7c9f45a6c7..e29fa9fda8 100644 --- a/nuttx/arch/z80/src/Makefile.sdcc +++ b/nuttx/arch/z80/src/Makefile.sdcc @@ -240,13 +240,19 @@ clean: $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi - $(Q) rm -f libarch$(LIBEXT) up_mem.h asm_mem.h pass1.* nuttx.* *~ .*.swp + $(call DELFILE up_mem.h) + $(call DELFILE asm_mem.h) + $(call DELFILE pass1.*) + $(call DELFILE nuttx.*) + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) + distclean: clean $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii index 666af89452..1d7b1f96d1 100644 --- a/nuttx/arch/z80/src/Makefile.zdsii +++ b/nuttx/arch/z80/src/Makefile.zdsii @@ -150,14 +150,18 @@ clean: $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi - $(Q) rm -f libarch$(LIBEXT) *~ .*.swp - $(Q) rm -f nuttx.linkcmd *.asm *.tmp *.map + $(call DELFILE nuttx.linkcmd) + $(call DELFILE *.asm) + $(call DELFILE *.tmp) + $(call DELFILE *.map) + $(call DELFILE libarch$(LIBEXT)) $(call CLEAN) distclean: clean $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile index 06def551f1..f90ea0417a 100644 --- a/nuttx/binfmt/Makefile +++ b/nuttx/binfmt/Makefile @@ -87,13 +87,11 @@ $(BIN): $(BINFMT_OBJS) depend: .depend clean: - $(Q) rm -f $(BIN) *~ .*.swp + $(call DELFILE $(BIN)) $(call CLEAN) - $(Q) ( for dir in $(SUBDIRS); do \ - rm -f $${dir}/*~ $${dir}/.*.swp; \ - done ; ) distclean: clean - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/stm32f4discovery/src/Makefile b/nuttx/configs/stm32f4discovery/src/Makefile index b6d0f6226d..f4d5a89d9f 100644 --- a/nuttx/configs/stm32f4discovery/src/Makefile +++ b/nuttx/configs/stm32f4discovery/src/Makefile @@ -126,16 +126,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile index 98bb8a7d0f..57b2b489a2 100644 --- a/nuttx/drivers/Makefile +++ b/nuttx/drivers/Makefile @@ -111,10 +111,11 @@ $(BIN): $(OBJS) depend: .depend clean: - $(Q) rm -f $(BIN) *~ .*.swp + $(call DELFILE $(BIN)) $(call CLEAN) distclean: clean - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile index b55ec6218b..eb036fed0d 100644 --- a/nuttx/fs/Makefile +++ b/nuttx/fs/Makefile @@ -130,13 +130,11 @@ $(BIN): $(OBJS) depend: .depend clean: - $(Q) rm -f $(BIN) *~ .*.swp + $(call DELFILE $(BIN)) $(call CLEAN) - $(Q) ( for dir in $(SUBDIRS); do \ - rm -f $${dir}/*~ $${dir}/.*.swp; \ - done ; ) distclean: clean - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/graphics/Makefile b/nuttx/graphics/Makefile index d0fdb647dd..ddcfd21d24 100644 --- a/nuttx/graphics/Makefile +++ b/nuttx/graphics/Makefile @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs DEPPATH = --dep-path . @@ -201,13 +200,14 @@ context: gensources clean: $(Q) $(MAKE) -C nxglib -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) $(Q) $(MAKE) -C nxfonts -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) - $(Q) rm -f $(BIN) *~ .*.swp + $(call DELFILE $(BIN)) $(call CLEAN) distclean: clean $(Q) $(MAKE) -C nxglib -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) $(Q) $(MAKE) -C nxfonts -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/graphics/nxfonts/Makefile.sources b/nuttx/graphics/nxfonts/Makefile.sources index f2aa87cafd..eeb47d1b25 100644 --- a/nuttx/graphics/nxfonts/Makefile.sources +++ b/nuttx/graphics/nxfonts/Makefile.sources @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs ifdef NXFONTS_BITSPERPIXEL @@ -177,13 +176,14 @@ all: $(GEN_CSRC) .PHONY : clean distclean $(GEN_CSRC) : $(DEPENDENCY) - @$(call PREPROCESS, $<, $(GEN_TMP)) - @cat $(GEN_TMP) | sed -e "/^#/d" >$@ - @rm -f $(GEN_TMP) + $(call PREPROCESS, $<, $(GEN_TMP)) + $(Q) cat $(GEN_TMP) | sed -e "/^#/d" >$@ + $(Q) rm -f $(GEN_TMP) clean: - @rm -f *~ .*.swp *.i + $(call DELFILE *.i) + $(call CLEAN) distclean: clean - @rm -f nxfonts_convert_*bpp.c - @rm -f nxfonts_bitmaps_*.c + $(call DELFILE nxfonts_convert_*bpp.c) + $(call DELFILE nxfonts_bitmaps_*.c) diff --git a/nuttx/graphics/nxglib/Makefile.sources b/nuttx/graphics/nxglib/Makefile.sources index 67f8defc31..bb94c1b20f 100644 --- a/nuttx/graphics/nxglib/Makefile.sources +++ b/nuttx/graphics/nxglib/Makefile.sources @@ -33,7 +33,6 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs ifeq ($(NXGLIB_BITSPERPIXEL),1) @@ -123,53 +122,54 @@ all: $(GEN_CSRCS) $(SETP_CSRC) : $(BLITDIR)/nxglib_setpixel.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - @$(call PREPROCESS, $(BLITDIR)/nxglib_setpixel.c, $(SETP_TMP)) - @cat $(SETP_TMP) | sed -e "/^#/d" >$@ - @rm -f $(SETP_TMP) + $(call PREPROCESS, $(BLITDIR)/nxglib_setpixel.c, $(SETP_TMP)) + $(Q) cat $(SETP_TMP) | sed -e "/^#/d" >$@ + $(Q) rm -f $(SETP_TMP) endif $(RFILL_CSRC) : $(BLITDIR)/nxglib_fillrectangle.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - @$(call PREPROCESS, $(BLITDIR)/nxglib_fillrectangle.c, $(RFILL_TMP)) - @cat $(RFILL_TMP) | sed -e "/^#/d" >$@ - @rm -f $(RFILL_TMP) + $(call PREPROCESS, $(BLITDIR)/nxglib_fillrectangle.c, $(RFILL_TMP)) + $(Q) cat $(RFILL_TMP) | sed -e "/^#/d" >$@ + $(Q) rm -f $(RFILL_TMP) endif $(RGET_CSRC) : $(BLITDIR)/nxglib_getrectangle.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - @$(call PREPROCESS, $(BLITDIR)/nxglib_getrectangle.c, $(RGET_TMP)) - @cat $(RGET_TMP) | sed -e "/^#/d" >$@ - @rm -f $(RGET_TMP) + $(call PREPROCESS, $(BLITDIR)/nxglib_getrectangle.c, $(RGET_TMP)) + $(Q) cat $(RGET_TMP) | sed -e "/^#/d" >$@ + $(Q) rm -f $(RGET_TMP) endif $(TFILL_CSRC) : $(BLITDIR)/nxglib_filltrapezoid.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - @$(call PREPROCESS, $(BLITDIR)/nxglib_filltrapezoid.c, $(TFILL_TMP)) - @cat $(TFILL_TMP) | sed -e "/^#/d" >$@ - @rm -f $(TFILL_TMP) + $(call PREPROCESS, $(BLITDIR)/nxglib_filltrapezoid.c, $(TFILL_TMP)) + $(Q) cat $(TFILL_TMP) | sed -e "/^#/d" >$@ + $(Q) rm -f $(TFILL_TMP) endif $(RMOVE_CSRC) : $(BLITDIR)/nxglib_moverectangle.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - @$(call PREPROCESS, $(BLITDIR)/nxglib_moverectangle.c, $(RMOVE_TMP)) - @cat $(RMOVE_TMP) | sed -e "/^#/d" >$@ - @rm -f $(RMOVE_TMP) + $(call PREPROCESS, $(BLITDIR)/nxglib_moverectangle.c, $(RMOVE_TMP)) + $(Q) cat $(RMOVE_TMP) | sed -e "/^#/d" >$@ + $(Q) rm -f $(RMOVE_TMP) endif $(RCOPY_CSRC) : $(BLITDIR)/nxglib_copyrectangle.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - @$(call PREPROCESS, $(BLITDIR)/nxglib_copyrectangle.c, $(RCOPY_TMP)) - @cat $(RCOPY_TMP) | sed -e "/^#/d" >$@ - @rm -f $(RCOPY_TMP) + $(call PREPROCESS, $(BLITDIR)/nxglib_copyrectangle.c, $(RCOPY_TMP)) + $(Q) cat $(RCOPY_TMP) | sed -e "/^#/d" >$@ + $(Q) rm -f $(RCOPY_TMP) endif clean: - @rm -f *~ .*.swp *.i + $(call DELFILE *.i) + $(call CLEAN) distclean: clean - @rm -f nxglib_setpixel_*bpp.c - @rm -f nxglib_fillrectangle_*bpp.c - @rm -f nxglib_getrectangle_*bpp.c - @rm -f nxglib_filltrapezoid_*bpp.c - @rm -f nxglib_moverectangle_*bpp.c - @rm -f nxglib_copyrectangle_*bpp.c + $(call DELFILE nxglib_setpixel_*bpp.c) + $(call DELFILE nxglib_fillrectangle_*bpp.c) + $(call DELFILE nxglib_getrectangle_*bpp.c) + $(call DELFILE nxglib_filltrapezoid_*bpp.c) + $(call DELFILE nxglib_moverectangle_*bpp.c) + $(call DELFILE nxglib_copyrectangle_*bpp.c) diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile index dca8ea035a..58857dbd41 100644 --- a/nuttx/lib/Makefile +++ b/nuttx/lib/Makefile @@ -40,6 +40,6 @@ all: depend: clean: - $(Q) rm -f *$(LIBEXT) + $(call CLEAN) distclean: clean diff --git a/nuttx/libc/Makefile b/nuttx/libc/Makefile index 313629f2b8..e7dec47768 100644 --- a/nuttx/libc/Makefile +++ b/nuttx/libc/Makefile @@ -114,7 +114,7 @@ else $(Q) ( if [ -f .userlib ]; then rm -f *$(OBJEXT); fi ) endif endif - $(Q) rm -f .userlib *~ .*.swp + $(call DELFILE .userlib) # Clean kernel-mode temporary files (retaining the KBIN binary) @@ -126,17 +126,20 @@ else $(Q) ( if [ -f .kernlib ]; then rm -f *$(OBJEXT); fi ) endif endif - $(Q) rm -f .kernlib *~ .*.swp + $(call DELFILE .kernlib) # Really clean everything clean: uclean kclean - $(Q) rm -f $(BIN) $(UBIN) $(KBIN) *~ .*.swp + $(call DELFILE $(BIN)) + $(call DELFILE $(UBIN)) + $(call DELFILE $(KBIN)) $(call CLEAN) # Deep clean -- removes all traces of the configuration distclean: clean - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile index 6093ad4902..cc55784274 100644 --- a/nuttx/libxx/Makefile +++ b/nuttx/libxx/Makefile @@ -105,10 +105,11 @@ $(BIN): $(OBJS) depend: .depend clean: - $(Q) rm -f $(BIN) *~ .*.swp + $(call DELFILE $(BIN)) $(call CLEAN) distclean: clean - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile index 8cdfb4d279..b14560ce36 100644 --- a/nuttx/mm/Makefile +++ b/nuttx/mm/Makefile @@ -70,10 +70,11 @@ $(BIN): $(OBJS) depend: .depend clean: - $(Q) rm -f $(BIN) *~ .*.swp + $(call DELFILE $(BIN)) $(call CLEAN) distclean: clean - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/mm/Makefile.test b/nuttx/mm/Makefile.test index 63cab910e9..e0f1109d86 100644 --- a/nuttx/mm/Makefile.test +++ b/nuttx/mm/Makefile.test @@ -33,12 +33,14 @@ # ############################################################################ -SRCS = mm_test.c mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c mm_shrinkchunk.c \ +-include $(TOPDIR)/Make.defs + +SRCS = mm_test.c mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c mm_shrinkchunk.c \ mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c \ mm_memalign.c mm_free.c mm_mallinfo.c -OBJS = $(SRCS:.c=.o1) +OBJS = $(SRCS:.c=.o1) -LIBS = -lpthread -lc +LIBS = -lpthread -lc CC = gcc LD = gcc @@ -48,17 +50,19 @@ WARNIGNS = -Wall -Wstrict-prototypes -Wshadow CFLAGS = -g $(DEFINES) LDFLAGS = -BIN = ../mm_test +BIN = ..$(DELIM)mm_test all: $(BIN) $(OBJS): %.o1: %.c @echo "Compiling $<" - $(CC) -c $(CFLAGS) $< -o $@ + $(Q) $(CC) -c $(CFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "Linking {$(OBJS)} to produce $@" - $(LD) $(LDFLAGS) $(OBJS) $(LIBS) -o $@ + $(Q) $(LD) $(LDFLAGS) $(OBJS) $(LIBS) -o $@ clean: - @rm -f $(BIN) *.o1 *~ + $(call DELFILE $(BIN)) + $(call DELFILE *.o1) + $(call CLEAN) diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile index aed5734dfc..29148fafac 100644 --- a/nuttx/net/Makefile +++ b/nuttx/net/Makefile @@ -111,11 +111,11 @@ endif depend: .depend clean: - $(Q) rm -f $(BIN) *~ .*.swp - $(Q) rm -f uip/*~ uip/.*.swp + $(call DELFILE $(BIN)) $(call CLEAN) distclean: clean - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 601ba58193..ac6489b184 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -188,6 +188,7 @@ OBJS = $(AOBJS) $(COBJS) BIN = libsched$(LIBEXT) all: $(BIN) +.PHONY: context depend clean distclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -205,10 +206,11 @@ $(BIN): $(OBJS) depend: .depend clean: - $(Q) rm -f $(BIN) + $(call DELFILE $(BIN)) $(call CLEAN) distclean: clean - $(Q) rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/syscall/Makefile b/nuttx/syscall/Makefile index a21eb04ee7..15e06e097b 100644 --- a/nuttx/syscall/Makefile +++ b/nuttx/syscall/Makefile @@ -34,11 +34,11 @@ ########################################################################### -include $(TOPDIR)/Make.defs -include proxies/Make.defs -include stubs/Make.defs +include proxies$(DELIM)Make.defs +include stubs$(DELIM)Make.defs -MKSYSCALL = "$(TOPDIR)/tools/mksyscall$(EXEEXT)" -CSVFILE = "$(TOPDIR)/syscall/syscall.csv" +MKSYSCALL = "$(TOPDIR)$(DELIM)tools$(DELIM)mksyscall$(EXEEXT)" +CSVFILE = "$(TOPDIR)$(DELIM)syscall$(DELIM)syscall.csv" STUB_SRCS += stub_lookup.c @@ -85,7 +85,7 @@ $(BIN2): $(STUB_OBJS) depend: .depend $(MKSYSCALL): - $(Q) $(MAKE) -C $(TOPDIR)/tools -f Makefile.host mksyscall + $(Q) $(MAKE) -C $(TOPDIR)$(DELIM)tools -f Makefile.host mksyscall .context: syscall.csv $(Q) (cd proxies; $(MKSYSCALL) -p $(CSVFILE);) @@ -95,15 +95,20 @@ $(MKSYSCALL): context: $(MKSYSCALL) .context clean: - $(Q) rm -f $(BIN1) $(BIN2) *~ .*.swp + $(call DELFILE $(BIN1)) + $(call DELFILE $(BIN2)) ifneq ($(OBJEXT),) - $(Q) rm -f proxies/*$(OBJEXT) stubs/*$(OBJEXT) + $(call DELFILE proxies$(DELIM)*$(OBJEXT)) + $(call DELFILE stubs$(DELIM)*$(OBJEXT)) endif $(call CLEAN) distclean: clean - $(Q) rm -f Make.dep .depend .context - $(Q) rm -f proxies/*.c stubs/*.c + $(call DELFILE .context) + $(call DELFILE Make.dep) + $(call DELFILE .depend) + $(call DELFILE proxies$(DELIM)*.c) + $(call DELFILE stubs$(DELIM)*.c) -include Make.dep diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk index 4cdda113c7..aafb58f35b 100644 --- a/nuttx/tools/Config.mk +++ b/nuttx/tools/Config.mk @@ -2,7 +2,9 @@ # Config.mk # Global build rules and macros. # +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Richard Cochran +# Gregory Nutt # # This file (along with $(TOPDIR)/.config) must be included by every # configuration-specific Make.defs file. @@ -43,6 +45,12 @@ CONFIG_ARCH := $(patsubst "%",%,$(strip $(CONFIG_ARCH))) CONFIG_ARCH_CHIP := $(patsubst "%",%,$(strip $(CONFIG_ARCH_CHIP))) CONFIG_ARCH_BOARD := $(patsubst "%",%,$(strip $(CONFIG_ARCH_BOARD))) +# Some defaults just to prohibit some bad behavior if for some reason they +# are not defined + +OBJEXT ?= .o +LIBEXT ?= .a + # DELIM - Path segment delimiter character # # Depends on this settings defined in board-specific defconfig file installed @@ -167,12 +175,30 @@ define ARCHIVE endef endif +# DELFILE - Delete one file + ifeq ($(CONFIG_WINDOWS_NATIVE),y) -define CLEAN - $(Q) rm -f *.o *.a +define DELFILE + $(Q) if exist $1 (del /f /q $1) endef else define CLEAN - $(Q) rm -f *.o *.a *~ .*.swp + $(Q) rm -f $1 endef endif + +# CLEAN - Default clean target + +ifeq ($(CONFIG_WINDOWS_NATIVE),y) +define CLEAN + $(Q) if exist *$(OBJEXT) (del /f /q *$(OBJEXT)) + $(Q) if exist *$(LIBEXT) (del /f /q *$(LIBEXT)) + $(Q) if exist *~ (del /f /q *~) + $(Q) if exist (del /f /q .*.swp) +endef +else +define CLEAN + $(Q) rm -f *$(OBJEXT) *$(LIBEXT) *~ .*.swp +endef +endif + \ No newline at end of file diff --git a/nuttx/tools/Makefile.host b/nuttx/tools/Makefile.host index 16975a42a3..559192c5e3 100644 --- a/nuttx/tools/Makefile.host +++ b/nuttx/tools/Makefile.host @@ -122,8 +122,18 @@ mkdeps: mkdeps$(HOSTEXEEXT) endif clean: - $(Q) rm -f *.o *.a *~ .*.swp - $(Q) rm -f mkdeps mkconfig mksyscall mkversion bdf-converter - $(Q) rm -f mkdeps.exe mkconfig.exe mksyscall.exe mkversion.exe bdf-converter.exe + $(call DELFILE mkdeps) + $(call DELFILE mkdeps.exe) + $(call DELFILE mkconfig) + $(call DELFILE mkconfig.exe) + $(call DELFILE Make.dep) + $(call DELFILE mksyscall) + $(call DELFILE mksyscall.exe) + $(call DELFILE mkversion) + $(call DELFILE mkversion.exe) + $(call DELFILE bdf-converter) + $(call DELFILE bdf-converter.exe) +ifneq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) rm -rf *.dSYM - +endif + $(call CLEAN) From e7b122cc626cc454d9af49e6d6928a46d667fd1f Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 17 Nov 2012 20:44:02 +0000 Subject: [PATCH 139/206] Finishes all Makefile file changes for Windows native clean git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5368 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/UnitTests/CButton/Makefile | 33 +++--- NxWidgets/UnitTests/CButtonArray/Makefile | 33 +++--- NxWidgets/UnitTests/CCheckBox/Makefile | 33 +++--- NxWidgets/UnitTests/CGlyphButton/Makefile | 33 +++--- NxWidgets/UnitTests/CImage/Makefile | 33 +++--- NxWidgets/UnitTests/CKeypad/Makefile | 33 +++--- NxWidgets/UnitTests/CLabel/Makefile | 33 +++--- NxWidgets/UnitTests/CLatchButton/Makefile | 33 +++--- .../UnitTests/CLatchButtonArray/Makefile | 33 +++--- NxWidgets/UnitTests/CListBox/Makefile | 33 +++--- NxWidgets/UnitTests/CProgressBar/Makefile | 33 +++--- NxWidgets/UnitTests/CRadioButton/Makefile | 33 +++--- .../UnitTests/CScrollbarHorizontal/Makefile | 29 ++--- .../UnitTests/CScrollbarVertical/Makefile | 33 +++--- NxWidgets/UnitTests/CSliderHorizonal/Makefile | 33 +++--- NxWidgets/UnitTests/CSliderVertical/Makefile | 33 +++--- NxWidgets/UnitTests/CTextBox/Makefile | 33 +++--- NxWidgets/UnitTests/nxwm/Makefile | 45 ++++---- NxWidgets/libnxwidgets/Makefile | 17 +-- NxWidgets/nxwm/Makefile | 23 ++-- misc/pascal/nuttx/Makefile | 43 ++++---- nuttx/configs/amber/src/Makefile | 9 +- nuttx/configs/avr32dev1/src/Makefile | 9 +- nuttx/configs/c5471evm/src/Makefile | 9 +- nuttx/configs/compal_e88/src/Makefile | 9 +- nuttx/configs/compal_e99/src/Makefile | 9 +- nuttx/configs/demo9s12ne64/src/Makefile | 9 +- nuttx/configs/ea3131/locked/Makefile | 38 +++---- nuttx/configs/ea3131/src/Makefile | 9 +- nuttx/configs/ea3152/src/Makefile | 9 +- nuttx/configs/eagle100/src/Makefile | 9 +- nuttx/configs/ekk-lm3s9b96/src/Makefile | 9 +- nuttx/configs/ez80f910200kitg/src/Makefile | 15 +-- nuttx/configs/ez80f910200zco/src/Makefile | 15 +-- nuttx/configs/fire-stm32v2/src/Makefile | 9 +- nuttx/configs/hymini-stm32v/src/Makefile | 9 +- nuttx/configs/kwikstik-k40/src/Makefile | 10 +- nuttx/configs/lincoln60/src/Makefile | 9 +- nuttx/configs/lm3s6432-s2e/src/Makefile | 9 +- nuttx/configs/lm3s6965-ek/src/Makefile | 9 +- nuttx/configs/lm3s8962-ek/src/Makefile | 9 +- nuttx/configs/lpc4330-xplorer/src/Makefile | 9 +- nuttx/configs/lpcxpresso-lpc1768/src/Makefile | 9 +- nuttx/configs/m68332evb/src/Makefile | 9 +- nuttx/configs/mbed/src/Makefile | 9 +- nuttx/configs/mcu123-lpc214x/src/Makefile | 9 +- nuttx/configs/micropendous3/src/Makefile | 9 +- nuttx/configs/mirtoo/src/Makefile | 9 +- nuttx/configs/mx1ads/src/Makefile | 9 +- nuttx/configs/ne64badge/src/Makefile | 9 +- nuttx/configs/ntosd-dm320/src/Makefile | 9 +- nuttx/configs/nucleus2g/src/Makefile | 9 +- nuttx/configs/olimex-lpc1766stk/src/Makefile | 9 +- nuttx/configs/olimex-lpc2378/src/Makefile | 9 +- nuttx/configs/olimex-stm32-p107/src/Makefile | 9 +- nuttx/configs/olimex-strp711/src/Makefile | 9 +- nuttx/configs/pcblogic-pic32mx/src/Makefile | 9 +- nuttx/configs/pic32-starterkit/src/Makefile | 9 +- nuttx/configs/pic32mx7mmb/src/Makefile | 9 +- nuttx/configs/pjrc-8051/src/Makefile | 9 +- nuttx/configs/qemu-i486/src/Makefile | 9 +- nuttx/configs/sam3u-ek/kernel/Makefile | 103 +++++++++--------- nuttx/configs/sam3u-ek/src/Makefile | 9 +- nuttx/configs/shenzhou/src/Makefile | 9 +- nuttx/configs/sim/src/Makefile | 11 +- nuttx/configs/skp16c26/src/Makefile | 9 +- nuttx/configs/stm3210e-eval/src/Makefile | 9 +- nuttx/configs/stm3220g-eval/src/Makefile | 9 +- nuttx/configs/stm3240g-eval/src/Makefile | 9 +- .../configs/stm32f100rc_generic/src/Makefile | 9 +- nuttx/configs/sure-pic32mx/src/Makefile | 9 +- nuttx/configs/teensy/src/Makefile | 9 +- nuttx/configs/twr-k60n512/src/Makefile | 9 +- nuttx/configs/ubw32/src/Makefile | 9 +- nuttx/configs/us7032evb1/shterm/Makefile | 9 +- nuttx/configs/us7032evb1/src/Makefile | 9 +- nuttx/configs/vsn/src/Makefile | 11 +- nuttx/configs/xtrs/src/Makefile | 15 +-- nuttx/configs/z16f2800100zcog/src/Makefile | 17 +-- nuttx/configs/z80sim/src/Makefile | 15 ++- nuttx/configs/z8encore000zco/src/Makefile | 17 +-- nuttx/configs/z8f64200100kit/src/Makefile | 17 +-- 82 files changed, 746 insertions(+), 664 deletions(-) diff --git a/NxWidgets/UnitTests/CButton/Makefile b/NxWidgets/UnitTests/CButton/Makefile index c2dcfcb5dd..778d465132 100644 --- a/NxWidgets/UnitTests/CButton/Makefile +++ b/NxWidgets/UnitTests/CButton/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CButtonArray/Makefile b/NxWidgets/UnitTests/CButtonArray/Makefile index 8df0b42135..39af8ff3a2 100644 --- a/NxWidgets/UnitTests/CButtonArray/Makefile +++ b/NxWidgets/UnitTests/CButtonArray/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CCheckBox/Makefile b/NxWidgets/UnitTests/CCheckBox/Makefile index e363aed44c..5838178572 100644 --- a/NxWidgets/UnitTests/CCheckBox/Makefile +++ b/NxWidgets/UnitTests/CCheckBox/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CGlyphButton/Makefile b/NxWidgets/UnitTests/CGlyphButton/Makefile index 9b529faee2..e61f960d14 100644 --- a/NxWidgets/UnitTests/CGlyphButton/Makefile +++ b/NxWidgets/UnitTests/CGlyphButton/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CImage/Makefile b/NxWidgets/UnitTests/CImage/Makefile index b35fb2f7ca..88e7865051 100644 --- a/NxWidgets/UnitTests/CImage/Makefile +++ b/NxWidgets/UnitTests/CImage/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CKeypad/Makefile b/NxWidgets/UnitTests/CKeypad/Makefile index 2003e13f99..873b7a6951 100644 --- a/NxWidgets/UnitTests/CKeypad/Makefile +++ b/NxWidgets/UnitTests/CKeypad/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CLabel/Makefile b/NxWidgets/UnitTests/CLabel/Makefile index dacfa6274b..5122558ff2 100644 --- a/NxWidgets/UnitTests/CLabel/Makefile +++ b/NxWidgets/UnitTests/CLabel/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CLatchButton/Makefile b/NxWidgets/UnitTests/CLatchButton/Makefile index 6730a6eb57..d38872079f 100644 --- a/NxWidgets/UnitTests/CLatchButton/Makefile +++ b/NxWidgets/UnitTests/CLatchButton/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CLatchButtonArray/Makefile b/NxWidgets/UnitTests/CLatchButtonArray/Makefile index 715ab3e2ac..94a2bc49ef 100644 --- a/NxWidgets/UnitTests/CLatchButtonArray/Makefile +++ b/NxWidgets/UnitTests/CLatchButtonArray/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CListBox/Makefile b/NxWidgets/UnitTests/CListBox/Makefile index 52f3ca038b..ca90558707 100644 --- a/NxWidgets/UnitTests/CListBox/Makefile +++ b/NxWidgets/UnitTests/CListBox/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CProgressBar/Makefile b/NxWidgets/UnitTests/CProgressBar/Makefile index 49eddf1885..b9c498df9b 100644 --- a/NxWidgets/UnitTests/CProgressBar/Makefile +++ b/NxWidgets/UnitTests/CProgressBar/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CRadioButton/Makefile b/NxWidgets/UnitTests/CRadioButton/Makefile index 17b58a7c9c..0a96580e0f 100644 --- a/NxWidgets/UnitTests/CRadioButton/Makefile +++ b/NxWidgets/UnitTests/CRadioButton/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile b/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile index 9efc5d4018..0fe12318b0 100644 --- a/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile +++ b/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,7 +148,7 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context @@ -159,10 +159,11 @@ context: .context depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CScrollbarVertical/Makefile b/NxWidgets/UnitTests/CScrollbarVertical/Makefile index 3f69266281..60fb0b5451 100644 --- a/NxWidgets/UnitTests/CScrollbarVertical/Makefile +++ b/NxWidgets/UnitTests/CScrollbarVertical/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CSliderHorizonal/Makefile b/NxWidgets/UnitTests/CSliderHorizonal/Makefile index 97be73810d..5675c55bf4 100644 --- a/NxWidgets/UnitTests/CSliderHorizonal/Makefile +++ b/NxWidgets/UnitTests/CSliderHorizonal/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CSliderVertical/Makefile b/NxWidgets/UnitTests/CSliderVertical/Makefile index 1c37913932..78dc6dc8d2 100644 --- a/NxWidgets/UnitTests/CSliderVertical/Makefile +++ b/NxWidgets/UnitTests/CSliderVertical/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CTextBox/Makefile b/NxWidgets/UnitTests/CTextBox/Makefile index 8a44caee29..c913b50a4c 100644 --- a/NxWidgets/UnitTests/CTextBox/Makefile +++ b/NxWidgets/UnitTests/CTextBox/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,8 +54,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # Hello, World! C++ Example @@ -70,7 +70,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -120,7 +120,7 @@ endif # Verify that the NXWidget library has been built chklib: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -136,11 +136,11 @@ $(NXWIDGETS_LIB): # Just to keep make happy. chklib does the work. .built: chkcxx chklib $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -148,21 +148,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/nxwm/Makefile b/NxWidgets/UnitTests/nxwm/Makefile index 3dd666b113..205caf8794 100644 --- a/NxWidgets/UnitTests/nxwm/Makefile +++ b/NxWidgets/UnitTests/nxwm/Makefile @@ -36,13 +36,13 @@ TESTDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Add the path to the NXWidget include directory to the CFLAGS -NXWIDGETS_DIR="$(TESTDIR)/../../libnxwidgets" -NXWIDGETS_INC="$(NXWIDGETS_DIR)/include" -NXWIDGETS_LIB="$(NXWIDGETS_DIR)/libnxwidgets$(LIBEXT)" +NXWIDGETS_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)libnxwidgets" +NXWIDGETS_INC="$(NXWIDGETS_DIR)$(DELIM)include" +NXWIDGETS_LIB="$(NXWIDGETS_DIR)$(DELIM)libnxwidgets$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWIDGETS_INC)"} @@ -54,9 +54,9 @@ endif # Add the path to the NxWM include directory to the CFLAGS -NXWM_DIR="$(TESTDIR)/../../nxwm" -NXWM_INC="$(NXWM_DIR)/include" -NXWM_LIB="$(NXWM_DIR)/libnxwm$(LIBEXT)" +NXWM_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)nxwm" +NXWM_INC="$(NXWM_DIR)$(DELIM)include" +NXWM_LIB="$(NXWM_DIR)$(DELIM)libnxwm$(LIBEXT)" ifeq ($(WINTOOL),y) CFLAGS += ${shell $(INCDIR) -w "$(CC)" "$(NXWM_INC)"} @@ -68,8 +68,8 @@ endif # Get the path to the archiver tool -TESTTOOL_DIR="$(TESTDIR)/../../tools" -ARCHIVER=$(TESTTOOL_DIR)/addobjs.sh +TESTTOOL_DIR="$(TESTDIR)$(DELIM)..$(DELIM)..$(DELIM)tools" +ARCHIVER=$(TESTTOOL_DIR)$(DELIM)addobjs.sh # NxWM unit test @@ -84,7 +84,7 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -POSIX_BIN = "$(APPDIR)/libapps$(LIBEXT)" +POSIX_BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" ifeq ($(WINTOOL),y) BIN = "${shell cygpath -w $(POSIX_BIN)}" else @@ -134,7 +134,7 @@ endif # Verify that the NXWidget library has been built chklibnxwidgets: - @( \ + $(Q) ( \ if [ ! -e "$(NXWIDGETS_LIB)" ]; then \ echo "$(NXWIDGETS_LIB) does not exist."; \ echo "Please go to $(NXWIDGETS_DIR)"; \ @@ -146,7 +146,7 @@ chklibnxwidgets: # Verify that the NxWM library has been built chklibnxwm: - @( \ + $(Q) ( \ if [ ! -e "$(NXWM_LIB)" ]; then \ echo "$(NXWM_LIB) does not exist."; \ echo "Please go to $(NXWM_LIB)"; \ @@ -164,13 +164,13 @@ $(NXWM_LIB): # Just to keep make happy. chklibnxwm does the work. .built: $(OBJS) $(NXWIDGETS_LIB) $(call ARCHIVE, $@, $(OBJS)) ifeq ($(WINTOOL),y) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) - @$(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWM_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -w -p "$(CROSSDEV)" $(BIN) $(NXWM_DIR) else - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) - @$(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWM_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWIDGETS_DIR) + $(Q) $(ARCHIVER) -p "$(CROSSDEV)" $(BIN) $(NXWM_DIR) endif - @touch .built + $(Q) touch .built # Standard housekeeping targets @@ -178,21 +178,22 @@ endif ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) endif - @touch $@ + $(Q) touch $@ context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(ROOTDEPPATH) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/NxWidgets/libnxwidgets/Makefile b/NxWidgets/libnxwidgets/Makefile index 654f1d2fc6..27a85b428b 100644 --- a/NxWidgets/libnxwidgets/Makefile +++ b/NxWidgets/libnxwidgets/Makefile @@ -87,8 +87,8 @@ ifeq ($(WINTOOL),y) INCDIROPT = -w endif -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} -CXXFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)$(DELIM)include} +CXXFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)$(DELIM)include} DEPPATH = --dep-path src VPATH = src @@ -105,7 +105,7 @@ $(CXXOBJS): %$(OBJEXT): %.cxx $(call COMPILEXX, $<, $@) check_nuttx: - @( \ + $(Q) ( \ if [ -z "$(TOPDIR)" ]; then \ echo "The path to the nuttx directory must be provided on the command line."; \ echo "Usage: make -C $(NXWIDGETDIR) TOPDIR=\"\""; \ @@ -115,7 +115,7 @@ check_nuttx: echo "The nuttx directory (TOPDIR) does not exist: $(TOPDIR)"; \ exit 1; \ fi; \ - if [ ! -f "$(TOPDIR)/.config" ]; then \ + if [ ! -f "$(TOPDIR)$(DELIM).config" ]; then \ echo "The nuttx directory (TOPDIR) has not been configured"; \ echo "Please configure NuttX and try again"; \ exit 1; \ @@ -126,17 +126,18 @@ $(BIN): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f $(BIN) *.a *.o *~ .*.sw* + $(call DELFILE $(BIN)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) export: $(BIN) zip -r nxwidgets-export.zip include $(BIN) COPYING diff --git a/NxWidgets/nxwm/Makefile b/NxWidgets/nxwm/Makefile index d272a83848..b176ce4f7c 100644 --- a/NxWidgets/nxwm/Makefile +++ b/NxWidgets/nxwm/Makefile @@ -44,7 +44,7 @@ export Q := @ endif NXWMDIR := ${shell pwd | sed -e 's/ /\\ /g'} -NXWIDGETDIR := $(NXWMDIR)/../libnxwidgets +NXWIDGETDIR := $(NXWMDIR)$(DELIM)..$(DELIM)libnxwidgets ASRCS = CSRCS = @@ -88,10 +88,10 @@ ifeq ($(WINTOOL),y) INCDIROPT = -w endif -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWMDIR)/include} -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} -CXXFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWMDIR)/include} -CXXFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)/include} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWMDIR)$(DELIM)include} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)$(DELIM)include} +CXXFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWMDIR)$(DELIM)include} +CXXFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(NXWIDGETDIR)$(DELIM)include} DEPPATH = --dep-path src VPATH = src @@ -109,7 +109,7 @@ $(CXXOBJS): %$(OBJEXT): %.cxx $(call COMPILEXX, $<, $@) check_nuttx: - @( \ + $(Q) ( \ if [ -z "$(TOPDIR)" ]; then \ echo "The path to the nuttx directory must be provided on the command line."; \ echo "Usage: make -C $(NXWMDIR) TOPDIR=\"\""; \ @@ -119,7 +119,7 @@ check_nuttx: echo "The nuttx directory (TOPDIR) does not exist: $(TOPDIR)"; \ exit 1; \ fi; \ - if [ ! -f "$(TOPDIR)/.config" ]; then \ + if [ ! -f "$(TOPDIR)$(DELIM).config" ]; then \ echo "The nuttx directory (TOPDIR) has not been configured"; \ echo "Please configure NuttX and try again"; \ exit 1; \ @@ -130,17 +130,18 @@ $(BIN): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f $(BIN) *.a *.o *~ .*.sw* + $(call DELFILE $(BIN)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) export: $(BIN) zip -r nxwm-export.zip include $(BIN) COPYING diff --git a/misc/pascal/nuttx/Makefile b/misc/pascal/nuttx/Makefile index fc9be25e3a..701353602e 100644 --- a/misc/pascal/nuttx/Makefile +++ b/misc/pascal/nuttx/Makefile @@ -36,20 +36,20 @@ PCODEDIR := ${shell pwd | sed -e 's/ /\\ /g'} -include $(TOPDIR)/Make.defs -include $(APPDIR)/Make.defs +include $(APPDIR)$(DELIM)Make.defs # Default tools ifeq ($(DIRLINK),) -DIRLINK = $(TOPDIR)/tools/link.sh -DIRUNLINK = $(TOPDIR)/tools/unlink.sh +DIRLINK = $(TOPDIR)$(DELIM)tools$(DELIM)link.sh +DIRUNLINK = $(TOPDIR)$(DELIM)tools$(DELIM)unlink.sh endif ifeq ($(WINTOOL),y) INCDIROPT = -w endif -USRINCLUDES = ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(PCODEDIR)/include $(PCODEDIR)/insn/include} +USRINCLUDES = ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(PCODEDIR)$(DELIM)include $(PCODEDIR)$(DELIM)insn$(DELIM)include} COMPILER = ${shell basename $(CC)} ifeq ($(COMPILER),zneocc.exe) @@ -60,9 +60,9 @@ endif CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) -include insn/prun/Make.defs -include libpoff/Make.defs -include libpas/Make.defs +include insn$(DELIM)prun$(DELIM)Make.defs +include libpoff$(DELIM)Make.defs +include libpas$(DELIM)Make.defs ASRCS = $(PRUN_ASRCS) $(POFF_ASRCS) $(PAS_ASRCS) AOBJS = $(ASRCS:.S=$(OBJEXT)) @@ -74,17 +74,17 @@ SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) ifeq ($(WINTOOL),y) - BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" + BIN = "${shell cygpath -w $(APPDIR)$(DELIM)libapps$(LIBEXT)}" else - BIN = "$(APPDIR)/libapps$(LIBEXT)" + BIN = "$(APPDIR)$(DELIM)libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . -PRUNDEPPATH = --dep-path insn/prun +PRUNDEPPATH = --dep-path insn$(DELIM)prun POFFDEPPATH = --dep-path libpoff PASDEPPATH = --dep-path libpas -VPATH = insn/prun:libpoff:libpas +VPATH = insn$(DELIM)prun:libpoff:libpas all: .built .PHONY: context depend clean distclean @@ -103,17 +103,17 @@ else $(call COMPILE, $<, $@) endif -$(APPDIR)/include/pcode: include - @$(DIRLINK) $(PCODEDIR)/include $(APPDIR)/include/pcode +$(APPDIR)$(DELIM)include$(DELIM)pcode: include + @$(DIRLINK) $(PCODEDIR)$(DELIM)include $(APPDIR)$(DELIM)include$(DELIM)pcode -$(APPDIR)/include/pcode/insn: $(APPDIR)/include/pcode insn/include - @$(DIRLINK) $(PCODEDIR)/insn/include $(APPDIR)/include/pcode/insn +$(APPDIR)$(DELIM)include$(DELIM)pcode$(DELIM)insn: $(APPDIR)$(DELIM)include$(DELIM)pcode insn$(DELIM)include + @$(DIRLINK) $(PCODEDIR)$(DELIM)insn$(DELIM)include $(APPDIR)$(DELIM)include$(DELIM)pcode$(DELIM)insn -.built: $(APPDIR)/include/pcode $(APPDIR)/include/pcode/insn $(OBJS) +.built: $(APPDIR)$(DELIM)include$(DELIM)pcode $(APPDIR)$(DELIM)include$(DELIM)pcode$(DELIM)insn $(OBJS) $(call ARCHIVE, $@, $(OBJS)) @touch .built -context: $(APPDIR)/include/pcode $(APPDIR)/include/pcode/insn +context: $(APPDIR)$(DELIM)include$(DELIM)pcode $(APPDIR)$(DELIM)include$(DELIM)pcode$(DELIM)insn .depend: Makefile $(SRCS) @$(MKDEP) $(ROOTDEPPATH) $(PRUNDEPPATH) $(POFFDEPPATH) $(PASDEPPATH) \ @@ -123,12 +123,13 @@ context: $(APPDIR)/include/pcode $(APPDIR)/include/pcode/insn depend: .depend clean: - @rm -f *.o *~ .*.swp .built + $(call DELFILE .built) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend - @$(DIRUNLINK) $(APPDIR)/include/pcode/insn - @$(DIRUNLINK) $(APPDIR)/include/pcode + $(call DELFILE Make.dep) + $(call DELFILE .depend) + @$(DIRUNLINK) $(APPDIR)$(DELIM)include$(DELIM)pcode$(DELIM)insn + @$(DIRUNLINK) $(APPDIR)$(DELIM)include$(DELIM)pcode -include Make.dep diff --git a/nuttx/configs/amber/src/Makefile b/nuttx/configs/amber/src/Makefile index befcee2134..f841ede06d 100644 --- a/nuttx/configs/amber/src/Makefile +++ b/nuttx/configs/amber/src/Makefile @@ -80,16 +80,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/avr32dev1/src/Makefile b/nuttx/configs/avr32dev1/src/Makefile index 1abc7c7b92..f92a05c4ed 100644 --- a/nuttx/configs/avr32dev1/src/Makefile +++ b/nuttx/configs/avr32dev1/src/Makefile @@ -73,17 +73,18 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/c5471evm/src/Makefile b/nuttx/configs/c5471evm/src/Makefile index 42c87ccab9..80a3da5225 100644 --- a/nuttx/configs/c5471evm/src/Makefile +++ b/nuttx/configs/c5471evm/src/Makefile @@ -60,16 +60,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/compal_e88/src/Makefile b/nuttx/configs/compal_e88/src/Makefile index 8394fd47d2..5e857da644 100644 --- a/nuttx/configs/compal_e88/src/Makefile +++ b/nuttx/configs/compal_e88/src/Makefile @@ -63,16 +63,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/compal_e99/src/Makefile b/nuttx/configs/compal_e99/src/Makefile index 915786222d..2f0ea61fd4 100644 --- a/nuttx/configs/compal_e99/src/Makefile +++ b/nuttx/configs/compal_e99/src/Makefile @@ -63,16 +63,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/demo9s12ne64/src/Makefile b/nuttx/configs/demo9s12ne64/src/Makefile index fc33ef32c9..ecc2ff2469 100644 --- a/nuttx/configs/demo9s12ne64/src/Makefile +++ b/nuttx/configs/demo9s12ne64/src/Makefile @@ -69,16 +69,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/ea3131/locked/Makefile b/nuttx/configs/ea3131/locked/Makefile index 163bebf252..e52b67880d 100644 --- a/nuttx/configs/ea3131/locked/Makefile +++ b/nuttx/configs/ea3131/locked/Makefile @@ -33,22 +33,21 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs # Board-specific directory, board library, and application library -PASS1_SRCDIR = arch/$(CONFIG_ARCH)/src -PASS1_BOARDDIR = $(PASS1_SRCDIR)/board -PASS1_LIBBOARD = $(PASS1_BOARDDIR)/libboard$(LIBEXT) +PASS1_SRCDIR = arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src +PASS1_BOARDDIR = $(PASS1_SRCDIR)$(DELIM)board +PASS1_LIBBOARD = $(PASS1_BOARDDIR)$(DELIM)libboard$(LIBEXT) # Where is the application library? ifneq ($(CONFIG_APPS_DIR),) -PASS1_LIBAPPS = $(CONFIG_APPS_DIR)/libapps$(LIBEXT) +PASS1_LIBAPPS = $(CONFIG_APPS_DIR)$(DELIM)libapps$(LIBEXT) else ifneq ($(APPDIR),) -PASS1_LIBAPPS = $(APPDIR)/libapps$(LIBEXT) +PASS1_LIBAPPS = $(APPDIR)$(DELIM)libapps$(LIBEXT) endif endif @@ -63,12 +62,12 @@ PASS1_LINKLIBS += $(PASS1_LIBBOARD) ifeq ($(WINTOOL),y) # Windows-native toolchains - PASS1_LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}" - PASS1_LDSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/locked/ld-locked.inc}" + PASS1_LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)$(DELIM)lib"}" + PASS1_LDSCRIPT = -T "${shell cygpath -w $(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)locked$(DELIM)ld-locked.inc}" else # Linux/Cygwin-native toolchain - PASS1_LIBPATHS += -L"(TOPDIR)/lib" - PASS1_LDSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/locked/ld-locked.inc + PASS1_LIBPATHS += -L"(TOPDIR)$(DELIM)lib" + PASS1_LDSCRIPT = -T$(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)locked$(DELIM)ld-locked.inc endif PASS1_LDFLAGS = -r $(PASS1_LDSCRIPT) @@ -77,23 +76,23 @@ PASS1_LIBGCC = "${shell $(CC) -print-libgcc-file-name}" # Targets: -all: $(PASS1_SRCDIR)/locked.r +all: $(PASS1_SRCDIR)$(DELIM)locked.r .PHONY: depend clean distclean # Create include-able linker script that specifies all of the symbols to be # resolved in the locked.r file. -ld-locked.inc: mklocked.sh $(TOPDIR)/.config +ld-locked.inc: mklocked.sh $(TOPDIR)$(DELIM).config @echo "MK: ld-locked.inc" - @./mklocked.sh "$(TOPDIR)" + @.$(DELIM)mklocked.sh "$(TOPDIR)" # Make the board library. This is normally done in arch/arm/src/Makefile. # However, we need it earlier here when doing a two-pass build so that libboard.a # is available to link against. $(PASS1_LIBBOARD): - @$(MAKE) -C $(TOPDIR)/configs/ea3131/src TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C $(TOPDIR)$(DELIM)configs$(DELIM)ea3131$(DELIM)src TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) # Create the locked.r file containing all of the code (except the start-up code) # that needs to lie in the locked text region. @@ -105,16 +104,17 @@ locked.r: ld-locked.inc $(PASS1_LIBBOARD) @fgrep " U " locked.map | grep -v os_start @$(CROSSDEV)size $@ -$(PASS1_SRCDIR)/locked.r: locked.r - @cp -a locked.r $(TOPDIR)/$(PASS1_SRCDIR)/locked.r +$(PASS1_SRCDIR)$(DELIM)locked.r: locked.r + @cp -a locked.r $(TOPDIR)$(DELIM)$(PASS1_SRCDIR)$(DELIM)locked.r .depend: depend: .depend clean: - @rm -f locked.r locked.map *~ .*.swp + $(call DELFILE locked.r) + $(call DELFILE locked.map) + $(call CLEAN) distclean: clean - @rm -f ld-locked.inc - + $(call DELFILE ld-locked.inc) diff --git a/nuttx/configs/ea3131/src/Makefile b/nuttx/configs/ea3131/src/Makefile index 8b628a0ebc..06089df464 100644 --- a/nuttx/configs/ea3131/src/Makefile +++ b/nuttx/configs/ea3131/src/Makefile @@ -88,16 +88,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/ea3152/src/Makefile b/nuttx/configs/ea3152/src/Makefile index c360856475..6ade0ffd38 100644 --- a/nuttx/configs/ea3152/src/Makefile +++ b/nuttx/configs/ea3152/src/Makefile @@ -88,16 +88,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/eagle100/src/Makefile b/nuttx/configs/eagle100/src/Makefile index 3bb71aa89e..9096f164fc 100644 --- a/nuttx/configs/eagle100/src/Makefile +++ b/nuttx/configs/eagle100/src/Makefile @@ -69,16 +69,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/ekk-lm3s9b96/src/Makefile b/nuttx/configs/ekk-lm3s9b96/src/Makefile index a012fcc255..adabe130a4 100644 --- a/nuttx/configs/ekk-lm3s9b96/src/Makefile +++ b/nuttx/configs/ekk-lm3s9b96/src/Makefile @@ -71,16 +71,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/ez80f910200kitg/src/Makefile b/nuttx/configs/ez80f910200kitg/src/Makefile index a5515d855b..e430be9ab7 100644 --- a/nuttx/configs/ez80f910200kitg/src/Makefile +++ b/nuttx/configs/ez80f910200kitg/src/Makefile @@ -53,9 +53,9 @@ OBJS = $(AOBJS) $(COBJS) all: libboard$(LIBEXT) $(ASRCS) $(HEAD_ASRC): %$(ASMEXT): %.S - @$(CPP) $(CPPFLAGS) `cygpath -w $<` -o $@.tmp - @cat $@.tmp | sed -e "s/^#/;/g" > $@ - @rm $@.tmp + $(Q) $(CPP) $(CPPFLAGS) `cygpath -w $<` -o $@.tmp + $(Q) cat $@.tmp | sed -e "s/^#/;/g" > $@ + $(Q) rm $@.tmp $(AOBJS): %$(OBJEXT): %$(ASMEXT) $(call ASSEMBLE, $<, $@) @@ -67,16 +67,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/ez80f910200zco/src/Makefile b/nuttx/configs/ez80f910200zco/src/Makefile index faaec39ef7..2b56c1cea1 100644 --- a/nuttx/configs/ez80f910200zco/src/Makefile +++ b/nuttx/configs/ez80f910200zco/src/Makefile @@ -60,9 +60,9 @@ OBJS = $(AOBJS) $(COBJS) all: libboard$(LIBEXT) $(ASRCS) $(HEAD_ASRC): %$(ASMEXT): %.S - @$(CPP) $(CPPFLAGS) `cygpath -w $<` -o $@.tmp - @cat $@.tmp | sed -e "s/^#/;/g" > $@ - @rm $@.tmp + $(Q) $(CPP) $(CPPFLAGS) `cygpath -w $<` -o $@.tmp + $(Q) cat $@.tmp | sed -e "s/^#/;/g" > $@ + $(Q) rm $@.tmp $(AOBJS): %$(OBJEXT): %$(ASMEXT) $(call ASSEMBLE, $<, $@) @@ -74,16 +74,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/fire-stm32v2/src/Makefile b/nuttx/configs/fire-stm32v2/src/Makefile index 2fa9039ce0..6492b216a6 100644 --- a/nuttx/configs/fire-stm32v2/src/Makefile +++ b/nuttx/configs/fire-stm32v2/src/Makefile @@ -110,16 +110,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/hymini-stm32v/src/Makefile b/nuttx/configs/hymini-stm32v/src/Makefile index 42b16287ca..c57eee3384 100644 --- a/nuttx/configs/hymini-stm32v/src/Makefile +++ b/nuttx/configs/hymini-stm32v/src/Makefile @@ -89,16 +89,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/kwikstik-k40/src/Makefile b/nuttx/configs/kwikstik-k40/src/Makefile index dda93719d0..7560007392 100644 --- a/nuttx/configs/kwikstik-k40/src/Makefile +++ b/nuttx/configs/kwikstik-k40/src/Makefile @@ -88,16 +88,16 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend - clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/lincoln60/src/Makefile b/nuttx/configs/lincoln60/src/Makefile index b31f42ba41..1be1108a59 100644 --- a/nuttx/configs/lincoln60/src/Makefile +++ b/nuttx/configs/lincoln60/src/Makefile @@ -79,16 +79,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/lm3s6432-s2e/src/Makefile b/nuttx/configs/lm3s6432-s2e/src/Makefile index 64faf3a778..1fe533a4ec 100644 --- a/nuttx/configs/lm3s6432-s2e/src/Makefile +++ b/nuttx/configs/lm3s6432-s2e/src/Makefile @@ -70,16 +70,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/lm3s6965-ek/src/Makefile b/nuttx/configs/lm3s6965-ek/src/Makefile index 12750d192a..ddba1f4107 100644 --- a/nuttx/configs/lm3s6965-ek/src/Makefile +++ b/nuttx/configs/lm3s6965-ek/src/Makefile @@ -73,16 +73,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/lm3s8962-ek/src/Makefile b/nuttx/configs/lm3s8962-ek/src/Makefile index 8b1400ea0d..07551c406b 100644 --- a/nuttx/configs/lm3s8962-ek/src/Makefile +++ b/nuttx/configs/lm3s8962-ek/src/Makefile @@ -73,16 +73,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/lpc4330-xplorer/src/Makefile b/nuttx/configs/lpc4330-xplorer/src/Makefile index 9698f78fc6..75b5b76119 100644 --- a/nuttx/configs/lpc4330-xplorer/src/Makefile +++ b/nuttx/configs/lpc4330-xplorer/src/Makefile @@ -107,16 +107,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile index d1012b8a90..522027ab6d 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile +++ b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile @@ -79,16 +79,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/m68332evb/src/Makefile b/nuttx/configs/m68332evb/src/Makefile index 46a06c71ab..dfc787419d 100644 --- a/nuttx/configs/m68332evb/src/Makefile +++ b/nuttx/configs/m68332evb/src/Makefile @@ -57,16 +57,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/mbed/src/Makefile b/nuttx/configs/mbed/src/Makefile index 31b5df171d..d5e4412a06 100644 --- a/nuttx/configs/mbed/src/Makefile +++ b/nuttx/configs/mbed/src/Makefile @@ -73,16 +73,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/mcu123-lpc214x/src/Makefile b/nuttx/configs/mcu123-lpc214x/src/Makefile index 62ff003a16..47feeb0c5d 100644 --- a/nuttx/configs/mcu123-lpc214x/src/Makefile +++ b/nuttx/configs/mcu123-lpc214x/src/Makefile @@ -80,16 +80,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/micropendous3/src/Makefile b/nuttx/configs/micropendous3/src/Makefile index 3041fb282d..66231a3b28 100644 --- a/nuttx/configs/micropendous3/src/Makefile +++ b/nuttx/configs/micropendous3/src/Makefile @@ -80,16 +80,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/mirtoo/src/Makefile b/nuttx/configs/mirtoo/src/Makefile index 9bda8246df..d560d803d9 100644 --- a/nuttx/configs/mirtoo/src/Makefile +++ b/nuttx/configs/mirtoo/src/Makefile @@ -79,16 +79,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/mx1ads/src/Makefile b/nuttx/configs/mx1ads/src/Makefile index e55195649a..a264617403 100644 --- a/nuttx/configs/mx1ads/src/Makefile +++ b/nuttx/configs/mx1ads/src/Makefile @@ -60,16 +60,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/ne64badge/src/Makefile b/nuttx/configs/ne64badge/src/Makefile index 52cd7897b1..deeca6abb8 100644 --- a/nuttx/configs/ne64badge/src/Makefile +++ b/nuttx/configs/ne64badge/src/Makefile @@ -69,16 +69,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/ntosd-dm320/src/Makefile b/nuttx/configs/ntosd-dm320/src/Makefile index 114e5bf997..47cedfaf78 100644 --- a/nuttx/configs/ntosd-dm320/src/Makefile +++ b/nuttx/configs/ntosd-dm320/src/Makefile @@ -60,16 +60,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/nucleus2g/src/Makefile b/nuttx/configs/nucleus2g/src/Makefile index 1f2c02fd1e..e6c33821ae 100644 --- a/nuttx/configs/nucleus2g/src/Makefile +++ b/nuttx/configs/nucleus2g/src/Makefile @@ -73,16 +73,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/olimex-lpc1766stk/src/Makefile b/nuttx/configs/olimex-lpc1766stk/src/Makefile index 955c80937e..8ac131ffdb 100644 --- a/nuttx/configs/olimex-lpc1766stk/src/Makefile +++ b/nuttx/configs/olimex-lpc1766stk/src/Makefile @@ -87,16 +87,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/olimex-lpc2378/src/Makefile b/nuttx/configs/olimex-lpc2378/src/Makefile index 12cddf95be..05a84cdeaf 100644 --- a/nuttx/configs/olimex-lpc2378/src/Makefile +++ b/nuttx/configs/olimex-lpc2378/src/Makefile @@ -76,16 +76,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/olimex-stm32-p107/src/Makefile b/nuttx/configs/olimex-stm32-p107/src/Makefile index a0d6fc5ff1..3fc0abe5df 100644 --- a/nuttx/configs/olimex-stm32-p107/src/Makefile +++ b/nuttx/configs/olimex-stm32-p107/src/Makefile @@ -72,16 +72,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/olimex-strp711/src/Makefile b/nuttx/configs/olimex-strp711/src/Makefile index 766305c03b..12c48d2133 100644 --- a/nuttx/configs/olimex-strp711/src/Makefile +++ b/nuttx/configs/olimex-strp711/src/Makefile @@ -73,16 +73,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/pcblogic-pic32mx/src/Makefile b/nuttx/configs/pcblogic-pic32mx/src/Makefile index 6eda3248bb..2e576b795b 100644 --- a/nuttx/configs/pcblogic-pic32mx/src/Makefile +++ b/nuttx/configs/pcblogic-pic32mx/src/Makefile @@ -71,16 +71,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/pic32-starterkit/src/Makefile b/nuttx/configs/pic32-starterkit/src/Makefile index a1ee69b929..acaaa91c58 100644 --- a/nuttx/configs/pic32-starterkit/src/Makefile +++ b/nuttx/configs/pic32-starterkit/src/Makefile @@ -82,16 +82,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/pic32mx7mmb/src/Makefile b/nuttx/configs/pic32mx7mmb/src/Makefile index 92445604ed..304989a847 100644 --- a/nuttx/configs/pic32mx7mmb/src/Makefile +++ b/nuttx/configs/pic32mx7mmb/src/Makefile @@ -86,16 +86,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/pjrc-8051/src/Makefile b/nuttx/configs/pjrc-8051/src/Makefile index 5d9b553692..fccb3ada2a 100644 --- a/nuttx/configs/pjrc-8051/src/Makefile +++ b/nuttx/configs/pjrc-8051/src/Makefile @@ -59,16 +59,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/qemu-i486/src/Makefile b/nuttx/configs/qemu-i486/src/Makefile index 785b78be7a..06debd3e0d 100644 --- a/nuttx/configs/qemu-i486/src/Makefile +++ b/nuttx/configs/qemu-i486/src/Makefile @@ -66,16 +66,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/sam3u-ek/kernel/Makefile b/nuttx/configs/sam3u-ek/kernel/Makefile index 24934c4794..6daf62253e 100644 --- a/nuttx/configs/sam3u-ek/kernel/Makefile +++ b/nuttx/configs/sam3u-ek/kernel/Makefile @@ -33,24 +33,23 @@ # ############################################################################ --include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs # This is the directory for the board-specific header files -BOARD_INCLUDE = $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/include +BOARD_INCLUDE = $(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)include # Get the paths to the libraries and the links script path in format that # is appropriate for the host OS ifeq ($(WINTOOL),y) # Windows-native toolchains - USER_LIBPATHS = ${shell for path in $(USERLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done} - USER_LDSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/kernel/kernel.ld}" + USER_LIBPATHS = ${shell for path in $(USERLIBS); do dir=`dirname $(TOPDIR)$(DELIM)$$path`;echo "-L\"`cygpath -w $$dir`\"";done} + USER_LDSCRIPT = -T "${shell cygpath -w $(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)kernel$(DELIM)kernel.ld}" else # Linux/Cygwin-native toolchain - USER_LIBPATHS = $(addprefix -L$(TOPDIR)/,$(dir $(USERLIBS))) - USER_LDSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/kernel/kernel.ld + USER_LIBPATHS = $(addprefix -L$(TOPDIR)$(DELIM),$(dir $(USERLIBS))) + USER_LDSCRIPT = -T$(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)kernel$(DELIM)kernel.ld endif USER_LDFLAGS = $(USER_LDSCRIPT) @@ -59,78 +58,80 @@ USER_LIBGCC = "${shell $(CC) -print-libgcc-file-name}" # Targets: -all: $(TOPDIR)/nuttx_user.elf $(TOPDIR)/User.map $(BOARD_INCLUDE)/user_map.h +all: $(TOPDIR)$(DELIM)nuttx_user.elf $(TOPDIR)$(DELIM)User.map $(BOARD_INCLUDE)$(DELIM)user_map.h .PHONY: depend clean distclean # Create the nuttx_user.elf file containing all of the user-mode code nuttx_user.elf: - @$(LD) -o $@ $(USER_LDFLAGS) $(USER_LIBPATHS) --start-group $(USER_LDLIBS) --end-group $(USER_LIBGCC) + $(Q) $(LD) -o $@ $(USER_LDFLAGS) $(USER_LIBPATHS) --start-group $(USER_LDLIBS) --end-group $(USER_LIBGCC) -$(TOPDIR)/nuttx_user.elf: nuttx_user.elf +$(TOPDIR)$(DELIM)nuttx_user.elf: nuttx_user.elf @echo "LD: nuttx_user.elf" - @cp -a nuttx_user.elf $(TOPDIR)/nuttx_user.elf + $(Q) cp -a nuttx_user.elf $(TOPDIR)$(DELIM)nuttx_user.elf ifeq ($(CONFIG_INTELHEX_BINARY),y) @echo "CP: nuttx_user.hex" - @$(OBJCOPY) $(OBJCOPYARGS) -O ihex nuttx_user.elf $(TOPDIR)/nuttx_user.hex + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O ihex nuttx_user.elf $(TOPDIR)$(DELIM)nuttx_user.hex endif ifeq ($(CONFIG_MOTOROLA_SREC),y) @echo "CP: nuttx_user.srec" - @$(OBJCOPY) $(OBJCOPYARGS) -O srec nuttx_user.elf $(TOPDIR)/nuttx_user.srec + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O srec nuttx_user.elf $(TOPDIR)$(DELIM)nuttx_user.srec endif ifeq ($(CONFIG_RAW_BINARY),y) @echo "CP: nuttx_user.bin" - @$(OBJCOPY) $(OBJCOPYARGS) -O binary nuttx_user.elf $(TOPDIR)/nuttx_user.bin + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O binary nuttx_user.elf $(TOPDIR)$(DELIM)nuttx_user.bin endif -$(TOPDIR)/User.map: nuttx_user.elf +$(TOPDIR)$(DELIM)User.map: nuttx_user.elf @echo "MK: User.map" - @$(NM) nuttx_user.elf >$(TOPDIR)/User.map - @$(CROSSDEV)size nuttx_user.elf + $(Q) $(NM) nuttx_user.elf >$(TOPDIR)$(DELIM)User.map + $(Q) $(CROSSDEV)size nuttx_user.elf -$(BOARD_INCLUDE)/user_map.h: $(TOPDIR)/User.map +$(BOARD_INCLUDE)$(DELIM)user_map.h: $(TOPDIR)$(DELIM)User.map @echo "MK: user_map.h" - @echo "/* configs/$(CONFIG_ARCH_BOARD)/include/user_map.h" > $(BOARD_INCLUDE)/user_map.h - @echo " *" >> $(BOARD_INCLUDE)/user_map.h - @echo " * This is an auto-generated file.. Do not edit this file!" >> $(BOARD_INCLUDE)/user_map.h - @echo " */" >> $(BOARD_INCLUDE)/user_map.h - @echo "" >> $(BOARD_INCLUDE)/user_map.h - @echo "#ifndef __ARCH_BOARD_USER_MAP_H" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define __ARCH_BOARD_USER_MAP_H" >> $(BOARD_INCLUDE)/user_map.h - @echo "" >> $(BOARD_INCLUDE)/user_map.h - @echo "/* General memory map */" >> $(BOARD_INCLUDE)/user_map.h - @echo "" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_ENTRYPOINT 0x`grep \" user_start$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_TEXTSTART 0x`grep \" _stext\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_TEXTEND 0x`grep \" _etext$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_DATASOURCE 0x`grep \" _eronly$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_DATADESTSTART 0x`grep \" _sdata$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_DATADESTEND 0x`grep \" _edata$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_BSSSTART 0x`grep \" _sbss\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_BSSEND 0x`grep \" _ebss$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "" >> $(BOARD_INCLUDE)/user_map.h - @echo "/* Memory manager entry points */" >> $(BOARD_INCLUDE)/user_map.h - @echo "" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_MMINIT 0x`grep \" mm_initialize$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_MMADDREGION 0x`grep \" mm_addregion$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_MMTRYSEM 0x`grep \" mm_trysemaphore$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_MMGIVESEM 0x`grep \" mm_givesemaphore$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_MALLOC 0x`grep \" malloc$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_REALLOC 0x`grep \" realloc$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_ZALLOC 0x`grep \" zalloc$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "#define CONFIG_USER_FREE 0x`grep \" free$\" $(TOPDIR)/User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)/user_map.h - @echo "" >> $(BOARD_INCLUDE)/user_map.h - @echo "#endif /* __ARCH_BOARD_USER_MAP_H */" >> $(BOARD_INCLUDE)/user_map.h + @echo "/* configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)include$(DELIM)user_map.h" > $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo " *" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo " * This is an auto-generated file.. Do not edit this file!" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo " */" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#ifndef __ARCH_BOARD_USER_MAP_H" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define __ARCH_BOARD_USER_MAP_H" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "/* General memory map */" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_ENTRYPOINT 0x`grep \" user_start$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_TEXTSTART 0x`grep \" _stext\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_TEXTEND 0x`grep \" _etext$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_DATASOURCE 0x`grep \" _eronly$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_DATADESTSTART 0x`grep \" _sdata$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_DATADESTEND 0x`grep \" _edata$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_BSSSTART 0x`grep \" _sbss\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_BSSEND 0x`grep \" _ebss$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "/* Memory manager entry points */" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_MMINIT 0x`grep \" mm_initialize$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_MMADDREGION 0x`grep \" mm_addregion$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_MMTRYSEM 0x`grep \" mm_trysemaphore$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_MMGIVESEM 0x`grep \" mm_givesemaphore$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_MALLOC 0x`grep \" malloc$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_REALLOC 0x`grep \" realloc$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_ZALLOC 0x`grep \" zalloc$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#define CONFIG_USER_FREE 0x`grep \" free$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + @echo "#endif /* __ARCH_BOARD_USER_MAP_H */" >> $(BOARD_INCLUDE)$(DELIM)user_map.h .depend: depend: .depend clean: - @rm -f nuttx_user.elf *~ .*.swp - @rm -f $(TOPDIR)/nuttx_user.elf $(TOPDIR)/User.map + $(call DELFILE nuttx_user.elf) + $(call DELFILE "$(TOPDIR)$(DELIM)nuttx_user.elf") + $(call DELFILE "$(TOPDIR)$(DELIM)User.map") + $(call CLEAN) distclean: clean diff --git a/nuttx/configs/sam3u-ek/src/Makefile b/nuttx/configs/sam3u-ek/src/Makefile index 97227b40a4..18fba3eb02 100644 --- a/nuttx/configs/sam3u-ek/src/Makefile +++ b/nuttx/configs/sam3u-ek/src/Makefile @@ -79,16 +79,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile index ad4c1d7718..d7ca85efcd 100644 --- a/nuttx/configs/shenzhou/src/Makefile +++ b/nuttx/configs/shenzhou/src/Makefile @@ -130,16 +130,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/sim/src/Makefile b/nuttx/configs/sim/src/Makefile index 9b924486d0..adfbb1f9a3 100644 --- a/nuttx/configs/sim/src/Makefile +++ b/nuttx/configs/sim/src/Makefile @@ -60,22 +60,23 @@ $(COBJS) $(LINKOBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libboard$(LIBEXT): $(OBJS) - @$(AR) $@ # Create an empty archive + $(Q) $(AR) $@ # Create an empty archive ifneq ($(OBJS),) $(call ARCHIVE, $@, $(OBJS)) endif .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/skp16c26/src/Makefile b/nuttx/configs/skp16c26/src/Makefile index 21a528c04c..306e268063 100644 --- a/nuttx/configs/skp16c26/src/Makefile +++ b/nuttx/configs/skp16c26/src/Makefile @@ -60,16 +60,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/stm3210e-eval/src/Makefile b/nuttx/configs/stm3210e-eval/src/Makefile index e9af34f213..e518366887 100644 --- a/nuttx/configs/stm3210e-eval/src/Makefile +++ b/nuttx/configs/stm3210e-eval/src/Makefile @@ -114,16 +114,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/stm3220g-eval/src/Makefile b/nuttx/configs/stm3220g-eval/src/Makefile index 1a670588f8..a5072bdb4e 100644 --- a/nuttx/configs/stm3220g-eval/src/Makefile +++ b/nuttx/configs/stm3220g-eval/src/Makefile @@ -114,16 +114,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/stm3240g-eval/src/Makefile b/nuttx/configs/stm3240g-eval/src/Makefile index 8ea4690c55..81924abcbd 100644 --- a/nuttx/configs/stm3240g-eval/src/Makefile +++ b/nuttx/configs/stm3240g-eval/src/Makefile @@ -122,16 +122,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/stm32f100rc_generic/src/Makefile b/nuttx/configs/stm32f100rc_generic/src/Makefile index c0916f40cb..57c96a57fd 100644 --- a/nuttx/configs/stm32f100rc_generic/src/Makefile +++ b/nuttx/configs/stm32f100rc_generic/src/Makefile @@ -66,16 +66,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/sure-pic32mx/src/Makefile b/nuttx/configs/sure-pic32mx/src/Makefile index 3c8e5277bd..dd2078ed18 100644 --- a/nuttx/configs/sure-pic32mx/src/Makefile +++ b/nuttx/configs/sure-pic32mx/src/Makefile @@ -91,16 +91,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/teensy/src/Makefile b/nuttx/configs/teensy/src/Makefile index a1e6a6e05c..e1c7c029a7 100644 --- a/nuttx/configs/teensy/src/Makefile +++ b/nuttx/configs/teensy/src/Makefile @@ -86,16 +86,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/twr-k60n512/src/Makefile b/nuttx/configs/twr-k60n512/src/Makefile index 3c036b0886..257e8e73f7 100644 --- a/nuttx/configs/twr-k60n512/src/Makefile +++ b/nuttx/configs/twr-k60n512/src/Makefile @@ -88,16 +88,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/ubw32/src/Makefile b/nuttx/configs/ubw32/src/Makefile index 49243ab83a..608563b7e9 100644 --- a/nuttx/configs/ubw32/src/Makefile +++ b/nuttx/configs/ubw32/src/Makefile @@ -82,16 +82,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/us7032evb1/shterm/Makefile b/nuttx/configs/us7032evb1/shterm/Makefile index 2ea23db331..f290eabc36 100644 --- a/nuttx/configs/us7032evb1/shterm/Makefile +++ b/nuttx/configs/us7032evb1/shterm/Makefile @@ -33,19 +33,20 @@ # ############################################################################ -include $(TOPDIR)/.config include $(TOPDIR)/Make.defs SRC = shterm.c BIN = shterm -all: ../bin/$(BIN)$(EXEEXT) +all: ..$(DELIM)bin$(DELIM)$(BIN)$(EXEEXT) $(BIN)$(EXEEXT): $(SRC) $(HOSTCC) $(HOSTCFLAGS) $^ -o $@ -../bin/$(BIN)$(EXEEXT): $(BIN)$(EXEEXT) +..$(DELIM)bin$(DELIM)$(BIN)$(EXEEXT): $(BIN)$(EXEEXT) install --mode 0755 $^ $@ + clean: - @rm -f $(BIN)$(EXEEXT) ../bin/$(BIN)$(EXEEXT) *~ .*.swp *.o + $(call DELFILE $(BIN)$(EXEEXT)) + $(call DELFILE..$(DELIM)bin$(DELIM)$(BIN)$(EXEEXT)) $(call CLEAN) diff --git a/nuttx/configs/us7032evb1/src/Makefile b/nuttx/configs/us7032evb1/src/Makefile index cd4fc1b746..bf457d1c5d 100644 --- a/nuttx/configs/us7032evb1/src/Makefile +++ b/nuttx/configs/us7032evb1/src/Makefile @@ -60,16 +60,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT))) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/vsn/src/Makefile b/nuttx/configs/vsn/src/Makefile index 917dcbd7a9..947cae18e5 100644 --- a/nuttx/configs/vsn/src/Makefile +++ b/nuttx/configs/vsn/src/Makefile @@ -87,23 +87,24 @@ libboard$(LIBEXT): $(OBJS) .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - @touch $@ + $(Q) touch $@ context: .context # Create dependencies .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend .context + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/xtrs/src/Makefile b/nuttx/configs/xtrs/src/Makefile index 0662e145e3..074e5c2945 100644 --- a/nuttx/configs/xtrs/src/Makefile +++ b/nuttx/configs/xtrs/src/Makefile @@ -35,7 +35,7 @@ -include $(TOPDIR)/Make.defs -CFLAGS += -I$(TOPDIR)/sched -I$(TOPDIR)/arch/z80/src/common -I$(TOPDIR)/arch/z80/src/z80 +CFLAGS += -I$(TOPDIR)$(DELIM)sched -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)common -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)z80 ASRCS = AOBJS = $(ASRCS:$(ASMEXT)=$(OBJEXT)) @@ -45,8 +45,8 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -CFLAGS += -I $(TOPDIR)/arch/$(CONFIG_ARCH)/src -CFLAGS += -I $(TOPDIR)/arch/$(CONFIG_ARCH)/include +CFLAGS += -I $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src +CFLAGS += -I $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)include all: libboard$(LIBEXT) @@ -60,16 +60,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/z16f2800100zcog/src/Makefile b/nuttx/configs/z16f2800100zcog/src/Makefile index 8c5bfd1e85..135dfc4774 100644 --- a/nuttx/configs/z16f2800100zcog/src/Makefile +++ b/nuttx/configs/z16f2800100zcog/src/Makefile @@ -35,7 +35,7 @@ -include $(TOPDIR)/Make.defs -ARCHSRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common' INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) @@ -53,9 +53,9 @@ OBJS = $(AOBJS) $(COBJS) all: libboard$(LIBEXT) $(ASRCS) $(HEAD_ASRC): %$(ASMEXT): %.S - @$(CPP) $(CPPFLAGS) $< -o $@.tmp - @cat $@.tmp | sed -e "s/^#/;/g" > $@ - @rm $@.tmp + $(Q) $(CPP) $(CPPFLAGS) $< -o $@.tmp + $(Q) cat $@.tmp | sed -e "s/^#/;/g" > $@ + $(Q) rm $@.tmp $(AOBJS): %$(OBJEXT): %$(ASMEXT) $(call ASSEMBLE, $<, $@) @@ -67,16 +67,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/z80sim/src/Makefile b/nuttx/configs/z80sim/src/Makefile index 2dc3a785ca..bc2e00715a 100644 --- a/nuttx/configs/z80sim/src/Makefile +++ b/nuttx/configs/z80sim/src/Makefile @@ -35,7 +35,9 @@ -include $(TOPDIR)/Make.defs -CFLAGS += -I$(TOPDIR)/sched -I$(TOPDIR)/arch/z80/src/common -I$(TOPDIR)/arch/z80/src/z80 +CFLAGS += -I$(TOPDIR)$(DELIM)sched +CFLAGS += -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)common -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)z80 +CFLAGS += -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)z80 ASRCS = AOBJS = $(ASRCS:$(ASMEXT)=$(OBJEXT)) @@ -45,7 +47,7 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -CFLAGS += -I $(TOPDIR)/arch/$(CONFIG_ARCH)/src +CFLAGS += -I $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src all: libboard$(LIBEXT) @@ -59,16 +61,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/z8encore000zco/src/Makefile b/nuttx/configs/z8encore000zco/src/Makefile index e274e7b83f..e034435c60 100644 --- a/nuttx/configs/z8encore000zco/src/Makefile +++ b/nuttx/configs/z8encore000zco/src/Makefile @@ -35,7 +35,7 @@ -include $(TOPDIR)/Make.defs -ARCHSRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common' INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) @@ -53,9 +53,9 @@ OBJS = $(AOBJS) $(COBJS) all: libboard$(LIBEXT) $(ASRCS) $(HEAD_ASRC): %$(ASMEXT): %.S - @$(CPP) $(CPPFLAGS) `cygpath -w $<` -o $@.tmp - @cat $@.tmp | sed -e "s/^#/;/g" > $@ - @rm $@.tmp + $(Q) $(CPP) $(CPPFLAGS) `cygpath -w $<` -o $@.tmp + $(Q) cat $@.tmp | sed -e "s/^#/;/g" > $@ + $(Q) rm $@.tmp $(AOBJS): %$(OBJEXT): %$(ASMEXT) $(call ASSEMBLE, $<, $@) @@ -67,16 +67,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep diff --git a/nuttx/configs/z8f64200100kit/src/Makefile b/nuttx/configs/z8f64200100kit/src/Makefile index da104cedf2..2a53b93425 100644 --- a/nuttx/configs/z8f64200100kit/src/Makefile +++ b/nuttx/configs/z8f64200100kit/src/Makefile @@ -35,7 +35,7 @@ -include $(TOPDIR)/Make.defs -ARCHSRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common' INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) @@ -53,9 +53,9 @@ OBJS = $(AOBJS) $(COBJS) all: libboard$(LIBEXT) $(ASRCS) $(HEAD_ASRC): %$(ASMEXT): %.S - @$(CPP) $(CPPFLAGS) `cygpath -w $<` -o $@.tmp - @cat $@.tmp | sed -e "s/^#/;/g" > $@ - @rm $@.tmp + $(Q) $(CPP) $(CPPFLAGS) `cygpath -w $<` -o $@.tmp + $(Q) cat $@.tmp | sed -e "s/^#/;/g" > $@ + $(Q) rm $@.tmp $(AOBJS): %$(OBJEXT): %$(ASMEXT) $(call ASSEMBLE, $<, $@) @@ -67,16 +67,17 @@ libboard$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f libboard$(LIBEXT) *~ .*.swp + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE Make.dep) + $(call DELFILE .depend) -include Make.dep From a98248b591a69249c97849745788737d25dc3731 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 18 Nov 2012 20:59:30 +0000 Subject: [PATCH 140/206] Fix typol in Config.mk that would effect non-Windows builds git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5369 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Makefile.win | 12 ++++++------ nuttx/tools/Config.mk | 14 +++++++++++++- 2 files changed, 19 insertions(+), 7 deletions(-) diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win index f98c5e6d83..7f96206924 100644 --- a/nuttx/Makefile.win +++ b/nuttx/Makefile.win @@ -442,12 +442,12 @@ clean_context: $(call DELFILE include\nuttx\version.h) $(call DELFILE include\math.h) $(call DELFILE include\stdarg.h) - $(Q) $(DIRUNLINK) include\arch\board - $(Q) $(DIRUNLINK) include\arch\chip - $(Q) $(DIRUNLINK) include\arch - $(Q) $(DIRUNLINK) $(ARCH_SRC)\board - $(Q) $(DIRUNLINK) $(ARCH_SRC)\chip - $(Q) $(DIRUNLINK) include\apps + $(call DELDIR include\arch\board) + $(call DELDIR include\arch\chip) + $(call DELDIR include\arch) + $(call DELDIR $(ARCH_SRC)\board) + $(call DELDIR $(ARCH_SRC)\chip) + $(call DELDIR include\apps) # check_context # diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk index aafb58f35b..300df7a6ac 100644 --- a/nuttx/tools/Config.mk +++ b/nuttx/tools/Config.mk @@ -182,11 +182,23 @@ define DELFILE $(Q) if exist $1 (del /f /q $1) endef else -define CLEAN +define DELFILE $(Q) rm -f $1 endef endif +# DELDIR - Delect one directory + +ifeq ($(CONFIG_WINDOWS_NATIVE),y) +define DELDIR + $(Q) if exist $1 (rmdir /q /s $1) +endef +else +define DELDIR + $(Q) rm -rf $1 +endef +endif + # CLEAN - Default clean target ifeq ($(CONFIG_WINDOWS_NATIVE),y) From 7a68d939992a06512b617200662807de441766d6 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 19 Nov 2012 19:53:53 +0000 Subject: [PATCH 141/206] Fix typo introduced into many Makefiles with last changes git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5370 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Makefile.unix | 2 +- nuttx/Makefile.win | 2 +- nuttx/configs/amber/src/Makefile | 2 +- nuttx/configs/avr32dev1/src/Makefile | 2 +- nuttx/configs/c5471evm/src/Makefile | 2 +- nuttx/configs/compal_e88/src/Makefile | 2 +- nuttx/configs/compal_e99/src/Makefile | 2 +- nuttx/configs/demo9s12ne64/src/Makefile | 2 +- nuttx/configs/ea3131/src/Makefile | 2 +- nuttx/configs/ea3152/src/Makefile | 2 +- nuttx/configs/eagle100/src/Makefile | 2 +- nuttx/configs/ekk-lm3s9b96/src/Makefile | 2 +- nuttx/configs/ez80f910200kitg/src/Makefile | 2 +- nuttx/configs/ez80f910200zco/src/Makefile | 2 +- nuttx/configs/fire-stm32v2/src/Makefile | 2 +- nuttx/configs/hymini-stm32v/src/Makefile | 2 +- nuttx/configs/kwikstik-k40/src/Makefile | 2 +- nuttx/configs/lincoln60/src/Makefile | 2 +- nuttx/configs/lm3s6432-s2e/src/Makefile | 2 +- nuttx/configs/lm3s6965-ek/src/Makefile | 2 +- nuttx/configs/lm3s8962-ek/src/Makefile | 2 +- nuttx/configs/lpc4330-xplorer/src/Makefile | 2 +- nuttx/configs/lpcxpresso-lpc1768/src/Makefile | 2 +- nuttx/configs/m68332evb/src/Makefile | 2 +- nuttx/configs/mbed/src/Makefile | 2 +- nuttx/configs/mcu123-lpc214x/src/Makefile | 2 +- nuttx/configs/micropendous3/src/Makefile | 2 +- nuttx/configs/mirtoo/src/Makefile | 2 +- nuttx/configs/mx1ads/src/Makefile | 2 +- nuttx/configs/ne64badge/src/Makefile | 2 +- nuttx/configs/ntosd-dm320/src/Makefile | 2 +- nuttx/configs/nucleus2g/src/Makefile | 2 +- nuttx/configs/olimex-lpc1766stk/src/Makefile | 2 +- nuttx/configs/olimex-lpc2378/src/Makefile | 2 +- nuttx/configs/olimex-stm32-p107/src/Makefile | 2 +- nuttx/configs/olimex-strp711/src/Makefile | 2 +- nuttx/configs/pcblogic-pic32mx/src/Makefile | 2 +- nuttx/configs/pic32-starterkit/src/Makefile | 2 +- nuttx/configs/pic32mx7mmb/src/Makefile | 2 +- nuttx/configs/pjrc-8051/src/Makefile | 2 +- nuttx/configs/qemu-i486/src/Makefile | 2 +- nuttx/configs/sam3u-ek/src/Makefile | 2 +- nuttx/configs/shenzhou/src/Makefile | 2 +- nuttx/configs/sim/src/Makefile | 2 +- nuttx/configs/skp16c26/src/Makefile | 2 +- nuttx/configs/stm3210e-eval/src/Makefile | 2 +- nuttx/configs/stm3220g-eval/src/Makefile | 2 +- nuttx/configs/stm3240g-eval/src/Makefile | 2 +- nuttx/configs/stm32f100rc_generic/src/Makefile | 2 +- nuttx/configs/sure-pic32mx/src/Makefile | 2 +- nuttx/configs/teensy/src/Makefile | 2 +- nuttx/configs/twr-k60n512/src/Makefile | 2 +- nuttx/configs/ubw32/src/Makefile | 2 +- nuttx/configs/us7032evb1/src/Makefile | 2 +- nuttx/include/nuttx/power/pm.h | 6 +++--- nuttx/libc/stdio/lib_fgets.c | 2 +- 56 files changed, 58 insertions(+), 58 deletions(-) diff --git a/nuttx/Makefile.unix b/nuttx/Makefile.unix index 3b641e8b26..c88a6cc92c 100644 --- a/nuttx/Makefile.unix +++ b/nuttx/Makefile.unix @@ -447,7 +447,7 @@ check_context: # Archive targets. The target build sequency will first create a series of # libraries, one per configured source file directory. The final NuttX # execution will then be built from those libraries. The following targets -# built those libraries. +# build those libraries. # # Possible kernel-mode builds diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win index 7f96206924..4fe0b2aa1f 100644 --- a/nuttx/Makefile.win +++ b/nuttx/Makefile.win @@ -463,7 +463,7 @@ check_context: # Archive targets. The target build sequency will first create a series of # libraries, one per configured source file directory. The final NuttX # execution will then be built from those libraries. The following targets -# built those libraries. +# build those libraries. # # Possible kernel-mode builds diff --git a/nuttx/configs/amber/src/Makefile b/nuttx/configs/amber/src/Makefile index f841ede06d..49e8d5df8c 100644 --- a/nuttx/configs/amber/src/Makefile +++ b/nuttx/configs/amber/src/Makefile @@ -86,7 +86,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/avr32dev1/src/Makefile b/nuttx/configs/avr32dev1/src/Makefile index f92a05c4ed..64b2ba0998 100644 --- a/nuttx/configs/avr32dev1/src/Makefile +++ b/nuttx/configs/avr32dev1/src/Makefile @@ -79,7 +79,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/c5471evm/src/Makefile b/nuttx/configs/c5471evm/src/Makefile index 80a3da5225..2161ac11aa 100644 --- a/nuttx/configs/c5471evm/src/Makefile +++ b/nuttx/configs/c5471evm/src/Makefile @@ -66,7 +66,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/compal_e88/src/Makefile b/nuttx/configs/compal_e88/src/Makefile index 5e857da644..c2b9182c5f 100644 --- a/nuttx/configs/compal_e88/src/Makefile +++ b/nuttx/configs/compal_e88/src/Makefile @@ -69,7 +69,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/compal_e99/src/Makefile b/nuttx/configs/compal_e99/src/Makefile index 2f0ea61fd4..deeacb0bd3 100644 --- a/nuttx/configs/compal_e99/src/Makefile +++ b/nuttx/configs/compal_e99/src/Makefile @@ -69,7 +69,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/demo9s12ne64/src/Makefile b/nuttx/configs/demo9s12ne64/src/Makefile index ecc2ff2469..18dd2ac095 100644 --- a/nuttx/configs/demo9s12ne64/src/Makefile +++ b/nuttx/configs/demo9s12ne64/src/Makefile @@ -75,7 +75,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/ea3131/src/Makefile b/nuttx/configs/ea3131/src/Makefile index 06089df464..2a09631a24 100644 --- a/nuttx/configs/ea3131/src/Makefile +++ b/nuttx/configs/ea3131/src/Makefile @@ -94,7 +94,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/ea3152/src/Makefile b/nuttx/configs/ea3152/src/Makefile index 6ade0ffd38..1620a3586d 100644 --- a/nuttx/configs/ea3152/src/Makefile +++ b/nuttx/configs/ea3152/src/Makefile @@ -94,7 +94,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/eagle100/src/Makefile b/nuttx/configs/eagle100/src/Makefile index 9096f164fc..c7e9e31370 100644 --- a/nuttx/configs/eagle100/src/Makefile +++ b/nuttx/configs/eagle100/src/Makefile @@ -75,7 +75,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/ekk-lm3s9b96/src/Makefile b/nuttx/configs/ekk-lm3s9b96/src/Makefile index adabe130a4..a44b698980 100644 --- a/nuttx/configs/ekk-lm3s9b96/src/Makefile +++ b/nuttx/configs/ekk-lm3s9b96/src/Makefile @@ -77,7 +77,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/ez80f910200kitg/src/Makefile b/nuttx/configs/ez80f910200kitg/src/Makefile index e430be9ab7..61103a9312 100644 --- a/nuttx/configs/ez80f910200kitg/src/Makefile +++ b/nuttx/configs/ez80f910200kitg/src/Makefile @@ -73,7 +73,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/ez80f910200zco/src/Makefile b/nuttx/configs/ez80f910200zco/src/Makefile index 2b56c1cea1..8cf20c750a 100644 --- a/nuttx/configs/ez80f910200zco/src/Makefile +++ b/nuttx/configs/ez80f910200zco/src/Makefile @@ -80,7 +80,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/fire-stm32v2/src/Makefile b/nuttx/configs/fire-stm32v2/src/Makefile index 6492b216a6..48bb5e6c74 100644 --- a/nuttx/configs/fire-stm32v2/src/Makefile +++ b/nuttx/configs/fire-stm32v2/src/Makefile @@ -116,7 +116,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/hymini-stm32v/src/Makefile b/nuttx/configs/hymini-stm32v/src/Makefile index c57eee3384..2f8cf9992c 100644 --- a/nuttx/configs/hymini-stm32v/src/Makefile +++ b/nuttx/configs/hymini-stm32v/src/Makefile @@ -95,7 +95,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/kwikstik-k40/src/Makefile b/nuttx/configs/kwikstik-k40/src/Makefile index 7560007392..eeaec8d0f9 100644 --- a/nuttx/configs/kwikstik-k40/src/Makefile +++ b/nuttx/configs/kwikstik-k40/src/Makefile @@ -93,7 +93,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/lincoln60/src/Makefile b/nuttx/configs/lincoln60/src/Makefile index 1be1108a59..8e9fd8f04d 100644 --- a/nuttx/configs/lincoln60/src/Makefile +++ b/nuttx/configs/lincoln60/src/Makefile @@ -85,7 +85,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/lm3s6432-s2e/src/Makefile b/nuttx/configs/lm3s6432-s2e/src/Makefile index 1fe533a4ec..751fe8c91f 100644 --- a/nuttx/configs/lm3s6432-s2e/src/Makefile +++ b/nuttx/configs/lm3s6432-s2e/src/Makefile @@ -76,7 +76,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/lm3s6965-ek/src/Makefile b/nuttx/configs/lm3s6965-ek/src/Makefile index ddba1f4107..48315415ce 100644 --- a/nuttx/configs/lm3s6965-ek/src/Makefile +++ b/nuttx/configs/lm3s6965-ek/src/Makefile @@ -79,7 +79,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/lm3s8962-ek/src/Makefile b/nuttx/configs/lm3s8962-ek/src/Makefile index 07551c406b..270906b6d0 100644 --- a/nuttx/configs/lm3s8962-ek/src/Makefile +++ b/nuttx/configs/lm3s8962-ek/src/Makefile @@ -79,7 +79,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/lpc4330-xplorer/src/Makefile b/nuttx/configs/lpc4330-xplorer/src/Makefile index 75b5b76119..c0d330df4c 100644 --- a/nuttx/configs/lpc4330-xplorer/src/Makefile +++ b/nuttx/configs/lpc4330-xplorer/src/Makefile @@ -113,7 +113,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile index 522027ab6d..1e946c3dd3 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile +++ b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile @@ -85,7 +85,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/m68332evb/src/Makefile b/nuttx/configs/m68332evb/src/Makefile index dfc787419d..f152f8fd9d 100644 --- a/nuttx/configs/m68332evb/src/Makefile +++ b/nuttx/configs/m68332evb/src/Makefile @@ -63,7 +63,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/mbed/src/Makefile b/nuttx/configs/mbed/src/Makefile index d5e4412a06..a55bd36159 100644 --- a/nuttx/configs/mbed/src/Makefile +++ b/nuttx/configs/mbed/src/Makefile @@ -79,7 +79,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/mcu123-lpc214x/src/Makefile b/nuttx/configs/mcu123-lpc214x/src/Makefile index 47feeb0c5d..ee6f8a7f33 100644 --- a/nuttx/configs/mcu123-lpc214x/src/Makefile +++ b/nuttx/configs/mcu123-lpc214x/src/Makefile @@ -86,7 +86,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/micropendous3/src/Makefile b/nuttx/configs/micropendous3/src/Makefile index 66231a3b28..df5dd45f24 100644 --- a/nuttx/configs/micropendous3/src/Makefile +++ b/nuttx/configs/micropendous3/src/Makefile @@ -86,7 +86,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/mirtoo/src/Makefile b/nuttx/configs/mirtoo/src/Makefile index d560d803d9..2a92f9a33e 100644 --- a/nuttx/configs/mirtoo/src/Makefile +++ b/nuttx/configs/mirtoo/src/Makefile @@ -85,7 +85,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/mx1ads/src/Makefile b/nuttx/configs/mx1ads/src/Makefile index a264617403..1de5cbf7e2 100644 --- a/nuttx/configs/mx1ads/src/Makefile +++ b/nuttx/configs/mx1ads/src/Makefile @@ -66,7 +66,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/ne64badge/src/Makefile b/nuttx/configs/ne64badge/src/Makefile index deeca6abb8..ea80cd087c 100644 --- a/nuttx/configs/ne64badge/src/Makefile +++ b/nuttx/configs/ne64badge/src/Makefile @@ -75,7 +75,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/ntosd-dm320/src/Makefile b/nuttx/configs/ntosd-dm320/src/Makefile index 47cedfaf78..f42558a712 100644 --- a/nuttx/configs/ntosd-dm320/src/Makefile +++ b/nuttx/configs/ntosd-dm320/src/Makefile @@ -66,7 +66,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/nucleus2g/src/Makefile b/nuttx/configs/nucleus2g/src/Makefile index e6c33821ae..ad6ee69b16 100644 --- a/nuttx/configs/nucleus2g/src/Makefile +++ b/nuttx/configs/nucleus2g/src/Makefile @@ -79,7 +79,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/olimex-lpc1766stk/src/Makefile b/nuttx/configs/olimex-lpc1766stk/src/Makefile index 8ac131ffdb..a8e3920b59 100644 --- a/nuttx/configs/olimex-lpc1766stk/src/Makefile +++ b/nuttx/configs/olimex-lpc1766stk/src/Makefile @@ -93,7 +93,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/olimex-lpc2378/src/Makefile b/nuttx/configs/olimex-lpc2378/src/Makefile index 05a84cdeaf..4ab2cffa6a 100644 --- a/nuttx/configs/olimex-lpc2378/src/Makefile +++ b/nuttx/configs/olimex-lpc2378/src/Makefile @@ -82,7 +82,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/olimex-stm32-p107/src/Makefile b/nuttx/configs/olimex-stm32-p107/src/Makefile index 3fc0abe5df..f0e0fc8d63 100644 --- a/nuttx/configs/olimex-stm32-p107/src/Makefile +++ b/nuttx/configs/olimex-stm32-p107/src/Makefile @@ -78,7 +78,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/olimex-strp711/src/Makefile b/nuttx/configs/olimex-strp711/src/Makefile index 12c48d2133..efe2df4f93 100644 --- a/nuttx/configs/olimex-strp711/src/Makefile +++ b/nuttx/configs/olimex-strp711/src/Makefile @@ -79,7 +79,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/pcblogic-pic32mx/src/Makefile b/nuttx/configs/pcblogic-pic32mx/src/Makefile index 2e576b795b..175f0f1315 100644 --- a/nuttx/configs/pcblogic-pic32mx/src/Makefile +++ b/nuttx/configs/pcblogic-pic32mx/src/Makefile @@ -77,7 +77,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/pic32-starterkit/src/Makefile b/nuttx/configs/pic32-starterkit/src/Makefile index acaaa91c58..f041f9b081 100644 --- a/nuttx/configs/pic32-starterkit/src/Makefile +++ b/nuttx/configs/pic32-starterkit/src/Makefile @@ -88,7 +88,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/pic32mx7mmb/src/Makefile b/nuttx/configs/pic32mx7mmb/src/Makefile index 304989a847..ffb83cc495 100644 --- a/nuttx/configs/pic32mx7mmb/src/Makefile +++ b/nuttx/configs/pic32mx7mmb/src/Makefile @@ -92,7 +92,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/pjrc-8051/src/Makefile b/nuttx/configs/pjrc-8051/src/Makefile index fccb3ada2a..fff994b9ba 100644 --- a/nuttx/configs/pjrc-8051/src/Makefile +++ b/nuttx/configs/pjrc-8051/src/Makefile @@ -65,7 +65,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/qemu-i486/src/Makefile b/nuttx/configs/qemu-i486/src/Makefile index 06debd3e0d..d945f9ccd6 100644 --- a/nuttx/configs/qemu-i486/src/Makefile +++ b/nuttx/configs/qemu-i486/src/Makefile @@ -72,7 +72,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/sam3u-ek/src/Makefile b/nuttx/configs/sam3u-ek/src/Makefile index 18fba3eb02..08ccb2f463 100644 --- a/nuttx/configs/sam3u-ek/src/Makefile +++ b/nuttx/configs/sam3u-ek/src/Makefile @@ -85,7 +85,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile index d7ca85efcd..e3aa181e42 100644 --- a/nuttx/configs/shenzhou/src/Makefile +++ b/nuttx/configs/shenzhou/src/Makefile @@ -136,7 +136,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/sim/src/Makefile b/nuttx/configs/sim/src/Makefile index adfbb1f9a3..7c5887e720 100644 --- a/nuttx/configs/sim/src/Makefile +++ b/nuttx/configs/sim/src/Makefile @@ -72,7 +72,7 @@ endif depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/skp16c26/src/Makefile b/nuttx/configs/skp16c26/src/Makefile index 306e268063..b54b130510 100644 --- a/nuttx/configs/skp16c26/src/Makefile +++ b/nuttx/configs/skp16c26/src/Makefile @@ -66,7 +66,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/stm3210e-eval/src/Makefile b/nuttx/configs/stm3210e-eval/src/Makefile index e518366887..22ff4d40bb 100644 --- a/nuttx/configs/stm3210e-eval/src/Makefile +++ b/nuttx/configs/stm3210e-eval/src/Makefile @@ -120,7 +120,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/stm3220g-eval/src/Makefile b/nuttx/configs/stm3220g-eval/src/Makefile index a5072bdb4e..b30f111f28 100644 --- a/nuttx/configs/stm3220g-eval/src/Makefile +++ b/nuttx/configs/stm3220g-eval/src/Makefile @@ -120,7 +120,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/stm3240g-eval/src/Makefile b/nuttx/configs/stm3240g-eval/src/Makefile index 81924abcbd..a22f75e703 100644 --- a/nuttx/configs/stm3240g-eval/src/Makefile +++ b/nuttx/configs/stm3240g-eval/src/Makefile @@ -128,7 +128,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/stm32f100rc_generic/src/Makefile b/nuttx/configs/stm32f100rc_generic/src/Makefile index 57c96a57fd..f32c947d0c 100644 --- a/nuttx/configs/stm32f100rc_generic/src/Makefile +++ b/nuttx/configs/stm32f100rc_generic/src/Makefile @@ -72,7 +72,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/sure-pic32mx/src/Makefile b/nuttx/configs/sure-pic32mx/src/Makefile index dd2078ed18..dc0ee13f92 100644 --- a/nuttx/configs/sure-pic32mx/src/Makefile +++ b/nuttx/configs/sure-pic32mx/src/Makefile @@ -97,7 +97,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/teensy/src/Makefile b/nuttx/configs/teensy/src/Makefile index e1c7c029a7..705315dde6 100644 --- a/nuttx/configs/teensy/src/Makefile +++ b/nuttx/configs/teensy/src/Makefile @@ -92,7 +92,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/twr-k60n512/src/Makefile b/nuttx/configs/twr-k60n512/src/Makefile index 257e8e73f7..bb0dcd3e02 100644 --- a/nuttx/configs/twr-k60n512/src/Makefile +++ b/nuttx/configs/twr-k60n512/src/Makefile @@ -94,7 +94,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/ubw32/src/Makefile b/nuttx/configs/ubw32/src/Makefile index 608563b7e9..6cbec5db30 100644 --- a/nuttx/configs/ubw32/src/Makefile +++ b/nuttx/configs/ubw32/src/Makefile @@ -88,7 +88,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/configs/us7032evb1/src/Makefile b/nuttx/configs/us7032evb1/src/Makefile index bf457d1c5d..93a9792770 100644 --- a/nuttx/configs/us7032evb1/src/Makefile +++ b/nuttx/configs/us7032evb1/src/Makefile @@ -66,7 +66,7 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT))) + $(call DELFILE libboard$(LIBEXT)) $(call CLEAN) distclean: clean diff --git a/nuttx/include/nuttx/power/pm.h b/nuttx/include/nuttx/power/pm.h index 86e23f090e..9c0568b2dd 100644 --- a/nuttx/include/nuttx/power/pm.h +++ b/nuttx/include/nuttx/power/pm.h @@ -163,7 +163,7 @@ #endif #if CONFIG_PM_IDLEENTER_THRESH >= CONFIG_PM_IDLEEXIT_THRESH -# error "Must have CONFIG_PM_IDLEENTER_THRESH < CONFIG_PM_IDLEEXIT_THRESH +# error "Must have CONFIG_PM_IDLEENTER_THRESH < CONFIG_PM_IDLEEXIT_THRESH" #endif #ifndef CONFIG_PM_IDLEENTER_COUNT @@ -181,7 +181,7 @@ #endif #if CONFIG_PM_STANDBYENTER_THRESH >= CONFIG_PM_STANDBYEXIT_THRESH -# error "Must have CONFIG_PM_STANDBYENTER_THRESH < CONFIG_PM_STANDBYEXIT_THRESH +# error "Must have CONFIG_PM_STANDBYENTER_THRESH < CONFIG_PM_STANDBYEXIT_THRESH" #endif #ifndef CONFIG_PM_STANDBYENTER_COUNT @@ -199,7 +199,7 @@ #endif #if CONFIG_PM_SLEEPENTER_THRESH >= CONFIG_PM_SLEEPEXIT_THRESH -# error "Must have CONFIG_PM_SLEEPENTER_THRESH < CONFIG_PM_SLEEPEXIT_THRESH +# error "Must have CONFIG_PM_SLEEPENTER_THRESH < CONFIG_PM_SLEEPEXIT_THRESH" #endif #ifndef CONFIG_PM_SLEEPENTER_COUNT diff --git a/nuttx/libc/stdio/lib_fgets.c b/nuttx/libc/stdio/lib_fgets.c index c2c98a38b6..35d024ebb0 100644 --- a/nuttx/libc/stdio/lib_fgets.c +++ b/nuttx/libc/stdio/lib_fgets.c @@ -150,7 +150,7 @@ char *fgets(FAR char *buf, int buflen, FILE *stream) if (ch == '\n') #elif defined(CONFIG_EOL_IS_CR) if (ch == '\r') -#elif CONFIG_EOL_IS_EITHER_CRLF +#else /* elif CONFIG_EOL_IS_EITHER_CRLF */ if (ch == '\n' || ch == '\r') #endif { From 2754c39e6ec0fb03b74bb714ccc1374025773ff9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 20 Nov 2012 13:34:04 +0000 Subject: [PATCH 142/206] 0001-RS-485-support-for-STM32-serial-driver.patch from Freddi Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5371 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/stm32/Kconfig | 113 +++++++++++++++++++ nuttx/arch/arm/src/stm32/stm32_lowputc.c | 75 ++++++++++++- nuttx/arch/arm/src/stm32/stm32_serial.c | 132 +++++++++++++++++++++-- nuttx/arch/arm/src/stm32/stm32_uart.h | 14 +++ nuttx/configs/shenzhou/src/up_mmcsd.c | 6 ++ 5 files changed, 329 insertions(+), 11 deletions(-) diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 81ba9e4a37..68cd9003c9 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -1831,6 +1831,27 @@ config STM32_TIM14_DAC2 endchoice +menu "U[S]ART Configuration" + depends on STM32_USART1 || STM32_USART2 || STM32_USART3 || STM32_USART4 || STM32_USART5 || STM32_USART6 + +config USART1_RS485 + bool "RS-485 on USART1" + default n + depends on STM32_USART1 + ---help--- + Enable RS-485 interface on USART1. Your board config will have to + provide GPIO_USART1_RS485_DIR pin definition. Currently it cannot be + used with USART1_RXDMA. + +config USART1_RS485_DIR_POLARITY + int "USART1 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART1_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART1. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + config USART1_RXDMA bool "USART1 Rx DMA" default n @@ -1838,6 +1859,24 @@ config USART1_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors +config USART2_RS485 + bool "RS-485 on USART2" + default n + depends on STM32_USART2 + ---help--- + Enable RS-485 interface on USART2. Your board config will have to + provide GPIO_USART2_RS485_DIR pin definition. Currently it cannot be + used with USART2_RXDMA. + +config USART2_RS485_DIR_POLARITY + int "USART2 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART2_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART2. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + config USART2_RXDMA bool "USART2 Rx DMA" default n @@ -1845,6 +1884,24 @@ config USART2_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors +config USART3_RS485 + bool "RS-485 on USART3" + default n + depends on STM32_USART3 + ---help--- + Enable RS-485 interface on USART3. Your board config will have to + provide GPIO_USART3_RS485_DIR pin definition. Currently it cannot be + used with USART3_RXDMA. + +config USART3_RS485_DIR_POLARITY + int "USART3 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART3_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART3. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + config USART3_RXDMA bool "USART3 Rx DMA" default n @@ -1852,6 +1909,24 @@ config USART3_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors +config UART4_RS485 + bool "RS-485 on UART4" + default n + depends on STM32_UART4 + ---help--- + Enable RS-485 interface on UART4. Your board config will have to + provide GPIO_UART4_RS485_DIR pin definition. Currently it cannot be + used with UART4_RXDMA. + +config UART4_RS485_DIR_POLARITY + int "UART4 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on UART4_RS485 + ---help--- + Polarity of DIR pin for RS-485 on UART4. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + config UART4_RXDMA bool "UART4 Rx DMA" default n @@ -1859,6 +1934,24 @@ config UART4_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors +config UART5_RS485 + bool "RS-485 on UART5" + default n + depends on STM32_UART5 + ---help--- + Enable RS-485 interface on UART5. Your board config will have to + provide GPIO_UART5_RS485_DIR pin definition. Currently it cannot be + used with UART5_RXDMA. + +config UART5_RS485_DIR_POLARITY + int "UART5 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on UART5_RS485 + ---help--- + Polarity of DIR pin for RS-485 on UART5. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + config UART5_RXDMA bool "UART5 Rx DMA" default n @@ -1866,6 +1959,24 @@ config UART5_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors +config USART6_RS485 + bool "RS-485 on USART6" + default n + depends on STM32_USART6 + ---help--- + Enable RS-485 interface on USART6. Your board config will have to + provide GPIO_USART6_RS485_DIR pin definition. Currently it cannot be + used with USART6_RXDMA. + +config USART6_RS485_DIR_POLARITY + int "USART6 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART6_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART6. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + config USART6_RXDMA bool "USART6 Rx DMA" default n @@ -1882,6 +1993,8 @@ config SERIAL_TERMIOS If this is not defined, then the terminal settings (baud, parity, etc). are not configurable at runtime; serial streams cannot be flushed, etc.. +endmenu + menu "SPI Configuration" depends on STM32_SPI diff --git a/nuttx/arch/arm/src/stm32/stm32_lowputc.c b/nuttx/arch/arm/src/stm32/stm32_lowputc.c index 7f72056729..6cb07dad93 100644 --- a/nuttx/arch/arm/src/stm32/stm32_lowputc.c +++ b/nuttx/arch/arm/src/stm32/stm32_lowputc.c @@ -67,6 +67,14 @@ # define STM32_CONSOLE_2STOP CONFIG_USART1_2STOP # define STM32_CONSOLE_TX GPIO_USART1_TX # define STM32_CONSOLE_RX GPIO_USART1_RX +# ifdef CONFIG_USART1_RS485 +# define STM32_CONSOLE_RS485_DIR GPIO_USART1_RS485_DIR +# if (CONFIG_USART1_RS485_DIR_POLARITY == 0) +# define STM32_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif #elif defined(CONFIG_USART2_SERIAL_CONSOLE) # define STM32_CONSOLE_BASE STM32_USART2_BASE # define STM32_APBCLOCK STM32_PCLK1_FREQUENCY @@ -76,6 +84,14 @@ # define STM32_CONSOLE_2STOP CONFIG_USART2_2STOP # define STM32_CONSOLE_TX GPIO_USART2_TX # define STM32_CONSOLE_RX GPIO_USART2_RX +# ifdef CONFIG_USART2_RS485 +# define STM32_CONSOLE_RS485_DIR GPIO_USART2_RS485_DIR +# if (CONFIG_USART2_RS485_DIR_POLARITY == 0) +# define STM32_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif #elif defined(CONFIG_USART3_SERIAL_CONSOLE) # define STM32_CONSOLE_BASE STM32_USART3_BASE # define STM32_APBCLOCK STM32_PCLK1_FREQUENCY @@ -85,6 +101,14 @@ # define STM32_CONSOLE_2STOP CONFIG_USART3_2STOP # define STM32_CONSOLE_TX GPIO_USART3_TX # define STM32_CONSOLE_RX GPIO_USART3_RX +# ifdef CONFIG_USART3_RS485 +# define STM32_CONSOLE_RS485_DIR GPIO_USART3_RS485_DIR +# if (CONFIG_USART3_RS485_DIR_POLARITY == 0) +# define STM32_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif #elif defined(CONFIG_UART4_SERIAL_CONSOLE) # define STM32_CONSOLE_BASE STM32_UART4_BASE # define STM32_APBCLOCK STM32_PCLK1_FREQUENCY @@ -94,6 +118,14 @@ # define STM32_CONSOLE_2STOP CONFIG_UART4_2STOP # define STM32_CONSOLE_TX GPIO_UART4_TX # define STM32_CONSOLE_RX GPIO_UART4_RX +# ifdef CONFIG_UART4_RS485 +# define STM32_CONSOLE_RS485_DIR GPIO_UART4_RS485_DIR +# if (CONFIG_UART4_RS485_DIR_POLARITY == 0) +# define STM32_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif #elif defined(CONFIG_UART5_SERIAL_CONSOLE) # define STM32_CONSOLE_BASE STM32_UART5_BASE # define STM32_APBCLOCK STM32_PCLK1_FREQUENCY @@ -103,6 +135,14 @@ # define STM32_CONSOLE_2STOP CONFIG_UART5_2STOP # define STM32_CONSOLE_TX GPIO_UART5_TX # define STM32_CONSOLE_RX GPIO_UART5_RX +# ifdef CONFIG_UART5_RS485 +# define STM32_CONSOLE_RS485_DIR GPIO_UART5_RS485_DIR +# if (CONFIG_UART5_RS485_DIR_POLARITY == 0) +# define STM32_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif #elif defined(CONFIG_USART6_SERIAL_CONSOLE) # define STM32_CONSOLE_BASE STM32_USART6_BASE # define STM32_APBCLOCK STM32_PCLK2_FREQUENCY @@ -112,6 +152,14 @@ # define STM32_CONSOLE_2STOP CONFIG_USART6_2STOP # define STM32_CONSOLE_TX GPIO_USART6_TX # define STM32_CONSOLE_RX GPIO_USART6_RX +# ifdef CONFIG_USART6_RS485 +# define STM32_CONSOLE_RS485_DIR GPIO_USART6_RS485_DIR +# if (CONFIG_USART6_RS485_DIR_POLARITY == 0) +# define STM32_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif #endif /* CR1 settings */ @@ -230,10 +278,19 @@ void up_lowputc(char ch) /* Wait until the TX data register is empty */ while ((getreg32(STM32_CONSOLE_BASE + STM32_USART_SR_OFFSET) & USART_SR_TXE) == 0); +#if STM32_CONSOLE_RS485_DIR + stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, STM32_CONSOLE_RS485_DIR_POLARITY); +#endif /* Then send the character */ putreg32((uint32_t)ch, STM32_CONSOLE_BASE + STM32_USART_DR_OFFSET); + +#if STM32_CONSOLE_RS485_DIR + while ((getreg32(STM32_CONSOLE_BASE + STM32_USART_SR_OFFSET) & USART_SR_TC) == 0); + stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY); +#endif + #endif } @@ -328,7 +385,14 @@ void stm32_lowsetup(void) #ifdef STM32_CONSOLE_TX stm32_configgpio(STM32_CONSOLE_TX); - stm32_configgpio(STM32_CONSOLE_TX); +#endif +#ifdef STM32_CONSOLE_RX + stm32_configgpio(STM32_CONSOLE_RX); +#endif + +#if STM32_CONSOLE_RS485_DIR + stm32_configgpio(STM32_CONSOLE_RS485_DIR); + stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY); #endif /* Enable and configure the selected console device */ @@ -382,7 +446,14 @@ void stm32_lowsetup(void) #ifdef STM32_CONSOLE_TX stm32_configgpio(STM32_CONSOLE_TX); - stm32_configgpio(STM32_CONSOLE_TX); +#endif +#ifdef STM32_CONSOLE_RX + stm32_configgpio(STM32_CONSOLE_RX); +#endif + +#if STM32_CONSOLE_RS485_DIR + stm32_configgpio(STM32_CONSOLE_RS485_DIR); + stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY); #endif /* Enable and configure the selected console device */ diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c index 45d6858235..6c1861ef8c 100644 --- a/nuttx/arch/arm/src/stm32/stm32_serial.c +++ b/nuttx/arch/arm/src/stm32/stm32_serial.c @@ -96,6 +96,19 @@ # endif # endif +/* Currently RS-485 support cannot be enabled when RXDMA is in use due to lack + * of testing - RS-485 support was developed on STM32F1x + */ + +# if (defined(CONFIG_USART1_RXDMA) && defined(CONFIG_USART1_RS485)) || \ + (defined(CONFIG_USART2_RXDMA) && defined(CONFIG_USART2_RS485)) || \ + (defined(CONFIG_USART3_RXDMA) && defined(CONFIG_USART3_RS485)) || \ + (defined(CONFIG_UART4_RXDMA) && defined(CONFIG_UART4_RS485)) || \ + (defined(CONFIG_UART5_RXDMA) && defined(CONFIG_UART5_RS485)) || \ + (defined(CONFIG_USART6_RXDMA) && defined(CONFIG_USART6_RS485)) \ +# error "RXDMA and RS-485 cannot be enabled at the same time for the same U[S]ART" +# endif + /* For the F4, there are alternate DMA channels for USART1 and 6. * Logic in the board.h file make the DMA channel selection by defining * the following in the board.h file. @@ -215,6 +228,11 @@ struct up_dev_s uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */ char *const rxfifo; /* Receive DMA buffer */ #endif + +#ifdef HAVE_RS485 + const uint32_t rs485_dir_gpio; /* U[S]ART RS-485 DIR GPIO pin configuration */ + const bool rs485_dir_polarity; /* U[S]ART RS-485 DIR pin state for TX enabled */ +#endif }; /**************************************************************************** @@ -409,6 +427,15 @@ static struct up_dev_s g_usart1priv = .rxfifo = g_usart1rxfifo, #endif .vector = up_interrupt_usart1, + +#ifdef CONFIG_USART1_RS485 + .rs485_dir_gpio = GPIO_USART1_RS485_DIR, +# if (CONFIG_USART1_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif }; #endif @@ -460,6 +487,15 @@ static struct up_dev_s g_usart2priv = .rxfifo = g_usart2rxfifo, #endif .vector = up_interrupt_usart2, + +#ifdef CONFIG_USART2_RS485 + .rs485_dir_gpio = GPIO_USART2_RS485_DIR, +# if (CONFIG_USART2_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif }; #endif @@ -511,6 +547,15 @@ static struct up_dev_s g_usart3priv = .rxfifo = g_usart3rxfifo, #endif .vector = up_interrupt_usart3, + +#ifdef CONFIG_USART3_RS485 + .rs485_dir_gpio = GPIO_USART3_RS485_DIR, +# if (CONFIG_USART3_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif }; #endif @@ -562,6 +607,15 @@ static struct up_dev_s g_uart4priv = .rxfifo = g_uart4rxfifo, #endif .vector = up_interrupt_uart4, + +#ifdef CONFIG_UART4_RS485 + .rs485_dir_gpio = GPIO_UART4_RS485_DIR, +# if (CONFIG_UART4_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif }; #endif @@ -613,6 +667,15 @@ static struct up_dev_s g_uart5priv = .rxfifo = g_uart5rxfifo, #endif .vector = up_interrupt_uart5, + +#ifdef CONFIG_UART5_RS485 + .rs485_dir_gpio = GPIO_UART5_RS485_DIR, +# if (CONFIG_UART5_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif }; #endif @@ -664,6 +727,15 @@ static struct up_dev_s g_usart6priv = .rxfifo = g_usart6rxfifo, #endif .vector = up_interrupt_usart6, + +#ifdef CONFIG_USART6_RS485 + .rs485_dir_gpio = GPIO_USART6_RS485_DIR, +# if (CONFIG_USART6_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif }; #endif @@ -736,8 +808,8 @@ static void up_restoreusartint(struct up_dev_s *priv, uint16_t ie) /* And restore the interrupt state (see the interrupt enable/usage table above) */ cr = up_serialin(priv, STM32_USART_CR1_OFFSET); - cr &= ~(USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE); - cr |= (ie & (USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE)); + cr &= ~(USART_CR1_USED_INTS); + cr |= (ie & (USART_CR1_USED_INTS)); up_serialout(priv, STM32_USART_CR1_OFFSET, cr); cr = up_serialin(priv, STM32_USART_CR3_OFFSET); @@ -764,7 +836,7 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie) * USART_CR1_IDLEIE 4 USART_SR_IDLE Idle Line Detected (not used) * USART_CR1_RXNEIE 5 USART_SR_RXNE Received Data Ready to be Read * " " USART_SR_ORE Overrun Error Detected - * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used) + * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485) * USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty * USART_CR1_PEIE 8 USART_SR_PE Parity Error * @@ -783,7 +855,7 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie) * overlap. This logic would fail if we needed the break interrupt! */ - *ie = (cr1 & (USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE)) | (cr3 & USART_CR3_EIE); + *ie = (cr1 & (USART_CR1_USED_INTS)) | (cr3 & USART_CR3_EIE); } /* Disable all interrupts */ @@ -893,6 +965,14 @@ static int up_setup(struct uart_dev_s *dev) stm32_configgpio(priv->rts_gpio); } +#if HAVE_RS485 + if (priv->rs485_dir_gpio != 0) + { + stm32_configgpio(priv->rs485_dir_gpio); + stm32_gpiowrite(priv->rs485_dir_gpio, !priv->rs485_dir_polarity); + } +#endif + /* Configure CR2 */ /* Clear STOP, CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */ @@ -1174,7 +1254,7 @@ static int up_interrupt_common(struct up_dev_s *priv) * USART_CR1_IDLEIE 4 USART_SR_IDLE Idle Line Detected (not used) * USART_CR1_RXNEIE 5 USART_SR_RXNE Received Data Ready to be Read * " " USART_SR_ORE Overrun Error Detected - * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used) + * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485) * USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty * USART_CR1_PEIE 8 USART_SR_PE Parity Error * @@ -1189,6 +1269,21 @@ static int up_interrupt_common(struct up_dev_s *priv) * being used. */ +#ifdef HAVE_RS485 + /* Transmission of whole buffer is over - TC is set, TXEIE is cleared. + * Note - this should be first, to have the most recent TC bit value from + * SR register - sending data affects TC, but without refresh we will not + * know that... + */ + + if ((priv->sr & USART_SR_TC) != 0 && (priv->ie & USART_CR1_TCIE) != 0 && + (priv->ie & USART_CR1_TXEIE) == 0) + { + stm32_gpiowrite(priv->rs485_dir_gpio, !priv->rs485_dir_polarity); + up_restoreusartint(priv, priv->ie & ~USART_CR1_TCIE); + } +#endif + /* Handle incoming, receive bytes. */ if ((priv->sr & USART_SR_RXNE) != 0 && (priv->ie & USART_CR1_RXNEIE) != 0) @@ -1222,13 +1317,14 @@ static int up_interrupt_common(struct up_dev_s *priv) if ((priv->sr & USART_SR_TXE) != 0 && (priv->ie & USART_CR1_TXEIE) != 0) { - /* Transmit data regiser empty ... process outgoing bytes */ + /* Transmit data register empty ... process outgoing bytes */ uart_xmitchars(&priv->dev); handled = true; } } - return OK; + + return OK; } /**************************************************************************** @@ -1527,6 +1623,10 @@ static bool up_dma_rxavailable(struct uart_dev_s *dev) static void up_send(struct uart_dev_s *dev, int ch) { struct up_dev_s *priv = (struct up_dev_s*)dev->priv; +#ifdef HAVE_RS485 + if (priv->rs485_dir_gpio != 0) + stm32_gpiowrite(priv->rs485_dir_gpio, priv->rs485_dir_polarity); +#endif up_serialout(priv, STM32_USART_DR_OFFSET, (uint32_t)ch); } @@ -1547,7 +1647,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable) * * Enable Bit Status Meaning Usage * ------------------ --- --------------- ---------------------------- ---------- - * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used) + * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485) * USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty * USART_CR3_CTSIE 10 USART_SR_CTS CTS flag (not used) */ @@ -1558,7 +1658,20 @@ static void up_txint(struct uart_dev_s *dev, bool enable) /* Set to receive an interrupt when the TX data register is empty */ #ifndef CONFIG_SUPPRESS_SERIAL_INTS - up_restoreusartint(priv, priv->ie | USART_CR1_TXEIE); + uint16_t ie = priv->ie | USART_CR1_TXEIE; + + /* If RS-485 is supported on this U[S]ART, then also enable the + * transmission complete interrupt. + */ + +# ifdef HAVE_RS485 + if (priv->rs485_dir_gpio != 0) + { + ie |= USART_CR1_TCIE; + } +# endif + + up_restoreusartint(priv, ie); /* Fake a TX interrupt here by just calling uart_xmitchars() with * interrupts disabled (note this may recurse). @@ -1573,6 +1686,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable) up_restoreusartint(priv, priv->ie & ~USART_CR1_TXEIE); } + irqrestore(flags); } diff --git a/nuttx/arch/arm/src/stm32/stm32_uart.h b/nuttx/arch/arm/src/stm32/stm32_uart.h index a70923cbf9..8ff6a9975f 100644 --- a/nuttx/arch/arm/src/stm32/stm32_uart.h +++ b/nuttx/arch/arm/src/stm32/stm32_uart.h @@ -223,6 +223,20 @@ # undef SERIAL_HAVE_ONLY_DMA #endif +/* Is RS-485 used? */ + +#if defined(CONFIG_USART1_RS485) || defined(CONFIG_USART2_RS485) || \ + defined(CONFIG_USART3_RS485) || defined(CONFIG_UART4_RS485) || \ + defined(CONFIG_UART5_RS485) || defined(CONFIG_USART6_RS485) +# define HAVE_RS485 1 +#endif + +#ifdef HAVE_RS485 +# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE | USART_CR1_TCIE) +#else +# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE) +#endif + /************************************************************************************ * Public Types ************************************************************************************/ diff --git a/nuttx/configs/shenzhou/src/up_mmcsd.c b/nuttx/configs/shenzhou/src/up_mmcsd.c index 531fbfd7e3..adf695cd5e 100644 --- a/nuttx/configs/shenzhou/src/up_mmcsd.c +++ b/nuttx/configs/shenzhou/src/up_mmcsd.c @@ -65,6 +65,12 @@ # endif #endif +/* Can't support MMC/SD features if MMC/SD driver support is not selected */ + +#ifndef CONFIG_MMCSD +# undef HAVE_MMCSD +#endif + /* Can't support MMC/SD features if mountpoints are disabled */ #ifdef CONFIG_DISABLE_MOUNTPOINT From 6833671f0c73c1b3d4eda7251e64410e421600c4 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 20 Nov 2012 13:36:07 +0000 Subject: [PATCH 143/206] 0001-some-fixes-for-FreeMODBUS-and-MODBUS-example.patch from Freddi Chopin git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5372 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/modbus/modbus_main.c | 4 +++- apps/modbus/mb.c | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/apps/examples/modbus/modbus_main.c b/apps/examples/modbus/modbus_main.c index 13967f6fd0..2247fd6756 100644 --- a/apps/examples/modbus/modbus_main.c +++ b/apps/examples/modbus/modbus_main.c @@ -217,7 +217,7 @@ static inline int modbus_initialize(void) /* Enable FreeModBus */ mberr = eMBEnable(); - if (mberr == MB_ENOERR) + if (mberr != MB_ENOERR) { fprintf(stderr, "modbus_main: " "ERROR: eMBEnable failed: %d\n", mberr); @@ -267,6 +267,8 @@ static void *modbus_pollthread(void *pvarg) return NULL; } + srand(time(NULL)); + /* Then loop until we are commanded to shutdown */ do diff --git a/apps/modbus/mb.c b/apps/modbus/mb.c index 8417d12749..54e96460d5 100644 --- a/apps/modbus/mb.c +++ b/apps/modbus/mb.c @@ -99,7 +99,7 @@ static xMBFunctionHandler xFuncHandlers[CONFIG_MB_FUNC_HANDLERS_MAX] = { #ifdef CONFIG_MB_FUNC_OTHER_REP_SLAVEID_ENABLED {MB_FUNC_OTHER_REPORT_SLAVEID, eMBFuncReportSlaveID}, #endif -#ifdef CONFIG_MB_FUNC_READ_INPUT_ENABLE +#ifdef CONFIG_MB_FUNC_READ_INPUT_ENABLED {MB_FUNC_READ_INPUT_REGISTER, eMBFuncReadInputRegister}, #endif #ifdef CONFIG_MB_FUNC_READ_HOLDING_ENABLED From f552862bb546891ecc51cda2fe662c630ff019cb Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 20 Nov 2012 15:47:41 +0000 Subject: [PATCH 144/206] Missing comma in EVERY DELFILE/DELDIR macro call in every Makefile git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5373 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/UnitTests/CButton/Makefile | 6 +-- NxWidgets/UnitTests/CButtonArray/Makefile | 6 +-- NxWidgets/UnitTests/CCheckBox/Makefile | 6 +-- NxWidgets/UnitTests/CGlyphButton/Makefile | 6 +-- NxWidgets/UnitTests/CImage/Makefile | 6 +-- NxWidgets/UnitTests/CKeypad/Makefile | 6 +-- NxWidgets/UnitTests/CLabel/Makefile | 6 +-- NxWidgets/UnitTests/CLatchButton/Makefile | 6 +-- .../UnitTests/CLatchButtonArray/Makefile | 6 +-- NxWidgets/UnitTests/CListBox/Makefile | 6 +-- NxWidgets/UnitTests/CProgressBar/Makefile | 6 +-- NxWidgets/UnitTests/CRadioButton/Makefile | 6 +-- .../UnitTests/CScrollbarHorizontal/Makefile | 6 +-- .../UnitTests/CScrollbarVertical/Makefile | 6 +-- NxWidgets/UnitTests/CSliderHorizonal/Makefile | 6 +-- NxWidgets/UnitTests/CSliderVertical/Makefile | 6 +-- NxWidgets/UnitTests/CTextBox/Makefile | 6 +-- NxWidgets/UnitTests/nxwm/Makefile | 6 +-- NxWidgets/libnxwidgets/Makefile | 6 +-- NxWidgets/nxwm/Makefile | 6 +-- apps/Makefile | 14 +++--- apps/examples/adc/Makefile | 6 +-- apps/examples/buttons/Makefile | 6 +-- apps/examples/can/Makefile | 6 +-- apps/examples/cdcacm/Makefile | 6 +-- apps/examples/composite/Makefile | 6 +-- apps/examples/cxxtest/Makefile | 6 +-- apps/examples/dhcpd/Makefile | 6 +-- apps/examples/discover/Makefile | 6 +-- apps/examples/elf/Makefile | 6 +-- apps/examples/elf/tests/errno/Makefile | 2 +- apps/examples/elf/tests/hello/Makefile | 2 +- apps/examples/elf/tests/helloxx/Makefile | 8 ++-- apps/examples/elf/tests/longjmp/Makefile | 2 +- apps/examples/elf/tests/mutex/Makefile | 2 +- apps/examples/elf/tests/pthread/Makefile | 2 +- apps/examples/elf/tests/signal/Makefile | 2 +- apps/examples/elf/tests/struct/Makefile | 2 +- apps/examples/elf/tests/task/Makefile | 2 +- apps/examples/ftpc/Makefile | 8 ++-- apps/examples/ftpd/Makefile | 6 +-- apps/examples/hello/Makefile | 6 +-- apps/examples/helloxx/Makefile | 6 +-- apps/examples/hidkbd/Makefile | 6 +-- apps/examples/igmp/Makefile | 6 +-- apps/examples/json/Makefile | 6 +-- apps/examples/lcdrw/Makefile | 6 +-- apps/examples/mm/Makefile | 6 +-- apps/examples/modbus/Makefile | 6 +-- apps/examples/mount/Makefile | 6 +-- apps/examples/nettest/Makefile | 8 ++-- apps/examples/nsh/Makefile | 6 +-- apps/examples/null/Makefile | 6 +-- apps/examples/nx/Makefile | 6 +-- apps/examples/nxconsole/Makefile | 6 +-- apps/examples/nxffs/Makefile | 6 +-- apps/examples/nxflat/Makefile | 6 +-- apps/examples/nxflat/tests/errno/Makefile | 8 ++-- apps/examples/nxflat/tests/hello++/Makefile | 20 ++++----- apps/examples/nxflat/tests/hello/Makefile | 8 ++-- apps/examples/nxflat/tests/longjmp/Makefile | 8 ++-- apps/examples/nxflat/tests/mutex/Makefile | 8 ++-- apps/examples/nxflat/tests/pthread/Makefile | 8 ++-- apps/examples/nxflat/tests/signal/Makefile | 8 ++-- apps/examples/nxflat/tests/struct/Makefile | 8 ++-- apps/examples/nxflat/tests/task/Makefile | 8 ++-- apps/examples/nxhello/Makefile | 6 +-- apps/examples/nximage/Makefile | 6 +-- apps/examples/nxlines/Makefile | 6 +-- apps/examples/nxtext/Makefile | 6 +-- apps/examples/ostest/Makefile | 6 +-- apps/examples/pashello/Makefile | 6 +-- apps/examples/pipe/Makefile | 6 +-- apps/examples/poll/Makefile | 8 ++-- apps/examples/pwm/Makefile | 6 +-- apps/examples/qencoder/Makefile | 6 +-- apps/examples/relays/Makefile | 6 +-- apps/examples/rgmp/Makefile | 6 +-- apps/examples/romfs/Makefile | 8 ++-- apps/examples/sendmail/Makefile | 6 +-- apps/examples/sendmail/Makefile.host | 4 +- apps/examples/serloop/Makefile | 6 +-- apps/examples/telnetd/Makefile | 6 +-- apps/examples/thttpd/Makefile | 6 +-- apps/examples/thttpd/content/Makefile | 4 +- apps/examples/thttpd/content/hello/Makefile | 8 ++-- apps/examples/thttpd/content/netstat/Makefile | 8 ++-- apps/examples/thttpd/content/tasks/Makefile | 8 ++-- apps/examples/tiff/Makefile | 12 ++--- apps/examples/touchscreen/Makefile | 6 +-- apps/examples/udp/Makefile | 10 ++--- apps/examples/uip/Makefile | 8 ++-- apps/examples/usbserial/Makefile | 6 +-- apps/examples/usbserial/Makefile.host | 2 +- apps/examples/usbstorage/Makefile | 6 +-- apps/examples/usbterm/Makefile | 6 +-- apps/examples/watchdog/Makefile | 6 +-- apps/examples/wget/Makefile | 6 +-- apps/examples/wget/Makefile.host | 4 +- apps/examples/wgetjson/Makefile | 6 +-- apps/examples/wlan/Makefile | 6 +-- apps/examples/xmlrpc/Makefile | 6 +-- apps/graphics/tiff/Makefile | 8 ++-- apps/interpreters/ficl/Makefile | 8 ++-- apps/modbus/Makefile | 8 ++-- apps/namedapp/Makefile | 12 ++--- apps/netutils/codecs/Makefile | 6 +-- apps/netutils/dhcpc/Makefile | 6 +-- apps/netutils/dhcpd/Makefile | 6 +-- apps/netutils/discover/Makefile | 6 +-- apps/netutils/ftpc/Makefile | 6 +-- apps/netutils/ftpd/Makefile | 6 +-- apps/netutils/json/Makefile | 6 +-- apps/netutils/resolv/Makefile | 6 +-- apps/netutils/smtp/Makefile | 6 +-- apps/netutils/telnetd/Makefile | 6 +-- apps/netutils/tftpc/Makefile | 6 +-- apps/netutils/thttpd/Makefile | 6 +-- apps/netutils/uiplib/Makefile | 6 +-- apps/netutils/webclient/Makefile | 6 +-- apps/netutils/webserver/Makefile | 6 +-- apps/netutils/xmlrpc/Makefile | 6 +-- apps/nshlib/Makefile | 8 ++-- apps/system/free/Makefile | 8 ++-- apps/system/i2c/Makefile | 8 ++-- apps/system/install/Makefile | 8 ++-- apps/system/poweroff/Makefile | 8 ++-- apps/system/ramtron/Makefile | 8 ++-- apps/system/readline/Makefile | 8 ++-- apps/system/sdcard/Makefile | 8 ++-- apps/system/sysinfo/Makefile | 8 ++-- misc/pascal/nuttx/Makefile | 6 +-- nuttx/Makefile.unix | 30 ++++++------- nuttx/Makefile.win | 44 +++++++++---------- nuttx/arch/8051/src/Makefile | 8 ++-- nuttx/arch/arm/src/Makefile | 6 +-- nuttx/arch/avr/src/Makefile | 6 +-- nuttx/arch/hc/src/Makefile | 6 +-- nuttx/arch/mips/src/Makefile | 6 +-- nuttx/arch/rgmp/src/Makefile | 12 ++--- nuttx/arch/sh/src/Makefile | 6 +-- nuttx/arch/sim/src/Makefile | 8 ++-- nuttx/arch/x86/src/Makefile | 6 +-- nuttx/arch/z16/src/Makefile | 14 +++--- nuttx/arch/z80/src/Makefile.sdcc | 14 +++--- nuttx/arch/z80/src/Makefile.zdsii | 14 +++--- nuttx/binfmt/Makefile | 6 +-- nuttx/configs/amber/src/Makefile | 6 +-- nuttx/configs/avr32dev1/src/Makefile | 6 +-- nuttx/configs/c5471evm/src/Makefile | 6 +-- nuttx/configs/compal_e88/src/Makefile | 6 +-- nuttx/configs/compal_e99/src/Makefile | 6 +-- nuttx/configs/demo9s12ne64/src/Makefile | 6 +-- nuttx/configs/ea3131/locked/Makefile | 6 +-- nuttx/configs/ea3131/src/Makefile | 6 +-- nuttx/configs/ea3152/src/Makefile | 6 +-- nuttx/configs/eagle100/src/Makefile | 6 +-- nuttx/configs/ekk-lm3s9b96/src/Makefile | 6 +-- nuttx/configs/ez80f910200kitg/src/Makefile | 6 +-- nuttx/configs/ez80f910200zco/src/Makefile | 6 +-- nuttx/configs/fire-stm32v2/src/Makefile | 6 +-- nuttx/configs/hymini-stm32v/src/Makefile | 6 +-- nuttx/configs/kwikstik-k40/src/Makefile | 6 +-- nuttx/configs/lincoln60/src/Makefile | 6 +-- nuttx/configs/lm3s6432-s2e/src/Makefile | 6 +-- nuttx/configs/lm3s6965-ek/src/Makefile | 6 +-- nuttx/configs/lm3s8962-ek/src/Makefile | 6 +-- nuttx/configs/lpc4330-xplorer/src/Makefile | 6 +-- nuttx/configs/lpcxpresso-lpc1768/src/Makefile | 6 +-- nuttx/configs/m68332evb/src/Makefile | 6 +-- nuttx/configs/mbed/src/Makefile | 6 +-- nuttx/configs/mcu123-lpc214x/src/Makefile | 6 +-- nuttx/configs/micropendous3/src/Makefile | 6 +-- nuttx/configs/mirtoo/src/Makefile | 6 +-- nuttx/configs/mx1ads/src/Makefile | 6 +-- nuttx/configs/ne64badge/src/Makefile | 6 +-- nuttx/configs/ntosd-dm320/src/Makefile | 6 +-- nuttx/configs/nucleus2g/src/Makefile | 6 +-- nuttx/configs/olimex-lpc1766stk/src/Makefile | 6 +-- nuttx/configs/olimex-lpc2378/src/Makefile | 6 +-- nuttx/configs/olimex-stm32-p107/src/Makefile | 6 +-- nuttx/configs/olimex-strp711/src/Makefile | 6 +-- nuttx/configs/pcblogic-pic32mx/src/Makefile | 6 +-- nuttx/configs/pic32-starterkit/src/Makefile | 6 +-- nuttx/configs/pic32mx7mmb/src/Makefile | 6 +-- nuttx/configs/pjrc-8051/src/Makefile | 6 +-- nuttx/configs/qemu-i486/src/Makefile | 6 +-- nuttx/configs/sam3u-ek/kernel/Makefile | 6 +-- nuttx/configs/sam3u-ek/src/Makefile | 6 +-- nuttx/configs/shenzhou/src/Makefile | 6 +-- nuttx/configs/sim/src/Makefile | 6 +-- nuttx/configs/skp16c26/src/Makefile | 6 +-- nuttx/configs/stm3210e-eval/src/Makefile | 6 +-- nuttx/configs/stm3220g-eval/src/Makefile | 6 +-- nuttx/configs/stm3240g-eval/src/Makefile | 6 +-- .../configs/stm32f100rc_generic/src/Makefile | 6 +-- nuttx/configs/stm32f4discovery/src/Makefile | 6 +-- nuttx/configs/sure-pic32mx/src/Makefile | 6 +-- nuttx/configs/teensy/src/Makefile | 6 +-- nuttx/configs/twr-k60n512/src/Makefile | 6 +-- nuttx/configs/ubw32/src/Makefile | 6 +-- nuttx/configs/us7032evb1/shterm/Makefile | 2 +- nuttx/configs/us7032evb1/src/Makefile | 6 +-- nuttx/configs/vsn/src/Makefile | 6 +-- nuttx/configs/xtrs/src/Makefile | 6 +-- nuttx/configs/z16f2800100zcog/src/Makefile | 6 +-- nuttx/configs/z80sim/src/Makefile | 6 +-- nuttx/configs/z8encore000zco/src/Makefile | 6 +-- nuttx/configs/z8f64200100kit/src/Makefile | 6 +-- nuttx/drivers/Makefile | 6 +-- nuttx/fs/Makefile | 6 +-- nuttx/graphics/Makefile | 6 +-- nuttx/graphics/nxfonts/Makefile.sources | 6 +-- nuttx/graphics/nxglib/Makefile.sources | 14 +++--- nuttx/libc/Makefile | 14 +++--- nuttx/libxx/Makefile | 6 +-- nuttx/mm/Makefile | 6 +-- nuttx/mm/Makefile.test | 4 +- nuttx/net/Makefile | 6 +-- nuttx/sched/Makefile | 6 +-- nuttx/syscall/Makefile | 18 ++++---- nuttx/tools/Makefile.host | 22 +++++----- 222 files changed, 760 insertions(+), 760 deletions(-) diff --git a/NxWidgets/UnitTests/CButton/Makefile b/NxWidgets/UnitTests/CButton/Makefile index 778d465132..d80ef3c760 100644 --- a/NxWidgets/UnitTests/CButton/Makefile +++ b/NxWidgets/UnitTests/CButton/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CButtonArray/Makefile b/NxWidgets/UnitTests/CButtonArray/Makefile index 39af8ff3a2..b4a3b0571d 100644 --- a/NxWidgets/UnitTests/CButtonArray/Makefile +++ b/NxWidgets/UnitTests/CButtonArray/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CCheckBox/Makefile b/NxWidgets/UnitTests/CCheckBox/Makefile index 5838178572..21e007b3d8 100644 --- a/NxWidgets/UnitTests/CCheckBox/Makefile +++ b/NxWidgets/UnitTests/CCheckBox/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CGlyphButton/Makefile b/NxWidgets/UnitTests/CGlyphButton/Makefile index e61f960d14..1e7faf0262 100644 --- a/NxWidgets/UnitTests/CGlyphButton/Makefile +++ b/NxWidgets/UnitTests/CGlyphButton/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CImage/Makefile b/NxWidgets/UnitTests/CImage/Makefile index 88e7865051..61978147e2 100644 --- a/NxWidgets/UnitTests/CImage/Makefile +++ b/NxWidgets/UnitTests/CImage/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CKeypad/Makefile b/NxWidgets/UnitTests/CKeypad/Makefile index 873b7a6951..d27b90192e 100644 --- a/NxWidgets/UnitTests/CKeypad/Makefile +++ b/NxWidgets/UnitTests/CKeypad/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CLabel/Makefile b/NxWidgets/UnitTests/CLabel/Makefile index 5122558ff2..14e8897d22 100644 --- a/NxWidgets/UnitTests/CLabel/Makefile +++ b/NxWidgets/UnitTests/CLabel/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CLatchButton/Makefile b/NxWidgets/UnitTests/CLatchButton/Makefile index d38872079f..435a4c3cdd 100644 --- a/NxWidgets/UnitTests/CLatchButton/Makefile +++ b/NxWidgets/UnitTests/CLatchButton/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CLatchButtonArray/Makefile b/NxWidgets/UnitTests/CLatchButtonArray/Makefile index 94a2bc49ef..0f6fe639f6 100644 --- a/NxWidgets/UnitTests/CLatchButtonArray/Makefile +++ b/NxWidgets/UnitTests/CLatchButtonArray/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CListBox/Makefile b/NxWidgets/UnitTests/CListBox/Makefile index ca90558707..301424c479 100644 --- a/NxWidgets/UnitTests/CListBox/Makefile +++ b/NxWidgets/UnitTests/CListBox/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CProgressBar/Makefile b/NxWidgets/UnitTests/CProgressBar/Makefile index b9c498df9b..d50d3ed055 100644 --- a/NxWidgets/UnitTests/CProgressBar/Makefile +++ b/NxWidgets/UnitTests/CProgressBar/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CRadioButton/Makefile b/NxWidgets/UnitTests/CRadioButton/Makefile index 0a96580e0f..ff6c2d2472 100644 --- a/NxWidgets/UnitTests/CRadioButton/Makefile +++ b/NxWidgets/UnitTests/CRadioButton/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile b/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile index 0fe12318b0..a5fab0dda8 100644 --- a/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile +++ b/NxWidgets/UnitTests/CScrollbarHorizontal/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CScrollbarVertical/Makefile b/NxWidgets/UnitTests/CScrollbarVertical/Makefile index 60fb0b5451..204b90a52c 100644 --- a/NxWidgets/UnitTests/CScrollbarVertical/Makefile +++ b/NxWidgets/UnitTests/CScrollbarVertical/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CSliderHorizonal/Makefile b/NxWidgets/UnitTests/CSliderHorizonal/Makefile index 5675c55bf4..67f00f6220 100644 --- a/NxWidgets/UnitTests/CSliderHorizonal/Makefile +++ b/NxWidgets/UnitTests/CSliderHorizonal/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CSliderVertical/Makefile b/NxWidgets/UnitTests/CSliderVertical/Makefile index 78dc6dc8d2..409f361fd1 100644 --- a/NxWidgets/UnitTests/CSliderVertical/Makefile +++ b/NxWidgets/UnitTests/CSliderVertical/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/CTextBox/Makefile b/NxWidgets/UnitTests/CTextBox/Makefile index c913b50a4c..a4c752e6c0 100644 --- a/NxWidgets/UnitTests/CTextBox/Makefile +++ b/NxWidgets/UnitTests/CTextBox/Makefile @@ -159,11 +159,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/UnitTests/nxwm/Makefile b/NxWidgets/UnitTests/nxwm/Makefile index 205caf8794..338b83e548 100644 --- a/NxWidgets/UnitTests/nxwm/Makefile +++ b/NxWidgets/UnitTests/nxwm/Makefile @@ -189,11 +189,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/NxWidgets/libnxwidgets/Makefile b/NxWidgets/libnxwidgets/Makefile index 27a85b428b..0c7c922eab 100644 --- a/NxWidgets/libnxwidgets/Makefile +++ b/NxWidgets/libnxwidgets/Makefile @@ -132,12 +132,12 @@ $(BIN): $(OBJS) depend: .depend clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) export: $(BIN) zip -r nxwidgets-export.zip include $(BIN) COPYING diff --git a/NxWidgets/nxwm/Makefile b/NxWidgets/nxwm/Makefile index b176ce4f7c..0bea357b2e 100644 --- a/NxWidgets/nxwm/Makefile +++ b/NxWidgets/nxwm/Makefile @@ -136,12 +136,12 @@ $(BIN): $(OBJS) depend: .depend clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) export: $(BIN) zip -r nxwm-export.zip include $(BIN) COPYING diff --git a/apps/Makefile b/apps/Makefile index 522731722d..353894b7f8 100644 --- a/apps/Makefile +++ b/apps/Makefile @@ -174,7 +174,7 @@ else $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ done endif - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: # clean @@ -182,9 +182,9 @@ ifeq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) for %%G in ($(SUBDIRS)) do ( \ $(MAKE) -C %%G distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" \ ) - $(call DELFILE .config) - $(call DELFILE .context) - $(call DELFILE .depend) + $(call DELFILE, .config) + $(call DELFILE, .context) + $(call DELFILE, .depend) $(Q) ( if exist external ( \ echo ********************************************************" \ echo * The external directory/link must be removed manually *" \ @@ -194,9 +194,9 @@ else $(Q) for dir in $(SUBDIRS) ; do \ $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ done - $(call DELFILE .config) - $(call DELFILE .context) - $(call DELFILE .depend) + $(call DELFILE, .config) + $(call DELFILE, .context) + $(call DELFILE, .depend) $(Q) ( if [ -e external ]; then \ echo "********************************************************"; \ echo "* The external directory/link must be removed manually *"; \ diff --git a/apps/examples/adc/Makefile b/apps/examples/adc/Makefile index e9f3980b13..69862b383d 100644 --- a/apps/examples/adc/Makefile +++ b/apps/examples/adc/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/buttons/Makefile b/apps/examples/buttons/Makefile index 01d0719a91..77c1cd67df 100644 --- a/apps/examples/buttons/Makefile +++ b/apps/examples/buttons/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/can/Makefile b/apps/examples/can/Makefile index 824cea3603..8924797e37 100644 --- a/apps/examples/can/Makefile +++ b/apps/examples/can/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/cdcacm/Makefile b/apps/examples/cdcacm/Makefile index 336f572442..e8d03807d8 100644 --- a/apps/examples/cdcacm/Makefile +++ b/apps/examples/cdcacm/Makefile @@ -101,12 +101,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/composite/Makefile b/apps/examples/composite/Makefile index da528b54bf..016ccbe3eb 100644 --- a/apps/examples/composite/Makefile +++ b/apps/examples/composite/Makefile @@ -103,12 +103,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/cxxtest/Makefile b/apps/examples/cxxtest/Makefile index f1ab33744c..f0764b6e94 100644 --- a/apps/examples/cxxtest/Makefile +++ b/apps/examples/cxxtest/Makefile @@ -115,11 +115,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/dhcpd/Makefile b/apps/examples/dhcpd/Makefile index 34575f802d..a41db5cdd7 100644 --- a/apps/examples/dhcpd/Makefile +++ b/apps/examples/dhcpd/Makefile @@ -98,12 +98,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/discover/Makefile b/apps/examples/discover/Makefile index 6fa70d0929..2ce52a18e9 100644 --- a/apps/examples/discover/Makefile +++ b/apps/examples/discover/Makefile @@ -99,11 +99,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/elf/Makefile b/apps/examples/elf/Makefile index ee34130316..1467bf0080 100644 --- a/apps/examples/elf/Makefile +++ b/apps/examples/elf/Makefile @@ -100,11 +100,11 @@ clean_tests: @$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) clean clean: clean_tests - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/elf/tests/errno/Makefile b/apps/examples/elf/tests/errno/Makefile index 08bffc7dd5..ca2f34bf91 100644 --- a/apps/examples/elf/tests/errno/Makefile +++ b/apps/examples/elf/tests/errno/Makefile @@ -51,7 +51,7 @@ $(BIN): $(OBJS) $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) install: diff --git a/apps/examples/elf/tests/hello/Makefile b/apps/examples/elf/tests/hello/Makefile index d4af19e02c..5cd80411b0 100644 --- a/apps/examples/elf/tests/hello/Makefile +++ b/apps/examples/elf/tests/hello/Makefile @@ -51,7 +51,7 @@ $(BIN): $(OBJS) $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) install: diff --git a/apps/examples/elf/tests/helloxx/Makefile b/apps/examples/elf/tests/helloxx/Makefile index e1c9cfc5be..cce33d843f 100644 --- a/apps/examples/elf/tests/helloxx/Makefile +++ b/apps/examples/elf/tests/helloxx/Makefile @@ -105,10 +105,10 @@ endif # $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN1)) - $(call DELFILE $(BIN2)) - $(call DELFILE $(BIN3)) - $(call DELFILE $(BIN4)) + $(call DELFILE, $(BIN1)) + $(call DELFILE, $(BIN2)) + $(call DELFILE, $(BIN3)) + $(call DELFILE, $(BIN4)) $(call CLEAN) install: $(ALL_BIN) diff --git a/apps/examples/elf/tests/longjmp/Makefile b/apps/examples/elf/tests/longjmp/Makefile index e7a54fc002..6ddbf9b8d0 100644 --- a/apps/examples/elf/tests/longjmp/Makefile +++ b/apps/examples/elf/tests/longjmp/Makefile @@ -51,7 +51,7 @@ $(BIN): $(OBJS) $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) install: diff --git a/apps/examples/elf/tests/mutex/Makefile b/apps/examples/elf/tests/mutex/Makefile index 958c0c38e6..04c1e8975e 100644 --- a/apps/examples/elf/tests/mutex/Makefile +++ b/apps/examples/elf/tests/mutex/Makefile @@ -51,7 +51,7 @@ $(BIN): $(OBJS) $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) install: diff --git a/apps/examples/elf/tests/pthread/Makefile b/apps/examples/elf/tests/pthread/Makefile index a491b98741..05c7c46502 100644 --- a/apps/examples/elf/tests/pthread/Makefile +++ b/apps/examples/elf/tests/pthread/Makefile @@ -51,7 +51,7 @@ $(BIN): $(OBJS) $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) install: diff --git a/apps/examples/elf/tests/signal/Makefile b/apps/examples/elf/tests/signal/Makefile index 227f995211..55ef2e5b98 100644 --- a/apps/examples/elf/tests/signal/Makefile +++ b/apps/examples/elf/tests/signal/Makefile @@ -51,7 +51,7 @@ $(BIN): $(OBJS) $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) install: diff --git a/apps/examples/elf/tests/struct/Makefile b/apps/examples/elf/tests/struct/Makefile index 3224c655e7..369fcb368d 100644 --- a/apps/examples/elf/tests/struct/Makefile +++ b/apps/examples/elf/tests/struct/Makefile @@ -52,7 +52,7 @@ $(BIN): $(OBJS) $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) install: diff --git a/apps/examples/elf/tests/task/Makefile b/apps/examples/elf/tests/task/Makefile index cf56b1287f..c30fa8076b 100644 --- a/apps/examples/elf/tests/task/Makefile +++ b/apps/examples/elf/tests/task/Makefile @@ -51,7 +51,7 @@ $(BIN): $(OBJS) $(Q) $(LD) $(LDELFFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) install: diff --git a/apps/examples/ftpc/Makefile b/apps/examples/ftpc/Makefile index 3cdc93060c..29960fb94c 100644 --- a/apps/examples/ftpc/Makefile +++ b/apps/examples/ftpc/Makefile @@ -98,12 +98,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/ftpd/Makefile b/apps/examples/ftpd/Makefile index 071784b8e2..0b43b85a9c 100644 --- a/apps/examples/ftpd/Makefile +++ b/apps/examples/ftpd/Makefile @@ -94,11 +94,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/hello/Makefile b/apps/examples/hello/Makefile index b35b97eb0d..560b0da358 100644 --- a/apps/examples/hello/Makefile +++ b/apps/examples/hello/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/helloxx/Makefile b/apps/examples/helloxx/Makefile index 739f262526..062da7d588 100644 --- a/apps/examples/helloxx/Makefile +++ b/apps/examples/helloxx/Makefile @@ -115,11 +115,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/hidkbd/Makefile b/apps/examples/hidkbd/Makefile index 0dbfbdb778..7663250c7b 100644 --- a/apps/examples/hidkbd/Makefile +++ b/apps/examples/hidkbd/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/igmp/Makefile b/apps/examples/igmp/Makefile index a94a97cf73..3715e1d34c 100644 --- a/apps/examples/igmp/Makefile +++ b/apps/examples/igmp/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/json/Makefile b/apps/examples/json/Makefile index bdd93fd178..c3e9203f93 100644 --- a/apps/examples/json/Makefile +++ b/apps/examples/json/Makefile @@ -96,11 +96,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/lcdrw/Makefile b/apps/examples/lcdrw/Makefile index bbe46025dd..ed612e0bec 100644 --- a/apps/examples/lcdrw/Makefile +++ b/apps/examples/lcdrw/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/mm/Makefile b/apps/examples/mm/Makefile index bb14a2e4ef..5ba7f4eec9 100644 --- a/apps/examples/mm/Makefile +++ b/apps/examples/mm/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/modbus/Makefile b/apps/examples/modbus/Makefile index f6e964f51f..d6caefe81d 100644 --- a/apps/examples/modbus/Makefile +++ b/apps/examples/modbus/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/mount/Makefile b/apps/examples/mount/Makefile index becc6670b8..133bdfa1f5 100644 --- a/apps/examples/mount/Makefile +++ b/apps/examples/mount/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/nettest/Makefile b/apps/examples/nettest/Makefile index 76ad94d6fb..085b9406d8 100644 --- a/apps/examples/nettest/Makefile +++ b/apps/examples/nettest/Makefile @@ -131,13 +131,13 @@ context: .context depend: .depend clean: - $(call DELFILE $(HOST_BIN)) - $(call DELFILE .built) + $(call DELFILE, $(HOST_BIN)) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/nsh/Makefile b/apps/examples/nsh/Makefile index 0c0ebe8b9f..c7d212fc2c 100644 --- a/apps/examples/nsh/Makefile +++ b/apps/examples/nsh/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/null/Makefile b/apps/examples/null/Makefile index d37d9e6371..47ec4cdafd 100644 --- a/apps/examples/null/Makefile +++ b/apps/examples/null/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/nx/Makefile b/apps/examples/nx/Makefile index a77ad792a2..ad2bee84ea 100644 --- a/apps/examples/nx/Makefile +++ b/apps/examples/nx/Makefile @@ -101,11 +101,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/nxconsole/Makefile b/apps/examples/nxconsole/Makefile index 555511882b..aa4cdc518c 100644 --- a/apps/examples/nxconsole/Makefile +++ b/apps/examples/nxconsole/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/nxffs/Makefile b/apps/examples/nxffs/Makefile index be2a34eae7..9af03897ff 100644 --- a/apps/examples/nxffs/Makefile +++ b/apps/examples/nxffs/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/nxflat/Makefile b/apps/examples/nxflat/Makefile index 5f5a302c34..344ee9c6de 100644 --- a/apps/examples/nxflat/Makefile +++ b/apps/examples/nxflat/Makefile @@ -91,11 +91,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/nxflat/tests/errno/Makefile b/apps/examples/nxflat/tests/errno/Makefile index d05154525a..d8d75b227e 100644 --- a/apps/examples/nxflat/tests/errno/Makefile +++ b/apps/examples/nxflat/tests/errno/Makefile @@ -70,10 +70,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/nxflat/tests/hello++/Makefile b/apps/examples/nxflat/tests/hello++/Makefile index 445049e94d..739562905b 100644 --- a/apps/examples/nxflat/tests/hello++/Makefile +++ b/apps/examples/nxflat/tests/hello++/Makefile @@ -163,16 +163,16 @@ $(BIN3): $(BIN3).r2 # $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN1)) - $(call DELFILE $(BIN2)) - $(call DELFILE $(BIN3)) - $(call DELFILE $(BIN4)) - $(call DELFILE $(R2SRC1)) - $(call DELFILE $(R2SRC2)) - $(call DELFILE $(R2SRC3)) - $(call DELFILE $(R2SRC4)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN1)) + $(call DELFILE, $(BIN2)) + $(call DELFILE, $(BIN3)) + $(call DELFILE, $(BIN4)) + $(call DELFILE, $(R2SRC1)) + $(call DELFILE, $(R2SRC2)) + $(call DELFILE, $(R2SRC3)) + $(call DELFILE, $(R2SRC4)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: $(ALL_BIN) diff --git a/apps/examples/nxflat/tests/hello/Makefile b/apps/examples/nxflat/tests/hello/Makefile index cf1a4eb80c..b4521a74e9 100644 --- a/apps/examples/nxflat/tests/hello/Makefile +++ b/apps/examples/nxflat/tests/hello/Makefile @@ -70,10 +70,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/nxflat/tests/longjmp/Makefile b/apps/examples/nxflat/tests/longjmp/Makefile index 55deadbb73..76d49417c6 100644 --- a/apps/examples/nxflat/tests/longjmp/Makefile +++ b/apps/examples/nxflat/tests/longjmp/Makefile @@ -70,10 +70,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/nxflat/tests/mutex/Makefile b/apps/examples/nxflat/tests/mutex/Makefile index 97e5c356e6..d45c49dddd 100644 --- a/apps/examples/nxflat/tests/mutex/Makefile +++ b/apps/examples/nxflat/tests/mutex/Makefile @@ -70,10 +70,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/nxflat/tests/pthread/Makefile b/apps/examples/nxflat/tests/pthread/Makefile index 5dd6a2a10d..fffb13dfb0 100644 --- a/apps/examples/nxflat/tests/pthread/Makefile +++ b/apps/examples/nxflat/tests/pthread/Makefile @@ -71,10 +71,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/nxflat/tests/signal/Makefile b/apps/examples/nxflat/tests/signal/Makefile index e39f3a8d49..372100030d 100644 --- a/apps/examples/nxflat/tests/signal/Makefile +++ b/apps/examples/nxflat/tests/signal/Makefile @@ -70,10 +70,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/nxflat/tests/struct/Makefile b/apps/examples/nxflat/tests/struct/Makefile index ac789f3f40..ff15256af0 100644 --- a/apps/examples/nxflat/tests/struct/Makefile +++ b/apps/examples/nxflat/tests/struct/Makefile @@ -72,10 +72,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/nxflat/tests/task/Makefile b/apps/examples/nxflat/tests/task/Makefile index d27213817b..a528c60b78 100644 --- a/apps/examples/nxflat/tests/task/Makefile +++ b/apps/examples/nxflat/tests/task/Makefile @@ -70,10 +70,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/nxhello/Makefile b/apps/examples/nxhello/Makefile index be52882c36..b1ac6f116f 100644 --- a/apps/examples/nxhello/Makefile +++ b/apps/examples/nxhello/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/nximage/Makefile b/apps/examples/nximage/Makefile index b20e463509..e2e9201e74 100644 --- a/apps/examples/nximage/Makefile +++ b/apps/examples/nximage/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/nxlines/Makefile b/apps/examples/nxlines/Makefile index cd5753ef9b..cdda7ad8cd 100644 --- a/apps/examples/nxlines/Makefile +++ b/apps/examples/nxlines/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/nxtext/Makefile b/apps/examples/nxtext/Makefile index 68c4a026f8..dffe66ba1f 100644 --- a/apps/examples/nxtext/Makefile +++ b/apps/examples/nxtext/Makefile @@ -102,11 +102,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/ostest/Makefile b/apps/examples/ostest/Makefile index 2d93126ad8..3e78c64e83 100644 --- a/apps/examples/ostest/Makefile +++ b/apps/examples/ostest/Makefile @@ -142,11 +142,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/pashello/Makefile b/apps/examples/pashello/Makefile index df86e7d626..5876b9d2a8 100644 --- a/apps/examples/pashello/Makefile +++ b/apps/examples/pashello/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/pipe/Makefile b/apps/examples/pipe/Makefile index e6cefbcdbd..bed3190858 100644 --- a/apps/examples/pipe/Makefile +++ b/apps/examples/pipe/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/poll/Makefile b/apps/examples/poll/Makefile index dc33d6b491..13173f1253 100644 --- a/apps/examples/poll/Makefile +++ b/apps/examples/poll/Makefile @@ -87,12 +87,12 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) - $(call DELFILE host$(HOSTEXEEXT)) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + $(call DELFILE, host$(HOSTEXEEXT)) -include Make.dep diff --git a/apps/examples/pwm/Makefile b/apps/examples/pwm/Makefile index c7cc700bdc..3a6f2520a0 100644 --- a/apps/examples/pwm/Makefile +++ b/apps/examples/pwm/Makefile @@ -96,11 +96,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/qencoder/Makefile b/apps/examples/qencoder/Makefile index 817ba17cc0..7d2427c6bf 100644 --- a/apps/examples/qencoder/Makefile +++ b/apps/examples/qencoder/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/relays/Makefile b/apps/examples/relays/Makefile index 385bc85203..9d7b036d38 100644 --- a/apps/examples/relays/Makefile +++ b/apps/examples/relays/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/rgmp/Makefile b/apps/examples/rgmp/Makefile index 72d5e660a0..d94d6ec3c8 100644 --- a/apps/examples/rgmp/Makefile +++ b/apps/examples/rgmp/Makefile @@ -86,11 +86,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/romfs/Makefile b/apps/examples/romfs/Makefile index 5190a7a6e8..2b02952eda 100644 --- a/apps/examples/romfs/Makefile +++ b/apps/examples/romfs/Makefile @@ -103,13 +103,13 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) - $(call DELFILE testdir.img) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + $(call DELFILE, testdir.img) -include Make.dep diff --git a/apps/examples/sendmail/Makefile b/apps/examples/sendmail/Makefile index 049321b524..a3b8b72882 100644 --- a/apps/examples/sendmail/Makefile +++ b/apps/examples/sendmail/Makefile @@ -87,13 +87,13 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) @$(MAKE) -f Makefile.host clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/sendmail/Makefile.host b/apps/examples/sendmail/Makefile.host index e6ff39540d..b62a8755b6 100644 --- a/apps/examples/sendmail/Makefile.host +++ b/apps/examples/sendmail/Makefile.host @@ -71,8 +71,8 @@ $(BIN): headers $(OBJS) $(HOSTCC) $(HOSTLDFLAGS) $(OBJS) -o $@ clean: - $(call DELFILE $(BIN).*) - $(call DELFILE *.o1) + $(call DELFILE, $(BIN).*) + $(call DELFILE, *.o1) $(call CLEAN) @rm -rf include diff --git a/apps/examples/serloop/Makefile b/apps/examples/serloop/Makefile index 01d2c60fef..4a262884bb 100644 --- a/apps/examples/serloop/Makefile +++ b/apps/examples/serloop/Makefile @@ -87,12 +87,12 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/telnetd/Makefile b/apps/examples/telnetd/Makefile index a1f0f7c63e..8f5e5b6d2f 100644 --- a/apps/examples/telnetd/Makefile +++ b/apps/examples/telnetd/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/thttpd/Makefile b/apps/examples/thttpd/Makefile index 5320a0a131..85a26d39f4 100644 --- a/apps/examples/thttpd/Makefile +++ b/apps/examples/thttpd/Makefile @@ -89,13 +89,13 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) @$(MAKE) -C content clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/thttpd/content/Makefile b/apps/examples/thttpd/content/Makefile index 8a74201b5a..b4deddef5a 100644 --- a/apps/examples/thttpd/content/Makefile +++ b/apps/examples/thttpd/content/Makefile @@ -98,8 +98,8 @@ $(SYMTAB): build clean: $(foreach DIR, $(SUBDIRS), $(DIR)_clean) $(call DELFILE$(ROMFS_HDR)) - $(call DELFILE $(ROMFS_IMG)) - $(call DELFILE $(SYMTAB)) + $(call DELFILE, $(ROMFS_IMG)) + $(call DELFILE, $(SYMTAB)) @rm -rf $(ROMFS_DIR) $(call CLEAN) diff --git a/apps/examples/thttpd/content/hello/Makefile b/apps/examples/thttpd/content/hello/Makefile index 74ff2116af..2cdead59c6 100644 --- a/apps/examples/thttpd/content/hello/Makefile +++ b/apps/examples/thttpd/content/hello/Makefile @@ -70,10 +70,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/thttpd/content/netstat/Makefile b/apps/examples/thttpd/content/netstat/Makefile index d9953547af..98675bd883 100644 --- a/apps/examples/thttpd/content/netstat/Makefile +++ b/apps/examples/thttpd/content/netstat/Makefile @@ -70,10 +70,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/thttpd/content/tasks/Makefile b/apps/examples/thttpd/content/tasks/Makefile index c668285d8b..bf98115246 100644 --- a/apps/examples/thttpd/content/tasks/Makefile +++ b/apps/examples/thttpd/content/tasks/Makefile @@ -70,10 +70,10 @@ $(BIN): $(BIN).r2 $(Q) $(LDNXFLAT) $(LDNXFLATFLAGS) -o $@ $^ clean: - $(call DELFILE $(BIN)) - $(call DELFILE $(R2SRC)) - $(call DELFILE *.r1) - $(call DELFILE *.r2) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(R2SRC)) + $(call DELFILE, *.r1) + $(call DELFILE, *.r2) $(call CLEAN) install: diff --git a/apps/examples/tiff/Makefile b/apps/examples/tiff/Makefile index 373c07ca7c..f62209931a 100644 --- a/apps/examples/tiff/Makefile +++ b/apps/examples/tiff/Makefile @@ -98,14 +98,14 @@ context: .context depend: .depend clean: - $(call DELFILE .built) - $(call DELFILE result.tif) - $(call DELFILE tmpfile1.dat) - $(call DELFILE tmpfile2.dat) + $(call DELFILE, .built) + $(call DELFILE, result.tif) + $(call DELFILE, tmpfile1.dat) + $(call DELFILE, tmpfile2.dat) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/touchscreen/Makefile b/apps/examples/touchscreen/Makefile index f252966201..b3943951ef 100644 --- a/apps/examples/touchscreen/Makefile +++ b/apps/examples/touchscreen/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/udp/Makefile b/apps/examples/udp/Makefile index 79606c69b3..9c35cc94f3 100644 --- a/apps/examples/udp/Makefile +++ b/apps/examples/udp/Makefile @@ -116,14 +116,14 @@ context: depend: .depend clean: - $(call DELFILE .built) - $(call DELFILE $(TARG_BIN)) - $(call DELFILE $(HOST_BIN)) + $(call DELFILE, .built) + $(call DELFILE, $(TARG_BIN)) + $(call DELFILE, $(HOST_BIN)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/uip/Makefile b/apps/examples/uip/Makefile index 99e140f043..b154532b71 100644 --- a/apps/examples/uip/Makefile +++ b/apps/examples/uip/Makefile @@ -89,13 +89,13 @@ context: epend: .depend clean: - $(call DELFILE .built) - $(call DELFILE httpd_fsdata.c) + $(call DELFILE, .built) + $(call DELFILE, httpd_fsdata.c) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/usbserial/Makefile b/apps/examples/usbserial/Makefile index 2c34fa2757..ec72195056 100644 --- a/apps/examples/usbserial/Makefile +++ b/apps/examples/usbserial/Makefile @@ -85,13 +85,13 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) @$(MAKE) -f Makefile.host clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/usbserial/Makefile.host b/apps/examples/usbserial/Makefile.host index 9fb43269d5..a98ed8d5ff 100644 --- a/apps/examples/usbserial/Makefile.host +++ b/apps/examples/usbserial/Makefile.host @@ -60,5 +60,5 @@ $(BIN): $(SRC) @$(HOSTCC) $(HOSTCFLAGS) $(DEFINES) $^ -o $@ clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) diff --git a/apps/examples/usbstorage/Makefile b/apps/examples/usbstorage/Makefile index 4c8323e005..5492e47dc4 100644 --- a/apps/examples/usbstorage/Makefile +++ b/apps/examples/usbstorage/Makefile @@ -103,12 +103,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/usbterm/Makefile b/apps/examples/usbterm/Makefile index acf9812bd6..c5fb95331e 100644 --- a/apps/examples/usbterm/Makefile +++ b/apps/examples/usbterm/Makefile @@ -98,12 +98,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/watchdog/Makefile b/apps/examples/watchdog/Makefile index 8bbdbfea61..9890959fb5 100644 --- a/apps/examples/watchdog/Makefile +++ b/apps/examples/watchdog/Makefile @@ -96,11 +96,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/wget/Makefile b/apps/examples/wget/Makefile index d74c248e91..3e5f5d63d1 100644 --- a/apps/examples/wget/Makefile +++ b/apps/examples/wget/Makefile @@ -86,13 +86,13 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) @$(MAKE) -f Makefile.host clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/wget/Makefile.host b/apps/examples/wget/Makefile.host index 14da45c7e9..3895835d85 100644 --- a/apps/examples/wget/Makefile.host +++ b/apps/examples/wget/Makefile.host @@ -71,8 +71,8 @@ $(BIN): headers $(OBJS) $(HOSTCC) $(HOSTLDFLAGS) $(OBJS) -o $@ clean: - $(call DELFILE $(BIN).*) - $(call DELFILE *.o1) + $(call DELFILE, $(BIN).*) + $(call DELFILE, *.o1) $(call CLEAN) @rm -rf net nuttx diff --git a/apps/examples/wgetjson/Makefile b/apps/examples/wgetjson/Makefile index 96748defb5..fa8f302c68 100644 --- a/apps/examples/wgetjson/Makefile +++ b/apps/examples/wgetjson/Makefile @@ -98,11 +98,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/wlan/Makefile b/apps/examples/wlan/Makefile index be2dbea7af..1da79736f1 100644 --- a/apps/examples/wlan/Makefile +++ b/apps/examples/wlan/Makefile @@ -87,12 +87,12 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/examples/xmlrpc/Makefile b/apps/examples/xmlrpc/Makefile index 5ab60a0dd5..7053f54d38 100644 --- a/apps/examples/xmlrpc/Makefile +++ b/apps/examples/xmlrpc/Makefile @@ -99,11 +99,11 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/graphics/tiff/Makefile b/apps/graphics/tiff/Makefile index 996f518940..e42091ad94 100644 --- a/apps/graphics/tiff/Makefile +++ b/apps/graphics/tiff/Makefile @@ -86,12 +86,12 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/interpreters/ficl/Makefile b/apps/interpreters/ficl/Makefile index 97cc9d6386..990630fb89 100644 --- a/apps/interpreters/ficl/Makefile +++ b/apps/interpreters/ficl/Makefile @@ -108,12 +108,12 @@ context: depend: .depend clean: - $(call DELFILE .context) - $(call DELFILE .built) + $(call DELFILE, .context) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/modbus/Makefile b/apps/modbus/Makefile index c0f01bc94d..d2b1481628 100644 --- a/apps/modbus/Makefile +++ b/apps/modbus/Makefile @@ -107,13 +107,13 @@ endif depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/namedapp/Makefile b/apps/namedapp/Makefile index f52e8a9d57..a88c735674 100644 --- a/apps/namedapp/Makefile +++ b/apps/namedapp/Makefile @@ -96,15 +96,15 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) - $(call DELFILE namedapp_list.h) - $(call DELFILE namedapp_proto.h) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + $(call DELFILE, namedapp_list.h) + $(call DELFILE, namedapp_proto.h) -include Make.dep diff --git a/apps/netutils/codecs/Makefile b/apps/netutils/codecs/Makefile index 644a07dece..5d2fe9ce6a 100644 --- a/apps/netutils/codecs/Makefile +++ b/apps/netutils/codecs/Makefile @@ -84,11 +84,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/dhcpc/Makefile b/apps/netutils/dhcpc/Makefile index 0fe9681011..3d41858863 100644 --- a/apps/netutils/dhcpc/Makefile +++ b/apps/netutils/dhcpc/Makefile @@ -90,11 +90,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/dhcpd/Makefile b/apps/netutils/dhcpd/Makefile index 3592313987..302b2ad434 100644 --- a/apps/netutils/dhcpd/Makefile +++ b/apps/netutils/dhcpd/Makefile @@ -90,11 +90,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/discover/Makefile b/apps/netutils/discover/Makefile index 22c06b4721..2cee70b4bd 100644 --- a/apps/netutils/discover/Makefile +++ b/apps/netutils/discover/Makefile @@ -93,11 +93,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/ftpc/Makefile b/apps/netutils/ftpc/Makefile index 9524895501..b610961d8a 100644 --- a/apps/netutils/ftpc/Makefile +++ b/apps/netutils/ftpc/Makefile @@ -106,11 +106,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/ftpd/Makefile b/apps/netutils/ftpd/Makefile index cccdf548af..b537e6d867 100644 --- a/apps/netutils/ftpd/Makefile +++ b/apps/netutils/ftpd/Makefile @@ -90,11 +90,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/json/Makefile b/apps/netutils/json/Makefile index d8f492aed3..b818ede81c 100644 --- a/apps/netutils/json/Makefile +++ b/apps/netutils/json/Makefile @@ -84,11 +84,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/resolv/Makefile b/apps/netutils/resolv/Makefile index c5ec8fff13..ef77eb9f6a 100644 --- a/apps/netutils/resolv/Makefile +++ b/apps/netutils/resolv/Makefile @@ -90,11 +90,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/smtp/Makefile b/apps/netutils/smtp/Makefile index ec3e513b86..b465b4f0b0 100644 --- a/apps/netutils/smtp/Makefile +++ b/apps/netutils/smtp/Makefile @@ -90,11 +90,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/telnetd/Makefile b/apps/netutils/telnetd/Makefile index f614719d5b..129162aca4 100644 --- a/apps/netutils/telnetd/Makefile +++ b/apps/netutils/telnetd/Makefile @@ -90,11 +90,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/tftpc/Makefile b/apps/netutils/tftpc/Makefile index 56d3ded125..cd0792a4e4 100644 --- a/apps/netutils/tftpc/Makefile +++ b/apps/netutils/tftpc/Makefile @@ -92,11 +92,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/thttpd/Makefile b/apps/netutils/thttpd/Makefile index aa053b709f..02a86f4774 100644 --- a/apps/netutils/thttpd/Makefile +++ b/apps/netutils/thttpd/Makefile @@ -122,11 +122,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/uiplib/Makefile b/apps/netutils/uiplib/Makefile index d4f73fb835..4d33255a58 100644 --- a/apps/netutils/uiplib/Makefile +++ b/apps/netutils/uiplib/Makefile @@ -106,11 +106,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/webclient/Makefile b/apps/netutils/webclient/Makefile index 7ade03cb9c..d0b43621d0 100644 --- a/apps/netutils/webclient/Makefile +++ b/apps/netutils/webclient/Makefile @@ -90,11 +90,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/webserver/Makefile b/apps/netutils/webserver/Makefile index 6c5e3d286f..1f3936f6e7 100644 --- a/apps/netutils/webserver/Makefile +++ b/apps/netutils/webserver/Makefile @@ -97,11 +97,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/netutils/xmlrpc/Makefile b/apps/netutils/xmlrpc/Makefile index bf78153604..7bc404b47c 100644 --- a/apps/netutils/xmlrpc/Makefile +++ b/apps/netutils/xmlrpc/Makefile @@ -91,11 +91,11 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile index 16efe99cc4..73325e899d 100644 --- a/apps/nshlib/Makefile +++ b/apps/nshlib/Makefile @@ -126,13 +126,13 @@ context: depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/system/free/Makefile b/apps/system/free/Makefile index 9637fa772e..dada00d992 100644 --- a/apps/system/free/Makefile +++ b/apps/system/free/Makefile @@ -107,12 +107,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile index 7cdbcdf593..029d2b6fe4 100644 --- a/apps/system/i2c/Makefile +++ b/apps/system/i2c/Makefile @@ -93,13 +93,13 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/system/install/Makefile b/apps/system/install/Makefile index 951917a77c..6a02d859ff 100644 --- a/apps/system/install/Makefile +++ b/apps/system/install/Makefile @@ -108,12 +108,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/system/poweroff/Makefile b/apps/system/poweroff/Makefile index 46b595e843..bbceccb9e9 100644 --- a/apps/system/poweroff/Makefile +++ b/apps/system/poweroff/Makefile @@ -108,12 +108,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/system/ramtron/Makefile b/apps/system/ramtron/Makefile index 60a2be66a7..9f5af1659b 100644 --- a/apps/system/ramtron/Makefile +++ b/apps/system/ramtron/Makefile @@ -108,12 +108,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/system/readline/Makefile b/apps/system/readline/Makefile index f67dc85f6e..3a48d324e7 100644 --- a/apps/system/readline/Makefile +++ b/apps/system/readline/Makefile @@ -96,12 +96,12 @@ depend: .depend # Housekeeping targets clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/system/sdcard/Makefile b/apps/system/sdcard/Makefile index ee95505a20..6d5d129608 100644 --- a/apps/system/sdcard/Makefile +++ b/apps/system/sdcard/Makefile @@ -108,12 +108,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/apps/system/sysinfo/Makefile b/apps/system/sysinfo/Makefile index 06c27a8be7..fa6aebf711 100644 --- a/apps/system/sysinfo/Makefile +++ b/apps/system/sysinfo/Makefile @@ -108,12 +108,12 @@ context: .context depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/misc/pascal/nuttx/Makefile b/misc/pascal/nuttx/Makefile index 701353602e..396fae834c 100644 --- a/misc/pascal/nuttx/Makefile +++ b/misc/pascal/nuttx/Makefile @@ -123,12 +123,12 @@ context: $(APPDIR)$(DELIM)include$(DELIM)pcode $(APPDIR)$(DELIM)include$(DELIM)p depend: .depend clean: - $(call DELFILE .built) + $(call DELFILE, .built) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) @$(DIRUNLINK) $(APPDIR)$(DELIM)include$(DELIM)pcode$(DELIM)insn @$(DIRUNLINK) $(APPDIR)$(DELIM)include$(DELIM)pcode diff --git a/nuttx/Makefile.unix b/nuttx/Makefile.unix index c88a6cc92c..78c34c2de5 100644 --- a/nuttx/Makefile.unix +++ b/nuttx/Makefile.unix @@ -419,10 +419,10 @@ context: check_context include/nuttx/config.h include/nuttx/version.h include/ma # and symbolic links created by the context target. clean_context: - $(call DELFILE include/nuttx/config.h) - $(call DELFILE include/nuttx/version.h) - $(call DELFILE include/math.h) - $(call DELFILE include/stdarg.h) + $(call DELFILE, include/nuttx/config.h) + $(call DELFILE, include/nuttx/version.h) + $(call DELFILE, include/math.h) + $(call DELFILE, include/stdarg.h) $(Q) $(DIRUNLINK) include/arch/board $(Q) $(DIRUNLINK) include/arch/chip $(Q) $(DIRUNLINK) include/arch @@ -686,12 +686,12 @@ ifeq ($(CONFIG_BUILD_2PASS),y) endif clean: subdir_clean - $(call DELFILE $(BIN)) - $(call DELFILE nuttx.*) - $(call DELFILE mm_test) - $(call DELFILE *.map) - $(call DELFILE _SAVED_APPS_config) - $(call DELFILE nuttx-export*) + $(call DELFILE, $(BIN)) + $(call DELFILE, nuttx.*) + $(call DELFILE, mm_test) + $(call DELFILE, *.map) + $(call DELFILE, _SAVED_APPS_config) + $(call DELFILE, nuttx-export*) $(call CLEAN) subdir_distclean: @@ -705,11 +705,11 @@ distclean: clean subdir_distclean clean_context ifeq ($(CONFIG_BUILD_2PASS),y) $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean endif - $(call DELFILE Make.defs) - $(call DELFILE setenv.sh) - $(call DELFILE setenv.bat) - $(call DELFILE .config) - $(call DELFILE .config.old) + $(call DELFILE, Make.defs) + $(call DELFILE, setenv.sh) + $(call DELFILE, setenv.bat) + $(call DELFILE, .config) + $(call DELFILE, .config.old) # Application housekeeping targets. The APPDIR variable refers to the user # application directory. A sample apps/ directory is included with NuttX, diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win index 4fe0b2aa1f..5cb6aa3534 100644 --- a/nuttx/Makefile.win +++ b/nuttx/Makefile.win @@ -438,16 +438,16 @@ context: check_context include\nuttx\config.h include\nuttx\version.h include\ma # and symbolic links created by the context target. clean_context: - $(call DELFILE include\nuttx\config.h) - $(call DELFILE include\nuttx\version.h) - $(call DELFILE include\math.h) - $(call DELFILE include\stdarg.h) - $(call DELDIR include\arch\board) - $(call DELDIR include\arch\chip) - $(call DELDIR include\arch) - $(call DELDIR $(ARCH_SRC)\board) - $(call DELDIR $(ARCH_SRC)\chip) - $(call DELDIR include\apps) + $(call DELFILE, include\nuttx\config.h) + $(call DELFILE, include\nuttx\version.h) + $(call DELFILE, include\math.h) + $(call DELFILE, include\stdarg.h) + $(call DELDIR, include\arch\board) + $(call DELDIR, include\arch\chip) + $(call DELDIR, include\arch) + $(call DELDIR, $(ARCH_SRC)\board) + $(call DELDIR, $(ARCH_SRC)\chip) + $(call DELDIR, include\apps) # check_context # @@ -688,12 +688,12 @@ ifeq ($(CONFIG_BUILD_2PASS),y) endif clean: subdir_clean - $(call DELFILE $(BIN)) - $(call DELFILE nuttx.*) - $(call DELFILE mm_test) - $(call DELFILE *.map) - $(call DELFILE _SAVED_APPS_config) - $(call DELFILE nuttx-export*) + $(call DELFILE, $(BIN)) + $(call DELFILE, nuttx.*) + $(call DELFILE, mm_test) + $(call DELFILE, *.map) + $(call DELFILE, _SAVED_APPS_config) + $(call DELFILE, nuttx-export*) $(call CLEAN) subdir_distclean: @@ -703,11 +703,11 @@ distclean: clean subdir_distclean clean_context ifeq ($(CONFIG_BUILD_2PASS),y) $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean endif - $(call DELFILE Make.defs) - $(call DELFILE setenv.sh) - $(call DELFILE setenv.bat) - $(call DELFILE .config) - $(call DELFILE .config.old) + $(call DELFILE, Make.defs) + $(call DELFILE, setenv.sh) + $(call DELFILE, setenv.bat) + $(call DELFILE, .config) + $(call DELFILE, .config.old) # Application housekeeping targets. The APPDIR variable refers to the user # application directory. A sample apps\ directory is included with NuttX, @@ -732,7 +732,7 @@ endif apps_distclean: ifneq ($(APPDIR),) - $(call DELFILE _SAVED_APPS_config + $(call DELFILE, _SAVED_APPS_config $(Q) if exist "$(TOPDIR)\$(APPDIR)\.config" ( cp "$(TOPDIR)\$(APPDIR)\.config" _SAVED_APPS_config ) $(Q) $(MAKE) -C "$(TOPDIR)\$(APPDIR)" TOPDIR="$(TOPDIR)" distclean $(Q) if exist _SAVED_APPS_config ( mv _SAVED_APPS_config "$(TOPDIR)\$(APPDIR)\.config" ) diff --git a/nuttx/arch/8051/src/Makefile b/nuttx/arch/8051/src/Makefile index 6c87b8bc96..61e40d84b9 100644 --- a/nuttx/arch/8051/src/Makefile +++ b/nuttx/arch/8051/src/Makefile @@ -221,15 +221,15 @@ clean: $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR=$(TOPDIR) clean ; \ fi - $(call DELFILE libarch$(LIBEXT)) - $(call DELFILE up_mem.h) + $(call DELFILE, libarch$(LIBEXT)) + $(call DELFILE, up_mem.h) $(call CLEAN) distclean: clean $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR=$(TOPDIR) distclean ; \ fi - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index a6d5fa4f46..e44def30c0 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -178,14 +178,14 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/arch/avr/src/Makefile b/nuttx/arch/avr/src/Makefile index 69d3a0fc04..c3d2f9816e 100644 --- a/nuttx/arch/avr/src/Makefile +++ b/nuttx/arch/avr/src/Makefile @@ -171,15 +171,15 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile index 7353b44ea5..d1ce2e205a 100644 --- a/nuttx/arch/hc/src/Makefile +++ b/nuttx/arch/hc/src/Makefile @@ -166,14 +166,14 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/arch/mips/src/Makefile b/nuttx/arch/mips/src/Makefile index b27fe8730a..906bac59fc 100644 --- a/nuttx/arch/mips/src/Makefile +++ b/nuttx/arch/mips/src/Makefile @@ -164,14 +164,14 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/arch/rgmp/src/Makefile b/nuttx/arch/rgmp/src/Makefile index 019dca4658..05ef21feaf 100644 --- a/nuttx/arch/rgmp/src/Makefile +++ b/nuttx/arch/rgmp/src/Makefile @@ -96,14 +96,14 @@ export_head: depend: .depend clean: - $(call DELFILE "$(TOPDIR)/arch/rgmp/src/x86/*.o") - $(call DELFILE "$(TOPDIR)/kernel.img") - $(call DELFILE nuttx.img) - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, "$(TOPDIR)/arch/rgmp/src/x86/*.o") + $(call DELFILE, "$(TOPDIR)/kernel.img") + $(call DELFILE, nuttx.img) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/arch/sh/src/Makefile b/nuttx/arch/sh/src/Makefile index af7c481a90..e8be489cde 100644 --- a/nuttx/arch/sh/src/Makefile +++ b/nuttx/arch/sh/src/Makefile @@ -161,14 +161,14 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile index 5abd6ce4f0..29eadb395b 100644 --- a/nuttx/arch/sim/src/Makefile +++ b/nuttx/arch/sim/src/Makefile @@ -214,16 +214,16 @@ clean: cleanrel $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi - $(call DELFILE nuttx.rel) - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, nuttx.rel) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) distclean: clean $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) $(Q) rm -rf GNU -include Make.dep diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile index e93dc2657c..2539c0f112 100644 --- a/nuttx/arch/x86/src/Makefile +++ b/nuttx/arch/x86/src/Makefile @@ -172,14 +172,14 @@ clean: ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean endif - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) distclean: clean ifeq ($(BOARDMAKE),y) $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean endif - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/arch/z16/src/Makefile b/nuttx/arch/z16/src/Makefile index d3f5819989..b34d91c687 100644 --- a/nuttx/arch/z16/src/Makefile +++ b/nuttx/arch/z16/src/Makefile @@ -138,19 +138,19 @@ clean: $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi ifeq ($(COMPILER),zneocc.exe) - $(call DELFILE nuttx.linkcmd) - $(call DELFILE *.asm) - $(call DELFILE *.tmp) - $(call DELFILE *.map) + $(call DELFILE, nuttx.linkcmd) + $(call DELFILE, *.asm) + $(call DELFILE, *.tmp) + $(call DELFILE, *.map) endif - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) distclean: clean $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/arch/z80/src/Makefile.sdcc b/nuttx/arch/z80/src/Makefile.sdcc index e29fa9fda8..a8a63c1115 100644 --- a/nuttx/arch/z80/src/Makefile.sdcc +++ b/nuttx/arch/z80/src/Makefile.sdcc @@ -240,11 +240,11 @@ clean: $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi - $(call DELFILE up_mem.h) - $(call DELFILE asm_mem.h) - $(call DELFILE pass1.*) - $(call DELFILE nuttx.*) - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, up_mem.h) + $(call DELFILE, asm_mem.h) + $(call DELFILE, pass1.*) + $(call DELFILE, nuttx.*) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) @@ -252,7 +252,7 @@ distclean: clean $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii index 1d7b1f96d1..338f2df935 100644 --- a/nuttx/arch/z80/src/Makefile.zdsii +++ b/nuttx/arch/z80/src/Makefile.zdsii @@ -150,18 +150,18 @@ clean: $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi - $(call DELFILE nuttx.linkcmd) - $(call DELFILE *.asm) - $(call DELFILE *.tmp) - $(call DELFILE *.map) - $(call DELFILE libarch$(LIBEXT)) + $(call DELFILE, nuttx.linkcmd) + $(call DELFILE, *.asm) + $(call DELFILE, *.tmp) + $(call DELFILE, *.map) + $(call DELFILE, libarch$(LIBEXT)) $(call CLEAN) distclean: clean $(Q) if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile index f90ea0417a..a59392fb05 100644 --- a/nuttx/binfmt/Makefile +++ b/nuttx/binfmt/Makefile @@ -87,11 +87,11 @@ $(BIN): $(BINFMT_OBJS) depend: .depend clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/amber/src/Makefile b/nuttx/configs/amber/src/Makefile index 49e8d5df8c..ed62de056b 100644 --- a/nuttx/configs/amber/src/Makefile +++ b/nuttx/configs/amber/src/Makefile @@ -86,11 +86,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/avr32dev1/src/Makefile b/nuttx/configs/avr32dev1/src/Makefile index 64b2ba0998..ccff5e0621 100644 --- a/nuttx/configs/avr32dev1/src/Makefile +++ b/nuttx/configs/avr32dev1/src/Makefile @@ -79,12 +79,12 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/c5471evm/src/Makefile b/nuttx/configs/c5471evm/src/Makefile index 2161ac11aa..8a33e81c1e 100644 --- a/nuttx/configs/c5471evm/src/Makefile +++ b/nuttx/configs/c5471evm/src/Makefile @@ -66,11 +66,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/compal_e88/src/Makefile b/nuttx/configs/compal_e88/src/Makefile index c2b9182c5f..c8793128e6 100644 --- a/nuttx/configs/compal_e88/src/Makefile +++ b/nuttx/configs/compal_e88/src/Makefile @@ -69,11 +69,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/compal_e99/src/Makefile b/nuttx/configs/compal_e99/src/Makefile index deeacb0bd3..ef479b64fb 100644 --- a/nuttx/configs/compal_e99/src/Makefile +++ b/nuttx/configs/compal_e99/src/Makefile @@ -69,11 +69,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/demo9s12ne64/src/Makefile b/nuttx/configs/demo9s12ne64/src/Makefile index 18dd2ac095..ac99b0c6bd 100644 --- a/nuttx/configs/demo9s12ne64/src/Makefile +++ b/nuttx/configs/demo9s12ne64/src/Makefile @@ -75,11 +75,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/ea3131/locked/Makefile b/nuttx/configs/ea3131/locked/Makefile index e52b67880d..21757036af 100644 --- a/nuttx/configs/ea3131/locked/Makefile +++ b/nuttx/configs/ea3131/locked/Makefile @@ -112,9 +112,9 @@ $(PASS1_SRCDIR)$(DELIM)locked.r: locked.r depend: .depend clean: - $(call DELFILE locked.r) - $(call DELFILE locked.map) + $(call DELFILE, locked.r) + $(call DELFILE, locked.map) $(call CLEAN) distclean: clean - $(call DELFILE ld-locked.inc) + $(call DELFILE, ld-locked.inc) diff --git a/nuttx/configs/ea3131/src/Makefile b/nuttx/configs/ea3131/src/Makefile index 2a09631a24..778a2b138a 100644 --- a/nuttx/configs/ea3131/src/Makefile +++ b/nuttx/configs/ea3131/src/Makefile @@ -94,11 +94,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/ea3152/src/Makefile b/nuttx/configs/ea3152/src/Makefile index 1620a3586d..cb945f5aa1 100644 --- a/nuttx/configs/ea3152/src/Makefile +++ b/nuttx/configs/ea3152/src/Makefile @@ -94,11 +94,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/eagle100/src/Makefile b/nuttx/configs/eagle100/src/Makefile index c7e9e31370..bfff3a89bb 100644 --- a/nuttx/configs/eagle100/src/Makefile +++ b/nuttx/configs/eagle100/src/Makefile @@ -75,11 +75,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/ekk-lm3s9b96/src/Makefile b/nuttx/configs/ekk-lm3s9b96/src/Makefile index a44b698980..4fb7fb63db 100644 --- a/nuttx/configs/ekk-lm3s9b96/src/Makefile +++ b/nuttx/configs/ekk-lm3s9b96/src/Makefile @@ -77,11 +77,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/ez80f910200kitg/src/Makefile b/nuttx/configs/ez80f910200kitg/src/Makefile index 61103a9312..940e331cf9 100644 --- a/nuttx/configs/ez80f910200kitg/src/Makefile +++ b/nuttx/configs/ez80f910200kitg/src/Makefile @@ -73,11 +73,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/ez80f910200zco/src/Makefile b/nuttx/configs/ez80f910200zco/src/Makefile index 8cf20c750a..ba80e9838c 100644 --- a/nuttx/configs/ez80f910200zco/src/Makefile +++ b/nuttx/configs/ez80f910200zco/src/Makefile @@ -80,11 +80,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/fire-stm32v2/src/Makefile b/nuttx/configs/fire-stm32v2/src/Makefile index 48bb5e6c74..f37ec51031 100644 --- a/nuttx/configs/fire-stm32v2/src/Makefile +++ b/nuttx/configs/fire-stm32v2/src/Makefile @@ -116,11 +116,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/hymini-stm32v/src/Makefile b/nuttx/configs/hymini-stm32v/src/Makefile index 2f8cf9992c..cbefe34ad3 100644 --- a/nuttx/configs/hymini-stm32v/src/Makefile +++ b/nuttx/configs/hymini-stm32v/src/Makefile @@ -95,11 +95,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/kwikstik-k40/src/Makefile b/nuttx/configs/kwikstik-k40/src/Makefile index eeaec8d0f9..e02cce78a2 100644 --- a/nuttx/configs/kwikstik-k40/src/Makefile +++ b/nuttx/configs/kwikstik-k40/src/Makefile @@ -93,11 +93,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/lincoln60/src/Makefile b/nuttx/configs/lincoln60/src/Makefile index 8e9fd8f04d..66862306ac 100644 --- a/nuttx/configs/lincoln60/src/Makefile +++ b/nuttx/configs/lincoln60/src/Makefile @@ -85,11 +85,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/lm3s6432-s2e/src/Makefile b/nuttx/configs/lm3s6432-s2e/src/Makefile index 751fe8c91f..2aa2eb14a8 100644 --- a/nuttx/configs/lm3s6432-s2e/src/Makefile +++ b/nuttx/configs/lm3s6432-s2e/src/Makefile @@ -76,11 +76,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/lm3s6965-ek/src/Makefile b/nuttx/configs/lm3s6965-ek/src/Makefile index 48315415ce..42b1a037d9 100644 --- a/nuttx/configs/lm3s6965-ek/src/Makefile +++ b/nuttx/configs/lm3s6965-ek/src/Makefile @@ -79,11 +79,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/lm3s8962-ek/src/Makefile b/nuttx/configs/lm3s8962-ek/src/Makefile index 270906b6d0..8ab822af76 100644 --- a/nuttx/configs/lm3s8962-ek/src/Makefile +++ b/nuttx/configs/lm3s8962-ek/src/Makefile @@ -79,11 +79,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/lpc4330-xplorer/src/Makefile b/nuttx/configs/lpc4330-xplorer/src/Makefile index c0d330df4c..b827c94346 100644 --- a/nuttx/configs/lpc4330-xplorer/src/Makefile +++ b/nuttx/configs/lpc4330-xplorer/src/Makefile @@ -113,11 +113,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile index 1e946c3dd3..6cc66793e0 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile +++ b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile @@ -85,11 +85,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/m68332evb/src/Makefile b/nuttx/configs/m68332evb/src/Makefile index f152f8fd9d..583184376d 100644 --- a/nuttx/configs/m68332evb/src/Makefile +++ b/nuttx/configs/m68332evb/src/Makefile @@ -63,11 +63,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/mbed/src/Makefile b/nuttx/configs/mbed/src/Makefile index a55bd36159..18019c0be3 100644 --- a/nuttx/configs/mbed/src/Makefile +++ b/nuttx/configs/mbed/src/Makefile @@ -79,11 +79,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/mcu123-lpc214x/src/Makefile b/nuttx/configs/mcu123-lpc214x/src/Makefile index ee6f8a7f33..5ddcebe424 100644 --- a/nuttx/configs/mcu123-lpc214x/src/Makefile +++ b/nuttx/configs/mcu123-lpc214x/src/Makefile @@ -86,11 +86,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/micropendous3/src/Makefile b/nuttx/configs/micropendous3/src/Makefile index df5dd45f24..31a8f540a1 100644 --- a/nuttx/configs/micropendous3/src/Makefile +++ b/nuttx/configs/micropendous3/src/Makefile @@ -86,11 +86,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/mirtoo/src/Makefile b/nuttx/configs/mirtoo/src/Makefile index 2a92f9a33e..88b4be12ad 100644 --- a/nuttx/configs/mirtoo/src/Makefile +++ b/nuttx/configs/mirtoo/src/Makefile @@ -85,11 +85,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/mx1ads/src/Makefile b/nuttx/configs/mx1ads/src/Makefile index 1de5cbf7e2..74bdca5d81 100644 --- a/nuttx/configs/mx1ads/src/Makefile +++ b/nuttx/configs/mx1ads/src/Makefile @@ -66,11 +66,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/ne64badge/src/Makefile b/nuttx/configs/ne64badge/src/Makefile index ea80cd087c..4a3d5502c7 100644 --- a/nuttx/configs/ne64badge/src/Makefile +++ b/nuttx/configs/ne64badge/src/Makefile @@ -75,11 +75,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/ntosd-dm320/src/Makefile b/nuttx/configs/ntosd-dm320/src/Makefile index f42558a712..c6e523073a 100644 --- a/nuttx/configs/ntosd-dm320/src/Makefile +++ b/nuttx/configs/ntosd-dm320/src/Makefile @@ -66,11 +66,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/nucleus2g/src/Makefile b/nuttx/configs/nucleus2g/src/Makefile index ad6ee69b16..518a0daaca 100644 --- a/nuttx/configs/nucleus2g/src/Makefile +++ b/nuttx/configs/nucleus2g/src/Makefile @@ -79,11 +79,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/olimex-lpc1766stk/src/Makefile b/nuttx/configs/olimex-lpc1766stk/src/Makefile index a8e3920b59..cf5b962fe9 100644 --- a/nuttx/configs/olimex-lpc1766stk/src/Makefile +++ b/nuttx/configs/olimex-lpc1766stk/src/Makefile @@ -93,11 +93,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/olimex-lpc2378/src/Makefile b/nuttx/configs/olimex-lpc2378/src/Makefile index 4ab2cffa6a..af8cafe70d 100644 --- a/nuttx/configs/olimex-lpc2378/src/Makefile +++ b/nuttx/configs/olimex-lpc2378/src/Makefile @@ -82,11 +82,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/olimex-stm32-p107/src/Makefile b/nuttx/configs/olimex-stm32-p107/src/Makefile index f0e0fc8d63..66bd595306 100644 --- a/nuttx/configs/olimex-stm32-p107/src/Makefile +++ b/nuttx/configs/olimex-stm32-p107/src/Makefile @@ -78,11 +78,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/olimex-strp711/src/Makefile b/nuttx/configs/olimex-strp711/src/Makefile index efe2df4f93..39067253aa 100644 --- a/nuttx/configs/olimex-strp711/src/Makefile +++ b/nuttx/configs/olimex-strp711/src/Makefile @@ -79,11 +79,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/pcblogic-pic32mx/src/Makefile b/nuttx/configs/pcblogic-pic32mx/src/Makefile index 175f0f1315..c02fc3d4fb 100644 --- a/nuttx/configs/pcblogic-pic32mx/src/Makefile +++ b/nuttx/configs/pcblogic-pic32mx/src/Makefile @@ -77,11 +77,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/pic32-starterkit/src/Makefile b/nuttx/configs/pic32-starterkit/src/Makefile index f041f9b081..0f1fd5ebc8 100644 --- a/nuttx/configs/pic32-starterkit/src/Makefile +++ b/nuttx/configs/pic32-starterkit/src/Makefile @@ -88,11 +88,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/pic32mx7mmb/src/Makefile b/nuttx/configs/pic32mx7mmb/src/Makefile index ffb83cc495..d3f84745ee 100644 --- a/nuttx/configs/pic32mx7mmb/src/Makefile +++ b/nuttx/configs/pic32mx7mmb/src/Makefile @@ -92,11 +92,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/pjrc-8051/src/Makefile b/nuttx/configs/pjrc-8051/src/Makefile index fff994b9ba..706742317d 100644 --- a/nuttx/configs/pjrc-8051/src/Makefile +++ b/nuttx/configs/pjrc-8051/src/Makefile @@ -65,11 +65,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/qemu-i486/src/Makefile b/nuttx/configs/qemu-i486/src/Makefile index d945f9ccd6..e7e9f117bd 100644 --- a/nuttx/configs/qemu-i486/src/Makefile +++ b/nuttx/configs/qemu-i486/src/Makefile @@ -72,11 +72,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/sam3u-ek/kernel/Makefile b/nuttx/configs/sam3u-ek/kernel/Makefile index 6daf62253e..e9a7ef7ffa 100644 --- a/nuttx/configs/sam3u-ek/kernel/Makefile +++ b/nuttx/configs/sam3u-ek/kernel/Makefile @@ -128,9 +128,9 @@ $(BOARD_INCLUDE)$(DELIM)user_map.h: $(TOPDIR)$(DELIM)User.map depend: .depend clean: - $(call DELFILE nuttx_user.elf) - $(call DELFILE "$(TOPDIR)$(DELIM)nuttx_user.elf") - $(call DELFILE "$(TOPDIR)$(DELIM)User.map") + $(call DELFILE, nuttx_user.elf) + $(call DELFILE, "$(TOPDIR)$(DELIM)nuttx_user.elf") + $(call DELFILE, "$(TOPDIR)$(DELIM)User.map") $(call CLEAN) distclean: clean diff --git a/nuttx/configs/sam3u-ek/src/Makefile b/nuttx/configs/sam3u-ek/src/Makefile index 08ccb2f463..381341e6a7 100644 --- a/nuttx/configs/sam3u-ek/src/Makefile +++ b/nuttx/configs/sam3u-ek/src/Makefile @@ -85,11 +85,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile index e3aa181e42..b70a6e9ce9 100644 --- a/nuttx/configs/shenzhou/src/Makefile +++ b/nuttx/configs/shenzhou/src/Makefile @@ -136,11 +136,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/sim/src/Makefile b/nuttx/configs/sim/src/Makefile index 7c5887e720..d7846788b4 100644 --- a/nuttx/configs/sim/src/Makefile +++ b/nuttx/configs/sim/src/Makefile @@ -72,11 +72,11 @@ endif depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/skp16c26/src/Makefile b/nuttx/configs/skp16c26/src/Makefile index b54b130510..da35b246c3 100644 --- a/nuttx/configs/skp16c26/src/Makefile +++ b/nuttx/configs/skp16c26/src/Makefile @@ -66,11 +66,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/stm3210e-eval/src/Makefile b/nuttx/configs/stm3210e-eval/src/Makefile index 22ff4d40bb..d2abed9da6 100644 --- a/nuttx/configs/stm3210e-eval/src/Makefile +++ b/nuttx/configs/stm3210e-eval/src/Makefile @@ -120,11 +120,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/stm3220g-eval/src/Makefile b/nuttx/configs/stm3220g-eval/src/Makefile index b30f111f28..0cff420da7 100644 --- a/nuttx/configs/stm3220g-eval/src/Makefile +++ b/nuttx/configs/stm3220g-eval/src/Makefile @@ -120,11 +120,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/stm3240g-eval/src/Makefile b/nuttx/configs/stm3240g-eval/src/Makefile index a22f75e703..5f65ae7994 100644 --- a/nuttx/configs/stm3240g-eval/src/Makefile +++ b/nuttx/configs/stm3240g-eval/src/Makefile @@ -128,11 +128,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/stm32f100rc_generic/src/Makefile b/nuttx/configs/stm32f100rc_generic/src/Makefile index f32c947d0c..8cd8a2af46 100644 --- a/nuttx/configs/stm32f100rc_generic/src/Makefile +++ b/nuttx/configs/stm32f100rc_generic/src/Makefile @@ -72,11 +72,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/stm32f4discovery/src/Makefile b/nuttx/configs/stm32f4discovery/src/Makefile index f4d5a89d9f..82ea0d1dda 100644 --- a/nuttx/configs/stm32f4discovery/src/Makefile +++ b/nuttx/configs/stm32f4discovery/src/Makefile @@ -132,11 +132,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/sure-pic32mx/src/Makefile b/nuttx/configs/sure-pic32mx/src/Makefile index dc0ee13f92..57a74ce358 100644 --- a/nuttx/configs/sure-pic32mx/src/Makefile +++ b/nuttx/configs/sure-pic32mx/src/Makefile @@ -97,11 +97,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/teensy/src/Makefile b/nuttx/configs/teensy/src/Makefile index 705315dde6..42d7d7843b 100644 --- a/nuttx/configs/teensy/src/Makefile +++ b/nuttx/configs/teensy/src/Makefile @@ -92,11 +92,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/twr-k60n512/src/Makefile b/nuttx/configs/twr-k60n512/src/Makefile index bb0dcd3e02..6ca9647b7c 100644 --- a/nuttx/configs/twr-k60n512/src/Makefile +++ b/nuttx/configs/twr-k60n512/src/Makefile @@ -94,11 +94,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/ubw32/src/Makefile b/nuttx/configs/ubw32/src/Makefile index 6cbec5db30..e35626f6e0 100644 --- a/nuttx/configs/ubw32/src/Makefile +++ b/nuttx/configs/ubw32/src/Makefile @@ -88,11 +88,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/us7032evb1/shterm/Makefile b/nuttx/configs/us7032evb1/shterm/Makefile index f290eabc36..7eba21db0f 100644 --- a/nuttx/configs/us7032evb1/shterm/Makefile +++ b/nuttx/configs/us7032evb1/shterm/Makefile @@ -47,6 +47,6 @@ $(BIN)$(EXEEXT): $(SRC) install --mode 0755 $^ $@ clean: - $(call DELFILE $(BIN)$(EXEEXT)) + $(call DELFILE, $(BIN)$(EXEEXT)) $(call DELFILE..$(DELIM)bin$(DELIM)$(BIN)$(EXEEXT)) $(call CLEAN) diff --git a/nuttx/configs/us7032evb1/src/Makefile b/nuttx/configs/us7032evb1/src/Makefile index 93a9792770..2ace3df3f9 100644 --- a/nuttx/configs/us7032evb1/src/Makefile +++ b/nuttx/configs/us7032evb1/src/Makefile @@ -66,11 +66,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/vsn/src/Makefile b/nuttx/configs/vsn/src/Makefile index 947cae18e5..a71c80c8ab 100644 --- a/nuttx/configs/vsn/src/Makefile +++ b/nuttx/configs/vsn/src/Makefile @@ -100,11 +100,11 @@ context: .context depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/xtrs/src/Makefile b/nuttx/configs/xtrs/src/Makefile index 074e5c2945..f673df5df6 100644 --- a/nuttx/configs/xtrs/src/Makefile +++ b/nuttx/configs/xtrs/src/Makefile @@ -66,11 +66,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/z16f2800100zcog/src/Makefile b/nuttx/configs/z16f2800100zcog/src/Makefile index 135dfc4774..3ce63092db 100644 --- a/nuttx/configs/z16f2800100zcog/src/Makefile +++ b/nuttx/configs/z16f2800100zcog/src/Makefile @@ -73,11 +73,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/z80sim/src/Makefile b/nuttx/configs/z80sim/src/Makefile index bc2e00715a..99d5578502 100644 --- a/nuttx/configs/z80sim/src/Makefile +++ b/nuttx/configs/z80sim/src/Makefile @@ -67,11 +67,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/z8encore000zco/src/Makefile b/nuttx/configs/z8encore000zco/src/Makefile index e034435c60..73452bfab3 100644 --- a/nuttx/configs/z8encore000zco/src/Makefile +++ b/nuttx/configs/z8encore000zco/src/Makefile @@ -73,11 +73,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/configs/z8f64200100kit/src/Makefile b/nuttx/configs/z8f64200100kit/src/Makefile index 2a53b93425..617c3db54e 100644 --- a/nuttx/configs/z8f64200100kit/src/Makefile +++ b/nuttx/configs/z8f64200100kit/src/Makefile @@ -73,11 +73,11 @@ libboard$(LIBEXT): $(OBJS) depend: .depend clean: - $(call DELFILE libboard$(LIBEXT)) + $(call DELFILE, libboard$(LIBEXT)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile index 57b2b489a2..575da606fe 100644 --- a/nuttx/drivers/Makefile +++ b/nuttx/drivers/Makefile @@ -111,11 +111,11 @@ $(BIN): $(OBJS) depend: .depend clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile index eb036fed0d..6955c164b5 100644 --- a/nuttx/fs/Makefile +++ b/nuttx/fs/Makefile @@ -130,11 +130,11 @@ $(BIN): $(OBJS) depend: .depend clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/graphics/Makefile b/nuttx/graphics/Makefile index ddcfd21d24..238e14df42 100644 --- a/nuttx/graphics/Makefile +++ b/nuttx/graphics/Makefile @@ -200,14 +200,14 @@ context: gensources clean: $(Q) $(MAKE) -C nxglib -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) $(Q) $(MAKE) -C nxfonts -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean $(Q) $(MAKE) -C nxglib -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) $(Q) $(MAKE) -C nxfonts -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/graphics/nxfonts/Makefile.sources b/nuttx/graphics/nxfonts/Makefile.sources index eeb47d1b25..76a099dcbe 100644 --- a/nuttx/graphics/nxfonts/Makefile.sources +++ b/nuttx/graphics/nxfonts/Makefile.sources @@ -181,9 +181,9 @@ $(GEN_CSRC) : $(DEPENDENCY) $(Q) rm -f $(GEN_TMP) clean: - $(call DELFILE *.i) + $(call DELFILE, *.i) $(call CLEAN) distclean: clean - $(call DELFILE nxfonts_convert_*bpp.c) - $(call DELFILE nxfonts_bitmaps_*.c) + $(call DELFILE, nxfonts_convert_*bpp.c) + $(call DELFILE, nxfonts_bitmaps_*.c) diff --git a/nuttx/graphics/nxglib/Makefile.sources b/nuttx/graphics/nxglib/Makefile.sources index bb94c1b20f..71d6e0661b 100644 --- a/nuttx/graphics/nxglib/Makefile.sources +++ b/nuttx/graphics/nxglib/Makefile.sources @@ -163,13 +163,13 @@ ifneq ($(NXGLIB_BITSPERPIXEL),) endif clean: - $(call DELFILE *.i) + $(call DELFILE, *.i) $(call CLEAN) distclean: clean - $(call DELFILE nxglib_setpixel_*bpp.c) - $(call DELFILE nxglib_fillrectangle_*bpp.c) - $(call DELFILE nxglib_getrectangle_*bpp.c) - $(call DELFILE nxglib_filltrapezoid_*bpp.c) - $(call DELFILE nxglib_moverectangle_*bpp.c) - $(call DELFILE nxglib_copyrectangle_*bpp.c) + $(call DELFILE, nxglib_setpixel_*bpp.c) + $(call DELFILE, nxglib_fillrectangle_*bpp.c) + $(call DELFILE, nxglib_getrectangle_*bpp.c) + $(call DELFILE, nxglib_filltrapezoid_*bpp.c) + $(call DELFILE, nxglib_moverectangle_*bpp.c) + $(call DELFILE, nxglib_copyrectangle_*bpp.c) diff --git a/nuttx/libc/Makefile b/nuttx/libc/Makefile index e7dec47768..22dbba1d91 100644 --- a/nuttx/libc/Makefile +++ b/nuttx/libc/Makefile @@ -114,7 +114,7 @@ else $(Q) ( if [ -f .userlib ]; then rm -f *$(OBJEXT); fi ) endif endif - $(call DELFILE .userlib) + $(call DELFILE, .userlib) # Clean kernel-mode temporary files (retaining the KBIN binary) @@ -126,20 +126,20 @@ else $(Q) ( if [ -f .kernlib ]; then rm -f *$(OBJEXT); fi ) endif endif - $(call DELFILE .kernlib) + $(call DELFILE, .kernlib) # Really clean everything clean: uclean kclean - $(call DELFILE $(BIN)) - $(call DELFILE $(UBIN)) - $(call DELFILE $(KBIN)) + $(call DELFILE, $(BIN)) + $(call DELFILE, $(UBIN)) + $(call DELFILE, $(KBIN)) $(call CLEAN) # Deep clean -- removes all traces of the configuration distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile index cc55784274..2ab146e9cc 100644 --- a/nuttx/libxx/Makefile +++ b/nuttx/libxx/Makefile @@ -105,11 +105,11 @@ $(BIN): $(OBJS) depend: .depend clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile index b14560ce36..da41f9f57b 100644 --- a/nuttx/mm/Makefile +++ b/nuttx/mm/Makefile @@ -70,11 +70,11 @@ $(BIN): $(OBJS) depend: .depend clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/mm/Makefile.test b/nuttx/mm/Makefile.test index e0f1109d86..2ae9dcb883 100644 --- a/nuttx/mm/Makefile.test +++ b/nuttx/mm/Makefile.test @@ -63,6 +63,6 @@ $(BIN): $(OBJS) $(Q) $(LD) $(LDFLAGS) $(OBJS) $(LIBS) -o $@ clean: - $(call DELFILE $(BIN)) - $(call DELFILE *.o1) + $(call DELFILE, $(BIN)) + $(call DELFILE, *.o1) $(call CLEAN) diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile index 29148fafac..74540b67d4 100644 --- a/nuttx/net/Makefile +++ b/nuttx/net/Makefile @@ -111,11 +111,11 @@ endif depend: .depend clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index ac6489b184..9b15108f4d 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -206,11 +206,11 @@ $(BIN): $(OBJS) depend: .depend clean: - $(call DELFILE $(BIN)) + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean - $(call DELFILE Make.dep) - $(call DELFILE .depend) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/syscall/Makefile b/nuttx/syscall/Makefile index 15e06e097b..ec2627b464 100644 --- a/nuttx/syscall/Makefile +++ b/nuttx/syscall/Makefile @@ -95,20 +95,20 @@ $(MKSYSCALL): context: $(MKSYSCALL) .context clean: - $(call DELFILE $(BIN1)) - $(call DELFILE $(BIN2)) + $(call DELFILE, $(BIN1)) + $(call DELFILE, $(BIN2)) ifneq ($(OBJEXT),) - $(call DELFILE proxies$(DELIM)*$(OBJEXT)) - $(call DELFILE stubs$(DELIM)*$(OBJEXT)) + $(call DELFILE, proxies$(DELIM)*$(OBJEXT)) + $(call DELFILE, stubs$(DELIM)*$(OBJEXT)) endif $(call CLEAN) distclean: clean - $(call DELFILE .context) - $(call DELFILE Make.dep) - $(call DELFILE .depend) - $(call DELFILE proxies$(DELIM)*.c) - $(call DELFILE stubs$(DELIM)*.c) + $(call DELFILE, .context) + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + $(call DELFILE, proxies$(DELIM)*.c) + $(call DELFILE, stubs$(DELIM)*.c) -include Make.dep diff --git a/nuttx/tools/Makefile.host b/nuttx/tools/Makefile.host index 559192c5e3..a661424dc8 100644 --- a/nuttx/tools/Makefile.host +++ b/nuttx/tools/Makefile.host @@ -122,17 +122,17 @@ mkdeps: mkdeps$(HOSTEXEEXT) endif clean: - $(call DELFILE mkdeps) - $(call DELFILE mkdeps.exe) - $(call DELFILE mkconfig) - $(call DELFILE mkconfig.exe) - $(call DELFILE Make.dep) - $(call DELFILE mksyscall) - $(call DELFILE mksyscall.exe) - $(call DELFILE mkversion) - $(call DELFILE mkversion.exe) - $(call DELFILE bdf-converter) - $(call DELFILE bdf-converter.exe) + $(call DELFILE, mkdeps) + $(call DELFILE, mkdeps.exe) + $(call DELFILE, mkconfig) + $(call DELFILE, mkconfig.exe) + $(call DELFILE, Make.dep) + $(call DELFILE, mksyscall) + $(call DELFILE, mksyscall.exe) + $(call DELFILE, mkversion) + $(call DELFILE, mkversion.exe) + $(call DELFILE, bdf-converter) + $(call DELFILE, bdf-converter.exe) ifneq ($(CONFIG_WINDOWS_NATIVE),y) $(Q) rm -rf *.dSYM endif From 8c8436926328e233a50e83c838f3659612418263 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 20 Nov 2012 19:59:40 +0000 Subject: [PATCH 145/206] Change how UARTs are enabled for i.MX, M16C, and ez80 to make them compatible with other chips git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5374 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/imx/Kconfig | 19 +++- nuttx/arch/arm/src/imx/imx_serial.c | 66 ++++++------ nuttx/arch/arm/src/lm3s/lm3s_lowputc.c | 16 ++- nuttx/arch/arm/src/lm3s/lm3s_serial.c | 62 ++++++----- nuttx/arch/sh/src/m16c/Kconfig | 16 ++- nuttx/arch/sh/src/m16c/m16c_lowputc.c | 8 +- nuttx/arch/sh/src/m16c/m16c_serial.c | 102 +++++++++--------- nuttx/arch/z80/Kconfig | 9 +- nuttx/arch/z80/src/ez80/Kconfig | 16 +++ nuttx/arch/z80/src/ez80/ez80_lowuart.c | 10 +- nuttx/arch/z80/src/ez80/ez80_serial.c | 30 +++--- nuttx/configs/eagle100/httpd/defconfig | 4 +- nuttx/configs/eagle100/nettest/defconfig | 4 +- nuttx/configs/eagle100/nsh/defconfig | 4 +- nuttx/configs/eagle100/nxflat/defconfig | 4 +- nuttx/configs/eagle100/ostest/defconfig | 4 +- nuttx/configs/eagle100/thttpd/defconfig | 4 +- nuttx/configs/ekk-lm3s9b96/nsh/defconfig | 6 +- nuttx/configs/ekk-lm3s9b96/ostest/defconfig | 6 +- .../configs/ez80f910200kitg/ostest/defconfig | 4 +- nuttx/configs/ez80f910200zco/dhcpd/defconfig | 4 +- nuttx/configs/ez80f910200zco/httpd/defconfig | 4 +- .../configs/ez80f910200zco/nettest/defconfig | 4 +- nuttx/configs/ez80f910200zco/nsh/defconfig | 4 +- nuttx/configs/ez80f910200zco/ostest/defconfig | 4 +- nuttx/configs/ez80f910200zco/poll/defconfig | 4 +- nuttx/configs/lm3s6432-s2e/nsh/defconfig | 6 +- nuttx/configs/lm3s6432-s2e/ostest/defconfig | 6 +- nuttx/configs/lm3s6432-s2e/src/up_boot.c | 2 +- nuttx/configs/lm3s6965-ek/nsh/defconfig | 6 +- nuttx/configs/lm3s6965-ek/nx/defconfig | 6 +- nuttx/configs/lm3s6965-ek/ostest/defconfig | 6 +- nuttx/configs/lm3s8962-ek/nsh/defconfig | 6 +- nuttx/configs/lm3s8962-ek/nx/defconfig | 6 +- nuttx/configs/lm3s8962-ek/ostest/defconfig | 6 +- nuttx/configs/mx1ads/ostest/defconfig | 6 +- nuttx/configs/skp16c26/include/board.h | 2 +- nuttx/configs/skp16c26/ostest/defconfig | 6 +- nuttx/configs/skp16c26/src/up_lcdconsole.c | 6 +- 39 files changed, 268 insertions(+), 220 deletions(-) diff --git a/nuttx/arch/arm/src/imx/Kconfig b/nuttx/arch/arm/src/imx/Kconfig index 879f50ef7d..e1081aefe7 100644 --- a/nuttx/arch/arm/src/imx/Kconfig +++ b/nuttx/arch/arm/src/imx/Kconfig @@ -3,4 +3,21 @@ # see misc/tools/kconfig-language.txt. # -comment "i.MX Configuration Options" +if ARCH_CHIP_IMX + +config IMX_UART0 + bool "UART0" + select ARCH_HAVE_UART0 + default n + +config IMX_UART1 + bool "UART1" + select ARCH_HAVE_UART1 + default n + +config IMX_UART2 + bool "UART2" + select ARCH_HAVE_UART2 + default n + +endif diff --git a/nuttx/arch/arm/src/imx/imx_serial.c b/nuttx/arch/arm/src/imx/imx_serial.c index 26e6592be8..07c9312f49 100644 --- a/nuttx/arch/arm/src/imx/imx_serial.c +++ b/nuttx/arch/arm/src/imx/imx_serial.c @@ -71,8 +71,8 @@ /* The i.MXL chip has only two UARTs */ -#if defined(CONFIG_ARCH_CHIP_IMXL) && !defined(CONFIG_UART3_DISABLE) -# define CONFIG_UART3_DISABLE 1 +#if defined(CONFIG_ARCH_CHIP_IMXL) && defined(CONFIG_IMX_UART3) +# undef CONFIG_IMX_UART3 #endif /**************************************************************************** @@ -144,24 +144,24 @@ struct uart_ops_s g_uart_ops = /* I/O buffers */ -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_IMX_UART1 static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE]; static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE]; #endif -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_IMX_UART2 static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE]; static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE]; #endif -#ifndef CONFIG_UART3_DISABLE +#ifdef CONFIG_IMX_UART3 static char g_uart3rxbuffer[CONFIG_UART2_RXBUFSIZE]; static char g_uart3txbuffer[CONFIG_UART2_TXBUFSIZE]; #endif /* This describes the state of the IMX uart1 port. */ -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_IMX_UART1 static struct up_dev_s g_uart1priv = { .uartbase = IMX_UART1_VBASE, @@ -196,7 +196,7 @@ static uart_dev_t g_uart1port = /* This describes the state of the IMX uart2 port. */ -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_IMX_UART2 static struct up_dev_s g_uart2priv = { .uartbase = IMX_UART2_VBASE, @@ -229,7 +229,7 @@ static uart_dev_t g_uart2port = }; #endif -#ifndef CONFIG_UART3_DISABLE +#ifdef CONFIG_IMX_UART3 static struct up_dev_s g_uart3priv = { .uartbase = IMX_UART3_REGISTER_BASE, @@ -264,19 +264,19 @@ static uart_dev_t g_uart3port = /* Now, which one with be tty0/console and which tty1 and tty2? */ -#if defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE) +#if defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_IMX_UART1) # define CONSOLE_DEV g_uart1port /* UART1 is /dev/console */ # undef CONFIG_UART2_SERIAL_CONSOLE # undef CONFIG_UART3_SERIAL_CONSOLE # define TTYS0_DEV g_uart1port /* UART1 is /dev/ttyS0 */ -# if !defined(CONFIG_UART2_DISABLE) +# if defined(CONFIG_IMX_UART2) # define TTYS1_DEV g_uart2port /* UART2 is /dev/ttyS1 */ -# if !defined(CONFIG_UART3_DISABLE) +# if defined(CONFIG_IMX_UART3) # define TTYS2_DEV g_uart3port /* UART3 is /dev/ttyS2 */ # else # undef TTYS2_DEV /* No /dev/ttyS2 */ # endif -# elif !defined(CONFIG_UART3_DISABLE) +# elif defined(CONFIG_IMX_UART3) # define TTYS1_DEV g_uart3port /* UART3 is /dev/ttyS1 */ # undef TTYS2_DEV /* No /dev/ttyS2 */ # else @@ -284,38 +284,38 @@ static uart_dev_t g_uart3port = # undef TTYS2_DEV /* No /dev/ttyS2 */ # endif -#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && !defined(CONFIG_UART2_DISABLE) +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_IMX_UART2) # define CONSOLE_DEV g_uart2port /* UART2 is /dev/console */ # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART3_SERIAL_CONSOLE # define TTYS0_DEV g_uart2port /* UART2 is /dev/ttyS0 */ -# if !defined(CONFIG_UART1_DISABLE) +# if defined(CONFIG_IMX_UART1) # define TTYS1_DEV g_uart1port /* UART1 is /dev/ttyS1 */ -# if !defined(CONFIG_UART3_DISABLE) +# if defined(CONFIG_IMX_UART3) # define TTYS2_DEV g_uart3port /* UART3 is /dev/ttyS2 */ # else # undef TTYS2_DEV /* No /dev/ttyS2 */ # endif -# elif !defined(CONFIG_UART3_DISABLE) +# elif defined(CONFIG_IMX_UART3) # define TTYS1_DEV g_uart3port /* UART3 is /dev/ttyS1 */ # else # undef TTYS1_DEV /* No /dev/ttyS1 */ # undef TTYS2_DEV /* No /dev/ttyS2 */ # endif -#elif defined(CONFIG_UART3_SERIAL_CONSOLE) && !defined(CONFIG_UART3_DISABLE) +#elif defined(CONFIG_UART3_SERIAL_CONSOLE) && defined(CONFIG_IMX_UART3) # define CONSOLE_DEV g_uart3port /* UART3 is /dev/console */ # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE # define TTYS0_DEV g_uart3port /* UART3 is /dev/ttyS0 */ -# if !defined(CONFIG_UART1_DISABLE) +# if defined(CONFIG_IMX_UART1) # define TTYS1_DEV g_uart1port /* UART1 is /dev/ttyS1 */ -# if !defined(CONFIG_UART2_DISABLE) +# if defined(CONFIG_IMX_UART2) # define TTYS2_DEV g_uart2port /* UART2 is /dev/ttyS2 */ # else # undef TTYS2_DEV /* No /dev/ttyS2 */ # endif -# elif !defined(CONFIG_UART2_DISABLE) +# elif defined(CONFIG_IMX_UART2) # define TTYS1_DEV g_uart2port /* UART2 is /dev/ttyS1 */ # undef TTYS2_DEV /* No /dev/ttyS2 */ # else @@ -329,16 +329,16 @@ static uart_dev_t g_uart3port = # undef CONFIG_UART2_SERIAL_CONSOLE # undef CONFIG_UART3_SERIAL_CONSOLE -# if !defined(CONFIG_UART1_DISABLE) +# if defined(CONFIG_IMX_UART1) # define TTYS0_DEV g_uart1port /* UART1 is /dev/ttyS0 */ -# if !defined(CONFIG_UART2_DISABLE) +# if defined(CONFIG_IMX_UART2) # define TTYS1_DEV g_uart2port /* UART2 is /dev/ttyS1 */ -# if !defined(CONFIG_UART3_DISABLE) +# if defined(CONFIG_IMX_UART3) # define TTYS2_DEV g_uart3port /* UART3 is /dev/ttyS2 */ # else # undef TTYS2_DEV /* No /dev/ttyS2 */ # endif -# elif !defined(CONFIG_UART3_DISABLE) +# elif defined(CONFIG_IMX_UART3) # define TTYS1_DEV g_uart3port /* UART3 is /dev/ttyS1 */ # undef TTYS2_DEV /* No /dev/ttyS2 */ # else @@ -346,16 +346,16 @@ static uart_dev_t g_uart3port = # undef TTYS2_DEV /* No /dev/ttyS2 */ # endif -# elif !defined(CONFIG_UART2_DISABLE) +# elif defined(CONFIG_IMX_UART2) # define TTYS0_DEV g_uart2port /* UART2 is /dev/ttyS0 */ # undef TTYS2_DEV /* No /dev/ttyS2 */ -# if !defined(CONFIG_UART3_DISABLE) +# if defined(CONFIG_IMX_UART3) # define TTYS1_DEV g_uart2port /* UART2 is /dev/ttyS1 */ # else # undef TTYS1_DEV /* No /dev/ttyS1 */ # endif -# elif !defined(CONFIG_UART3_DISABLE) +# elif defined(CONFIG_IMX_UART3) # define TTYS0_DEV g_uart3port /* UART3 is /dev/ttyS0 */ # undef TTYS1_DEV /* No /dev/ttyS1 */ # undef TTYS2_DEV /* No /dev/ttyS2 */ @@ -765,7 +765,7 @@ static inline struct uart_dev_s *up_mapirq(int irq) switch (irq) { -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_IMX_UART1 #if defined(CONFIG_ARCH_CHIP_IMX1) || defined(CONFIG_ARCH_CHIP_IMXL) case IMX_IRQ_UART1RX: case IMX_IRQ_UART1TX: @@ -776,7 +776,7 @@ static inline struct uart_dev_s *up_mapirq(int irq) break; #endif -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_IMX_UART2 #if defined(CONFIG_ARCH_CHIP_IMX1) || defined(CONFIG_ARCH_CHIP_IMXL) case IMX_IRQ_UART2RX: case IMX_IRQ_UART2TX: @@ -787,7 +787,7 @@ static inline struct uart_dev_s *up_mapirq(int irq) break; #endif -#ifndef CONFIG_UART3_DISABLE +#ifdef CONFIG_IMX_UART3 #if defined(CONFIG_ARCH_CHIP_IMX1) || defined(CONFIG_ARCH_CHIP_IMXL) case IMX_IRQ_UART3RX: case IMX_IRQ_UART3TX: @@ -1068,7 +1068,7 @@ void up_earlyserialinit(void) { /* Configure and disable the UART1 */ -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_IMX_UART1 up_serialout(&g_uart1priv, UART_UCR1, 0); up_serialout(&g_uart1priv, UART_UCR2, 0); @@ -1082,7 +1082,7 @@ void up_earlyserialinit(void) /* Configure and disable the UART2 */ -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_IMX_UART2 up_serialout(&g_uart2priv, UART_UCR1, 0); up_serialout(&g_uart2priv, UART_UCR2, 0); @@ -1098,7 +1098,7 @@ void up_earlyserialinit(void) /* Configure and disable the UART3 */ -#ifndef CONFIG_UART3_DISABLE +#ifdef CONFIG_IMX_UART3 up_serialout(&g_uart3priv, UART_UCR1, 0); up_serialout(&g_uart3priv, UART_UCR2, 0); diff --git a/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c b/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c index 69ac56a9d3..b1cb21b2c2 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c @@ -55,28 +55,26 @@ /* Configuration **********************************************************/ #if LM3S_NUARTS < 2 -# undef CONFIG_UART1_DISABLE +# undef CONFIG_LM3S_UART1 # undef CONFIG_UART1_SERIAL_CONSOLE -# define CONFIG_UART1_DISABLE 1 #endif #if LM3S_NUARTS < 3 -# undef CONFIG_UART2_DISABLE +# undef CONFIG_LM3S_UART2 # undef CONFIG_UART2_SERIAL_CONSOLE -# define CONFIG_UART2_DISABLE 1 #endif /* Is there a serial console? */ -#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_UART0_DISABLE) +#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART0) # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE # define HAVE_CONSOLE 1 -#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE) +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART1) # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE # define HAVE_CONSOLE 1 -#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && !defined(CONFIG_UART2_DISABLE) +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART2) # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART1_SERIAL_CONSOLE # define HAVE_CONSOLE 1 @@ -258,7 +256,7 @@ void up_lowsetup(void) * this pin configuration -- whether or not a serial console is selected. */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_LM3S_UART0 regval = getreg32(LM3S_SYSCON_RCGC1); regval |= SYSCON_RCGC1_UART0; putreg32(regval, LM3S_SYSCON_RCGC1); @@ -267,7 +265,7 @@ void up_lowsetup(void) lm3s_configgpio(GPIO_UART0_TX); #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_LM3S_UART1 regval = getreg32(LM3S_SYSCON_RCGC1); regval |= SYSCON_RCGC1_UART1; putreg32(regval, LM3S_SYSCON_RCGC1); diff --git a/nuttx/arch/arm/src/lm3s/lm3s_serial.c b/nuttx/arch/arm/src/lm3s/lm3s_serial.c index 51f9ce955f..7ed9b6fa84 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_serial.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_serial.c @@ -67,34 +67,32 @@ /* Some sanity checks *******************************************************/ #if LM3S_NUARTS < 2 -# undef CONFIG_UART1_DISABLE +# undef CONFIG_LM3S_UART1 # undef CONFIG_UART1_SERIAL_CONSOLE -# define CONFIG_UART1_DISABLE 1 #endif #if LM3S_NUARTS < 3 -# undef CONFIG_UART2_DISABLE +# undef CONFIG_LM3S_UART2 # undef CONFIG_UART2_SERIAL_CONSOLE -# define CONFIG_UART2_DISABLE 1 #endif /* Is there a UART enabled? */ -#if defined(CONFIG_UART0_DISABLE) && defined(CONFIG_UART1_DISABLE) +#if !defined(CONFIG_LM3S_UART0) && !defined(CONFIG_LM3S_UART1) && !defined(CONFIG_LM3S_UART2) # error "No UARTs enabled" #endif /* Is there a serial console? */ -#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_UART0_DISABLE) +#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART0) # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE # define HAVE_CONSOLE 1 -#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE) +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART1) # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE # define HAVE_CONSOLE 1 -#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && !defined(CONFIG_UART2_DISABLE) +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART2) # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART1_SERIAL_CONSOLE # define HAVE_CONSOLE 1 @@ -117,16 +115,16 @@ #if defined(CONFIG_UART0_SERIAL_CONSOLE) # define CONSOLE_DEV g_uart0port /* UART0 is console */ # define TTYS0_DEV g_uart0port /* UART0 is ttyS0 */ -# ifndef CONFIG_UART1_DISABLE +# ifdef CONFIG_LM3S_UART1 # define TTYS1_DEV g_uart1port /* UART1 is ttyS1 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_LM3S_UART2 # define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */ # else # undef TTYS2_DEV /* No ttyS2 */ # endif # else # undef TTYS2_DEV /* No ttyS2 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_LM3S_UART2 # define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */ # else # undef TTYS1_DEV /* No ttyS1 */ @@ -135,16 +133,16 @@ #elif defined(CONFIG_UART1_SERIAL_CONSOLE) # define CONSOLE_DEV g_uart1port /* UART1 is console */ # define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */ -# ifndef CONFIG_UART0_DISABLE +# ifdef CONFIG_LM3S_UART0 # define TTYS1_DEV g_uart0port /* UART0 is ttyS1 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_LM3S_UART2 # define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */ # else # undef TTYS2_DEV /* No ttyS2 */ # endif # else # undef TTYS2_DEV /* No ttyS2 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_LM3S_UART2 # define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */ # else # undef TTYS1_DEV /* No ttyS1 */ @@ -153,49 +151,49 @@ #elif defined(CONFIG_UART2_SERIAL_CONSOLE) # define CONSOLE_DEV g_uart2port /* UART2 is console */ # define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */ -# ifndef CONFIG_UART0_DISABLE +# ifdef CONFIG_LM3S_UART0 # define TTYS1_DEV g_uart0port /* UART0 is ttyS1 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_LM3S_UART2 # define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */ # else # undef TTYS2_DEV /* No ttyS2 */ # endif # else # undef TTYS2_DEV /* No ttyS2 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_LM3S_UART2 # define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */ # else # undef TTYS1_DEV /* No ttyS1 */ # endif # endif -#elif !defined(CONFIG_UART0_DISABLE) +#elifdefined(CONFIG_LM3S_UART0) # undef CONSOLE_DEV /* No console device */ # define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */ -# ifndef CONFIG_UART1_DISABLE +# ifdef CONFIG_LM3S_UART1 # define TTYS1_DEV g_uart1port /* UART1 is ttyS1 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_LM3S_UART2 # define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */ # else # undef TTYS2_DEV /* No ttyS2 */ # endif # else # undef TTYS2_DEV /* No ttyS2 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_LM3S_UART2 # define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */ # else # undef TTYS1_DEV /* No ttyS1 */ # endif # endif -#elif !defined(CONFIG_UART1_DISABLE) +#elifdefined(CONFIG_LM3S_UART1) # undef CONSOLE_DEV /* No console device */ # define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */ # undef TTYS2_DEV /* No ttyS2 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_LM3S_UART2 # define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */ # else # undef TTYS1_DEV /* No ttyS1 */ # endif -#elif !defined(CONFIG_UART2_DISABLE) +#elifdefined(CONFIG_LM3S_UART2) # undef CONSOLE_DEV /* No console device */ # define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */ # undef TTYS1_DEV /* No ttyS1 */ @@ -263,22 +261,22 @@ struct uart_ops_s g_uart_ops = /* I/O buffers */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_LM3S_UART0 static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE]; static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE]; #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_LM3S_UART1 static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE]; static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE]; #endif -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_LM3S_UART2 static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE]; static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE]; #endif /* This describes the state of the LM3S uart0 port. */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_LM3S_UART0 static struct up_dev_s g_uart0priv = { .uartbase = LM3S_UART0_BASE, @@ -308,7 +306,7 @@ static uart_dev_t g_uart0port = /* This describes the state of the LM3S uart1 port. */ -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_LM3S_UART1 static struct up_dev_s g_uart1priv = { .uartbase = LM3S_UART1_BASE, @@ -338,7 +336,7 @@ static uart_dev_t g_uart1port = /* This describes the state of the LM3S uart1 port. */ -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_LM3S_UART2 static struct up_dev_s g_uart2priv = { .uartbase = LM3S_UART2_BASE, @@ -688,14 +686,14 @@ static int up_interrupt(int irq, void *context) int passes; bool handled; -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_LM3S_UART0 if (g_uart0priv.irq == irq) { dev = &g_uart0port; } else #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_LM3S_UART1 if (g_uart1priv.irq == irq) { dev = &g_uart1port; diff --git a/nuttx/arch/sh/src/m16c/Kconfig b/nuttx/arch/sh/src/m16c/Kconfig index 56db601be2..1b7318e20a 100644 --- a/nuttx/arch/sh/src/m16c/Kconfig +++ b/nuttx/arch/sh/src/m16c/Kconfig @@ -4,6 +4,20 @@ # if ARCH_M16C -comment "M16C Configuration Options" + +config M16C_UART0 + bool "UART0" + select ARCH_HAVE_UART0 + default n + +config M16C_UART1 + bool "UART1" + select ARCH_HAVE_UART1 + default n + +config M16C_UART2 + bool "UART2" + select ARCH_HAVE_UART2 + default n endif diff --git a/nuttx/arch/sh/src/m16c/m16c_lowputc.c b/nuttx/arch/sh/src/m16c/m16c_lowputc.c index a473351f3f..8d55d361f0 100644 --- a/nuttx/arch/sh/src/m16c/m16c_lowputc.c +++ b/nuttx/arch/sh/src/m16c/m16c_lowputc.c @@ -63,7 +63,7 @@ * not have serial ports but supports stdout through, say, an LCD. */ -#if defined(CONFIG_UART0_DISABLE) || defined(CONFIG_UART1_DISABLE) || defined(CONFIG_UART2_DISABLE) +#if defined(CONFIG_M16C_UART0) || defined(CONFIG_M16C_UART1) || defined(CONFIG_M16C_UART2) # define HAVE_SERIAL #else # undef HAVE_SERIAL @@ -71,15 +71,15 @@ /* Is one of the serial ports a console? */ -#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_UART0_DISABLE) +#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_M16C_UART0) # define HAVE_SERIALCONSOLE 1 # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE -#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE) +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_M16C_UART1) # define HAVE_SERIALCONSOLE 1 # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE -#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && !defined(CONFIG_UART2_DISABLE) +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_M16C_UART2) # define HAVE_SERIALCONSOLE 1 # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART1_SERIAL_CONSOLE diff --git a/nuttx/arch/sh/src/m16c/m16c_serial.c b/nuttx/arch/sh/src/m16c/m16c_serial.c index 0027d423a4..a725d6217c 100644 --- a/nuttx/arch/sh/src/m16c/m16c_serial.c +++ b/nuttx/arch/sh/src/m16c/m16c_serial.c @@ -63,7 +63,7 @@ * not have serial ports but supports a console through, say, an LCD. */ -#if !defined(CONFIG_UART0_DISABLE) && !defined(CONFIG_UART1_DISABLE) && !defined(CONFIG_UART2_DISABLE) +#if defined(CONFIG_M16C_UART0) || defined(CONFIG_M16C_UART1) || defined(CONFIG_M16C_UART2) /**************************************************************************** * Definitions @@ -100,24 +100,24 @@ /* Are there any UARTs? */ -#if defined(CONFIG_UART0_DISABLE) && defined(CONFIG_UART1_DISABLE) && defined(CONFIG_UART2_DISABLE) +#if !defined(CONFIG_M16C_UART0) && !defined(CONFIG_M16C_UART1) && !defined(CONFIG_M16C_UART2) # ifdef USE_SERIALDRIVER -# error "Serial driver selected, but UARTs not enabled" +# error "Serial driver selected, but No UARTs is enabled" # undef USE_SERIALDRIVER # endif #endif /* Is there a serial console? */ -#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_UART0_DISABLE) +#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_M16C_UART0) # define HAVE_SERIALCONSOLE 1 # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE -#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE) +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_M16C_UART1) # define HAVE_SERIALCONSOLE 1 # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE -#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && !defined(CONFIG_UART2_DISABLE) +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_M16C_UART2) # define HAVE_SERIALCONSOLE 1 # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART1_SERIAL_CONSOLE @@ -141,18 +141,18 @@ /* Which UART with be tty0/console and which tty1 and tty2? */ -/* CONFIG_UART0_SERIAL_CONSOLE (implies CONFIG_UART0_DISABLE also un-defined) */ +/* CONFIG_UART0_SERIAL_CONSOLE (implies CONFIG_M16C_UART0 also defined) */ #if defined(CONFIG_UART0_SERIAL_CONSOLE) # define CONSOLE_DEV g_uart0port /* UART0 is console */ # define TTYS0_DEV g_uart0port /* UART0 is tty0 */ -# ifndef CONFIG_UART1_DISABLE +# ifdef CONFIG_M16C_UART1 # define TTYS1_DEV g_uart1port /* UART1 is tty1 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_M16C_UART2 # define TTYS2_DEV g_uart2port /* UART2 is tty2 */ # endif # else -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_M16C_UART2 # define TTYS2_DEV g_uart2port /* UART2 is tty1 */ # else # undef TTYS1_DEV /* No tty1 */ @@ -160,18 +160,18 @@ # undef TTYS2_DEV /* No tty2 */ # endif -/* CONFIG_UART1_SERIAL_CONSOLE (implies CONFIG_UART1_DISABLE also un-defined) */ +/* CONFIG_UART1_SERIAL_CONSOLE (implies CONFIG_M16C_UART1 also defined) */ #elif defined(CONFIG_UART1_SERIAL_CONSOLE) # define CONSOLE_DEV g_uart1port /* UART1 is console */ # define TTYS0_DEV g_uart1port /* UART1 is tty0 */ -# ifndef CONFIG_UART0_DISABLE +# ifdef CONFIG_M16C_UART0 # define TTYS1_DEV g_uart0port /* UART0 is tty1 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_M16C_UART2 # define TTYS2_DEV g_uart2port /* UART2 is tty2 */ # endif # else -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_M16C_UART2 # define TTYS2_DEV g_uart2port /* UART2 is tty1 */ # else # undef TTYS1_DEV /* No tty1 */ @@ -179,18 +179,18 @@ # undef TTYS2_DEV /* No tty2 */ # endif -/* CONFIG_UART2_SERIAL_CONSOLE (implies CONFIG_UART2_DISABLE also un-defined) */ +/* CONFIG_UART2_SERIAL_CONSOLE (implies CONFIG_M16C_UART2 also defined) */ #elif defined(CONFIG_UART2_SERIAL_CONSOLE) # define CONSOLE_DEV g_uart2port /* UART2 is console */ # define TTYS0_DEV g_uart2port /* UART2 is tty0 */ -# ifndef CONFIG_UART0_DISABLE +# ifdef CONFIG_M16C_UART0 # define TTYS1_DEV g_uart0port /* UART0 is tty1 */ -# ifndef CONFIG_UART1_DISABLE +# ifdef CONFIG_M16C_UART1 # define TTYS2_DEV g_uart1port /* UART1 is tty2 */ # endif # else -# ifndef CONFIG_UART1_DISABLE +# ifdef CONFIG_M16C_UART1 # define TTYS1_DEV g_uart1port /* UART1 is tty1 */ # else # undef TTYS1_DEV /* No tty1 */ @@ -198,18 +198,18 @@ # undef TTYS2_DEV /* No tty2 */ # endif -/* No console, at least one of CONFIG_UART0/1/2_DISABLE defined */ +/* No console, at least one of CONFIG_M16C_UART0/1/2 defined */ -#elif !defined(CONFIG_UART0_DISABLE) +#elif defined(CONFIG_M16C_UART0) # undef CONSOLE_DEV /* No console */ # define TTYS0_DEV g_uart0port /* UART0 is tty0 */ -# ifndef CONFIG_UART1_DISABLE +# ifdef CONFIG_M16C_UART1 # define TTYS1_DEV g_uart1port /* UART1 is tty1 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_M16C_UART2 # define TTYS2_DEV g_uart2port /* UART2 is tty2 */ # endif # else -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_M16C_UART2 # define TTYS1_DEV g_uart1port /* UART2 is tty1 */ # else # undef TTYS1_DEV /* No tty1 */ @@ -217,17 +217,17 @@ # undef TTYS2_DEV /* No tty2 */ # endif -elif !defined(CONFIG_UART1_DISABLE) +elif defined(CONFIG_M16C_UART1) # undef CONSOLE_DEV /* No console */ # undef TTYS2_DEV /* No tty2 */ # define TTYS0_DEV g_uart1port /* UART1 is tty0 */ -# ifndef CONFIG_UART2_DISABLE +# ifdef CONFIG_M16C_UART2 # define TTYS1_DEV g_uart2port /* UART2 is tty1 */ # else # undef TTYS1_DEV /* No tty1 */ # endif -/* Otherwise, there is no console and only CONFIG_UART2_DISABLE is un-defined */ +/* Otherwise, there is no console and only CONFIG_M16C_UART2 is defined */ #else # undef CONSOLE_DEV /* No console */ @@ -300,22 +300,22 @@ struct uart_ops_s g_uart_ops = /* I/O buffers */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_M16C_UART0 static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE]; static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE]; #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_M16C_UART1 static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE]; static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE]; #endif -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_M16C_UART2 static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE]; static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE]; #endif /* This describes the state of the M16C UART0 port. */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_M16C_UART0 static struct up_dev_s g_uart0priv = { .baud = CONFIG_UART0_BAUD, @@ -347,7 +347,7 @@ static uart_dev_t g_uart0port = /* This describes the state of the M16C UART1 port. */ -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_M16C_UART1 static struct up_dev_s g_uart1priv = { .baud = CONFIG_UART1_BAUD, @@ -379,7 +379,7 @@ static uart_dev_t g_uart1port = /* This describes the state of the M16C UART2 port. */ -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_M16C_UART2 static struct up_dev_s g_uart2priv = { .baud = CONFIG_UART2_BAUD, @@ -558,7 +558,7 @@ static int up_setup(struct uart_dev_s *dev) /* Set interrupt cause=TX complete and continuous receive mode */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_M16C_UART0 if (priv->uartno == 0) { regval = getreg8(M16C_UCON); @@ -567,7 +567,7 @@ static int up_setup(struct uart_dev_s *dev) } else #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_M16C_UART1 if (priv->uartno == 1) { regval = getreg8(M16C_UCON); @@ -576,7 +576,7 @@ static int up_setup(struct uart_dev_s *dev) } else #endif -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_M16C_UART2 if (priv->uartno == 2) { regval = getreg8(M16C_U2C1); @@ -632,7 +632,7 @@ static int up_setup(struct uart_dev_s *dev) /* Set port direction registers for Rx/TX pins */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_M16C_UART0 if (priv->uartno == 0) { regval = getreg8(M16C_PD6); @@ -642,7 +642,7 @@ static int up_setup(struct uart_dev_s *dev) } else #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_M16C_UART1 if (priv->uartno == 1) { regval = getreg8(M16C_PD6); @@ -652,7 +652,7 @@ static int up_setup(struct uart_dev_s *dev) } else #endif -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_M16C_UART2 if (priv->uartno == 2) { regval = getreg8(M16C_PD7); @@ -766,21 +766,21 @@ static int up_rcvinterrupt(int irq, void *context) { struct uart_dev_s *dev = NULL; -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_M16C_UART0 if (irq == g_uart0priv.rcvirq) { dev = &g_uart0port; } else #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_M16C_UART1 if (irq == g_uart1priv.rcvirq) { dev = &g_uart1port; } else #endif -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_M16C_UART2 if (irq = g_uart2priv.rcvirq) { dev = &g_uart2port; @@ -845,7 +845,7 @@ static void m16c_rxint(struct up_dev_s *dev, bool enable) /* Pick the SxTIC register and enable interrupt priority */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_M16C_UART0 if (dev->uartno == 0) { regaddr = M16C_S0RIC; @@ -853,7 +853,7 @@ static void m16c_rxint(struct up_dev_s *dev, bool enable) } else #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_M16C_UART1 if (dev->uartno == 1) { regaddr = M16C_S1RIC; @@ -861,7 +861,7 @@ static void m16c_rxint(struct up_dev_s *dev, bool enable) } else #endif -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_M16C_UART2 if (dev->uartno == 2) { regaddr = M16C_S2RIC; @@ -932,21 +932,21 @@ static int up_xmtinterrupt(int irq, void *context) { struct uart_dev_s *dev = NULL; -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_M16C_UART0 if (irq == g_uart0priv.xmtirq) { dev = &g_uart0port; } else #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_M16C_UART1 if (irq == g_uart1priv.xmtirq) { dev = &g_uart1port; } else #endif -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_M16C_UART2 if (irq == g_uart2priv.xmtirq) { dev = &g_uart1port; @@ -1000,7 +1000,7 @@ static void m16c_txint(struct up_dev_s *dev, bool enable) /* Pick the SxTIC register and enable interrupt priority */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_M16C_UART0 if (dev->uartno == 0) { regaddr = M16C_S0TIC; @@ -1008,7 +1008,7 @@ static void m16c_txint(struct up_dev_s *dev, bool enable) } else #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_M16C_UART1 if (dev->uartno == 1) { regaddr = M16C_S1TIC; @@ -1016,7 +1016,7 @@ static void m16c_txint(struct up_dev_s *dev, bool enable) } else #endif -#ifndef CONFIG_UART2_DISABLE +#ifdef CONFIG_M16C_UART2 if (dev->uartno == 2) { regaddr = M16C_S2TIC; @@ -1202,5 +1202,5 @@ int up_putc(int ch) #endif /* USE_SERIALDRIVER */ #elif defined(CONFIG_UART0_SERIAL_CONSOLE) || defined(CONFIG_UART1_SERIAL_CONSOLE)|| defined(CONFIG_UART2_SERIAL_CONSOLE) # error "A serial console selected, but corresponding UART not enabled" -#endif /* !CONFIG_UART0_DISABLE && !CONFIG_UART1_DISABLE && !CONFIG_UART2_DISABLE */ +#endif /* CONFIG_M16C_UART0 || CONFIG_M16C_UART1 || CONFIG_M16C_UART2 */ diff --git a/nuttx/arch/z80/Kconfig b/nuttx/arch/z80/Kconfig index 160b92d916..a2764cb653 100644 --- a/nuttx/arch/z80/Kconfig +++ b/nuttx/arch/z80/Kconfig @@ -15,36 +15,43 @@ config ARCH_CHIP_Z80 config ARCH_CHIP_Z8F640X bool "Z8F640X" + select ARCH_CHIP_Z8 ---help--- ZiLOG Z8F640X (z8 Encore) config ARCH_CHIP_Z8F6403 bool "Z8F6403" + select ARCH_CHIP_Z8 ---help--- ZiLOG Z8F6403 (z8 Encore) config ARCH_CHIP_Z8F642X bool "Z8F642X" + select ARCH_CHIP_Z8 ---help--- ZiLOG Z8F642X (z8 Encore) config ARCH_CHIP_Z8F6423 bool "Z8F6423" + select ARCH_CHIP_Z8 ---help--- ZiLOG Z8F6423 (z8 Encore) config ARCH_CHIP_EZ80F91 bool "EZ80F91" + select ARCH_CHIP_EZ80 ---help--- ZiLOG EZ80F91 (ez80 Acclaim) config ARCH_CHIP_EZ80F92 bool "EZ80F92" + select ARCH_CHIP_EZ80 ---help--- ZiLOG EZ80F92 (ez80 Acclaim) config ARCH_CHIP_EZ80F93 bool "EZ80F93" + select ARCH_CHIP_EZ80 ---help--- ZiLOG EZ80F93 (ez80 Acclaim) @@ -52,11 +59,9 @@ endchoice config ARCH_CHIP_Z8 bool - default y if ARCH_CHIP_Z8F640X || ARCH_CHIP_Z8F6403 || ARCH_CHIP_Z8F642X || ARCH_CHIP_Z8F6423 config ARCH_CHIP_EZ80 bool - default y if ARCH_CHIP_EZ80F91 || ARCH_CHIP_EZ80F92 || ARCH_CHIP_EZ80F93 config ARCH_CHIP string diff --git a/nuttx/arch/z80/src/ez80/Kconfig b/nuttx/arch/z80/src/ez80/Kconfig index 018ecb5112..d02a62c8b3 100644 --- a/nuttx/arch/z80/src/ez80/Kconfig +++ b/nuttx/arch/z80/src/ez80/Kconfig @@ -4,4 +4,20 @@ # if ARCH_CHIP_EZ80 + +config EZ80_UART0 + bool "UART0" + select ARCH_HAVE_UART0 + default n + +config EZ80_UART1 + bool "UART1" + select ARCH_HAVE_UART1 + default n + +config EZ80_UART2 + bool "UART2" + select ARCH_HAVE_UART2 + default n + endif diff --git a/nuttx/arch/z80/src/ez80/ez80_lowuart.c b/nuttx/arch/z80/src/ez80/ez80_lowuart.c index ed4f92faca..cc535530d8 100644 --- a/nuttx/arch/z80/src/ez80/ez80_lowuart.c +++ b/nuttx/arch/z80/src/ez80/ez80_lowuart.c @@ -59,7 +59,7 @@ * not have serial ports but supports stdout through, say, an LCD. */ -#if defined(CONFIG_UART0_DISABLE) || defined(CONFIG_UART1_DISABLE) +#if defined(CONFIG_EZ80_UART0) || defined(CONFIG_EZ80_UART1) # define HAVE_SERIAL #else # undef HAVE_SERIAL @@ -67,10 +67,10 @@ /* Is one of the serial ports a console? */ -#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_UART0_DISABLE) +#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_EZ80_UART0) # define HAVE_SERIALCONSOLE 1 # undef CONFIG_UART1_SERIAL_CONSOLE -#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE) +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_EZ80_UART1) # define HAVE_SERIALCONSOLE 1 # undef CONFIG_UART0_SERIAL_CONSOLE #else @@ -186,7 +186,7 @@ void up_lowuartinit(void) /* Configure pins for usage of UARTs (whether or not we have a console) */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_EZ80_UART0 /* Set Port D, pins 0 and 1 for their alternate function (Mode 7) to enable UART0 */ regval = inp(EZ80_PD_DDR); @@ -202,7 +202,7 @@ void up_lowuartinit(void) outp(EZ80_PD_ALT2, regval); #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_EZ80_UART1 /* Set Port C, pins 0 and 1 for their alternate function (Mode 7) to enable UART1 */ regval = inp(EZ80_PC_DDR); diff --git a/nuttx/arch/z80/src/ez80/ez80_serial.c b/nuttx/arch/z80/src/ez80/ez80_serial.c index e2f9b02941..61c31ba317 100644 --- a/nuttx/arch/z80/src/ez80/ez80_serial.c +++ b/nuttx/arch/z80/src/ez80/ez80_serial.c @@ -118,18 +118,18 @@ struct uart_ops_s g_uart_ops = /* I/O buffers */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_EZ80_UART0 static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE]; static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE]; #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_EZ80_UART1 static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE]; static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE]; #endif /* This describes the state of the UART0 port. */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_EZ80_UART0 static struct ez80_dev_s g_uart0priv = { EZ80_UART0_BASE, /* uartbase */ @@ -174,7 +174,7 @@ static uart_dev_t g_uart0port = /* This describes the state of the UART1 port. */ -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_EZ80_UART1 static struct ez80_dev_s g_uart1priv = { EZ80_UART1_BASE, /* uartbase */ @@ -219,24 +219,24 @@ static uart_dev_t g_uart1port = /* Now, which one with be tty0/console and which tty1? */ -#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_UART0_DISABLE) +#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_EZ80_UART0) # define CONSOLE_DEV g_uart0port # define TTYS0_DEV g_uart0port -# if !defined(CONFIG_UART1_DISABLE) +# if defined(CONFIG_EZ80_UART1) # define TTYS1_DEV g_uart1port # endif -#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE) +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_EZ80_UART1) # define CONSOLE_DEV g_uart1port # define TTYS0_DEV g_uart1port -# if !defined(CONFIG_UART0_DISABLE) +# if defined(CONFIG_EZ80_UART0) # define TTYS1_DEV g_uart0port # endif -#elif !defined(CONFIG_UART0_DISABLE) +#elif defined(CONFIG_EZ80_UART0) # define TTYS0_DEV g_uart0port -# if !defined(CONFIG_UART1_DISABLE) +# if defined(CONFIG_EZ80_UART1) # define TTYS1_DEV g_uart1port # endif -#elif !defined(CONFIG_UART0_DISABLE) +#elif defined(CONFIG_EZ80_UART0) # define TTYS0_DEV g_uart1port #endif @@ -475,14 +475,14 @@ static int ez80_interrrupt(int irq, void *context) struct ez80_dev_s *priv; volatile uint32_t cause; -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_EZ80_UART0 if (g_uart0priv.irq == irq) { dev = &g_uart0port; } else #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_EZ80_UART1 if (g_uart1priv.irq == irq) { dev = &g_uart1port; @@ -683,7 +683,7 @@ void up_serialinit(void) /* Configure pins for usage of UARTs */ -#ifndef CONFIG_UART0_DISABLE +#ifdef CONFIG_EZ80_UART0 /* Set Port D, pins 0 and 1 for their alternate function (Mode 7) to enable UART0 */ regval = inp(EZ80_PD_DDR); @@ -699,7 +699,7 @@ void up_serialinit(void) outp(EZ80_PD_ALT2, regval); #endif -#ifndef CONFIG_UART1_DISABLE +#ifdef CONFIG_EZ80_UART1 /* Set Port C, pins 0 and 1 for their alternate function (Mode 7) to enable UART1 */ regval = inp(EZ80_PC_DDR); diff --git a/nuttx/configs/eagle100/httpd/defconfig b/nuttx/configs/eagle100/httpd/defconfig index 6d4ee61a27..2d8f82180e 100644 --- a/nuttx/configs/eagle100/httpd/defconfig +++ b/nuttx/configs/eagle100/httpd/defconfig @@ -69,8 +69,8 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6918 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=256 diff --git a/nuttx/configs/eagle100/nettest/defconfig b/nuttx/configs/eagle100/nettest/defconfig index 4956d0875b..fa07402085 100644 --- a/nuttx/configs/eagle100/nettest/defconfig +++ b/nuttx/configs/eagle100/nettest/defconfig @@ -69,8 +69,8 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6918 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=256 diff --git a/nuttx/configs/eagle100/nsh/defconfig b/nuttx/configs/eagle100/nsh/defconfig index 7f6bd1f540..d8041c299c 100644 --- a/nuttx/configs/eagle100/nsh/defconfig +++ b/nuttx/configs/eagle100/nsh/defconfig @@ -69,8 +69,8 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6918 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=256 diff --git a/nuttx/configs/eagle100/nxflat/defconfig b/nuttx/configs/eagle100/nxflat/defconfig index a4760eae52..756902bb0f 100644 --- a/nuttx/configs/eagle100/nxflat/defconfig +++ b/nuttx/configs/eagle100/nxflat/defconfig @@ -69,8 +69,8 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6918 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=256 diff --git a/nuttx/configs/eagle100/ostest/defconfig b/nuttx/configs/eagle100/ostest/defconfig index 4b98e25e0f..43c77fe07f 100644 --- a/nuttx/configs/eagle100/ostest/defconfig +++ b/nuttx/configs/eagle100/ostest/defconfig @@ -69,8 +69,8 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6918 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=256 diff --git a/nuttx/configs/eagle100/thttpd/defconfig b/nuttx/configs/eagle100/thttpd/defconfig index 5af32d2022..dceac09900 100644 --- a/nuttx/configs/eagle100/thttpd/defconfig +++ b/nuttx/configs/eagle100/thttpd/defconfig @@ -69,8 +69,8 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6918 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=256 diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/defconfig b/nuttx/configs/ekk-lm3s9b96/nsh/defconfig index 8047a23dac..82ad3ce5dd 100644 --- a/nuttx/configs/ekk-lm3s9b96/nsh/defconfig +++ b/nuttx/configs/ekk-lm3s9b96/nsh/defconfig @@ -78,9 +78,9 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6B96 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y -CONFIG_UART2_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n +CONFIG_LM3S_UART2=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/defconfig b/nuttx/configs/ekk-lm3s9b96/ostest/defconfig index 6ce065ca81..bcf2a94262 100644 --- a/nuttx/configs/ekk-lm3s9b96/ostest/defconfig +++ b/nuttx/configs/ekk-lm3s9b96/ostest/defconfig @@ -78,9 +78,9 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6B96 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y -CONFIG_UART2_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n +CONFIG_LM3S_UART2=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/ez80f910200kitg/ostest/defconfig b/nuttx/configs/ez80f910200kitg/ostest/defconfig index 3039eec6cb..9450ff876a 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/defconfig +++ b/nuttx/configs/ez80f910200kitg/ostest/defconfig @@ -56,8 +56,8 @@ CONFIG_ARCH_TIMERHOOK=n # # eZ80 specific device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_EZ80_UART0=y +CONFIG_EZ80_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=0 diff --git a/nuttx/configs/ez80f910200zco/dhcpd/defconfig b/nuttx/configs/ez80f910200zco/dhcpd/defconfig index 329ff28245..37a256d5eb 100644 --- a/nuttx/configs/ez80f910200zco/dhcpd/defconfig +++ b/nuttx/configs/ez80f910200zco/dhcpd/defconfig @@ -57,8 +57,8 @@ CONFIG_ARCH_STACKDUMP=n # # eZ80 specific device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_EZ80_UART0=y +CONFIG_EZ80_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=0 diff --git a/nuttx/configs/ez80f910200zco/httpd/defconfig b/nuttx/configs/ez80f910200zco/httpd/defconfig index 1feeafd585..0cf4c33aaa 100644 --- a/nuttx/configs/ez80f910200zco/httpd/defconfig +++ b/nuttx/configs/ez80f910200zco/httpd/defconfig @@ -57,8 +57,8 @@ CONFIG_ARCH_STACKDUMP=n # # eZ80 specific device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_EZ80_UART0=y +CONFIG_EZ80_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=0 diff --git a/nuttx/configs/ez80f910200zco/nettest/defconfig b/nuttx/configs/ez80f910200zco/nettest/defconfig index 1ba356095a..9f7d438be7 100644 --- a/nuttx/configs/ez80f910200zco/nettest/defconfig +++ b/nuttx/configs/ez80f910200zco/nettest/defconfig @@ -57,8 +57,8 @@ CONFIG_ARCH_STACKDUMP=n # # eZ80 specific device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_EZ80_UART0=y +CONFIG_EZ80_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=0 diff --git a/nuttx/configs/ez80f910200zco/nsh/defconfig b/nuttx/configs/ez80f910200zco/nsh/defconfig index 73de6b096e..804a4563ff 100644 --- a/nuttx/configs/ez80f910200zco/nsh/defconfig +++ b/nuttx/configs/ez80f910200zco/nsh/defconfig @@ -57,8 +57,8 @@ CONFIG_ARCH_STACKDUMP=n # # eZ80 specific device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_EZ80_UART0=y +CONFIG_EZ80_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=64 diff --git a/nuttx/configs/ez80f910200zco/ostest/defconfig b/nuttx/configs/ez80f910200zco/ostest/defconfig index bf306e38d1..7ffd452ee1 100644 --- a/nuttx/configs/ez80f910200zco/ostest/defconfig +++ b/nuttx/configs/ez80f910200zco/ostest/defconfig @@ -56,8 +56,8 @@ CONFIG_ARCH_TIMERHOOK=y # # eZ80 specific device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_EZ80_UART0=y +CONFIG_EZ80_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=64 diff --git a/nuttx/configs/ez80f910200zco/poll/defconfig b/nuttx/configs/ez80f910200zco/poll/defconfig index 0d7d765cf4..316d150d0a 100644 --- a/nuttx/configs/ez80f910200zco/poll/defconfig +++ b/nuttx/configs/ez80f910200zco/poll/defconfig @@ -57,8 +57,8 @@ CONFIG_ARCH_STACKDUMP=n # # eZ80 specific device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y +CONFIG_EZ80_UART0=y +CONFIG_EZ80_UART1=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART0_TXBUFSIZE=0 diff --git a/nuttx/configs/lm3s6432-s2e/nsh/defconfig b/nuttx/configs/lm3s6432-s2e/nsh/defconfig index 9aa8f1db39..704d8ad91a 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/defconfig +++ b/nuttx/configs/lm3s6432-s2e/nsh/defconfig @@ -77,9 +77,9 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6432 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=n -CONFIG_UART2_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=y +CONFIG_LM3S_UART2=n CONFIG_UART0_SERIAL_CONSOLE=n CONFIG_UART1_SERIAL_CONSOLE=y CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/lm3s6432-s2e/ostest/defconfig b/nuttx/configs/lm3s6432-s2e/ostest/defconfig index 299cef48c2..0be2cfd4c2 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/defconfig +++ b/nuttx/configs/lm3s6432-s2e/ostest/defconfig @@ -77,9 +77,9 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6432 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=n -CONFIG_UART2_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=y +CONFIG_LM3S_UART2=n CONFIG_UART0_SERIAL_CONSOLE=n CONFIG_UART1_SERIAL_CONSOLE=y CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/lm3s6432-s2e/src/up_boot.c b/nuttx/configs/lm3s6432-s2e/src/up_boot.c index 3c5787f99a..5bb7b670fe 100644 --- a/nuttx/configs/lm3s6432-s2e/src/up_boot.c +++ b/nuttx/configs/lm3s6432-s2e/src/up_boot.c @@ -54,7 +54,7 @@ * Definitions ************************************************************************************/ -#if !defined(CONFIG_UART1_DISABLE) && !defined(CONFIG_SSI0_DISABLE) +#if defined(CONFIG_LM3S_UART1) && !defined(CONFIG_SSI0_DISABLE) # error Only one of UART1 and SSI0 can be enabled on this board. #endif diff --git a/nuttx/configs/lm3s6965-ek/nsh/defconfig b/nuttx/configs/lm3s6965-ek/nsh/defconfig index d10ad9db9b..7b75178eab 100755 --- a/nuttx/configs/lm3s6965-ek/nsh/defconfig +++ b/nuttx/configs/lm3s6965-ek/nsh/defconfig @@ -78,9 +78,9 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6965 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y -CONFIG_UART2_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n +CONFIG_LM3S_UART2=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/lm3s6965-ek/nx/defconfig b/nuttx/configs/lm3s6965-ek/nx/defconfig index 10d10f705c..bca864013d 100755 --- a/nuttx/configs/lm3s6965-ek/nx/defconfig +++ b/nuttx/configs/lm3s6965-ek/nx/defconfig @@ -78,9 +78,9 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6965 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y -CONFIG_UART2_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n +CONFIG_LM3S_UART2=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/lm3s6965-ek/ostest/defconfig b/nuttx/configs/lm3s6965-ek/ostest/defconfig index e638ac3c70..fcee444333 100755 --- a/nuttx/configs/lm3s6965-ek/ostest/defconfig +++ b/nuttx/configs/lm3s6965-ek/ostest/defconfig @@ -78,9 +78,9 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S6965 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y -CONFIG_UART2_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n +CONFIG_LM3S_UART2=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/lm3s8962-ek/nsh/defconfig b/nuttx/configs/lm3s8962-ek/nsh/defconfig index 769c5d8e97..573ea582ef 100755 --- a/nuttx/configs/lm3s8962-ek/nsh/defconfig +++ b/nuttx/configs/lm3s8962-ek/nsh/defconfig @@ -77,9 +77,9 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S8962 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y -CONFIG_UART2_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n +CONFIG_LM3S_UART2=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/lm3s8962-ek/nx/defconfig b/nuttx/configs/lm3s8962-ek/nx/defconfig index 653bdc4834..30c3b89522 100755 --- a/nuttx/configs/lm3s8962-ek/nx/defconfig +++ b/nuttx/configs/lm3s8962-ek/nx/defconfig @@ -77,9 +77,9 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S8962 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y -CONFIG_UART2_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n +CONFIG_LM3S_UART2=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/lm3s8962-ek/ostest/defconfig b/nuttx/configs/lm3s8962-ek/ostest/defconfig index ce1ed1a1dd..e19cab1cc2 100755 --- a/nuttx/configs/lm3s8962-ek/ostest/defconfig +++ b/nuttx/configs/lm3s8962-ek/ostest/defconfig @@ -77,9 +77,9 @@ CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y # # LM3S8962 specific serial device driver settings # -CONFIG_UART0_DISABLE=n -CONFIG_UART1_DISABLE=y -CONFIG_UART2_DISABLE=y +CONFIG_LM3S_UART0=y +CONFIG_LM3S_UART1=n +CONFIG_LM3S_UART2=n CONFIG_UART0_SERIAL_CONSOLE=y CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/mx1ads/ostest/defconfig b/nuttx/configs/mx1ads/ostest/defconfig index 03d79e70af..54dbf6cce4 100644 --- a/nuttx/configs/mx1ads/ostest/defconfig +++ b/nuttx/configs/mx1ads/ostest/defconfig @@ -59,9 +59,9 @@ CONFIG_ARCH_ROMPGTABLE=n # # IMX specific serial device driver settings # -CONFIG_UART1_DISABLE=n -CONFIG_UART2_DISABLE=y -CONFIG_UART3_DISABLE=y +CONFIG_IMX_UART1=y +CONFIG_IMX_UART2=n +CONFIG_IMX_UART3=n CONFIG_UART1_SERIAL_CONSOLE=y CONFIG_UART2_SERIAL_CONSOLE=n CONFIG_UART3_SERIAL_CONSOLE=n diff --git a/nuttx/configs/skp16c26/include/board.h b/nuttx/configs/skp16c26/include/board.h index cf0a1c15be..d656e13522 100644 --- a/nuttx/configs/skp16c26/include/board.h +++ b/nuttx/configs/skp16c26/include/board.h @@ -57,7 +57,7 @@ * To be safe, we will error out on either selection: */ -#if !defined(CONFIG_UART1_DISABLE) || !defined(CONFIG_UART2_DISABLE) +#if defined(CONFIG_M16C_UART1) || defined(CONFIG_M16C_UART2) # error "UART1/2 should not be used on SKP16C26" #endif diff --git a/nuttx/configs/skp16c26/ostest/defconfig b/nuttx/configs/skp16c26/ostest/defconfig index d223a8350d..cf93d5b10a 100644 --- a/nuttx/configs/skp16c26/ostest/defconfig +++ b/nuttx/configs/skp16c26/ostest/defconfig @@ -57,9 +57,9 @@ CONFIG_ARCH_LCD=y # # M16C specific device driver settings # -CONFIG_UART0_DISABLE=y -CONFIG_UART1_DISABLE=y -CONFIG_UART2_DISABLE=y +CONFIG_M16C_UART0=n +CONFIG_M16C_UART1=n +CONFIG_M16C_UART2=n CONFIG_UART0_SERIAL_CONSOLE=n CONFIG_UART1_SERIAL_CONSOLE=n CONFIG_UART2_SERIAL_CONSOLE=n diff --git a/nuttx/configs/skp16c26/src/up_lcdconsole.c b/nuttx/configs/skp16c26/src/up_lcdconsole.c index 1ae00fb222..617cc26ece 100644 --- a/nuttx/configs/skp16c26/src/up_lcdconsole.c +++ b/nuttx/configs/skp16c26/src/up_lcdconsole.c @@ -46,11 +46,11 @@ /* Only use the LCD as a console if there are is no serial console */ -#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_UART0_DISABLE) +#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_M16C_UART0) # define HAVE_SERIALCONSOLE 1 -#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE) +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_M16C_UART1) # define HAVE_SERIALCONSOLE 1 -#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && !defined(CONFIG_UART2_DISABLE) +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_M16C_UART2) # define HAVE_SERIALCONSOLE 1 #else # undef HAVE_SERIALCONSOLE From bd050bdf6ba90482254331fa8cdd4f1c6e122c5d Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 20 Nov 2012 21:19:36 +0000 Subject: [PATCH 146/206] Convert configs/ez80f910200kitg/RCS/ostest to use the newer mconf-based configuration git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5375 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 3 + nuttx/arch/z80/src/ez80/Kconfig | 82 ++ nuttx/configs/Kconfig | 12 +- nuttx/configs/ez80f910200kitg/README.txt | 11 +- .../configs/ez80f910200kitg/ostest/appconfig | 39 - .../configs/ez80f910200kitg/ostest/defconfig | 794 ++++++++++-------- nuttx/tools/mkdeps.c | 2 +- 7 files changed, 537 insertions(+), 406 deletions(-) delete mode 100644 nuttx/configs/ez80f910200kitg/ostest/appconfig diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 551e5c0fcf..d5f13d4070 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3648,4 +3648,7 @@ * graphics/nxmw: Extended the blocked messages to cover mouse movement and redraw events. These will also cause problems if sent to a window while it is closing. + * arch/several: Change UARTs are enabled for i.MX, LM3S, ez80, and M16C to + match how they are enabled for other architectures. + * configs/ez80f910200kitg: Convert to use mconf configuration. diff --git a/nuttx/arch/z80/src/ez80/Kconfig b/nuttx/arch/z80/src/ez80/Kconfig index d02a62c8b3..5b6d7e6d2e 100644 --- a/nuttx/arch/z80/src/ez80/Kconfig +++ b/nuttx/arch/z80/src/ez80/Kconfig @@ -5,6 +5,8 @@ if ARCH_CHIP_EZ80 +menu "ez80 Peripheral Support" + config EZ80_UART0 bool "UART0" select ARCH_HAVE_UART0 @@ -20,4 +22,84 @@ config EZ80_UART2 select ARCH_HAVE_UART2 default n +config EZ80_EMAC + bool "Ethernet MAC" + default n + select ARCH_HAVE_PHY + ---help--- + Enables support for ez80 EMAC driver. + +endmenu + +config HAVE_LOWUARTINIT + bool "Low UART Init" + default y if !EZ80_UART0 && !EZ80_UART1 && !EZ80_UART2 + default n if EZ80_UART0 || EZ80_UART1 || EZ80_UART2 + ---help--- + Provides low-level UART initialization logic as up_lowuartinit (only needed if there is no serial driver). + +if EZ80_EMAC + +config EZ80_FIAD +hex "PHY Address" + range 0x00 0x1f + default 0x1f + ---help--- + Provides the MII address of the PHY device + +# Belongs in net/Kconfig as PHY_AM79C874 +# EZ80_PHYAM79C874 - Define for Am79c874 PHY + +config EZ80_PHYCONFIG + int "PHY Configuration" + default 0 + ---help--- + 0:Autonegotiate, 1:100FD, 2:100HD, 3:10FD, 4:10HD + +config EZ80_RAMADDR + hex "Address of internal SRAM" + default 0xffc000 + ---help--- + Address of internal SRAM (default is 0xffc000) + +config EZ80_PKTBUFSIZE + int "Packet Buffer Size" + default 64 + ---help--- + The size of one packet buffer. EZ80_PKTBUFSIZE + (EZ80_NTXPKTBUFS+EZ80_NRXPKTBUFS) + must add up to exactly 8192 bytes. + +config EZ80_NTXPKTBUFS + int "Number of Tx Packets" + default 64 + ---help--- + The number of Tx packets. EZ80_PKTBUFSIZE + (EZ80_NTXPKTBUFS+EZ80_NRXPKTBUFS) + must add up to exactly 8192 bytes. + +config EZ80_NRXPKTBUFS + int "Number of Rx Packets" + default 64 + ---help--- + The number of Rx packets. EZ80_PKTBUFSIZE + (EZ80_NTXPKTBUFS+EZ80_NRXPKTBUFS) + must add up to exactly 8192 bytes. + +config EZ80_MDCDIV + int "SCLK Divider" + default 0 + ---help--- + The value to use for the divider to derive the MII MDC clock from SCLK. Options are 1->4; 2->6; 3->8; 4->10; 5->14; 6->20; and 7->28 + +config EZ80_TXPOLLTIMERMS + int "Tx Poll Milliseconds" + default 10 + ---help--- + Specifies how often the EMAC controller should poll for a Tx packet (milliseconds) + +config ARCH_MCFILTER + bool "Multicast Filtering" + default n + ---help--- + Enables multicast MAC address filtering (not fully implemented) + +endif endif diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig index be93b7a442..8d812c19bc 100644 --- a/nuttx/configs/Kconfig +++ b/nuttx/configs/Kconfig @@ -112,21 +112,21 @@ config ARCH_BOARD_EKK_LM3S9B96 an EKK-LM3S9B96 which is a Cortex-M3. config ARCH_BOARD_EZ80F910200KITG - bool "ZiLOG ez80f0910200kitg development kit" + bool "ZiLOG ez80f910200kitg development kit" depends on ARCH_CHIP_EZ80F91 select ARCH_HAVE_LEDS ---help--- - ez80Acclaim! Microcontroller. This port use the ZiLOG ez80f0910200kitg + ez80Acclaim! Microcontroller. This port use the ZiLOG ez80f910200kitg development kit, eZ80F091 part, and the Zilog ZDS-II Windows command line tools. The development environment is Cygwin under WinXP. config ARCH_BOARD_EZ80F910200ZCO - bool "ZiLOG ez80f0910200zco development kit" + bool "ZiLOG ez80f910200zco development kit" depends on ARCH_CHIP_EZ80F91 select ARCH_HAVE_LEDS select ARCH_HAVE_BUTTONS ---help--- - ez80Acclaim! Microcontroller. This port use the Zilog ez80f0910200zco + ez80Acclaim! Microcontroller. This port use the Zilog ez80f910200zco development kit, eZ80F091 part, and the Zilog ZDS-II Windows command line tools. The development environment is Cygwin under WinXP. @@ -614,8 +614,8 @@ config ARCH_BOARD default "ea3152" if ARCH_BOARD_EA3152 default "eagle100" if ARCH_BOARD_EAGLE100 default "ekk-lm3s9b96" if ARCH_BOARD_EKK_LM3S9B96 - default "ez80f0910200kitg" if ARCH_BOARD_EZ80F910200KITG - default "ez80f0910200zco" if ARCH_BOARD_EZ80F910200ZCO + default "ez80f910200kitg" if ARCH_BOARD_EZ80F910200KITG + default "ez80f910200zco" if ARCH_BOARD_EZ80F910200ZCO default "fire-stm32v2" if ARCH_BOARD_FIRE_STM32 default "hymini-stm32v" if ARCH_BOARD_HYMINI_STM32V default "kwikstik-k40" if ARCH_BOARD_KWIKSTIK_K40 diff --git a/nuttx/configs/ez80f910200kitg/README.txt b/nuttx/configs/ez80f910200kitg/README.txt index 57520b88e6..3c0b16e342 100644 --- a/nuttx/configs/ez80f910200kitg/README.txt +++ b/nuttx/configs/ez80f910200kitg/README.txt @@ -72,7 +72,7 @@ following steps: cd /tools ./configure.sh ez80f910200kitg/ - cd + cd make Where is the specific board configuration that you @@ -83,4 +83,13 @@ available: This builds the examples/ostest application for execution from FLASH. See examples/README.txt for information about ostest. + This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + Check out any README.txt files in these s. diff --git a/nuttx/configs/ez80f910200kitg/ostest/appconfig b/nuttx/configs/ez80f910200kitg/ostest/appconfig deleted file mode 100644 index 64d83b55ee..0000000000 --- a/nuttx/configs/ez80f910200kitg/ostest/appconfig +++ /dev/null @@ -1,39 +0,0 @@ -############################################################################ -# configs/ez80f910200kitg/ostest/appconfig -# -# Copyright (C) 2011 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. -# -############################################################################ - -# Path to example in apps/examples containing the user_start entry point - -CONFIGURED_APPS += examples/ostest - diff --git a/nuttx/configs/ez80f910200kitg/ostest/defconfig b/nuttx/configs/ez80f910200kitg/ostest/defconfig index 9450ff876a..831e3326db 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/defconfig +++ b/nuttx/configs/ez80f910200kitg/ostest/defconfig @@ -1,142 +1,170 @@ -############################################################################ -# configs/ez80f910200kitg/ostest/defconfig # -# Copyright (C) 2008-2010 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration # -# 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. -# -############################################################################ -# -# Architecture selection -# -CONFIG_ARCH="z80" -CONFIG_ARCH_Z80=y -CONFIG_ARCH_CHIP="ez80" -CONFIG_ARCH_CHIP_EZ80=y -CONFIG_ARCH_CHIP_EZ80F91=y -CONFIG_ARCH_CHIP_EZ80F92=n -CONFIG_ARCH_CHIP_EZ80F93=n -CONFIG_ARCH_BOARD="ez80f910200kitg" -CONFIG_ARCH_BOARD_EZ80F910200KITG=y -CONFIG_ARCH_NOINTC=n -CONFIG_ARCH_IRQPRIO=n -CONFIG_BOARD_LOOPSPERMSEC=1250 -CONFIG_ENDIAN_BIG=n -CONFIG_DRAM_SIZE=65536 -CONFIG_ARCH_LEDS=n -CONFIG_ARCH_BUTTONS=n -CONFIG_ARCH_TIMERHOOK=n +CONFIG_NUTTX_NEWCONFIG=y # -# eZ80 specific device driver settings +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_HOST_LINUX is not set +# CONFIG_HOST_OSX is not set +CONFIG_HOST_WINDOWS=y +# CONFIG_HOST_OTHER is not set +# CONFIG_WINDOWS_NATIVE is not set +CONFIG_WINDOWS_CYGWIN=y +# CONFIG_WINDOWS_MSYS is not set +# CONFIG_WINDOWS_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +# CONFIG_RAW_BINARY is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG=y +# CONFIG_DEBUG_VERBOSE is not set +# CONFIG_DEBUG_ENABLE is not set + +# +# Subsystem Debug Options +# +# CONFIG_DEBUG_MM is not set +# CONFIG_DEBUG_SCHED 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_ANALOG is not set +# CONFIG_DEBUG_DMA is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +# CONFIG_ARCH_ARM is not set +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +CONFIG_ARCH_Z80=y +CONFIG_ARCH="z80" +CONFIG_ARCH_CHIP="ez80" +CONFIG_BOARD_LOOPSPERMSEC=1250 +# CONFIG_SDIO_DMA is not set +# CONFIG_SDIO_WIDTH_D1_ONLY is not set +# CONFIG_ARCH_CHIP_Z80 is not set +# CONFIG_ARCH_CHIP_Z8F640X is not set +# CONFIG_ARCH_CHIP_Z8F6403 is not set +# CONFIG_ARCH_CHIP_Z8F642X is not set +# CONFIG_ARCH_CHIP_Z8F6423 is not set +CONFIG_ARCH_CHIP_EZ80F91=y +# CONFIG_ARCH_CHIP_EZ80F92 is not set +# CONFIG_ARCH_CHIP_EZ80F93 is not set +CONFIG_ARCH_CHIP_EZ80=y + +# +# ez80 Peripheral Support # CONFIG_EZ80_UART0=y -CONFIG_EZ80_UART1=n -CONFIG_UART0_SERIAL_CONSOLE=y -CONFIG_UART1_SERIAL_CONSOLE=n -CONFIG_UART0_TXBUFSIZE=0 -CONFIG_UART1_TXBUFSIZE=0 -CONFIG_UART0_RXBUFSIZE=0 -CONFIG_UART1_RXBUFSIZE=0 -CONFIG_UART0_BAUD=57600 -CONFIG_UART1_BAUD=57600 -CONFIG_UART0_PARITY=0 -CONFIG_UART1_PARITY=0 -CONFIG_UART0_2STOP=0 -CONFIG_UART1_2STOP=0 +# CONFIG_EZ80_UART1 is not set +# CONFIG_EZ80_UART2 is not set +# CONFIG_EZ80_EMAC is not set +CONFIG_HAVE_LOWUARTINIT=y # -# ez80 EMAC +# Architecture Options # -CONFIG_EZ80_EMAC=n -CONFIG_EZ80_FIAD=0x1f -CONFIG_EZ80_PHYAM79C874=y -CONFIG_EZ80_PHYCONFIG=1 -CONFIG_EZ80_RAMADDR=0xf7c000 -CONFIG_EZ80_PKTBUFSIZE=64 -CONFIG_EZ80_NTXPKTBUFS=64 -CONFIG_EZ80_NRXPKTBUFS=64 -CONFIG_EZ80_PKTBUFSIZE=64 -CONFIG_EZ80_MDCDIV=0 -CONFIG_EZ80_TXPOLLTIMERMS=10 -CONFIG_ARCH_MCFILTER=n +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +# CONFIG_ARCH_STACKDUMP is not set # -# General build options +# Board Settings # -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=n -CONFIG_MOTOROLA_SREC=n -CONFIG_RAW_BINARY=n +CONFIG_DRAM_START= +CONFIG_DRAM_SIZE=65536 # -# General OS setup +# Boot options # -CONFIG_USER_ENTRYPOINT="ostest_main" -CONFIG_DEBUG=y -CONFIG_DEBUG_VERBOSE=n -CONFIG_DEBUG_SYMBOLS=n -CONFIG_MM_REGIONS=1 -CONFIG_ARCH_LOWPUTC=y +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_EZ80F910200KITG=y +# CONFIG_ARCH_BOARD_EZ80F910200ZCO is not set +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="ez80f910200kitg" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +# CONFIG_ARCH_LEDS is not set + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 CONFIG_RR_INTERVAL=0 -CONFIG_SCHED_INSTRUMENTATION=n +# CONFIG_SCHED_INSTRUMENTATION is not set CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set CONFIG_START_YEAR=2009 CONFIG_START_MONTH=2 CONFIG_START_DAY=25 -CONFIG_JULIAN_TIME=n -CONFIG_HAVE_LOWUARTINIT=y CONFIG_DEV_CONSOLE=y CONFIG_DEV_LOWCONSOLE=y -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=n +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set CONFIG_SDCLONE_DISABLE=y - -# -# The following can be used to disable categories of -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_WAITPID is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="ostest_main" +CONFIG_DISABLE_OS_API=y CONFIG_DISABLE_CLOCK=y CONFIG_DISABLE_POSIX_TIMERS=y CONFIG_DISABLE_PTHREAD=y @@ -146,28 +174,6 @@ CONFIG_DISABLE_MOUNTPOINT=y CONFIG_DISABLE_ENVIRON=y CONFIG_DISABLE_POLL=y -# -# Misc libc settings -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve sysem performance -# -CONFIG_ARCH_MEMCPY=n -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n - # # Sizes of configurable things (0 disables) # @@ -177,237 +183,307 @@ CONFIG_NPTHREAD_KEYS=0 CONFIG_NFILE_DESCRIPTORS=8 CONFIG_NFILE_STREAMS=8 CONFIG_NAME_MAX=32 -CONFIG_STDIO_BUFFER_SIZE=0 -CONFIG_NUNGET_CHARS=0 CONFIG_PREALLOC_MQ_MSGS=0 CONFIG_MQ_MAXMSGSIZE=0 CONFIG_MAX_WDOGPARMS=2 CONFIG_PREALLOC_WDOGS=4 CONFIG_PREALLOC_TIMERS=0 -# -# Framebuffer driver options -CONFIG_FB_CMAP=n -CONFIG_FB_HWCURSOR=n -CONFIG_FB_HWCURSORIMAGE=n -#CONFIG_FB_HWCURSORSIZE -#CONFIG_FB_TRANSPARENCY - -# -# Filesystem configuration -# -CONFIG_FS_FAT=n -CONFIG_FS_ROMFS=n - -# -# Maintain legacy build behavior (revisit) -# - -CONFIG_MMCSD=y -CONFIG_MMCSD_SPI=y -CONFIG_MMCSD_SDIO=y - -# -# SPI-based MMC/SD driver -# -CONFIG_MMCSD_NSLOTS=1 -CONFIG_MMCSD_READONLY=n - -# -# TCP/IP and UDP support via uIP -# -CONFIG_NET=n -CONFIG_NET_IPv6=n -CONFIG_NSOCKET_DESCRIPTORS=0 -CONFIG_NET_SOCKOPTS=y -CONFIG_NET_BUFSIZE=420 -CONFIG_NET_TCP=n -CONFIG_NET_TCP_CONNS=40 -CONFIG_NET_MAX_LISTENPORTS=40 -CONFIG_NET_UDP=n -CONFIG_NET_UDP_CHECKSUMS=y -#CONFIG_NET_UDP_CONNS=10 -CONFIG_NET_ICMP=n -CONFIG_NET_ICMP_PING=n -#CONFIG_NET_PINGADDRCONF=0 -CONFIG_NET_STATISTICS=y -#CONFIG_NET_RECEIVE_WINDOW= -#CONFIG_NET_ARPTAB_SIZE=8 -CONFIG_NET_BROADCAST=n - -# -# UIP Network Utilities -# -CONFIG_NET_DHCP_LIGHT=n -CONFIG_NET_RESOLV_ENTRIES=4 - -# -# USB Device Configuration -# -CONFIG_USBDEV=n -CONFIG_USBDEV_ISOCHRONOUS=n -CONFIG_USBDEV_DUALSPEED=n -CONFIG_USBDEV_SELFPOWERED=y -CONFIG_USBDEV_REMOTEWAKEUP=n -CONFIG_USBDEV_MAXPOWER=100 -CONFIG_USBDEV_TRACE=n -CONFIG_USBDEV_TRACE_NRECORDS=128 - -# -# USB Serial Device Configuration -# -CONFIG_PL2303=n -CONFIG_PL2303_EPINTIN=1 -CONFIG_PL2303_EPBULKOUT=2 -CONFIG_PL2303_EPBULKIN=5 -CONFIG_PL2303_NWRREQS=4 -CONFIG_PL2303_NRDREQS=4 -CONFIG_PL2303_VENDORID=0x067b -CONFIG_PL2303_PRODUCTID=0x2303 -CONFIG_PL2303_VENDORSTR="Nuttx" -CONFIG_PL2303_PRODUCTSTR="USBdev Serial" -CONFIG_PL2303_RXBUFSIZE=512 -CONFIG_PL2303_TXBUFSIZE=512 - -# -# USB Storage Device Configuration -# -CONFIG_USBMSC=n -CONFIG_USBMSC_EP0MAXPACKET=64 -CONFIG_USBMSC_EPBULKOUT=2 -CONFIG_USBMSC_EPBULKIN=5 -CONFIG_USBMSC_NRDREQS=2 -CONFIG_USBMSC_NWRREQS=2 -CONFIG_USBMSC_BULKINREQLEN=256 -CONFIG_USBMSC_BULKOUTREQLEN=256 -CONFIG_USBMSC_VENDORID=0x584e -CONFIG_USBMSC_VENDORSTR="NuttX" -CONFIG_USBMSC_PRODUCTID=0x5342 -CONFIG_USBMSC_PRODUCTSTR="USBdev Storage" -CONFIG_USBMSC_VERSIONNO=0x0399 -CONFIG_USBMSC_REMOVABLE=y - -# -CONFIG_NX=n -CONFIG_NX_MULTIUSER=n -CONFIG_NX_NPLANES=1 -CONFIG_NX_DISABLE_1BPP=y -CONFIG_NX_DISABLE_2BPP=y -CONFIG_NX_DISABLE_4BPP=y -CONFIG_NX_DISABLE_8BPP=n -CONFIG_NX_DISABLE_16BPP=y -CONFIG_NX_DISABLE_24BPP=y -CONFIG_NX_DISABLE_32BPP=y -CONFIG_NX_PACKEDMSFIRST=n -CONFIG_NX_MOUSE=y -CONFIG_NX_KBD=y -#CONFIG_NXTK_BORDERWIDTH=4 -#CONFIG_NXTK_BORDERCOLOR1 -#CONFIG_NXTK_BORDERCOLOR2 -CONFIG_NXTK_AUTORAISE=n -CONFIG_NXFONT_SANS23X27=y -CONFIG_NXFONTS_CHARBITS=7 -CONFIG_NX_BLOCKING=y -CONFIG_NX_MXSERVERMSGS=32 -CONFIG_NX_MXCLIENTMSGS=16 - -# -# Settings for examples/uip -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_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 -CONFIG_EXAMPLES_OSTEST_LOOPS=1 -CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048 -CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 - -# -# Settings for apps/nshlib -# -CONFIG_NSH_FILEIOSIZE=512 -CONFIG_NSH_STRERROR=n -CONFIG_NSH_LINELEN=64 -CONFIG_NSH_NESTDEPTH=3 -CONFIG_NSH_DISABLESCRIPT=n -CONFIG_NSH_DISABLEBG=n -CONFIG_NSH_ROMFSETC=n -CONFIG_NSH_CONSOLE=y -CONFIG_NSH_TELNET=n -CONFIG_NSH_IOBUFFER_SIZE=512 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=n -CONFIG_NSH_IPADDR=0x0a000002 -CONFIG_NSH_DRIPADDR=0x0a000001 -CONFIG_NSH_NETMASK=0xffffff00 -CONFIG_NSH_ROMFSMOUNTPT="/etc" -CONFIG_NSH_INITSCRIPT="init.d/rcS" -CONFIG_NSH_ROMFSDEVNO=0 -CONFIG_NSH_ROMFSSECTSIZE=64 -CONFIG_NSH_FATDEVNO=1 -CONFIG_NSH_FATSECTSIZE=512 -CONFIG_NSH_FATNSECTORS=1024 -CONFIG_NSH_FATMOUNTPT="/tmp" - -# -# Architecture-specific NSH options -CONFIG_NSH_MMCSDSPIPORTNO=1 -CONFIG_NSH_MMCSDSLOTNO=0 -CONFIG_NSH_MMCSDMINOR=0 - -# -# Settings for examples/nx -# -CONFIG_EXAMPLES_NX_VPLANE=0 -#CONFIG_EXAMPLES_NX_BGCOLOR -#CONFIG_EXAMPLES_NX_COLOR1 -#CONFIG_EXAMPLES_NX_COLOR2 -#CONFIG_EXAMPLES_NX_TBCOLOR -#CONFIG_EXAMPLES_NX_FONTCOLOR -CONFIG_EXAMPLES_NX_BPP=CONFIG_SIM_FBBPP -CONFIG_EXAMPLES_NX_RAWWINDOWS=n -CONFIG_EXAMPLES_NX_STACKSIZE=8192 -CONFIG_EXAMPLES_NX_CLIENTPRIO=80 -CONFIG_EXAMPLES_NX_SERVERPRIO=120 -CONFIG_EXAMPLES_NX_NOTIFYSIGNO=4 - -# -# Settings for examples/mount -CONFIG_EXAMPLES_MOUNT_DEVNAME="/dev/ram0" -#CONFIG_EXAMPLES_MOUNT_NSECTORS=2048 -#CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512 -#CONFIG_EXAMPLES_MOUNT_RAMDEVNO=1 - -# -# Settings for examples/wget -# -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 # -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n +# CONFIG_CUSTOM_STACK is not set CONFIG_IDLETHREAD_STACKSIZE=1024 CONFIG_USERMAIN_STACKSIZE=1024 CONFIG_PTHREAD_STACK_MIN=256 CONFIG_PTHREAD_STACK_DEFAULT=1024 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +# CONFIG_SPI is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +CONFIG_MMCSD=y +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set +CONFIG_MMCSD_MMCSUPPORT=y +CONFIG_MMCSD_HAVECARDDETECT=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SPICLOCK=20000000 +CONFIG_MMCSD_SDIO=y +# CONFIG_SDIO_MUXBUS is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_UART0=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_UART0_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# UART0 Configuration +# +CONFIG_UART0_RXBUFSIZE=0 +CONFIG_UART0_TXBUFSIZE=0 +CONFIG_UART0_BAUD=57600 +CONFIG_UART0_BITS=8 +CONFIG_UART0_PARITY=0 +CONFIG_UART0_2STOP=0 +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_FS_RAMMAP is not set + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +CONFIG_ARCH_HAVE_HEAP2=y +CONFIG_HEAP2_BASE=0x00000000 +CONFIG_HEAP2_SIZE=0 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# +CONFIG_STDIO_BUFFER_SIZE=0 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=0 +# CONFIG_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set + +# +# Basic CXX Support +# +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# Named Applications +# +# CONFIG_NAMEDAPP is not set + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_NETTEST is not set +# CONFIG_EXAMPLES_NSH is not set +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +CONFIG_EXAMPLES_OSTEST=y +# CONFIG_EXAMPLES_OSTEST_BUILTIN is not set +CONFIG_EXAMPLES_OSTEST_LOOPS=1 +CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048 +CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 +CONFIG_EXAMPLES_OSTEST_RR_RANGE=10000 +CONFIG_EXAMPLES_OSTEST_RR_RUNS=10 +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WLAN is not set + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +# CONFIG_NSH_LIBRARY is not set + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +# CONFIG_SYSTEM_READLINE is not set + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# 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/tools/mkdeps.c b/nuttx/tools/mkdeps.c index 97934a2493..289385dfc0 100644 --- a/nuttx/tools/mkdeps.c +++ b/nuttx/tools/mkdeps.c @@ -501,7 +501,7 @@ static void do_dependency(const char *file, char separator) } else { - fprintf(stderr, "ERROR: %s failed: %s\n", g_cc, WEXITSTATUS(ret)); + fprintf(stderr, "ERROR: %s failed: %d\n", g_cc, WEXITSTATUS(ret)); } fprintf(stderr, " command: %s\n", g_command); From 90b0f6d2bcdf292f0cbb681f223149e43f767ae6 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 21 Nov 2012 00:39:30 +0000 Subject: [PATCH 147/206] Implement pause() git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5376 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/Documentation/NuttxUserGuide.html | 40 ++++++++- nuttx/include/unistd.h | 1 + nuttx/sched/Makefile | 2 +- nuttx/sched/pause.c | 110 ++++++++++++++++++++++++ 5 files changed, 152 insertions(+), 3 deletions(-) create mode 100644 nuttx/sched/pause.c diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index d5f13d4070..c5537e17ad 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3651,4 +3651,6 @@ * arch/several: Change UARTs are enabled for i.MX, LM3S, ez80, and M16C to match how they are enabled for other architectures. * configs/ez80f910200kitg: Convert to use mconf configuration. + * sched/pause.c: Implements the POSIX pause() function. + diff --git a/nuttx/Documentation/NuttxUserGuide.html b/nuttx/Documentation/NuttxUserGuide.html index 586b744c71..5326f22805 100644 --- a/nuttx/Documentation/NuttxUserGuide.html +++ b/nuttx/Documentation/NuttxUserGuide.html @@ -13,7 +13,7 @@

    NuttX Operating System

    User's Manual

    by

    Gregory Nutt

    -

    Last Updated: August 1, 2012

    +

    Last Updated: November 20, 2012

    @@ -3419,6 +3419,7 @@ interface of the same name.
  • 2.8.11 sigtimedwait
  • 2.8.12 sigqueue
  • 2.8.13 kill
  • +
  • 2.8.14 pause
  • 2.8.1 sigemptyset

    @@ -3946,7 +3947,7 @@ be sent. Function Prototype:
        #include <sys/types.h>
    -   #include <signal.h>
    +   #include <signal.h>
        int kill(pid_t pid, int sig);
     
    @@ -3996,6 +3997,39 @@ be sent.
  • Sending of signals to 'process groups' is not supported in NuttX.
  • +

    2.8.14 pause

    + +

    +Function Prototype: +

    +   #include <unistd.h>
    +   int pause(void);
    +
    + +

    +Description: + The pause() function will suspend the calling thread until delivery of a non-blocked signal. +

    +Input Parameters: +
      +
    • None +
    + +

    + Returned Value: + Since pause() suspends thread execution indefinitely unless interrupted a signal, there is no successful completion return value. + A value of -1 (ERROR will always be returned and errno set to indicate the error (EINTR). +

    + +

    + Assumptions/Limitations: +

    +

    + POSIX Compatibility: + In the POSIX description of this function is the pause() function will suspend the calling thread until delivery of a signal whose action is either to execute a signal-catching function or to terminate the process. + This implementation only waits for any non-blocked signal to be recieved. +

    +
    @@ -6711,6 +6745,7 @@ pid_t getpid(void); void _exit(int status) noreturn_function; unsigned int sleep(unsigned int seconds); void usleep(unsigned long usec); +int pause(void); int close(int fd); int dup(int fd); @@ -8187,6 +8222,7 @@ notify a task when a message is available on a queue.
  • OS Interfaces
  • +
  • pause
  • pipe
  • poll
  • poll.h
  • diff --git a/nuttx/include/unistd.h b/nuttx/include/unistd.h index e2ad6ff826..681ce9e632 100644 --- a/nuttx/include/unistd.h +++ b/nuttx/include/unistd.h @@ -133,6 +133,7 @@ EXTERN pid_t getpid(void); EXTERN void _exit(int status) noreturn_function; EXTERN unsigned int sleep(unsigned int seconds); EXTERN int usleep(useconds_t usec); +EXTERN int pause(void); /* File descriptor operations */ diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 9b15108f4d..82f74fc3c8 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -94,7 +94,7 @@ SIGNAL_SRCS = sig_initialize.c \ sig_findaction.c sig_allocatependingsigaction.c \ sig_releasependingsigaction.c sig_unmaskpendingsignal.c \ sig_removependingsignal.c sig_releasependingsignal.c sig_lowest.c \ - sig_mqnotempty.c sig_cleanup.c sig_received.c sig_deliver.c + sig_mqnotempty.c sig_cleanup.c sig_received.c sig_deliver.c pause.c MQUEUE_SRCS = mq_open.c mq_close.c mq_unlink.c mq_send.c mq_timedsend.c\ mq_sndinternal.c mq_receive.c mq_timedreceive.c mq_rcvinternal.c \ diff --git a/nuttx/sched/pause.c b/nuttx/sched/pause.c new file mode 100644 index 0000000000..fb5542d84d --- /dev/null +++ b/nuttx/sched/pause.c @@ -0,0 +1,110 @@ +/**************************************************************************** + * sched/pause.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +/**************************************************************************** + * Preprocessor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Definitions + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pause + * + * Description: + * The pause() function will suspend the calling thread until delivery of a + * non-blocked signal. + * + * Input Parameters: + * None + * + * Returned Value: + * Since pause() suspends thread execution indefinitely unless interrupted + * a signal, there is no successful completion return value. A value of -1 + * will always be returned and errno set to indicate the error (EINTR). + * + * POSIX compatibility: + * In the POSIX description of this function is the pause() function will + * suspend the calling thread until delivery of a signal whose action is + * either to execute a signal-catching function or to terminate the + * process. This implementation only waits for any non-blocked signal + * to be recieved. + * + ****************************************************************************/ + +int pause(void) +{ + sigset_t set; + struct siginfo value; + + /* Set up for the sleep. Using the empty set means that we are not + * waiting for any particualar signal. However, any unmasked signal + * can still awaken sigtimedwait(). + */ + + (void)sigemptyset(&set); + + /* sigtwaitinfo() cannot succeed. It should always return error EINTR + * meaning that some unblocked signal was caught. + */ + + return sigwaitinfo(&set, &value); +} From b665308a8704df02b7f40d03646cb3ad650e5995 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 21 Nov 2012 17:44:14 +0000 Subject: [PATCH 148/206] Update for ez80 Windows native build (still does not work) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5377 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Documentation/NuttxUserGuide.html | 2 +- nuttx/Kconfig | 2 +- nuttx/Makefile.win | 2 +- nuttx/arch/z80/src/Makefile.zdsii | 114 +++++++--- nuttx/configs/ez80f910200kitg/README.txt | 27 ++- .../configs/ez80f910200kitg/ostest/Make.defs | 209 ++++++++++++------ .../configs/ez80f910200kitg/ostest/defconfig | 2 +- .../configs/ez80f910200kitg/ostest/setenv.bat | 50 +++++ .../configs/ez80f910200kitg/ostest/setenv.sh | 32 ++- nuttx/configs/ez80f910200kitg/src/Makefile | 29 ++- nuttx/configs/ez80f910200zco/src/Makefile | 35 +-- .../stm32f4discovery/winbuild/setenv.bat | 10 +- nuttx/configs/z16f2800100zcog/src/Makefile | 29 ++- nuttx/configs/z8encore000zco/ostest/defconfig | 1 + nuttx/configs/z8encore000zco/src/Makefile | 29 ++- nuttx/configs/z8f64200100kit/src/Makefile | 29 ++- nuttx/sched/pause.c | 4 +- nuttx/sched/sleep.c | 2 +- nuttx/sched/usleep.c | 2 +- nuttx/tools/README.txt | 6 +- nuttx/tools/configure.sh | 36 ++- nuttx/tools/define.bat | 178 +++++++++++++++ nuttx/tools/define.sh | 8 +- nuttx/tools/mkdeps.c | 14 +- 24 files changed, 631 insertions(+), 221 deletions(-) create mode 100644 nuttx/configs/ez80f910200kitg/ostest/setenv.bat create mode 100644 nuttx/tools/define.bat diff --git a/nuttx/Documentation/NuttxUserGuide.html b/nuttx/Documentation/NuttxUserGuide.html index 5326f22805..d9dddf9be6 100644 --- a/nuttx/Documentation/NuttxUserGuide.html +++ b/nuttx/Documentation/NuttxUserGuide.html @@ -4027,7 +4027,7 @@ be sent.

    POSIX Compatibility: In the POSIX description of this function is the pause() function will suspend the calling thread until delivery of a signal whose action is either to execute a signal-catching function or to terminate the process. - This implementation only waits for any non-blocked signal to be recieved. + This implementation only waits for any non-blocked signal to be received.

    diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 129a503673..10d624efb8 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -67,7 +67,7 @@ endchoice config WINDOWS_MKLINK bool "Use mklink" - default y + default n depends on WINDOWS_NATIVE ---help--- Use the mklink command to set up symbolic links when NuttX is diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win index 5cb6aa3534..6257dbdc85 100644 --- a/nuttx/Makefile.win +++ b/nuttx/Makefile.win @@ -49,7 +49,7 @@ endif # This define is passed as EXTRADEFINES for kernel-mode builds. It is also passed # during PASS1 (but not PASS2) context and depend targets. -KDEFINE = -D__KERNEL__ +KDEFINE = ${shell $(TOPDIR)\tools\define.bat "$(CC)" __KERNEL__} # Process architecture and board-specific directories diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii index 338f2df935..dccb48d461 100644 --- a/nuttx/arch/z80/src/Makefile.zdsii +++ b/nuttx/arch/z80/src/Makefile.zdsii @@ -35,44 +35,52 @@ ############################################################################ # Tools -ARCHSRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src -WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} -USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common' -INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -CPPFLAGS += -I$(ARCHSRCDIR) -I$(ZDSSTDINCDIR) -I$(ZDSZILOGINCDIR) -LDFLAGS += @nuttx.linkcmd +SCHEDSRCDIR = $(TOPDIR)$(DELIM)sched +ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src + +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + USRINCLUDES = -usrinc:'.;$(SCHEDSRCDIR);$(ARCHSRCDIR);$(ARCHSRCDIR)\common' +else + WSCHEDSRCDIR = ${shell cygpath -w $(SCHEDSRCDIR)} + WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} + USRINCLUDES = -usrinc:'.;$(WSCHEDSRCDIR);$(WARCHSRCDIR);$(WARCHSRCDIR)\common' +endif + +INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +CPPFLAGS += -I$(ARCHSRCDIR) -I$(ZDSSTDINCDIR) -I$(ZDSZILOGINCDIR) +LDFLAGS += @nuttx.linkcmd ############################################################################ # Files and directories ifneq ($(HEAD_SSRC),) -HEAD_GENSRC = $(HEAD_SSRC:.S=$(ASMEXT)) -HEAD_OBJ = $(HEAD_SSRC:.S=$(OBJEXT)) +HEAD_GENSRC = $(HEAD_SSRC:.S=$(ASMEXT)) +HEAD_OBJ = $(HEAD_SSRC:.S=$(OBJEXT)) else -HEAD_OBJ = $(HEAD_ASRC:$(ASMEXT)=$(OBJEXT)) +HEAD_OBJ = $(HEAD_ASRC:$(ASMEXT)=$(OBJEXT)) endif -SSRCS = $(CHIP_SSRCS) $(CMN_SSRCS) -ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS) -GENSRCS = $(SSRCS:.S=$(ASMEXT)) -AOBJS = $(SSRCS:.S=$(OBJEXT)) $(ASRCS:$(ASMEXT)=$(OBJEXT)) +SSRCS = $(CHIP_SSRCS) $(CMN_SSRCS) +ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS) +GENSRCS = $(SSRCS:.S=$(ASMEXT)) +AOBJS = $(SSRCS:.S=$(OBJEXT)) $(ASRCS:$(ASMEXT)=$(OBJEXT)) -CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS) -COBJS = $(CSRCS:.c=$(OBJEXT)) +CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS) +COBJS = $(CSRCS:.c=$(OBJEXT)) -DEPSRCS = $(SSRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +DEPSRCS = $(SSRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) -BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board +BOARDDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board -VPATH = chip:common +VPATH = chip:common ############################################################################ # Targets all: $(HEAD_OBJ) libarch$(LIBEXT) -.PHONY: board/libboard$(LIBEXT) +.PHONY: board$(DELIM)libboard$(LIBEXT) $(HEAD_GENSRC) $(GENSRCS) : %$(ASMEXT): %.S $(Q) $(CPP) $(CPPFLAGS) $< -o $@.tmp @@ -88,17 +96,46 @@ $(COBJS): %$(OBJEXT): %.c libarch$(LIBEXT): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) -board/libboard$(LIBEXT): +board$(DELIM)libboard$(LIBEXT): $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) nuttx.linkcmd: $(LINKCMDTEMPLATE) $(Q) cp -f $(LINKCMDTEMPLATE) nuttx.linkcmd - @echo "\"${shell cygpath -w "$(TOPDIR)/nuttx"}\"= \\" >>nuttx.linkcmd - @echo " \"${shell cygpath -w "$(ARCHSRCDIR)/$(HEAD_OBJ)"}\", \\" >>nuttx.linkcmd +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + @echo "\"$(TOPDIR)/nuttx\"= \\" >>nuttx.linkcmd + @echo " \"$(ARCHSRCDIR)/$(HEAD_OBJ)\", \\" >>nuttx.linkcmd + $(Q) ( for lib in $(LINKLIBS); do \ + echo " \"$(TOPDIR)/lib/$${lib}\", \\" >>nuttx.linkcmd; \ + done ; ) + @echo " \"$(ARCHSRCDIR)/board/libboard$(LIBEXT)\", \\" >>nuttx.linkcmd +ifeq ($(CONFIG_ARCH_CHIP_Z8F640X),y) + @echo " \"$(ZDSSTDLIBDIR)/chelprevaaD$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSSTDLIBDIR)/crtrevaaLDD$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSSTDLIBDIR)/fprevaaLDD$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSZILOGLIBDIR)/csiorevaaLDD$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSZILOGLIBDIR)/zsldevinitdummy$(LIBEXT)\"" >>nuttx.linkcmd +endif +ifeq ($(CONFIG_ARCH_CHIP_Z8F642X),y) + @echo " \"$(ZDSSTDLIBDIR)/chelpD$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSSTDLIBDIR)/crtLDD$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSSTDLIBDIR)/fpdumyLD$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSZILOGLIBDIR)/csioLDD$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSZILOGLIBDIR)/zsldevinitdummy$(LIBEXT)\"" >>nuttx.linkcmd +endif +ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y) + @echo " \"$(ZDSSTDLIBDIR)/chelp$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSSTDLIBDIR)/crt$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSSTDLIBDIR)/fplib$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSZILOGLIBDIR)/gpio$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo " \"$(ZDSZILOGLIBDIR)/uartf91$(LIBEXT)\"" >>nuttx.linkcmd +endif +else + @echo "\"${shell cygpath -w "$(TOPDIR)/nuttx\"= \\" >>nuttx.linkcmd + @echo " \"${shell cygpath -w "$(ARCHSRCDIR)/$(HEAD_OBJ)\", \\" >>nuttx.linkcmd $(Q) ( for lib in $(LINKLIBS); do \ echo " \"`cygpath -w "$(TOPDIR)/lib/$${lib}"`\", \\" >>nuttx.linkcmd; \ done ; ) - @echo " \"${shell cygpath -w "$(ARCHSRCDIR)/board/libboard$(LIBEXT)"}\", \\" >>nuttx.linkcmd + @echo " \"${shell cygpath -w "$(ARCHSRCDIR)/board/libboard$(LIBEXT)\", \\" >>nuttx.linkcmd ifeq ($(CONFIG_ARCH_CHIP_Z8F640X),y) @echo " \"${shell cygpath -w "$(ZDSSTDLIBDIR)/chelprevaaD$(LIBEXT)"}\", \\" >>nuttx.linkcmd @echo " \"${shell cygpath -w "$(ZDSSTDLIBDIR)/crtrevaaLDD$(LIBEXT)"}\", \\" >>nuttx.linkcmd @@ -120,34 +157,43 @@ ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y) @echo " \"${shell cygpath -w "$(ZDSZILOGLIBDIR)/gpio$(LIBEXT)"}\", \\" >>nuttx.linkcmd @echo " \"${shell cygpath -w "$(ZDSZILOGLIBDIR)/uartf91$(LIBEXT)"}\"" >>nuttx.linkcmd endif +endif -nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) nuttx.linkcmd +nuttx$(EXEEXT): $(HEAD_OBJ) board$(DELIM)libboard$(LIBEXT) nuttx.linkcmd @echo "LD: nuttx$(EXEEXT)" $(Q) "$(LD)" $(LDFLAGS) -.depend: Makefile chip/Make.defs $(DEPSRCS) - $(Q) if [ -e board/Makefile ]; then \ +.depend: Makefile chip$(DELIM)Make.defs $(DEPSRCS) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + $(Q) if exist board$(DELIM)Makefile ( $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ) +else + $(Q) if [ -e board$(DELIM)Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \ fi +endif $(Q) $(MKDEP) --dep-path chip --dep-path common "$(CC)" -- $(CFLAGS) -- $(DEPSRCS) >Make.dep $(Q) touch $@ # This is part of the top-level export target -export_head: board/libboard$(LIBEXT) $(HEAD_OBJ) - $(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \ - cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \ +export_head: board$(DELIM)libboard$(LIBEXT) $(HEAD_OBJ) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + $(Q) if exist "$(EXPORT_DIR)$(DELIM)startup" ( copy $(HEAD_OBJ) "$(EXPORT_DIR)$(DELIM)startup$(DELIM)." /b /y) +else + $(Q) if [ -d "$(EXPORT_DIR)$(DELIM)startup" ]; then \ + cp -f $(HEAD_OBJ) "$(EXPORT_DIR)$(DELIM)startup"; \ else \ - echo "$(EXPORT_DIR)/startup does not exist"; \ + echo "$(EXPORT_DIR)$(DELIM)startup does not exist"; \ exit 1; \ fi +endif # Dependencies depend: .depend clean: - $(Q) if [ -e board/Makefile ]; then \ + $(Q) if [ -e board$(DELIM)Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi $(call DELFILE, nuttx.linkcmd) @@ -158,7 +204,7 @@ clean: $(call CLEAN) distclean: clean - $(Q) if [ -e board/Makefile ]; then \ + $(Q) if [ -e board$(DELIM)Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi $(call DELFILE, Make.dep) diff --git a/nuttx/configs/ez80f910200kitg/README.txt b/nuttx/configs/ez80f910200kitg/README.txt index 3c0b16e342..2bac3c5db8 100644 --- a/nuttx/configs/ez80f910200kitg/README.txt +++ b/nuttx/configs/ez80f910200kitg/README.txt @@ -83,13 +83,28 @@ available: This builds the examples/ostest application for execution from FLASH. See examples/README.txt for information about ostest. - This configuration uses the mconf-based configuration tool. To - change this configuration using that tool, you should: + NOTES: - a. Build and install the mconf tool. See nuttx/README.txt and - misc/tools/ + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: - b. Execute 'make menuconfig' in nuttx/ in order to start the - reconfiguration process. + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. By default, this configuration assumes that you are using the + Cygwin environment on Windows. An option is to use the native + CMD.exe window build as described in the top-level README.txt + file. To set up that configuration: + + -CONFIG_WINDOWS_CYGWIN=y + +CONFIG_WINDOWS_NATIVE=y + + And after configuring, make sure that CONFIG_APPS_DIR uses + the back slash character. For example: + + CONFIG_APPS_DIR="..\apps" Check out any README.txt files in these s. diff --git a/nuttx/configs/ez80f910200kitg/ostest/Make.defs b/nuttx/configs/ez80f910200kitg/ostest/Make.defs index 88280d8ecb..54e377de7e 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/Make.defs +++ b/nuttx/configs/ez80f910200kitg/ostest/Make.defs @@ -47,6 +47,20 @@ ifeq ($(CONFIG_WINDOWS_NATIVE),y) ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog + + # Escaped versions + + # ETOPDIR := ${shell echo "$(TOPDIR)" | sed -e "s/ /%%%%20/g"} + # EZDSSTDINCDIR := ${shell echo "$(ZDSSTDINCDIR)" | sed -e "s/ /%%%%20/g"} + # EZDSZILOGINCDIR := ${shell echo "$(ZDSZILOGINCDIR)" | sed -e "s/ /%%%%20/g"} + + # CFLAGs + + ARCHASMINCLUDES = -include:'$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR)' + # EARCHASMINCLUDES = -include:'$(ETOPDIR)\include;$(EZDSSTDINCDIR);$(EZDSZILOGINCDIR)' + EARCHASMINCLUDES = -include:'$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR)' + ARCHSTDINCLUDES = -stdinc:'$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR)' + ARCHUSRINCLUDES = -usrinc:'.' else WINTOOL := y INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"} @@ -55,99 +69,139 @@ else ZDSZILOGINCDIR := $(INSTALLDIR)/include/zilog ZDSSTDLIBDIR := $(INSTALLDIR)/lib/std ZDSZILOGLIBDIR := $(INSTALLDIR)/lib/zilog + + # These are the same directories but with the directory separator + # character swapped as needed by the ZDS-II compiler + + WTOPDIR := ${shell cygpath -w "$(TOPDIR)"} + WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"} + WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"} + WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"} + WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"} + + # Escaped versions + + ETOPDIR := ${shell echo "$(WTOPDIR)" | sed -e "s/ /%20/g"} + EZDSSTDINCDIR := ${shell echo "$(WZDSSTDINCDIR)" | sed -e "s/ /%20/g"} + EZDSZILOGINCDIR := ${shell echo "$(WZDSZILOGINCDIR)" | sed -e "s/ /%20/g"} + + # CFLAGs + + ARCHASMINCLUDES = -include:'$(WTOPDIR)\include;$(WZDSSTDINCDIR);$(WZDSZILOGINCDIR)' + EARCHASMINCLUDES = -include:'$(ETOPDIR)\include;$(EZDSSTDINCDIR);$(EZDSZILOGINCDIR)' + ARCHSTDINCLUDES = -stdinc:'$(WTOPDIR)\include;$(WZDSSTDINCDIR);$(WZDSZILOGINCDIR)' + ARCHUSRINCLUDES = -usrinc:'.' endif -# These are the same directories but with the directory separator -# character swapped as needed by the ZDS-II compiler - -WTOPDIR := ${shell cygpath -w "$(TOPDIR)"} -WZDSSTDINCDIR := ${shell cygpath -w "$(ZDSSTDINCDIR)"} -WZDSZILOGINCDIR := ${shell cygpath -w "$(ZDSZILOGINCDIR)"} -WZDSSTDLIBDIR := ${shell cygpath -w "$(ZDSSTDLIBDIR)"} -WZDSZILOGLIBDIR := ${shell cygpath -w "$(ZDSZILOGLIBDIR)"} - -# Escaped versions - -ETOPDIR := ${shell echo "$(WTOPDIR)" | sed -e "s/ /%20/g"} -EZDSSTDINCDIR := ${shell echo "$(WZDSSTDINCDIR)" | sed -e "s/ /%20/g"} -EZDSZILOGINCDIR := ${shell echo "$(WZDSZILOGINCDIR)" | sed -e "s/ /%20/g"} - # Assembler definitions ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y) -ARCHCPU = eZ80F91 -ARCHCPUDEF = _EZ80F91 -ARCHFAMILY = _EZ80ACCLAIM! +ARCHCPU = eZ80F91 +ARCHCPUDEF = _EZ80F91 +ARCHFAMILY = _EZ80ACCLAIM! endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - ARCHASMOPTIMIZATION = -debug -NOsdiopt + ARCHASMOPTIMIZATION = -debug -NOsdiopt else - ARCHASMOPTIMIZATION = -nodebug -NOsdiopt + ARCHASMOPTIMIZATION = -nodebug -NOsdiopt endif -ARCHASMCPUFLAGS = -cpu:$(ARCHCPU) -NOigcase -ARCHASMLIST = -list -NOlistmac -name -pagelen:56 -pagewidth:80 -quiet -ARCHASMWARNINGS = -warn -ARCHASMDEFINES = -define:$(ARCHCPUDEF)=1 -define:$(ARCHFAMILYDEF)=1 -define:__ASSEMBLY__ -ARCHASMINCLUDES = -include:'$(WTOPDIR)\include;$(WZDSSTDINCDIR);$(WZDSZILOGINCDIR)' -EARCHASMINCLUDES = -include:'$(ETOPDIR)\include;$(EZDSSTDINCDIR);$(EZDSZILOGINCDIR)' -AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ - $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION) +ARCHASMCPUFLAGS = -cpu:$(ARCHCPU) -NOigcase +ARCHASMLIST = -list -NOlistmac -name -pagelen:56 -pagewidth:80 -quiet +ARCHASMWARNINGS = -warn +ARCHASMDEFINES = -define:$(ARCHCPUDEF)=1 -define:$(ARCHFAMILYDEF)=1 -define:__ASSEMBLY__ +AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ + $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION) # Compiler definitions ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - ARCHOPTIMIZATION = -debug -reduceopt + ARCHOPTIMIZATION = -debug -reduceopt else - ARCHOPTIMIZATION = -nodebug -optsize + ARCHOPTIMIZATION = -nodebug -optsize endif -ARCHCPUFLAGS = -chartype:S -promote -cpu:$(ARCHCPU) -NOgenprintf -NOmodsect \ - -asmsw:" $(ARCHASMCPUFLAGS) $(EARCHASMINCLUDES) $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION)" -ARCHLIST = -keeplst -NOlist -NOlistinc -keepasm -ARCHPICFLAGS = -ARCHWARNINGS = -warn -ARCHDEFINES = -define:$(ARCHCPUDEF) -define:$(ARCHFAMILYDEF) -ARCHSTDINCLUDES = -stdinc:'$(WTOPDIR)\include;$(WZDSSTDINCDIR);$(WZDSZILOGINCDIR)' -ARCHUSRINCLUDES = -usrinc:'.' -ARCHINCLUDES = $(ARCHSTDINCLUDES) $(ARCHUSRINCLUDES) -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHLIST) \ - $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +ARCHCPUFLAGS = -chartype:S -promote -cpu:$(ARCHCPU) -NOgenprintf -NOmodsect \ + -asmsw:" $(ARCHASMCPUFLAGS) $(EARCHASMINCLUDES) $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION)" +ARCHLIST = -keeplst -NOlist -NOlistinc -keepasm +ARCHPICFLAGS = +ARCHWARNINGS = -warn +ARCHDEFINES = -define:$(ARCHCPUDEF) -define:$(ARCHFAMILYDEF) +ARCHINCLUDES = $(ARCHSTDINCLUDES) $(ARCHUSRINCLUDES) +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHLIST) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -CPPDEFINES = -D$(ARCHFAMILYDEF) -D$(ARCHCPUDEF) -D__ASSEMBLY__ -CPPINCLUDES = -I$(TOPDIR)/include -CPPFLAGS = $(CPPDEFINES) $(CPPINCLUDES) +CPPDEFINES = -D$(ARCHFAMILYDEF) -D$(ARCHCPUDEF) -D__ASSEMBLY__ +CPPINCLUDES = -I$(TOPDIR)$(DELIM)include +CPPFLAGS = $(CPPDEFINES) $(CPPINCLUDES) # Librarian definitions -ARFLAGS = -quiet -warn +ARFLAGS = -quiet -warn # Linker definitions -LINKCMDTEMPLATE = $(TOPDIR)/configs/ez80f910200kitg/ostest/ostest.linkcmd +LINKCMDTEMPLATE = $(TOPDIR)$(DELIM)configs$(DELIM)ez80f910200kitg$(DELIM)ostest$(DELIM)ostest.linkcmd # Tool names/pathes -CROSSDEV = -CC = $(ZDSBINDIR)/ez80cc.exe -CPP = gcc -E -LD = $(ZDSBINDIR)/ez80link.exe -AS = $(ZDSBINDIR)/ez80asm.exe -AR = $(ZDSBINDIR)/ez80lib.exe +CROSSDEV = +CPP = gcc -E + +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + # PATH varialble should be set + CC = ez80cc.exe + LD = ez80link.exe + AS = ez80asm.exe + AR = ez80lib.exe +else + # Cygwin PATH variable is not sufficient + CC = "$(ZDSBINDIR)$(DELIM)ez80cc.exe" + LD = "$(ZDSBINDIR)$(DELIM)ez80link.exe" + AS = "$(ZDSBINDIR)$(DELIM)ez80asm.exe" + AR = "$(ZDSBINDIR)$(DELIM)ez80lib.exe" +endif # File extensions -ASMEXT = .asm -OBJEXT = .obj -LIBEXT = .lib -EXEEXT = .lod -HEXEXT = .hex +ASMEXT = .asm +OBJEXT = .obj +LIBEXT = .lib +EXEEXT = .lod +HEXEXT = .hex # These are the macros that will be used in the NuttX make system # to compile and assembly source files and to insert the resulting # object files into an archive +ifeq ($(CONFIG_WINDOWS_NATIVE),y) +define PREPROCESS + @echo CPP: $1->$2 + $(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2 +endef + +define COMPILE + $(Q) "$(CC)" $(CFLAGS) $1 +endef + +define ASSEMBLE + $(Q) "$(AS)" $(AFLAGS) $1 +endef + +define ARCHIVE + echo AR: $2 + $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) +endef + +define CLEAN + $(Q) if exist *.obj (del /f /q *.obj) + $(Q) if exist *.src (del /f /q *.src) + $(Q) if exist *.lib (del /f /q *.lib) + $(Q) if exist *.hex (del /f /q *.hex) + $(Q) if exist *.lod (del /f /q *.lod) + $(Q) if exist *.lst (del /f /q *.lst) +endef +else define PREPROCESS @echo "CPP: $1->$2" $(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2 @@ -163,36 +217,45 @@ define ASSEMBLE $(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile) endef -ifeq ($(CONFIG_WINDOWS_NATIVE),y) -define ARCHIVE - echo "AR: $2"; - $(Q) for %%G in ($(2)) do ( "$(AR)" $(ARFLAGS) $1=-+%%G ) -endef -else define ARCHIVE $(Q) for __obj in $(2) ; do \ echo "AR: $$__obj"; \ "$(AR)" $(ARFLAGS) $1=-+$$__obj || { echo "$(AR) $1=-+$$__obj FAILED!" ; exit 1 ; } \ done endef -endif define CLEAN $(Q) rm -f *.obj *.src *.lib *.hex *.lod *.lst endef +endif -# This is the tool to use for dependencies (i.e., none) +# Windows native host tool definitions -MKDEP = $(TOPDIR)/tools/mknulldeps.sh +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + HOSTCC = mingw32-gcc.exe + HOSTINCLUDES = -I. + HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe + HOSTLDFLAGS = + HOSTEXEEXT = .exe -# ZDS-II cannot follow Cygwin soft links, so we will have to use directory copies + # Windows-native host tools -DIRLINK = $(TOPDIR)/tools/winlink.sh -DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)\tools\mkdeps.exe --winnative +else # Linux/Cygwin host tool definitions -HOSTCC = gcc -HOSTINCLUDES = -I. -HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe -HOSTLDFLAGS = + HOSTCC = gcc + HOSTINCLUDES = -I. + HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe + HOSTLDFLAGS = + + # This is the tool to use for dependencies (i.e., none) + + MKDEP = $(TOPDIR)$(DELIM)tools$(DELIM)mknulldeps.sh + + # ZDS-II cannot follow Cygwin soft links, so we will have to use directory copies + + DIRLINK = $(TOPDIR)$(DELIM)tools$(DELIM)winlink.sh + DIRUNLINK = $(TOPDIR)$(DELIM)tools$(DELIM)unlink.sh +endif diff --git a/nuttx/configs/ez80f910200kitg/ostest/defconfig b/nuttx/configs/ez80f910200kitg/ostest/defconfig index 831e3326db..e061e6289f 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/defconfig +++ b/nuttx/configs/ez80f910200kitg/ostest/defconfig @@ -111,7 +111,7 @@ CONFIG_HAVE_LOWUARTINIT=y # # Board Settings # -CONFIG_DRAM_START= +CONFIG_DRAM_START=0 CONFIG_DRAM_SIZE=65536 # diff --git a/nuttx/configs/ez80f910200kitg/ostest/setenv.bat b/nuttx/configs/ez80f910200kitg/ostest/setenv.bat new file mode 100644 index 0000000000..f461cf1cc2 --- /dev/null +++ b/nuttx/configs/ez80f910200kitg/ostest/setenv.bat @@ -0,0 +1,50 @@ +@echo off + +rem configs/ez80f810200kitg/ostest/setenv.bat +rem +rem Copyright (C) 2012 Gregory Nutt. All rights reserved. +rem Author: Gregory Nutt +rem +rem Redistribution and use in source and binary forms, with or without +rem modification, are permitted provided that the following conditions +rem are met: +rem +rem 1. Redistributions of source code must retain the above copyright +rem notice, this list of conditions and the following disclaimer. +rem 2. Redistributions in binary form must reproduce the above copyright +rem notice, this list of conditions and the following disclaimer in +rem the documentation and/or other materials provided with the +rem distribution. +rem 3. Neither the name NuttX nor the names of its contributors may be +rem used to endorse or promote products derived from this software +rem without specific prior written permission. +rem +rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +rem POSSIBILITY OF SUCH DAMAGE. + +rem This is the location where I installed in the MinGW compiler. With +rem this configuration, it is recommended that you do NOT install the +rem MSYS tools; they conflict with the GNUWin32 tools. See +rem http://www.mingw.org/ for further info. + +set PATH=C:\MinGW\bin;%PATH% + +rem This is the location where I installed the ZDS-II toolchain. + +set PATH=C:\Program Files (x86)\ZiLOG\ZDSII_eZ80Acclaim!_5.1.1\bin;%PATH% + +rem This is the location where I installed the GNUWin32 tools. See +rem http://gnuwin32.sourceforge.net/. + +set PATH=C:\gnuwin32\bin;%PATH% +echo %PATH% diff --git a/nuttx/configs/ez80f910200kitg/ostest/setenv.sh b/nuttx/configs/ez80f910200kitg/ostest/setenv.sh index e692029ae4..ce3ea8b53b 100755 --- a/nuttx/configs/ez80f910200kitg/ostest/setenv.sh +++ b/nuttx/configs/ez80f910200kitg/ostest/setenv.sh @@ -33,20 +33,28 @@ # # Check how we were executed # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -# -# The ZDS-II toolchain lies outside of the Cygwin "sandbox" and -# attempts to set the PATH variable do not have the desired effect. -# Instead, alias are provided for all of the ZDS-II command line tools. -# Version 4.10.1 installed in the default location is assumed here. -# -ZDSBINDIR="C:/Program\ Files/ZiLOG/ZDSII_eZ80Acclaim!_4.11.1/bin" -alias ez8asm="${ZDSBINDIR}/ez8asm.exe" -alias ez8cc="${ZDSBINDIR}/ez8cc.exe" -alias ez8lib="${ZDSBINDIR}/ez8lib.exe" -alias ez8link="${ZDSBINDIR}/ez8link.exe" +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 location where the XDS-II tools were installed +# +TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1\bin" + +# +# Add the path to the toolchain to the PATH varialble +# +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" +echo "PATH : ${PATH}" diff --git a/nuttx/configs/ez80f910200kitg/src/Makefile b/nuttx/configs/ez80f910200kitg/src/Makefile index 940e331cf9..12c39824e5 100644 --- a/nuttx/configs/ez80f910200kitg/src/Makefile +++ b/nuttx/configs/ez80f910200kitg/src/Makefile @@ -35,20 +35,27 @@ -include $(TOPDIR)/Make.defs -ARCHSRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src -WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} -USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common' -INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +SCHEDSRCDIR = $(TOPDIR)$(DELIM)sched +ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src -ASRCS = -AOBJS = $(ASRCS:.S=$(OBJEXT)) -CSRCS = ez80_lowinit.c ez80_leds.c -COBJS = $(CSRCS:.c=$(OBJEXT)) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + USRINCLUDES = -usrinc:'.;$(SCHEDSRCDIR);$(ARCHSRCDIR);$(ARCHSRCDIR)\common' +else + WSCHEDSRCDIR = ${shell cygpath -w $(SCHEDSRCDIR)} + WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} + USRINCLUDES = -usrinc:'.;$(WSCHEDSRCDIR);$(WARCHSRCDIR);$(WARCHSRCDIR)\common' +endif -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) +CSRCS = ez80_lowinit.c ez80_leds.c +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) all: libboard$(LIBEXT) diff --git a/nuttx/configs/ez80f910200zco/src/Makefile b/nuttx/configs/ez80f910200zco/src/Makefile index ba80e9838c..216f422902 100644 --- a/nuttx/configs/ez80f910200zco/src/Makefile +++ b/nuttx/configs/ez80f910200zco/src/Makefile @@ -35,27 +35,34 @@ -include $(TOPDIR)/Make.defs -ARCHSRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src -WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} -USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common' -INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +SCHEDSRCDIR = $(TOPDIR)$(DELIM)sched +ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src -ASRCS = -AOBJS = $(ASRCS:.S=$(OBJEXT)) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + USRINCLUDES = -usrinc:'.;$(SCHEDSRCDIR);$(ARCHSRCDIR);$(ARCHSRCDIR)\common' +else + WSCHEDSRCDIR = ${shell cygpath -w $(SCHEDSRCDIR)} + WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} + USRINCLUDES = -usrinc:'.;$(WSCHEDSRCDIR);$(WARCHSRCDIR);$(WARCHSRCDIR)\common' +endif -CSRCS = ez80_lowinit.c +INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) + +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) + +CSRCS = ez80_lowinit.c ifeq ($(CONFIG_ARCH_LEDS),y) -CSRCS += ez80_leds.c +CSRCS += ez80_leds.c endif ifeq ($(CONFIG_ARCH_BUTTONS),y) -CSRCS += ez80_buttons.c +CSRCS += ez80_buttons.c endif -COBJS = $(CSRCS:.c=$(OBJEXT)) - -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +COBJS = $(CSRCS:.c=$(OBJEXT)) +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) all: libboard$(LIBEXT) diff --git a/nuttx/configs/stm32f4discovery/winbuild/setenv.bat b/nuttx/configs/stm32f4discovery/winbuild/setenv.bat index 1d4a95f3a3..b4580f778d 100755 --- a/nuttx/configs/stm32f4discovery/winbuild/setenv.bat +++ b/nuttx/configs/stm32f4discovery/winbuild/setenv.bat @@ -1,6 +1,6 @@ @echo off -rem configs/stm32f4discovery/winbuild/setenv.sh +rem configs/stm32f4discovery/winbuild/setenv.bat rem rem Copyright (C) 2012 Gregory Nutt. All rights reserved. rem Author: Gregory Nutt @@ -32,6 +32,9 @@ rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE rem POSSIBILITY OF SUCH DAMAGE. +rem This script is not needed for setting the path because the full path +rem to the ZDI-II tools are used in Make.defs. + rem This is the location where I installed in the MinGW compiler. With rem this configuration, it is recommended that you do NOT install the rem MSYS tools; they conflict with the GNUWin32 tools. See @@ -39,11 +42,6 @@ rem http://www.mingw.org/ for further info. set PATH=C:\MinGW\bin;%PATH% -rem This is the location where I installed the CodeSourcey toolchain. See -rem http://www.mentor.com/embedded-software/codesourcery - -set PATH=C:\Program Files (x86)\CodeSourcery\Sourcery G++ Lite\bin;%PATH% - rem This is the location where I installed the GNUWin32 tools. See rem http://gnuwin32.sourceforge.net/. diff --git a/nuttx/configs/z16f2800100zcog/src/Makefile b/nuttx/configs/z16f2800100zcog/src/Makefile index 3ce63092db..0977550077 100644 --- a/nuttx/configs/z16f2800100zcog/src/Makefile +++ b/nuttx/configs/z16f2800100zcog/src/Makefile @@ -35,20 +35,27 @@ -include $(TOPDIR)/Make.defs -ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src -WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} -USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common' -INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) $(EXTRADEFINES) +SCHEDSRCDIR = $(TOPDIR)$(DELIM)sched +ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src -ASRCS = -AOBJS = $(ASRCS:.S=$(OBJEXT)) -CSRCS = z16f_lowinit.c z16f_leds.c -COBJS = $(CSRCS:.c=$(OBJEXT)) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + USRINCLUDES = -usrinc:'.;$(SCHEDSRCDIR);$(ARCHSRCDIR);$(ARCHSRCDIR)\common' +else + WSCHEDSRCDIR = ${shell cygpath -w $(SCHEDSRCDIR)} + WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} + USRINCLUDES = -usrinc:'.;$(WSCHEDSRCDIR);$(WARCHSRCDIR);$(WARCHSRCDIR)\common' +endif -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) $(EXTRADEFINES) +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) +CSRCS = z16f_lowinit.c z16f_leds.c +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) all: libboard$(LIBEXT) diff --git a/nuttx/configs/z8encore000zco/ostest/defconfig b/nuttx/configs/z8encore000zco/ostest/defconfig index 4ed80ba69c..05e7c906c0 100644 --- a/nuttx/configs/z8encore000zco/ostest/defconfig +++ b/nuttx/configs/z8encore000zco/ostest/defconfig @@ -47,6 +47,7 @@ CONFIG_ARCH_BOARD="z8encore000zco" CONFIG_ARCH_BOARD_Z8ENCORE000ZCO=y CONFIG_BOARD_LOOPSPERMSEC=1250 CONFIG_ENDIAN_BIG=y +CONFIG_DRAM_START=0x0 CONFIG_DRAM_SIZE=65536 CONFIG_ARCH_LEDS=n # diff --git a/nuttx/configs/z8encore000zco/src/Makefile b/nuttx/configs/z8encore000zco/src/Makefile index 73452bfab3..21117dd531 100644 --- a/nuttx/configs/z8encore000zco/src/Makefile +++ b/nuttx/configs/z8encore000zco/src/Makefile @@ -35,20 +35,27 @@ -include $(TOPDIR)/Make.defs -ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src -WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} -USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common' -INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +SCHEDSRCDIR = $(TOPDIR)$(DELIM)sched +ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src -ASRCS = -AOBJS = $(ASRCS:.S=$(OBJEXT)) -CSRCS = z8_lowinit.c z8_leds.c -COBJS = $(CSRCS:.c=$(OBJEXT)) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + USRINCLUDES = -usrinc:'.;$(SCHEDSRCDIR);$(ARCHSRCDIR);$(ARCHSRCDIR)\common' +else + WSCHEDSRCDIR = ${shell cygpath -w $(SCHEDSRCDIR)} + WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} + USRINCLUDES = -usrinc:'.;$(WSCHEDSRCDIR);$(WARCHSRCDIR);$(WARCHSRCDIR)\common' +endif -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) +CSRCS = z8_lowinit.c z8_leds.c +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) all: libboard$(LIBEXT) diff --git a/nuttx/configs/z8f64200100kit/src/Makefile b/nuttx/configs/z8f64200100kit/src/Makefile index 617c3db54e..c9b7a6dc2d 100644 --- a/nuttx/configs/z8f64200100kit/src/Makefile +++ b/nuttx/configs/z8f64200100kit/src/Makefile @@ -35,20 +35,27 @@ -include $(TOPDIR)/Make.defs -ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src -WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} -USRINCLUDES = -usrinc:'.;$(WTOPDIR)\sched;$(WARCHSRCDIR);$(WARCHSRCDIR)\common' -INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +SCHEDSRCDIR = $(TOPDIR)$(DELIM)sched +ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src -ASRCS = -AOBJS = $(ASRCS:.S=$(OBJEXT)) -CSRCS = z8_lowinit.c z8_leds.c -COBJS = $(CSRCS:.c=$(OBJEXT)) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + USRINCLUDES = -usrinc:'.;$(SCHEDSRCDIR);$(ARCHSRCDIR);$(ARCHSRCDIR)\common' +else + WSCHEDSRCDIR = ${shell cygpath -w $(SCHEDSRCDIR)} + WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} + USRINCLUDES = -usrinc:'.;$(WSCHEDSRCDIR);$(WARCHSRCDIR);$(WARCHSRCDIR)\common' +endif -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +INCLUDES = $(ARCHSTDINCLUDES) $(USRINCLUDES) +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) +CSRCS = z8_lowinit.c z8_leds.c +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) all: libboard$(LIBEXT) diff --git a/nuttx/sched/pause.c b/nuttx/sched/pause.c index fb5542d84d..607c4c7751 100644 --- a/nuttx/sched/pause.c +++ b/nuttx/sched/pause.c @@ -86,7 +86,7 @@ * suspend the calling thread until delivery of a signal whose action is * either to execute a signal-catching function or to terminate the * process. This implementation only waits for any non-blocked signal - * to be recieved. + * to be received. * ****************************************************************************/ @@ -96,7 +96,7 @@ int pause(void) struct siginfo value; /* Set up for the sleep. Using the empty set means that we are not - * waiting for any particualar signal. However, any unmasked signal + * waiting for any particular signal. However, any unmasked signal * can still awaken sigtimedwait(). */ diff --git a/nuttx/sched/sleep.c b/nuttx/sched/sleep.c index 03884a5b64..9b3b6d57fc 100644 --- a/nuttx/sched/sleep.c +++ b/nuttx/sched/sleep.c @@ -141,7 +141,7 @@ unsigned int sleep(unsigned int seconds) if (seconds) { /* Set up for the sleep. Using the empty set means that we are not - * waiting for any particualar signal. However, any unmasked signal + * waiting for any particular signal. However, any unmasked signal * can still awaken sigtimedwait(). */ diff --git a/nuttx/sched/usleep.c b/nuttx/sched/usleep.c index 21996d788b..893a420f4e 100644 --- a/nuttx/sched/usleep.c +++ b/nuttx/sched/usleep.c @@ -137,7 +137,7 @@ int usleep(useconds_t usec) if (usec) { /* Set up for the sleep. Using the empty set means that we are not - * waiting for any particualar signal. However, any unmasked signal + * waiting for any particular signal. However, any unmasked signal * can still awaken sigtimedwait(). */ diff --git a/nuttx/tools/README.txt b/nuttx/tools/README.txt index dd971fadc5..68b85dc4f3 100644 --- a/nuttx/tools/README.txt +++ b/nuttx/tools/README.txt @@ -344,6 +344,7 @@ mknulldeps.sh that mixed environment. define.sh +define.bat --------- Different compilers have different conventions for specifying pre- @@ -351,6 +352,9 @@ define.sh script allows the build system to create create command line definitions without concern for the particular compiler in use. + The define.bat script is a counterpart for use in the native Windows + build. + incdir.sh incdir.bat --------- @@ -361,7 +365,7 @@ incdir.bat concern for the particular compiler in use. The incdir.bat script is a counterpart for use in the native Windows - build. However, their is currently only one compiler supported in + build. However, there is currently only one compiler supported in that context: MinGW-GCC. link.sh diff --git a/nuttx/tools/configure.sh b/nuttx/tools/configure.sh index 1cba7805f6..5bff899227 100755 --- a/nuttx/tools/configure.sh +++ b/nuttx/tools/configure.sh @@ -135,11 +135,15 @@ fi # Extract values needed from the defconfig file. We need: # (1) The CONFIG_NUTTX_NEWCONFIG setting to know if this is a "new" style -# configuration, and -# (2) The CONFIG_APPS_DIR to see if there is a configured location for the -# application directory. +# configuration, +# (2) The CONFIG_WINDOWS_NATIVE setting to know it this is target for a +# native Windows (meaning that we want setenv.bat vs setenv.sh and we need +# to use backslashes in the CONFIG_APPS_DIR setting). +# (3) The CONFIG_APPS_DIR setting to see if there is a configured location for the +# application directory. This can be overridden from the command line. newconfig=`grep CONFIG_NUTTX_NEWCONFIG= "${src_config}" | cut -d'=' -f2` +winnative=`grep CONFIG_WINDOWS_NATIVE= "${src_config}" | cut -d'=' -f2` defappdir=y if [ -z "${appdir}" ]; then @@ -175,24 +179,29 @@ if [ -z "${appdir}" ]; then fi fi +# For checking the apps dir path, we need a POSIX version of the relative path. + +posappdir=`echo "${appdir}" | sed -e "s/\\/\/g"` +winappdir=`echo "${appdir}" | sed -e "s/\//\\/g"` + # If appsdir was provided (or discovered) then make sure that the apps/ # directory exists -if [ ! -z "${appdir}" -a ! -d "${TOPDIR}/${appdir}" ]; then - echo "Directory \"${TOPDIR}/${appdir}\" does not exist" +if [ ! -z "${appdir}" -a ! -d "${TOPDIR}/${posappdir}" ]; then + echo "Directory \"${TOPDIR}/${posappdir}\" does not exist" exit 7 fi # Okay... Everything looks good. Setup the configuration -install -C "${src_makedefs}" "${dest_makedefs}" || \ +install "${src_makedefs}" "${dest_makedefs}" || \ { echo "Failed to copy \"${src_makedefs}\"" ; exit 7 ; } if [ "X${have_setenv}" = "Xy" ]; then - install -C "${src_setenv}" "${dest_setenv}" || \ + install "${src_setenv}" "${dest_setenv}" || \ { echo "Failed to copy ${src_setenv}" ; exit 8 ; } chmod 755 "${dest_setenv}" fi -install -C "${src_config}" "${tmp_config}" || \ +install "${src_config}" "${tmp_config}" || \ { echo "Failed to copy \"${src_config}\"" ; exit 9 ; } # If we did not use the CONFIG_APPS_DIR that was in the defconfig config file, @@ -204,7 +213,11 @@ if [ "X${defappdir}" = "Xy" ]; then echo "" >> "${tmp_config}" echo "# Application configuration" >> "${tmp_config}" echo "" >> "${tmp_config}" - echo "CONFIG_APPS_DIR=\"$appdir\"" >> "${tmp_config}" + if [ "X${winnative)" = "Xy" ]; then + echo "CONFIG_APPS_DIR=\"$winappdir\"" >> "${tmp_config}" + else + echo "CONFIG_APPS_DIR=\"$posappdir\"" >> "${tmp_config}" + fi fi # Copy appconfig file. The appconfig file will be copied to ${appdir}/.config @@ -215,7 +228,7 @@ if [ ! -z "${appdir}" -a "X${newconfig}" != "Xy" ]; then if [ ! -r "${configpath}/appconfig" ]; then echo "NOTE: No readable appconfig file found in ${configpath}" else - install -C "${configpath}/appconfig" "${TOPDIR}/${appdir}/.config" || \ + install "${configpath}/appconfig" "${TOPDIR}/${posappdir}/.config" || \ { echo "Failed to copy ${configpath}/appconfig" ; exit 10 ; } fi fi @@ -223,6 +236,5 @@ fi # install the final .configX only if it differs from any existing # .config file. -install -C "${tmp_config}" "${dest_config}" +install "${tmp_config}" "${dest_config}" rm -f "${tmp_config}" - diff --git a/nuttx/tools/define.bat b/nuttx/tools/define.bat new file mode 100644 index 0000000000..13d29ac319 --- /dev/null +++ b/nuttx/tools/define.bat @@ -0,0 +1,178 @@ +@echo off + +rem tools/define.bat +rem +rem Copyright (C) 2012 Gregory Nutt. All rights reserved. +rem Author: Gregory Nutt +rem +rem Redistribution and use in source and binary forms, with or without +rem modification, are permitted provided that the following conditions +rem are met: +rem +rem 1. Redistributions of source code must retain the above copyright +rem notice, this list of conditions and the following disclaimer. +rem 2. Redistributions in binary form must reproduce the above copyright +rem notice, this list of conditions and the following disclaimer in +rem the documentation and/or other materials provided with the +rem distribution. +rem 3. Neither the name NuttX nor the names of its contributors may be +rem used to endorse or promote products derived from this software +rem without specific prior written permission. +rem +rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +rem POSSIBILITY OF SUCH DAMAGE. + +rem Handle command line options +rem [-h] [-val ] [ [-val ] [ [-val ] ...]] +rem [-w] [-d] ignored for compatibility with define.sh + +set progname=%0 + +:ArgLoop +if "%1"=="-d" goto :NextArg +if "%1"=="-w" goto :NextArg +if "%1"=="-h" goto :ShowUsage + +goto :CheckCompilerPath + +:NextArg +shift +goto :ArgLoop + +:CheckCompilerPath + +if "%1"=="" ( + echo Missing compiler path + goto :ShowUsage +) + +set ccpath=%1 +shift + +set compiler= +for /F %%i in ("%ccpath%") do set compiler=%%~ni + +if "%1"=="" ( + echo Missing definition list + goto :ShowUsage +) + +rem Check for some well known, non-GCC Windows native tools that require +rem a special output format as well as special paths + +:GetFormat +set fmt=std +if "%compiler%"=="ez8cc" goto :SetZdsFormt +if "%compiler%"=="zneocc" goto :SetZdsFormt +if "%compiler%"=="ez80cc" goto :SetZdsFormt +goto :ProcessDefinitions + +:SetZdsFormt +set fmt=zds + +rem Now process each directory in the directory list + +:ProcessDefinitions +set response= + +:DefinitionLoop +if "%1"=="" goto :Done + +set varname=%1 +shift + +rem Handle the output depending on if there is a value for the variable or not + +if "%1"=="-val" goto :GetValue + +rem Handle the output using the selected format + +:NoValue +if "%fmt%"=="zds" goto :NoValueZDS + +:NoValueStandard +rem Treat the first definition differently + +if "%response%"=="" ( + set response=-D%varname% + goto :DefinitionLoop +) + +set response=%response% -D%varname% +goto :DefinitionLoop + +:NoValueZDS +rem Treat the first definition differently + +if "%response%"=="" ( + set response=-define:%varname% + goto :DefinitionLoop +) + +set response=%response% -define:%varname% +goto :DefinitionLoop + +rem Get value following the variable name + +:GetValue +shift +set varvalue=%1 +shift + +rem Handle the output using the selected format + +if "%fmt%"=="zds" goto :ValueZDS + +:ValueStandard +rem Treat the first definition differently + +if "%response%"=="" ( + set response=-D%varname%=%varvalue% + goto :DefinitionLoop +) + +set response=%response% -D%varname%=%varvalue% +goto :DefinitionLoop + +:ValueZds +rem Treat the first definition differently + +if "%response%"=="" ( + set response=-define:%varname%=%varvalue% + goto :DefinitionLoop +) + +set response=%response% -define:%varname%=%varvalue% +goto :DefinitionLoop + +:Done +echo %response% +goto :End + +:ShowUsage +echo %progname% is a tool for flexible generation of command line pre-processor +echo definitions arguments for a variety of diffent ccpaths in a variety of +echo compilation environments" +echo USAGE:%progname% [-h] ^ [-val ^<^val1^>] [^ [-val ^] [^ [-val ^] ...]] +echo Where:" +echo ^ +echo The full path to your ccpath +echo ^ ^ ^ ... +echo A list of pre-preprocesser variable names to be defined. +echo [-val ^] [-val ^] [-val ^] ... +echo optional values to be assigned to each pre-processor variable. +echo If not supplied, the variable will be defined with no explicit value. +echo -h +echo Show this text and exit + +:End diff --git a/nuttx/tools/define.sh b/nuttx/tools/define.sh index c53cb92a83..dc982cc648 100755 --- a/nuttx/tools/define.sh +++ b/nuttx/tools/define.sh @@ -1,7 +1,7 @@ #!/bin/bash # tools/define.sh # -# 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 @@ -38,7 +38,7 @@ progname=$0 wintool=n -usage="USAGE: $progname [-w] [-d] [-l] [-h] [=val1] [[=val2] [[=val3] ...]]" +usage="USAGE: $progname [-w] [-d] [-h] [=val1] [[=val2] [[=val3] ...]]" advice="Try '$progname -h' for more information" while [ ! -z "$1" ]; do @@ -60,7 +60,7 @@ while [ ! -z "$1" ]; do echo " " echo " The full path to your compiler" echo " [ ..." - echo " A list of pre-preprocesser variable names to be defind." + echo " A list of pre-preprocesser variable names to be defined." echo " [=val1] [=val2] [=val3]" echo " optional values to be assigned to each pre-processor variable." echo " If not supplied, the variable will be defined with no explicit value." @@ -164,7 +164,7 @@ else fmt=std fi -# Now process each directory in the directory list +# Now process each definition in the definition list unset response for vardef in $varlist; do diff --git a/nuttx/tools/mkdeps.c b/nuttx/tools/mkdeps.c index 289385dfc0..64d81cbd77 100644 --- a/nuttx/tools/mkdeps.c +++ b/nuttx/tools/mkdeps.c @@ -314,18 +314,18 @@ static void parse_args(int argc, char **argv) if (g_debug) { fprintf(stderr, "SELECTIONS\n"); - fprintf(stderr, " CC : \"%s\"\n", g_cc ? g_cc : "(None)"); - fprintf(stderr, " CFLAGS : \"%s\"\n", g_cflags ? g_cflags : "(None)"); - fprintf(stderr, " FILES : \"%s\"\n", g_files ? g_files : "(None)"); - fprintf(stderr, " PATHS : \"%s\"\n", g_altpath ? g_altpath : "(None)"); + fprintf(stderr, " CC : [%s]\n", g_cc ? g_cc : "(None)"); + fprintf(stderr, " CFLAGS : [%s]\n", g_cflags ? g_cflags : "(None)"); + fprintf(stderr, " FILES : [%s]\n", g_files ? g_files : "(None)"); + fprintf(stderr, " PATHS : [%s]\n", g_altpath ? g_altpath : "(None)"); #ifdef HAVE_WINPATH - fprintf(stderr, " Windows Paths : \"%s\"\n", g_winpath ? "TRUE" : "FALSE"); + fprintf(stderr, " Windows Paths : [%s]\n", g_winpath ? "TRUE" : "FALSE"); if (g_winpath) { - fprintf(stderr, " TOPDIR : \"%s\"\n", g_topdir); + fprintf(stderr, " TOPDIR : [%s]\n", g_topdir); } #endif - fprintf(stderr, " Windows Native : \"%s\"\n", g_winnative ? "TRUE" : "FALSE"); + fprintf(stderr, " Windows Native : [%s]\n", g_winnative ? "TRUE" : "FALSE"); } /* Check for required paramters */ From 62432f165f89f1c37ba37f5fa3c91a5c418bc8f3 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 21 Nov 2012 18:19:49 +0000 Subject: [PATCH 149/206] configs/cloudctrl and tools/prebuild.py from Darcy Gong git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5378 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 8 +- nuttx/configs/Kconfig | 7 + nuttx/configs/README.txt | 5 + nuttx/configs/cloudctrl/Kconfig | 8 + nuttx/configs/cloudctrl/README.txt | 869 ++++++++++++++++++ nuttx/configs/cloudctrl/include/board.h | 415 +++++++++ nuttx/configs/cloudctrl/nsh/Make.defs | 173 ++++ nuttx/configs/cloudctrl/nsh/defconfig | 729 +++++++++++++++ nuttx/configs/cloudctrl/nsh/setenv.sh | 78 ++ nuttx/configs/cloudctrl/scripts/ld.script | 115 +++ nuttx/configs/cloudctrl/scripts/ld.script.dfu | 117 +++ nuttx/configs/cloudctrl/src/Makefile | 128 +++ .../cloudctrl/src/cloudctrl-internal.h | 282 ++++++ nuttx/configs/cloudctrl/src/up_adc.c | 174 ++++ nuttx/configs/cloudctrl/src/up_autoleds.c | 408 ++++++++ nuttx/configs/cloudctrl/src/up_boot.c | 117 +++ nuttx/configs/cloudctrl/src/up_buttons.c | 170 ++++ .../configs/cloudctrl/src/up_cxxinitialize.c | 156 ++++ nuttx/configs/cloudctrl/src/up_nsh.c | 160 ++++ nuttx/configs/cloudctrl/src/up_relays.c | 287 ++++++ nuttx/configs/cloudctrl/src/up_spi.c | 177 ++++ nuttx/configs/cloudctrl/src/up_usb.c | 295 ++++++ nuttx/configs/cloudctrl/src/up_usbmsc.c | 104 +++ nuttx/configs/cloudctrl/src/up_userleds.c | 132 +++ nuttx/configs/cloudctrl/src/up_w25.c | 154 ++++ nuttx/configs/cloudctrl/src/up_watchdog.c | 137 +++ .../cloudctrl/tools/olimex-arm-usb-ocd.cfg | 11 + nuttx/configs/cloudctrl/tools/oocd.sh | 92 ++ nuttx/configs/cloudctrl/tools/stm32.cfg | 69 ++ nuttx/configs/cloudctrl/tools/usb-driver.txt | 25 + nuttx/tools/README.txt | 24 + nuttx/tools/prebuild.py | 256 ++++++ 32 files changed, 5881 insertions(+), 1 deletion(-) create mode 100644 nuttx/configs/cloudctrl/Kconfig create mode 100644 nuttx/configs/cloudctrl/README.txt create mode 100644 nuttx/configs/cloudctrl/include/board.h create mode 100644 nuttx/configs/cloudctrl/nsh/Make.defs create mode 100644 nuttx/configs/cloudctrl/nsh/defconfig create mode 100644 nuttx/configs/cloudctrl/nsh/setenv.sh create mode 100644 nuttx/configs/cloudctrl/scripts/ld.script create mode 100644 nuttx/configs/cloudctrl/scripts/ld.script.dfu create mode 100644 nuttx/configs/cloudctrl/src/Makefile create mode 100644 nuttx/configs/cloudctrl/src/cloudctrl-internal.h create mode 100644 nuttx/configs/cloudctrl/src/up_adc.c create mode 100644 nuttx/configs/cloudctrl/src/up_autoleds.c create mode 100644 nuttx/configs/cloudctrl/src/up_boot.c create mode 100644 nuttx/configs/cloudctrl/src/up_buttons.c create mode 100644 nuttx/configs/cloudctrl/src/up_cxxinitialize.c create mode 100644 nuttx/configs/cloudctrl/src/up_nsh.c create mode 100644 nuttx/configs/cloudctrl/src/up_relays.c create mode 100644 nuttx/configs/cloudctrl/src/up_spi.c create mode 100644 nuttx/configs/cloudctrl/src/up_usb.c create mode 100644 nuttx/configs/cloudctrl/src/up_usbmsc.c create mode 100644 nuttx/configs/cloudctrl/src/up_userleds.c create mode 100644 nuttx/configs/cloudctrl/src/up_w25.c create mode 100644 nuttx/configs/cloudctrl/src/up_watchdog.c create mode 100644 nuttx/configs/cloudctrl/tools/olimex-arm-usb-ocd.cfg create mode 100644 nuttx/configs/cloudctrl/tools/oocd.sh create mode 100644 nuttx/configs/cloudctrl/tools/stm32.cfg create mode 100644 nuttx/configs/cloudctrl/tools/usb-driver.txt create mode 100644 nuttx/tools/prebuild.py diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index c5537e17ad..452dd35196 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3652,5 +3652,11 @@ match how they are enabled for other architectures. * configs/ez80f910200kitg: Convert to use mconf configuration. * sched/pause.c: Implements the POSIX pause() function. - + * ez80: Lots of changes to ez80 configurations and build logic as I + struggle to get a clean Windows build (still not working). + * tools/prebuild.py: A Python script for Darcy Gong that can automate + many build/configuration operations. + * configs/cloudctrl: Darcy Gong's CloudController board. This is a + small network relay development board. Based on the Shenzhou IV development + board design. It is based on the STM32F107VC MCU. diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig index 8d812c19bc..70b3ed76ec 100644 --- a/nuttx/configs/Kconfig +++ b/nuttx/configs/Kconfig @@ -45,6 +45,13 @@ config ARCH_BOARD_C5471EVM 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_CLOUDCTRL + bool "Darcy's CloudController stm32f10x board" + depends on ARCH_CHIP_STM32F107VC + ---help--- + Small network relay development board. Based on the Shenzhou IV development + board design. + config ARCH_BOARD_COMPALE88 bool "Compal e88 phone" depends on ARCH_CHIP_CALYPSO diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 575eb690ab..b7d9f84d1e 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -1609,6 +1609,11 @@ configs/c5471evm NuttX runs on the ARM core and is built with a GNU arm-nuttx-elf toolchain*. This port is complete and verified. +configs/cloudctrl + Darcy's CloudController board. This is a small network relay development + board. Based on the Shenzhou IV development board design. It is based on + the STM32F107VC MCU. + configs/compal_e88 and compal_e99 These directories contain the board support for compal e88 and e99 phones. These ports are based on patches contributed by Denis Carikli for both the diff --git a/nuttx/configs/cloudctrl/Kconfig b/nuttx/configs/cloudctrl/Kconfig new file mode 100644 index 0000000000..a98bcae4c0 --- /dev/null +++ b/nuttx/configs/cloudctrl/Kconfig @@ -0,0 +1,8 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +if ARCH_BOARD_CLOUDCTRL + +endif diff --git a/nuttx/configs/cloudctrl/README.txt b/nuttx/configs/cloudctrl/README.txt new file mode 100644 index 0000000000..f931f3a12a --- /dev/null +++ b/nuttx/configs/cloudctrl/README.txt @@ -0,0 +1,869 @@ +README +====== + +This README discusses issues unique to NuttX configurations for the CloudController +development board featuring the STMicro STM32F107VCT MCU. + +Features of the CloudController board include: + + - STM32F107VCT + - 10/100M PHY (DM9161AEP) + - USB OTG + - USART connectos (USART1-2) + - SPI Flash (W25X16) + - (3) LEDs (LED1-3) + - (3) Buttons (KEY1-3, USERKEY2, USERKEY, TEMPER, WAKEUP) + - 5V/3.3V power conversion + - SWD + +Contents +======== + + - STM32F107VCT Pin Usage + - Development Environment + - GNU Toolchain Options + - IDEs + - NuttX EABI buildroot Toolchain + - NuttX OABI buildroot Toolchain + - NXFLAT Toolchain + - Cloudctrl-specific Configuration Options + - LEDs + - Cloudctrl-specific Configuration Options + - Configurations + +STM32F107VCT Pin Usage +====================== + +-- ---- -------------- ------------------------------------------------------------------- +PN NAME SIGNAL NOTES +-- ---- -------------- ------------------------------------------------------------------- +**23 PA0 WAKEUP Connected to KEY4. Active low: Closing KEY4 pulls WAKEUP to ground. +24 PA1 MII_RX_CLK + RMII_REF_CLK +25 PA2 MII_MDIO +26 PA3 315M_VT +29 PA4 DAC_OUT1 To CON5(CN14) +30 PA5 DAC_OUT2 To CON5(CN14). JP10 + SPI1_SCK To the SD card, SPI FLASH +31 PA6 SPI1_MISO To the SD card, SPI FLASH +32 PA7 SPI1_MOSI To the SD card, SPI FLASH +67 PA8 MCO To DM9161AEP PHY +68 PA9 USB_VBUS MINI-USB-AB. JP3 + USART1_TX MAX3232 to CN5 +69 PA10 USB_ID MINI-USB-AB. JP5 + USART1_RX MAX3232 to CN5 +70 PA11 USB_DM MINI-USB-AB +71 PA12 USB_DP MINI-USB-AB +72 PA13 TMS/SWDIO +76 PA14 TCK/SWCLK +77 PA15 TDI + +-- ---- -------------- ------------------------------------------------------------------- +PN NAME SIGNAL NOTES +-- ---- -------------- ------------------------------------------------------------------- +35 PB0 ADC_IN1 To CON5(CN14) +36 PB1 ADC_IN2 To CON5(CN14) +37 PB2 DATA_LE To TFT LCD (CN13) + BOOT1 JP13 +89 PB3 TDO/SWO +90 PB4 TRST +91 PB5 CAN2_RX +92 PB6 CAN2_TX JP11 + I2C1_SCL +93 PB7 I2C1_SDA +95 PB8 USB_PWR Drives USB VBUS +96 PB9 F_CS To both the TFT LCD (CN13) and to the W25X16 SPI FLASH +47 PB10 USERKEY Connected to KEY2 +48 PB11 MII_TX_EN Ethernet PHY +51 PB12 I2S_WS Audio DAC + MII_TXD0 Ethernet PHY +52 PB13 I2S_CK Audio DAC + MII_TXD1 Ethernet PHY +53 PB14 SD_CD There is confusion here. Schematic is wrong LCD_WR is PB14. +54 PB15 I2S_DIN Audio DAC + +-- ---- -------------- ------------------------------------------------------------------- +PN NAME SIGNAL NOTES +-- ---- -------------- ------------------------------------------------------------------- +15 PC0 POTENTIO_METER +16 PC1 MII_MDC Ethernet PHY +17 PC2 WIRELESS_INT +18 PC3 WIRELESS_CE To the NRF24L01 2.4G wireless module +33 PC4 USERKEY2 Connected to KEY1 +34 PC5 TP_INT JP6. To TFT LCD (CN13) module + MII_INT Ethernet PHY +63 PC6 I2S_MCK Audio DAC. Active low: Pulled high +64 PC7 PCM1770_CS Audio DAC. Active low: Pulled high +65 PC8 LCD_CS TFT LCD (CN13). Active low: Pulled high +66 PC9 TP_CS TFT LCD (CN13). Active low: Pulled high +78 PC10 SPI3_SCK To TFT LCD (CN13), the NRF24L01 2.4G wireless module +79 PC11 SPI3_MISO To TFT LCD (CN13), the NRF24L01 2.4G wireless module +80 PC12 SPI3_MOSI To TFT LCD (CN13), the NRF24L01 2.4G wireless module +7 PC13 TAMPER Connected to KEY3 +8 PC14 OSC32_IN Y1 32.768Khz XTAL +9 PC15 OSC32_OUT Y1 32.768Khz XTAL + +-- ---- -------------- ------------------------------------------------------------------- +PN NAME SIGNAL NOTES +-- ---- -------------- ------------------------------------------------------------------- +81 PD0 CAN1_RX +82 PD1 CAN1_TX +83 PD2 LED1 Active low: Pulled high +84 PD3 LED2 Active low: Pulled high +85 PD4 LED3 Active low: Pulled high +86 PD5 485_TX Same as USART2_TX but goes to SP3485 + USART2_TX MAX3232 to CN6 +87 PD6 485_RX Save as USART2_RX but goes to SP3485 (see JP4) + USART2_RX MAX3232 to CN6 +88 PD7 LED4 Active low: Pulled high + 485_DIR SP3485 read enable (not) +55 PD8 MII_RX_DV Ethernet PHY + RMII_CRSDV Ethernet PHY +56 PD9 MII_RXD0 Ethernet PHY +57 PD10 MII_RXD1 Ethernet PHY +58 PD11 SD_CS Active low: Pulled high (See also TFT LCD CN13, pin 32) +59 PD12 WIRELESS_CS To the NRF24L01 2.4G wireless module +60 PD13 LCD_RS To TFT LCD (CN13) +61 PD14 LCD_WR To TFT LCD (CN13). Schematic is wrong LCD_WR is PB14. +62 PD15 LCD_RD To TFT LCD (CN13) + +-- ---- -------------- ------------------------------------------------------------------- +PN NAME SIGNAL NOTES +-- ---- -------------- ------------------------------------------------------------------- +97 PE0 DB00 To TFT LCD (CN13) +98 PE1 DB01 To TFT LCD (CN13) +1 PE2 DB02 To TFT LCD (CN13) +2 PE3 DB03 To TFT LCD (CN13) +3 PE4 DB04 To TFT LCD (CN13) +4 PE5 DB05 To TFT LCD (CN13) +5 PE6 DB06 To TFT LCD (CN13) +38 PE7 DB07 To TFT LCD (CN13) +39 PE8 DB08 To TFT LCD (CN13) +40 PE9 DB09 To TFT LCD (CN13) +41 PE10 DB10 To TFT LCD (CN13) +42 PE11 DB11 To TFT LCD (CN13) +43 PE12 DB12 To TFT LCD (CN13) +44 PE13 DB13 To TFT LCD (CN13) +45 PE14 DB14 To TFT LCD (CN13) +46 PE15 DB15 To TFT LCD (CN13) + +-- ---- -------------- ------------------------------------------------------------------- +PN NAME SIGNAL NOTES +-- ---- -------------- ------------------------------------------------------------------- +73 N/C + +12 OSC_IN Y2 25Mhz XTAL +13 OSC_OUT Y2 25Mhz XTAL + +94 BOOT0 JP15 (3.3V or GND) +14 RESET S5 +6 VBAT JP14 (3.3V or battery) + +49 VSS_1 GND +74 VSS_2 GND +99 VSS_3 GND +27 VSS_4 GND +10 VSS_5 GND +19 VSSA VSSA +20 VREF- VREF- + +Development Environment +======================= + + Either Linux or Cygwin on Windows can be used for the development environment. + The source has been built only using the GNU toolchain (see below). Other + toolchains will likely cause problems. Testing was performed using the Cygwin + environment because the development tools that I used only work under Windows. + +GNU Toolchain Options +===================== + + Toolchain Configurations + ------------------------ + The NuttX make system has been modified to support the following different + toolchain options. + + 1. The CodeSourcery GNU toolchain, + 2. The Atollic Toolchain, + 3. The devkitARM GNU toolchain, + 4. Raisonance GNU toolchain, or + 5. The NuttX buildroot Toolchain (see below). + + Most testing has been conducted using the CodeSourcery toolchain for Windows and + that is the default toolchain in most configurations. To use the Atollic, + devkitARM, Raisonance GNU, or NuttX buildroot toolchain, you simply need to + add one of the following configuration options to your .config (or defconfig) + file: + + CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux + CONFIG_STM32_ATOLLIC_LITE=y : The free, "Lite" version of Atollic toolchain under Windows + CONFIG_STM32_ATOLLIC_PRO=y : The paid, "Pro" version of Atollic toolchain under Windows + 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) + + If you change the default toolchain, then you may also have to modify the PATH in + the setenv.h file if your make cannot find the tools. + + NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are + Windows native toolchains. The CodeSourcery (for Linux) and NuttX buildroot + toolchains are Cygwin and/or Linux native toolchains. There are several limitations + to using a Windows based toolchain in a Cygwin environment. The three biggest are: + + 1. The Windows toolchain cannot follow Cygwin paths. Path conversions are + performed automatically in the Cygwin makefiles using the 'cygpath' utility + but you might easily find some new path problems. If so, check out 'cygpath -w' + + 2. Windows toolchains cannot follow Cygwin symbolic links. Many symbolic links + are used in Nuttx (e.g., include/arch). The make system works around these + problems for the Windows tools by copying directories instead of linking them. + But this can also cause some confusion for you: For example, you may edit + a file in a "linked" directory and find that your changes had no effect. + That is because you are building the copy of the file in the "fake" symbolic + directory. If you use a Windows toolchain, you should get in the habit of + making like this: + + make clean_context all + + An alias in your .bashrc file might make that less painful. + + 3. Dependencies are not made when using Windows versions of the GCC. This is + because the dependencies are generated using Windows pathes which do not + work with the Cygwin make. + + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + + The CodeSourcery Toolchain (2009q1) + ----------------------------------- + The CodeSourcery toolchain (2009q1) does not work with default optimization + level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with + -Os. + + The Atollic "Pro" and "Lite" Toolchain + -------------------------------------- + One problem that I had with the Atollic toolchains is that the provide a gcc.exe + and g++.exe in the same bin/ file as their ARM binaries. If the Atollic bin/ path + appears in your PATH variable before /usr/bin, then you will get the wrong gcc + when you try to build host executables. This will cause to strange, uninterpretable + errors build some host binaries in tools/ when you first make. + + The Atollic "Lite" Toolchain + ---------------------------- + The free, "Lite" version of the Atollic toolchain does not support C++ nor + does it support ar, nm, objdump, or objdcopy. If you use the Atollic "Lite" + toolchain, you will have to set: + + CONFIG_HAVE_CXX=n + + In order to compile successfully. Otherwise, you will get errors like: + + "C++ Compiler only available in TrueSTUDIO Professional" + + The make may then fail in some of the post link processing because of some of + the other missing tools. The Make.defs file replaces the ar and nm with + the default system x86 tool versions and these seem to work okay. Disable all + of the following to avoid using objcopy: + + CONFIG_RRLOAD_BINARY=n + CONFIG_INTELHEX_BINARY=n + CONFIG_MOTOROLA_SREC=n + CONFIG_RAW_BINARY=n + + devkitARM + --------- + The devkitARM toolchain includes a version of MSYS make. Make sure that the + the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM + path or will get the wrong version of make. + +IDEs +==== + + NuttX is built using command-line make. It can be used with an IDE, but some + effort will be required to create the project. + + Makefile Build + -------------- + Under Eclipse, it is pretty easy to set up an "empty makefile project" and + simply use the NuttX makefile to build the system. That is almost for free + under Linux. Under Windows, you will need to set up the "Cygwin GCC" empty + makefile project in order to work with Windows (Google for "Eclipse Cygwin" - + there is a lot of help on the internet). + + Native Build + ------------ + Here are a few tips before you start that effort: + + 1) Select the toolchain that you will be using in your .config file + 2) Start the NuttX build at least one time from the Cygwin command line + before trying to create your project. This is necessary to create + certain auto-generated files and directories that will be needed. + 3) Set up include pathes: You will need include/, arch/arm/src/stm32, + arch/arm/src/common, arch/arm/src/armv7-m, and sched/. + 4) All assembly files need to have the definition option -D __ASSEMBLY__ + on the command line. + + Startup files will probably cause you some headaches. The NuttX startup file + is arch/arm/src/stm32/stm32_vectors.S. With RIDE, I have to build NuttX + one time from the Cygwin command line in order to obtain the pre-built + startup object needed by RIDE. + +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 + different from the default in your PATH variable). + + If you have no Cortex-M3 toolchain, one can be downloaded from the NuttX + SourceForge download site (https://sourceforge.net/projects/nuttx/files/buildroot/). + 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 shenzhou/ + + cd .. + make context + + 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-eabi-defconfig-4.6.3 .config + + 6. make oldconfig + + 7. make + + 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. + + 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 +================================ + + 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 +==== + +The Cloudctrl board has four LEDs labeled LED1, LED2, LED3 and LED4 on the +board. These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is +defined. In that case, the usage by the board port is defined in +include/board.h and src/up_leds.c. The LEDs are used to encode OS-related +events 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) + + * 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 + ** The normal state is LED1 ON and LED1 faintly glowing. This faint glow + is because of timer interupts that result in the LED being illuminated + on a small proportion of the time. + *** LED2 may also flicker normally if signals are processed. +**** LED4 may not be available if RS-485 is also used. For RS-485, it will + then indicate the RS-485 direction. + +Cloudctrl-specific Configuration Options +============================================ + + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: + + CONFIG_ARCH=arm + + CONFIG_ARCH_family - For use in C code: + + CONFIG_ARCH_ARM=y + + CONFIG_ARCH_architecture - For use in C code: + + CONFIG_ARCH_CORTEXM3=y + + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + + CONFIG_ARCH_CHIP=stm32 + + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: + + CONFIG_ARCH_CHIP_STM32F107VC=y + + 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=shenzhou (for the Cloudctrl development board) + + CONFIG_ARCH_BOARD_name - For use in C code + + CONFIG_ARCH_BOARD_SHENZHOU=y + + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops + + 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=0x00010000 (64Kb) + + CONFIG_DRAM_START - The start address of installed DRAM + + CONFIG_DRAM_START=0x20000000 + + CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP + + CONFIG_ARCH_IRQPRIO - The STM32107xxx supports interrupt prioritization + + CONFIG_ARCH_IRQPRIO=y + + 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_STACKDUMP - Do stack dumps after assertions + + 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. + + Individual subsystems can be enabled: + + AHB + --- + CONFIG_STM32_DMA1 + CONFIG_STM32_DMA2 + CONFIG_STM32_CRC + CONFIG_STM32_ETHMAC + CONFIG_STM32_OTGFS + CONFIG_STM32_IWDG + CONFIG_STM32_PWR -- Required for RTC + + APB1 (low speed) + ---------------- + CONFIG_STM32_BKP + CONFIG_STM32_TIM2 + CONFIG_STM32_TIM3 + CONFIG_STM32_TIM4 + CONFIG_STM32_TIM5 + CONFIG_STM32_TIM6 + CONFIG_STM32_TIM7 + CONFIG_STM32_USART2 + CONFIG_STM32_USART3 + CONFIG_STM32_UART4 + CONFIG_STM32_UART5 + CONFIG_STM32_SPI2 + CONFIG_STM32_SPI3 + CONFIG_STM32_I2C1 + CONFIG_STM32_I2C2 + CONFIG_STM32_CAN1 + CONFIG_STM32_CAN2 + CONFIG_STM32_DAC1 + CONFIG_STM32_DAC2 + CONFIG_STM32_WWDG + + APB2 (high speed) + ----------------- + CONFIG_STM32_TIM1 + CONFIG_STM32_SPI1 + CONFIG_STM32_USART1 + CONFIG_STM32_ADC1 + CONFIG_STM32_ADC2 + + 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 + initialized). + + CONFIG_STM32_FORCEPOWER + + Timer devices may be used for different purposes. One special purpose is + to generate modulated outputs for such things as motor control. If CONFIG_STM32_TIMn + is defined (as above) then the following may also be defined to indicate that + the timer is intended to be used for pulsed output modulation, ADC conversion, + or DAC conversion. Note that ADC/DAC require two definition: Not only do you have + 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,..,14 + CONFIG_STM32_TIMn_ADC Reserve timer n for use by ADC, n=1,..,14 + CONFIG_STM32_TIMn_ADCm Reserve timer n to trigger ADCm, n=1,..,14, m=1,..,3 + CONFIG_STM32_TIMn_DAC Reserve timer n for use by DAC, n=1,..,14 + CONFIG_STM32_TIMn_DACm Reserve timer n to trigger DACm, n=1,..,14, m=1,..,2 + + For each timer that is enabled for PWM usage, we need the following additional + configuration settings: + + CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4} + + NOTE: The STM32 timers are each capable of generating different signals on + each of the four channels with different duty cycles. That capability is + not supported by this driver: Only one output channel per timer. + + JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): + + CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) + CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) + but without JNTRST. + CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled + + STM32107xxx specific device driver settings + + 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). + 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_STM32_PHYADDR - The 5-bit address of the PHY on the board + CONFIG_STM32_MII - Support Ethernet MII interface + CONFIG_STM32_MII_MCO - Use MCO to clock the MII interface + CONFIG_STM32_RMII - Support Ethernet RMII interface + CONFIG_STM32_RMII_MCO - Use MCO to clock the RMII interface + CONFIG_STM32_AUTONEG - Use PHY autonegotion to determine speed and mode + CONFIG_STM32_ETHFD - If CONFIG_STM32_AUTONEG is not defined, then this + may be defined to select full duplex mode. Default: half-duplex + CONFIG_STM32_ETH100MBPS - If CONFIG_STM32_AUTONEG is not defined, then this + may be defined to select 100 MBps speed. Default: 10 Mbps + CONFIG_STM32_PHYSR - This must be provided if CONFIG_STM32_AUTONEG is + defined. The PHY status register address may diff from PHY to PHY. This + configuration sets the address of the PHY status register. + CONFIG_STM32_PHYSR_SPEED - This must be provided if CONFIG_STM32_AUTONEG is + defined. This provides bit mask indicating 10 or 100MBps speed. + CONFIG_STM32_PHYSR_100MBPS - This must be provided if CONFIG_STM32_AUTONEG is + defined. This provides the value of the speed bit(s) indicating 100MBps speed. + CONFIG_STM32_PHYSR_MODE - This must be provided if CONFIG_STM32_AUTONEG is + defined. This provide bit mask indicating full or half duplex modes. + CONFIG_STM32_PHYSR_FULLDUPLEX - This must be provided if CONFIG_STM32_AUTONEG is + defined. This provides the value of the mode bits indicating full duplex mode. + CONFIG_STM32_ETH_PTP - Precision Time Protocol (PTP). Not supported + but some hooks are indicated with this condition. + + Cloudctrl CAN Configuration + + CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or + CONFIG_STM32_CAN2 must also be defined) + 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. + + Cloudctrl LCD Hardware Configuration + + The LCD driver supports the following LCDs on the STM324xG_EVAL board: + + AM-240320L8TNQW00H (LCD_ILI9320 or LCD_ILI9321) OR + AM-240320D5TOQW01H (LCD_ILI9325) + + Configuration options. + + CONFIG_LCD_LANDSCAPE - Define for 320x240 display "landscape" + support. Default is this 320x240 "landscape" orientation + For the Cloudctrl board, the edge opposite from the row of buttons + is used as the top of the display in this orientation. + CONFIG_LCD_RLANDSCAPE - Define for 320x240 display "reverse + landscape" support. Default is this 320x240 "landscape" + orientation + For the Cloudctrl board, the edge next to the row of buttons + is used as the top of the display in this orientation. + CONFIG_LCD_PORTRAIT - Define for 240x320 display "portrait" + orientation support. + CONFIG_LCD_RPORTRAIT - Define for 240x320 display "reverse + portrait" orientation support. + CONFIG_LCD_RDSHIFT - When reading 16-bit gram data, there appears + to be a shift in the returned data. This value fixes the offset. + Default 5. + + The LCD driver dynamically selects the LCD based on the reported LCD + ID value. However, code size can be reduced by suppressing support for + individual LCDs using: + + CONFIG_STM32_ILI9320_DISABLE (includes ILI9321) + CONFIG_STM32_ILI9325_DISABLE + + STM32 USB OTG FS Host Driver Support + + Pre-requisites + + CONFIG_USBHOST - Enable USB host support + CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block + CONFIG_STM32_SYSCFG - Needed + CONFIG_SCHED_WORKQUEUE - Worker thread support is required + + Options: + + CONFIG_STM32_OTGFS_RXFIFO_SIZE - Size of the RX FIFO in 32-bit words. + Default 128 (512 bytes) + CONFIG_STM32_OTGFS_NPTXFIFO_SIZE - Size of the non-periodic Tx FIFO + in 32-bit words. Default 96 (384 bytes) + CONFIG_STM32_OTGFS_PTXFIFO_SIZE - Size of the periodic Tx FIFO in 32-bit + words. Default 96 (384 bytes) + CONFIG_STM32_OTGFS_DESCSIZE - Maximum size of a descriptor. Default: 128 + CONFIG_STM32_OTGFS_SOFINTR - Enable SOF interrupts. Why would you ever + want to do that? + CONFIG_STM32_USBHOST_REGDEBUG - Enable very low-level register access + debug. Depends on CONFIG_DEBUG. + CONFIG_STM32_USBHOST_PKTDUMP - Dump all incoming and outgoing USB + packets. Depends on CONFIG_DEBUG. + +Configurations +============== + +Each Cloudctrl configuration is maintained in a sudirectory and +can be selected as follow: + + cd tools + ./configure.sh shenzhou/ + cd - + . ./setenv.sh + +Where is one of the following: + + nsh: + --- + Configures the NuttShell (nsh) located at apps/examples/nsh. The + Configuration enables both the serial and telnet NSH interfaces. + + CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + CONFIG_NSH_DHCPC=n : DHCP is disabled + CONFIG_NSH_IPADDR=0x0a000002 : Target IP address 10.0.0.2 + CONFIG_NSH_DRIPADDR=0x0a000001 : Host IP address 10.0.0.1 + + NOTES: + 1. This example assumes that a network is connected. During its + initialization, it will try to negotiate the link speed. If you have + no network connected when you reset the board, there will be a long + delay (maybe 30 seconds?) before anything happens. That is the timeout + before the networking finally gives up and decides that no network is + available. + + 2. Enabling the ADC example: + + The only internal signal for ADC testing is the potentiometer input: + + ADC1_IN10(PC0) Potentiometer + + External signals are also available on CON5 CN14: + + ADC_IN8 (PB0) CON5 CN14 Pin2 + ADC_IN9 (PB1) CON5 CN14 Pin1 + + The signal selection is hard-coded in configs/shenzhou/src/up_adc.c: The + potentiometer input (only) is selected. + + These selections will enable sampling the potentiometer input at 100Hz using + Timer 1: + + CONFIG_ANALOG=y : Enable analog device support + CONFIG_ADC=y : Enable generic ADC driver support + CONFIG_ADC_DMA=n : ADC DMA is not supported + CONFIG_STM32_ADC1=y : Enable ADC 1 + CONFIG_STM32_TIM1=y : Enable Timer 1 + CONFIG_STM32_TIM1_ADC=y : Use Timer 1 for ADC + CONFIG_STM32_TIM1_ADC1=y : Allocate Timer 1 to ADC 1 + CONFIG_STM32_ADC1_SAMPLE_FREQUENCY=100 : Set sampling frequency to 100Hz + CONFIG_STM32_ADC1_TIMTRIG=0 : Trigger on timer output 0 + CONFIG_STM32_FORCEPOWER=y : Apply power to TIM1 a boot up time + CONFIG_EXAMPLES_ADC=y : Enable the apps/examples/adc built-in + + nxwm + ---- + This is a special configuration setup for the NxWM window manager + UnitTest. The NxWM window manager can be found here: + + nuttx-code/NxWidgets/nxwm + + The NxWM unit test can be found at: + + 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 + interrupt. + + Documentation for installing the NxWM unit test can be found here: + + nuttx-code/NxWidgets/UnitTests/README.txt + + 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-code/tools + $ ./configure.sh shenzhou/nxwm + + 2. Make the build context (only) + + $ cd .. + $ . ./setenv.sh + $ make context + ... + + 3. Install the nxwm unit test + + $ cd ~/nuttx-code/NxWidgets + $ tools/install.sh ~/nuttx-code/apps nxwm + Creating symbolic link + - To ~/nuttx-code/NxWidgets/UnitTests/nxwm + - At ~/nuttx-code/apps/external + + 4. Build the NxWidgets library + + $ cd ~/nuttx-code/NxWidgets/libnxwidgets + $ make TOPDIR=~/nuttx-code + ... + + 5. Build the NxWM library + + $ cd ~/nuttx-code/NxWidgets/nxwm + $ make TOPDIR=~/nuttx-code + ... + + 6. Built NuttX with the installed unit test as the application + + $ cd ~/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. + + 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 + + -CONFIG_NX_WRITEONLY=y + +# CONFIG_NX_WRITEONLY is not set + + thttpd + ------ + + 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 due to incompatibilities introduced in later + GCC releases. diff --git a/nuttx/configs/cloudctrl/include/board.h b/nuttx/configs/cloudctrl/include/board.h new file mode 100644 index 0000000000..5f5e86ebc4 --- /dev/null +++ b/nuttx/configs/cloudctrl/include/board.h @@ -0,0 +1,415 @@ +/************************************************************************************ + * configs/cloudctrl/include/board.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __CONFIGS_CLOUDCTRL_INCLUDE_BOARD_H +#define __CONFIGS_CLOUDCTRL_INCLUDE_BOARD_H 1 + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +#endif +#include "stm32_rcc.h" +#include "stm32_sdio.h" +#include "stm32_internal.h" + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ + +/* 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 */ +#define STM32_PLL_PLL2MUL RCC_CFGR2_PLL2MULx8 /* 5MHz * 8 => 40MHz */ +#define STM32_PLL_PREDIV1 RCC_CFGR2_PREDIV1d5 /* 40MHz / 5 => 8MHz */ +#define STM32_PLL_PLLMUL RCC_CFGR_PLLMUL_CLKx9 /* 8MHz * 9 => 72Mhz */ +#define STM32_PLL_FREQUENCY (72000000) + +/* SYCLLK and HCLK are the PLL frequency */ + +#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY +#define STM32_HCLK_FREQUENCY STM32_PLL_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB2 clock (PCLK2) is HCLK (72MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK +#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY +#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-7, 12-14 */ + +/* APB2 timers 1 and 8 will receive PCLK2. */ + +#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY) + +/* APB1 clock (PCLK1) is HCLK/2 (36MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB1 timers 2-4 will be twice PCLK1 (I presume the remaining will receive PCLK1) */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (STM32_PCLK1_FREQUENCY) + +/* MCO output driven by PLL3. From above, we already have PLL3 input frequency as: + * + * STM32_PLL_PREDIV2 = 5, 25MHz / 5 => 5MHz + */ + +#if defined(CONFIG_STM32_MII_MCO) || defined(CONFIG_STM32_RMII_MCO) +# define BOARD_CFGR_MCO_SOURCE RCC_CFGR_PLL3CLK /* Source: PLL3 */ +# define STM32_PLL_PLL3MUL RCC_CFGR2_PLL3MULx10 /* MCO 5MHz * 10 = 50MHz */ +#endif + +/* LED definitions ******************************************************************/ +/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any + * way. The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with stm32_setled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_LED4 3 +#define BOARD_NLEDS 4 + +/* LED bits for use with stm32_setleds() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) +#define BOARD_LED4_BIT (1 << BOARD_LED4) + +/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 4 LEDs on board the + * STM3240G-EVAL. The following definitions describe how NuttX controls the LEDs: + */ + +#define LED_STARTED 0 /* LED1 */ +#define LED_HEAPALLOCATE 1 /* LED2 */ +#define LED_IRQSENABLED 2 /* LED1 + LED2 */ +#define LED_STACKCREATED 3 /* LED3 */ +#define LED_INIRQ 4 /* LED1 + LED3 */ +#define LED_SIGNAL 5 /* LED2 + LED3 */ +#define LED_ASSERTION 6 /* LED1 + LED2 + LED3 */ +#define LED_PANIC 7 /* N/C + N/C + N/C + LED4 */ + +/* Button definitions ***************************************************************/ +/* The STM3240G-EVAL supports three buttons: */ + +#define BUTTON_KEY1 0 /* Name printed on board */ +#define BUTTON_KEY2 1 +#define BUTTON_KEY3 2 +#define NUM_BUTTONS 3 + +#define BUTTON_USERKEY BUTTON_KEY1 /* Names in schematic */ +#define BUTTON_TAMPER BUTTON_KEY2 +#define BUTTON_WAKEUP BUTTON_KEY3 + +#define BUTTON_KEY1_BIT (1 << BUTTON_KEY1) +#define BUTTON_KEY2_BIT (1 << BUTTON_KEY2) +#define BUTTON_KEY3_BIT (1 << BUTTON_KEY3) + +#define BUTTON_USERKEY_BIT BUTTON_KEY1_BIT +#define BUTTON_TAMPER_BIT BUTTON_KEY2_BIT +#define BUTTON_WAKEUP_BIT BUTTON_KEY3_BIT + +/* Relays */ + +#define NUM_RELAYS 2 + +/* Pin selections ******************************************************************/ +/* Ethernet + * + * -- ---- -------------- ---------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ---------------------------------------------------------- + * 24 PA1 MII_RX_CLK Ethernet PHY NOTE: Despite the MII labeling of these + * RMII_REF_CLK Ethernet PHY signals, the DM916AEP is actually configured + * 25 PA2 MII_MDIO Ethernet PHY to work in RMII mode. + * 48 PB11 MII_TX_EN Ethernet PHY + * 51 PB12 MII_TXD0 Ethernet PHY + * 52 PB13 MII_TXD1 Ethernet PHY + * 16 PC1 MII_MDC Ethernet PHY + * 34 PC5 MII_INT Ethernet PHY + * 55 PD8 MII_RX_DV Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP + * 55 PD8 RMII_CRSDV Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP + * 56 PD9 MII_RXD0 Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP + * 57 PD10 MII_RXD1 Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP + * + * The board desdign can support a 50MHz external clock to drive the PHY + * (U9). However, on my board, U9 is not present. + * + * 67 PA8 MCO DM9161AEP + */ + +#ifdef CONFIG_STM32_ETHMAC +# ifndef CONFIG_STM32_ETH_REMAP +# error "STM32 Ethernet requires CONFIG_STM32_ETH_REMAP" +# endif +# ifndef CONFIG_STM32_RMII +# error "STM32 Ethernet requires CONFIG_STM32_RMII" +# endif +# ifndef CONFIG_STM32_RMII_MCO +# error "STM32 Ethernet requires CONFIG_STM32_RMII_MCO" +# endif +#endif + +/* USB + * + * -- ---- -------------- ---------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ---------------------------------------------------------- + * 68 PA9 USB_VBUS MINI-USB-AB. JP3 + * 69 PA10 USB_ID MINI-USB-AB. JP5 + * 70 PA11 USB_DM MINI-USB-AB + * 71 PA12 USB_DP MINI-USB-AB + * 95 PB8 USB_PWR Drives USB VBUS + */ + +/* UARTS/USARTS + * + * -- ---- -------------- ---------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ---------------------------------------------------------- + * 68 PA9 USART1_TX MAX3232 to CN5. Requires CONFIG_STM32_USART1_REMAP + * 69 PA10 USART1_RX MAX3232 to CN5. Requires CONFIG_STM32_USART1_REMAP + * 86 PD5 USART2_TX MAX3232 to CN6. Requires CONFIG_STM32_USART2_REMAP + * 87 PD6 USART2_RX MAX3232 to CN6. Requires CONFIG_STM32_USART2_REMAP + * 86 PD5 485_TX Same as USART2_TX but goes to SP3485 + * 87 PD6 485_RX Save as USART2_RX but goes to SP3485 (see JP4) + */ + +#if defined(CONFIG_STM32_USART1) && !defined(CONFIG_STM32_USART1_REMAP) +# error "CONFIG_STM32_USART1 requires CONFIG_STM32_USART1_REMAP" +#endif + +#if defined(CONFIG_STM32_USART2) && !defined(CONFIG_STM32_USART2_REMAP) +# error "CONFIG_STM32_USART2 requires CONFIG_STM32_USART2_REMAP" +#endif + +/* SPI + * + * -- ---- -------------- ---------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ---------------------------------------------------------- + * 30 PA5 SPI1_SCK To the SD card, SPI FLASH. + * Requires !CONFIG_STM32_SPI1_REMAP + * 31 PA6 SPI1_MISO To the SD card, SPI FLASH. + * Requires !CONFIG_STM32_SPI1_REMAP + * 32 PA7 SPI1_MOSI To the SD card, SPI FLASH. + * Requires !CONFIG_STM32_SPI1_REMAP + * 78 PC10 SPI3_SCK To TFT LCD (CN13), the NRF24L01 2.4G wireless module. + * Requires CONFIG_STM32_SPI3_REMAP. + * 79 PC11 SPI3_MISO To TFT LCD (CN13), the NRF24L01 2.4G wireless module. + * Requires CONFIG_STM32_SPI3_REMAP. + * 80 PC12 SPI3_MOSI To TFT LCD (CN13), the NRF24L01 2.4G wireless module. + * Requires CONFIG_STM32_SPI3_REMAP. + */ + +#if defined(CONFIG_STM32_SPI1) && defined(CONFIG_STM32_SPI1_REMAP) +# error "CONFIG_STM32_SPI1 must not have CONFIG_STM32_SPI1_REMAP" +#endif + +#if defined(CONFIG_STM32_SPI3) && !defined(CONFIG_STM32_SPI3_REMAP) +# error "CONFIG_STM32_SPI3 requires CONFIG_STM32_SPI3_REMAP" +#endif + +/* DAC + * + * -- ---- -------------- ---------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ---------------------------------------------------------- + * 29 PA4 DAC_OUT1 To CON5(CN14) + * 30 PA5 DAC_OUT2 To CON5(CN14). JP10 + */ + +/* ADC + * + * -- ---- -------------- ---------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ---------------------------------------------------------- + * 35 PB0 ADC_IN1 GPIO_ADC12_IN8. To CON5(CN14) + * 36 PB1 ADC_IN2 GPIO_ADC12_IN9. To CON5(CN14) + * 15 PC0 POTENTIO_METER GPIO_ADC12_IN10 + */ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32_boardinitialize(void); + +/************************************************************************************ + * Button support. + * + * Description: + * up_buttoninit() must be called to initialize button resources. After + * that, up_buttons() may be called to collect the current state of all + * buttons or up_irqbutton() may be called to register button interrupt + * handlers. + * + * After up_buttoninit() has been called, up_buttons() may be called to + * collect the state of all buttons. up_buttons() returns an 8-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT + * definitions in board.h for the meaning of each bit. + * + * up_irqbutton() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* and JOYSTICK_* definitions in board.h for the meaning of enumeration + * value. The previous interrupt handler address is returned (so that it may + * restored, if so desired). + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_BUTTONS +EXTERN void up_buttoninit(void); +EXTERN uint8_t up_buttons(void); +#ifdef CONFIG_ARCH_IRQBUTTONS +EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler); +#endif +#endif + +/************************************************************************************ + * Name: stm32_ledinit, stm32_setled, and stm32_setleds + * + * Description: + * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If + * CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to + * control the LEDs from user applications. + * + ************************************************************************************/ + +#ifndef CONFIG_ARCH_LEDS +EXTERN void stm32_ledinit(void); +EXTERN void stm32_setled(int led, bool ledon); +EXTERN void stm32_setleds(uint8_t ledset); +#endif + +/************************************************************************************ + * Name: stm32_lcdclear + * + * Description: + * This is a non-standard LCD interface just for the Shenzhou board. Because + * of the various rotations, clearing the display in the normal way by writing a + * sequences of runs that covers the entire display can be very slow. Here the + * display is cleared by simply setting all GRAM memory to the specified color. + * + ************************************************************************************/ + +EXTERN void stm32_lcdclear(uint16_t color); + +/************************************************************************************ + * Relay control functions + * + * Description: + * Non-standard functions for relay control from the Shenzhou board. + * + * NOTE: These must match the prototypes in include/nuttx/arch.h + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_RELAYS +EXTERN void up_relaysinit(void); +EXTERN void relays_setstat(int relays, bool stat); +EXTERN bool relays_getstat(int relays); +EXTERN void relays_setstats(uint32_t relays_stat); +EXTERN uint32_t relays_getstats(void); +EXTERN void relays_onoff(int relays, uint32_t mdelay); +EXTERN void relays_onoffs(uint32_t relays_stat, uint32_t mdelay); +EXTERN void relays_resetmode(int relays); +EXTERN void relays_powermode(int relays); +EXTERN void relays_resetmodes(uint32_t relays_stat); +EXTERN void relays_powermodes(uint32_t relays_stat); +#endif + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_CLOUDCTRL_INCLUDE_BOARD_H */ diff --git a/nuttx/configs/cloudctrl/nsh/Make.defs b/nuttx/configs/cloudctrl/nsh/Make.defs new file mode 100644 index 0000000000..a33f8d3174 --- /dev/null +++ b/nuttx/configs/cloudctrl/nsh/Make.defs @@ -0,0 +1,173 @@ +############################################################################ +# configs/cloudctrl/nsh/Make.defs +# +# 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk + +# Setup for the selected toolchain + +ifeq ($(CONFIG_STM32_CODESOURCERYW),y) + # CodeSourcery under Windows + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_CODESOURCERYL),y) + # CodeSourcery under Linux + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -O2 +endif +ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) + # Atollic toolchain under Windows + CROSSDEV = arm-atollic-eabi- + ARCROSSDEV = + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) + # Atollic toolchain under Windows + CROSSDEV = arm-atollic-eabi- + ARCROSSDEV = arm-atollic-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_DEVKITARM),y) + # devkitARM under Windows + CROSSDEV = arm-eabi- + ARCROSSDEV = arm-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif +ifeq ($(CONFIG_STM32_RAISONANCE),y) + # Raisonance RIDE7 under Windows + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -Os +endif + +# Pick the linker script + +ifeq ($(CONFIG_STM32_DFU),y) + LDSCRIPT = ld.script.dfu +else + LDSCRIPT = ld.script +endif + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/winlink.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + 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)/scripts/$(LDSCRIPT)}" + MAXOPTIMIZATION = -O2 +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)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +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 ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +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__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-eabi-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx/configs/cloudctrl/nsh/defconfig b/nuttx/configs/cloudctrl/nsh/defconfig new file mode 100644 index 0000000000..5547333d88 --- /dev/null +++ b/nuttx/configs/cloudctrl/nsh/defconfig @@ -0,0 +1,729 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +# CONFIG_RAW_BINARY is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM3S is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set +CONFIG_ARCH_IRQPRIO=y +CONFIG_BOARD_LOOPSPERMSEC=5483 +# CONFIG_ARCH_CALIBRATION is not set +# CONFIG_SERIAL_TERMIOS is not set +# CONFIG_NET_MULTICAST is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +CONFIG_ARCH_CHIP_STM32F107VC=y +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +CONFIG_STM32_STM32F10XX=y +CONFIG_STM32_CONNECTIVITYLINE=y +CONFIG_STM32_CODESOURCERYW=y +# CONFIG_STM32_CODESOURCERYL is not set +# CONFIG_STM32_ATOLLIC_LITE is not set +# CONFIG_STM32_ATOLLIC_PRO is not set +# CONFIG_STM32_DEVKITARM is not set +# CONFIG_STM32_RAISONANCE is not set +# CONFIG_STM32_BUILDROOT is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +CONFIG_STM32_BKP=y +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +CONFIG_STM32_ETHMAC=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_SPI1=y +# CONFIG_STM32_SPI2 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 +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_USART1 is not set +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USB is not set +# CONFIG_STM32_WWDG is not set +CONFIG_STM32_SPI=y + +# +# Alternate Pin Mapping +# +CONFIG_STM32_ETH_REMAP=y +# CONFIG_STM32_SPI1_REMAP is not set +CONFIG_STM32_USART2_REMAP=y +# CONFIG_STM32_JTAG_DISABLE is not set +CONFIG_STM32_JTAG_FULL_ENABLE=y +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +# CONFIG_STM32_JTAG_SW_ENABLE is not set +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set + +# +# SPI Configuration +# +# CONFIG_STM32_SPI_INTERRUPTS is not set +# CONFIG_STM32_SPI_DMA is not set + +# +# Ethernet MAC configuration +# +CONFIG_STM32_PHYADDR=0 +# CONFIG_STM32_MII is not set +CONFIG_STM32_AUTONEG=y +CONFIG_STM32_PHYSR=17 +CONFIG_STM32_PHYSR_ALTCONFIG=y +CONFIG_STM32_PHYSR_ALTMODE=0xf000 +CONFIG_STM32_PHYSR_10HD=0x1000 +CONFIG_STM32_PHYSR_100HD=0x4000 +CONFIG_STM32_PHYSR_10FD=0x2000 +CONFIG_STM32_PHYSR_100FD=0x8000 +# CONFIG_STM32_ETH_PTP is not set +CONFIG_STM32_RMII=y +CONFIG_STM32_RMII_MCO=y +# CONFIG_STM32_RMII_EXTCLK is not set + +# +# USB Host Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_STACKDUMP=y + +# +# Board Settings +# +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=65536 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +# CONFIG_ARCH_BOARD_OLIMEX_STM32P107 is not set +CONFIG_ARCH_BOARD_CLOUDCTRL=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="cloudctrl" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 +CONFIG_NSH_MMCSDSPIPORTNO=1 + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2012 +CONFIG_START_MONTH=9 +CONFIG_START_DAY=8 +CONFIG_DEV_CONSOLE=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_WORKPRIORITY=192 +CONFIG_SCHED_WORKPERIOD=50000 +CONFIG_SCHED_WORKSTACKSIZE=2048 +CONFIG_SIG_SIGWORK=4 +# CONFIG_SCHED_LPWORK is not set +CONFIG_SCHED_WAITPID=y +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set +CONFIG_DISABLE_POLL=y + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=8 +CONFIG_PREALLOC_TIMERS=4 + +# +# Stack and heap information +# +# CONFIG_CUSTOM_STACK is not set +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +CONFIG_ARCH_HAVE_I2CRESET=y +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_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +CONFIG_MMCSD=y +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set +CONFIG_MMCSD_MMCSUPPORT=y +CONFIG_MMCSD_HAVECARDDETECT=y +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SPICLOCK=12500000 +# CONFIG_MMCSD_SDIO is not set +# CONFIG_MTD is not set +# CONFIG_NETDEVICES is not set +# CONFIG_NET_SLIP is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_LOWLEVEL_CONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_USART2=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# 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 +CONFIG_NSOCKET_DESCRIPTORS=10 +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_READAHEAD_BUFSIZE=562 +CONFIG_NET_NTCP_READAHEAD_BUFFERS=16 +CONFIG_NET_TCP_RECVDELAY=0 +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_CONNS=8 +# CONFIG_NET_BROADCAST is not set +CONFIG_NET_ICMP=y +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_ARPTAB_SIZE=16 +# CONFIG_NET_ARP_IPIN is not set + +# +# File Systems +# + +# +# 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_RAMMAP is not set +# CONFIG_NFS is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set + +# +# Basic CXX Support +# +CONFIG_HAVE_CXX=y +# CONFIG_HAVE_CXXINITIALIZE is not set +# CONFIG_CXX_NEWLONG is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Named Applications +# +CONFIG_NAMEDAPP=y + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_NETTEST is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_DISCOVER is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WLAN is not set + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_FICL is not set +# CONFIG_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +CONFIG_NETUTILS_RESOLV=y +CONFIG_NET_RESOLV_ENTRIES=8 +CONFIG_NET_RESOLV_MAXRESPONSE=96 +# CONFIG_NETUTILS_SMTP is not set +CONFIG_NETUTILS_TELNETD=y +CONFIG_NETUTILS_TFTPC=y +# CONFIG_NETUTILS_THTTPD is not set +CONFIG_NETUTILS_UIPLIB=y +CONFIG_NETUTILS_WEBCLIENT=y +CONFIG_NSH_WGET_USERAGENT="NuttX/6.xx.x (; http://www.nuttx.org/)" +# CONFIG_NETUTILS_WEBSERVER is not set +# CONFIG_NETUTILS_DISCOVER is not set +# CONFIG_NETUTILS_XMLRPC is not set + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSFMOUNT is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PING is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_CONDEV is not set +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_CLIENTPRIO=100 +CONFIG_NSH_TELNETD_CLIENTSTACKSIZE=2048 +CONFIG_NSH_IOBUFFER_SIZE=512 +# CONFIG_NSH_TELNET_LOGIN is not set +CONFIG_NSH_IPADDR=0x0a000002 +CONFIG_NSH_DRIPADDR=0x0a000001 +CONFIG_NSH_NETMASK=0xffffff00 +CONFIG_NSH_NOMAC=y +CONFIG_NSH_MAX_ROUNDTRIP=20 + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# 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/cloudctrl/nsh/setenv.sh b/nuttx/configs/cloudctrl/nsh/setenv.sh new file mode 100644 index 0000000000..6d341313e2 --- /dev/null +++ b/nuttx/configs/cloudctrl/nsh/setenv.sh @@ -0,0 +1,78 @@ +#!/bin/bash +# configs/cloudctrl/nsh/setenv.sh +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +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" + +# This is the path to the tools/ subdirectory +export TOOLS_DIR="${WD}/configs/shenzhou/tools" + +# Add the path to the toolchain to the PATH variable +export PATH="${TOOLCHAIN_BIN}:${TOOLS_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/cloudctrl/scripts/ld.script b/nuttx/configs/cloudctrl/scripts/ld.script new file mode 100644 index 0000000000..139b964684 --- /dev/null +++ b/nuttx/configs/cloudctrl/scripts/ld.script @@ -0,0 +1,115 @@ +/**************************************************************************** + * configs/cloudctrl/scripts/ld.script + * + * 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. + * + ****************************************************************************/ + +/* The STM32F107VC has 256K of FLASH beginning at address 0x0800:0000 and + * 64K of SRAM beginning at address 0x2000:0000. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K +} + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + /* The STM32F107VC has 64Kb of SRAM beginning at the following address */ + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* 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/cloudctrl/scripts/ld.script.dfu b/nuttx/configs/cloudctrl/scripts/ld.script.dfu new file mode 100644 index 0000000000..9cab21406d --- /dev/null +++ b/nuttx/configs/cloudctrl/scripts/ld.script.dfu @@ -0,0 +1,117 @@ +/**************************************************************************** + * configs/cloudctrl/scripts/ld.script.dfu + * + * 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. + * + ****************************************************************************/ + +/* The STM32F107VC has 256K of FLASH beginning at address 0x0800:0000 and + * 64K of SRAM beginning at address 0x2000:0000. Here we assume that the + * STMicro DFU bootloader is being used. In that case, the corrct load .text + * load address is 0x08003000 (leaving 208K). + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08003000, LENGTH = 208K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K +} + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + /* The STM32F107VC has 64Kb of SRAM beginning at the following address */ + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* 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/cloudctrl/src/Makefile b/nuttx/configs/cloudctrl/src/Makefile new file mode 100644 index 0000000000..3e4773518a --- /dev/null +++ b/nuttx/configs/cloudctrl/src/Makefile @@ -0,0 +1,128 @@ +############################################################################ +# configs/cloudctrl/src/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +CFLAGS += -I$(TOPDIR)/sched + +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) + +CSRCS = up_boot.c up_spi.c + +ifeq ($(CONFIG_HAVE_CXX),y) +CSRCS += up_cxxinitialize.c +endif + +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += up_autoleds.c +else +CSRCS += up_userleds.c +endif + +ifeq ($(CONFIG_ARCH_BUTTONS),y) +CSRCS += up_buttons.c +endif + +ifeq ($(CONFIG_ARCH_RELAYS),y) +CSRCS += up_relays.c +endif + +ifeq ($(CONFIG_STM32_OTGFS),y) +CSRCS += up_usb.c +endif + +ifeq ($(CONFIG_NSH_ARCHINIT),y) +CSRCS += up_nsh.c +endif + +ifeq ($(CONFIG_MTD_W25),y) +CSRCS += up_w25.c +endif + +ifeq ($(CONFIG_USBMSC),y) +CSRCS += up_usbmsc.c +endif + +ifeq ($(CONFIG_ADC),y) +CSRCS += up_adc.c +endif + +ifeq ($(CONFIG_WATCHDOG),y) +CSRCS += up_watchdog.c +endif + + +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +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}" +else + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m +endif + +all: libboard$(LIBEXT) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +libboard$(LIBEXT): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + +.depend: Makefile $(SRCS) + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ + +depend: .depend + +clean: + $(call DELFILE, libboard$(LIBEXT)) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep diff --git a/nuttx/configs/cloudctrl/src/cloudctrl-internal.h b/nuttx/configs/cloudctrl/src/cloudctrl-internal.h new file mode 100644 index 0000000000..7fbbb76bbf --- /dev/null +++ b/nuttx/configs/cloudctrl/src/cloudctrl-internal.h @@ -0,0 +1,282 @@ +/**************************************************************************************************** + * configs/cloudctrl/src/cloudctrl-internal.h + * arch/arm/src/board/cloudctrl-internal.n + * + * 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. + * + ****************************************************************************************************/ + +#ifndef __CONFIGS_CLOUDCTRLL_SRC_CLOUDCTRL_INTERNAL_H +#define __CONFIGS_CLOUDCTRLL_SRC_CLOUDCTRL_INTERNAL_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ +/* Configuration ************************************************************************************/ +/* How many SPI modules does this chip support? */ + +#if STM32_NSPI < 1 +# undef CONFIG_STM32_SPI1 +# undef CONFIG_STM32_SPI2 +# undef CONFIG_STM32_SPI3 +#elif STM32_NSPI < 2 +# undef CONFIG_STM32_SPI2 +# undef CONFIG_STM32_SPI3 +#elif STM32_NSPI < 3 +# undef CONFIG_STM32_SPI3 +#endif + +/* cloudctrl GPIO Configuration **********************************************************************/ + +/* STM3240G-EVAL GPIOs ******************************************************************************/ +/* Ethernet + * + * -- ---- -------------- ---------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ---------------------------------------------------------- + * 24 PA1 MII_RX_CLK Ethernet PHY NOTE: Despite the MII labeling of these + * RMII_REF_CLK Ethernet PHY signals, the DM916AEP is actually configured + * 25 PA2 MII_MDIO Ethernet PHY to work in RMII mode. + * 48 PB11 MII_TX_EN Ethernet PHY + * 51 PB12 MII_TXD0 Ethernet PHY + * 52 PB13 MII_TXD1 Ethernet PHY + * 16 PC1 MII_MDC Ethernet PHY + * 34 PC5 MII_INT Ethernet PHY + * 55 PD8 MII_RX_DV Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP + * 55 PD8 RMII_CRSDV Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP + * 56 PD9 MII_RXD0 Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP + * 57 PD10 MII_RXD1 Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP + * + * The board desdign can support a 50MHz external clock to drive the PHY + * (U9). However, on my board, U9 is not present. + * + * 67 PA8 MCO DM9161AEP + */ + +#ifdef CONFIG_STM32_ETHMAC +# define GPIO_MII_INT (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN5) +#endif + +/* Use MCU Pin Reset DM9161 PHY Chip */ + +#ifdef CONFIG_PHY_DM9161 +# define GPIO_DM9161_RET (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|\ + GPIO_PORTB|GPIO_PIN15) +#endif + +/* Wireless + * + * -- ---- -------------- ------------------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ------------------------------------------------------------------- + * 26 PA3 315M_VT + * 17 PC2 WIRELESS_INT + * 18 PC3 WIRELESS_CE To the NRF24L01 2.4G wireless module + * 59 PD12 WIRELESS_CS To the NRF24L01 2.4G wireless module + */ + +#define GPIO_WIRELESS_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN12) + +/* Buttons + * + * -- ---- -------------- ------------------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ------------------------------------------------------------------- + * 23 PA0 WAKEUP Connected to KEY3. Active low: Closing KEY4 pulls WAKEUP to ground. + * 47 PB10 USERKEY Connected to KEY1 + * 33 PC4 TAMPER Connected to KEY2 + */ + +/* BUTTONS -- NOTE that all have EXTI interrupts configured */ + +#define MIN_IRQBUTTON BUTTON_KEY1 +#define MAX_IRQBUTTON BUTTON_KEY3 +#define NUM_IRQBUTTONS (BUTTON_KEY3 - BUTTON_KEY1 + 1) + +#define GPIO_BTN_WAKEUP (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN4) +#define GPIO_BTN_USERKEY (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN10) +#define GPIO_BTN_TAMPER (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_EXTI|GPIO_PORTA|GPIO_PIN0) + +/* LEDs + * + * -- ---- -------------- ------------------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ------------------------------------------------------------------- + * 1 PE2 LED1 Active low: Pulled high + * 2 PE3 LED2 Active low: Pulled high + * 3 PE4 LED3 Active low: Pulled high + * 4 PE5 LED4 Active low: Pulled high + */ + +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) +#define GPIO_LED4 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) + +/* RS-485 + * + * -- ---- -------------- ------------------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ------------------------------------------------------------------- + * 88 PD7 485_DIR SP3485 read enable (not) + */ + +/* To be provided */ + +/* USB + * + * -- ---- -------------- ------------------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ------------------------------------------------------------------- + * 95 PB8 USB_PWR Drives USB VBUS + */ + +#define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_SPEED_100MHz|\ + GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) + +/* Audio DAC + * + * -- ---- -------------- ------------------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ------------------------------------------------------------------- + */ + +/* To be provided */ + +/* SPI FLASH + * + * -- ---- -------------- ------------------------------------------------------------------- + * PN NAME SIGNAL NOTES + * -- ---- -------------- ------------------------------------------------------------------- + * 96 PB9 F_CS To both the TFT LCD (CN13) and to the W25X16 SPI FLASH + */ + +#define GPIO_FLASH_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) + + +/* Relays */ + +#define NUM_RELAYS 2 +#define GPIO_RELAYS_R00 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN0) +#define GPIO_RELAYS_R01 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN1) + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the STM3240G-EVAL board. + * + ****************************************************************************************************/ + +void weak_function stm32_spiinitialize(void); + +/**************************************************************************************************** + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in inialization to setup USB-related GPIO pins for + * the STM3240G-EVAL board. + * + ****************************************************************************************************/ + +#ifdef CONFIG_STM32_OTGFS +void weak_function stm32_usbinitialize(void); +#endif + +/**************************************************************************************************** + * Name: stm32_usbhost_initialize + * + * Description: + * Called at application startup time to initialize the USB host functionality. This function will + * start a thread that will monitor for device connection/disconnection events. + * + ****************************************************************************************************/ + +#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST) +int stm32_usbhost_initialize(void); +#endif + +/**************************************************************************** + * Name: stm32_sdinitialize + * + * Description: + * Initialize the SPI-based SD card. Requires CONFIG_DISABLE_MOUNTPOINT=n + * and CONFIG_STM32_SPI1=y + * + ****************************************************************************/ + +int stm32_sdinitialize(int minor); + +/**************************************************************************** + * Name: stm32_w25initialize + * + * Description: + * Initialize and register the W25 FLASH file system. + * + ****************************************************************************/ + +#ifdef CONFIG_MTD_W25 +int stm32_w25initialize(int minor); +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_CLOUDCTRLL_SRC_CLOUDCTRL_INTERNAL_H */ diff --git a/nuttx/configs/cloudctrl/src/up_adc.c b/nuttx/configs/cloudctrl/src/up_adc.c new file mode 100644 index 0000000000..f66dee35d0 --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_adc.c @@ -0,0 +1,174 @@ +/************************************************************************************ + * configs/cloudctrl/src/up_adc.c + * arch/arm/src/board/up_adc.c + * + * Copyright (C) 2011-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 + +#include +#include + +#include "chip.h" +#include "up_arch.h" + +#include "stm32_pwm.h" +#include "cloudctrl-internal.h" + +#ifdef CONFIG_ADC + +/************************************************************************************ + * Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ +/* Up to 3 ADC interfaces are supported */ + +#if STM32_NADC < 3 +# undef CONFIG_STM32_ADC3 +#endif + +#if STM32_NADC < 2 +# undef CONFIG_STM32_ADC2 +#endif + +#if STM32_NADC < 1 +# undef CONFIG_STM32_ADC1 +#endif + +#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3) +#ifndef CONFIG_STM32_ADC1 +# warning "Channel information only available for ADC1" +#endif + +/* The number of ADC channels in the conversion list */ + +#define ADC1_NCHANNELS 1 + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/* Identifying number of each ADC channel. The only internal signal for ADC testing + * is the potentiometer input: + * + * ADC1_IN10(PC0) Potentiometer + * + * External signals are also available on CON5 CN14: + * + * ADC_IN8 (PB0) CON5 CN14 Pin2 + * ADC_IN9 (PB1) CON5 CN14 Pin1 + */ + +#ifdef CONFIG_STM32_ADC1 +static const uint8_t g_chanlist[ADC1_NCHANNELS] = {10}; //{10, 8, 9}; + +/* Configurations of pins used by each ADC channel */ + +static const uint32_t g_pinlist[ADC1_NCHANNELS] = {GPIO_ADC12_IN10}; //{GPIO_ADC12_IN10, GPIO_ADC12_IN8, GPIO_ADC12_IN9}; +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: adc_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/adc. + * + ************************************************************************************/ + +int adc_devinit(void) +{ +#ifdef CONFIG_STM32_ADC1 + static bool initialized = false; + struct adc_dev_s *adc; + int ret; + int i; + + /* Check if we have already initialized */ + + if (!initialized) + { + /* Configure the pins as analog inputs for the selected channels */ + + for (i = 0; i < ADC1_NCHANNELS; i++) + { + stm32_configgpio(g_pinlist[i]); + } + + /* Call stm32_adcinitialize() to get an instance of the ADC interface */ + + adc = stm32_adcinitialize(1, g_chanlist, ADC1_NCHANNELS); + if (adc == NULL) + { + adbg("ERROR: Failed to get ADC interface\n"); + return -ENODEV; + } + + /* Register the ADC driver at "/dev/adc0" */ + + ret = adc_register("/dev/adc0", adc); + if (ret < 0) + { + adbg("adc_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +#else + return -ENOSYS; +#endif +} + +#endif /* CONFIG_STM32_ADC1 || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */ +#endif /* CONFIG_ADC */ diff --git a/nuttx/configs/cloudctrl/src/up_autoleds.c b/nuttx/configs/cloudctrl/src/up_autoleds.c new file mode 100644 index 0000000000..83df13510f --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_autoleds.c @@ -0,0 +1,408 @@ +/**************************************************************************** + * configs/cloudctrl/src/up_autoleds.c + * arch/arm/src/board/up_autoleds.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 +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32_internal.h" +#include "cloudctrl-internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Enables debug output from this file (needs CONFIG_DEBUG with + * CONFIG_DEBUG_VERBOSE too) + */ + +#undef LED_DEBUG /* Define to enable debug */ + +#ifdef LED_DEBUG +# define leddbg lldbg +# define ledvdbg llvdbg +#else +# define leddbg(x...) +# define ledvdbg(x...) +#endif + +/* The following definitions map the encoded LED setting to GPIO settings */ + +#define CLOUDCTRL_LED1 (1 << 0) +#define CLOUDCTRL_LED2 (1 << 1) +#define CLOUDCTRL_LED3 (1 << 2) +#define CLOUDCTRL_LED4 (1 << 3) + +#define ON_SETBITS_SHIFT (0) +#define ON_CLRBITS_SHIFT (4) +#define OFF_SETBITS_SHIFT (8) +#define OFF_CLRBITS_SHIFT (12) + +#define ON_BITS(v) ((v) & 0xff) +#define OFF_BITS(v) (((v) >> 8) & 0x0ff) +#define SETBITS(b) ((b) & 0x0f) +#define CLRBITS(b) (((b) >> 4) & 0x0f) + +#define ON_SETBITS(v) (SETBITS(ON_BITS(v)) +#define ON_CLRBITS(v) (CLRBITS(ON_BITS(v)) +#define OFF_SETBITS(v) (SETBITS(OFF_BITS(v)) +#define OFF_CLRBITS(v) (CLRBITS(OFF_BITS(v)) + +#define LED_STARTED_ON_SETBITS ((CLOUDCTRL_LED1) << ON_SETBITS_SHIFT) +#define LED_STARTED_ON_CLRBITS ((CLOUDCTRL_LED2|CLOUDCTRL_LED3|CLOUDCTRL_LED4) << ON_CLRBITS_SHIFT) +#define LED_STARTED_OFF_SETBITS (0 << OFF_SETBITS_SHIFT) +#define LED_STARTED_OFF_CLRBITS ((CLOUDCTRL_LED1|CLOUDCTRL_LED2|CLOUDCTRL_LED3|CLOUDCTRL_LED4) << OFF_CLRBITS_SHIFT) + +#define LED_HEAPALLOCATE_ON_SETBITS ((CLOUDCTRL_LED2) << ON_SETBITS_SHIFT) +#define LED_HEAPALLOCATE_ON_CLRBITS ((CLOUDCTRL_LED1|CLOUDCTRL_LED3|CLOUDCTRL_LED4) << ON_CLRBITS_SHIFT) +#define LED_HEAPALLOCATE_OFF_SETBITS ((CLOUDCTRL_LED1) << OFF_SETBITS_SHIFT) +#define LED_HEAPALLOCATE_OFF_CLRBITS ((CLOUDCTRL_LED2|CLOUDCTRL_LED3|CLOUDCTRL_LED4) << OFF_CLRBITS_SHIFT) + +#define LED_IRQSENABLED_ON_SETBITS ((CLOUDCTRL_LED1|CLOUDCTRL_LED2) << ON_SETBITS_SHIFT) +#define LED_IRQSENABLED_ON_CLRBITS ((CLOUDCTRL_LED3|CLOUDCTRL_LED4) << ON_CLRBITS_SHIFT) +#define LED_IRQSENABLED_OFF_SETBITS ((CLOUDCTRL_LED2) << OFF_SETBITS_SHIFT) +#define LED_IRQSENABLED_OFF_CLRBITS ((CLOUDCTRL_LED1|CLOUDCTRL_LED3|CLOUDCTRL_LED4) << OFF_CLRBITS_SHIFT) + +#define LED_STACKCREATED_ON_SETBITS ((CLOUDCTRL_LED3) << ON_SETBITS_SHIFT) +#define LED_STACKCREATED_ON_CLRBITS ((CLOUDCTRL_LED1|CLOUDCTRL_LED2|CLOUDCTRL_LED4) << ON_CLRBITS_SHIFT) +#define LED_STACKCREATED_OFF_SETBITS ((CLOUDCTRL_LED1|CLOUDCTRL_LED2) << OFF_SETBITS_SHIFT) +#define LED_STACKCREATED_OFF_CLRBITS ((CLOUDCTRL_LED3|CLOUDCTRL_LED4) << OFF_CLRBITS_SHIFT) + +#define LED_INIRQ_ON_SETBITS ((CLOUDCTRL_LED1) << ON_SETBITS_SHIFT) +#define LED_INIRQ_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT) +#define LED_INIRQ_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT) +#define LED_INIRQ_OFF_CLRBITS ((CLOUDCTRL_LED1) << OFF_CLRBITS_SHIFT) + +#define LED_SIGNAL_ON_SETBITS ((CLOUDCTRL_LED2) << ON_SETBITS_SHIFT) +#define LED_SIGNAL_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT) +#define LED_SIGNAL_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT) +#define LED_SIGNAL_OFF_CLRBITS ((CLOUDCTRL_LED2) << OFF_CLRBITS_SHIFT) + +#define LED_ASSERTION_ON_SETBITS ((CLOUDCTRL_LED3) << ON_SETBITS_SHIFT) +#define LED_ASSERTION_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT) +#define LED_ASSERTION_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT) +#define LED_ASSERTION_OFF_CLRBITS ((CLOUDCTRL_LED3) << OFF_CLRBITS_SHIFT) + +#define LED_PANIC_ON_SETBITS ((CLOUDCTRL_LED3) << ON_SETBITS_SHIFT) +#define LED_PANIC_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT) +#define LED_PANIC_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT) +#define LED_PANIC_OFF_CLRBITS ((CLOUDCTRL_LED3) << OFF_CLRBITS_SHIFT) + +/************************************************************************************** + * Private Function Protototypes + **************************************************************************************/ + +/* LED State Controls */ + +static inline void led_clrbits(unsigned int clrbits); +static inline void led_setbits(unsigned int setbits); +static void led_setonoff(unsigned int bits); + +/* LED Power Management */ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, enum pm_state_e pmstate); +static int led_pm_prepare(struct pm_callback_s *cb, enum pm_state_e pmstate); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const uint16_t g_ledbits[8] = +{ + (LED_STARTED_ON_SETBITS | LED_STARTED_ON_CLRBITS | + LED_STARTED_OFF_SETBITS | LED_STARTED_OFF_CLRBITS), + + (LED_HEAPALLOCATE_ON_SETBITS | LED_HEAPALLOCATE_ON_CLRBITS | + LED_HEAPALLOCATE_OFF_SETBITS | LED_HEAPALLOCATE_OFF_CLRBITS), + + (LED_IRQSENABLED_ON_SETBITS | LED_IRQSENABLED_ON_CLRBITS | + LED_IRQSENABLED_OFF_SETBITS | LED_IRQSENABLED_OFF_CLRBITS), + + (LED_STACKCREATED_ON_SETBITS | LED_STACKCREATED_ON_CLRBITS | + LED_STACKCREATED_OFF_SETBITS | LED_STACKCREATED_OFF_CLRBITS), + + (LED_INIRQ_ON_SETBITS | LED_INIRQ_ON_CLRBITS | + LED_INIRQ_OFF_SETBITS | LED_INIRQ_OFF_CLRBITS), + + (LED_SIGNAL_ON_SETBITS | LED_SIGNAL_ON_CLRBITS | + LED_SIGNAL_OFF_SETBITS | LED_SIGNAL_OFF_CLRBITS), + + (LED_ASSERTION_ON_SETBITS | LED_ASSERTION_ON_CLRBITS | + LED_ASSERTION_OFF_SETBITS | LED_ASSERTION_OFF_CLRBITS), + + (LED_PANIC_ON_SETBITS | LED_PANIC_ON_CLRBITS | + LED_PANIC_OFF_SETBITS | LED_PANIC_OFF_CLRBITS) +}; + +#ifdef CONFIG_PM +static struct pm_callback_s g_ledscb = +{ + .notify = led_pm_notify, + .prepare = led_pm_prepare, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: led_clrbits + * + * Description: + * Clear all LEDs to the bit encoded state + * + ****************************************************************************/ + +static inline void led_clrbits(unsigned int clrbits) +{ + /* All LEDs are pulled up and, hence, active low */ + + if ((clrbits & CLOUDCTRL_LED1) != 0) + { + stm32_gpiowrite(GPIO_LED1, true); + } + + if ((clrbits & CLOUDCTRL_LED2) != 0) + { + stm32_gpiowrite(GPIO_LED2, true); + } + + if ((clrbits & CLOUDCTRL_LED3) != 0) + { + stm32_gpiowrite(GPIO_LED3, true); + } + + if ((clrbits & CLOUDCTRL_LED4) != 0) + { + stm32_gpiowrite(GPIO_LED4, true); + } + +} + +/**************************************************************************** + * Name: led_setbits + * + * Description: + * Set all LEDs to the bit encoded state + * + ****************************************************************************/ + +static inline void led_setbits(unsigned int setbits) +{ + /* All LEDs are pulled up and, hence, active low */ + + if ((setbits & CLOUDCTRL_LED1) != 0) + { + stm32_gpiowrite(GPIO_LED1, false); + } + + if ((setbits & CLOUDCTRL_LED2) != 0) + { + stm32_gpiowrite(GPIO_LED2, false); + } + + if ((setbits & CLOUDCTRL_LED3) != 0) + { + stm32_gpiowrite(GPIO_LED3, false); + } + + if ((setbits & CLOUDCTRL_LED4) != 0) + { + stm32_gpiowrite(GPIO_LED4, false); + } + +} + +/**************************************************************************** + * Name: led_setonoff + * + * Description: + * Set/clear all LEDs to the bit encoded state + * + ****************************************************************************/ + +static void led_setonoff(unsigned int bits) +{ + led_clrbits(CLRBITS(bits)); + led_setbits(SETBITS(bits)); +} + +/**************************************************************************** + * Name: led_pm_notify + * + * Description: + * Notify the driver of new power state. This callback is called after + * all drivers have had the opportunity to prepare for the new power state. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb , enum pm_state_e pmstate) +{ + switch (pmstate) + { + case(PM_NORMAL): + { + /* Restore normal LEDs operation */ + + } + break; + + case(PM_IDLE): + { + /* Entering IDLE mode - Turn leds off */ + + } + break; + + case(PM_STANDBY): + { + /* Entering STANDBY mode - Logic for PM_STANDBY goes here */ + + } + break; + + case(PM_SLEEP): + { + /* Entering SLEEP mode - Logic for PM_SLEEP goes here */ + + } + break; + + default: + { + /* Should not get here */ + + } + break; + } +} +#endif + +/**************************************************************************** + * Name: led_pm_prepare + * + * Description: + * Request the driver to prepare for a new power state. This is a warning + * that the system is about to enter into a new power state. The driver + * should begin whatever operations that may be required to enter power + * state. The driver may abort the state change mode by returning a + * non-zero value from the callback function. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static int led_pm_prepare(struct pm_callback_s *cb , enum pm_state_e pmstate) +{ + /* No preparation to change power modes is required by the LEDs driver. + * We always accept the state change by returning OK. + */ + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_ledinit + ****************************************************************************/ + +#ifdef CONFIG_ARCH_LEDS +void up_ledinit(void) +{ + /* Configure LED1-4 GPIOs for output */ + + stm32_configgpio(GPIO_LED1); + stm32_configgpio(GPIO_LED2); + stm32_configgpio(GPIO_LED3); + stm32_configgpio(GPIO_LED4); +} + +/**************************************************************************** + * Name: up_ledon + ****************************************************************************/ + +void up_ledon(int led) +{ + led_setonoff(ON_BITS(g_ledbits[led])); +} + +/**************************************************************************** + * Name: up_ledoff + ****************************************************************************/ + +void up_ledoff(int led) +{ + led_setonoff(OFF_BITS(g_ledbits[led])); +} + +/**************************************************************************** + * Name: up_ledpminitialize + ****************************************************************************/ + +#ifdef CONFIG_PM +void up_ledpminitialize(void) +{ + /* Register to receive power management callbacks */ + + int ret = pm_register(&g_ledscb); + if (ret != OK) + { + up_ledon(LED_ASSERTION); + } +} +#endif /* CONFIG_PM */ + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/cloudctrl/src/up_boot.c b/nuttx/configs/cloudctrl/src/up_boot.c new file mode 100644 index 0000000000..f536429716 --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_boot.c @@ -0,0 +1,117 @@ +/************************************************************************************ + * configs/cloudctrl/src/up_boot.c + * arch/arm/src/board/up_boot.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 + +#include "up_arch.h" +#include "cloudctrl-internal.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +#ifdef CONFIG_PHY_DM9161 +static inline void stm232_configdm9161(void) +{ + stm32_configgpio(GPIO_DM9161_RET); + stm32_gpiowrite(GPIO_DM9161_RET, true); +} +# else +# define stm232_configdm9161() +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32_boardinitialize(void) +{ + /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function + * stm32_spiinitialize() has been brought into the link. + */ + +#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI3) + if (stm32_spiinitialize) + { + stm32_spiinitialize(); + } +#endif + + /* Configure the DM9161 PHY reset pin and take it out of reset */ + + stm232_configdm9161(); + + /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not + * disabled, and 3) the weak function stm32_usbinitialize() has been brought + * into the build. + */ + +#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB) + if (stm32_usbinitialize) + { + stm32_usbinitialize(); + } +#endif + + /* Configure on-board LEDs if LED support has been selected. */ + +#ifdef CONFIG_ARCH_LEDS + up_ledinit(); +#endif +} diff --git a/nuttx/configs/cloudctrl/src/up_buttons.c b/nuttx/configs/cloudctrl/src/up_buttons.c new file mode 100644 index 0000000000..81535f1263 --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_buttons.c @@ -0,0 +1,170 @@ +/**************************************************************************** + * configs/cloudctrl/src/up_buttons.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 +#include "cloudctrl-internal.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* Pin configuration for each cloudctrl button. This array is indexed by + * the BUTTON_* definitions in board.h + */ + +static const uint16_t g_buttons[NUM_BUTTONS] = +{ + GPIO_BTN_USERKEY, GPIO_BTN_TAMPER, GPIO_BTN_WAKEUP +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_buttoninit + * + * Description: + * up_buttoninit() must be called to initialize button resources. After + * that, up_buttons() may be called to collect the current state of all + * buttons or up_irqbutton() may be called to register button interrupt + * handlers. + * + ****************************************************************************/ + +void up_buttoninit(void) +{ + int i; + + /* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are + * configured for some pins but NOT used in this file + */ + + for (i = 0; i < NUM_BUTTONS; i++) + { + stm32_configgpio(g_buttons[i]); + } +} + +/**************************************************************************** + * Name: up_buttons + ****************************************************************************/ + +uint8_t up_buttons(void) +{ + uint8_t ret = 0; + int i; + + /* Check that state of each key */ + + for (i = 0; i < NUM_BUTTONS; i++) + { + /* A LOW value means that the key is pressed for most keys. The exception + * is the WAKEUP button. + */ + + bool released = stm32_gpioread(g_buttons[i]); + if (i == BUTTON_WAKEUP) + { + released = !released; + } + + /* Accumulate the set of depressed (not released) keys */ + + if (!released) + { + ret |= (1 << i); + } + } + + return ret; +} + +/************************************************************************************ + * Button support. + * + * Description: + * up_buttoninit() must be called to initialize button resources. After + * that, up_buttons() may be called to collect the current state of all + * buttons or up_irqbutton() may be called to register button interrupt + * handlers. + * + * After up_buttoninit() has been called, up_buttons() may be called to + * collect the state of all buttons. up_buttons() returns an 8-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT + * definitions in board.h for the meaning of each bit. + * + * up_irqbutton() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* and JOYSTICK_* definitions in board.h for the meaning of enumeration + * value. The previous interrupt handler address is returned (so that it may + * restored, if so desired). + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +xcpt_t up_irqbutton(int id, xcpt_t irqhandler) +{ + xcpt_t oldhandler = NULL; + + /* The following should be atomic */ + + if (id >= MIN_IRQBUTTON && id <= MAX_IRQBUTTON) + { + oldhandler = stm32_gpiosetevent(g_buttons[id], true, true, true, irqhandler); + } + return oldhandler; +} +#endif +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/nuttx/configs/cloudctrl/src/up_cxxinitialize.c b/nuttx/configs/cloudctrl/src/up_cxxinitialize.c new file mode 100644 index 0000000000..8f01ba5335 --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_cxxinitialize.c @@ -0,0 +1,156 @@ +/************************************************************************************ + * configs/cloudctrl/src/up_cxxinitialize.c + * arch/arm/src/board/up_cxxinitialize.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 + +#include +#include "chip.h" + +#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE) + +/************************************************************************************ + * Definitions + ************************************************************************************/ +/* Debug ****************************************************************************/ +/* Non-standard debug that may be enabled just for testing the static constructors */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_CXX +#endif + +#ifdef CONFIG_DEBUG_CXX +# define cxxdbg dbg +# define cxxlldbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define cxxvdbg vdbg +# define cxxllvdbg llvdbg +# else +# define cxxvdbg(x...) +# define cxxllvdbg(x...) +# endif +#else +# define cxxdbg(x...) +# define cxxlldbg(x...) +# define cxxvdbg(x...) +# define cxxllvdbg(x...) +#endif + +/************************************************************************************ + * Private Types + ************************************************************************************/ +/* This type defines one entry in initialization array */ + +typedef void (*initializer_t)(void); + +/************************************************************************************ + * External references + ************************************************************************************/ +/* _sinit and _einit are symbols exported by the linker script that mark the + * beginning and the end of the C++ initialization section. + */ + +extern initializer_t _sinit; +extern initializer_t _einit; + +/* _stext and _etext are symbols exported by the linker script that mark the + * beginning and the end of text. + */ + +extern uint32_t _stext; +extern uint32_t _etext; + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: up_cxxinitialize + * + * Description: + * If C++ and C++ static constructors are supported, then this function + * must be provided by board-specific logic in order to perform + * initialization of the static C++ class instances. + * + * This function should then be called in the application-specific + * user_start logic in order to perform the C++ initialization. NOTE + * that no component of the core NuttX RTOS logic is involved; This + * function defintion only provides the 'contract' between application + * specific C++ code and platform-specific toolchain support + * + ***************************************************************************/ + +void up_cxxinitialize(void) +{ + initializer_t *initp; + + cxxdbg("_sinit: %p _einit: %p _stext: %p _etext: %p\n", + &_sinit, &_einit, &_stext, &_etext); + + /* Visit each entry in the initialzation table */ + + for (initp = &_sinit; initp != &_einit; initp++) + { + initializer_t initializer = *initp; + cxxdbg("initp: %p initializer: %p\n", initp, initializer); + + /* Make sure that the address is non-NULL and lies in the text region + * defined by the linker script. Some toolchains may put NULL values + * or counts in the initialization table + */ + + if ((void*)initializer > (void*)&_stext && (void*)initializer < (void*)&_etext) + { + cxxdbg("Calling %p\n", initializer); + initializer(); + } + } +} + +#endif /* CONFIG_HAVE_CXX && CONFIG_HAVE_CXXINITIALIZE */ + diff --git a/nuttx/configs/cloudctrl/src/up_nsh.c b/nuttx/configs/cloudctrl/src/up_nsh.c new file mode 100644 index 0000000000..f389460bb8 --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_nsh.c @@ -0,0 +1,160 @@ +/**************************************************************************** + * config/cloudctrl/src/up_nsh.c + * arch/arm/src/board/up_nsh.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 +#include +#include + +#include "stm32_internal.h" +#include "cloudctrl-internal.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ + +/* Assume that we support everything until convinced otherwise */ + +#define HAVE_USBDEV 1 +#define HAVE_USBHOST 1 +#define HAVE_W25 1 + +/* Can't support the W25 device if it SPI1 or W25 support is not enabled */ + +#if !defined(CONFIG_STM32_SPI1) || !defined(CONFIG_MTD_W25) +# undef HAVE_W25 +#endif + +/* Can't support W25 features if mountpoints are disabled */ + +#ifdef CONFIG_DISABLE_MOUNTPOINT +# undef HAVE_W25 +#endif + +/* Default W25 minor number */ + +#if defined(HAVE_W25) && !defined(CONFIG_NSH_W25MINOR) +# define CONFIG_NSH_W25MINOR 0 +#endif + +/* Can't support USB host or device features if USB OTG FS is not enabled */ + +#ifndef CONFIG_STM32_OTGFS +# undef HAVE_USBDEV +# undef HAVE_USBHOST +#endif + +/* Can't support USB device is USB device is not enabled */ + +#ifndef CONFIG_USBDEV +# undef HAVE_USBDEV +#endif + +/* Can't support USB host is USB host is not enabled */ + +#ifndef CONFIG_USBHOST +# undef HAVE_USBHOST +#endif + +/* Debug ********************************************************************/ + +#ifdef CONFIG_CPP_HAVE_VARARGS +# ifdef CONFIG_DEBUG +# define message(...) lib_lowprintf(__VA_ARGS__) +# else +# define message(...) printf(__VA_ARGS__) +# endif +#else +# ifdef CONFIG_DEBUG +# define message lib_lowprintf +# else +# define message printf +# endif +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nsh_archinitialize + * + * Description: + * Perform architecture specific initialization + * + ****************************************************************************/ + +int nsh_archinitialize(void) +{ +#if defined(HAVE_USBHOST) || defined(HAVE_W25) + int ret; +#endif + + /* Initialize and register the W25 FLASH file system. */ + +#ifdef HAVE_W25 + ret = stm32_w25initialize(CONFIG_NSH_W25MINOR); + if (ret < 0) + { + message("nsh_archinitialize: Failed to initialize W25 minor %d: %d\n", + CONFIG_NSH_W25MINOR, ret); + return ret; + } +#endif + + /* Initialize USB host operation. stm32_usbhost_initialize() starts a thread + * will monitor for USB connection and disconnection events. + */ + +#ifdef HAVE_USBHOST + ret = stm32_usbhost_initialize(); + if (ret != OK) + { + message("nsh_archinitialize: Failed to initialize USB host: %d\n", ret); + return ret; + } +#endif + + return OK; +} diff --git a/nuttx/configs/cloudctrl/src/up_relays.c b/nuttx/configs/cloudctrl/src/up_relays.c new file mode 100644 index 0000000000..60630dd8af --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_relays.c @@ -0,0 +1,287 @@ +/**************************************************************************** + * configs/cloudctrl/src/up_relays.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 +#include + +#include +#include + +#include "cloudctrl-internal.h" + +#ifdef CONFIG_ARCH_RELAYS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define RELAYS_MIN_RESET_TIME 5 +#define RELAYS_RESET_MTIME 5 +#define RELAYS_POWER_MTIME 50 + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static uint32_t g_relays_stat = 0; +static bool g_relays_init = false; + +static const uint16_t g_relays[NUM_RELAYS] = +{ + GPIO_RELAYS_R00 +#ifdef GPIO_RELAYS_R01 + , GPIO_RELAYS_R01 +#endif +#ifdef GPIO_RELAYS_R02 + , GPIO_RELAYS_R02 +#endif +#ifdef GPIO_RELAYS_R03 + , GPIO_RELAYS_R03 +#endif +#ifdef GPIO_RELAYS_R04 + , GPIO_RELAYS_R04 +#endif +#ifdef GPIO_RELAYS_R05 + , GPIO_RELAYS_R05 +#endif +#ifdef GPIO_RELAYS_R06 + , GPIO_RELAYS_R06 +#endif +#ifdef GPIO_RELAYS_R07 + , GPIO_RELAYS_R07 +#endif +#ifdef GPIO_RELAYS_R08 + , GPIO_RELAYS_R08 +#endif +#ifdef GPIO_RELAYS_R09 + , GPIO_RELAYS_R09 +#endif +#ifdef GPIO_RELAYS_R10 + , GPIO_RELAYS_R10 +#endif +#ifdef GPIO_RELAYS_R11 + , GPIO_RELAYS_R11 +#endif +#ifdef GPIO_RELAYS_R12 + , GPIO_RELAYS_R12 +#endif +#ifdef GPIO_RELAYS_R13 + , GPIO_RELAYS_R13 +#endif +#ifdef GPIO_RELAYS_R14 + , GPIO_RELAYS_R14 +#endif +#ifdef GPIO_RELAYS_R15 + , GPIO_RELAYS_R15 +#endif +#ifdef GPIO_RELAYS_R16 + , GPIO_RELAYS_R16 +#endif +#ifdef GPIO_RELAYS_R17 + , GPIO_RELAYS_R17 +#endif +#ifdef GPIO_RELAYS_R18 + , GPIO_RELAYS_R18 +#endif +#ifdef GPIO_RELAYS_R19 + , GPIO_RELAYS_R19 +#endif +#ifdef GPIO_RELAYS_R20 + , GPIO_RELAYS_R20 +#endif +#ifdef GPIO_RELAYS_R21 + , GPIO_RELAYS_R21 +#endif +#ifdef GPIO_RELAYS_R22 + , GPIO_RELAYS_R22 +#endif +#ifdef GPIO_RELAYS_R23 + , GPIO_RELAYS_R23 +#endif +#ifdef GPIO_RELAYS_R24 + , GPIO_RELAYS_R24 +#endif +#ifdef GPIO_RELAYS_R25 + , GPIO_RELAYS_R25 +#endif +#ifdef GPIO_RELAYS_R26 + , GPIO_RELAYS_R26 +#endif +#ifdef GPIO_RELAYS_R27 + , GPIO_RELAYS_R27 +#endif +#ifdef GPIO_RELAYS_R28 + , GPIO_RELAYS_R28 +#endif +#ifdef GPIO_RELAYS_R29 + , GPIO_RELAYS_R29 +#endif +#ifdef GPIO_RELAYS_R30 + , GPIO_RELAYS_R30 +#endif +#ifdef GPIO_RELAYS_R31 + , GPIO_RELAYS_R31 +#endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +void up_relaysinit(void) +{ + int i; + + if (g_relays_init) + { + return; + } + + /* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are + * configured for some pins but NOT used in this file + */ + + for (i = 0; i < NUM_RELAYS; i++) + { + stm32_configgpio(g_relays[i]); + stm32_gpiowrite(g_relays[i], false); + } + + g_relays_init = true; +} + +void relays_setstat(int relays,bool stat) +{ + if ((unsigned)relays < NUM_RELAYS) + { + stm32_gpiowrite(g_relays[relays], stat); + if (!stat) + { + g_relays_stat &= ~(1 << relays); + } + else + { + g_relays_stat |= (1 << relays); + } + } +} + +bool relays_getstat(int relays) +{ + if ((unsigned)relays < NUM_RELAYS) + { + return (g_relays_stat & (1 << relays)) != 0; + } + + return false; +} + +void relays_setstats(uint32_t relays_stat) +{ + int i; + + for (i = 0; i < NUM_RELAYS; i++) + { + relays_setstat(i, (relays_stat & (1<0) + { + if (relays_getstat(relays)) + { + relays_setstat(relays, false); + usleep(RELAYS_MIN_RESET_TIME*1000*1000); + } + + relays_setstat(relays,true); + usleep(mdelay*100*1000); + relays_setstat(relays, false); + } + } +} + +void relays_onoffs(uint32_t relays_stat, uint32_t mdelay) +{ + int i; + + for (i = 0; i < NUM_RELAYS; i++) + { + relays_onoff(i, mdelay); + } +} + +void relays_resetmode(int relays) +{ + relays_onoff(relays, RELAYS_RESET_MTIME); +} + +void relays_powermode(int relays) +{ + relays_onoff(relays, RELAYS_POWER_MTIME); +} + +void relays_resetmodes(uint32_t relays_stat) +{ + relays_onoffs(relays_stat, RELAYS_RESET_MTIME); +} + +void relays_powermodes(uint32_t relays_stat) +{ + relays_onoffs(relays_stat, RELAYS_POWER_MTIME); +} + +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/nuttx/configs/cloudctrl/src/up_spi.c b/nuttx/configs/cloudctrl/src/up_spi.c new file mode 100644 index 0000000000..47ade8488a --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_spi.c @@ -0,0 +1,177 @@ +/************************************************************************************ + * configs/cloudctrl/src/up_spi.c + * arch/arm/src/board/up_spi.c + * + * Copyright (C) 2009 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 +#include + +#include +#include + +#include "up_arch.h" +#include "chip.h" +#include "stm32_internal.h" +#include "cloudctrl-internal.h" + +#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI3) + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Enables debug output from this file (needs CONFIG_DEBUG too) */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_SPI +#endif + +#ifdef CONFIG_DEBUG_SPI +# define spidbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define spivdbg lldbg +# else +# define spivdbg(x...) +# endif +#else +# define spidbg(x...) +# define spivdbg(x...) +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the cloudctrl board. + * + ************************************************************************************/ + +void weak_function stm32_spiinitialize(void) +{ + /* NOTE: Clocking for SPI1 and/or SPI3 was already provided in stm32_rcc.c. + * Configurations of SPI pins is performed in stm32_spi.c. + * Here, we only initialize chip select pins unique to the board + * architecture. + */ + + /* SPI1 connects to the SD CARD and to the SPI FLASH */ + +#ifdef CONFIG_STM32_SPI1 + stm32_configgpio(GPIO_FLASH_CS); /* FLASH chip select */ +#endif + + /* SPI3 connects to TFT LCD module and the RF24L01 2.4G wireless module */ + +#ifdef CONFIG_STM32_SPI3 + +#endif +} + +/**************************************************************************** + * Name: stm32_spi1/2/3select and stm32_spi1/2/3status + * + * Description: + * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status must be + * provided by board-specific logic. They are implementations of the select + * and status methods of the SPI interface defined by struct spi_ops_s (see + * include/nuttx/spi.h). All other methods (including up_spiinitialize()) + * are provided by common STM32 logic. To use this common SPI logic on your + * board: + * + * 1. Provide logic in stm32_boardinitialize() to configure SPI chip select + * pins. + * 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions in your + * board-specific logic. These functions will perform chip selection and + * status operations using GPIOs in the way your board is configured. + * 3. Add a calls to up_spiinitialize() in your low level application + * initialization logic + * 4. The handle returned by up_spiinitialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_SPI1 +void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + + /* SPI1 connects to the SD CARD and to the SPI FLASH */ + + if (devid == SPIDEV_FLASH) + { + /* Set the GPIO low to select and high to de-select */ + + stm32_gpiowrite(GPIO_FLASH_CS, !selected); + } +} + +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + + return SPI_STATUS_PRESENT; +} +#endif + +#ifdef CONFIG_STM32_SPI3 +void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + +} + +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + return 0; +} +#endif + +#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI3 */ diff --git a/nuttx/configs/cloudctrl/src/up_usb.c b/nuttx/configs/cloudctrl/src/up_usb.c new file mode 100644 index 0000000000..2ee9822f57 --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_usb.c @@ -0,0 +1,295 @@ +/************************************************************************************ + * configs/cloudctrl/src/up_usbdev.c + * arch/arm/src/board/up_boot.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 +#include +#include +#include +#include + +#include +#include +#include + +#include "up_arch.h" +#include "stm32_internal.h" +#include "cloudctrl-internal.h" + +#ifdef CONFIG_STM32_OTGFS + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#if defined(CONFIG_USBDEV) || defined(CONFIG_USBHOST) +# define HAVE_USB 1 +#else +# warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBHOST" +# undef HAVE_USB +#endif + +#ifndef CONFIG_USBHOST_DEFPRIO +# define CONFIG_USBHOST_DEFPRIO 50 +#endif + +#ifndef CONFIG_USBHOST_STACKSIZE +# define CONFIG_USBHOST_STACKSIZE 1024 +#endif + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +static struct usbhost_driver_s *g_drvr; +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: usbhost_waiter + * + * Description: + * Wait for USB devices to be connected. + * + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +static int usbhost_waiter(int argc, char *argv[]) +{ + bool connected = false; + int ret; + + uvdbg("Running\n"); + for (;;) + { + /* Wait for the device to change state */ + + ret = DRVR_WAIT(g_drvr, connected); + DEBUGASSERT(ret == OK); + + connected = !connected; + uvdbg("%s\n", connected ? "connected" : "disconnected"); + + /* Did we just become connected? */ + + if (connected) + { + /* Yes.. enumerate the newly connected device */ + + (void)DRVR_ENUMERATE(g_drvr); + } + } + + /* Keep the compiler from complaining */ + + return 0; +} +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in inialization to setup USB-related + * GPIO pins for the STM3240G-EVAL board. + * + ************************************************************************************/ + +void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up. No GPIO configuration is required */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); + stm32_configgpio(GPIO_OTGFS_PWRON); + stm32_configgpio(GPIO_OTGFS_OVER); +#endif +} + +/*********************************************************************************** + * Name: stm32_usbhost_initialize + * + * Description: + * Called at application startup time to initialize the USB host functionality. + * This function will start a thread that will monitor for device + * connection/disconnection events. + * + ***********************************************************************************/ + +#ifdef CONFIG_USBHOST +int stm32_usbhost_initialize(void) +{ + int pid; + int ret; + + /* First, register all of the class drivers needed to support the drivers + * that we care about: + */ + + uvdbg("Register class drivers\n"); + ret = usbhost_storageinit(); + if (ret != OK) + { + udbg("Failed to register the mass storage class\n"); + } + + /* Then get an instance of the USB host interface */ + + uvdbg("Initialize USB host\n"); + g_drvr = usbhost_initialize(0); + if (g_drvr) + { + /* Start a thread to handle device connection. */ + + uvdbg("Start usbhost_waiter\n"); + + pid = TASK_CREATE("usbhost", CONFIG_USBHOST_DEFPRIO, + CONFIG_USBHOST_STACKSIZE, + (main_t)usbhost_waiter, (const char **)NULL); + return pid < 0 ? -ENOEXEC : OK; + } + + return -ENODEV; +} +#endif + +/*********************************************************************************** + * Name: stm32_usbhost_vbusdrive + * + * Description: + * Enable/disable driving of VBUS 5V output. This function must be provided be + * each platform that implements the STM32 OTG FS host interface + * + * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump + * or, if 5 V are available on the application board, a basic power switch, must + * be added externally to drive the 5 V VBUS line. The external charge pump can + * be driven by any GPIO output. When the application decides to power on VBUS + * using the chosen GPIO, it must also set the port power bit in the host port + * control and status register (PPWR bit in OTG_FS_HPRT). + * + * "The application uses this field to control power to this port, and the core + * clears this bit on an overcurrent condition." + * + * Input Parameters: + * iface - For future growth to handle multiple USB host interface. Should be zero. + * enable - true: enable VBUS power; false: disable VBUS power + * + * Returned Value: + * None + * + ***********************************************************************************/ + +#ifdef CONFIG_USBHOST +void stm32_usbhost_vbusdrive(int iface, bool enable) +{ + DEBUGASSERT(iface == 0); + + if (enable) + { + /* Enable the Power Switch by driving the enable pin low */ + + stm32_gpiowrite(GPIO_OTGFS_PWRON, false); + } + else + { + /* Disable the Power Switch by driving the enable pin high */ + + stm32_gpiowrite(GPIO_OTGFS_PWRON, true); + } +} +#endif + +/************************************************************************************ + * Name: stm32_setup_overcurrent + * + * Description: + * Setup to receive an interrupt-level callback if an overcurrent condition is + * detected. + * + * Input paramter: + * handler - New overcurrent interrupt handler + * + * Returned value: + * Old overcurrent interrupt handler + * + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +xcpt_t stm32_setup_overcurrent(xcpt_t handler) +{ + return NULL; +} +#endif + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +#ifdef CONFIG_USBDEV +void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + ulldbg("resume: %d\n", resume); +} +#endif + +#endif /* CONFIG_STM32_OTGFS */ + + + diff --git a/nuttx/configs/cloudctrl/src/up_usbmsc.c b/nuttx/configs/cloudctrl/src/up_usbmsc.c new file mode 100644 index 0000000000..1e74e6f242 --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_usbmsc.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * configs/cloudctrl/src/up_usbmsc.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Darcy Gong + * + * Configure and register the STM32 SPI-based MMC/SD block driver. + * + * 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 "stm32_internal.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ + +#ifndef CONFIG_EXAMPLES_USBMSC_DEVMINOR1 +# define CONFIG_EXAMPLES_USBMSC_DEVMINOR1 0 +#endif + +/* Debug ********************************************************************/ + +#ifdef CONFIG_CPP_HAVE_VARARGS +# ifdef CONFIG_DEBUG +# define message(...) lib_lowprintf(__VA_ARGS__) +# define msgflush() +# else +# define message(...) printf(__VA_ARGS__) +# define msgflush() fflush(stdout) +# endif +#else +# ifdef CONFIG_DEBUG +# define message lib_lowprintf +# define msgflush() +# else +# define message printf +# define msgflush() fflush(stdout) +# endif +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usbmsc_archinitialize + * + * Description: + * Perform architecture specific initialization + * + ****************************************************************************/ + +int usbmsc_archinitialize(void) +{ + /* If examples/usbmsc is built as an NSH command, then SD slot should + * already have been initized in nsh_archinitialize() (see up_nsh.c). In + * this case, there is nothing further to be done here. + */ + +#ifndef CONFIG_EXAMPLES_USBMSC_BUILTIN + return stm32_sdinitialize(CONFIG_EXAMPLES_USBMSC_DEVMINOR1); +#else + return OK; +#endif +} diff --git a/nuttx/configs/cloudctrl/src/up_userleds.c b/nuttx/configs/cloudctrl/src/up_userleds.c new file mode 100644 index 0000000000..5c112123b8 --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_userleds.c @@ -0,0 +1,132 @@ +/**************************************************************************** + * configs/cloudctrl/src/up_userleds.c + * arch/arm/src/board/up_userleds.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 +#include + +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32_internal.h" +#include "cloudctrl-internal.h" + +#ifndef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Enables debug output from this file (needs CONFIG_DEBUG with + * CONFIG_DEBUG_VERBOSE too) + */ + +#undef LED_DEBUG /* Define to enable debug */ + +#ifdef LED_DEBUG +# define leddbg lldbg +# define ledvdbg llvdbg +#else +# define leddbg(x...) +# define ledvdbg(x...) +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* This array maps an LED number to GPIO pin configuration */ + +static uint32_t g_ledcfg[BOARD_NLEDS] = +{ + GPIO_LED1, GPIO_LED2, GPIO_LED3, GPIO_LED4 +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ledinit + ****************************************************************************/ + +void stm32_ledinit(void) +{ + /* Configure LED1-3 GPIOs for output */ + + stm32_configgpio(GPIO_LED1); + stm32_configgpio(GPIO_LED2); + stm32_configgpio(GPIO_LED3); + stm32_configgpio(GPIO_LED4); +} + +/**************************************************************************** + * Name: stm32_setled + ****************************************************************************/ + +void stm32_setled(int led, bool ledon) +{ + if ((unsigned)led < BOARD_NLEDS) + { + stm32_gpiowrite(g_ledcfg[led], ledon); + } +} + +/**************************************************************************** + * Name: stm32_setleds + ****************************************************************************/ + +void stm32_setleds(uint8_t ledset) +{ + stm32_gpiowrite(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0); + stm32_gpiowrite(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0); + stm32_gpiowrite(BOARD_LED3, (ledset & BOARD_LED3_BIT) == 0); + stm32_gpiowrite(BOARD_LED4, (ledset & BOARD_LED4_BIT) == 0); +} + +#endif /* !CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/cloudctrl/src/up_w25.c b/nuttx/configs/cloudctrl/src/up_w25.c new file mode 100644 index 0000000000..83ed67cc04 --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_w25.c @@ -0,0 +1,154 @@ +/**************************************************************************** + * config/cloudctrl/src/up_w25.c + * arch/arm/src/board/up_w25.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 +#include +#include +#include + +#ifdef CONFIG_STM32_SPI1 +# include +# include +# include +#endif + +#include "cloudctrl-internal.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ +/* Can't support the W25 device if it SPI1 or W25 support is not enabled */ + +#define HAVE_W25 1 +#if !defined(CONFIG_STM32_SPI1) || !defined(CONFIG_MTD_W25) +# undef HAVE_W25 +#endif + +/* Can't support W25 features if mountpoints are disabled */ + +#if defined(CONFIG_DISABLE_MOUNTPOINT) +# undef HAVE_W25 +#endif + +/* Can't support both FAT and NXFFS */ + +#if defined(CONFIG_FS_FAT) && defined(CONFIG_FS_NXFFS) +# warning "Can't support both FAT and NXFFS -- using FAT" +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_w25initialize + * + * Description: + * Initialize and register the W25 FLASH file system. + * + ****************************************************************************/ + +int stm32_w25initialize(int minor) +{ +#ifdef HAVE_W25 + FAR struct spi_dev_s *spi; + FAR struct mtd_dev_s *mtd; +#ifdef CONFIG_FS_NXFFS + char devname[12]; +#endif + int ret; + + /* Get the SPI port */ + + spi = up_spiinitialize(1); + if (!spi) + { + fdbg("ERROR: Failed to initialize SPI port 2\n"); + return -ENODEV; + } + + /* Now bind the SPI interface to the W25 SPI FLASH driver */ + + mtd = w25_initialize(spi); + if (!mtd) + { + fdbg("ERROR: Failed to bind SPI port 2 to the SST 25 FLASH driver\n"); + return -ENODEV; + } + +#ifndef CONFIG_FS_NXFFS + /* And finally, use the FTL layer to wrap the MTD driver as a block driver */ + + ret = ftl_initialize(minor, mtd); + if (ret < 0) + { + fdbg("ERROR: Initialize the FTL layer\n"); + return ret; + } +#else + /* Initialize to provide NXFFS on the MTD interface */ + + ret = nxffs_initialize(mtd); + if (ret < 0) + { + fdbg("ERROR: NXFFS initialization failed: %d\n", -ret); + return ret; + } + + /* Mount the file system at /mnt/w25 */ + + snprintf(devname, 12, "/mnt/w25%c", 'a' + minor); + ret = mount(NULL, devname, "nxffs", 0, NULL); + if (ret < 0) + { + fdbg("ERROR: Failed to mount the NXFFS volume: %d\n", errno); + return ret; + } +#endif +#endif + return OK; +} diff --git a/nuttx/configs/cloudctrl/src/up_watchdog.c b/nuttx/configs/cloudctrl/src/up_watchdog.c new file mode 100644 index 0000000000..eaaeccd324 --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_watchdog.c @@ -0,0 +1,137 @@ +/************************************************************************************ + * configs/cloudctrl/src/up_watchdog.c + * arch/arm/src/board/up_watchdog.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 + +#include +#include + +#include "stm32_wdg.h" + +#ifdef CONFIG_WATCHDOG + +/************************************************************************************ + * Definitions + ************************************************************************************/ +/* Configuration *******************************************************************/ +/* Wathdog hardware should be enabled */ + +#if !defined(CONFIG_STM32_WWDG) && !defined(CONFIG_STM32_IWDG) +# warning "One of CONFIG_STM32_WWDG or CONFIG_STM32_IWDG must be defined" +#endif + +/* Select the path to the registered watchdog timer device */ + +#ifndef CONFIG_STM32_WDG_DEVPATH +# ifdef CONFIG_EXAMPLES_WATCHDOG_DEVPATH +# define CONFIG_STM32_WDG_DEVPATH CONFIG_EXAMPLES_WATCHDOG_DEVPATH +# else +# define CONFIG_STM32_WDG_DEVPATH "/dev/watchdog0" +# endif +#endif + +/* Use the un-calibrated LSI frequency if we have nothing better */ + +#if defined(CONFIG_STM32_IWDG) && !defined(CONFIG_STM32_LSIFREQ) +# define CONFIG_STM32_LSIFREQ STM32_LSI_FREQUENCY +#endif + +/* Debug ***************************************************************************/ +/* Non-standard debug that may be enabled just for testing the watchdog timer */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_WATCHDOG +#endif + +#ifdef CONFIG_DEBUG_WATCHDOG +# define wdgdbg dbg +# define wdglldbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define wdgvdbg vdbg +# define wdgllvdbg llvdbg +# else +# define wdgvdbg(x...) +# define wdgllvdbg(x...) +# endif +#else +# define wdgdbg(x...) +# define wdglldbg(x...) +# define wdgvdbg(x...) +# define wdgllvdbg(x...) +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: up_wdginitialize() + * + * Description: + * Perform architecuture-specific initialization of the Watchdog hardware. + * This interface must be provided by all configurations using + * apps/examples/watchdog + * + ****************************************************************************/ + +int up_wdginitialize(void) +{ + /* Initialize tha register the watchdog timer device */ + +#if defined(CONFIG_STM32_WWDG) + stm32_wwdginitialize(CONFIG_STM32_WDG_DEVPATH); + return OK; +#elif defined(CONFIG_STM32_IWDG) + stm32_iwdginitialize(CONFIG_STM32_WDG_DEVPATH, CONFIG_STM32_LSIFREQ); + return OK; +#else + return -ENODEV; +#endif +} + +#endif /* CONFIG_WATCHDOG */ diff --git a/nuttx/configs/cloudctrl/tools/olimex-arm-usb-ocd.cfg b/nuttx/configs/cloudctrl/tools/olimex-arm-usb-ocd.cfg new file mode 100644 index 0000000000..d9ff2e5154 --- /dev/null +++ b/nuttx/configs/cloudctrl/tools/olimex-arm-usb-ocd.cfg @@ -0,0 +1,11 @@ +# +# Olimex ARM-USB-OCD +# +# http://www.olimex.com/dev/arm-usb-ocd.html +# + +interface ft2232 +ft2232_device_desc "Olimex OpenOCD JTAG" +ft2232_layout "olimex-jtag" +ft2232_vid_pid 0x15BA 0x0003 + diff --git a/nuttx/configs/cloudctrl/tools/oocd.sh b/nuttx/configs/cloudctrl/tools/oocd.sh new file mode 100644 index 0000000000..259156e319 --- /dev/null +++ b/nuttx/configs/cloudctrl/tools/oocd.sh @@ -0,0 +1,92 @@ +#!/bin/sh + +# Get command line parameters + +USAGE="USAGE: $0 [-dh] " +ADVICE="Try '$0 -h' for more information" + +unset DEBUG + +while [ ! -z "$1" ]; do + case $1 in + -d ) + set -x + DEBUG=-d3 + ;; + -h ) + echo "$0 is a tool for generation of proper version files for the NuttX build" + echo "" + echo $USAGE + echo "" + echo "Where:" + echo " -d" + echo " Enable script debug" + echo " -h" + echo " show this help message and exit" + echo " Use the OpenOCD 0.4.0" + echo " " + echo " The full path to the top-level NuttX directory" + exit 0 + ;; + * ) + break; + ;; + esac + shift +done + +TOPDIR=$1 +if [ -z "${TOPDIR}" ]; then + echo "Missing argument" + echo $USAGE + echo $ADVICE + exit 1 +fi + +# This script *probably* only works with the following versions of OpenOCD: + +# Local search directory and configurations + +OPENOCD_SEARCHDIR="${TOPDIR}/configs/shenzhou/tools" +OPENOCD_WSEARCHDIR="`cygpath -w ${OPENOCD_SEARCHDIR}`" + +OPENOCD_PATH="/cygdrive/c/Program Files (x86)/OpenOCD/0.4.0/bin" +OPENOCD_EXE=openocd.exe +OPENOCD_INTERFACE="olimex-arm-usb-ocd.cfg" + + +OPENOCD_TARGET="stm32.cfg" +OPENOCD_ARGS="${DEBUG} -s ${OPENOCD_WSEARCHDIR} -f ${OPENOCD_INTERFACE} -f ${OPENOCD_TARGET}" + +echo "Trying OpenOCD 0.4.0 path: ${OPENOCD_PATH}/${OPENOCD_EXE}" + +# Verify that everything is what it claims it is and is located where it claims it is. + +if [ ! -x "${OPENOCD_PATH}/${OPENOCD_EXE}" ]; then + echo "OpenOCD executable does not exist: ${OPENOCD_PATH}/${OPENOCD_EXE}" + exit 1 +fi +if [ ! -f "${OPENOCD_SEARCHDIR}/${OPENOCD_TARGET}" ]; then + echo "OpenOCD target config file does not exist: ${OPENOCD_SEARCHDIR}/${OPENOCD_TARGET}" + exit 1 +fi +if [ ! -f "${OPENOCD_SEARCHDIR}/${OPENOCD_INTERFACE}" ]; then + echo "OpenOCD interface config file does not exist: ${OPENOCD_SEARCHDIR}/${OPENOCD_INTERFACE}" + exit 1 +fi + +# Enable debug if so requested + +if [ "X$2" = "X-d" ]; then + OPENOCD_ARGS=$OPENOCD_ARGS" -d3" + set -x +fi + +# Okay... do it! + +echo "Starting OpenOCD" +"${OPENOCD_PATH}/${OPENOCD_EXE}" ${OPENOCD_ARGS} & +echo "OpenOCD daemon started" +ps -ef | grep openocd +echo "In GDB: target remote localhost:3333" + diff --git a/nuttx/configs/cloudctrl/tools/stm32.cfg b/nuttx/configs/cloudctrl/tools/stm32.cfg new file mode 100644 index 0000000000..463a85cfd2 --- /dev/null +++ b/nuttx/configs/cloudctrl/tools/stm32.cfg @@ -0,0 +1,69 @@ +# script for stm32 + +if { [info exists CHIPNAME] } { + set _CHIPNAME $CHIPNAME +} else { + set _CHIPNAME stm32 +} + +if { [info exists ENDIAN] } { + set _ENDIAN $ENDIAN +} else { + set _ENDIAN little +} + +# Work-area is a space in RAM used for flash programming +# By default use 16kB +if { [info exists WORKAREASIZE] } { + set _WORKAREASIZE $WORKAREASIZE +} else { + set _WORKAREASIZE 0x4000 +} + +# JTAG speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so use F_JTAG = 1MHz +jtag_khz 1000 + +jtag_nsrst_delay 100 +jtag_ntrst_delay 100 + +#jtag scan chain +if { [info exists CPUTAPID ] } { + set _CPUTAPID $CPUTAPID +} else { + # See STM Document RM0008 + # Section 26.6.3 + set _CPUTAPID 0x3ba00477 +} +jtag newtap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID + +if { [info exists BSTAPID ] } { + # FIXME this never gets used to override defaults... + set _BSTAPID $BSTAPID +} else { + # See STM Document RM0008 + # Section 29.6.2 + # Low density devices, Rev A + set _BSTAPID1 0x06412041 + # Medium density devices, Rev A + set _BSTAPID2 0x06410041 + # Medium density devices, Rev B and Rev Z + set _BSTAPID3 0x16410041 + # High density devices, Rev A + set _BSTAPID4 0x06414041 + # Connectivity line devices, Rev A and Rev Z + set _BSTAPID5 0x06418041 +} +jtag newtap $_CHIPNAME bs -irlen 5 -expected-id $_BSTAPID1 \ + -expected-id $_BSTAPID2 -expected-id $_BSTAPID3 \ + -expected-id $_BSTAPID4 -expected-id $_BSTAPID5 + +set _TARGETNAME $_CHIPNAME.cpu +target create $_TARGETNAME cortex_m3 -endian $_ENDIAN -chain-position $_TARGETNAME + +$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0 + +set _FLASHNAME $_CHIPNAME.flash +flash bank $_FLASHNAME stm32x 0 0 0 0 $_TARGETNAME + +# For more information about the configuration files, take a look at: +# openocd.texi diff --git a/nuttx/configs/cloudctrl/tools/usb-driver.txt b/nuttx/configs/cloudctrl/tools/usb-driver.txt new file mode 100644 index 0000000000..83d7598a55 --- /dev/null +++ b/nuttx/configs/cloudctrl/tools/usb-driver.txt @@ -0,0 +1,25 @@ +https://www.olimex.com/dev/pdf/ARM/JTAG/Repair%20Procedure%20for%20OpenOcd-Rev.%20G%20drivers.pdf + +Repair procedure for ARM-USB-OCD drivers + +1. Uninstalling ARM-USB-OCD drivers +------------------------------------- +1.1. Connect your programmer/debugger to your computer, open Device Manager + and uninstall the drivers for ARM-USB-OCD. +1.2. After you have uninstalled ARM-USB-TINY driver from Device Manager, + disconnect the programmer from your computer. +1.3. Now you should download FTClean.exe from here: + http://www.ftdichip.com/Support/Utilities/FTClean.zip. +1.4. After download is complete extract the "*.zip" file, open folder FTClean, + and run FTClean.exe +1.5. Ror VID (Hex) select "Other". And after that fill the first box with 15ba + and "PID (Hex)" with 0004. +1.6. Press "Clean System" button. Make sure that all FTDI devices are + disconnected. (My require administrator privileges). + +2. Re-installing the ARM-USB-OCD driver +--------------------------------------- +2.1 Connect the programmer/debugger to the computer. +2.2 When prompted, browse to the C:\gccfd\DRIVERS\ARM-USB-OCD-DRIVER + directory and install. (A different driver is required for OpenOCD + 0.4.0. That driver is available from the olimex.com web site). diff --git a/nuttx/tools/README.txt b/nuttx/tools/README.txt index 68b85dc4f3..efe8ad68f3 100644 --- a/nuttx/tools/README.txt +++ b/nuttx/tools/README.txt @@ -403,6 +403,30 @@ unlink.sh script so that it uses the NTFS mklink command. But I have never tried that +prebuild.py +----------- + + This is a Python script contributed by Darcy Gong that automates many + build actions: + + Nuttx configure utils v 0.3 + usage: tools/prebuild.py [-abcdfhmr] [-b boardname] [-l number]\n'%(program_name) + -c, --clean : Will execute "make clean" command. + -d, --distclean : Will execute "make distclean" command. + -l, --cleanlevel : Will execute "make clean"(value of 1) or "make distclean"(value of 2) command. + -f, --fixcfg : The configuration correction nuttx.cfg defconfig configuration items. + -a, --auto : Equivalent parameters -d and -f. + -b, --boardname : The boardname configuration. + -r, --mkromfs : Make Romfs. + -m, --make : Make now. + -h, --help : Help Message. + + example:' + usage 1 : tools/prebuild.py -b fire-stm32v2/nsh + usage 2 : tools/prebuild.py -f -b fire-stm32v2/nsh + usage 3 : tools/prebuild.py -a -b fire-stm32v2/nsh + usage 4 : tools/prebuild.py -l 1 -f -b fire-stm32v2/nsh + mkimage.sh ---------- diff --git a/nuttx/tools/prebuild.py b/nuttx/tools/prebuild.py new file mode 100644 index 0000000000..34fed09b6b --- /dev/null +++ b/nuttx/tools/prebuild.py @@ -0,0 +1,256 @@ +#!/usr/bin/python + +import os +import sys,getopt +import commands +import ConfigParser +import socket +import fcntl +import struct +import re + +class Enum(object): + def __init__(self, *keys): + self.__dict__.update(zip(keys, range(len(keys)))) + +enum_parse_tag = Enum('tag','item') +enum_config = Enum('std','ext') + +def put_file_contents(filename,data=''): + if not os.path.isfile(filename): + return '' + try: + f = open(filename,'w') + contents = f.write(data) + f.close() + except IOError: + print 'file open or write err!' + +def fix_nuttx_cfg_value(key,val): + #if key == "CONFIG_NSH_IPADDR": + if re.search(r"_IPADDR$", key): + return '%s=%s\n'%(key,get_local_ip(50,2)) + #elif key == "CONFIG_NSH_DRIPADDR": + elif re.search(r"_DRIPADDR$", key): + return '%s=%s\n'%(key,get_local_ip(1,2)) + else: + return '%s=%s\n'%(key,val) + +def fix_nuttx_config(cfg,fix_cfgs): + result = '' + for line in cfg.readlines(): + line = line.strip() + if line.startswith('#'): + result += line+'\n' + continue + elif len(line) == 0: + result += '\n' + continue + elif line.count('=') > 0 : + #print line + it = line.find('=') + key = line[0:it].strip() + val = line[it + 1:].strip() + if fix_cfgs.has_key(key): + result += fix_nuttx_cfg_value(key, fix_cfgs.pop(key)) + else: + result += line+'\n' + else: + result += line+'\n' + #fix_cfgs = {} + #print fix_cfgs.viewitems() + if (len(fix_cfgs.keys())>0): + result += '\n\n####################################################\n\n' + for key in fix_cfgs.keys(): + result += fix_nuttx_cfg_value(key, fix_cfgs.pop(key)) + return result + + +def usage(): + program_name = sys.argv[0] + print 'Nuttx configure utils v 0.3\n' + print ' usage: %s [-abcdfhmr] [-b boardname] [-l number]\n'%(program_name) + print ' -c, --clean : Will execute "make clean" command.' + print ' -d, --distclean : Will execute "make distclean" command.' + print ' -l, --cleanlevel : Will execute "make clean"(value of 1) or "make distclean"(value of 2) command.' + print ' -f, --fixcfg : The configuration correction nuttx.cfg defconfig configuration items.' + print ' -a, --auto : Equivalent parameters -d and -f.' + print ' -b, --boardname : The boardname configuration.' + print ' -r, --mkromfs : Make Romfs.' + print ' -m, --make : Make now.' + print ' -h, --help : Help Message.' + print '\n example:' + print ' usage 1 : %s -b fire-stm32v2/nsh'%(program_name) + print ' usage 2 : %s -f -b fire-stm32v2/nsh'%(program_name) + print ' usage 3 : %s -a -b fire-stm32v2/nsh'%(program_name) + print ' usage 4 : %s -l 1 -f -b fire-stm32v2/nsh'%(program_name) + +def fix_config(boardname,fix_cfgs): + cfg_path = './configs/%s/defconfig'%boardname + if (os.path.isfile(cfg_path)): + try: + cfg = open(cfg_path, "r") + contents = fix_nuttx_config(cfg,fix_cfgs) + cfg.close() + #print contents + put_file_contents(cfg_path,contents) + except IOError: + print 'nuttx config open err!' + return '' + +def fix_root_config(fix_cfgs): + cfg_path = '.config' + if (os.path.isfile(cfg_path)): + try: + cfg = open(cfg_path, "r") + contents = fix_nuttx_config(cfg,fix_cfgs) + cfg.close() + #print contents + put_file_contents(cfg_path,contents) + except IOError: + print 'nuttx config open err!' + return '' + +def get_local_ipn(ifname): + s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) + ip = fcntl.ioctl(s.fileno(), + 0x8915, # SIOCGIFADDR + struct.pack('256s', ifname[:15]))[20:24] + return ip + +def get_local_ip(id=-1,mode=1): + ip = get_local_ipn('eth0') + if (id < 0): + id = ord(ip[3]) + ipr = ord(ip[0])<<24|ord(ip[1])<<16|ord(ip[2])<<8|(id & 0xFF) + if mode == 1 : + return socket.inet_ntoa(struct.pack('>L', ipr)) + if mode == 2 : + return "0x%x"%ipr + else: + return ipr + +def get_ip_address(ifname): + s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) + return socket.inet_ntoa(fcntl.ioctl( + s.fileno(), + 0x8915, # SIOCGIFADDR + struct.pack('256s', ifname[:15]) + )[20:24]) + +def config(cfg={}): + output = '' + fix_cfgs = {} + if cfg.clearlevel == 2: + print "make distclean apps_distclean" + output = commands.getoutput("make distclean apps_distclean") + elif cfg.clearlevel == 1: + print "make clean apps_clean" + output = commands.getoutput("make clean apps_clean") + + ini = ConfigParser.ConfigParser() + ini.optionxform = str + cfgf = 'nuttx_cfg.py' + #if not(os.path.isfile(cfgf)): + #fp = open(cfgf,'w') + #fp.write('# is nuttx config\n[info]\nlast=') + #fp.close() + #cfgf = open(cfgf,'rw') + ini.readfp(open(cfgf)) + lastfile = ini.get('info','last') + if (cmp(lastfile,cfg.boardname) != 0): + if ((cfg.boardname.strip() !='')): + lastfile = cfg.boardname + ini.set('info','last',lastfile) + ini.write(open(cfgf, "w")) + if cfg.usefix: + #print lastfile + if ini.has_section('defconfig'): + opts = ini.items('defconfig') + for item in opts: + fix_cfgs[item[0]] = item[1] + if ini.has_section(lastfile): + opts = ini.items(lastfile) + for item in opts: + fix_cfgs[item[0]] = item[1] + #print fix_cfgs + #fix_config(boardname,fix_cfgs) + + output = commands.getoutput("cd tools;./configure.sh %s;cd .."%lastfile) + print "tools/configure.sh %s"%lastfile + if cfg.usefix: + fix_root_config(fix_cfgs) + print "fix .config file" + if cfg.mkromfs: + if (os.path.isfile("./rcS.template")): + print "tools/mkromfsimg.sh ." + #output = commands.getoutput("tools/mkromfs.sh .") + os.system("tools/mkromfsimg.sh .") + bpath = "configs/%s/include"%(lastfile.split('/')[0]) + if (not os.path.exists(bpath)): + print "mkdir -p %s"%(bpath) + #commands.getoutput("mkdir -pv %s"%(bpath)) + os.system("mkdir -pv %s"%(bpath)) + if (not os.path.exists(bpath)): + print "[ERROR] no %s"%(bpath) + if (os.path.isfile("nsh_romfsimg.h")): + print "cp nsh_romfsimg.h %s/nsh_romfsimg.h"%(bpath) + #output = commands.getoutput("cp nsh_romfsimg.h include/arch/board/nsh_romfsimg.h") + os.system("cp nsh_romfsimg.h %s/nsh_romfsimg.h"%(bpath)) + if cfg.make: + os.system("sleep 3") + print "make" + os.system("make") + if '' != output.strip(): + print output + +class cfgobj(): + usefix = False + mkromfs = False + make = False + clearlevel = 0 + boardname = '' + +def main(): + try: + opts, args = getopt.getopt(sys.argv[1:], "dcb:hal:frm", + ["dictclean","clean","board=", "auto", "cleanlevel=", + "help","fixcfg","mkromfs","make"]) + except getopt.GetoptError: + # print help information and exit: + usage() + sys.exit(2) + #cfg = {"usefix":False,"mkromfs":False,"make":False,"clearlevel":0,"boardname":'' } + cfg = cfgobj() + for o, v in opts: + if o in ("-a","--auto"): + cfg.clearlevel = 2 + cfg.usefix = True + cfg.mkromfs = True + cfg.make = True + if o in ("-c","--clean"): + cfg.clearlevel = 1 + if o in ("-d","--distclean"): + cfg.clearlevel = 2 + if o in ("-l","--cleanlevel"): + if v == '1': + cfg.clearlevel = 1 + elif v == '2': + cfg.clearlevel = 2 + else: + cfg.clearlevel = 0 + if o in ("-b","--board"): + cfg.boardname = v + if o in ("-f","--fixcfg"): + cfg.usefix = True + if o in ("-r","--mkromfs"): + cfg.mkromfs = True + if o in ("-m","--make"): + cfg.make = True + if o in ("-h", "--help"): + usage() + sys.exit() + config(cfg) + +if __name__ == "__main__": + main() From 057c41d277bedaac328423816182669fab99a7b4 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 21 Nov 2012 18:34:10 +0000 Subject: [PATCH 150/206] Big refactoring of toolchain definitions by Mike Smith git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5379 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/Kconfig | 3 + nuttx/arch/arm/src/armv7-m/Kconfig | 51 ++++ nuttx/arch/arm/src/armv7-m/Toolchain.defs | 256 ++++++++++++++++++ nuttx/arch/arm/src/lm3s/Kconfig | 23 -- nuttx/arch/arm/src/lpc17xx/Kconfig | 32 --- nuttx/arch/arm/src/lpc43xx/Kconfig | 28 -- nuttx/arch/arm/src/stm32/Kconfig | 36 --- nuttx/arch/mips/src/mips32/Kconfig | 41 +++ nuttx/arch/mips/src/mips32/Toolchain.defs | 199 ++++++++++++++ nuttx/configs/ekk-lm3s9b96/nsh/Make.defs | 32 +-- nuttx/configs/ekk-lm3s9b96/ostest/Make.defs | 32 +-- nuttx/configs/fire-stm32v2/nsh/Make.defs | 60 +--- nuttx/configs/hymini-stm32v/buttons/Make.defs | 38 +-- nuttx/configs/hymini-stm32v/nsh/Make.defs | 38 +-- nuttx/configs/hymini-stm32v/nsh2/Make.defs | 38 +-- nuttx/configs/hymini-stm32v/nx/Make.defs | 38 +-- nuttx/configs/hymini-stm32v/nxlines/Make.defs | 41 +-- .../configs/hymini-stm32v/usbserial/Make.defs | 38 +-- .../hymini-stm32v/usbstorage/Make.defs | 38 +-- nuttx/configs/kwikstik-k40/ostest/Make.defs | 32 +-- nuttx/configs/lincoln60/nsh/Make.defs | 32 +-- nuttx/configs/lincoln60/ostest/Make.defs | 32 +-- nuttx/configs/lm3s6432-s2e/nsh/Make.defs | 32 +-- nuttx/configs/lm3s6432-s2e/ostest/Make.defs | 32 +-- nuttx/configs/lm3s6965-ek/nsh/Make.defs | 32 +-- nuttx/configs/lm3s6965-ek/nx/Make.defs | 32 +-- nuttx/configs/lm3s6965-ek/ostest/Make.defs | 32 +-- nuttx/configs/lm3s8962-ek/nsh/Make.defs | 32 +-- nuttx/configs/lm3s8962-ek/nx/Make.defs | 32 +-- nuttx/configs/lm3s8962-ek/ostest/Make.defs | 32 +-- nuttx/configs/lpc4330-xplorer/nsh/Make.defs | 69 +---- .../configs/lpc4330-xplorer/ostest/Make.defs | 69 +---- .../lpcxpresso-lpc1768/dhcpd/Make.defs | 44 +-- .../configs/lpcxpresso-lpc1768/nsh/Make.defs | 44 +-- nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs | 44 +-- .../lpcxpresso-lpc1768/ostest/Make.defs | 44 +-- .../lpcxpresso-lpc1768/thttpd/Make.defs | 44 +-- .../lpcxpresso-lpc1768/usbstorage/Make.defs | 44 +-- nuttx/configs/mbed/hidkbd/Make.defs | 32 +-- nuttx/configs/mbed/nsh/Make.defs | 32 +-- nuttx/configs/mirtoo/nsh/Make.defs | 74 +---- nuttx/configs/mirtoo/nxffs/Make.defs | 74 +---- nuttx/configs/mirtoo/ostest/Make.defs | 74 +---- nuttx/configs/nucleus2g/nsh/Make.defs | 32 +-- nuttx/configs/nucleus2g/ostest/Make.defs | 32 +-- nuttx/configs/nucleus2g/usbserial/Make.defs | 32 +-- nuttx/configs/nucleus2g/usbstorage/Make.defs | 32 +-- .../configs/olimex-lpc1766stk/ftpc/Make.defs | 32 +-- .../olimex-lpc1766stk/hidkbd/Make.defs | 32 +-- .../olimex-lpc1766stk/nettest/Make.defs | 32 +-- nuttx/configs/olimex-lpc1766stk/nsh/Make.defs | 32 +-- nuttx/configs/olimex-lpc1766stk/nx/Make.defs | 32 +-- .../olimex-lpc1766stk/ostest/Make.defs | 32 +-- .../olimex-lpc1766stk/slip-httpd/Make.defs | 32 +-- .../olimex-lpc1766stk/thttpd/Make.defs | 32 +-- .../olimex-lpc1766stk/usbserial/Make.defs | 32 +-- .../olimex-lpc1766stk/usbstorage/Make.defs | 32 +-- .../configs/olimex-lpc1766stk/wlan/Make.defs | 32 +-- nuttx/configs/olimex-stm32-p107/nsh/Make.defs | 44 +-- .../olimex-stm32-p107/ostest/Make.defs | 44 +-- nuttx/configs/pcblogic-pic32mx/nsh/Make.defs | 38 +-- .../configs/pcblogic-pic32mx/ostest/Make.defs | 38 +-- nuttx/configs/pic32-starterkit/nsh/Make.defs | 38 +-- nuttx/configs/pic32-starterkit/nsh2/Make.defs | 38 +-- .../configs/pic32-starterkit/ostest/Make.defs | 38 +-- nuttx/configs/pic32mx7mmb/nsh/Make.defs | 38 +-- nuttx/configs/pic32mx7mmb/ostest/Make.defs | 38 +-- nuttx/configs/sam3u-ek/knsh/Make.defs | 32 +-- nuttx/configs/sam3u-ek/nsh/Make.defs | 32 +-- nuttx/configs/sam3u-ek/nx/Make.defs | 32 +-- nuttx/configs/sam3u-ek/ostest/Make.defs | 32 +-- nuttx/configs/sam3u-ek/touchscreen/Make.defs | 32 +-- nuttx/configs/shenzhou/nsh/Make.defs | 58 +--- nuttx/configs/shenzhou/nxwm/Make.defs | 58 +--- nuttx/configs/shenzhou/thttpd/Make.defs | 58 +--- nuttx/configs/stm3210e-eval/RIDE/Make.defs | 38 +-- nuttx/configs/stm3210e-eval/buttons/Make.defs | 38 +-- .../configs/stm3210e-eval/composite/Make.defs | 38 +-- nuttx/configs/stm3210e-eval/nsh/Make.defs | 38 +-- nuttx/configs/stm3210e-eval/nsh2/Make.defs | 38 +-- nuttx/configs/stm3210e-eval/nx/Make.defs | 38 +-- .../configs/stm3210e-eval/nxconsole/Make.defs | 41 +-- nuttx/configs/stm3210e-eval/nxlines/Make.defs | 41 +-- nuttx/configs/stm3210e-eval/nxtext/Make.defs | 41 +-- nuttx/configs/stm3210e-eval/ostest/Make.defs | 38 +-- nuttx/configs/stm3210e-eval/pm/Make.defs | 38 +-- .../configs/stm3210e-eval/usbserial/Make.defs | 38 +-- .../stm3210e-eval/usbstorage/Make.defs | 38 +-- nuttx/configs/stm3220g-eval/dhcpd/Make.defs | 66 +---- nuttx/configs/stm3220g-eval/nettest/Make.defs | 66 +---- nuttx/configs/stm3220g-eval/nsh/Make.defs | 66 +---- nuttx/configs/stm3220g-eval/nsh2/Make.defs | 66 +---- nuttx/configs/stm3220g-eval/nxwm/Make.defs | 66 +---- nuttx/configs/stm3220g-eval/ostest/Make.defs | 66 +---- nuttx/configs/stm3220g-eval/telnetd/Make.defs | 66 +---- nuttx/configs/stm3240g-eval/dhcpd/Make.defs | 66 +---- .../configs/stm3240g-eval/discover/Make.defs | 66 +---- nuttx/configs/stm3240g-eval/nettest/Make.defs | 66 +---- nuttx/configs/stm3240g-eval/nsh/Make.defs | 66 +---- nuttx/configs/stm3240g-eval/nsh2/Make.defs | 66 +---- .../configs/stm3240g-eval/nxconsole/Make.defs | 66 +---- nuttx/configs/stm3240g-eval/nxwm/Make.defs | 66 +---- nuttx/configs/stm3240g-eval/ostest/Make.defs | 66 +---- nuttx/configs/stm3240g-eval/telnetd/Make.defs | 66 +---- .../configs/stm3240g-eval/webserver/Make.defs | 67 +---- nuttx/configs/stm3240g-eval/xmlrpc/Make.defs | 66 +---- .../configs/stm32f100rc_generic/nsh/Make.defs | 38 +-- .../stm32f100rc_generic/ostest/Make.defs | 38 +-- .../stm32f4discovery/cxxtest/Make.defs | 66 +---- nuttx/configs/stm32f4discovery/elf/Make.defs | 66 +---- nuttx/configs/stm32f4discovery/nsh/Make.defs | 66 +---- .../stm32f4discovery/nxlines/Make.defs | 66 +---- .../configs/stm32f4discovery/ostest/Make.defs | 66 +---- nuttx/configs/stm32f4discovery/pm/Make.defs | 66 +---- nuttx/configs/sure-pic32mx/nsh/Make.defs | 38 +-- nuttx/configs/sure-pic32mx/ostest/Make.defs | 38 +-- nuttx/configs/sure-pic32mx/usbnsh/Make.defs | 38 +-- nuttx/configs/twr-k60n512/nsh/Make.defs | 32 +-- nuttx/configs/twr-k60n512/ostest/Make.defs | 32 +-- nuttx/configs/ubw32/nsh/Make.defs | 38 +-- nuttx/configs/ubw32/ostest/Make.defs | 38 +-- nuttx/configs/vsn/nsh/Make.defs | 38 +-- 122 files changed, 664 insertions(+), 5062 deletions(-) create mode 100644 nuttx/arch/arm/src/armv7-m/Kconfig create mode 100644 nuttx/arch/arm/src/armv7-m/Toolchain.defs create mode 100644 nuttx/arch/mips/src/mips32/Toolchain.defs diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig index 9bec34ff1e..eb3bfe85b3 100644 --- a/nuttx/arch/arm/Kconfig +++ b/nuttx/arch/arm/Kconfig @@ -253,6 +253,9 @@ config DEBUG_HARDFAULT output is sometimes helpful when debugging difficult hard fault problems, but may be more than you typcially want to see. +if ARCH_CORTEXM3 || ARCH_CORTEXM4 +source arch/arm/src/armv7-m/Kconfig +endif if ARCH_CHIP_C5471 source arch/arm/src/c5471/Kconfig endif diff --git a/nuttx/arch/arm/src/armv7-m/Kconfig b/nuttx/arch/arm/src/armv7-m/Kconfig new file mode 100644 index 0000000000..dc5aa39153 --- /dev/null +++ b/nuttx/arch/arm/src/armv7-m/Kconfig @@ -0,0 +1,51 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +comment "ARMV7M Configuration Options" + +choice + prompt "Toolchain Selection" + default ARMV7M_TOOLCHAIN_CODESOURCERYW if HOST_WINDOWS + default ARMV7M_TOOLCHAIN_GNU_EABI if !HOST_WINDOWS + +config ARMV7M_TOOLCHAIN_ATOLLIC + bool "Atollic Lite/Pro for Windows" + depends on HOST_WINDOWS + +config ARMV7M_TOOLCHAIN_BUILDROOT + bool "Buildroot (Cygwin or Linux)" + depends on !WINDOWS_NATIVE + +config ARMV7M_TOOLCHAIN_CODEREDL + bool "CodeRed for Linux" + depends on HOST_LINUX + +config ARMV7M_TOOLCHAIN_CODEREDW + bool "CodeRed for Windows" + depends on HOST_WINDOWS + +config ARMV7M_TOOLCHAIN_CODESOURCERYL + bool "CodeSourcery GNU toolchain under Linux" + depends on HOST_LINUX + +config ARMV7M_TOOLCHAIN_CODESOURCERYW + bool "CodeSourcery GNU toolchain under Windows" + depends on HOST_WINDOWS + +config ARMV7M_TOOLCHAIN_DEVKITARM + bool "devkitARM GNU toolchain" + depends on HOST_WINDOWS + +config ARMV7M_TOOLCHAIN_GNU_EABI + bool "Generic GNU EABI toolchain" + ---help--- + This option should work for any modern GNU toolchain (GCC 4.5 or newer) + configured for arm-none-eabi. + +config ARMV7M_TOOLCHAIN_RAISONANCE + bool "STMicro Raisonance for Windows" + depends on HOST_WINDOWS + +endchoice diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs new file mode 100644 index 0000000000..ab77e3eb34 --- /dev/null +++ b/nuttx/arch/arm/src/armv7-m/Toolchain.defs @@ -0,0 +1,256 @@ +############################################################################ +# arch/arm/src/armv7-m/Toolchain.defs +# +# 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. +# +############################################################################ + +# Setup for the selected toolchain + +# +# Handle old-style chip-specific toolchain names in the absence of +# a new-style toolchain specification, force the selection of a single +# toolchain and allow the selected toolchain to be overridden by a +# command-line selection. +# + +ifeq ($(filter y, \ + $(CONFIG_LPC43_ATOLLIC_LITE) \ + $(CONFIG_STM32_ATOLLIC_LITE) \ + $(CONFIG_LPC43_ATOLLIC_PRO) \ + $(CONFIG_STM32_ATOLLIC_PRO) \ + $(CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC) \ + ),y) + CONFIG_ARMV7M_TOOLCHAIN ?= ATOLLIC +endif +ifeq ($(filter y, \ + $(CONFIG_KINETIS_BUILDROOT) \ + $(CONFIG_LM3S_BUILDROOT) \ + $(CONFIG_LPC17_BUILDROOT) \ + $(CONFIG_LPC43_BUILDROOT) \ + $(CONFIG_SAM3U_BUILDROOT) \ + $(CONFIG_STM32_BUILDROOT) \ + $(CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT) \ + ),y) + CONFIG_ARMV7M_TOOLCHAIN ?= BUILDROOT +endif +ifeq ($(filter y, \ + $(CONFIG_LPC17_CODEREDL) \ + $(CONFIG_ARMV7M_TOOLCHAIN_CODEREDL) \ + ),y) + CONFIG_ARMV7M_TOOLCHAIN ?= CODEREDL +endif +ifeq ($(filter y, \ + $(CONFIG_LPC17_CODEREDW) \ + $(CONFIG_LPC43_CODEREDW) \ + $(CONFIG_ARMV7M_TOOLCHAIN_CODEREDW) \ + ),y) + CONFIG_ARMV7M_TOOLCHAIN ?= CODEREDW +endif +ifeq ($(filter y, \ + $(CONFIG_KINETIS_CODESOURCERYL) \ + $(CONFIG_LM3S_CODESOURCERYL) \ + $(CONFIG_LPC17_CODESOURCERYL) \ + $(CONFIG_LPC43_CODESOURCERYL) \ + $(CONFIG_SAM3U_CODESOURCERYL) \ + $(CONFIG_STM32_CODESOURCERYL) \ + $(CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL) \ + ),y) + CONFIG_ARMV7M_TOOLCHAIN ?= CODESOURCERYL +endif +ifeq ($(filter y, \ + $(CONFIG_KINETIS_CODESOURCERYW) \ + $(CONFIG_LM3S_CODESOURCERYW) \ + $(CONFIG_LPC17_CODESOURCERYW) \ + $(CONFIG_LPC43_CODESOURCERYW) \ + $(CONFIG_SAM3U_CODESOURCERYW) \ + $(CONFIG_STM32_CODESOURCERYW) \ + $(CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW) \ + ),y) + CONFIG_ARMV7M_TOOLCHAIN ?= CODESOURCERYW +endif +ifeq ($(filter y, \ + $(CONFIG_KINETIS_DEVKITARM) \ + $(CONFIG_LM3S_DEVKITARM) \ + $(CONFIG_LPC17_DEVKITARM) \ + $(CONFIG_LPC43_DEVKITARM) \ + $(CONFIG_SAM3U_DEVKITARM) \ + $(CONFIG_STM32_DEVKITARM) \ + $(CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM) \ + ),y) + CONFIG_ARMV7M_TOOLCHAIN ?= DEVKITARM +endif +ifeq ($(filter y, \ + $(CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI) \ + ),y) + CONFIG_ARMV7M_TOOLCHAIN ?= GNU_EABI +endif +ifeq ($(filter y, \ + $(CONFIG_STM32_RAISONANCE) \ + $(CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE) \ + ),y) + CONFIG_ARMV7M_TOOLCHAIN ?= RAISONANCE +endif + +# +# Supported toolchains +# +# TODO - It's likely that all of these toolchains now support the +# CortexM4. Since they are all GCC-based, we could almost +# certainly simplify this further. +# +# Each toolchain definition should set: +# +# CROSSDEV The GNU toolchain triple (command prefix) +# ARCROSSDEV If required, an alternative prefix used when +# invoking ar and nm. +# ARCHCPUFLAGS CPU-specific flags selecting the instruction set +# FPU options, etc. +# MAXOPTIMIZATION The maximum optimization level that results in +# reliable code generation. +# + +# Atollic toolchain under Windows + +ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),ATOLLIC) + CROSSDEV = arm-atollic-eabi- + ARCROSSDEV = arm-atollic-eabi- + WINTOOL = y + ifeq ($(CONFIG_ARCH_CORTEXM4),y) + ifeq ($(CONFIG_ARCH_FPU),y) + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard + else + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft + endif + else ifeq ($(CONFIG_ARCH_CORTEXM3),y) + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + endif +endif + +# NuttX buildroot under Linux or Cygwin + +ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),BUILDROOT) + # 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 + +# Code Red RedSuite under Linux + +ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDL) + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + ifeq ($(CONFIG_ARCH_CORTEXM4),y) + ifeq ($(CONFIG_ARCH_FPU),y) + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard + else + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft + endif + else ifeq ($(CONFIG_ARCH_CORTEXM3),y) + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + endif +endif + +# Code Red RedSuite under Windows + +ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDW) + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ifeq ($(CONFIG_ARCH_CORTEXM4),y) + ifeq ($(CONFIG_ARCH_FPU),y) + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard + else + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft + endif + else ifeq ($(CONFIG_ARCH_CORTEXM3),y) + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + endif +endif + +# CodeSourcery under Linux + +ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYL) + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + MAXOPTIMIZATION = -O2 +endif + +# CodeSourcery under Windows + +ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYW) + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif + +# devkitARM under Windows + +ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),DEVKITARM) + CROSSDEV = arm-eabi- + ARCROSSDEV = arm-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif + +# Generic GNU EABI toolchain on OS X, Linux or any typical Posix system + +ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),GNU_EABI) + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + MAXOPTIMIZATION = -O3 + ifeq ($(CONFIG_ARCH_CORTEXM4),y) + ifeq ($(CONFIG_ARCH_FPU),y) + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard + else + ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft + endif + else ifeq ($(CONFIG_ARCH_CORTEXM3),y) + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft + endif +endif + +# Raisonance RIDE7 under Windows + +ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),RAISONANCE) + CROSSDEV = arm-none-eabi- + ARCROSSDEV = arm-none-eabi- + WINTOOL = y + ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft +endif diff --git a/nuttx/arch/arm/src/lm3s/Kconfig b/nuttx/arch/arm/src/lm3s/Kconfig index ef33655f55..469ff1fc91 100644 --- a/nuttx/arch/arm/src/lm3s/Kconfig +++ b/nuttx/arch/arm/src/lm3s/Kconfig @@ -27,29 +27,6 @@ config ARCH_CHIP_LM3S8962 endchoice -choice - prompt "Toolchain Selection" - default LM3S_BUILDROOT if !HOST_WINDOWS - default LM3S_CODESOURCERYW if HOST_WINDOWS - -config LM3S_CODESOURCERYW - bool "CodeSourcery GNU toolchain under Windows" - depends on HOST_WINDOWS - -config LM3S_CODESOURCERYL - bool "CodeSourcery GNU toolchain under Linux" - depends on HOST_LINUX - -config LM3S_DEVKITARM - bool "devkitARM GNU toolchain" - depends on HOST_WINDOWS - -config LM3S_BUILDROOT - bool "Buildroot" - depends on !WINDOWS_NATIVE - -endchoice - config LM3S_DFU bool "DFU" default y diff --git a/nuttx/arch/arm/src/lpc17xx/Kconfig b/nuttx/arch/arm/src/lpc17xx/Kconfig index 8a12ad9023..8acd67595f 100644 --- a/nuttx/arch/arm/src/lpc17xx/Kconfig +++ b/nuttx/arch/arm/src/lpc17xx/Kconfig @@ -56,38 +56,6 @@ config ARCH_FAMILY_LPC176X bool default y if ARCH_CHIP_LPC1764 || ARCH_CHIP_LPC1765 || ARCH_CHIP_LPC1766 || ARCH_CHIP_LPC1767 || ARCH_CHIP_LPC1768 || ARCH_CHIP_LPC1769 -choice - prompt "Toolchain Selection" - default LPC17_BUILDROOT if !HOST_WINDOWS - default LPC17_CODESOURCERYW if HOST_WINDOWS - depends on ARCH_CHIP_LPC17XX - -config LPC17_CODESOURCERYW - bool "CodeSourcery GNU toolchain under Windows" - depends on HOST_WINDOWS - -config LPC17_CODESOURCERYL - bool "CodeSourcery GNU toolchain under Linux" - depends on HOST_LINUX - -config LPC17_DEVKITARM - bool "devkitARM GNU toolchain" - depends on HOST_WINDOWS - -config LPC17_BUILDROOT - bool "Buildroot" - depends on !WINDOWS_NATIVE - -config LPC17_CODEREDW - bool "CodeRed for Windows" - depends on HOST_WINDOWS - -config LPC17_CODEREDL - bool "CodeRed for Windows" - depends on HOST_LINUX - -endchoice - menu "LPC17xx Peripheral Support" config LPC17_MAINOSC diff --git a/nuttx/arch/arm/src/lpc43xx/Kconfig b/nuttx/arch/arm/src/lpc43xx/Kconfig index 4653b2ee35..6902935ca9 100644 --- a/nuttx/arch/arm/src/lpc43xx/Kconfig +++ b/nuttx/arch/arm/src/lpc43xx/Kconfig @@ -87,34 +87,6 @@ config ARCH_FAMILY_LPC4357 bool default y if ARCH_CHIP_LPC4357FET180 || ARCH_CHIP_LPC4357FBD208 || ARCH_CHIP_LPC4357FET256 -choice - prompt "Toolchain Selection" - default LPC43_CODEREDW - depends on ARCH_CHIP_LPC43XX - -config LPC43_CODEREDW - bool "CodeRed for Windows" - -config LPC43_CODESOURCERYW - bool "CodeSourcery for Windows" - -config LPC43_CODESOURCERYL - bool "CodeSourcery for Linux" - -config LPC43_ATOLLIC_LITE - bool "Atollic Lite for Windows" - -config LPC43_ATOLLIC_PRO - bool "Atollic Pro for Windows" - -config LPC43_DEVKITARM - bool "DevkitARM (Windows)" - -config LPC43_BUILDROOT - bool "NuttX buildroot (Cygwin or Linux)" - -endchoice - choice prompt "LPC43XX Boot Configuration" default BOOT_SRAM diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 68cd9003c9..4e369cb1a2 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -193,42 +193,6 @@ config STM32_STM32F20XX config STM32_STM32F40XX bool -choice - prompt "Toolchain Selection" - default LPC31_BUILDROOT if !HOST_WINDOWS - default STM32_CODESOURCERYW if HOST_WINDOWS - depends on ARCH_CHIP_STM32 - -config STM32_CODESOURCERYW - bool "CodeSourcery GNU toolchain under Windows" - depends on HOST_WINDOWS - -config STM32_CODESOURCERYL - bool "CodeSourcery GNU toolchain under Linux" - depends on HOST_LINUX - -config STM32_ATOLLIC_LITE - bool "Atollic Lite for Windows" - depends on HOST_WINDOWS - -config STM32_ATOLLIC_PRO - bool "Atollic Pro for Windows" - depends on HOST_WINDOWS - -config STM32_DEVKITARM - bool "devkitARM GNU toolchain" - depends on HOST_WINDOWS - -config STM32_RAISONANCE - bool "STMicro Raisonance for Windows" - depends on HOST_WINDOWS - -config STM32_BUILDROOT - bool "Buildroot (Cygwin or Linux)" - depends on !WINDOWS_NATIVE - -endchoice - config STM32_DFU bool "DFU bootloader" default n diff --git a/nuttx/arch/mips/src/mips32/Kconfig b/nuttx/arch/mips/src/mips32/Kconfig index 1b44995687..b8b5d9b926 100644 --- a/nuttx/arch/mips/src/mips32/Kconfig +++ b/nuttx/arch/mips/src/mips32/Kconfig @@ -6,4 +6,45 @@ if ARCH_MIPS32 comment "MIPS32 Configuration Options" +choice + prompt "Toolchain Selection" + default MIPS32_TOOLCHAIN_MICROCHIPW_LITE if HOST_WINDOWS + default MIPS32_TOOLCHAIN_GNU_ELF if !HOST_WINDOWS + +config MIPS32_TOOLCHAIN_GNU_ELF + bool "Generic GNU ELF toolchain" + ---help--- + This option should work for any modern GNU toolchain (GCC 4.5 or newer) + configured for mips32-elf. + +config MIPS32_TOOLCHAIN_MICROCHIPL + bool "Microchip C32 toolchain under Linux" + depends on HOST_LINUX + +config MIPS32_TOOLCHAIN_MICROCHIPL_LITE + bool "Microchip C32 toolchain under Linux (Lite edition)" + depends on HOST_LINUX + +config MIPS32_TOOLCHAIN_MICROCHIPW + bool "Microchip C32 toolchain under Windows" + depends on HOST_WINDOWS + +config MIPS32_TOOLCHAIN_MICROCHIPW_LITE + bool "Microchip C32 toolchain under Windows (Lite edition)" + depends on HOST_WINDOWS + +config MIPS32_TOOLCHAIN_MICROCHIPOPENL + bool "microchipOpen toolchain under Linux" + depends on HOST_LINUX + +config MIPS32_TOOLCHAIN_PINGUINOW + bool "Pinguino mips-elf toolchain under Windows" + depends on HOST_WINDOWS + +config MIPS32_TOOLCHAIN_PINGUINOL + bool "Pinguino mips-elf toolchain under OS X or Linux" + depends on HOST_LINUX || HOST_OSX + +endchoice + endif diff --git a/nuttx/arch/mips/src/mips32/Toolchain.defs b/nuttx/arch/mips/src/mips32/Toolchain.defs new file mode 100644 index 0000000000..9a39c5eda0 --- /dev/null +++ b/nuttx/arch/mips/src/mips32/Toolchain.defs @@ -0,0 +1,199 @@ +############################################################################ +# arch/mips/src/mips32/Toolchain.defs +# +# 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. +# +############################################################################ + +# Setup for the selected toolchain + +# +# Handle old-style chip-specific toolchain names in the absence of +# a new-style toolchain specification, force the selection of a single +# toolchain and allow the selected toolchain to be overridden by a +# command-line selection. +# +ifeq ($(filter y, \ + $(CONFIG_MIPS32_TOOLCHAIN_GNU_ELF) \ + ),y) + CONFIG_MIPS32_TOOLCHAIN ?= GNU_ELF +endif +ifeq ($(filter y, \ + $(CONFIG_PIC32MX_MICROCHIPL) \ + $(CONFIG_MIPS32_TOOLCHAIN_MICROCHIPL) \ + ),y) + CONFIG_MIPS32_TOOLCHAIN ?= MICROCHIPL +endif +ifeq ($(filter y, \ + $(CONFIG_PIC32MX_MICROCHIPL_LITE) \ + $(CONFIG_MIPS32_TOOLCHAIN_MICROCHIPL_LITE) \ + ),y) + CONFIG_MIPS32_TOOLCHAIN ?= MICROCHIPL_LITE +endif +ifeq ($(filter y, \ + $(CONFIG_PIC32MX_MICROCHIPW) \ + $(CONFIG_MIPS32_TOOLCHAIN_MICROCHIPW) \ + ),y) + CONFIG_MIPS32_TOOLCHAIN ?= MICROCHIPW +endif +ifeq ($(filter y, \ + $(CONFIG_PIC32MX_MICROCHIPW_LITE) \ + $(CONFIG_MIPS32_TOOLCHAIN_MICROCHIPW_LITE) \ + ),y) + CONFIG_MIPS32_TOOLCHAIN ?= MICROCHIPW_LITE +endif +ifeq ($(filter y, \ + $(CONFIG_PIC32MX_MICROCHIPOPENL) \ + $(CONFIG_MIPS32_TOOLCHAIN_MICROCHIPOPENL) \ + ),y) + CONFIG_MIPS32_TOOLCHAIN ?= MICROCHIPOPENL +endif +ifeq ($(filter y, \ + $(CONFIG_PIC32MX_PINGUINOW) \ + $(CONFIG_MIPS32_TOOLCHAIN_PINGUINOW) \ + ),y) + CONFIG_MIPS32_TOOLCHAIN ?= PINGUINOW +endif +ifeq ($(filter y, \ + $(CONFIG_PIC32MX_PINGUINOL) \ + $(CONFIG_MIPS32_TOOLCHAIN_PINGUINOL) \ + ),y) + CONFIG_MIPS32_TOOLCHAIN ?= PINGUINOL +endif + +# +# Supported toolchains +# +# Each toolchain definition should set: +# +# CROSSDEV The GNU toolchain triple (command prefix) +# ARCROSSDEV If required, an alternative prefix used when +# invoking ar and nm. +# ARCHCPUFLAGS CPU-specific flags selecting the instruction set +# FPU options, etc. +# MAXOPTIMIZATION The maximum optimization level that results in +# reliable code generation. +# + +# Generic GNU mip32 toolchain on OS X or Linux + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN),GNU_ELF) + CROSSDEV = mips-elf- + MAXOPTIMIZATION = -O2 + ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL + ARCHPICFLAGS = -fpic -membedded-pic + LDFLAGS += -nostartfiles -nodefaultlibs + LDSCRIPT = mips-elf-debug.ld +endif + +# Microchip C32 toolchain under Linux + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPL) + CROSSDEV = pic32- + # CROSSDEV = xc32- + MAXOPTIMIZATION = -O2 + ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data + ARCHPICFLAGS = -fpic -membedded-pic + LDFLAGS += -nostartfiles -nodefaultlibs + LDSCRIPT = xc32-debug.ld +endif + +# Microchip C32 toolchain under Windows + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPW) + CROSSDEV = pic32- + # CROSSDEV = xc32- + WINTOOL = y + MAXOPTIMIZATION = -O2 + ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data + ARCHPICFLAGS = -fpic -membedded-pic + LDFLAGS += -nostartfiles -nodefaultlibs + LDSCRIPT = c32-debug.ld +endif + +# Microchip C32 toolchain under Linux + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPL_LITE) + CROSSDEV = pic32- + # CROSSDEV = xc32- + # MAXOPTIMIZATION = -O2 + ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data + ARCHPICFLAGS = -fpic -membedded-pic + LDFLAGS += -nostartfiles -nodefaultlibs + LDSCRIPT = xc32-debug.ld +endif + +# Microchip C32 toolchain under Windows + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPW_LITE) + CROSSDEV = pic32- + # CROSSDEV = xc32- + WINTOOL = y + # MAXOPTIMIZATION = -O2 + ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data + ARCHPICFLAGS = -fpic -membedded-pic + LDFLAGS += -nostartfiles -nodefaultlibs + LDSCRIPT = c32-debug.ld +endif + +# microchipOpen toolchain under Linux + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPOPENL) + CROSSDEV = mypic32- + # MAXOPTIMIZATION = -O2 + ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data + ARCHPICFLAGS = -fpic -membedded-pic + LDFLAGS += -nostartfiles -nodefaultlibs + LDSCRIPT = c32-debug.ld +endif + +# Pinguino mips-elf toolchain under Windows + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN),PINGUINOW) + CROSSDEV = mips- + WINTOOL = y + MAXOPTIMIZATION = -O2 + ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL + ARCHPICFLAGS = -fpic -membedded-pic + LDFLAGS += -nostartfiles -nodefaultlibs + LDSCRIPT = mips-elf-debug.ld +endif + +# Pinguino mips-elf toolchain under OS X or Linux + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN),PINGUINOL) + CROSSDEV = mips-elf- + MAXOPTIMIZATION = -O2 + ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL + ARCHPICFLAGS = -fpic -membedded-pic + LDFLAGS += -nostartfiles -nodefaultlibs + LDSCRIPT = mips-elf-debug.ld +endif diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs b/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs index 1563e73a97..930c50d2b4 100644 --- a/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs +++ b/nuttx/configs/ekk-lm3s9b96/nsh/Make.defs @@ -36,37 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LM3S_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LM3S_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs b/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs index b052c86aeb..1aa37e6dfe 100644 --- a/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs +++ b/nuttx/configs/ekk-lm3s9b96/ostest/Make.defs @@ -36,37 +36,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LM3S_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LM3S_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/fire-stm32v2/nsh/Make.defs b/nuttx/configs/fire-stm32v2/nsh/Make.defs index 271d4ab17c..6022fac750 100644 --- a/nuttx/configs/fire-stm32v2/nsh/Make.defs +++ b/nuttx/configs/fire-stm32v2/nsh/Make.defs @@ -35,65 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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- - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs # Pick the linker script diff --git a/nuttx/configs/hymini-stm32v/buttons/Make.defs b/nuttx/configs/hymini-stm32v/buttons/Make.defs index fde36e025b..73ad7f66e6 100644 --- a/nuttx/configs/hymini-stm32v/buttons/Make.defs +++ b/nuttx/configs/hymini-stm32v/buttons/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/hymini-stm32v/nsh/Make.defs b/nuttx/configs/hymini-stm32v/nsh/Make.defs index f819679f29..bb92fd59fc 100644 --- a/nuttx/configs/hymini-stm32v/nsh/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/hymini-stm32v/nsh2/Make.defs b/nuttx/configs/hymini-stm32v/nsh2/Make.defs index c1c55a1f70..6ba30422e1 100644 --- a/nuttx/configs/hymini-stm32v/nsh2/Make.defs +++ b/nuttx/configs/hymini-stm32v/nsh2/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/hymini-stm32v/nx/Make.defs b/nuttx/configs/hymini-stm32v/nx/Make.defs index 2d26b881b1..7af7f82460 100644 --- a/nuttx/configs/hymini-stm32v/nx/Make.defs +++ b/nuttx/configs/hymini-stm32v/nx/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/hymini-stm32v/nxlines/Make.defs b/nuttx/configs/hymini-stm32v/nxlines/Make.defs index 1970020f1b..9f00a4939c 100644 --- a/nuttx/configs/hymini-stm32v/nxlines/Make.defs +++ b/nuttx/configs/hymini-stm32v/nxlines/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,44 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O1 -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O1 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/hymini-stm32v/usbserial/Make.defs b/nuttx/configs/hymini-stm32v/usbserial/Make.defs index 68a0618b0a..c514e9b53d 100644 --- a/nuttx/configs/hymini-stm32v/usbserial/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbserial/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs index b59091c5e5..a3b6d55954 100644 --- a/nuttx/configs/hymini-stm32v/usbstorage/Make.defs +++ b/nuttx/configs/hymini-stm32v/usbstorage/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/kwikstik-k40/ostest/Make.defs b/nuttx/configs/kwikstik-k40/ostest/Make.defs index 7f260d2671..45d30d3200 100644 --- a/nuttx/configs/kwikstik-k40/ostest/Make.defs +++ b/nuttx/configs/kwikstik-k40/ostest/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_KINETIS_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls -endif -ifeq ($(CONFIG_KINETIS_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_KINETIS_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls -endif -ifeq ($(CONFIG_KINETIS_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lincoln60/nsh/Make.defs b/nuttx/configs/lincoln60/nsh/Make.defs index 8d17270240..6d80293679 100644 --- a/nuttx/configs/lincoln60/nsh/Make.defs +++ b/nuttx/configs/lincoln60/nsh/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lincoln60/ostest/Make.defs b/nuttx/configs/lincoln60/ostest/Make.defs index e8a4ec3ea5..6c8db35318 100644 --- a/nuttx/configs/lincoln60/ostest/Make.defs +++ b/nuttx/configs/lincoln60/ostest/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs index 6597c42838..e39eb4447e 100644 --- a/nuttx/configs/lm3s6432-s2e/nsh/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/nsh/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LM3S_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LM3S_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs index 3ac4c12ac4..94285fc78a 100644 --- a/nuttx/configs/lm3s6432-s2e/ostest/Make.defs +++ b/nuttx/configs/lm3s6432-s2e/ostest/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LM3S_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LM3S_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lm3s6965-ek/nsh/Make.defs b/nuttx/configs/lm3s6965-ek/nsh/Make.defs index d8c4978bda..b25c1be620 100644 --- a/nuttx/configs/lm3s6965-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nsh/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LM3S_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LM3S_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lm3s6965-ek/nx/Make.defs b/nuttx/configs/lm3s6965-ek/nx/Make.defs index eccfcde079..0b0e668f97 100644 --- a/nuttx/configs/lm3s6965-ek/nx/Make.defs +++ b/nuttx/configs/lm3s6965-ek/nx/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LM3S_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LM3S_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lm3s6965-ek/ostest/Make.defs b/nuttx/configs/lm3s6965-ek/ostest/Make.defs index fe15153db3..8dcc94b3f7 100644 --- a/nuttx/configs/lm3s6965-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s6965-ek/ostest/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LM3S_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LM3S_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lm3s8962-ek/nsh/Make.defs b/nuttx/configs/lm3s8962-ek/nsh/Make.defs index 3269059c9b..fc7216f229 100644 --- a/nuttx/configs/lm3s8962-ek/nsh/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nsh/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LM3S_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LM3S_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lm3s8962-ek/nx/Make.defs b/nuttx/configs/lm3s8962-ek/nx/Make.defs index 5c2bab9154..bab1ab565c 100644 --- a/nuttx/configs/lm3s8962-ek/nx/Make.defs +++ b/nuttx/configs/lm3s8962-ek/nx/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LM3S_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LM3S_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lm3s8962-ek/ostest/Make.defs b/nuttx/configs/lm3s8962-ek/ostest/Make.defs index 19b7fef1d1..c19c7e91f6 100644 --- a/nuttx/configs/lm3s8962-ek/ostest/Make.defs +++ b/nuttx/configs/lm3s8962-ek/ostest/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LM3S_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LM3S_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LM3S_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lpc4330-xplorer/nsh/Make.defs b/nuttx/configs/lpc4330-xplorer/nsh/Make.defs index 49fc903aa1..49cec55529 100644 --- a/nuttx/configs/lpc4330-xplorer/nsh/Make.defs +++ b/nuttx/configs/lpc4330-xplorer/nsh/Make.defs @@ -35,74 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC43_CODEREDW),y) - # Code Red RedSuite under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_LPC43_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC43_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC43_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_LPC43_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_LPC43_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC43_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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs # Setup for the kind of memory that we are executing from diff --git a/nuttx/configs/lpc4330-xplorer/ostest/Make.defs b/nuttx/configs/lpc4330-xplorer/ostest/Make.defs index 49fc903aa1..49cec55529 100644 --- a/nuttx/configs/lpc4330-xplorer/ostest/Make.defs +++ b/nuttx/configs/lpc4330-xplorer/ostest/Make.defs @@ -35,74 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC43_CODEREDW),y) - # Code Red RedSuite under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_LPC43_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC43_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC43_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_LPC43_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_LPC43_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC43_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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs # Setup for the kind of memory that we are executing from diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs index 5c7bd715eb..0f6b8914a9 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/Make.defs @@ -35,49 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif -ifeq ($(CONFIG_LPC17_CODEREDW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ -endif -ifeq ($(CONFIG_LPC17_CODEREDL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ - MAXOPTIMIZATION = -O2 -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs index 020006de32..84cec73996 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/Make.defs @@ -35,49 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif -ifeq ($(CONFIG_LPC17_CODEREDW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ -endif -ifeq ($(CONFIG_LPC17_CODEREDL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ - MAXOPTIMIZATION = -O2 -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs index 79390242bb..4e17bd90a3 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/nx/Make.defs @@ -35,49 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif -ifeq ($(CONFIG_LPC17_CODEREDW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ -endif -ifeq ($(CONFIG_LPC17_CODEREDL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ - MAXOPTIMIZATION = -O2 -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs index 5a99725c07..ad40aa69b0 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/Make.defs @@ -35,49 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif -ifeq ($(CONFIG_LPC17_CODEREDW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ -endif -ifeq ($(CONFIG_LPC17_CODEREDL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ - MAXOPTIMIZATION = -O2 -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs index 9fe82fe83a..b9ba57b0dd 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/Make.defs @@ -35,49 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - # CROSSDEV = arm-nuttx-eabi- - # ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif -ifeq ($(CONFIG_LPC17_CODEREDW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ -endif -ifeq ($(CONFIG_LPC17_CODEREDL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ - MAXOPTIMIZATION = -O2 -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs index a42b8e84a6..bb63eeec77 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs +++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/Make.defs @@ -35,49 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif -ifeq ($(CONFIG_LPC17_CODEREDW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ -endif -ifeq ($(CONFIG_LPC17_CODEREDL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -D__NEWLIB__ - MAXOPTIMIZATION = -O2 -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/mbed/hidkbd/Make.defs b/nuttx/configs/mbed/hidkbd/Make.defs index b11b33d6d3..58652c1ef9 100644 --- a/nuttx/configs/mbed/hidkbd/Make.defs +++ b/nuttx/configs/mbed/hidkbd/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/mbed/nsh/Make.defs b/nuttx/configs/mbed/nsh/Make.defs index a7bc14423f..0c6292e358 100644 --- a/nuttx/configs/mbed/nsh/Make.defs +++ b/nuttx/configs/mbed/nsh/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/mirtoo/nsh/Make.defs b/nuttx/configs/mirtoo/nsh/Make.defs index 28ea99ab04..51193893c3 100644 --- a/nuttx/configs/mirtoo/nsh/Make.defs +++ b/nuttx/configs/mirtoo/nsh/Make.defs @@ -35,79 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip C32 toolchain under Windows - CROSSDEV = pic32- - # CROSSDEV = xc32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = c32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip C32 toolchain under Windows - CROSSDEV = pic32- - # CROSSDEV = xc32- - WINTOOL = y - # MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = c32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip C32 toolchain under Linux - CROSSDEV = pic32- - # CROSSDEV = xc32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = xc32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip C32 toolchain under Linux - CROSSDEV = pic32- - # CROSSDEV = xc32- - # MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = xc32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPOPENL),y) - # microchipOpen toolchain under Linux - CROSSDEV = mypic32- - # MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = c32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_PINGUINOW),y) - # Penquino mips-elf toolchain under Windows - CROSSDEV = mips- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = mips-elf-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_PINGUINOL),y) - # Penquino mips-elf toolchain under Linux - CROSSDEV = mips-elf- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = mips-elf-debug.ld -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/mirtoo/nxffs/Make.defs b/nuttx/configs/mirtoo/nxffs/Make.defs index 09989324e5..6bc3bee804 100644 --- a/nuttx/configs/mirtoo/nxffs/Make.defs +++ b/nuttx/configs/mirtoo/nxffs/Make.defs @@ -35,79 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip C32 toolchain under Windows - CROSSDEV = pic32- - # CROSSDEV = xc32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = c32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip C32 toolchain under Windows - CROSSDEV = pic32- - # CROSSDEV = xc32- - WINTOOL = y - # MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = c32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip C32 toolchain under Linux - CROSSDEV = pic32- - # CROSSDEV = xc32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = xc32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip C32 toolchain under Linux - CROSSDEV = pic32- - # CROSSDEV = xc32- - # MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = xc32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPOPENL),y) - # microchipOpen toolchain under Linux - CROSSDEV = mypic32- - # MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = c32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_PINGUINOW),y) - # Penquino mips-elf toolchain under Windows - CROSSDEV = mips- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = mips-elf-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_PINGUINOL),y) - # Penquino mips-elf toolchain under Linux - CROSSDEV = mips-elf- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = mips-elf-debug.ld -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/mirtoo/ostest/Make.defs b/nuttx/configs/mirtoo/ostest/Make.defs index 7a087665b9..eb04d01962 100644 --- a/nuttx/configs/mirtoo/ostest/Make.defs +++ b/nuttx/configs/mirtoo/ostest/Make.defs @@ -35,79 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip C32 toolchain under Windows - CROSSDEV = pic32- - # CROSSDEV = xc32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = c32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip C32 toolchain under Windows - CROSSDEV = pic32- - # CROSSDEV = xc32- - WINTOOL = y - # MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = c32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip C32 toolchain under Linux - CROSSDEV = pic32- - # CROSSDEV = xc32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = xc32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip C32 toolchain under Linux - CROSSDEV = pic32- - # CROSSDEV = xc32- - # MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = xc32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPOPENL),y) - # microchipOpen toolchain under Linux - CROSSDEV = mypic32- - # MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = c32-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_PINGUINOW),y) - # Penquino mips-elf toolchain under Windows - CROSSDEV = mips- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = mips-elf-debug.ld -endif -ifeq ($(CONFIG_PIC32MX_PINGUINOL),y) - # Penquino mips-elf toolchain under Linux - CROSSDEV = mips-elf- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs - LDSCRIPT = mips-elf-debug.ld -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/nucleus2g/nsh/Make.defs b/nuttx/configs/nucleus2g/nsh/Make.defs index 7b82800bfd..7510cef3ed 100644 --- a/nuttx/configs/nucleus2g/nsh/Make.defs +++ b/nuttx/configs/nucleus2g/nsh/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/nucleus2g/ostest/Make.defs b/nuttx/configs/nucleus2g/ostest/Make.defs index b0ec211649..1c4ebf8a9c 100644 --- a/nuttx/configs/nucleus2g/ostest/Make.defs +++ b/nuttx/configs/nucleus2g/ostest/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/nucleus2g/usbserial/Make.defs b/nuttx/configs/nucleus2g/usbserial/Make.defs index 04e94eda90..8cd4b0cc4b 100644 --- a/nuttx/configs/nucleus2g/usbserial/Make.defs +++ b/nuttx/configs/nucleus2g/usbserial/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/nucleus2g/usbstorage/Make.defs b/nuttx/configs/nucleus2g/usbstorage/Make.defs index 3e15c52d04..659a5142e3 100644 --- a/nuttx/configs/nucleus2g/usbstorage/Make.defs +++ b/nuttx/configs/nucleus2g/usbstorage/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs index 91bd0e27cb..ce5508390a 100644 --- a/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ftpc/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs index c785dc7b7c..c882ce94fe 100644 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs index 119acc0f69..e1c96eb6be 100644 --- a/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nettest/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs index ea6ad5670b..3312b63cdd 100644 --- a/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nsh/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs index 67d74dcde1..5eb7bbbb76 100644 --- a/nuttx/configs/olimex-lpc1766stk/nx/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/nx/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs index 78618bddbe..f9b164deb5 100644 --- a/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/ostest/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs index 4f217561ff..b7f9c37fd1 100644 --- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs index e7095d9379..32d0530bd4 100644 --- a/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/thttpd/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - # CROSSDEV = arm-nuttx-eabi- - # ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs index 0ff4bb94af..8658c457af 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbserial/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs index c7f954ff9a..1d8990cb5c 100644 --- a/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs index 31f4023e6a..07bb91c09d 100644 --- a/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs +++ b/nuttx/configs/olimex-lpc1766stk/wlan/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_LPC17_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_LPC17_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_LPC17_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 - # EABI - CROSSDEV = arm-nuttx-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-stm32-p107/nsh/Make.defs b/nuttx/configs/olimex-stm32-p107/nsh/Make.defs index f88fb67312..98871a47de 100644 --- a/nuttx/configs/olimex-stm32-p107/nsh/Make.defs +++ b/nuttx/configs/olimex-stm32-p107/nsh/Make.defs @@ -35,49 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_DFU),y) - LDSCRIPT = ld.script.dfu -else - LDSCRIPT = ld.script -endif - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/olimex-stm32-p107/ostest/Make.defs b/nuttx/configs/olimex-stm32-p107/ostest/Make.defs index 2a1bc6d9cd..75f0ed8817 100644 --- a/nuttx/configs/olimex-stm32-p107/ostest/Make.defs +++ b/nuttx/configs/olimex-stm32-p107/ostest/Make.defs @@ -35,49 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_DFU),y) - LDSCRIPT = ld.script.dfu -else - LDSCRIPT = ld.script -endif - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs b/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs index 166378988e..1c709c1f85 100644 --- a/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs +++ b/nuttx/configs/pcblogic-pic32mx/nsh/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs b/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs index 834a8ed53e..ee8661d910 100644 --- a/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs +++ b/nuttx/configs/pcblogic-pic32mx/ostest/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/pic32-starterkit/nsh/Make.defs b/nuttx/configs/pic32-starterkit/nsh/Make.defs index 1063e57bec..7e4f5d43e0 100644 --- a/nuttx/configs/pic32-starterkit/nsh/Make.defs +++ b/nuttx/configs/pic32-starterkit/nsh/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/pic32-starterkit/nsh2/Make.defs b/nuttx/configs/pic32-starterkit/nsh2/Make.defs index 730ec22b6f..4d29bc904f 100644 --- a/nuttx/configs/pic32-starterkit/nsh2/Make.defs +++ b/nuttx/configs/pic32-starterkit/nsh2/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/pic32-starterkit/ostest/Make.defs b/nuttx/configs/pic32-starterkit/ostest/Make.defs index d5eb4fb7f0..942ec383fa 100644 --- a/nuttx/configs/pic32-starterkit/ostest/Make.defs +++ b/nuttx/configs/pic32-starterkit/ostest/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/pic32mx7mmb/nsh/Make.defs b/nuttx/configs/pic32mx7mmb/nsh/Make.defs index 249c359d4d..cf3bd8db2a 100644 --- a/nuttx/configs/pic32mx7mmb/nsh/Make.defs +++ b/nuttx/configs/pic32mx7mmb/nsh/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/pic32mx7mmb/ostest/Make.defs b/nuttx/configs/pic32mx7mmb/ostest/Make.defs index 4196872a7f..808f12193b 100644 --- a/nuttx/configs/pic32mx7mmb/ostest/Make.defs +++ b/nuttx/configs/pic32mx7mmb/ostest/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/sam3u-ek/knsh/Make.defs b/nuttx/configs/sam3u-ek/knsh/Make.defs index b6275f283f..f387da6006 100644 --- a/nuttx/configs/sam3u-ek/knsh/Make.defs +++ b/nuttx/configs/sam3u-ek/knsh/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_SAM3U_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_SAM3U_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_SAM3U_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_SAM3U_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/sam3u-ek/nsh/Make.defs b/nuttx/configs/sam3u-ek/nsh/Make.defs index f314f6765c..b4313cdec4 100644 --- a/nuttx/configs/sam3u-ek/nsh/Make.defs +++ b/nuttx/configs/sam3u-ek/nsh/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_SAM3U_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_SAM3U_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_SAM3U_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_SAM3U_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/sam3u-ek/nx/Make.defs b/nuttx/configs/sam3u-ek/nx/Make.defs index 10ef94ff3f..67b0191f4c 100644 --- a/nuttx/configs/sam3u-ek/nx/Make.defs +++ b/nuttx/configs/sam3u-ek/nx/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_SAM3U_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_SAM3U_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_SAM3U_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_SAM3U_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/sam3u-ek/ostest/Make.defs b/nuttx/configs/sam3u-ek/ostest/Make.defs index 167b9217bf..ff119f6cd0 100644 --- a/nuttx/configs/sam3u-ek/ostest/Make.defs +++ b/nuttx/configs/sam3u-ek/ostest/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_SAM3U_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_SAM3U_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_SAM3U_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_SAM3U_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/sam3u-ek/touchscreen/Make.defs b/nuttx/configs/sam3u-ek/touchscreen/Make.defs index a1f1e71514..749ffbbc30 100644 --- a/nuttx/configs/sam3u-ek/touchscreen/Make.defs +++ b/nuttx/configs/sam3u-ek/touchscreen/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_SAM3U_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_SAM3U_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_SAM3U_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_SAM3U_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/shenzhou/nsh/Make.defs b/nuttx/configs/shenzhou/nsh/Make.defs index ef2bf35fb0..3e7ef5db78 100644 --- a/nuttx/configs/shenzhou/nsh/Make.defs +++ b/nuttx/configs/shenzhou/nsh/Make.defs @@ -35,63 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs # Pick the linker script diff --git a/nuttx/configs/shenzhou/nxwm/Make.defs b/nuttx/configs/shenzhou/nxwm/Make.defs index 66e4945b12..c162ebdd1a 100644 --- a/nuttx/configs/shenzhou/nxwm/Make.defs +++ b/nuttx/configs/shenzhou/nxwm/Make.defs @@ -35,63 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs # Pick the linker script diff --git a/nuttx/configs/shenzhou/thttpd/Make.defs b/nuttx/configs/shenzhou/thttpd/Make.defs index 8773aee1b3..c8658035ba 100644 --- a/nuttx/configs/shenzhou/thttpd/Make.defs +++ b/nuttx/configs/shenzhou/thttpd/Make.defs @@ -35,63 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs # Pick the linker script diff --git a/nuttx/configs/stm3210e-eval/RIDE/Make.defs b/nuttx/configs/stm3210e-eval/RIDE/Make.defs index 33c95f4cf3..8a53198e22 100644 --- a/nuttx/configs/stm3210e-eval/RIDE/Make.defs +++ b/nuttx/configs/stm3210e-eval/RIDE/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/buttons/Make.defs b/nuttx/configs/stm3210e-eval/buttons/Make.defs index 0ff9bef0cd..0a14d2d944 100644 --- a/nuttx/configs/stm3210e-eval/buttons/Make.defs +++ b/nuttx/configs/stm3210e-eval/buttons/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/composite/Make.defs b/nuttx/configs/stm3210e-eval/composite/Make.defs index 5c22eb8e43..7af8b7593e 100644 --- a/nuttx/configs/stm3210e-eval/composite/Make.defs +++ b/nuttx/configs/stm3210e-eval/composite/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/nsh/Make.defs b/nuttx/configs/stm3210e-eval/nsh/Make.defs index 348c721d13..08c8415c0b 100644 --- a/nuttx/configs/stm3210e-eval/nsh/Make.defs +++ b/nuttx/configs/stm3210e-eval/nsh/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/nsh2/Make.defs b/nuttx/configs/stm3210e-eval/nsh2/Make.defs index 9cea646855..cd5caf8f58 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3210e-eval/nsh2/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/nx/Make.defs b/nuttx/configs/stm3210e-eval/nx/Make.defs index b4f210369f..c6c2db5b3b 100644 --- a/nuttx/configs/stm3210e-eval/nx/Make.defs +++ b/nuttx/configs/stm3210e-eval/nx/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/nxconsole/Make.defs b/nuttx/configs/stm3210e-eval/nxconsole/Make.defs index bb51b10f91..730545d3fb 100644 --- a/nuttx/configs/stm3210e-eval/nxconsole/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxconsole/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,44 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O1 -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O1 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/nxlines/Make.defs b/nuttx/configs/stm3210e-eval/nxlines/Make.defs index 9f1de2f93b..0ff741f416 100644 --- a/nuttx/configs/stm3210e-eval/nxlines/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxlines/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,44 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O1 -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O1 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/nxtext/Make.defs b/nuttx/configs/stm3210e-eval/nxtext/Make.defs index d977538864..9fdbf2ad91 100644 --- a/nuttx/configs/stm3210e-eval/nxtext/Make.defs +++ b/nuttx/configs/stm3210e-eval/nxtext/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,44 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O1 -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O1 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/ostest/Make.defs b/nuttx/configs/stm3210e-eval/ostest/Make.defs index ccb90fe273..258fd1a593 100644 --- a/nuttx/configs/stm3210e-eval/ostest/Make.defs +++ b/nuttx/configs/stm3210e-eval/ostest/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/pm/Make.defs b/nuttx/configs/stm3210e-eval/pm/Make.defs index b5e08c9a08..64706c8888 100644 --- a/nuttx/configs/stm3210e-eval/pm/Make.defs +++ b/nuttx/configs/stm3210e-eval/pm/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/usbserial/Make.defs b/nuttx/configs/stm3210e-eval/usbserial/Make.defs index 9219e6099e..3690b36952 100644 --- a/nuttx/configs/stm3210e-eval/usbserial/Make.defs +++ b/nuttx/configs/stm3210e-eval/usbserial/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3210e-eval/usbstorage/Make.defs b/nuttx/configs/stm3210e-eval/usbstorage/Make.defs index 2c9e2a9e1b..98843f3c50 100644 --- a/nuttx/configs/stm3210e-eval/usbstorage/Make.defs +++ b/nuttx/configs/stm3210e-eval/usbstorage/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs index 71cb52eea6..22bab8f55d 100644 --- a/nuttx/configs/stm3220g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3220g-eval/dhcpd/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3220g-eval/nettest/Make.defs b/nuttx/configs/stm3220g-eval/nettest/Make.defs index de62c90567..2a324e0ac9 100644 --- a/nuttx/configs/stm3220g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3220g-eval/nettest/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3220g-eval/nsh/Make.defs b/nuttx/configs/stm3220g-eval/nsh/Make.defs index fcb4bf93f7..1f5077cd75 100644 --- a/nuttx/configs/stm3220g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3220g-eval/nsh2/Make.defs b/nuttx/configs/stm3220g-eval/nsh2/Make.defs index af4359dd8b..39b6b5d66b 100644 --- a/nuttx/configs/stm3220g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3220g-eval/nsh2/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3220g-eval/nxwm/Make.defs b/nuttx/configs/stm3220g-eval/nxwm/Make.defs index bb46adff7c..11048e4c58 100644 --- a/nuttx/configs/stm3220g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3220g-eval/nxwm/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3220g-eval/ostest/Make.defs b/nuttx/configs/stm3220g-eval/ostest/Make.defs index 8e72558f94..4484f54519 100644 --- a/nuttx/configs/stm3220g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3220g-eval/ostest/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3220g-eval/telnetd/Make.defs b/nuttx/configs/stm3220g-eval/telnetd/Make.defs index c82a2715a2..d820898430 100644 --- a/nuttx/configs/stm3220g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3220g-eval/telnetd/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/dhcpd/Make.defs b/nuttx/configs/stm3240g-eval/dhcpd/Make.defs index 599ad69ec7..51075db663 100644 --- a/nuttx/configs/stm3240g-eval/dhcpd/Make.defs +++ b/nuttx/configs/stm3240g-eval/dhcpd/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/discover/Make.defs b/nuttx/configs/stm3240g-eval/discover/Make.defs index 37280e89b0..c1da1e5bfa 100644 --- a/nuttx/configs/stm3240g-eval/discover/Make.defs +++ b/nuttx/configs/stm3240g-eval/discover/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/nettest/Make.defs b/nuttx/configs/stm3240g-eval/nettest/Make.defs index b03eb2a3d4..6d7d099ead 100644 --- a/nuttx/configs/stm3240g-eval/nettest/Make.defs +++ b/nuttx/configs/stm3240g-eval/nettest/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/nsh/Make.defs b/nuttx/configs/stm3240g-eval/nsh/Make.defs index a1587e4828..38b5479d30 100644 --- a/nuttx/configs/stm3240g-eval/nsh/Make.defs +++ b/nuttx/configs/stm3240g-eval/nsh/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/nsh2/Make.defs b/nuttx/configs/stm3240g-eval/nsh2/Make.defs index 9a2f75e73d..368baf7eab 100644 --- a/nuttx/configs/stm3240g-eval/nsh2/Make.defs +++ b/nuttx/configs/stm3240g-eval/nsh2/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/nxconsole/Make.defs b/nuttx/configs/stm3240g-eval/nxconsole/Make.defs index c822180f56..8a4ec77097 100644 --- a/nuttx/configs/stm3240g-eval/nxconsole/Make.defs +++ b/nuttx/configs/stm3240g-eval/nxconsole/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/nxwm/Make.defs b/nuttx/configs/stm3240g-eval/nxwm/Make.defs index edb007bd61..60f8e223ed 100644 --- a/nuttx/configs/stm3240g-eval/nxwm/Make.defs +++ b/nuttx/configs/stm3240g-eval/nxwm/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/ostest/Make.defs b/nuttx/configs/stm3240g-eval/ostest/Make.defs index 19c1c22640..810a48baaf 100644 --- a/nuttx/configs/stm3240g-eval/ostest/Make.defs +++ b/nuttx/configs/stm3240g-eval/ostest/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/telnetd/Make.defs b/nuttx/configs/stm3240g-eval/telnetd/Make.defs index 325d0fd97e..11000a4f99 100644 --- a/nuttx/configs/stm3240g-eval/telnetd/Make.defs +++ b/nuttx/configs/stm3240g-eval/telnetd/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/webserver/Make.defs b/nuttx/configs/stm3240g-eval/webserver/Make.defs index d303a06fb0..cd13c24e98 100644 --- a/nuttx/configs/stm3240g-eval/webserver/Make.defs +++ b/nuttx/configs/stm3240g-eval/webserver/Make.defs @@ -34,71 +34,8 @@ ############################################################################ include ${TOPDIR}/.config - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs b/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs index 09e4b985b7..8c99420ade 100644 --- a/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs +++ b/nuttx/configs/stm3240g-eval/xmlrpc/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm32f100rc_generic/nsh/Make.defs b/nuttx/configs/stm32f100rc_generic/nsh/Make.defs index 76ab1751f8..9ba5b8f992 100644 --- a/nuttx/configs/stm32f100rc_generic/nsh/Make.defs +++ b/nuttx/configs/stm32f100rc_generic/nsh/Make.defs @@ -36,46 +36,10 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm32f100rc_generic/ostest/Make.defs b/nuttx/configs/stm32f100rc_generic/ostest/Make.defs index 2742e18cdf..b14abfb34e 100644 --- a/nuttx/configs/stm32f100rc_generic/ostest/Make.defs +++ b/nuttx/configs/stm32f100rc_generic/ostest/Make.defs @@ -36,46 +36,10 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh diff --git a/nuttx/configs/stm32f4discovery/cxxtest/Make.defs b/nuttx/configs/stm32f4discovery/cxxtest/Make.defs index 57254cc4af..60af5b155a 100644 --- a/nuttx/configs/stm32f4discovery/cxxtest/Make.defs +++ b/nuttx/configs/stm32f4discovery/cxxtest/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ diff --git a/nuttx/configs/stm32f4discovery/elf/Make.defs b/nuttx/configs/stm32f4discovery/elf/Make.defs index e65571c68a..463f6920d2 100644 --- a/nuttx/configs/stm32f4discovery/elf/Make.defs +++ b/nuttx/configs/stm32f4discovery/elf/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm32f4discovery/nsh/Make.defs b/nuttx/configs/stm32f4discovery/nsh/Make.defs index b3ccbbcc18..e5035cbdc7 100644 --- a/nuttx/configs/stm32f4discovery/nsh/Make.defs +++ b/nuttx/configs/stm32f4discovery/nsh/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm32f4discovery/nxlines/Make.defs b/nuttx/configs/stm32f4discovery/nxlines/Make.defs index b3d9337791..7d6d53469f 100644 --- a/nuttx/configs/stm32f4discovery/nxlines/Make.defs +++ b/nuttx/configs/stm32f4discovery/nxlines/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm32f4discovery/ostest/Make.defs b/nuttx/configs/stm32f4discovery/ostest/Make.defs index 4527a9b223..480529117c 100644 --- a/nuttx/configs/stm32f4discovery/ostest/Make.defs +++ b/nuttx/configs/stm32f4discovery/ostest/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/stm32f4discovery/pm/Make.defs b/nuttx/configs/stm32f4discovery/pm/Make.defs index e7276aa2ff..75a81aea6d 100644 --- a/nuttx/configs/stm32f4discovery/pm/Make.defs +++ b/nuttx/configs/stm32f4discovery/pm/Make.defs @@ -35,71 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs LDSCRIPT = ld.script diff --git a/nuttx/configs/sure-pic32mx/nsh/Make.defs b/nuttx/configs/sure-pic32mx/nsh/Make.defs index 4aaf906ed8..836ec0ac71 100644 --- a/nuttx/configs/sure-pic32mx/nsh/Make.defs +++ b/nuttx/configs/sure-pic32mx/nsh/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/sure-pic32mx/ostest/Make.defs b/nuttx/configs/sure-pic32mx/ostest/Make.defs index cc25177391..8dbc884b9b 100644 --- a/nuttx/configs/sure-pic32mx/ostest/Make.defs +++ b/nuttx/configs/sure-pic32mx/ostest/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/sure-pic32mx/usbnsh/Make.defs b/nuttx/configs/sure-pic32mx/usbnsh/Make.defs index fbb58949ba..791750fe68 100644 --- a/nuttx/configs/sure-pic32mx/usbnsh/Make.defs +++ b/nuttx/configs/sure-pic32mx/usbnsh/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/twr-k60n512/nsh/Make.defs b/nuttx/configs/twr-k60n512/nsh/Make.defs index bb4a3f941c..99ef12d478 100644 --- a/nuttx/configs/twr-k60n512/nsh/Make.defs +++ b/nuttx/configs/twr-k60n512/nsh/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_KINETIS_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls -endif -ifeq ($(CONFIG_KINETIS_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_KINETIS_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls -endif -ifeq ($(CONFIG_KINETIS_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/twr-k60n512/ostest/Make.defs b/nuttx/configs/twr-k60n512/ostest/Make.defs index cb7d962baa..efa53b08af 100644 --- a/nuttx/configs/twr-k60n512/ostest/Make.defs +++ b/nuttx/configs/twr-k60n512/ostest/Make.defs @@ -35,37 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_KINETIS_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls -endif -ifeq ($(CONFIG_KINETIS_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_KINETIS_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls -endif -ifeq ($(CONFIG_KINETIS_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/ubw32/nsh/Make.defs b/nuttx/configs/ubw32/nsh/Make.defs index 0f034825a9..e8c0fcbb37 100644 --- a/nuttx/configs/ubw32/nsh/Make.defs +++ b/nuttx/configs/ubw32/nsh/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/ubw32/ostest/Make.defs b/nuttx/configs/ubw32/ostest/Make.defs index 143ab7b9c9..dc4a358386 100644 --- a/nuttx/configs/ubw32/ostest/Make.defs +++ b/nuttx/configs/ubw32/ostest/Make.defs @@ -35,43 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y) - # Microchip toolchain under Windows - CROSSDEV = pic32- - WINTOOL = y -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- - MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif -ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y) - # Microchip toolchain under Linux - CROSSDEV = pic32- -# MAXOPTIMIZATION = -O2 - ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data - ARCHPICFLAGS = -fpic -membedded-pic - LDFLAGS += -nostartfiles -nodefaultlibs -endif +include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/nuttx/configs/vsn/nsh/Make.defs b/nuttx/configs/vsn/nsh/Make.defs index 98ef2d94c4..273a01dab8 100644 --- a/nuttx/configs/vsn/nsh/Make.defs +++ b/nuttx/configs/vsn/nsh/Make.defs @@ -35,8 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs ifeq ($(CONFIG_STM32_DFU),y) LDSCRIPT = ld.script.dfu @@ -44,41 +43,6 @@ else LDSCRIPT = ld.script endif -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_BUILDROOT),y) - # NuttX buildroot under Linux or Cygwin - # 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 ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/winlink.sh From 27ec2129d73f3144f8b6436a6a6b10937a3d7155 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 21 Nov 2012 19:54:44 +0000 Subject: [PATCH 151/206] /configs/stm32f4discovery/winbuild and configs/cloudctrl upated to use Mike's Toolchain.defs; Fix error introduced into tools/configure.sh git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5380 42af7a65-404d-4744-a932-0658087f49c3 --- apps/graphics/Makefile | 6 +- nuttx/ChangeLog | 7 +++ nuttx/arch/arm/src/armv7-m/Toolchain.defs | 10 ++++ nuttx/arch/mips/src/mips32/Toolchain.defs | 6 ++ nuttx/configs/cloudctrl/nsh/Make.defs | 58 +----------------- nuttx/configs/stm32f4discovery/src/Makefile | 60 ++++++++++--------- .../stm32f4discovery/winbuild/Make.defs | 44 +------------- .../stm32f4discovery/winbuild/setenv.bat | 8 ++- nuttx/tools/configure.sh | 6 +- 9 files changed, 68 insertions(+), 137 deletions(-) diff --git a/apps/graphics/Makefile b/apps/graphics/Makefile index 94d2ff5c0f..a5d67b676a 100644 --- a/apps/graphics/Makefile +++ b/apps/graphics/Makefile @@ -33,7 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration +-include $(TOPDIR)/.config # Sub-directories @@ -51,14 +51,14 @@ $(1)_$(2): $(Q) $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" endef -$(foreach SDIR, $(CNTXTDIRS), $(eval $(call SDIR_template,$(SDIR),context))) +# $(foreach SDIR, $(CNTXTDIRS), $(eval $(call SDIR_template,$(SDIR),context))) $(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),depend))) $(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),clean))) $(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),distclean))) nothing: -context: $(foreach SDIR, $(CNTXTDIRS), $(SDIR)_context) +context: # $(foreach SDIR, $(CNTXTDIRS), $(SDIR)_context) depend: $(foreach SDIR, $(SUBDIRS), $(SDIR)_depend) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 452dd35196..103c03de3e 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3659,4 +3659,11 @@ * configs/cloudctrl: Darcy Gong's CloudController board. This is a small network relay development board. Based on the Shenzhou IV development board design. It is based on the STM32F107VC MCU. + * Lots of build files: ARMv7-M and MIPS32 Make.defs now include a common + Toolchain.defs file that can be used to manage toolchains in a more + configurable way. Contributed by Mike Smith + * configs/stm32f4discovery/winbuild and configs/cloudctrl: Adapted to use + Mike's Toolchain.defs. + * tools/configure.sh: Adapted to handle paths and setenv.bat files correctly + for native Windows builds. diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs index ab77e3eb34..e39d7f4141 100644 --- a/nuttx/arch/arm/src/armv7-m/Toolchain.defs +++ b/nuttx/arch/arm/src/armv7-m/Toolchain.defs @@ -143,7 +143,9 @@ endif ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),ATOLLIC) CROSSDEV = arm-atollic-eabi- ARCROSSDEV = arm-atollic-eabi- +ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y +endif ifeq ($(CONFIG_ARCH_CORTEXM4),y) ifeq ($(CONFIG_ARCH_FPU),y) ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard @@ -190,7 +192,9 @@ endif ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDW) CROSSDEV = arm-none-eabi- ARCROSSDEV = arm-none-eabi- +ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y +endif ifeq ($(CONFIG_ARCH_CORTEXM4),y) ifeq ($(CONFIG_ARCH_FPU),y) ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard @@ -216,7 +220,9 @@ endif ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYW) CROSSDEV = arm-none-eabi- ARCROSSDEV = arm-none-eabi- +ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y +endif ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft endif @@ -225,7 +231,9 @@ endif ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),DEVKITARM) CROSSDEV = arm-eabi- ARCROSSDEV = arm-eabi- +ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y +endif ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft endif @@ -251,6 +259,8 @@ endif ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),RAISONANCE) CROSSDEV = arm-none-eabi- ARCROSSDEV = arm-none-eabi- +ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y +endif ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft endif diff --git a/nuttx/arch/mips/src/mips32/Toolchain.defs b/nuttx/arch/mips/src/mips32/Toolchain.defs index 9a39c5eda0..554e5f044f 100644 --- a/nuttx/arch/mips/src/mips32/Toolchain.defs +++ b/nuttx/arch/mips/src/mips32/Toolchain.defs @@ -131,7 +131,9 @@ endif ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPW) CROSSDEV = pic32- # CROSSDEV = xc32- +ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y +endif MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data ARCHPICFLAGS = -fpic -membedded-pic @@ -156,7 +158,9 @@ endif ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPW_LITE) CROSSDEV = pic32- # CROSSDEV = xc32- +ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y +endif # MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data ARCHPICFLAGS = -fpic -membedded-pic @@ -179,7 +183,9 @@ endif ifeq ($(CONFIG_MIPS32_TOOLCHAIN),PINGUINOW) CROSSDEV = mips- +ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y +endif MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL ARCHPICFLAGS = -fpic -membedded-pic diff --git a/nuttx/configs/cloudctrl/nsh/Make.defs b/nuttx/configs/cloudctrl/nsh/Make.defs index a33f8d3174..2b53029471 100644 --- a/nuttx/configs/cloudctrl/nsh/Make.defs +++ b/nuttx/configs/cloudctrl/nsh/Make.defs @@ -35,63 +35,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_CODESOURCERYL),y) - # CodeSourcery under Linux - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - WINTOOL = y - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -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 = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -Os -endif +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs # Pick the linker script diff --git a/nuttx/configs/stm32f4discovery/src/Makefile b/nuttx/configs/stm32f4discovery/src/Makefile index 82ea0d1dda..68419e5d0e 100644 --- a/nuttx/configs/stm32f4discovery/src/Makefile +++ b/nuttx/configs/stm32f4discovery/src/Makefile @@ -35,83 +35,87 @@ -include $(TOPDIR)/Make.defs -CFLAGS += -I$(TOPDIR)/sched +CFLAGS += -I$(TOPDIR)/sched -ASRCS = -AOBJS = $(ASRCS:.S=$(OBJEXT)) +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) -CSRCS = up_boot.c up_spi.c +CSRCS = up_boot.c up_spi.c ifeq ($(CONFIG_HAVE_CXX),y) -CSRCS += up_cxxinitialize.c +CSRCS += up_cxxinitialize.c endif ifeq ($(CONFIG_ARCH_LEDS),y) -CSRCS += up_autoleds.c +CSRCS += up_autoleds.c else -CSRCS += up_userleds.c +CSRCS += up_userleds.c endif ifeq ($(CONFIG_ARCH_BUTTONS),y) -CSRCS += up_buttons.c +CSRCS += up_buttons.c endif ifeq ($(CONFIG_STM32_OTGFS),y) -CSRCS += up_usb.c +CSRCS += up_usb.c endif ifeq ($(CONFIG_PWM),y) -CSRCS += up_pwm.c +CSRCS += up_pwm.c endif ifeq ($(CONFIG_QENCODER),y) -CSRCS += up_qencoder.c +CSRCS += up_qencoder.c endif ifeq ($(CONFIG_WATCHDOG),y) -CSRCS += up_watchdog.c +CSRCS += up_watchdog.c endif ifeq ($(CONFIG_NSH_ARCHINIT),y) -CSRCS += up_nsh.c +CSRCS += up_nsh.c endif ifeq ($(CONFIG_PM_CUSTOMINIT),y) -CSRCS += up_pm.c +CSRCS += up_pm.c endif ifeq ($(CONFIG_PM_BUTTONS),y) -CSRCS += up_pmbuttons.c +CSRCS += up_pmbuttons.c endif ifeq ($(CONFIG_IDLE_CUSTOM),y) -CSRCS += up_idle.c +CSRCS += up_idle.c endif ifeq ($(CONFIG_STM32_FSMC),y) -CSRCS += up_extmem.c +CSRCS += up_extmem.c ifeq ($(CONFIG_LCD_SSD1289),y) -CSRCS += up_ssd1289.c +CSRCS += up_ssd1289.c endif endif ifeq ($(CONFIG_LCD_UG2864AMBAG01),y) -CSRCS += up_ug2864ambag01.c +CSRCS += up_ug2864ambag01.c endif -COBJS = $(CSRCS:.c=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +SRCS = $(ASRCS) $(CSRCS) +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}" +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + CFLAGS += -I$(ARCH_SRCDIR)\chip -I$(ARCH_SRCDIR)\common -I$(ARCH_SRCDIR)\armv7-m else - CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m +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}" +else + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m +endif endif all: libboard$(LIBEXT) diff --git a/nuttx/configs/stm32f4discovery/winbuild/Make.defs b/nuttx/configs/stm32f4discovery/winbuild/Make.defs index 2d9e4f1e2a..5a99ad199f 100644 --- a/nuttx/configs/stm32f4discovery/winbuild/Make.defs +++ b/nuttx/configs/stm32f4discovery/winbuild/Make.defs @@ -35,52 +35,10 @@ include ${TOPDIR}\.config include ${TOPDIR}\tools\Config.mk - -# Setup for the selected toolchain - -ifeq ($(CONFIG_STM32_CODESOURCERYW),y) - # CodeSourcery under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_ATOLLIC_PRO),y) - # Atollic toolchain under Windows - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- -ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard -else - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -endif -ifeq ($(CONFIG_STM32_DEVKITARM),y) - # devkitARM under Windows - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif -ifeq ($(CONFIG_STM32_RAISONANCE),y) - # Raisonance RIDE7 under Windows - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif +include ${TOPDIR}\arch\arm\src\armv7-m\Toolchain.defs LDSCRIPT = ld.script -# Windows-native toolchains - ARCHINCLUDES = -I. -isystem $(TOPDIR)\include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)\include -isystem $(TOPDIR)\include\cxx ARCHSCRIPT = -T$(TOPDIR)\configs\$(CONFIG_ARCH_BOARD)\scripts\$(LDSCRIPT) diff --git a/nuttx/configs/stm32f4discovery/winbuild/setenv.bat b/nuttx/configs/stm32f4discovery/winbuild/setenv.bat index b4580f778d..22fa1e599b 100755 --- a/nuttx/configs/stm32f4discovery/winbuild/setenv.bat +++ b/nuttx/configs/stm32f4discovery/winbuild/setenv.bat @@ -32,9 +32,6 @@ rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE rem POSSIBILITY OF SUCH DAMAGE. -rem This script is not needed for setting the path because the full path -rem to the ZDI-II tools are used in Make.defs. - rem This is the location where I installed in the MinGW compiler. With rem this configuration, it is recommended that you do NOT install the rem MSYS tools; they conflict with the GNUWin32 tools. See @@ -42,6 +39,11 @@ rem http://www.mingw.org/ for further info. set PATH=C:\MinGW\bin;%PATH% +rem This is the location where I installed the CodeSourcey toolchain. See +rem http://www.mentor.com/embedded-software/codesourcery + +set PATH=C:\Program Files (x86)\CodeSourcery\Sourcery G++ Lite\bin;%PATH% + rem This is the location where I installed the GNUWin32 tools. See rem http://gnuwin32.sourceforge.net/. diff --git a/nuttx/tools/configure.sh b/nuttx/tools/configure.sh index 5bff899227..ffa997178e 100755 --- a/nuttx/tools/configure.sh +++ b/nuttx/tools/configure.sh @@ -181,8 +181,8 @@ fi # For checking the apps dir path, we need a POSIX version of the relative path. -posappdir=`echo "${appdir}" | sed -e "s/\\/\/g"` -winappdir=`echo "${appdir}" | sed -e "s/\//\\/g"` +posappdir=`echo "${appdir}" | sed -e 's/\\\\/\\//g'` +winappdir=`echo "${appdir}" | sed -e 's/\\//\\\\/g'` # If appsdir was provided (or discovered) then make sure that the apps/ # directory exists @@ -213,7 +213,7 @@ if [ "X${defappdir}" = "Xy" ]; then echo "" >> "${tmp_config}" echo "# Application configuration" >> "${tmp_config}" echo "" >> "${tmp_config}" - if [ "X${winnative)" = "Xy" ]; then + if [ "X${winnative}" = "Xy" ]; then echo "CONFIG_APPS_DIR=\"$winappdir\"" >> "${tmp_config}" else echo "CONFIG_APPS_DIR=\"$posappdir\"" >> "${tmp_config}" From cbf2eea7f0bc4fbdc3a78cbf4b193331b3cf2e73 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 21 Nov 2012 23:22:38 +0000 Subject: [PATCH 152/206] A few more fixes for ez80 Windows Native build (still not enough) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5381 42af7a65-404d-4744-a932-0658087f49c3 --- apps/interpreters/Makefile | 8 ++- nuttx/arch/z80/src/Makefile.zdsii | 54 +++++++++++-------- nuttx/binfmt/Makefile | 6 +-- .../configs/ez80f910200kitg/ostest/Make.defs | 34 +++++------- nuttx/configs/ez80f910200kitg/src/Makefile | 2 +- 5 files changed, 56 insertions(+), 48 deletions(-) diff --git a/apps/interpreters/Makefile b/apps/interpreters/Makefile index 08385433aa..867d45f996 100644 --- a/apps/interpreters/Makefile +++ b/apps/interpreters/Makefile @@ -33,7 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config # Current configuration +-include $(TOPDIR)/.config # Sub-directories containing interpreter runtime @@ -41,9 +41,15 @@ SUBDIRS = pcode ficl # Create the list of installed runtime modules (INSTALLED_DIRS) +ifeq ($(CONFIG_WINDOWS_NATIVE),y) +define ADD_DIRECTORY +INSTALLED_DIRS += ${shell if exist $1\Makefile (echo $1)} +endef +else define ADD_DIRECTORY INSTALLED_DIRS += ${shell if [ -r $1/Makefile ]; then echo "$1"; fi} endef +endif $(foreach DIR, $(SUBDIRS), $(eval $(call ADD_DIRECTORY,$(DIR)))) diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii index dccb48d461..30cb63b14f 100644 --- a/nuttx/arch/z80/src/Makefile.zdsii +++ b/nuttx/arch/z80/src/Makefile.zdsii @@ -1,5 +1,5 @@ ############################################################################ -# arch/z16/src/Makefile +# arch/z80/src/Makefile.zdsii # # Copyright (C) 2008, 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt @@ -33,13 +33,15 @@ # ############################################################################ +-include $(TOPDIR)\Make.defs + ############################################################################ # Tools SCHEDSRCDIR = $(TOPDIR)$(DELIM)sched ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src ifeq ($(CONFIG_WINDOWS_NATIVE),y) - USRINCLUDES = -usrinc:'.;$(SCHEDSRCDIR);$(ARCHSRCDIR);$(ARCHSRCDIR)\common' + USRINCLUDES = -usrinc:".;$(SCHEDSRCDIR);$(ARCHSRCDIR);$(ARCHSRCDIR)\common" else WSCHEDSRCDIR = ${shell cygpath -w $(SCHEDSRCDIR)} WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} @@ -102,32 +104,30 @@ board$(DELIM)libboard$(LIBEXT): nuttx.linkcmd: $(LINKCMDTEMPLATE) $(Q) cp -f $(LINKCMDTEMPLATE) nuttx.linkcmd ifeq ($(CONFIG_WINDOWS_NATIVE),y) - @echo "\"$(TOPDIR)/nuttx\"= \\" >>nuttx.linkcmd - @echo " \"$(ARCHSRCDIR)/$(HEAD_OBJ)\", \\" >>nuttx.linkcmd - $(Q) ( for lib in $(LINKLIBS); do \ - echo " \"$(TOPDIR)/lib/$${lib}\", \\" >>nuttx.linkcmd; \ - done ; ) - @echo " \"$(ARCHSRCDIR)/board/libboard$(LIBEXT)\", \\" >>nuttx.linkcmd + @echo "$(TOPDIR)\nuttx"= \>>nuttx.linkcmd + @echo "$(ARCHSRCDIR)\$(HEAD_OBJ)", \>>nuttx.linkcmd + $(Q) for %%G in ($(LINKLIBS)) do ( echo "$(TOPDIR)\lib\%%G", \>>nuttx.linkcmd; ) + @echo "$(ARCHSRCDIR)\board\libboard$(LIBEXT)", \>>nuttx.linkcmd ifeq ($(CONFIG_ARCH_CHIP_Z8F640X),y) - @echo " \"$(ZDSSTDLIBDIR)/chelprevaaD$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSSTDLIBDIR)/crtrevaaLDD$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSSTDLIBDIR)/fprevaaLDD$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSZILOGLIBDIR)/csiorevaaLDD$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSZILOGLIBDIR)/zsldevinitdummy$(LIBEXT)\"" >>nuttx.linkcmd + @echo "$(ZDSSTDLIBDIR)\chelprevaaD$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSSTDLIBDIR)\crtrevaaLDD$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSSTDLIBDIR)\fprevaaLDD$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSZILOGLIBDIR)\csiorevaaLDD$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSZILOGLIBDIR)\zsldevinitdummy$(LIBEXT)">>nuttx.linkcmd endif ifeq ($(CONFIG_ARCH_CHIP_Z8F642X),y) - @echo " \"$(ZDSSTDLIBDIR)/chelpD$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSSTDLIBDIR)/crtLDD$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSSTDLIBDIR)/fpdumyLD$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSZILOGLIBDIR)/csioLDD$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSZILOGLIBDIR)/zsldevinitdummy$(LIBEXT)\"" >>nuttx.linkcmd + @echo "$(ZDSSTDLIBDIR)\chelpD$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSSTDLIBDIR)\crtLDD$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSSTDLIBDIR)\fpdumyLD$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSZILOGLIBDIR)\csioLDD$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSZILOGLIBDIR)\zsldevinitdummy$(LIBEXT)">>nuttx.linkcmd endif ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y) - @echo " \"$(ZDSSTDLIBDIR)/chelp$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSSTDLIBDIR)/crt$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSSTDLIBDIR)/fplib$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSZILOGLIBDIR)/gpio$(LIBEXT)\", \\" >>nuttx.linkcmd - @echo " \"$(ZDSZILOGLIBDIR)/uartf91$(LIBEXT)\"" >>nuttx.linkcmd + @echo "$(ZDSSTDLIBDIR)\chelp$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSSTDLIBDIR)\crt$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSSTDLIBDIR)\fplib$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSZILOGLIBDIR)\gpio$(LIBEXT)", \>>nuttx.linkcmd + @echo "$(ZDSZILOGLIBDIR)\uartf91$(LIBEXT)">>nuttx.linkcmd endif else @echo "\"${shell cygpath -w "$(TOPDIR)/nuttx\"= \\" >>nuttx.linkcmd @@ -193,9 +193,13 @@ endif depend: .depend clean: +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + $(Q) if exist board$(DELIM)Makefile ( $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ) +else $(Q) if [ -e board$(DELIM)Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi +endif $(call DELFILE, nuttx.linkcmd) $(call DELFILE, *.asm) $(call DELFILE, *.tmp) @@ -204,9 +208,13 @@ clean: $(call CLEAN) distclean: clean +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + $(Q) if exist board$(DELIM)Makefile ( $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ) +else $(Q) if [ -e board$(DELIM)Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ fi +endif $(call DELFILE, Make.dep) $(call DELFILE, .depend) diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile index a59392fb05..317d4a422f 100644 --- a/nuttx/binfmt/Makefile +++ b/nuttx/binfmt/Makefile @@ -38,7 +38,7 @@ ifeq ($(WINTOOL),y) INCDIROPT = -w endif -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/sched} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)sched} # Basic BINFMT source files @@ -58,8 +58,8 @@ VPATH = SUBDIRS = DEPPATH = --dep-path . -include libnxflat/Make.defs -include libelf/Make.defs +include libnxflat$(DELIM)Make.defs +include libelf$(DELIM)Make.defs BINFMT_AOBJS = $(BINFMT_ASRCS:.S=$(OBJEXT)) BINFMT_COBJS = $(BINFMT_CSRCS:.c=$(OBJEXT)) diff --git a/nuttx/configs/ez80f910200kitg/ostest/Make.defs b/nuttx/configs/ez80f910200kitg/ostest/Make.defs index 54e377de7e..141a45e4ce 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/Make.defs +++ b/nuttx/configs/ez80f910200kitg/ostest/Make.defs @@ -39,30 +39,25 @@ include ${TOPDIR}/tools/Config.mk # These are the directories where the ZDS-II toolchain is installed ZDSVERSION := 5.1.1 -ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION) ifeq ($(CONFIG_WINDOWS_NATIVE),y) - ZDSBINDIR := $(ZDSINSTALLDIR)\bin - ZDSSTDINCDIR := $(ZDSINSTALLDIR)\include\std - ZDSZILOGINCDIR := $(ZDSINSTALLDIR)\include\zilog - ZDSSTDLIBDIR := $(ZDSINSTALLDIR)\lib\std - ZDSZILOGLIBDIR := $(ZDSINSTALLDIR)\lib\zilog - - # Escaped versions - - # ETOPDIR := ${shell echo "$(TOPDIR)" | sed -e "s/ /%%%%20/g"} - # EZDSSTDINCDIR := ${shell echo "$(ZDSSTDINCDIR)" | sed -e "s/ /%%%%20/g"} - # EZDSZILOGINCDIR := ${shell echo "$(ZDSZILOGINCDIR)" | sed -e "s/ /%%%%20/g"} + ZDSINSTALLDIR := C:/PROGRA~2/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION) + INSTALLDIR = ${shell echo $(ZDSINSTALLDIR)| sed -e "s/\//\\/g"} + ZDSBINDIR := $(INSTALLDIR)\bin + ZDSSTDINCDIR := $(INSTALLDIR)\include\std + ZDSZILOGINCDIR := $(INSTALLDIR)\include\zilog + ZDSSTDLIBDIR := $(INSTALLDIR)\lib\std + ZDSZILOGLIBDIR := $(INSTALLDIR)\lib\zilog # CFLAGs ARCHASMINCLUDES = -include:'$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR)' - # EARCHASMINCLUDES = -include:'$(ETOPDIR)\include;$(EZDSSTDINCDIR);$(EZDSZILOGINCDIR)' EARCHASMINCLUDES = -include:'$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR)' - ARCHSTDINCLUDES = -stdinc:'$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR)' - ARCHUSRINCLUDES = -usrinc:'.' + ARCHSTDINCLUDES = -stdinc:"$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR)" + ARCHUSRINCLUDES = -usrinc:. else WINTOOL := y + ZDSINSTALLDIR := C:/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_$(ZDSVERSION) INSTALLDIR = ${shell cygpath -u "$(ZDSINSTALLDIR)"} ZDSBINDIR := $(INSTALLDIR)/bin ZDSSTDINCDIR := $(INSTALLDIR)/include/std @@ -96,9 +91,9 @@ endif # Assembler definitions ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y) -ARCHCPU = eZ80F91 -ARCHCPUDEF = _EZ80F91 -ARCHFAMILY = _EZ80ACCLAIM! + ARCHCPU = eZ80F91 + ARCHCPUDEF = _EZ80F91 + ARCHFAMILY = _EZ80ACCLAIM! endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) @@ -111,8 +106,7 @@ ARCHASMCPUFLAGS = -cpu:$(ARCHCPU) -NOigcase ARCHASMLIST = -list -NOlistmac -name -pagelen:56 -pagewidth:80 -quiet ARCHASMWARNINGS = -warn ARCHASMDEFINES = -define:$(ARCHCPUDEF)=1 -define:$(ARCHFAMILYDEF)=1 -define:__ASSEMBLY__ -AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \ - $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION) +AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION) # Compiler definitions diff --git a/nuttx/configs/ez80f910200kitg/src/Makefile b/nuttx/configs/ez80f910200kitg/src/Makefile index 12c39824e5..f023e14185 100644 --- a/nuttx/configs/ez80f910200kitg/src/Makefile +++ b/nuttx/configs/ez80f910200kitg/src/Makefile @@ -39,7 +39,7 @@ SCHEDSRCDIR = $(TOPDIR)$(DELIM)sched ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src ifeq ($(CONFIG_WINDOWS_NATIVE),y) - USRINCLUDES = -usrinc:'.;$(SCHEDSRCDIR);$(ARCHSRCDIR);$(ARCHSRCDIR)\common' + USRINCLUDES = -usrinc:".;$(SCHEDSRCDIR);$(ARCHSRCDIR);$(ARCHSRCDIR)\common" else WSCHEDSRCDIR = ${shell cygpath -w $(SCHEDSRCDIR)} WARCHSRCDIR = ${shell cygpath -w $(ARCHSRCDIR)} From 00f711cdf193646c2068fb037b49213fe0d927c4 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 22 Nov 2012 14:44:38 +0000 Subject: [PATCH 153/206] Move some PHY initialization logic for Darcy git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5382 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/stm32/Kconfig | 10 + nuttx/arch/arm/src/stm32/stm32_eth.c | 11 + nuttx/arch/arm/src/stm32/stm32_eth.h | 35 +++- nuttx/configs/cloudctrl/src/Makefile | 3 + nuttx/configs/cloudctrl/src/up_boot.c | 14 -- nuttx/configs/cloudctrl/src/up_phyinit.c | 71 +++++++ nuttx/configs/ez80f910200kitg/README.txt | 4 + nuttx/tools/README.txt | 24 --- nuttx/tools/incdir.sh | 1 + nuttx/tools/prebuild.py | 256 ----------------------- 10 files changed, 129 insertions(+), 300 deletions(-) create mode 100644 nuttx/configs/cloudctrl/src/up_phyinit.c delete mode 100644 nuttx/tools/prebuild.py diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 4e369cb1a2..2807e1a47a 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -2058,6 +2058,16 @@ config STM32_PHYADDR ---help--- The 5-bit address of the PHY on the board. Default: 1 +config STM32_PHYINIT + bool "Board-specific PHY Initialization" + default n + ---help--- + Some boards require specialized initialization of the PHY before it can be used. + This may include such things as configuring GPIOs, resetting the PHY, etc. If + STM32_PHYINIT is defined in the configuration then the board specific logic must + provide stm32_phyinitialize(); The STM32 Ethernet driver will call this function + one time before it first uses the PHY. + config STM32_MII bool "Use MII interface" default n diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c index 3054142ce8..006f67142b 100644 --- a/nuttx/arch/arm/src/stm32/stm32_eth.c +++ b/nuttx/arch/arm/src/stm32/stm32_eth.c @@ -2594,6 +2594,17 @@ static int stm32_phyinit(FAR struct stm32_ethmac_s *priv) } up_mdelay(PHY_RESET_DELAY); + /* Perform any necessary, board-specific PHY initialization */ + +#ifdef CONFIG_STM32_PHYINIT + ret = stm32_phy_boardinitialize(0); + if (ret < 0) + { + ndbg("Failed to initialize the PHY: %d\n", ret); + return ret; + } +#endif + /* Special workaround for the Davicom DM9161 PHY is required. */ #ifdef CONFIG_PHY_DM9161 diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.h b/nuttx/arch/arm/src/stm32/stm32_eth.h index f0c14b5b1f..4501712b14 100644 --- a/nuttx/arch/arm/src/stm32/stm32_eth.h +++ b/nuttx/arch/arm/src/stm32/stm32_eth.h @@ -66,14 +66,13 @@ extern "C" { * Function: stm32_ethinitialize * * Description: - * Initialize the Ethernet driver for one interface. If the STM32 chip - * supports multiple Ethernet controllers, then board specific logic - * must implement up_netinitialize() and call this function to initialize - * the desired interfaces. + * Initialize the Ethernet driver for one interface. If the STM32 chip supports + * multiple Ethernet controllers, then board specific logic must implement + * up_netinitialize() and call this function to initialize the desired interfaces. * * Parameters: - * intf - In the case where there are multiple EMACs, this value - * identifies which EMAC is to be initialized. + * intf - In the case where there are multiple EMACs, this value identifies which + * EMAC is to be initialized. * * Returned Value: * OK on success; Negated errno on failure. @@ -86,6 +85,30 @@ extern "C" { EXTERN int stm32_ethinitialize(int intf); #endif +/************************************************************************************ + * Function: stm32_phy_boardinitialize + * + * Description: + * Some boards require specialized initialization of the PHY before it can be used. + * This may include such things as configuring GPIOs, resetting the PHY, etc. If + * CONFIG_STM32_PHYINIT is defined in the configuration then the board specific + * logic must provide stm32_phyinitialize(); The STM32 Ethernet driver will call + * this function one time before it first uses the PHY. + * + * Parameters: + * intf - Always zero for now. + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ************************************************************************************/ + +#ifdef CONFIG_STM32_PHYINIT +EXTERN int stm32_phy_boardinitialize(int intf); +#endif + #undef EXTERN #if defined(__cplusplus) } diff --git a/nuttx/configs/cloudctrl/src/Makefile b/nuttx/configs/cloudctrl/src/Makefile index 3e4773518a..37c944f4d4 100644 --- a/nuttx/configs/cloudctrl/src/Makefile +++ b/nuttx/configs/cloudctrl/src/Makefile @@ -85,6 +85,9 @@ ifeq ($(CONFIG_WATCHDOG),y) CSRCS += up_watchdog.c endif +ifeq ($(CONFIG_STM32_PHYINIT),y) +CSRCS += up_phyinit.c +endif COBJS = $(CSRCS:.c=$(OBJEXT)) diff --git a/nuttx/configs/cloudctrl/src/up_boot.c b/nuttx/configs/cloudctrl/src/up_boot.c index f536429716..fe0093d48d 100644 --- a/nuttx/configs/cloudctrl/src/up_boot.c +++ b/nuttx/configs/cloudctrl/src/up_boot.c @@ -56,16 +56,6 @@ * Private Functions ************************************************************************************/ -#ifdef CONFIG_PHY_DM9161 -static inline void stm232_configdm9161(void) -{ - stm32_configgpio(GPIO_DM9161_RET); - stm32_gpiowrite(GPIO_DM9161_RET, true); -} -# else -# define stm232_configdm9161() -#endif - /************************************************************************************ * Public Functions ************************************************************************************/ @@ -93,10 +83,6 @@ void stm32_boardinitialize(void) } #endif - /* Configure the DM9161 PHY reset pin and take it out of reset */ - - stm232_configdm9161(); - /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not * disabled, and 3) the weak function stm32_usbinitialize() has been brought * into the build. diff --git a/nuttx/configs/cloudctrl/src/up_phyinit.c b/nuttx/configs/cloudctrl/src/up_phyinit.c new file mode 100644 index 0000000000..114c9f07bf --- /dev/null +++ b/nuttx/configs/cloudctrl/src/up_phyinit.c @@ -0,0 +1,71 @@ +/************************************************************************************ + * configs/cloudctrl/src/up_phyinit.c + * arch/arm/src/board/up_phyinit.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 "stm32_gpio.h" +#include "stm32_eth.h" + +#include "cloudctrl-internal.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#if defined(CONFIG_PHY_DM9161) && defined(CONFIG_STM32_PHYINIT) +int stm32_phy_boardinitialize(int intf) +{ + /* Configure the DM9161 PHY reset pin and take it out of reset */ + + stm32_configgpio(GPIO_DM9161_RET); + stm32_gpiowrite(GPIO_DM9161_RET, true); + return 0; +} +#endif + diff --git a/nuttx/configs/ez80f910200kitg/README.txt b/nuttx/configs/ez80f910200kitg/README.txt index 2bac3c5db8..222a25db1f 100644 --- a/nuttx/configs/ez80f910200kitg/README.txt +++ b/nuttx/configs/ez80f910200kitg/README.txt @@ -107,4 +107,8 @@ available: CONFIG_APPS_DIR="..\apps" + NOTE: If you need to change the toolchain path used in Make.defs, + you will need to use the short 8.3 filenames to avoid spaces. On + my change C:\PROGRA~1\ is C:\PROGRA~2\ is C:\Program Files (x86)\ + Check out any README.txt files in these s. diff --git a/nuttx/tools/README.txt b/nuttx/tools/README.txt index efe8ad68f3..68b85dc4f3 100644 --- a/nuttx/tools/README.txt +++ b/nuttx/tools/README.txt @@ -403,30 +403,6 @@ unlink.sh script so that it uses the NTFS mklink command. But I have never tried that -prebuild.py ------------ - - This is a Python script contributed by Darcy Gong that automates many - build actions: - - Nuttx configure utils v 0.3 - usage: tools/prebuild.py [-abcdfhmr] [-b boardname] [-l number]\n'%(program_name) - -c, --clean : Will execute "make clean" command. - -d, --distclean : Will execute "make distclean" command. - -l, --cleanlevel : Will execute "make clean"(value of 1) or "make distclean"(value of 2) command. - -f, --fixcfg : The configuration correction nuttx.cfg defconfig configuration items. - -a, --auto : Equivalent parameters -d and -f. - -b, --boardname : The boardname configuration. - -r, --mkromfs : Make Romfs. - -m, --make : Make now. - -h, --help : Help Message. - - example:' - usage 1 : tools/prebuild.py -b fire-stm32v2/nsh - usage 2 : tools/prebuild.py -f -b fire-stm32v2/nsh - usage 3 : tools/prebuild.py -a -b fire-stm32v2/nsh - usage 4 : tools/prebuild.py -l 1 -f -b fire-stm32v2/nsh - mkimage.sh ---------- diff --git a/nuttx/tools/incdir.sh b/nuttx/tools/incdir.sh index 181fb1fa29..1e862aae12 100755 --- a/nuttx/tools/incdir.sh +++ b/nuttx/tools/incdir.sh @@ -65,6 +65,7 @@ while [ ! -z "$1" ]; do echo " Enable script debug" echo " -h" echo " Shows this help text and exits." + exit 0 ;; * ) break; diff --git a/nuttx/tools/prebuild.py b/nuttx/tools/prebuild.py deleted file mode 100644 index 34fed09b6b..0000000000 --- a/nuttx/tools/prebuild.py +++ /dev/null @@ -1,256 +0,0 @@ -#!/usr/bin/python - -import os -import sys,getopt -import commands -import ConfigParser -import socket -import fcntl -import struct -import re - -class Enum(object): - def __init__(self, *keys): - self.__dict__.update(zip(keys, range(len(keys)))) - -enum_parse_tag = Enum('tag','item') -enum_config = Enum('std','ext') - -def put_file_contents(filename,data=''): - if not os.path.isfile(filename): - return '' - try: - f = open(filename,'w') - contents = f.write(data) - f.close() - except IOError: - print 'file open or write err!' - -def fix_nuttx_cfg_value(key,val): - #if key == "CONFIG_NSH_IPADDR": - if re.search(r"_IPADDR$", key): - return '%s=%s\n'%(key,get_local_ip(50,2)) - #elif key == "CONFIG_NSH_DRIPADDR": - elif re.search(r"_DRIPADDR$", key): - return '%s=%s\n'%(key,get_local_ip(1,2)) - else: - return '%s=%s\n'%(key,val) - -def fix_nuttx_config(cfg,fix_cfgs): - result = '' - for line in cfg.readlines(): - line = line.strip() - if line.startswith('#'): - result += line+'\n' - continue - elif len(line) == 0: - result += '\n' - continue - elif line.count('=') > 0 : - #print line - it = line.find('=') - key = line[0:it].strip() - val = line[it + 1:].strip() - if fix_cfgs.has_key(key): - result += fix_nuttx_cfg_value(key, fix_cfgs.pop(key)) - else: - result += line+'\n' - else: - result += line+'\n' - #fix_cfgs = {} - #print fix_cfgs.viewitems() - if (len(fix_cfgs.keys())>0): - result += '\n\n####################################################\n\n' - for key in fix_cfgs.keys(): - result += fix_nuttx_cfg_value(key, fix_cfgs.pop(key)) - return result - - -def usage(): - program_name = sys.argv[0] - print 'Nuttx configure utils v 0.3\n' - print ' usage: %s [-abcdfhmr] [-b boardname] [-l number]\n'%(program_name) - print ' -c, --clean : Will execute "make clean" command.' - print ' -d, --distclean : Will execute "make distclean" command.' - print ' -l, --cleanlevel : Will execute "make clean"(value of 1) or "make distclean"(value of 2) command.' - print ' -f, --fixcfg : The configuration correction nuttx.cfg defconfig configuration items.' - print ' -a, --auto : Equivalent parameters -d and -f.' - print ' -b, --boardname : The boardname configuration.' - print ' -r, --mkromfs : Make Romfs.' - print ' -m, --make : Make now.' - print ' -h, --help : Help Message.' - print '\n example:' - print ' usage 1 : %s -b fire-stm32v2/nsh'%(program_name) - print ' usage 2 : %s -f -b fire-stm32v2/nsh'%(program_name) - print ' usage 3 : %s -a -b fire-stm32v2/nsh'%(program_name) - print ' usage 4 : %s -l 1 -f -b fire-stm32v2/nsh'%(program_name) - -def fix_config(boardname,fix_cfgs): - cfg_path = './configs/%s/defconfig'%boardname - if (os.path.isfile(cfg_path)): - try: - cfg = open(cfg_path, "r") - contents = fix_nuttx_config(cfg,fix_cfgs) - cfg.close() - #print contents - put_file_contents(cfg_path,contents) - except IOError: - print 'nuttx config open err!' - return '' - -def fix_root_config(fix_cfgs): - cfg_path = '.config' - if (os.path.isfile(cfg_path)): - try: - cfg = open(cfg_path, "r") - contents = fix_nuttx_config(cfg,fix_cfgs) - cfg.close() - #print contents - put_file_contents(cfg_path,contents) - except IOError: - print 'nuttx config open err!' - return '' - -def get_local_ipn(ifname): - s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) - ip = fcntl.ioctl(s.fileno(), - 0x8915, # SIOCGIFADDR - struct.pack('256s', ifname[:15]))[20:24] - return ip - -def get_local_ip(id=-1,mode=1): - ip = get_local_ipn('eth0') - if (id < 0): - id = ord(ip[3]) - ipr = ord(ip[0])<<24|ord(ip[1])<<16|ord(ip[2])<<8|(id & 0xFF) - if mode == 1 : - return socket.inet_ntoa(struct.pack('>L', ipr)) - if mode == 2 : - return "0x%x"%ipr - else: - return ipr - -def get_ip_address(ifname): - s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) - return socket.inet_ntoa(fcntl.ioctl( - s.fileno(), - 0x8915, # SIOCGIFADDR - struct.pack('256s', ifname[:15]) - )[20:24]) - -def config(cfg={}): - output = '' - fix_cfgs = {} - if cfg.clearlevel == 2: - print "make distclean apps_distclean" - output = commands.getoutput("make distclean apps_distclean") - elif cfg.clearlevel == 1: - print "make clean apps_clean" - output = commands.getoutput("make clean apps_clean") - - ini = ConfigParser.ConfigParser() - ini.optionxform = str - cfgf = 'nuttx_cfg.py' - #if not(os.path.isfile(cfgf)): - #fp = open(cfgf,'w') - #fp.write('# is nuttx config\n[info]\nlast=') - #fp.close() - #cfgf = open(cfgf,'rw') - ini.readfp(open(cfgf)) - lastfile = ini.get('info','last') - if (cmp(lastfile,cfg.boardname) != 0): - if ((cfg.boardname.strip() !='')): - lastfile = cfg.boardname - ini.set('info','last',lastfile) - ini.write(open(cfgf, "w")) - if cfg.usefix: - #print lastfile - if ini.has_section('defconfig'): - opts = ini.items('defconfig') - for item in opts: - fix_cfgs[item[0]] = item[1] - if ini.has_section(lastfile): - opts = ini.items(lastfile) - for item in opts: - fix_cfgs[item[0]] = item[1] - #print fix_cfgs - #fix_config(boardname,fix_cfgs) - - output = commands.getoutput("cd tools;./configure.sh %s;cd .."%lastfile) - print "tools/configure.sh %s"%lastfile - if cfg.usefix: - fix_root_config(fix_cfgs) - print "fix .config file" - if cfg.mkromfs: - if (os.path.isfile("./rcS.template")): - print "tools/mkromfsimg.sh ." - #output = commands.getoutput("tools/mkromfs.sh .") - os.system("tools/mkromfsimg.sh .") - bpath = "configs/%s/include"%(lastfile.split('/')[0]) - if (not os.path.exists(bpath)): - print "mkdir -p %s"%(bpath) - #commands.getoutput("mkdir -pv %s"%(bpath)) - os.system("mkdir -pv %s"%(bpath)) - if (not os.path.exists(bpath)): - print "[ERROR] no %s"%(bpath) - if (os.path.isfile("nsh_romfsimg.h")): - print "cp nsh_romfsimg.h %s/nsh_romfsimg.h"%(bpath) - #output = commands.getoutput("cp nsh_romfsimg.h include/arch/board/nsh_romfsimg.h") - os.system("cp nsh_romfsimg.h %s/nsh_romfsimg.h"%(bpath)) - if cfg.make: - os.system("sleep 3") - print "make" - os.system("make") - if '' != output.strip(): - print output - -class cfgobj(): - usefix = False - mkromfs = False - make = False - clearlevel = 0 - boardname = '' - -def main(): - try: - opts, args = getopt.getopt(sys.argv[1:], "dcb:hal:frm", - ["dictclean","clean","board=", "auto", "cleanlevel=", - "help","fixcfg","mkromfs","make"]) - except getopt.GetoptError: - # print help information and exit: - usage() - sys.exit(2) - #cfg = {"usefix":False,"mkromfs":False,"make":False,"clearlevel":0,"boardname":'' } - cfg = cfgobj() - for o, v in opts: - if o in ("-a","--auto"): - cfg.clearlevel = 2 - cfg.usefix = True - cfg.mkromfs = True - cfg.make = True - if o in ("-c","--clean"): - cfg.clearlevel = 1 - if o in ("-d","--distclean"): - cfg.clearlevel = 2 - if o in ("-l","--cleanlevel"): - if v == '1': - cfg.clearlevel = 1 - elif v == '2': - cfg.clearlevel = 2 - else: - cfg.clearlevel = 0 - if o in ("-b","--board"): - cfg.boardname = v - if o in ("-f","--fixcfg"): - cfg.usefix = True - if o in ("-r","--mkromfs"): - cfg.mkromfs = True - if o in ("-m","--make"): - cfg.make = True - if o in ("-h", "--help"): - usage() - sys.exit() - config(cfg) - -if __name__ == "__main__": - main() From 1cb21ddcd1fe9e45e3fec29fff11a747d740d4a1 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 22 Nov 2012 21:21:48 +0000 Subject: [PATCH 154/206] A few more Windows native build fixes for eZ80 git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5383 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/TODO | 28 +++---- nuttx/arch/z80/src/Makefile.zdsii | 2 +- nuttx/arch/z80/src/ez80/ez80f91_init.asm | 4 +- nuttx/binfmt/Makefile | 32 ++++---- .../configs/ez80f910200kitg/ostest/Make.defs | 19 ++--- nuttx/drivers/Kconfig | 76 ++++++++++--------- nuttx/drivers/Makefile | 14 ++-- nuttx/tools/incdir.bat | 35 ++++++++- 8 files changed, 121 insertions(+), 89 deletions(-) diff --git a/nuttx/TODO b/nuttx/TODO index 343212a313..28ffa1387f 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -32,7 +32,7 @@ nuttx/ (0) ARM/LPC43x (arch/arm/src/lpc43xx/) (3) ARM/STR71x (arch/arm/src/str71x/) (3) ARM/LM3S6918 (arch/arm/src/lm3s/) - (6) ARM/STM32 (arch/arm/src/stm32/) + (4) ARM/STM32 (arch/arm/src/stm32/) (3) AVR (arch/avr) (0) Intel x86 (arch/x86) (4) 8051 / MCS51 (arch/8051/) @@ -1349,11 +1349,6 @@ o ARM/LM3S6918 (arch/arm/src/lm3s/) o ARM/STM32 (arch/arm/src/stm32/) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - Title: NOR FLASH DRIVER - Description: NOR Flash driver with FTL layer to support a file system. - Status: Open - Priority: Low - Title: USBSERIAL ISSUES Description A USB device-side driver is in place but not well tested. At present, the apps/examples/usbserial test sometimes fails. The situation @@ -1376,11 +1371,6 @@ o ARM/STM32 (arch/arm/src/stm32/) Status: Open Priority: Medium-High - Title: FSMC EXTERNAL MEMORY UNTESTED - Description: FSMC external memory support is untested - Status: Open - Priority: Low - Title: DMA EXTENSIONS Description: DMA logic needs to be extended. DMA2, Channel 5, will not work because the DMA2 channels 4 & 5 share the same interrupt. @@ -1388,12 +1378,6 @@ o ARM/STM32 (arch/arm/src/stm32/) Priority: Low until someone needs DMA1, Channel 5 (ADC3, UART4_TX, TIM5_CH1, or TIM8_CH2). - Title: UNFINISHED DRIVERS - Description: The following drivers are incomplete: DAC. The following drivers - are untested: DMA on the F4, CAN. - Status: Open - Priority: Medium - Title: F4 SDIO MULTI-BLOCK TRANSFER FAILURES Description: If you use a large I/O buffer to access the file system, then the MMCSD driver will perform multiple block SD transfers. With DMA @@ -1417,6 +1401,16 @@ o ARM/STM32 (arch/arm/src/stm32/) Status: Open Priority: Low (I am not even sure if this is a problem yet). + Title: DMA FROM EXTERNAL, FSMC MEMORY + Description: I have seen a problem on F1 where all SDIO DMAs work exist for + write DMAs from FSMC memory (i.e., from FSMC memory to SDIO). + Read transfers work fine (SDIO to FSMC memory). The failure is + a data underrun error with zero bytes of data transferred. The + workaround for now is to use DMA buffers allocted from internal + SRAM. + Status: Open + Priority: Low + o AVR (arch/avr) ^^^^^^^^^^^^^^ diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii index 30cb63b14f..7a145017c4 100644 --- a/nuttx/arch/z80/src/Makefile.zdsii +++ b/nuttx/arch/z80/src/Makefile.zdsii @@ -106,7 +106,7 @@ nuttx.linkcmd: $(LINKCMDTEMPLATE) ifeq ($(CONFIG_WINDOWS_NATIVE),y) @echo "$(TOPDIR)\nuttx"= \>>nuttx.linkcmd @echo "$(ARCHSRCDIR)\$(HEAD_OBJ)", \>>nuttx.linkcmd - $(Q) for %%G in ($(LINKLIBS)) do ( echo "$(TOPDIR)\lib\%%G", \>>nuttx.linkcmd; ) + $(Q) for %%G in ($(LINKLIBS)) do ( echo "$(TOPDIR)\lib\%%G", \>>nuttx.linkcmd ) @echo "$(ARCHSRCDIR)\board\libboard$(LIBEXT)", \>>nuttx.linkcmd ifeq ($(CONFIG_ARCH_CHIP_Z8F640X),y) @echo "$(ZDSSTDLIBDIR)\chelprevaaD$(LIBEXT)", \>>nuttx.linkcmd diff --git a/nuttx/arch/z80/src/ez80/ez80f91_init.asm b/nuttx/arch/z80/src/ez80/ez80f91_init.asm index 17ef5f2952..fbce8502f0 100644 --- a/nuttx/arch/z80/src/ez80/ez80f91_init.asm +++ b/nuttx/arch/z80/src/ez80/ez80f91_init.asm @@ -37,7 +37,7 @@ ; Included Files ;************************************************************************** - include "ez80f91.inc" + include "ez80F91.inc" ;************************************************************************** ; Constants @@ -254,4 +254,4 @@ _ez80_oscfreqmult: ; dl _SYS_CLK_FREQ _ez80_sysclksrc: db _SYS_CLK_SRC - end \ No newline at end of file + end diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile index 317d4a422f..932a5ec13b 100644 --- a/nuttx/binfmt/Makefile +++ b/nuttx/binfmt/Makefile @@ -36,38 +36,38 @@ -include $(TOPDIR)/Make.defs ifeq ($(WINTOOL),y) -INCDIROPT = -w +INCDIROPT = -w endif -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)sched} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" "$(TOPDIR)$(DELIM)sched"} # Basic BINFMT source files -BINFMT_ASRCS = -BINFMT_CSRCS = binfmt_globals.c binfmt_register.c binfmt_unregister.c \ - binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_execmodule.c \ - binfmt_exec.c binfmt_dumpmodule.c +BINFMT_ASRCS = +BINFMT_CSRCS = binfmt_globals.c binfmt_register.c binfmt_unregister.c \ + binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_execmodule.c \ + binfmt_exec.c binfmt_dumpmodule.c # Symbol table source files -BINFMT_CSRCS += symtab_findbyname.c symtab_findbyvalue.c \ - symtab_findorderedbyname.c symtab_findorderedbyvalue.c +BINFMT_CSRCS += symtab_findbyname.c symtab_findbyvalue.c \ + symtab_findorderedbyname.c symtab_findorderedbyvalue.c # Add configured binary modules -VPATH = -SUBDIRS = -DEPPATH = --dep-path . +VPATH = +SUBDIRS = +DEPPATH = --dep-path . include libnxflat$(DELIM)Make.defs include libelf$(DELIM)Make.defs -BINFMT_AOBJS = $(BINFMT_ASRCS:.S=$(OBJEXT)) -BINFMT_COBJS = $(BINFMT_CSRCS:.c=$(OBJEXT)) +BINFMT_AOBJS = $(BINFMT_ASRCS:.S=$(OBJEXT)) +BINFMT_COBJS = $(BINFMT_CSRCS:.c=$(OBJEXT)) -BINFMT_SRCS = $(BINFMT_ASRCS) $(BINFMT_CSRCS) -BINFMT_OBJS = $(BINFMT_AOBJS) $(BINFMT_COBJS) +BINFMT_SRCS = $(BINFMT_ASRCS) $(BINFMT_CSRCS) +BINFMT_OBJS = $(BINFMT_AOBJS) $(BINFMT_COBJS) -BIN = libbinfmt$(LIBEXT) +BIN = libbinfmt$(LIBEXT) all: $(BIN) diff --git a/nuttx/configs/ez80f910200kitg/ostest/Make.defs b/nuttx/configs/ez80f910200kitg/ostest/Make.defs index 141a45e4ce..9f787ef1bb 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/Make.defs +++ b/nuttx/configs/ez80f910200kitg/ostest/Make.defs @@ -51,9 +51,9 @@ ifeq ($(CONFIG_WINDOWS_NATIVE),y) # CFLAGs - ARCHASMINCLUDES = -include:'$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR)' - EARCHASMINCLUDES = -include:'$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR)' - ARCHSTDINCLUDES = -stdinc:"$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR)" + ARCHASMINCLUDES = -include:$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR) + EARCHASMINCLUDES = -include:$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR) + ARCHSTDINCLUDES = -stdinc:$(TOPDIR)\include;$(ZDSSTDINCDIR);$(ZDSZILOGINCDIR) ARCHUSRINCLUDES = -usrinc:. else WINTOOL := y @@ -169,17 +169,18 @@ HEXEXT = .hex # object files into an archive ifeq ($(CONFIG_WINDOWS_NATIVE),y) + define PREPROCESS @echo CPP: $1->$2 $(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2 endef define COMPILE - $(Q) "$(CC)" $(CFLAGS) $1 + $(Q) "$(CC)" $(CFLAGS) ${shell echo $1 | sed -e "s/\//\\/g"} endef define ASSEMBLE - $(Q) "$(AS)" $(AFLAGS) $1 + $(Q) "$(AS)" $(AFLAGS) ${shell echo $1 | sed -e "s/\//\\/g"} endef define ARCHIVE @@ -195,20 +196,20 @@ define CLEAN $(Q) if exist *.lod (del /f /q *.lod) $(Q) if exist *.lst (del /f /q *.lst) endef + else + define PREPROCESS @echo "CPP: $1->$2" $(Q) "$(CPP)" $(CPPFLAGS) $1 -o $2 endef define COMPILE - @#echo "CC: $1" - $(Q) (wfile=`cygpath -w "$1"`; "$(CC)" $(CFLAGS) $$wfile) + $(Q) "$(CC)" $(CFLAGS) ${shell echo $1 | sed -e "s/\//\\/g"} endef define ASSEMBLE - @#echo "AS: $1" - $(Q) (wfile=`cygpath -w "$1"`; "$(AS)" $(AFLAGS) $$wfile) + $(Q) "$(AS)" $(AFLAGS) ${shell echo $1 | sed -e "s/\//\\/g"} endef define ARCHIVE diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig index 1d263ec145..8302d21b71 100644 --- a/nuttx/drivers/Kconfig +++ b/nuttx/drivers/Kconfig @@ -47,7 +47,8 @@ config CAN_EXTID bool "CAN extended IDs" default n ---help--- - Enables support for the 29-bit extended ID. Default Standard 11-bit IDs. + Enables support for the 29-bit extended ID. Default Standard 11-bit + IDs. config CAN_FIFOSIZE int "CAN driver I/O buffer size" @@ -83,10 +84,10 @@ config PWM_PULSECOUNT bool "PWM Pulse Count Support" default n ---help--- - Some hardware will support generation of a fixed number of pulses. This - might be used, for example to support a stepper motor. If the hardware - will support a fixed pulse count, then this configuration should be set to - enable the capability. + Some hardware will support generation of a fixed number of pulses. + This might be used, for example to support a stepper motor. If the + hardware will support a fixed pulse count, then this configuration + should be set to enable the capability. endif @@ -147,23 +148,25 @@ config SPI_OWNBUS bool "SPI single device" default n ---help--- - Set if there is only one active device on the SPI bus. No locking or SPI - configuration will be performed. It is not necessary for clients to lock, - re-configure, etc.. + Set if there is only one active device on the SPI bus. No locking or + SPI configuration will be performed. It is not necessary for clients to + lock, re-configure, etc.. config SPI_EXCHANGE bool "SPI exchange" default y ---help--- - Driver supports a single exchange method (vs a recvblock() and sndblock ()methods). + Driver supports a single exchange method (vs a recvblock() and + sndblock() methods). config SPI_CMDDATA bool "SPI CMD/DATA" default n ---help--- - Devices on the SPI bus require out-of-band support to distinguish command - transfers from data transfers. Such devices will often support either 9-bit - SPI (yech) or 8-bit SPI and a GPIO output that selects between command and data. + Devices on the SPI bus require out-of-band support to distinguish + command transfers from data transfers. Such devices will often support + either 9-bit SPI (yech) or 8-bit SPI and a GPIO output that selects + between command and data. endif @@ -173,35 +176,36 @@ menuconfig RTC ---help--- This selection enables configuration of a real time clock (RTCdriver. See include/nuttx/rtc.h for further watchdog timer driver information. - Most RTC drivers are MCU specific and may require other specific settings. + Most RTC drivers are MCU specific and may require other specific + settings. config RTC_DATETIME bool "Date/Time RTC Support" default n depends on RTC ---help--- - There are two general types of RTC: (1) A simple battery backed counter - that keeps the time when power is down, and (2) a full date / time RTC the - provides the date and time information, often in BCD format. If - RTC_DATETIME is selected, it specifies this second kind of RTC. In this - case, the RTC is used to "seed" the normal NuttX timer and the NuttX system - timer provides for higher resolution time. + There are two general types of RTC: (1) A simple battery backed + counter that keeps the time when power is down, and (2) a full + date / time RTC the provides the date and time information, often in + BCD format. If RTC_DATETIME is selected, it specifies this second kind + of RTC. In this case, the RTC is used to "seed" the normal NuttX timer + and the NuttX system timer provides for higher resolution time. config RTC_HIRES bool "Hi-Res RTC Support" default n depends on RTC && !RTC_DATETIME ---help--- - If RTC_DATETIME not selected, then the simple, battery backed counter is - used. There are two different implementations of such simple counters - based on the time resolution of the counter: The typical RTC keeps time - to resolution of 1 second, usually supporting a 32-bit time_t value. In - this case, the RTC is used to "seed" the normal NuttX timer and the NuttX - timer provides for higherresoution time. + If RTC_DATETIME not selected, then the simple, battery backed counter + is used. There are two different implementations of such simple + counters based on the time resolution of the counter: The typical RTC + keeps time to resolution of 1 second, usually supporting a 32-bit + time_t value. In this case, the RTC is used to "seed" the normal NuttX + timer and the NuttX timer provides for higherresoution time. - If RTC_HIRES is enabled in the NuttX configuration, then the RTC provides - higher resolution time and completely replaces the system timer for purpose - of date and time. + If RTC_HIRES is enabled in the NuttX configuration, then the RTC + provides higher resolution time and completely replaces the system + timer for purpose of date and time. config RTC_FREQUENCY int "Hi-Res RTC frequency" @@ -209,8 +213,8 @@ config RTC_FREQUENCY depends on RTC && !RTC_DATETIME && RTC_HIRES ---help--- If RTC_HIRES is defined, then the frequency of the high resolution RTC - must be provided. If RTC_HIRES is not defined, RTC_FREQUENCY is assumed - to be one Hz. + must be provided. If RTC_HIRES is not defined, RTC_FREQUENCY is + assumed to be one Hz. config RTC_ALARM bool "RTC Alarm Support" @@ -224,8 +228,9 @@ menuconfig WATCHDOG bool "Watchdog Timer Support" default n ---help--- - This selection enables building of the "upper-half" watchdog timer driver. - See include/nuttx/watchdog.h for further watchdog timer driver information. + This selection enables building of the "upper-half" watchdog timer + driver. See include/nuttx/watchdog.h for further watchdog timer driver + information. if WATCHDOG endif @@ -348,7 +353,8 @@ menuconfig POWER bool "Power Management Support" default n ---help--- - Enable building of power-related devices (battery monitors, chargers, etc). + Enable building of power-related devices (battery monitors, chargers, + etc). if POWER source drivers/power/Kconfig @@ -386,8 +392,8 @@ menuconfig SERIAL default y ---help--- Front-end character drivers for chip-specific UARTs. This provide - some TTY-like functionality and are commonly used (but not required for) - the NuttX system console. See also include/nuttx/serial/serial.h + some TTY-like functionality and are commonly used (but not required + for) the NuttX system console. See also include/nuttx/serial/serial.h if SERIAL source drivers/serial/Kconfig diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile index 575da606fe..13a5078236 100644 --- a/nuttx/drivers/Makefile +++ b/nuttx/drivers/Makefile @@ -85,15 +85,15 @@ ifeq ($(CONFIG_WATCHDOG),y) endif endif -AOBJS = $(ASRCS:.S=$(OBJEXT)) -COBJS = $(CSRCS:.c=$(OBJEXT)) +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) -BIN = libdrivers$(LIBEXT) +BIN = libdrivers$(LIBEXT) -all: $(BIN) +all: $(BIN) $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -101,7 +101,7 @@ $(AOBJS): %$(OBJEXT): %.S $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) -$(BIN): $(OBJS) +$(BIN): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) diff --git a/nuttx/tools/incdir.bat b/nuttx/tools/incdir.bat index a53afdd475..093c5bd2e3 100755 --- a/nuttx/tools/incdir.bat +++ b/nuttx/tools/incdir.bat @@ -55,16 +55,34 @@ if "%1"=="" ( echo ERROR: Missing compiler name goto :Usage ) + +set ccpath=%1 shift -rem Generate the compiler include path directives. Easy since only MinGW is -rem supported +set compiler= +for /F %%i in ("%ccpath%") do set compiler=%%~ni if "%1"=="" ( echo ERROR: Missing directory paths goto :Usage ) +rem Check for some well known, non-GCC Windows native tools that require +rem a special output format as well as special paths + +:GetFormat +set fmt=std +if "%compiler%"=="ez8cc" goto :SetZdsFormt +if "%compiler%"=="zneocc" goto :SetZdsFormt +if "%compiler%"=="ez80cc" goto :SetZdsFormt +goto :GeneratePaths + +:SetZdsFormt +set fmt=zds + +rem Generate the compiler include path directives. + +:GeneratePaths set response= :DirLoop @@ -78,11 +96,24 @@ if not exist %1 ( goto :Usage ) +if "%fmt%"=="zds" goto :GenerateZdsPath + if "%response"=="" ( set response=-I "%1" ) else ( set response=%response% -I "%1" ) +goto :EndOfDirLoop + +:GenerateZdsPath + +if "%response"=="" ( + set response=-usrinc:%1 +) else ( + set response=%response%;%1 +) + +:EndOfDirLoop shift goto :DirLoop From adb04f632f765f821cb327448339de8af1e49adb Mon Sep 17 00:00:00 2001 From: px4dev Date: Thu, 22 Nov 2012 20:35:08 -0800 Subject: [PATCH 155/206] Local changes to match upstream changes. --- .gitignore | 4 + apps/drivers/boards/px4fmu/px4fmu_init.c | 38 +- nuttx/configs/px4fmu/common/Make.defs | 8 +- nuttx/configs/px4fmu/nsh/defconfig | 5 + nuttx/configs/px4io/common/Make.defs | 8 +- nuttx/configs/px4io/io/defconfig | 3 + nuttx/configs/px4io/nsh/Make.defs | 3 - nuttx/configs/px4io/nsh/appconfig | 43 -- nuttx/configs/px4io/nsh/defconfig | 565 ----------------------- nuttx/configs/px4io/nsh/setenv.sh | 47 -- 10 files changed, 30 insertions(+), 694 deletions(-) delete mode 100644 nuttx/configs/px4io/nsh/Make.defs delete mode 100644 nuttx/configs/px4io/nsh/appconfig delete mode 100755 nuttx/configs/px4io/nsh/defconfig delete mode 100755 nuttx/configs/px4io/nsh/setenv.sh diff --git a/.gitignore b/.gitignore index ea416fae48..b91311ce85 100644 --- a/.gitignore +++ b/.gitignore @@ -40,3 +40,7 @@ nsh_romfsimg.h cscope.out .configX-e nuttx-export.zip +nuttx/tools/mkconfig.dSYM +nuttx/tools/mkversion.dSYM +nuttx/tools/mkdeps.dSYM +nuttx/tools/mkdeps diff --git a/apps/drivers/boards/px4fmu/px4fmu_init.c b/apps/drivers/boards/px4fmu/px4fmu_init.c index 57ffb77d34..bc047aa4f1 100644 --- a/apps/drivers/boards/px4fmu/px4fmu_init.c +++ b/apps/drivers/boards/px4fmu/px4fmu_init.c @@ -150,9 +150,7 @@ __EXPORT int nsh_archinitialize(void) int result; /* configure the high-resolution time/callout interface */ -#ifdef CONFIG_HRT_TIMER hrt_init(); -#endif /* configure CPU load estimation */ #ifdef CONFIG_SCHED_INSTRUMENTATION @@ -160,27 +158,21 @@ __EXPORT int nsh_archinitialize(void) #endif /* set up the serial DMA polling */ -#ifdef SERIAL_HAVE_DMA - { - static struct hrt_call serial_dma_call; - struct timespec ts; + static struct hrt_call serial_dma_call; + struct timespec ts; - /* - * Poll at 1ms intervals for received bytes that have not triggered - * a DMA event. - */ - ts.tv_sec = 0; - ts.tv_nsec = 1000000; + /* + * Poll at 1ms intervals for received bytes that have not triggered + * a DMA event. + */ + ts.tv_sec = 0; + ts.tv_nsec = 1000000; - hrt_call_every(&serial_dma_call, - ts_to_abstime(&ts), - ts_to_abstime(&ts), - (hrt_callout)stm32_serial_dma_poll, - NULL); - } -#endif - - message("\r\n"); + hrt_call_every(&serial_dma_call, + ts_to_abstime(&ts), + ts_to_abstime(&ts), + (hrt_callout)stm32_serial_dma_poll, + NULL); // initial LED state drv_led_start(); @@ -209,8 +201,7 @@ __EXPORT int nsh_archinitialize(void) message("[boot] Successfully initialized SPI port 1\r\n"); -#if defined(CONFIG_STM32_SPI3) - /* Get the SPI port */ + /* Get the SPI port for the microsd slot */ message("[boot] Initializing SPI port 3\n"); spi3 = up_spiinitialize(3); @@ -233,7 +224,6 @@ __EXPORT int nsh_archinitialize(void) } message("[boot] Successfully bound SPI port 3 to the MMCSD driver\n"); -#endif /* SPI3 */ #ifdef CONFIG_ADC int adc_state = adc_devinit(); diff --git a/nuttx/configs/px4fmu/common/Make.defs b/nuttx/configs/px4fmu/common/Make.defs index ff2e4c5fac..8ffe5223ba 100644 --- a/nuttx/configs/px4fmu/common/Make.defs +++ b/nuttx/configs/px4fmu/common/Make.defs @@ -39,12 +39,8 @@ # Make.defs in the per-config directories. # -# -# We only support building with the ARM bare-metal toolchain from -# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. -# - -CROSSDEV = arm-none-eabi- +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig index 9d61cae5ba..dc040d426f 100755 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -93,6 +93,9 @@ CONFIG_ARCH_MATH_H=y CONFIG_ARMV7M_CMNVECTOR=y +# default to a generic arm-none-eabi toolchain +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y + # # JTAG Enable settings (by default JTAG-DP and SW-DP are enabled): # @@ -767,6 +770,8 @@ CONFIG_FS_ROMFS=y # CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card. # Default is 20MHz, current setting 24 MHz # +CONFIG_MMCSD=y +CONFIG_MMCSD_SPI=y CONFIG_MMCSD_NSLOTS=1 CONFIG_MMCSD_READONLY=n CONFIG_MMCSD_SPICLOCK=24000000 diff --git a/nuttx/configs/px4io/common/Make.defs b/nuttx/configs/px4io/common/Make.defs index a3996a9ed3..a7cdd9d50a 100644 --- a/nuttx/configs/px4io/common/Make.defs +++ b/nuttx/configs/px4io/common/Make.defs @@ -39,12 +39,8 @@ # Make.defs in the per-config directories. # -# -# We only support building with the ARM bare-metal toolchain from -# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. -# - -CROSSDEV = arm-none-eabi- +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig index e90e7ce62b..a5a33d4fdd 100755 --- a/nuttx/configs/px4io/io/defconfig +++ b/nuttx/configs/px4io/io/defconfig @@ -89,6 +89,9 @@ CONFIG_ARCH_CALIBRATION=n CONFIG_ARCH_DMA=n CONFIG_ARMV7M_CMNVECTOR=y +# default to a generic arm-none-eabi toolchain +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y + # # JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): # diff --git a/nuttx/configs/px4io/nsh/Make.defs b/nuttx/configs/px4io/nsh/Make.defs deleted file mode 100644 index 87508e22ec..0000000000 --- a/nuttx/configs/px4io/nsh/Make.defs +++ /dev/null @@ -1,3 +0,0 @@ -include ${TOPDIR}/.config - -include $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/Make.defs diff --git a/nuttx/configs/px4io/nsh/appconfig b/nuttx/configs/px4io/nsh/appconfig deleted file mode 100644 index d5809a9391..0000000000 --- a/nuttx/configs/px4io/nsh/appconfig +++ /dev/null @@ -1,43 +0,0 @@ -############################################################################ -# configs/stm3210e-eval/nsh/appconfig -# -# 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. -# -############################################################################ - -# Path to example in apps/examples containing the user_start entry point - -CONFIGURED_APPS += examples/nsh - -CONFIGURED_APPS += system/readline -CONFIGURED_APPS += nshlib -CONFIGURED_APPS += reboot - diff --git a/nuttx/configs/px4io/nsh/defconfig b/nuttx/configs/px4io/nsh/defconfig deleted file mode 100755 index 6f4e208691..0000000000 --- a/nuttx/configs/px4io/nsh/defconfig +++ /dev/null @@ -1,565 +0,0 @@ -############################################################################ -# configs/px4io/nsh/defconfig -# -# 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. -# -############################################################################ -# -# architecture selection -# -# CONFIG_ARCH - identifies the arch subdirectory and, hence, the -# processor architecture. -# CONFIG_ARCH_family - for use in C code. This identifies the -# particular chip family that the architecture is implemented -# in. -# CONFIG_ARCH_architecture - for use in C code. This identifies the -# specific architecture within the chip familyl. -# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory -# CONFIG_ARCH_CHIP_name - For use in C code -# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, -# the board that supports the particular chip or SoC. -# CONFIG_ARCH_BOARD_name - for use in C code -# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) -# CONFIG_BOARD_LOOPSPERMSEC - for delay loops -# CONFIG_DRAM_SIZE - Describes the installed DRAM. -# CONFIG_DRAM_START - The start address of DRAM (physical) -# CONFIG_DRAM_END - Last address+1 of installed RAM -# CONFIG_ARCH_IRQPRIO - The ST32F100CB 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_STACKDUMP - Do stack dumps after assertions -# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. -# 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_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 calibrate -# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure -# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until -# the delay actually is 100 seconds. -# CONFIG_ARCH_DMA - Support DMA initialization -# -CONFIG_ARCH=arm -CONFIG_ARCH_ARM=y -CONFIG_ARCH_CORTEXM3=y -CONFIG_ARCH_CHIP=stm32 -CONFIG_ARCH_CHIP_STM32F100C8=y -CONFIG_ARCH_BOARD=px4io -CONFIG_ARCH_BOARD_PX4IO=y -CONFIG_BOARD_LOOPSPERMSEC=24000 -CONFIG_DRAM_SIZE=0x00002000 -CONFIG_DRAM_START=0x20000000 -CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE) -CONFIG_ARCH_IRQPRIO=y -CONFIG_ARCH_INTERRUPTSTACK=n -CONFIG_ARCH_STACKDUMP=y -CONFIG_ARCH_BOOTLOADER=n -CONFIG_ARCH_LEDS=y -CONFIG_ARCH_BUTTONS=y -CONFIG_ARCH_CALIBRATION=n -CONFIG_ARCH_DMA=n -CONFIG_ARMV7M_CMNVECTOR=y - -# -# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): -# -# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG -# -# JTAG Enable options: -# -# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) -# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) -# but without JNTRST. -# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled -# -CONFIG_STM32_DFU=n -CONFIG_STM32_JTAG_FULL_ENABLE=y -CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n -CONFIG_STM32_JTAG_SW_ENABLE=n - -# -# Individual subsystems can be enabled: -# AHB: -CONFIG_STM32_DMA1=n -CONFIG_STM32_DMA2=n -CONFIG_STM32_CRC=n -# APB1: -# Timers 2,3 and 4 are owned by the PWM driver -CONFIG_STM32_TIM2=n -CONFIG_STM32_TIM3=n -CONFIG_STM32_TIM4=n -CONFIG_STM32_TIM5=n -CONFIG_STM32_TIM6=n -CONFIG_STM32_TIM7=n -CONFIG_STM32_WWDG=n -CONFIG_STM32_SPI2=n -CONFIG_STM32_USART2=y -CONFIG_STM32_USART3=y -CONFIG_STM32_I2C1=y -CONFIG_STM32_I2C2=n -CONFIG_STM32_BKP=n -CONFIG_STM32_PWR=n -CONFIG_STM32_DAC=n -# APB2: -CONFIG_STM32_ADC1=y -CONFIG_STM32_ADC2=n -# TIM1 is owned by the HRT -CONFIG_STM32_TIM1=n -CONFIG_STM32_SPI1=n -CONFIG_STM32_TIM8=n -CONFIG_STM32_USART1=y -CONFIG_STM32_ADC3=n - -# -# Timer and I2C devices may need to the following to force power to be applied: -# -#CONFIG_STM32_FORCEPOWER=y - -# -# STM32F100 specific serial device driver settings -# -# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the -# console and ttys0 (default is the USART1). -# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received. -# This specific the size of the receive buffer -# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before -# being sent. This specific the size of the transmit buffer -# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be -# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8. -# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity -# CONFIG_USARTn_2STOP - Two stop bits -# -CONFIG_USART1_SERIAL_CONSOLE=y -CONFIG_USART2_SERIAL_CONSOLE=n -CONFIG_USART3_SERIAL_CONSOLE=n - -CONFIG_USART1_TXBUFSIZE=64 -CONFIG_USART2_TXBUFSIZE=64 -CONFIG_USART3_TXBUFSIZE=64 - -CONFIG_USART1_RXBUFSIZE=64 -CONFIG_USART2_RXBUFSIZE=64 -CONFIG_USART3_RXBUFSIZE=64 - -CONFIG_USART1_BAUD=57600 -CONFIG_USART2_BAUD=115200 -CONFIG_USART3_BAUD=115200 - -CONFIG_USART1_BITS=8 -CONFIG_USART2_BITS=8 -CONFIG_USART3_BITS=8 - -CONFIG_USART1_PARITY=0 -CONFIG_USART2_PARITY=0 -CONFIG_USART3_PARITY=0 - -CONFIG_USART1_2STOP=0 -CONFIG_USART2_2STOP=0 -CONFIG_USART3_2STOP=0 - -# -# PX4IO specific driver settings -# -# CONFIG_HRT_TIMER -# Enables the high-resolution timer. The board definition must -# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/ -# compare channels to be used. -# CONFIG_HRT_PPM -# Enables R/C PPM input using the HRT. The board definition must -# set HRT_PPM_CHANNEL to the timer capture/compare channel to be -# used, and define GPIO_PPM_IN to configure the appropriate timer -# GPIO. -# CONFIG_PWM_SERVO -# Enables the PWM servo driver. The driver configuration must be -# supplied by the board support at initialisation time. -# Note that USART2 must be disabled on the PX4 board for this to -# be available. -# -# -CONFIG_HRT_TIMER=y -CONFIG_HRT_PPM=y -CONFIG_PWM_SERVO=y - -# -# General build options -# -# CONFIG_RRLOAD_BINARY - make the rrload binary format used with -# BSPs from www.ridgerun.com using the tools/mkimage.sh script -# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_RAW_BINARY - make a raw binary format file used with many -# different loaders using the GNU objcopy program. This option -# should not be selected if you are not using the GNU toolchain. -# CONFIG_HAVE_LIBM - toolchain supports libm.a -# -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=n -CONFIG_MOTOROLA_SREC=n -CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n - -# -# General OS setup -# -# CONFIG_APPS_DIR - Identifies the relative path to the directory -# that builds the application to link with NuttX. Default: ../apps -# CONFIG_DEBUG - enables built-in debug options -# CONFIG_DEBUG_VERBOSE - enables verbose debug output -# CONFIG_DEBUG_SYMBOLS - build without optimization and with -# debug symbols (needed for use with a debugger). -# CONFIG_HAVE_CXX - Enable support for C++ -# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support -# for initialization of static C++ instances for this architecture -# and for the selected toolchain (via up_cxxinitialize()). -# CONFIG_MM_REGIONS - If the architecture includes multiple -# regions of memory to allocate from, this specifies the -# number of memory regions that the memory manager must -# handle and enables the API mm_addregion(start, end); -# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot -# time console output -# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz -# or MSEC_PER_TICK=10. This setting may be defined to -# inform NuttX that the processor hardware is providing -# system timer interrupts at some interrupt interval other -# than 10 msec. -# CONFIG_RR_INTERVAL - The round robin timeslice will be set -# this number of milliseconds; Round robin scheduling can -# be disabled by setting this value to zero. -# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in -# scheduler to monitor system performance -# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a -# task name to save in the TCB. Useful if scheduler -# instrumentation is selected. Set to zero to disable. -# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - -# Used to initialize the internal time logic. -# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. -# You would only need this if you are concerned about accurate -# time conversions in the past or in the distant future. -# CONFIG_JULIAN_TIME - Enables Julian time conversions. You -# would only need this if you are concerned about accurate -# time conversion in the distand past. You must also define -# CONFIG_GREGORIAN_TIME in order to use Julian time. -# CONFIG_DEV_CONSOLE - Set if architecture-specific logic -# provides /dev/console. Enables stdout, stderr, stdin. -# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console -# driver (minimul support) -# CONFIG_MUTEX_TYPES: Set to enable support for recursive and -# errorcheck mutexes. Enables pthread_mutexattr_settype(). -# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority -# inheritance on mutexes and semaphores. -# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority -# inheritance is enabled. It defines the maximum number of -# different threads (minus one) that can take counts on a -# semaphore with priority inheritance support. This may be -# set to zero if priority inheritance is disabled OR if you -# are only using semaphores as mutexes (only one holder) OR -# if no more than two threads participate using a counting -# semaphore. -# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, -# then this setting is the maximum number of higher priority -# threads (minus 1) than can be waiting for another thread -# to release a count on a semaphore. This value may be set -# to zero if no more than one thread is expected to wait for -# a semaphore. -# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors -# by task_create() when a new task is started. If set, all -# files/drivers will appear to be closed in the new task. -# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first -# three file descriptors (stdin, stdout, stderr) by task_create() -# when a new task is started. If set, all files/drivers will -# appear to be closed in the new task except for stdin, stdout, -# and stderr. -# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket -# desciptors by task_create() when a new task is started. If -# set, all sockets will appear to be closed in the new task. -# CONFIG_NXFLAT. Enable support for the NXFLAT binary format. -# This format will support execution of NuttX binaries located -# in a ROMFS filesystem (see examples/nxflat). -# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to -# handle delayed processing from interrupt handlers. This feature -# is required for some drivers but, if there are not complaints, -# can be safely disabled. The worker thread also performs -# garbage collection -- completing any delayed memory deallocations -# from interrupt handlers. If the worker thread is disabled, -# then that clean will be performed by the IDLE thread instead -# (which runs at the lowest of priority and may not be appropriate -# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE -# is enabled, then the following options can also be used: -# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker -# thread. Default: 50 -# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for -# work in units of microseconds. Default: 50*1000 (50 MS). -# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker -# thread. Default: CONFIG_IDLETHREAD_STACKSIZE. -# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up -# the worker thread. Default: 4 -# -#CONFIG_APPS_DIR= -CONFIG_DEBUG=n -CONFIG_DEBUG_VERBOSE=n -CONFIG_DEBUG_SYMBOLS=y -CONFIG_HAVE_CXX=n -CONFIG_HAVE_CXXINITIALIZE=n -CONFIG_MM_REGIONS=1 -CONFIG_MM_SMALL=y -CONFIG_ARCH_LOWPUTC=y -CONFIG_RR_INTERVAL=200 -CONFIG_SCHED_INSTRUMENTATION=n -CONFIG_TASK_NAME_SIZE=0 -CONFIG_START_YEAR=2009 -CONFIG_START_MONTH=9 -CONFIG_START_DAY=21 -CONFIG_GREGORIAN_TIME=n -CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=n -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=y -CONFIG_SDCLONE_DISABLE=y -CONFIG_NXFLAT=n -CONFIG_SCHED_WORKQUEUE=n -CONFIG_SCHED_WORKPRIORITY=50 -CONFIG_SCHED_WORKPERIOD=(50*1000) -CONFIG_SCHED_WORKSTACKSIZE=512 -CONFIG_SIG_SIGWORK=4 - -# -# The following can be used to disable categories of -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=y -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=y -CONFIG_DISABLE_MOUNTPOINT=y -CONFIG_DISABLE_ENVIRON=y -CONFIG_DISABLE_POLL=y - -# -# Misc libc settings -# -# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a -# little smaller if we do not support fieldwidthes -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve system performance -# -CONFIG_ARCH_MEMCPY=n -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n - -# -# Sizes of configurable things (0 disables) -# -# CONFIG_MAX_TASKS - The maximum number of simultaneously -# active tasks. This value must be a power of two. -# CONFIG_MAX_TASK_ARGS - This controls the maximum number of -# of parameters that a task may receive (i.e., maxmum value -# of 'argc') -# CONFIG_NPTHREAD_KEYS - The number of items of thread- -# specific data that can be retained -# CONFIG_NFILE_DESCRIPTORS - The maximum number of file -# descriptors (one for each open) -# CONFIG_NFILE_STREAMS - The maximum number of streams that -# can be fopen'ed -# CONFIG_NAME_MAX - The maximum size of a file name. -# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate -# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) -# CONFIG_NUNGET_CHARS - Number of characters that can be -# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) -# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message -# structures. The system manages a pool of preallocated -# message structures to minimize dynamic allocations -# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with -# a fixed payload size given by this settin (does not include -# other message structure overhead. -# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that -# can be passed to a watchdog handler -# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog -# structures. The system manages a pool of preallocated -# watchdog structures to minimize dynamic allocations -# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX -# timer structures. The system manages a pool of preallocated -# timer structures to minimize dynamic allocations. Set to -# zero for all dynamic allocations. -# -CONFIG_MAX_TASKS=4 -CONFIG_MAX_TASK_ARGS=4 -CONFIG_NPTHREAD_KEYS=2 -CONFIG_NFILE_DESCRIPTORS=6 -CONFIG_NFILE_STREAMS=4 -CONFIG_NAME_MAX=32 -CONFIG_STDIO_BUFFER_SIZE=64 -CONFIG_NUNGET_CHARS=2 -CONFIG_PREALLOC_MQ_MSGS=1 -CONFIG_MQ_MAXMSGSIZE=32 -CONFIG_MAX_WDOGPARMS=2 -CONFIG_PREALLOC_WDOGS=3 -CONFIG_PREALLOC_TIMERS=1 - - -# -# Settings for apps/nshlib -# -# CONFIG_NSH_BUILTIN_APPS - Support external registered, -# "named" applications that can be executed from the NSH -# command line (see apps/README.txt for more information). -# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer -# CONFIG_NSH_STRERROR - Use strerror(errno) -# CONFIG_NSH_LINELEN - Maximum length of one command line -# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi -# CONFIG_NSH_DISABLESCRIPT - Disable scripting support -# CONFIG_NSH_DISABLEBG - Disable background commands -# CONFIG_NSH_ROMFSETC - Use startup script in /etc -# CONFIG_NSH_CONSOLE - Use serial console front end -# CONFIG_NSH_TELNET - Use telnetd console front end -# CONFIG_NSH_ARCHINIT - Platform provides architecture -# specific initialization (nsh_archinitialize()). -# -# If CONFIG_NSH_TELNET is selected: -# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size -# CONFIG_NSH_DHCPC - Obtain address using DHCP -# CONFIG_NSH_IPADDR - Provides static IP address -# CONFIG_NSH_DRIPADDR - Provides static router IP address -# CONFIG_NSH_NETMASK - Provides static network mask -# CONFIG_NSH_NOMAC - Use a bogus MAC address -# -# If CONFIG_NSH_ROMFSETC is selected: -# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint -# CONFIG_NSH_INITSCRIPT - Relative path to init script -# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor -# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size -# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor -# CONFIG_NSH_FATSECTSIZE - FAT FS sector size -# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors -# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint -# -CONFIG_NSH_BUILTIN_APPS=y -CONFIG_NSH_FILEIOSIZE=64 -CONFIG_NSH_STRERROR=n -CONFIG_NSH_LINELEN=64 -CONFIG_NSH_NESTDEPTH=1 -CONFIG_NSH_DISABLESCRIPT=y -CONFIG_NSH_DISABLEBG=n -CONFIG_NSH_ROMFSETC=n -CONFIG_NSH_CONSOLE=y -CONFIG_NSH_TELNET=n -CONFIG_NSH_ARCHINIT=y -CONFIG_NSH_IOBUFFER_SIZE=256 -#CONFIG_NSH_STACKSIZE=1024 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=n -CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) -CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) -CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0) -CONFIG_NSH_ROMFSMOUNTPT="/etc" -CONFIG_NSH_INITSCRIPT="init.d/rcS" -CONFIG_NSH_ROMFSDEVNO=0 -CONFIG_NSH_ROMFSSECTSIZE=64 -CONFIG_NSH_FATDEVNO=1 -CONFIG_NSH_FATSECTSIZE=512 -CONFIG_NSH_FATNSECTORS=1024 -CONFIG_NSH_FATMOUNTPT=/tmp - -# -# Architecture-specific NSH options -# -CONFIG_NSH_MMCSDSPIPORTNO=0 -CONFIG_NSH_MMCSDSLOTNO=0 -CONFIG_NSH_MMCSDMINOR=0 - -# -# Stack and heap information -# -# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP -# operation from FLASH but must copy initialized .data sections to RAM. -# (should also be =n for the STM3210E-EVAL which always runs from flash) -# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH -# but copy themselves entirely into RAM for better performance. -# CONFIG_CUSTOM_STACK - The up_ implementation will handle -# all stack operations outside of the nuttx model. -# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only) -# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. -# This is the thread that (1) performs the inital boot of the system up -# to the point where user_start() is spawned, and (2) there after is the -# IDLE thread that executes only when there is no other thread ready to -# run. -# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate -# for the main user thread that begins at the user_start() entry point. -# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size -# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size -# CONFIG_HEAP_BASE - The beginning of the heap -# CONFIG_HEAP_SIZE - The size of the heap -# -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_STACK_POINTER= -CONFIG_IDLETHREAD_STACKSIZE=800 -CONFIG_USERMAIN_STACKSIZE=1024 -CONFIG_PTHREAD_STACK_MIN=256 -CONFIG_PTHREAD_STACK_DEFAULT=512 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= diff --git a/nuttx/configs/px4io/nsh/setenv.sh b/nuttx/configs/px4io/nsh/setenv.sh deleted file mode 100755 index d836851921..0000000000 --- a/nuttx/configs/px4io/nsh/setenv.sh +++ /dev/null @@ -1,47 +0,0 @@ -#!/bin/bash -# configs/stm3210e-eval/dfu/setenv.sh -# -# 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. -# - -if [ "$(basename $0)" = "setenv.sh" ] ; 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` -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" - -echo "PATH : ${PATH}" From c184d7baeb2176d424d8a520801554dbfcd7b8f3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 24 Nov 2012 19:37:51 +0100 Subject: [PATCH 156/206] Enabled aux manual control channels --- apps/sensors/sensor_params.c | 2 +- apps/sensors/sensors.cpp | 51 +++++++++++++++++++++++++++++++----- 2 files changed, 46 insertions(+), 7 deletions(-) diff --git a/apps/sensors/sensor_params.c b/apps/sensors/sensor_params.c index cc74ae705d..c83d6358e0 100644 --- a/apps/sensors/sensor_params.c +++ b/apps/sensors/sensor_params.c @@ -136,5 +136,5 @@ PARAM_DEFINE_INT32(RC_MAP_AUX3, 8); PARAM_DEFINE_FLOAT(RC_SCALE_ROLL, 0.4f); PARAM_DEFINE_FLOAT(RC_SCALE_PITCH, 0.4f); -PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 3.0f); +PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 1.0f); diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index 466284a1b4..a07a1bb276 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -184,6 +184,10 @@ private: int rc_map_throttle; int rc_map_mode_sw; + int rc_map_aux1; + int rc_map_aux2; + int rc_map_aux3; + float rc_scale_roll; float rc_scale_pitch; float rc_scale_yaw; @@ -212,6 +216,10 @@ private: param_t rc_map_throttle; param_t rc_map_mode_sw; + param_t rc_map_aux1; + param_t rc_map_aux2; + param_t rc_map_aux3; + param_t rc_scale_roll; param_t rc_scale_pitch; param_t rc_scale_yaw; @@ -389,6 +397,9 @@ Sensors::Sensors() : _parameter_handles.rc_map_yaw = param_find("RC_MAP_YAW"); _parameter_handles.rc_map_throttle = param_find("RC_MAP_THROTTLE"); _parameter_handles.rc_map_mode_sw = param_find("RC_MAP_MODE_SW"); + _parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1"); + _parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2"); + _parameter_handles.rc_map_aux3 = param_find("RC_MAP_AUX3"); _parameter_handles.rc_scale_roll = param_find("RC_SCALE_ROLL"); _parameter_handles.rc_scale_pitch = param_find("RC_SCALE_PITCH"); @@ -480,14 +491,20 @@ Sensors::parameters_update() _parameters.scaling_factor[i] = 0; } + /* handle wrong values */ + // XXX TODO + } /* update RC function mappings */ - _rc.function[0] = _parameters.rc_map_throttle - 1; - _rc.function[1] = _parameters.rc_map_roll - 1; - _rc.function[2] = _parameters.rc_map_pitch - 1; - _rc.function[3] = _parameters.rc_map_yaw - 1; - _rc.function[4] = _parameters.rc_map_mode_sw - 1; + _rc.function[THROTTLE] = _parameters.rc_map_throttle - 1; + _rc.function[ROLL] = _parameters.rc_map_roll - 1; + _rc.function[PITCH] = _parameters.rc_map_pitch - 1; + _rc.function[YAW] = _parameters.rc_map_yaw - 1; + _rc.function[OVERRIDE] = _parameters.rc_map_mode_sw - 1; + _rc.function[FUNC_0] = _parameters.rc_map_aux1 - 1; + _rc.function[FUNC_1] = _parameters.rc_map_aux2 - 1; + _rc.function[FUNC_2] = _parameters.rc_map_aux3 - 1; /* remote control type */ if (param_get(_parameter_handles.rc_type, &(_parameters.rc_type)) != OK) { @@ -510,6 +527,15 @@ Sensors::parameters_update() if (param_get(_parameter_handles.rc_map_mode_sw, &(_parameters.rc_map_mode_sw)) != OK) { warnx("Failed getting mode sw chan index"); } + if (param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1)) != OK) { + warnx("Failed getting mode aux 1 index"); + } + if (param_get(_parameter_handles.rc_map_aux2, &(_parameters.rc_map_aux2)) != OK) { + warnx("Failed getting mode aux 2 index"); + } + if (param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3)) != OK) { + warnx("Failed getting mode aux 3 index"); + } if (param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll)) != OK) { warnx("Failed getting rc scaling for roll"); @@ -973,7 +999,7 @@ Sensors::ppm_poll() } /* yaw input - stick right is positive and positive rotation */ - manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled * _parameters.rc_scale_yaw; + manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled; if (manual_control.yaw < -1.0f) manual_control.yaw = -1.0f; if (manual_control.yaw > 1.0f) manual_control.yaw = 1.0f; if (!isnan(_parameters.rc_scale_yaw) || !isinf(_parameters.rc_scale_yaw)) { @@ -990,6 +1016,19 @@ Sensors::ppm_poll() if (manual_control.override_mode_switch < -1.0f) manual_control.override_mode_switch = -1.0f; if (manual_control.override_mode_switch > 1.0f) manual_control.override_mode_switch = 1.0f; + /* aux functions */ + manual_control.aux1_cam_pan_flaps = _rc.chan[_rc.function[FUNC_0]].scaled; + if (manual_control.aux1_cam_pan_flaps < -1.0f) manual_control.aux1_cam_pan_flaps = -1.0f; + if (manual_control.aux1_cam_pan_flaps > 1.0f) manual_control.aux1_cam_pan_flaps = 1.0f; + + manual_control.aux2_cam_tilt = _rc.chan[_rc.function[FUNC_1]].scaled; + if (manual_control.aux2_cam_tilt < -1.0f) manual_control.aux2_cam_tilt = -1.0f; + if (manual_control.aux2_cam_tilt > 1.0f) manual_control.aux2_cam_tilt = 1.0f; + + manual_control.aux3_cam_zoom = _rc.chan[_rc.function[FUNC_2]].scaled; + if (manual_control.aux3_cam_zoom < -1.0f) manual_control.aux3_cam_zoom = -1.0f; + if (manual_control.aux3_cam_zoom > 1.0f) manual_control.aux3_cam_zoom = 1.0f; + orb_publish(ORB_ID(rc_channels), _rc_pub, &_rc); orb_publish(ORB_ID(manual_control_setpoint), _manual_control_pub, &manual_control); } From faa672f8bb257ec0ee357ad55da3195b79aeb54b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 25 Nov 2012 13:55:28 +0100 Subject: [PATCH 157/206] mode switching for all platforms, additional fixed wing modes --- apps/commander/commander.c | 18 +- .../fixedwing_att_control_main.c | 58 ++++- .../fixedwing_att_control_rate.c | 8 +- .../fixedwing_pos_control_main.c | 246 ++++++++++-------- apps/sensors/sensors.cpp | 17 +- 5 files changed, 215 insertions(+), 132 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 7277e9fa4c..33ed5ebc26 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -1496,14 +1496,20 @@ int commander_thread_main(int argc, char *argv[]) } //printf("RC: y:%i/t:%i s:%i chans: %i\n", rc_yaw_scale, rc_throttle_scale, mode_switch_rc_value, rc.chan_count); - if (sp_man.override_mode_switch > STICK_ON_OFF_LIMIT) { + if (sp_man.aux1_cam_pan_flaps < -STICK_ON_OFF_LIMIT) { update_state_machine_mode_manual(stat_pub, ¤t_status, mavlink_fd); - - } else if (sp_man.override_mode_switch < -STICK_ON_OFF_LIMIT) { - update_state_machine_mode_auto(stat_pub, ¤t_status, mavlink_fd); - } else { - update_state_machine_mode_stabilized(stat_pub, ¤t_status, mavlink_fd); + if (sp_man.override_mode_switch > STICK_ON_OFF_LIMIT) { + //update_state_machine_mode_manual(stat_pub, ¤t_status, mavlink_fd); + // XXX hack + update_state_machine_mode_stabilized(stat_pub, ¤t_status, mavlink_fd); + + } else if (sp_man.override_mode_switch < -STICK_ON_OFF_LIMIT) { + update_state_machine_mode_auto(stat_pub, ¤t_status, mavlink_fd); + + } else { + update_state_machine_mode_stabilized(stat_pub, ¤t_status, mavlink_fd); + } } /* handle the case where RC signal was regained */ diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index 38f58ac33a..9dd34b9ecd 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -62,8 +62,8 @@ #include #include #include +#include #include - #include #include @@ -126,7 +126,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) } /* welcome user */ - printf("[fixedwing att_control] started\n"); + printf("[fixedwing att control] started\n"); /* declare and safely initialize all structs */ struct vehicle_attitude_s att; @@ -153,6 +153,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) actuators.control[i] = 0.0f; } orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators); + orb_advert_t rates_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); // orb_advert_t debug_pub = orb_advertise(ORB_ID(debug_key_value), &debug_output); // debug_output.key[0] = '1'; @@ -185,19 +186,51 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) /* Control */ if (vstatus.state_machine == SYSTEM_STATE_AUTO) { - /* Attitude Control */ - fixedwing_att_control_attitude(&att_sp, - &att, - &rates_sp); + /* attitude control */ + fixedwing_att_control_attitude(&att_sp, &att, &rates_sp); + /* publish rate setpoint */ + orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp); - /* Attitude Rate Control */ + /* angular rate control */ fixedwing_att_control_rates(&rates_sp, gyro, &actuators); - //REMOVEME XXX - actuators.control[3] = 0.7f; + /* pass through throttle */ + actuators.control[3] = att_sp.thrust; + + } else if (vstatus.state_machine == SYSTEM_STATE_STABILIZED) { + + /* if the RC signal is lost, try to stay level and go slowly back down to ground */ + if(vstatus.rc_signal_lost) { + + // XXX define failsafe throttle param + //param_get(failsafe_throttle_handle, &failsafe_throttle); + att_sp.roll_body = 0.3f; + att_sp.pitch_body = 0.0f; + att_sp.thrust = 0.5f; + + // XXX disable yaw control, loiter + + } else { + + att_sp.roll_body = manual_sp.roll; + att_sp.pitch_body = manual_sp.pitch; + att_sp.yaw_body = 0; + att_sp.thrust = manual_sp.throttle; + att_sp.timestamp = hrt_absolute_time(); + } + + fixedwing_att_control_attitude(&att_sp, &att, &rates_sp); + + /* publish rate setpoint */ + orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp); + + /* angular rate control */ + fixedwing_att_control_rates(&rates_sp, gyro, &actuators); + + /* pass through throttle */ + actuators.control[3] = att_sp.thrust; + - // debug_output.value = rates_sp.pitch; - // orb_publish(ORB_ID(debug_key_value), debug_pub, &debug_output); } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) { /* directly pass through values */ actuators.control[0] = manual_sp.roll; @@ -224,6 +257,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) close(att_sub); close(actuator_pub); + close(rates_pub); fflush(stdout); exit(0); @@ -268,7 +302,7 @@ int fixedwing_att_control_main(int argc, char *argv[]) deamon_task = task_spawn("fixedwing_att_control", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 20, - 4096, + 2048, fixedwing_att_control_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); thread_running = true; diff --git a/apps/fixedwing_att_control/fixedwing_att_control_rate.c b/apps/fixedwing_att_control/fixedwing_att_control_rate.c index b81d50168b..f46761922e 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_rate.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_rate.c @@ -1,7 +1,7 @@ /**************************************************************************** * * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * Author: @author Thomas Gubler + * Author: Thomas Gubler * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -34,6 +34,8 @@ /** * @file fixedwing_att_control_rate.c * Implementation of a fixed wing attitude controller. + * + * @author Thomas Gubler */ #include @@ -171,8 +173,8 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp, actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0, deltaT); - actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT); //TODO: (-) sign comes from the elevator (positive --> deflection downwards), this has to be moved to the mixer... - actuators->control[2] = 0;//pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now + actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT); + actuators->control[2] = 0.0f;//pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now counter++; diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c index a70b9bd30d..d9acd8db9d 100644 --- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c +++ b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c @@ -57,9 +57,11 @@ #include #include #include +#include #include #include #include +#include #include /* @@ -162,16 +164,16 @@ static int parameters_update(const struct fw_pos_control_param_handles *h, struc int fixedwing_pos_control_thread_main(int argc, char *argv[]) { /* read arguments */ - bool verbose = false; + // bool verbose = false; - for (int i = 1; i < argc; i++) { - if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) { - verbose = true; - } - } + // for (int i = 1; i < argc; i++) { + // if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) { + // verbose = true; + // } + // } /* welcome user */ - printf("[fixedwing att_control] started\n"); + printf("[fixedwing pos control] started\n"); /* declare and safely initialize all structs */ struct vehicle_global_position_s global_pos; @@ -184,6 +186,8 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) memset(&att, 0, sizeof(att)); struct crosstrack_error_s xtrack_err; memset(&xtrack_err, 0, sizeof(xtrack_err)); + struct parameter_update_s param_update; + memset(¶m_update, 0, sizeof(param_update)); /* output structs */ struct vehicle_attitude_setpoint_s attitude_setpoint; @@ -193,129 +197,151 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) attitude_setpoint.roll_body = 0.0f; attitude_setpoint.pitch_body = 0.0f; attitude_setpoint.yaw_body = 0.0f; + attitude_setpoint.thrust = 0.0f; orb_advert_t attitude_setpoint_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &attitude_setpoint); /* subscribe */ int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); int global_setpoint_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint)); int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); + int param_sub = orb_subscribe(ORB_ID(parameter_update)); /* Setup of loop */ - struct pollfd fds = { .fd = att_sub, .events = POLLIN }; + struct pollfd fds[2] = { + { .fd = param_sub, .events = POLLIN }, + { .fd = att_sub, .events = POLLIN } + }; bool global_sp_updated_set_once = false; float psi_track = 0.0f; + int counter = 0; + + struct fw_pos_control_params p; + struct fw_pos_control_param_handles h; + + PID_t heading_controller; + PID_t altitude_controller; + + parameters_init(&h); + parameters_update(&h, &p); + pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f,p.roll_lim,PID_MODE_DERIVATIV_NONE); + pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f,p.pitch_lim,PID_MODE_DERIVATIV_NONE); + + /* error and performance monitoring */ + perf_counter_t fw_interval_perf = perf_alloc(PC_INTERVAL, "fixedwing_pos_control_interval"); + perf_counter_t fw_err_perf = perf_alloc(PC_COUNT, "fixedwing_pos_control_err"); + while(!thread_should_exit) { /* wait for a sensor update, check for exit condition every 500 ms */ - poll(&fds, 1, 500); + int ret = poll(fds, 2, 500); - static int counter = 0; - static bool initialized = false; + if (ret < 0) { + /* poll error, count it in perf */ + perf_count(fw_err_perf); + } else if (ret == 0) { + /* no return value, ignore */ + } else { - static struct fw_pos_control_params p; - static struct fw_pos_control_param_handles h; + /* only update parameters if they changed */ + if (fds[0].revents & POLLIN) { + /* read from param to clear updated flag */ + struct parameter_update_s update; + orb_copy(ORB_ID(parameter_update), param_sub, &update); - PID_t heading_controller; - PID_t altitude_controller; - - if(!initialized) - { - parameters_init(&h); - parameters_update(&h, &p); - pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f,p.roll_lim,PID_MODE_DERIVATIV_NONE); - pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f,p.pitch_lim,PID_MODE_DERIVATIV_NONE); - initialized = true; - } - - /* load new parameters with lower rate */ - if (counter % 100 == 0) { - /* update parameters from storage */ - parameters_update(&h, &p); - pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, p.roll_lim); - pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_lim); - - } - - /* Check if there is a new position or setpoint */ - bool pos_updated; - orb_check(global_pos_sub, &pos_updated); - bool global_sp_updated; - orb_check(global_setpoint_sub, &global_sp_updated); - - /* Load local copies */ - orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); - if(pos_updated) - orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos); - if (global_sp_updated) - orb_copy(ORB_ID(vehicle_global_position_setpoint), global_setpoint_sub, &global_setpoint); - - if(global_sp_updated) { - start_pos = global_pos; //for now using the current position as the startpoint (= approx. last waypoint because the setpoint switch occurs at the waypoint) - global_sp_updated_set_once = true; - psi_track = get_bearing_to_next_waypoint((double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d, - (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d); - printf("psi_track: %0.4f\n", (double)psi_track); - } - - /* Control */ - - - /* Simple Horizontal Control */ - if(global_sp_updated_set_once) - { -// if (counter % 100 == 0) -// printf("lat_sp %d, ln_sp %d, lat: %d, lon: %d\n", global_setpoint.lat, global_setpoint.lon, global_pos.lat, global_pos.lon); - - /* calculate crosstrack error */ - // Only the case of a straight line track following handled so far - int distance_res = get_distance_to_line(&xtrack_err, (double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d, - (double)start_pos.lat / (double)1e7d, (double)start_pos.lon / (double)1e7d, - (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d); - - if(!(distance_res != OK || xtrack_err.past_end)) { - - float delta_psi_c = -p.xtrack_p * xtrack_err.distance; //(-) because z axis points downwards - - if(delta_psi_c > 60.0f*M_DEG_TO_RAD_F) - delta_psi_c = 60.0f*M_DEG_TO_RAD_F; - - if(delta_psi_c < -60.0f*M_DEG_TO_RAD_F) - delta_psi_c = -60.0f*M_DEG_TO_RAD_F; - - float psi_c = psi_track + delta_psi_c; - - float psi_e = psi_c - att.yaw; - - /* shift error to prevent wrapping issues */ - psi_e = _wrap_pi(psi_e); - - /* calculate roll setpoint, do this artificially around zero */ - attitude_setpoint.roll_body = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f); - -// if (counter % 100 == 0) -// printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c); - } - else { - if (counter % 100 == 0) - printf("distance_res: %d, past_end %d\n", distance_res, xtrack_err.past_end); + /* update parameters from storage */ + parameters_update(&h, &p); + pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, p.roll_lim); + pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_lim); } + /* only run controller if attitude changed */ + if (fds[1].revents & POLLIN) { + + /* check if there is a new position or setpoint */ + bool pos_updated; + orb_check(global_pos_sub, &pos_updated); + bool global_sp_updated; + orb_check(global_setpoint_sub, &global_sp_updated); + + /* load local copies */ + orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); + + if (pos_updated) { + orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos); + } + + if (global_sp_updated) { + orb_copy(ORB_ID(vehicle_global_position_setpoint), global_setpoint_sub, &global_setpoint); + + start_pos = global_pos; //for now using the current position as the startpoint (= approx. last waypoint because the setpoint switch occurs at the waypoint) + global_sp_updated_set_once = true; + psi_track = get_bearing_to_next_waypoint((double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d, + (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d); + printf("psi_track: %0.4f\n", (double)psi_track); + } + + /* simple horizontal control, execute if line between wps is known */ + if(global_sp_updated_set_once) + { + // if (counter % 100 == 0) + // printf("lat_sp %d, ln_sp %d, lat: %d, lon: %d\n", global_setpoint.lat, global_setpoint.lon, global_pos.lat, global_pos.lon); + + /* calculate crosstrack error */ + // Only the case of a straight line track following handled so far + int distance_res = get_distance_to_line(&xtrack_err, (double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d, + (double)start_pos.lat / (double)1e7d, (double)start_pos.lon / (double)1e7d, + (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d); + + if(!(distance_res != OK || xtrack_err.past_end)) { + + float delta_psi_c = -p.xtrack_p * xtrack_err.distance; //(-) because z axis points downwards + + if(delta_psi_c > 60.0f*M_DEG_TO_RAD_F) + delta_psi_c = 60.0f*M_DEG_TO_RAD_F; + + if(delta_psi_c < -60.0f*M_DEG_TO_RAD_F) + delta_psi_c = -60.0f*M_DEG_TO_RAD_F; + + float psi_c = psi_track + delta_psi_c; + + float psi_e = psi_c - att.yaw; + + /* shift error to prevent wrapping issues */ + psi_e = _wrap_pi(psi_e); + + /* calculate roll setpoint, do this artificially around zero */ + attitude_setpoint.roll_body = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f); + + // if (counter % 100 == 0) + // printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c); + } + else { + if (counter % 100 == 0) + printf("distance_res: %d, past_end %d\n", distance_res, xtrack_err.past_end); + } + + // XXX SIMPLE ALTITUDE, BUT NO SPEED CONTROL + if (pos_updated) { + //TODO: take care of relative vs. ab. altitude + attitude_setpoint.pitch_body = pid_calculate(&altitude_controller, global_setpoint.altitude, global_pos.alt, 0.0f, 0.0f); + } + + // XXX need speed control + attitude_setpoint.thrust = 0.7f; + + /* publish the attitude setpoint */ + orb_publish(ORB_ID(vehicle_attitude_setpoint), attitude_setpoint_pub, &attitude_setpoint); + + /* measure in what intervals the controller runs */ + perf_count(fw_interval_perf); + + } else { + // XXX no setpoint, decent default needed (loiter?) + } + } } - - /* Very simple Altitude Control */ - if(global_sp_updated_set_once && pos_updated) - { - - //TODO: take care of relative vs. ab. altitude - attitude_setpoint.pitch_body = pid_calculate(&altitude_controller, global_setpoint.altitude, global_pos.alt, 0.0f, 0.0f); - - } - /*Publish the attitude setpoint */ - orb_publish(ORB_ID(vehicle_attitude_setpoint), attitude_setpoint_pub, &attitude_setpoint); - - counter++; } printf("[fixedwing_pos_control] exiting.\n"); @@ -367,7 +393,7 @@ int fixedwing_pos_control_main(int argc, char *argv[]) deamon_task = task_spawn("fixedwing_pos_control", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 20, - 4096, + 2048, fixedwing_pos_control_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); thread_running = true; diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index 466284a1b4..a633e012cf 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -973,7 +973,7 @@ Sensors::ppm_poll() } /* yaw input - stick right is positive and positive rotation */ - manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled * _parameters.rc_scale_yaw; + manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled; if (manual_control.yaw < -1.0f) manual_control.yaw = -1.0f; if (manual_control.yaw > 1.0f) manual_control.yaw = 1.0f; if (!isnan(_parameters.rc_scale_yaw) || !isinf(_parameters.rc_scale_yaw)) { @@ -990,6 +990,21 @@ Sensors::ppm_poll() if (manual_control.override_mode_switch < -1.0f) manual_control.override_mode_switch = -1.0f; if (manual_control.override_mode_switch > 1.0f) manual_control.override_mode_switch = 1.0f; + /* aux inputs */ + manual_control.aux1_cam_pan_flaps = _rc.chan[_rc.function[FUNC_0]].scaled; + if (manual_control.aux1_cam_pan_flaps < -1.0f) manual_control.aux1_cam_pan_flaps = -1.0f; + if (manual_control.aux1_cam_pan_flaps > 1.0f) manual_control.aux1_cam_pan_flaps = 1.0f; + + /* aux inputs */ + manual_control.aux2_cam_tilt = _rc.chan[_rc.function[FUNC_1]].scaled; + if (manual_control.aux2_cam_tilt < -1.0f) manual_control.aux2_cam_tilt = -1.0f; + if (manual_control.aux2_cam_tilt > 1.0f) manual_control.aux2_cam_tilt = 1.0f; + + /* aux inputs */ + manual_control.aux3_cam_zoom = _rc.chan[_rc.function[FUNC_2]].scaled; + if (manual_control.aux3_cam_zoom < -1.0f) manual_control.aux3_cam_zoom = -1.0f; + if (manual_control.aux3_cam_zoom > 1.0f) manual_control.aux3_cam_zoom = 1.0f; + orb_publish(ORB_ID(rc_channels), _rc_pub, &_rc); orb_publish(ORB_ID(manual_control_setpoint), _manual_control_pub, &manual_control); } From 20a29bff9923b5fd82c4f0484808e0b5538016bf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 25 Nov 2012 16:42:31 +0100 Subject: [PATCH 158/206] Fixes for roll/pitch feedforward --- apps/fixedwing_att_control/fixedwing_att_control_att.c | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.c b/apps/fixedwing_att_control/fixedwing_att_control_att.c index 334b95226f..0456277007 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_att.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_att.c @@ -146,8 +146,12 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body, att->roll, 0, 0); /* Pitch (P) */ - float pitch_sp_rollcompensation = att_sp->pitch_body + p.pitch_roll_compensation_p * att_sp->roll_body; - rates_sp->pitch = pid_calculate(&pitch_controller, pitch_sp_rollcompensation, att->pitch, 0, 0); + + /* compensate feedforward for loss of lift due to non-horizontal angle of wing */ + float pitch_sp_rollcompensation = p.pitch_roll_compensation_p * fabsf(att_sp->roll_body); + /* set pitch plus feedforward roll compensation */ + rates_sp->pitch = pid_calculate(&pitch_controller, att_sp->pitch_body + pitch_sp_rollcompensation, + att->pitch, 0, 0); /* Yaw (from coordinated turn constraint or lateral force) */ //TODO From 4366d9e31904a9b96992e1bb41388bd69ba92407 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sun, 25 Nov 2012 18:20:54 +0100 Subject: [PATCH 159/206] fw_controller testing --- .../fixedwing_att_control_att.c | 5 +- .../fixedwing_att_control_main.c | 4 +- .../fixedwing_att_control_rate.c | 6 +-- .../fixedwing_pos_control_main.c | 48 ++++++++++++++----- apps/mavlink/mavlink_receiver.c | 2 +- 5 files changed, 46 insertions(+), 19 deletions(-) diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.c b/apps/fixedwing_att_control/fixedwing_att_control_att.c index 98442ed558..877360c6f9 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_att.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_att.c @@ -146,13 +146,16 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att /* Roll (P) */ rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body, att->roll, 0, 0); + /* Pitch (P) */ float pitch_sp_rollcompensation = att_sp->pitch_body + p.pitch_roll_compensation_p * att_sp->roll_body; rates_sp->pitch = pid_calculate(&pitch_controller, pitch_sp_rollcompensation, att->pitch, 0, 0); /* Yaw (from coordinated turn constraint or lateral force) */ rates_sp->yaw = (att->rollspeed * rates_sp->roll + 9.81f * sinf(att->roll) * cosf(att->pitch) + speed_body[0] * rates_sp->pitch * sinf(att->roll)) - / (speed_body[0] * cosf(att->roll) * cosf(att->pitch) + speed_body[1] * sinf(att->pitch)); + / (speed_body[0] * cosf(att->roll) * cosf(att->pitch) + speed_body[2] * sinf(att->pitch)); + +// printf("rates_sp->yaw %.4f \n", (double)rates_sp->yaw); counter++; diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index 658bf3e695..f4efad31d9 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -230,8 +230,8 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) //REMOVEME XXX actuators.control[3] = 0.7f; - // debug_output.value = rates_sp.pitch; - // orb_publish(ORB_ID(debug_key_value), debug_pub, &debug_output); + debug_output.value = rates_sp.pitch; + orb_publish(ORB_ID(debug_key_value), debug_pub, &debug_output); } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) { /* directly pass through values */ actuators.control[0] = manual_sp.roll; diff --git a/apps/fixedwing_att_control/fixedwing_att_control_rate.c b/apps/fixedwing_att_control/fixedwing_att_control_rate.c index 6f3a7f6e8d..2bc07a7fc9 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_rate.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_rate.c @@ -169,10 +169,8 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp, /* Roll Rate (PI) */ actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0, deltaT); - - - actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT); //TODO: (-) sign comes from the elevator (positive --> deflection downwards), this has to be moved to the mixer... - actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now + actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT); + actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); counter++; diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c index 640edba990..be73214be3 100644 --- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c +++ b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c @@ -66,10 +66,13 @@ * Controller parameters, accessible via MAVLink * */ -PARAM_DEFINE_FLOAT(FW_HEADING_P, 0.1f); +PARAM_DEFINE_FLOAT(FW_HEAD_P, 0.1f); +PARAM_DEFINE_FLOAT(FW_HEADR_I, 0.1f); +PARAM_DEFINE_FLOAT(FW_HEADR_LIM, 1.5f); //TODO: think about reasonable value PARAM_DEFINE_FLOAT(FW_XTRACK_P, 0.01745f); // Radians per meter off track PARAM_DEFINE_FLOAT(FW_ALT_P, 0.1f); PARAM_DEFINE_FLOAT(FW_ROLL_LIM, 0.7f); // Roll angle limit in radians +PARAM_DEFINE_FLOAT(FW_HEADR_P, 0.1f); PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); // Pitch angle limit in radians @@ -77,6 +80,7 @@ struct fw_pos_control_params { float heading_p; float headingr_p; float headingr_i; + float headingr_lim; float xtrack_p; float altitude_p; float roll_lim; @@ -87,6 +91,7 @@ struct fw_pos_control_param_handles { param_t heading_p; param_t headingr_p; param_t headingr_i; + param_t headingr_lim; param_t xtrack_p; param_t altitude_p; param_t roll_lim; @@ -140,9 +145,10 @@ static int deamon_task; /**< Handle of deamon task / thread */ static int parameters_init(struct fw_pos_control_param_handles *h) { /* PID parameters */ - h->heading_p = param_find("FW_HEADING_P"); - h->headingr_p = param_find("FW_HEADINGR_P"); - h->headingr_i = param_find("FW_HEADINGR_I"); + h->heading_p = param_find("FW_HEAD_P"); + h->headingr_p = param_find("FW_HEADR_P"); + h->headingr_i = param_find("FW_HEADR_I"); + h->headingr_lim = param_find("FW_HEADR_LIM"); h->xtrack_p = param_find("FW_XTRACK_P"); h->altitude_p = param_find("FW_ALT_P"); h->roll_lim = param_find("FW_ROLL_LIM"); @@ -157,6 +163,7 @@ static int parameters_update(const struct fw_pos_control_param_handles *h, struc param_get(h->heading_p, &(p->heading_p)); param_get(h->headingr_p, &(p->headingr_p)); param_get(h->headingr_i, &(p->headingr_i)); + param_get(h->headingr_lim, &(p->headingr_lim)); param_get(h->xtrack_p, &(p->xtrack_p)); param_get(h->altitude_p, &(p->altitude_p)); param_get(h->roll_lim, &(p->roll_lim)); @@ -239,7 +246,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) parameters_init(&h); parameters_update(&h, &p); pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f, 10000.0f, PID_MODE_DERIVATIV_NONE); //arbitrary high limit - pid_init(&heading_rate_controller, p.headingr_p, p.headingr_i, 0.0f, 0.0f, p.roll_lim, PID_MODE_DERIVATIV_NONE); + pid_init(&heading_rate_controller, p.headingr_p, p.headingr_i, 0.0f, 1.0f, p.roll_lim, PID_MODE_DERIVATIV_NONE); //TODO: integrator limit pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f, p.pitch_lim, PID_MODE_DERIVATIV_NONE); pid_init(&offtrack_controller, p.xtrack_p, 0.0f, 0.0f, 0.0f , 60.0f*M_DEG_TO_RAD, PID_MODE_DERIVATIV_NONE); //TODO: remove hardcoded value initialized = true; @@ -250,7 +257,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) /* update parameters from storage */ parameters_update(&h, &p); pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, 10000.0f); //arbitrary high limit - pid_set_parameters(&heading_rate_controller, p.headingr_p, p.headingr_i, 0, 0, p.roll_lim); + pid_set_parameters(&heading_rate_controller, p.headingr_p, p.headingr_i, 0, 1.0f, p.roll_lim); //TODO: integrator limit pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_lim); pid_set_parameters(&offtrack_controller, p.xtrack_p, 0, 0, 0, 60.0f*M_DEG_TO_RAD); //TODO: remove hardcoded value @@ -293,28 +300,47 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) if(!(distance_res != OK || xtrack_err.past_end)) { - float delta_psi_c = -pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance; //(-) because z axis points downwards +// printf("xtrack_err.distance %.4f ", (double)xtrack_err.distance); + + float delta_psi_c = pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance + +// printf("delta_psi_c %.4f ", (double)delta_psi_c); float psi_c = psi_track + delta_psi_c; +// printf("psi_c %.4f ", (double)psi_c); + +// printf("att.yaw %.4f ", (double)att.yaw); + float psi_e = psi_c - att.yaw; +// printf("psi_e %.4f ", (double)psi_e); + /* shift error to prevent wrapping issues */ psi_e = _wrap_pi(psi_e); /* calculate roll setpoint, do this artificially around zero */ - //TODO: psi rate loop incomplete float delta_psi_rate_c = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f); float psi_rate_track = 0; //=V_gr/r_track , this will be needed for implementation of arc following float psi_rate_c = delta_psi_rate_c + psi_rate_track; - //TODO limit turn rate + //limit turn rate + if(psi_rate_c > p.headingr_lim) + psi_rate_c = p.headingr_lim; + else if(psi_rate_c < -p.headingr_lim) + psi_rate_c = - p.headingr_lim; + +// printf("psi_rate_c %.4f ", (double)psi_rate_c); float psi_rate_e = psi_rate_c - att.yawspeed; - float psi_rate_e_scaled = psi_rate_e * sqrtf(pow(global_pos.vx,2) + pow(global_pos.vy,2)) / 9.81f; //* V_gr / g + float psi_rate_e_scaled = psi_rate_e * sqrtf(powf(global_pos.vx, 2.0f) + powf(global_pos.vy, 2.0f)) / 9.81f; //* V_gr / g - attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT); +// printf("psi_rate_e_scaled %.4f ", (double)psi_rate_e_scaled); + + attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT);\ + +// printf("rollbody %.4f\n", (double)attitude_setpoint.roll_body); // if (counter % 100 == 0) // printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c); diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c index e2f28dabde..1801ddc9bf 100644 --- a/apps/mavlink/mavlink_receiver.c +++ b/apps/mavlink/mavlink_receiver.c @@ -300,7 +300,7 @@ handle_message(mavlink_message_t *msg) //TODO: better clarification which app does this, atm we have a ekf for quadrotors which does this, but there is no such thing if fly in fixed wing mode if(mavlink_system.type == MAV_TYPE_FIXED_WING) { - //TODO: asuming low pitch and roll for now + //TODO: assuming low pitch and roll values for now hil_attitude.R[0][0] = cosf(hil_state.yaw); hil_attitude.R[0][1] = sinf(hil_state.yaw); hil_attitude.R[0][2] = 0.0f; From 7cc712b286f3a6132e8abb897d099dabea9bca72 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 26 Nov 2012 17:41:51 +0100 Subject: [PATCH 160/206] More fixed wing improvements --- apps/fixedwing_att_control/fixedwing_att_control_main.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index ee259f78c0..e1776f74a8 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -264,7 +264,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) /* directly pass through values */ actuators.control[0] = manual_sp.roll; /* positive pitch means negative actuator -> pull up */ - actuators.control[1] = -manual_sp.pitch; + actuators.control[1] = manual_sp.pitch; actuators.control[2] = manual_sp.yaw; actuators.control[3] = manual_sp.throttle; } From 9bc044eae91a2d0f0f7d71b7a1d178663008aace Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 26 Nov 2012 17:42:08 +0100 Subject: [PATCH 161/206] More fixed wing improvements --- apps/fixedwing_pos_control/fixedwing_pos_control_main.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c index 45736aa2f3..2dab705e16 100644 --- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c +++ b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c @@ -334,7 +334,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) float psi_rate_e = psi_rate_c - att.yawspeed; - float psi_rate_e_scaled = psi_rate_e * sqrtf(pow(global_pos.vx,2) + pow(global_pos.vy,2)) / 9.81f; //* V_gr / g + float psi_rate_e_scaled = psi_rate_e * sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy) / 9.81f; //* V_gr / g attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT); From 7777d4416d77a683621ef8c18769f4661356e65e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 27 Nov 2012 11:29:48 +0100 Subject: [PATCH 162/206] Changed to actuators effective in mavlink app --- apps/mavlink/mavlink.c | 1 + apps/mavlink/orb_listener.c | 14 +++++++------- apps/mavlink/orb_topics.h | 2 +- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index b393620e20..a94591424f 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -745,6 +745,7 @@ int mavlink_main(int argc, char *argv[]) thread_should_exit = true; while (thread_running) { usleep(200000); + printf("."); } warnx("terminated."); exit(0); diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index 82f8a1534b..ef4cd5598d 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -566,27 +566,27 @@ l_manual_control_setpoint(struct listener *l) void l_vehicle_attitude_controls(struct listener *l) { - struct actuator_controls_s actuators; + struct actuator_controls_effective_s actuators; - orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, mavlink_subs.actuators_sub, &actuators); + orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE, mavlink_subs.actuators_sub, &actuators); if (gcs_link) { /* send, add spaces so that string buffer is at least 10 chars long */ mavlink_msg_named_value_float_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, - "ctrl0 ", + "eff ctrl0 ", actuators.control[0]); mavlink_msg_named_value_float_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, - "ctrl1 ", + "eff ctrl1 ", actuators.control[1]); mavlink_msg_named_value_float_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, - "ctrl2 ", + "eff ctrl2 ", actuators.control[2]); mavlink_msg_named_value_float_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, - "ctrl3 ", + "eff ctrl3 ", actuators.control[3]); } } @@ -739,7 +739,7 @@ uorb_receive_start(void) orb_set_interval(mavlink_subs.man_control_sp_sub, 100); /* 10Hz updates */ /* --- ACTUATOR CONTROL VALUE --- */ - mavlink_subs.actuators_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); + mavlink_subs.actuators_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE); orb_set_interval(mavlink_subs.actuators_sub, 100); /* 10Hz updates */ /* --- DEBUG VALUE OUTPUT --- */ diff --git a/apps/mavlink/orb_topics.h b/apps/mavlink/orb_topics.h index 61ed8cbfe7..0eb2fabfd4 100644 --- a/apps/mavlink/orb_topics.h +++ b/apps/mavlink/orb_topics.h @@ -55,7 +55,7 @@ #include #include #include -#include +#include #include #include #include From 90b94b50501cd388d6acfba66bb048393860af74 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 27 Nov 2012 11:53:50 +0100 Subject: [PATCH 163/206] Ported all mixers to actuator_controls_effective topic, mixers do not output the limited result yet --- apps/drivers/px4fmu/fmu.cpp | 18 +++++++++++++++++- apps/drivers/px4io/px4io.cpp | 18 +++++++++++++++++- apps/mavlink/orb_listener.c | 8 ++++---- apps/uORB/topics/actuator_controls_effective.h | 7 ++++--- 4 files changed, 42 insertions(+), 9 deletions(-) diff --git a/apps/drivers/px4fmu/fmu.cpp b/apps/drivers/px4fmu/fmu.cpp index 61dd418f86..ff610b0b9b 100644 --- a/apps/drivers/px4fmu/fmu.cpp +++ b/apps/drivers/px4fmu/fmu.cpp @@ -64,6 +64,7 @@ #include #include +#include #include #include @@ -96,6 +97,7 @@ private: int _t_actuators; int _t_armed; orb_advert_t _t_outputs; + orb_advert_t _t_actuators_effective; unsigned _num_outputs; bool _primary_pwm_device; @@ -161,6 +163,7 @@ PX4FMU::PX4FMU() : _t_actuators(-1), _t_armed(-1), _t_outputs(0), + _t_actuators_effective(0), _num_outputs(0), _primary_pwm_device(false), _task_should_exit(false), @@ -315,6 +318,13 @@ PX4FMU::task_main() _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), &outputs); + /* advertise the effective control inputs */ + actuator_controls_effective_s controls_effective; + memset(&controls_effective, 0, sizeof(controls_effective)); + /* advertise the effective control inputs */ + _t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), + &controls_effective); + pollfd fds[2]; fds[0].fd = _t_actuators; fds[0].events = POLLIN; @@ -360,6 +370,11 @@ PX4FMU::task_main() /* do mixing */ _mixers->mix(&outputs.output[0], num_outputs); + // XXX output actual limited values + memcpy(&controls_effective, &_controls, sizeof(controls_effective)); + + orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), _t_actuators_effective, &controls_effective); + /* iterate actuators */ for (unsigned i = 0; i < num_outputs; i++) { @@ -371,7 +386,7 @@ PX4FMU::task_main() } /* and publish for anyone that cares to see */ - orb_publish(ORB_ID_VEHICLE_CONTROLS, _t_outputs, &outputs); + orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &outputs); } } @@ -388,6 +403,7 @@ PX4FMU::task_main() } ::close(_t_actuators); + ::close(_t_actuators_effective); ::close(_t_armed); /* make sure servos are off */ diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index bf23c3937c..2385385a2a 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -70,6 +70,7 @@ #include #include +#include #include #include @@ -102,6 +103,9 @@ private: int _t_actuators; ///< actuator output topic actuator_controls_s _controls; ///< actuator outputs + orb_advert_t _t_actuators_effective; ///< effective actuator controls topic + actuator_controls_effective_s _controls_effective; ///< effective controls + int _t_armed; ///< system armed control topic actuator_armed_s _armed; ///< system armed state @@ -184,6 +188,7 @@ PX4IO::PX4IO() : _task_should_exit(false), _connected(false), _t_actuators(-1), + _t_actuators_effective(-1), _t_armed(-1), _t_outputs(-1), _mixers(nullptr), @@ -319,6 +324,11 @@ PX4IO::task_main() _t_armed = orb_subscribe(ORB_ID(actuator_armed)); orb_set_interval(_t_armed, 200); /* 5Hz update rate */ + /* advertise the limited control inputs */ + memset(&_controls_effective, 0, sizeof(_controls_effective)); + _t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_1), + &_controls_effective); + /* advertise the mixed control outputs */ memset(&_outputs, 0, sizeof(_outputs)); _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), @@ -372,6 +382,12 @@ PX4IO::task_main() /* XXX is this the right count? */ _mixers->mix(&_outputs.output[0], _max_actuators); + // XXX output actual limited values + memcpy(&_controls_effective, &_controls, sizeof(_controls_effective)); + + orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), _t_actuators_effective, &_controls_effective); + + /* convert to PWM values */ for (unsigned i = 0; i < _max_actuators; i++) _outputs.output[i] = 1500 + (600 * _outputs.output[i]); @@ -496,7 +512,7 @@ PX4IO::io_send() cmd.servo_command[i] = _outputs.output[i]; /* publish as we send */ - orb_publish(ORB_ID_VEHICLE_CONTROLS, _t_outputs, &_outputs); + orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &_outputs); // XXX relays diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index ef4cd5598d..254100b2e6 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -575,19 +575,19 @@ l_vehicle_attitude_controls(struct listener *l) mavlink_msg_named_value_float_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, "eff ctrl0 ", - actuators.control[0]); + actuators.control_effective[0]); mavlink_msg_named_value_float_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, "eff ctrl1 ", - actuators.control[1]); + actuators.control_effective[1]); mavlink_msg_named_value_float_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, "eff ctrl2 ", - actuators.control[2]); + actuators.control_effective[2]); mavlink_msg_named_value_float_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, "eff ctrl3 ", - actuators.control[3]); + actuators.control_effective[3]); } } diff --git a/apps/uORB/topics/actuator_controls_effective.h b/apps/uORB/topics/actuator_controls_effective.h index 3c72e4cb7e..83f082c8a6 100644 --- a/apps/uORB/topics/actuator_controls_effective.h +++ b/apps/uORB/topics/actuator_controls_effective.h @@ -32,7 +32,7 @@ ****************************************************************************/ /** - * @file actuator_controls.h + * @file actuator_controls_effective.h * * Actuator control topics - mixer inputs. * @@ -48,9 +48,10 @@ #include #include "../uORB.h" +#include "actuator_controls.h" -#define NUM_ACTUATOR_CONTROLS 8 -#define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */ +#define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS +#define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */ struct actuator_controls_effective_s { uint64_t timestamp; From cc1e0ef2356fd3fe24726386add7e6f7106574b6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 27 Nov 2012 17:38:16 +0100 Subject: [PATCH 164/206] Removed old fixed wing control process --- apps/fixedwing_control/Makefile | 44 -- apps/fixedwing_control/fixedwing_control.c | 566 --------------------- nuttx/configs/px4fmu/nsh/appconfig | 1 - 3 files changed, 611 deletions(-) delete mode 100644 apps/fixedwing_control/Makefile delete mode 100644 apps/fixedwing_control/fixedwing_control.c diff --git a/apps/fixedwing_control/Makefile b/apps/fixedwing_control/Makefile deleted file mode 100644 index 02d4463dd0..0000000000 --- a/apps/fixedwing_control/Makefile +++ /dev/null @@ -1,44 +0,0 @@ -############################################################################ -# -# Copyright (C) 2012 PX4 Development Team. All rights reserved. -# -# 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 PX4 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. -# -############################################################################ - -# -# fixedwing_control Application -# - -APPNAME = fixedwing_control -PRIORITY = SCHED_PRIORITY_MAX - 1 -STACKSIZE = 4096 - -CSRCS = fixedwing_control.c - -include $(APPDIR)/mk/app.mk diff --git a/apps/fixedwing_control/fixedwing_control.c b/apps/fixedwing_control/fixedwing_control.c deleted file mode 100644 index e040334819..0000000000 --- a/apps/fixedwing_control/fixedwing_control.c +++ /dev/null @@ -1,566 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * Author: @author Ivan Ovinnikov - * Modifications: Doug Weibel - * - * 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 PX4 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 fixedwing_control.c - * Implementation of a fixed wing attitude and position controller. - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -static bool thread_should_exit = false; /**< Deamon exit flag */ -static bool thread_running = false; /**< Deamon status flag */ -static int deamon_task; /**< Handle of deamon task / thread */ - -/** - * Deamon management function. - */ -__EXPORT int fixedwing_control_main(int argc, char *argv[]); - -/** - * Mainloop of deamon. - */ -int fixedwing_control_thread_main(int argc, char *argv[]); - -/** - * Print the correct usage. - */ -static void usage(const char *reason); - -/* - * Controller parameters, accessible via MAVLink - * - */ -// Roll control parameters -PARAM_DEFINE_FLOAT(FW_ROLLRATE_P, 0.3f); -// Need to add functionality to suppress integrator windup while on the ground -// Suggested value of FW_ROLLRATE_I is 0.0 till this is in place -PARAM_DEFINE_FLOAT(FW_ROLLRATE_I, 0.0f); -PARAM_DEFINE_FLOAT(FW_ROLLRATE_AWU, 0.0f); -PARAM_DEFINE_FLOAT(FW_ROLLRATE_LIM, 0.7f); // Roll rate limit in radians/sec -PARAM_DEFINE_FLOAT(FW_ROLL_P, 0.3f); -PARAM_DEFINE_FLOAT(FW_ROLL_LIM, 0.7f); // Roll angle limit in radians - -//Pitch control parameters -PARAM_DEFINE_FLOAT(FW_PITCHRATE_P, 0.3f); -// Need to add functionality to suppress integrator windup while on the ground -// Suggested value of FW_PITCHRATE_I is 0.0 till this is in place -PARAM_DEFINE_FLOAT(FW_PITCHRATE_I, 0.0f); -PARAM_DEFINE_FLOAT(FW_PITCHRATE_AWU, 0.0f); -PARAM_DEFINE_FLOAT(FW_PITCHRATE_LIM, 0.35f); // Pitch rate limit in radians/sec -PARAM_DEFINE_FLOAT(FW_PITCH_P, 0.3f); -PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); // Pitch angle limit in radians - -struct fw_att_control_params { - float rollrate_p; - float rollrate_i; - float rollrate_awu; - float rollrate_lim; - float roll_p; - float roll_lim; - float pitchrate_p; - float pitchrate_i; - float pitchrate_awu; - float pitchrate_lim; - float pitch_p; - float pitch_lim; -}; - -struct fw_att_control_param_handles { - param_t rollrate_p; - param_t rollrate_i; - param_t rollrate_awu; - param_t rollrate_lim; - param_t roll_p; - param_t roll_lim; - param_t pitchrate_p; - param_t pitchrate_i; - param_t pitchrate_awu; - param_t pitchrate_lim; - param_t pitch_p; - param_t pitch_lim; -}; - - -// TO_DO - Navigation control will be moved to a separate app -// Attitude control will just handle the inner angle and rate loops -// to control pitch and roll, and turn coordination via rudder and -// possibly throttle compensation for battery voltage sag. - -PARAM_DEFINE_FLOAT(FW_HEADING_P, 0.1f); -PARAM_DEFINE_FLOAT(FW_HEADING_LIM, 0.15f); - -struct fw_pos_control_params { - float heading_p; - float heading_lim; -}; - -struct fw_pos_control_param_handles { - param_t heading_p; - param_t heading_lim; -}; - -/** - * Initialize all parameter handles and values - * - */ -static int att_parameters_init(struct fw_att_control_param_handles *h); - -/** - * Update all parameters - * - */ -static int att_parameters_update(const struct fw_att_control_param_handles *h, struct fw_att_control_params *p); - -/** - * Initialize all parameter handles and values - * - */ -static int pos_parameters_init(struct fw_pos_control_param_handles *h); - -/** - * Update all parameters - * - */ -static int pos_parameters_update(const struct fw_pos_control_param_handles *h, struct fw_pos_control_params *p); - - -/** - * The fixed wing control main thread. - * - * The main loop executes continously and calculates the control - * response. - * - * @param argc number of arguments - * @param argv argument array - * - * @return 0 - * - */ -int fixedwing_control_thread_main(int argc, char *argv[]) -{ - /* read arguments */ - bool verbose = false; - - for (int i = 1; i < argc; i++) { - if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) { - verbose = true; - } - } - - /* welcome user */ - printf("[fixedwing control] started\n"); - - /* output structs */ - struct actuator_controls_s actuators; - struct vehicle_attitude_setpoint_s att_sp; - memset(&att_sp, 0, sizeof(att_sp)); - - /* publish actuator controls */ - for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) - actuators.control[i] = 0.0f; - orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators); - orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); - - /* Subscribe to global position, attitude and rc */ - /* declare and safely initialize all structs */ - struct vehicle_status_s state; - memset(&state, 0, sizeof(state)); - struct vehicle_attitude_s att; - memset(&att_sp, 0, sizeof(att_sp)); - struct manual_control_setpoint_s manual; - memset(&manual, 0, sizeof(manual)); - - /* subscribe to attitude, motor setpoints and system state */ - struct vehicle_global_position_s global_pos; - int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); - struct vehicle_global_position_setpoint_s global_setpoint; - int global_setpoint_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint)); - int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); - int att_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); - int state_sub = orb_subscribe(ORB_ID(vehicle_status)); - int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); - - /* Mainloop setup */ - unsigned int loopcounter = 0; - - uint64_t last_run = 0; - uint64_t last_run_pos = 0; - - bool global_sp_updated_set_once = false; - - struct fw_att_control_params p; - struct fw_att_control_param_handles h; - - struct fw_pos_control_params ppos; - struct fw_pos_control_param_handles hpos; - - /* initialize the pid controllers */ - att_parameters_init(&h); - att_parameters_update(&h, &p); - - pos_parameters_init(&hpos); - pos_parameters_update(&hpos, &ppos); - -// TO_DO Fix output limit functionallity of PID controller or add that function elsewhere - PID_t roll_rate_controller; - pid_init(&roll_rate_controller, p.rollrate_p, p.rollrate_i, 0.0f, p.rollrate_awu, - p.rollrate_lim,PID_MODE_DERIVATIV_NONE); - PID_t roll_angle_controller; - pid_init(&roll_angle_controller, p.roll_p, 0.0f, 0.0f, 0.0f, - p.roll_lim,PID_MODE_DERIVATIV_NONE); - - PID_t pitch_rate_controller; - pid_init(&pitch_rate_controller, p.pitchrate_p, p.pitchrate_i, 0.0f, p.pitchrate_awu, - p.pitchrate_lim,PID_MODE_DERIVATIV_NONE); - PID_t pitch_angle_controller; - pid_init(&pitch_angle_controller, p.pitch_p, 0.0f, 0.0f, 0.0f, - p.pitch_lim,PID_MODE_DERIVATIV_NONE); - - PID_t heading_controller; - pid_init(&heading_controller, ppos.heading_p, 0.0f, 0.0f, 0.0f, - 100.0f,PID_MODE_DERIVATIV_SET); // Temporary arbitrarily large limit - - // XXX remove in production - /* advertise debug value */ - struct debug_key_value_s dbg = { .key = "", .value = 0.0f }; - orb_advert_t pub_dbg = orb_advertise(ORB_ID(debug_key_value), &dbg); - - // This is the top of the main loop - while(!thread_should_exit) { - - struct pollfd fds[1] = { - { .fd = att_sub, .events = POLLIN }, - }; - int ret = poll(fds, 1, 1000); - - if (ret < 0) { - /* XXX this is seriously bad - should be an emergency */ - } else if (ret == 0) { - /* XXX this means no sensor data - should be critical or emergency */ - printf("[fixedwing control] WARNING: Not getting attitude - estimator running?\n"); - } else { - - // FIXME SUBSCRIBE - if (loopcounter % 100 == 0) { - att_parameters_update(&h, &p); - pos_parameters_update(&hpos, &ppos); - pid_set_parameters(&roll_rate_controller, p.rollrate_p, p.rollrate_i, 0.0f, - p.rollrate_awu, p.rollrate_lim); - pid_set_parameters(&roll_angle_controller, p.roll_p, 0.0f, 0.0f, - 0.0f, p.roll_lim); - pid_set_parameters(&pitch_rate_controller, p.pitchrate_p, p.pitchrate_i, 0.0f, - p.pitchrate_awu, p.pitchrate_lim); - pid_set_parameters(&pitch_angle_controller, p.pitch_p, 0.0f, 0.0f, - 0.0f, p.pitch_lim); - pid_set_parameters(&heading_controller, ppos.heading_p, 0.0f, 0.0f, 0.0f, 90.0f); -//printf("[fixedwing control debug] p: %8.4f, i: %8.4f, limit: %8.4f \n", -//p.rollrate_p, p.rollrate_i, p.rollrate_lim); - } - - /* if position updated, run position control loop */ - bool pos_updated; - orb_check(global_pos_sub, &pos_updated); - bool global_sp_updated; - orb_check(global_setpoint_sub, &global_sp_updated); - if (global_sp_updated) { - global_sp_updated_set_once = true; - } - /* checking has to happen before the read, as the read clears the changed flag */ - - /* get a local copy of system state */ - orb_copy(ORB_ID(vehicle_status), state_sub, &state); - /* get a local copy of manual setpoint */ - orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual); - /* get a local copy of attitude */ - orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); - /* get a local copy of attitude setpoint */ - //orb_copy(ORB_ID(vehicle_attitude_setpoint), att_setpoint_sub, &att_sp); - // XXX update to switch between external attitude reference and the - // attitude calculated here - - char name[10]; - - if (pos_updated) { - - /* get position */ - orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos); - - if (global_sp_updated_set_once) { - orb_copy(ORB_ID(vehicle_global_position_setpoint), global_setpoint_sub, &global_setpoint); - - - /* calculate delta T */ - const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f; - last_run = hrt_absolute_time(); - - /* calculate bearing error */ - float target_bearing = get_bearing_to_next_waypoint(global_pos.lat / (double)1e7d, global_pos.lon / (double)1e7d, - global_setpoint.lat / (double)1e7d, global_setpoint.lon / (double)1e7d); - - /* shift error to prevent wrapping issues */ - float bearing_error = target_bearing - att.yaw; - - if (loopcounter % 2 == 0) { - sprintf(name, "hdng err1"); - memcpy(dbg.key, name, sizeof(name)); - dbg.value = bearing_error; - orb_publish(ORB_ID(debug_key_value), pub_dbg, &dbg); - } - - if (bearing_error < M_PI_F) { - bearing_error += 2.0f * M_PI_F; - } - - if (bearing_error > M_PI_F) { - bearing_error -= 2.0f * M_PI_F; - } - - if (loopcounter % 2 != 0) { - sprintf(name, "hdng err2"); - memcpy(dbg.key, name, sizeof(name)); - dbg.value = bearing_error; - orb_publish(ORB_ID(debug_key_value), pub_dbg, &dbg); - } - - /* calculate roll setpoint, do this artificially around zero */ - att_sp.roll_body = pid_calculate(&heading_controller, bearing_error, - 0.0f, att.yawspeed, deltaT); - - /* limit roll angle output */ - if (att_sp.roll_body > ppos.heading_lim) { - att_sp.roll_body = ppos.heading_lim; - heading_controller.saturated = 1; - } - - if (att_sp.roll_body < -ppos.heading_lim) { - att_sp.roll_body = -ppos.heading_lim; - heading_controller.saturated = 1; - } - - att_sp.pitch_body = 0.0f; - att_sp.yaw_body = 0.0f; - - } else { - /* no setpoint, maintain level flight */ - att_sp.roll_body = 0.0f; - att_sp.pitch_body = 0.0f; - att_sp.yaw_body = 0.0f; - } - - att_sp.thrust = 0.7f; - } - - /* calculate delta T */ - const float deltaTpos = (hrt_absolute_time() - last_run_pos) / 1000000.0f; - last_run_pos = hrt_absolute_time(); - - if (verbose && (loopcounter % 20 == 0)) { - printf("[fixedwing control] roll sp: %8.4f, \n", att_sp.roll_body); - } - - // actuator control[0] is aileron (or elevon roll control) - // Commanded roll rate from P controller on roll angle - float roll_rate_command = pid_calculate(&roll_angle_controller, att_sp.roll_body, - att.roll, 0.0f, deltaTpos); - // actuator control from PI controller on roll rate - actuators.control[0] = pid_calculate(&roll_rate_controller, roll_rate_command, - att.rollspeed, 0.0f, deltaTpos); - - // actuator control[1] is elevator (or elevon pitch control) - // Commanded pitch rate from P controller on pitch angle - float pitch_rate_command = pid_calculate(&pitch_angle_controller, att_sp.pitch_body, - att.pitch, 0.0f, deltaTpos); - // actuator control from PI controller on pitch rate - actuators.control[1] = pid_calculate(&pitch_rate_controller, pitch_rate_command, - att.pitchspeed, 0.0f, deltaTpos); - - // actuator control[3] is throttle - actuators.control[3] = att_sp.thrust; - - /* publish attitude setpoint (for MAVLink) */ - orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); - - /* publish actuator setpoints (for mixer) */ - orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); - - loopcounter++; - - } - } - - printf("[fixedwing_control] exiting.\n"); - thread_running = false; - - return 0; -} - -static void -usage(const char *reason) -{ - if (reason) - fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: fixedwing_control {start|stop|status}\n\n"); - exit(1); -} - -/** - * The deamon app only briefly exists to start - * the background job. The stack size assigned in the - * Makefile does only apply to this management task. - * - * The actual stack size should be set in the call - * to task_create(). - */ -int fixedwing_control_main(int argc, char *argv[]) -{ - if (argc < 1) - usage("missing command"); - - if (!strcmp(argv[1], "start")) { - - if (thread_running) { - printf("fixedwing_control already running\n"); - /* this is not an error */ - exit(0); - } - - thread_should_exit = false; - deamon_task = task_spawn("fixedwing_control", - SCHED_DEFAULT, - SCHED_PRIORITY_MAX - 20, - 4096, - fixedwing_control_thread_main, - (argv) ? (const char **)&argv[2] : (const char **)NULL); - thread_running = true; - exit(0); - } - - if (!strcmp(argv[1], "stop")) { - thread_should_exit = true; - exit(0); - } - - if (!strcmp(argv[1], "status")) { - if (thread_running) { - printf("\tfixedwing_control is running\n"); - } else { - printf("\tfixedwing_control not started\n"); - } - exit(0); - } - - usage("unrecognized command"); - exit(1); -} - -static int att_parameters_init(struct fw_att_control_param_handles *h) -{ - /* PID parameters */ - - h->rollrate_p = param_find("FW_ROLLRATE_P"); - h->rollrate_i = param_find("FW_ROLLRATE_I"); - h->rollrate_awu = param_find("FW_ROLLRATE_AWU"); - h->rollrate_lim = param_find("FW_ROLLRATE_LIM"); - h->roll_p = param_find("FW_ROLL_P"); - h->roll_lim = param_find("FW_ROLL_LIM"); - h->pitchrate_p = param_find("FW_PITCHRATE_P"); - h->pitchrate_i = param_find("FW_PITCHRATE_I"); - h->pitchrate_awu = param_find("FW_PITCHRATE_AWU"); - h->pitchrate_lim = param_find("FW_PITCHRATE_LIM"); - h->pitch_p = param_find("FW_PITCH_P"); - h->pitch_lim = param_find("FW_PITCH_LIM"); - - return OK; -} - -static int att_parameters_update(const struct fw_att_control_param_handles *h, struct fw_att_control_params *p) -{ - param_get(h->rollrate_p, &(p->rollrate_p)); - param_get(h->rollrate_i, &(p->rollrate_i)); - param_get(h->rollrate_awu, &(p->rollrate_awu)); - param_get(h->rollrate_lim, &(p->rollrate_lim)); - param_get(h->roll_p, &(p->roll_p)); - param_get(h->roll_lim, &(p->roll_lim)); - param_get(h->pitchrate_p, &(p->pitchrate_p)); - param_get(h->pitchrate_i, &(p->pitchrate_i)); - param_get(h->pitchrate_awu, &(p->pitchrate_awu)); - param_get(h->pitchrate_lim, &(p->pitchrate_lim)); - param_get(h->pitch_p, &(p->pitch_p)); - param_get(h->pitch_lim, &(p->pitch_lim)); - - return OK; -} - -static int pos_parameters_init(struct fw_pos_control_param_handles *h) -{ - /* PID parameters */ - h->heading_p = param_find("FW_HEADING_P"); - h->heading_lim = param_find("FW_HEADING_LIM"); - - return OK; -} - -static int pos_parameters_update(const struct fw_pos_control_param_handles *h, struct fw_pos_control_params *p) -{ - param_get(h->heading_p, &(p->heading_p)); - param_get(h->heading_lim, &(p->heading_lim)); - - return OK; -} diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig index d32ca5ef7b..ca9f3f4ee3 100644 --- a/nuttx/configs/px4fmu/nsh/appconfig +++ b/nuttx/configs/px4fmu/nsh/appconfig @@ -77,7 +77,6 @@ CONFIGURED_APPS += sensors CONFIGURED_APPS += ardrone_interface CONFIGURED_APPS += multirotor_att_control CONFIGURED_APPS += multirotor_pos_control -#CONFIGURED_APPS += fixedwing_control CONFIGURED_APPS += fixedwing_att_control CONFIGURED_APPS += fixedwing_pos_control CONFIGURED_APPS += position_estimator From 54d624f7c7b5e57d6ec7747056ba2a795ef47dd0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 27 Nov 2012 18:11:48 +0100 Subject: [PATCH 165/206] Added feedforward throttle to pitch compensation, heading from position controller still broken --- .../fixedwing_att_control_att.c | 5 +- .../fixedwing_att_control_main.c | 25 ---------- .../fixedwing_att_control_rate.c | 49 ++++++++++++++----- .../fixedwing_pos_control_main.c | 38 +++++++------- 4 files changed, 59 insertions(+), 58 deletions(-) diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.c b/apps/fixedwing_att_control/fixedwing_att_control_att.c index d27f50b437..957036b415 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_att.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_att.c @@ -152,8 +152,9 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att /* compensate feedforward for loss of lift due to non-horizontal angle of wing */ float pitch_sp_rollcompensation = p.pitch_roll_compensation_p * fabsf(sinf(att_sp->roll_body)); /* set pitch plus feedforward roll compensation */ - rates_sp->pitch = pid_calculate(&pitch_controller, att_sp->pitch_body + pitch_sp_rollcompensation, - att->pitch, 0, 0); + rates_sp->pitch = pid_calculate(&pitch_controller, + att_sp->pitch_body + pitch_sp_rollcompensation, + att->pitch, 0, 0); /* Yaw (from coordinated turn constraint or lateral force) */ rates_sp->yaw = (att->rollspeed * rates_sp->roll + 9.81f * sinf(att->roll) * cosf(att->pitch) + speed_body[0] * rates_sp->pitch * sinf(att->roll)) diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index 8773db9b6c..8ca87ab53f 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -68,31 +68,6 @@ #include #include -/* - * Controller parameters, accessible via MAVLink - * - */ -// Roll control parameters -PARAM_DEFINE_FLOAT(FW_ROLLR_P, 0.9f); -PARAM_DEFINE_FLOAT(FW_ROLLR_I, 0.2f); -PARAM_DEFINE_FLOAT(FW_ROLLR_AWU, 0.9f); -PARAM_DEFINE_FLOAT(FW_ROLLR_LIM, 0.7f); // Roll rate limit in radians/sec, applies to the roll controller -PARAM_DEFINE_FLOAT(FW_ROLL_P, 4.0f); -PARAM_DEFINE_FLOAT(FW_PITCH_RCOMP, 0.1f); - -//Pitch control parameters -PARAM_DEFINE_FLOAT(FW_PITCHR_P, 0.8f); -PARAM_DEFINE_FLOAT(FW_PITCHR_I, 0.2f); -PARAM_DEFINE_FLOAT(FW_PITCHR_AWU, 0.8f); -PARAM_DEFINE_FLOAT(FW_PITCHR_LIM, 0.35f); // Pitch rate limit in radians/sec, applies to the pitch controller -PARAM_DEFINE_FLOAT(FW_PITCH_P, 8.0f); - -//Yaw control parameters //XXX TODO this is copy paste, asign correct values -PARAM_DEFINE_FLOAT(FW_YAWR_P, 0.3f); -PARAM_DEFINE_FLOAT(FW_YAWR_I, 0.0f); -PARAM_DEFINE_FLOAT(FW_YAWR_AWU, 0.0f); -PARAM_DEFINE_FLOAT(FW_YAWR_LIM, 0.35f); // Yaw rate limit in radians/sec - /* Prototypes */ /** * Deamon management function. diff --git a/apps/fixedwing_att_control/fixedwing_att_control_rate.c b/apps/fixedwing_att_control/fixedwing_att_control_rate.c index e8277f3de3..f3e36c0ec3 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_rate.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_rate.c @@ -61,9 +61,33 @@ #include #include +/* + * Controller parameters, accessible via MAVLink + * + */ +// Roll control parameters +PARAM_DEFINE_FLOAT(FW_ROLLR_P, 0.9f); +PARAM_DEFINE_FLOAT(FW_ROLLR_I, 0.2f); +PARAM_DEFINE_FLOAT(FW_ROLLR_AWU, 0.9f); +PARAM_DEFINE_FLOAT(FW_ROLLR_LIM, 0.7f); // Roll rate limit in radians/sec, applies to the roll controller +PARAM_DEFINE_FLOAT(FW_ROLL_P, 4.0f); +PARAM_DEFINE_FLOAT(FW_PITCH_RCOMP, 0.1f); +//Pitch control parameters +PARAM_DEFINE_FLOAT(FW_PITCHR_P, 0.8f); +PARAM_DEFINE_FLOAT(FW_PITCHR_I, 0.2f); +PARAM_DEFINE_FLOAT(FW_PITCHR_AWU, 0.8f); +PARAM_DEFINE_FLOAT(FW_PITCHR_LIM, 0.35f); // Pitch rate limit in radians/sec, applies to the pitch controller +PARAM_DEFINE_FLOAT(FW_PITCH_P, 8.0f); +//Yaw control parameters //XXX TODO this is copy paste, asign correct values +PARAM_DEFINE_FLOAT(FW_YAWR_P, 0.3f); +PARAM_DEFINE_FLOAT(FW_YAWR_I, 0.0f); +PARAM_DEFINE_FLOAT(FW_YAWR_AWU, 0.0f); +PARAM_DEFINE_FLOAT(FW_YAWR_LIM, 0.35f); // Yaw rate limit in radians/sec +/* feedforward compensation */ +PARAM_DEFINE_FLOAT(FW_PITCH_THR_P, 0.1f); /**< throttle to pitch coupling feedforward */ struct fw_rate_control_params { float rollrate_p; @@ -75,7 +99,7 @@ struct fw_rate_control_params { float yawrate_p; float yawrate_i; float yawrate_awu; - + float pitch_thr_ff; }; struct fw_rate_control_param_handles { @@ -88,7 +112,7 @@ struct fw_rate_control_param_handles { param_t yawrate_p; param_t yawrate_i; param_t yawrate_awu; - + param_t pitch_thr_ff; }; @@ -100,17 +124,18 @@ static int parameters_update(const struct fw_rate_control_param_handles *h, stru static int parameters_init(struct fw_rate_control_param_handles *h) { /* PID parameters */ - h->rollrate_p = param_find("FW_ROLLR_P"); //TODO define rate params for fixed wing - h->rollrate_i = param_find("FW_ROLLR_I"); - h->rollrate_awu = param_find("FW_ROLLR_AWU"); + h->rollrate_p = param_find("FW_ROLLR_P"); //TODO define rate params for fixed wing + h->rollrate_i = param_find("FW_ROLLR_I"); + h->rollrate_awu = param_find("FW_ROLLR_AWU"); - h->pitchrate_p = param_find("FW_PITCHR_P"); - h->pitchrate_i = param_find("FW_PITCHR_I"); + h->pitchrate_p = param_find("FW_PITCHR_P"); + h->pitchrate_i = param_find("FW_PITCHR_I"); h->pitchrate_awu = param_find("FW_PITCHR_AWU"); - h->yawrate_p = param_find("FW_YAWR_P"); - h->yawrate_i = param_find("FW_YAWR_I"); - h->yawrate_awu = param_find("FW_YAWR_AWU"); + h->yawrate_p = param_find("FW_YAWR_P"); + h->yawrate_i = param_find("FW_YAWR_I"); + h->yawrate_awu = param_find("FW_YAWR_AWU"); + h->pitch_thr_ff = param_find("FW_PITCH_THR_P"); return OK; } @@ -126,7 +151,7 @@ static int parameters_update(const struct fw_rate_control_param_handles *h, stru param_get(h->yawrate_p, &(p->yawrate_p)); param_get(h->yawrate_i, &(p->yawrate_i)); param_get(h->yawrate_awu, &(p->yawrate_awu)); - + param_get(h->pitch_thr_ff, &(p->pitch_thr_ff)); return OK; } @@ -173,6 +198,8 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp, actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0.0f, deltaT); /* pitch rate (PI) */ actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0.0f, deltaT); + /* set pitch minus feedforward throttle compensation (nose pitches up from throttle */ + actuators->control[1] += (-1.0f) * p.pitch_thr_ff * rate_sp->thrust; /* yaw rate (PI) */ actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0.0f, deltaT); diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c index 5bb794cad5..1d7e9ccd2f 100644 --- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c +++ b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c @@ -75,8 +75,7 @@ PARAM_DEFINE_FLOAT(FW_XTRACK_P, 0.01745f); // Radians per meter off track PARAM_DEFINE_FLOAT(FW_ALT_P, 0.1f); PARAM_DEFINE_FLOAT(FW_ROLL_LIM, 0.7f); // Roll angle limit in radians PARAM_DEFINE_FLOAT(FW_HEADR_P, 0.1f); -PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); // Pitch angle limit in radians - +PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); /**< Pitch angle limit in radians per second */ struct fw_pos_control_params { float heading_p; @@ -98,7 +97,6 @@ struct fw_pos_control_param_handles { param_t altitude_p; param_t roll_lim; param_t pitch_lim; - }; @@ -147,15 +145,14 @@ static int deamon_task; /**< Handle of deamon task / thread */ static int parameters_init(struct fw_pos_control_param_handles *h) { /* PID parameters */ - h->heading_p = param_find("FW_HEAD_P"); - h->headingr_p = param_find("FW_HEADR_P"); - h->headingr_i = param_find("FW_HEADR_I"); + h->heading_p = param_find("FW_HEAD_P"); + h->headingr_p = param_find("FW_HEADR_P"); + h->headingr_i = param_find("FW_HEADR_I"); h->headingr_lim = param_find("FW_HEADR_LIM"); - h->xtrack_p = param_find("FW_XTRACK_P"); - h->altitude_p = param_find("FW_ALT_P"); - h->roll_lim = param_find("FW_ROLL_LIM"); - h->pitch_lim = param_find("FW_PITCH_LIM"); - + h->xtrack_p = param_find("FW_XTRACK_P"); + h->altitude_p = param_find("FW_ALT_P"); + h->roll_lim = param_find("FW_ROLL_LIM"); + h->pitch_lim = param_find("FW_PITCH_LIM"); return OK; } @@ -325,7 +322,8 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) (double)start_pos.lat / (double)1e7d, (double)start_pos.lon / (double)1e7d, (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d); - if(!(distance_res != OK || xtrack_err.past_end)) { + // XXX what is xtrack_err.past_end? + if(distance_res == OK /*&& !xtrack_err.past_end*/) { // printf("xtrack_err.distance %.4f ", (double)xtrack_err.distance); @@ -360,19 +358,17 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) // printf("psi_rate_c %.4f ", (double)psi_rate_c); float psi_rate_e = psi_rate_c - att.yawspeed; - - float psi_rate_e_scaled = psi_rate_e * sqrtf(powf(global_pos.vx, 2.0f) + powf(global_pos.vy, 2.0f)) / 9.81f; //* V_gr / g + float psi_rate_e_scaled = psi_rate_e * sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy) / 9.81f; //* V_gr / g // printf("psi_rate_e_scaled %.4f ", (double)psi_rate_e_scaled); - attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT);\ + attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT); - // printf("rollbody %.4f\n", (double)attitude_setpoint.roll_body); + // printf("rollbody %.4f\n", (double)attitude_setpoint.roll_body); - // if (counter % 100 == 0) - // printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c); - } - else { + if (counter % 100 == 0) + printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c); + } else { if (counter % 100 == 0) printf("distance_res: %d, past_end %d\n", distance_res, xtrack_err.past_end); } @@ -395,6 +391,8 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) /* measure in what intervals the controller runs */ perf_count(fw_interval_perf); + counter++; + } else { // XXX no setpoint, decent default needed (loiter?) } From 520f335b557fdcfbbcdebf967ee02d71c574b353 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 28 Nov 2012 15:02:24 +0100 Subject: [PATCH 166/206] fix for ground speed minimum, untested --- .../fixedwing_pos_control_main.c | 66 +++++++++++-------- 1 file changed, 37 insertions(+), 29 deletions(-) diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c index 1d7e9ccd2f..3cff75a1a3 100644 --- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c +++ b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c @@ -176,13 +176,13 @@ static int parameters_update(const struct fw_pos_control_param_handles *h, struc int fixedwing_pos_control_thread_main(int argc, char *argv[]) { /* read arguments */ - // bool verbose = false; + bool verbose = false; - // for (int i = 1; i < argc; i++) { - // if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) { - // verbose = true; - // } - // } + for (int i = 1; i < argc; i++) { + if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) { + verbose = true; + } + } /* welcome user */ printf("[fixedwing pos control] started\n"); @@ -307,7 +307,9 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) global_sp_updated_set_once = true; psi_track = get_bearing_to_next_waypoint((double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d, (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d); - printf("psi_track: %0.4f\n", (double)psi_track); + + if (verbose) + printf("psi_track: %0.4f\n", (double)psi_track); } /* Simple Horizontal Control */ @@ -325,21 +327,18 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) // XXX what is xtrack_err.past_end? if(distance_res == OK /*&& !xtrack_err.past_end*/) { - // printf("xtrack_err.distance %.4f ", (double)xtrack_err.distance); - float delta_psi_c = pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance - // printf("delta_psi_c %.4f ", (double)delta_psi_c); - float psi_c = psi_track + delta_psi_c; - - // printf("psi_c %.4f ", (double)psi_c); - - // printf("att.yaw %.4f ", (double)att.yaw); - float psi_e = psi_c - att.yaw; - // printf("psi_e %.4f ", (double)psi_e); + if (verbose) { + printf("xtrack_err.distance %.4f ", (double)xtrack_err.distance); + printf("delta_psi_c %.4f ", (double)delta_psi_c); + printf("psi_c %.4f ", (double)psi_c); + printf("att.yaw %.4f ", (double)att.yaw); + printf("psi_e %.4f ", (double)psi_e); + } /* shift error to prevent wrapping issues */ psi_e = _wrap_pi(psi_e); @@ -349,27 +348,36 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) float psi_rate_track = 0; //=V_gr/r_track , this will be needed for implementation of arc following float psi_rate_c = delta_psi_rate_c + psi_rate_track; - //limit turn rate - if(psi_rate_c > p.headingr_lim) - psi_rate_c = p.headingr_lim; - else if(psi_rate_c < -p.headingr_lim) - psi_rate_c = - p.headingr_lim; - - // printf("psi_rate_c %.4f ", (double)psi_rate_c); + /* limit turn rate */ + if(psi_rate_c > p.headingr_lim) { + psi_rate_c = p.headingr_lim; + } else if(psi_rate_c < -p.headingr_lim) { + psi_rate_c = -p.headingr_lim; + } float psi_rate_e = psi_rate_c - att.yawspeed; - float psi_rate_e_scaled = psi_rate_e * sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy) / 9.81f; //* V_gr / g - // printf("psi_rate_e_scaled %.4f ", (double)psi_rate_e_scaled); + // XXX sanity check: Assume 10 m/s stall speed and no stall condition + float ground_speed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy); + + if (ground_speed < 10.0f) { + ground_speed = 10.0f; + } + + float psi_rate_e_scaled = psi_rate_e * ground_speed / 9.81f; //* V_gr / g attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT); - // printf("rollbody %.4f\n", (double)attitude_setpoint.roll_body); + if (verbose) { + printf("psi_rate_c %.4f ", (double)psi_rate_c); + printf("psi_rate_e_scaled %.4f ", (double)psi_rate_e_scaled); + printf("rollbody %.4f\n", (double)attitude_setpoint.roll_body); + } - if (counter % 100 == 0) + if (verbose && counter % 100 == 0) printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c); } else { - if (counter % 100 == 0) + if (verbose && counter % 100 == 0) printf("distance_res: %d, past_end %d\n", distance_res, xtrack_err.past_end); } From 00b79764d795edf2914e4c5dcb6e5eaa00376aee Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 28 Nov 2012 23:00:43 +0100 Subject: [PATCH 167/206] minor code cleanup, not changing functionality --- apps/commander/state_machine_helper.c | 2 +- .../fixedwing_pos_control_main.c | 15 ++++----------- 2 files changed, 5 insertions(+), 12 deletions(-) diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c index 46793c89b0..c6b2465746 100644 --- a/apps/commander/state_machine_helper.c +++ b/apps/commander/state_machine_helper.c @@ -597,7 +597,7 @@ uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_ publish_armed_status(current_status); printf("[commander] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n"); } else if (current_status->state_machine != SYSTEM_STATE_STANDBY) { - mavlink_log_critical(mavlink_fd, "[commander] REJECTING switch to HIL, not in standby.") + mavlink_log_critical(mavlink_fd, "[commander] REJECTING HIL, not in standby.") } /* NEVER actually switch off HIL without reboot */ diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c index 3cff75a1a3..fbd6138def 100644 --- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c +++ b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c @@ -297,19 +297,12 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) if (global_sp_updated) { orb_copy(ORB_ID(vehicle_global_position_setpoint), global_setpoint_sub, &global_setpoint); - // printf("xtrack_err.distance %.4f ", (double)xtrack_err.distance); - - float delta_psi_c = pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance - - // printf("delta_psi_c %.4f ", (double)delta_psi_c); - start_pos = global_pos; //for now using the current position as the startpoint (= approx. last waypoint because the setpoint switch occurs at the waypoint) global_sp_updated_set_once = true; psi_track = get_bearing_to_next_waypoint((double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d, (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d); - if (verbose) - printf("psi_track: %0.4f\n", (double)psi_track); + printf("next wp direction: %0.4f\n", (double)psi_track); } /* Simple Horizontal Control */ @@ -331,6 +324,9 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) float psi_c = psi_track + delta_psi_c; float psi_e = psi_c - att.yaw; + + /* wrap difference back onto -pi..pi range */ + psi_e = _wrap_pi(psi_e); if (verbose) { printf("xtrack_err.distance %.4f ", (double)xtrack_err.distance); @@ -340,9 +336,6 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[]) printf("psi_e %.4f ", (double)psi_e); } - /* shift error to prevent wrapping issues */ - psi_e = _wrap_pi(psi_e); - /* calculate roll setpoint, do this artificially around zero */ float delta_psi_rate_c = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f); float psi_rate_track = 0; //=V_gr/r_track , this will be needed for implementation of arc following From aa1d57c08549f9c75582e5608b93adc5254b04a4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Dec 2012 16:28:53 +0100 Subject: [PATCH 168/206] Allowed mode switching via command --- apps/commander/state_machine_helper.c | 35 +++++++++++++++++---------- 1 file changed, 22 insertions(+), 13 deletions(-) diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c index c6b2465746..aa916dafa3 100644 --- a/apps/commander/state_machine_helper.c +++ b/apps/commander/state_machine_helper.c @@ -565,6 +565,28 @@ uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_ { printf("[commander] Requested new mode: %d\n", (int)mode); uint8_t ret = 1; + + /* Switch on HIL if in standby and not already in HIL mode */ + if ((current_status->state_machine == SYSTEM_STATE_STANDBY) && (mode & VEHICLE_MODE_FLAG_HIL_ENABLED) + && !current_status->flag_hil_enabled) { + /* Enable HIL on request */ + current_status->flag_hil_enabled = true; + ret = OK; + state_machine_publish(status_pub, current_status, mavlink_fd); + publish_armed_status(current_status); + printf("[commander] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n"); + } else if (current_status->state_machine != SYSTEM_STATE_STANDBY) { + mavlink_log_critical(mavlink_fd, "[commander] REJECTING HIL, not in standby.") + } + + /* switch manual / auto */ + if (mode & VEHICLE_MODE_FLAG_AUTO_ENABLED) { + update_state_machine_mode_auto(status_pub, current_status, mavlink_fd); + } else if (mode & VEHICLE_MODE_FLAG_STABILIZED_ENABLED) { + update_state_machine_mode_stabilized(status_pub, current_status, mavlink_fd); + } else if (mode & VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED) { + update_state_machine_mode_manual(status_pub, current_status, mavlink_fd); + } /* vehicle is disarmed, mode requests arming */ if (!(current_status->flag_system_armed) && (mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) { @@ -587,19 +609,6 @@ uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_ } } - /* Switch on HIL if in standby and not already in HIL mode */ - if ((current_status->state_machine == SYSTEM_STATE_STANDBY) && (mode & VEHICLE_MODE_FLAG_HIL_ENABLED) - && !current_status->flag_hil_enabled) { - /* Enable HIL on request */ - current_status->flag_hil_enabled = true; - ret = OK; - state_machine_publish(status_pub, current_status, mavlink_fd); - publish_armed_status(current_status); - printf("[commander] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n"); - } else if (current_status->state_machine != SYSTEM_STATE_STANDBY) { - mavlink_log_critical(mavlink_fd, "[commander] REJECTING HIL, not in standby.") - } - /* NEVER actually switch off HIL without reboot */ if (current_status->flag_hil_enabled && !(mode & VEHICLE_MODE_FLAG_HIL_ENABLED)) { fprintf(stderr, "[commander] DENYING request to switch of HIL. Please power cycle (safety reasons)\n"); From 2bfb6727912e804325e5a512c9c09d36e8fe06d3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Dec 2012 16:29:06 +0100 Subject: [PATCH 169/206] Cleaned up mode indication --- apps/mavlink/mavlink.c | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index 77034914ff..575b42b37b 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -189,10 +189,6 @@ get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_mode) *mavlink_mode = 0; /* set mode flags independent of system state */ - if (v_status.flag_control_manual_enabled) { - *mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; - } - if (v_status.flag_hil_enabled) { *mavlink_mode |= MAV_MODE_FLAG_HIL_ENABLED; } @@ -231,11 +227,14 @@ get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_mode) case SYSTEM_STATE_STABILIZED: *mavlink_state = MAV_STATE_ACTIVE; *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED; + *mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED; break; case SYSTEM_STATE_AUTO: *mavlink_state = MAV_STATE_ACTIVE; *mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED; + *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED; + *mavlink_mode |= MAV_MODE_FLAG_AUTO_ENABLED; break; case SYSTEM_STATE_MISSION_ABORT: From 126e6ac2073ffb96c3867e7cbdd4e51e8408d0ec Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Dec 2012 16:30:21 +0100 Subject: [PATCH 170/206] Enabled manual override switch, work in progress. Added initial demix testing code to support delta mixing on the remote for convenient manual override --- apps/px4io/comms.c | 4 +- apps/px4io/controls.c | 21 +++++++- apps/px4io/mixer.c | 5 +- apps/px4io/px4io.h | 31 ++++++++--- apps/px4io/safety.c | 2 +- apps/sensors/sensor_params.c | 2 + apps/sensors/sensors.cpp | 86 ++++++++++++++++++++++--------- apps/uORB/topics/vehicle_status.h | 2 +- 8 files changed, 113 insertions(+), 40 deletions(-) diff --git a/apps/px4io/comms.c b/apps/px4io/comms.c index 40ea38cf74..f4eddbdd3b 100644 --- a/apps/px4io/comms.c +++ b/apps/px4io/comms.c @@ -177,13 +177,13 @@ comms_handle_command(const void *buffer, size_t length) for (unsigned i = 0; i < PX4IO_OUTPUT_CHANNELS; i++) system_state.fmu_channel_data[i] = cmd->servo_command[i]; - /* if the IO is armed and the FMU gets disarmed, the IO must also disarm */ + /* if the IO is armed and FMU gets disarmed, IO must also disarm */ if(system_state.arm_ok && !cmd->arm_ok) { system_state.armed = false; } system_state.arm_ok = cmd->arm_ok; - system_state.mixer_use_fmu = true; + system_state.mixer_fmu_available = true; system_state.fmu_data_received = true; diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c index d4eace3df5..0e02103731 100644 --- a/apps/px4io/controls.c +++ b/apps/px4io/controls.c @@ -59,6 +59,10 @@ #define DEBUG #include "px4io.h" +#define RC_FAILSAFE_TIMEOUT 2000000 /**< two seconds failsafe timeout */ +#define RC_CHANNEL_HIGH_THRESH 1600 +#define RC_CHANNEL_LOW_THRESH 1400 + void controls_main(void) { @@ -80,7 +84,22 @@ controls_main(void) if (fds[1].revents & POLLIN) sbus_input(); - /* XXX do ppm processing, bypass mode, etc. here */ + /* force manual input override */ + if (system_state.rc_channel_data[4] > RC_CHANNEL_HIGH_THRESH) { + system_state.mixer_use_fmu = false; + } else { + /* override not engaged, use FMU */ + system_state.mixer_use_fmu = true; + } + + /* detect rc loss event */ + if (hrt_absolute_time() - system_state.rc_channels_timestamp > RC_FAILSAFE_TIMEOUT) { + system_state.rc_lost = true; + } + + /* XXX detect fmu loss event */ + + /* XXX handle failsave events - RC loss and FMU loss - here */ /* do PWM output updates */ mixer_tick(); diff --git a/apps/px4io/mixer.c b/apps/px4io/mixer.c index 483e9fe4d4..d9626c1e3f 100644 --- a/apps/px4io/mixer.c +++ b/apps/px4io/mixer.c @@ -97,7 +97,7 @@ mixer_tick(void) /* * Decide which set of inputs we're using. */ - if (system_state.mixer_use_fmu) { + if (system_state.mixer_use_fmu && system_state.mixer_fmu_available) { /* we have recent control data from the FMU */ control_count = PX4IO_OUTPUT_CHANNELS; control_values = &system_state.fmu_channel_data[0]; @@ -141,9 +141,10 @@ mixer_tick(void) /* * Decide whether the servos should be armed right now. + * A sufficient reason is armed state and either FMU or RC control inputs */ - should_arm = system_state.armed && system_state.arm_ok && (control_count > 0) && system_state.mixer_use_fmu; + should_arm = system_state.armed && system_state.arm_ok && (control_count > 0); if (should_arm && !mixer_servos_armed) { /* need to arm, but not armed */ up_pwm_servo_arm(true); diff --git a/apps/px4io/px4io.h b/apps/px4io/px4io.h index 483b9bcc81..9bfe3b1e4d 100644 --- a/apps/px4io/px4io.h +++ b/apps/px4io/px4io.h @@ -76,43 +76,58 @@ struct sys_state_s bool dsm_input_ok; /* valid Spektrum DSM data */ bool sbus_input_ok; /* valid Futaba S.Bus data */ - /* + /** * Data from the remote control input(s) */ int rc_channels; uint16_t rc_channel_data[PX4IO_INPUT_CHANNELS]; uint64_t rc_channels_timestamp; - /* + /** * Control signals from FMU. */ uint16_t fmu_channel_data[PX4IO_OUTPUT_CHANNELS]; - /* + /** * Relay controls */ bool relays[PX4IO_RELAY_CHANNELS]; - /* - * If true, we are using the FMU controls. + /** + * If true, we are using the FMU controls, else RC input if available. */ bool mixer_use_fmu; - /* + /** + * If true, FMU input is available. + */ + bool mixer_fmu_available; + + /** * If true, state that should be reported to FMU has been updated. */ bool fmu_report_due; - /* + /** * If true, new control data from the FMU has been received. */ bool fmu_data_received; - /* + /** * Current serial interface mode, per the serial_rx_mode parameter * in the config packet. */ uint8_t serial_rx_mode; + + /** + * If true, the RC signal has been lost for more than a timeout interval + */ + bool rc_lost; + + /** + * If true, the connection to FMU has been lost for more than a timeout interval + */ + bool fmu_lost; }; extern struct sys_state_s system_state; diff --git a/apps/px4io/safety.c b/apps/px4io/safety.c index d5bd103c10..916988af16 100644 --- a/apps/px4io/safety.c +++ b/apps/px4io/safety.c @@ -58,7 +58,7 @@ static struct hrt_call failsafe_call; * Count the number of times in a row that we see the arming button * held down. */ -static unsigned counter; +static unsigned counter = 0; #define ARM_COUNTER_THRESHOLD 10 #define DISARM_COUNTER_THRESHOLD 2 diff --git a/apps/sensors/sensor_params.c b/apps/sensors/sensor_params.c index c83d6358e0..37ba0ec3ef 100644 --- a/apps/sensors/sensor_params.c +++ b/apps/sensors/sensor_params.c @@ -122,6 +122,8 @@ PARAM_DEFINE_FLOAT(RC8_EXP, 0.0f); PARAM_DEFINE_INT32(RC_TYPE, 1); // 1 = FUTABA +PARAM_DEFINE_INT32(RC_DEMIX, 0); /**< 0 = off, 1 = auto, 2 = delta */ + /* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */ PARAM_DEFINE_FLOAT(BAT_V_SCALING, (3.3f * 52.0f / 5.0f / 4095.0f)); diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index 71feb377b2..b63bfb195a 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -95,6 +95,12 @@ #define PPM_INPUT_TIMEOUT_INTERVAL 50000 /**< 50 ms timeout / 20 Hz */ +enum RC_DEMIX { + RC_DEMIX_NONE = 0, + RC_DEMIX_AUTO = 1, + RC_DEMIX_DELTA = 2 +}; + /** * Sensor app start / stop handling function * @@ -178,6 +184,8 @@ private: int rc_type; + int rc_demix; /**< enabled de-mixing of RC mixers */ + int rc_map_roll; int rc_map_pitch; int rc_map_yaw; @@ -204,6 +212,8 @@ private: param_t ex[_rc_max_chan_count]; param_t rc_type; + param_t rc_demix; + param_t gyro_offset[3]; param_t accel_offset[3]; param_t accel_scale[3]; @@ -392,6 +402,8 @@ Sensors::Sensors() : _parameter_handles.rc_type = param_find("RC_TYPE"); + _parameter_handles.rc_demix = param_find("RC_DEMIX"); + _parameter_handles.rc_map_roll = param_find("RC_MAP_ROLL"); _parameter_handles.rc_map_pitch = param_find("RC_MAP_PITCH"); _parameter_handles.rc_map_yaw = param_find("RC_MAP_YAW"); @@ -496,21 +508,16 @@ Sensors::parameters_update() } - /* update RC function mappings */ - _rc.function[THROTTLE] = _parameters.rc_map_throttle - 1; - _rc.function[ROLL] = _parameters.rc_map_roll - 1; - _rc.function[PITCH] = _parameters.rc_map_pitch - 1; - _rc.function[YAW] = _parameters.rc_map_yaw - 1; - _rc.function[OVERRIDE] = _parameters.rc_map_mode_sw - 1; - _rc.function[FUNC_0] = _parameters.rc_map_aux1 - 1; - _rc.function[FUNC_1] = _parameters.rc_map_aux2 - 1; - _rc.function[FUNC_2] = _parameters.rc_map_aux3 - 1; - /* remote control type */ if (param_get(_parameter_handles.rc_type, &(_parameters.rc_type)) != OK) { warnx("Failed getting remote control type"); } + /* de-mixing */ + if (param_get(_parameter_handles.rc_demix, &(_parameters.rc_demix)) != OK) { + warnx("Failed getting demix setting"); + } + /* channel mapping */ if (param_get(_parameter_handles.rc_map_roll, &(_parameters.rc_map_roll)) != OK) { warnx("Failed getting roll chan index"); @@ -547,6 +554,16 @@ Sensors::parameters_update() warnx("Failed getting rc scaling for yaw"); } + /* update RC function mappings */ + _rc.function[THROTTLE] = _parameters.rc_map_throttle - 1; + _rc.function[ROLL] = _parameters.rc_map_roll - 1; + _rc.function[PITCH] = _parameters.rc_map_pitch - 1; + _rc.function[YAW] = _parameters.rc_map_yaw - 1; + _rc.function[OVERRIDE] = _parameters.rc_map_mode_sw - 1; + _rc.function[FUNC_0] = _parameters.rc_map_aux1 - 1; + _rc.function[FUNC_1] = _parameters.rc_map_aux2 - 1; + _rc.function[FUNC_2] = _parameters.rc_map_aux3 - 1; + /* gyro offsets */ param_get(_parameter_handles.gyro_offset[0], &(_parameters.gyro_offset[0])); param_get(_parameter_handles.gyro_offset[1], &(_parameters.gyro_offset[1])); @@ -905,7 +922,7 @@ Sensors::ppm_poll() */ if (ppm_decoded_channels > 4 && hrt_absolute_time() - _ppm_last_valid < PPM_INPUT_TIMEOUT_INTERVAL) { - for (int i = 0; i < ppm_decoded_channels; i++) { + for (unsigned int i = 0; i < ppm_decoded_channels; i++) { raw.values[i] = ppm_buffer[i]; } @@ -979,35 +996,54 @@ Sensors::ppm_poll() manual_control.timestamp = rc_input.timestamp; - /* roll input - rolling right is stick-wise and rotation-wise positive */ - manual_control.roll = _rc.chan[_rc.function[ROLL]].scaled; + /* check if input needs to be de-mixed */ + if (_parameters.rc_demix == (int)RC_DEMIX_DELTA) { + // XXX hardcoded for testing purposes, replace with inverted delta mixer from ROMFS + + /* roll input - mixed roll and pitch channels */ + manual_control.roll = _rc.chan[_rc.function[ROLL]].scaled - _rc.chan[_rc.function[PITCH]].scaled; + /* pitch input - mixed roll and pitch channels */ + manual_control.pitch = -0.5f * (_rc.chan[_rc.function[ROLL]].scaled + _rc.chan[_rc.function[PITCH]].scaled); + /* yaw input - stick right is positive and positive rotation */ + manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled; + /* throttle input */ + manual_control.throttle = _rc.chan[_rc.function[THROTTLE]].scaled; + + /* direct pass-through of manual input */ + } else { + /* roll input - rolling right is stick-wise and rotation-wise positive */ + manual_control.roll = _rc.chan[_rc.function[ROLL]].scaled; + /* + * pitch input - stick down is negative, but stick down is pitching up (pos) in NED, + * so reverse sign. + */ + manual_control.pitch = -1.0f * _rc.chan[_rc.function[PITCH]].scaled; + /* yaw input - stick right is positive and positive rotation */ + manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled; + /* throttle input */ + manual_control.throttle = _rc.chan[_rc.function[THROTTLE]].scaled; + } + + /* limit outputs */ if (manual_control.roll < -1.0f) manual_control.roll = -1.0f; if (manual_control.roll > 1.0f) manual_control.roll = 1.0f; - if (!isnan(_parameters.rc_scale_roll) || !isinf(_parameters.rc_scale_roll)) { + if (isfinite(_parameters.rc_scale_roll) && _parameters.rc_scale_roll > 0.0f) { manual_control.roll *= _parameters.rc_scale_roll; } - /* - * pitch input - stick down is negative, but stick down is pitching up (pos) in NED, - * so reverse sign. - */ - manual_control.pitch = -1.0f * _rc.chan[_rc.function[PITCH]].scaled; + if (manual_control.pitch < -1.0f) manual_control.pitch = -1.0f; if (manual_control.pitch > 1.0f) manual_control.pitch = 1.0f; - if (!isnan(_parameters.rc_scale_pitch) || !isinf(_parameters.rc_scale_pitch)) { + if (isfinite(_parameters.rc_scale_pitch) && _parameters.rc_scale_pitch > 0.0f) { manual_control.pitch *= _parameters.rc_scale_pitch; } - /* yaw input - stick right is positive and positive rotation */ - manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled; if (manual_control.yaw < -1.0f) manual_control.yaw = -1.0f; if (manual_control.yaw > 1.0f) manual_control.yaw = 1.0f; - if (!isnan(_parameters.rc_scale_yaw) || !isinf(_parameters.rc_scale_yaw)) { + if (isfinite(_parameters.rc_scale_yaw) && _parameters.rc_scale_yaw > 0.0f) { manual_control.yaw *= _parameters.rc_scale_yaw; } - /* throttle input */ - manual_control.throttle = _rc.chan[_rc.function[THROTTLE]].scaled; if (manual_control.throttle < 0.0f) manual_control.throttle = 0.0f; if (manual_control.throttle > 1.0f) manual_control.throttle = 1.0f; diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h index 23172d7cf1..b70b322d8d 100644 --- a/apps/uORB/topics/vehicle_status.h +++ b/apps/uORB/topics/vehicle_status.h @@ -79,7 +79,7 @@ enum VEHICLE_MODE_FLAG { VEHICLE_MODE_FLAG_SAFETY_ARMED = 128, VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED = 64, VEHICLE_MODE_FLAG_HIL_ENABLED = 32, - VEHICLE_MODE_FLAG_STABILIZE_ENABLED = 16, + VEHICLE_MODE_FLAG_STABILIZED_ENABLED = 16, VEHICLE_MODE_FLAG_GUIDED_ENABLED = 8, VEHICLE_MODE_FLAG_AUTO_ENABLED = 4, VEHICLE_MODE_FLAG_TEST_ENABLED = 2, From 03076a72ca75917cf62d7889c6c6d0de36866b04 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 13 Dec 2012 10:23:02 +0100 Subject: [PATCH 171/206] Added required additional fields: If system is ok to launch (required for LED indicator), if system is ok to override fully by RC (required for multirotors which should not support this), desired PWM output rate in Hz (again required for some multirotors). --- apps/commander/commander.c | 94 ++++++++++++++- apps/drivers/px4fmu/fmu.cpp | 10 +- apps/drivers/px4io/px4io.cpp | 108 ++++++++++++++++-- .../fixedwing_att_control_main.c | 55 +++++++-- apps/mavlink/mavlink_receiver.c | 24 +++- apps/px4io/comms.c | 40 ++++--- apps/px4io/controls.c | 36 ++++++ apps/px4io/mixer.c | 14 ++- apps/px4io/protocol.h | 9 +- apps/px4io/px4io.c | 2 + apps/px4io/px4io.h | 31 ++++- apps/px4io/safety.c | 13 ++- apps/uORB/topics/vehicle_status.h | 7 +- 13 files changed, 390 insertions(+), 53 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 7277e9fa4c..310a707aa9 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -72,10 +72,12 @@ #include #include #include -#include +#include +#include #include #include #include +#include #include #include @@ -1167,6 +1169,8 @@ int commander_thread_main(int argc, char *argv[]) failsafe_lowlevel_timeout_ms = 0; param_get(param_find("SYS_FAILSAVE_LL"), &failsafe_lowlevel_timeout_ms); + param_t _param_sys_type = param_find("MAV_TYPE"); + /* welcome user */ printf("[commander] I am in command now!\n"); @@ -1199,6 +1203,8 @@ int commander_thread_main(int argc, char *argv[]) /* mark all signals lost as long as they haven't been found */ current_status.rc_signal_lost = true; current_status.offboard_control_signal_lost = true; + /* allow manual override initially */ + current_status.flag_external_manual_override_ok = true; /* advertise to ORB */ stat_pub = orb_advertise(ORB_ID(vehicle_status), ¤t_status); @@ -1249,9 +1255,15 @@ int commander_thread_main(int argc, char *argv[]) struct offboard_control_setpoint_s sp_offboard; memset(&sp_offboard, 0, sizeof(sp_offboard)); - int gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); - struct vehicle_gps_position_s gps; - memset(&gps, 0, sizeof(gps)); + int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position)); + struct vehicle_global_position_s global_position; + memset(&global_position, 0, sizeof(global_position)); + uint64_t last_global_position_time = 0; + + int local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position)); + struct vehicle_local_position_s local_position; + memset(&local_position, 0, sizeof(local_position)); + uint64_t last_local_position_time = 0; int sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); struct sensor_combined_s sensors; @@ -1262,6 +1274,11 @@ int commander_thread_main(int argc, char *argv[]) struct vehicle_command_s cmd; memset(&cmd, 0, sizeof(cmd)); + /* Subscribe to parameters changed topic */ + int param_changed_sub = orb_subscribe(ORB_ID(parameter_update)); + struct parameter_update_s param_changed; + memset(¶m_changed, 0, sizeof(param_changed)); + // uint8_t vehicle_state_previous = current_status.state_machine; float voltage_previous = 0.0f; @@ -1288,7 +1305,6 @@ int commander_thread_main(int argc, char *argv[]) if (new_data) { orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard); } - orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps); orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors); orb_check(cmd_sub, &new_data); @@ -1300,6 +1316,46 @@ int commander_thread_main(int argc, char *argv[]) handle_command(stat_pub, ¤t_status, &cmd); } + /* update parameters */ + orb_check(param_changed_sub, &new_data); + if (new_data) { + /* parameters changed */ + orb_copy(ORB_ID(parameter_update), param_changed_sub, ¶m_changed); + + /* update parameters */ + if (!current_status.flag_system_armed) { + current_status.system_type = param_get(_param_sys_type, &(current_status.system_type)); + + /* disable manual override for all systems that rely on electronic stabilization */ + if (current_status.system_type == MAV_TYPE_QUADROTOR || + current_status.system_type == MAV_TYPE_HEXAROTOR || + current_status.system_type == MAV_TYPE_OCTOROTOR) { + current_status.flag_external_manual_override_ok = false; + } else { + current_status.flag_external_manual_override_ok = true; + } + printf("param changed, val: %d, override: %s\n", current_status.system_type, (current_status.flag_external_manual_override_ok) ? "ON" : "OFF"); + } else { + printf("ARMED, rejecting sys type change\n"); + } + } + + /* update global position estimate */ + orb_check(global_position_sub, &new_data); + if (new_data) { + /* position changed */ + orb_copy(ORB_ID(vehicle_global_position), global_position_sub, &global_position); + last_global_position_time = global_position.timestamp; + } + + /* update local position estimate */ + orb_check(local_position_sub, &new_data); + if (new_data) { + /* position changed */ + orb_copy(ORB_ID(vehicle_local_position), local_position_sub, &local_position); + last_local_position_time = local_position.timestamp; + } + battery_voltage = sensors.battery_voltage_v; battery_voltage_valid = sensors.battery_voltage_valid; @@ -1406,6 +1462,32 @@ int commander_thread_main(int argc, char *argv[]) /* End battery voltage check */ + bool vector_flight_mode_ok = current_status.flag_vector_flight_mode_ok; + bool global_pos_valid = current_status.flag_global_position_valid; + bool local_pos_valid = current_status.flag_local_position_valid; + + /* check for global or local position updates, set a timeout of 2s */ + if (hrt_absolute_time() - last_global_position_time < 2000000) { + current_status.flag_vector_flight_mode_ok = true; + current_status.flag_global_position_valid = true; + // XXX check for controller status and home position as well + } + + if (hrt_absolute_time() - last_local_position_time < 2000000) { + current_status.flag_vector_flight_mode_ok = true; + current_status.flag_local_position_valid = true; + // XXX check for controller status and home position as well + } + + /* consolidate state change, flag as changed if required */ + if (vector_flight_mode_ok != current_status.flag_vector_flight_mode_ok || + global_pos_valid != current_status.flag_global_position_valid || + local_pos_valid != current_status.flag_local_position_valid) { + state_changed = true; + } + + + /* Check if last transition deserved an audio event */ // #warning This code depends on state that is no longer? maintained // #if 0 @@ -1669,7 +1751,7 @@ int commander_thread_main(int argc, char *argv[]) buzzer_deinit(); close(sp_man_sub); close(sp_offboard_sub); - close(gps_sub); + close(global_position_sub); close(sensor_sub); close(cmd_sub); diff --git a/apps/drivers/px4fmu/fmu.cpp b/apps/drivers/px4fmu/fmu.cpp index 61dd418f86..d5c50fbf0f 100644 --- a/apps/drivers/px4fmu/fmu.cpp +++ b/apps/drivers/px4fmu/fmu.cpp @@ -331,8 +331,16 @@ PX4FMU::task_main() /* handle update rate changes */ if (_current_update_rate != _update_rate) { int update_rate_in_ms = int(1000 / _update_rate); - if (update_rate_in_ms < 2) + /* reject faster than 500 Hz updates */ + if (update_rate_in_ms < 2) { update_rate_in_ms = 2; + _update_rate = 500; + } + /* reject slower than 50 Hz updates */ + if (update_rate_in_ms > 20) { + update_rate_in_ms = 20; + _update_rate = 50; + } orb_set_interval(_t_actuators, update_rate_in_ms); up_pwm_servo_set_rate(_update_rate); _current_update_rate = _update_rate; diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index 456564ba73..868d53cfd7 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -55,6 +55,7 @@ #include #include #include +#include #include @@ -72,6 +73,7 @@ #include #include +#include #include #include @@ -88,8 +90,17 @@ public: virtual int ioctl(file *filp, int cmd, unsigned long arg); + /** + * Set the PWM via serial update rate + * @warning this directly affects CPU load + */ + int set_pwm_rate(int hz); + + bool dump_one; + private: static const unsigned _max_actuators = PX4IO_OUTPUT_CHANNELS; + int _update_rate; ///< serial send rate in Hz int _serial_fd; ///< serial interface to PX4IO hx_stream_t _io_stream; ///< HX protocol stream @@ -103,6 +114,8 @@ private: int _t_armed; ///< system armed control topic actuator_armed_s _armed; ///< system armed state + int _t_vstatus; ///< system / vehicle status + vehicle_status_s _vstatus; ///< overall system state orb_advert_t _to_input_rc; ///< rc inputs from io rc_input_values _input_rc; ///< rc input values @@ -175,6 +188,8 @@ PX4IO *g_dev; PX4IO::PX4IO() : CDev("px4io", "/dev/px4io"), + dump_one(false), + _update_rate(50), _serial_fd(-1), _io_stream(nullptr), _task(-1), @@ -182,6 +197,7 @@ PX4IO::PX4IO() : _connected(false), _t_actuators(-1), _t_armed(-1), + _t_vstatus(-1), _t_outputs(-1), _mixers(nullptr), _primary_pwm_device(false), @@ -256,6 +272,17 @@ PX4IO::init() return OK; } +int +PX4IO::set_pwm_rate(int hz) +{ + if (hz > 0 && hz <= 400) { + _update_rate = hz; + return OK; + } else { + return -EINVAL; + } +} + void PX4IO::task_main_trampoline(int argc, char *argv[]) { @@ -266,6 +293,7 @@ void PX4IO::task_main() { log("starting"); + int update_rate_in_ms; /* open the serial port */ _serial_fd = ::open("/dev/ttyS2", O_RDWR); @@ -303,12 +331,20 @@ PX4IO::task_main() _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_1)); /* convert the update rate in hz to milliseconds, rounding down if necessary */ - //int update_rate_in_ms = int(1000 / _update_rate); - orb_set_interval(_t_actuators, 20); /* XXX 50Hz hardcoded for now */ + update_rate_in_ms = int(1000 / _update_rate); + orb_set_interval(_t_actuators, update_rate_in_ms); _t_armed = orb_subscribe(ORB_ID(actuator_armed)); orb_set_interval(_t_armed, 200); /* 5Hz update rate */ + _t_vstatus = orb_subscribe(ORB_ID(vehicle_status)); + orb_set_interval(_t_vstatus, 200); /* 5Hz update rate max. */ + + /* advertise the limited control inputs */ + memset(&_controls_effective, 0, sizeof(_controls_effective)); + _t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_1), + &_controls_effective); + /* advertise the mixed control outputs */ memset(&_outputs, 0, sizeof(_outputs)); _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), @@ -319,13 +355,15 @@ PX4IO::task_main() _to_input_rc = orb_advertise(ORB_ID(input_rc), &_input_rc); /* poll descriptor */ - pollfd fds[3]; + pollfd fds[4]; fds[0].fd = _serial_fd; fds[0].events = POLLIN; fds[1].fd = _t_actuators; fds[1].events = POLLIN; fds[2].fd = _t_armed; fds[2].events = POLLIN; + fds[3].fd = _t_vstatus; + fds[3].events = POLLIN; log("ready"); @@ -354,7 +392,8 @@ PX4IO::task_main() if (fds[1].revents & POLLIN) { /* get controls */ - orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls); + orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : + ORB_ID(actuator_controls_1), _t_actuators, &_controls); /* mix */ if (_mixers != nullptr) { @@ -362,8 +401,19 @@ PX4IO::task_main() _mixers->mix(&_outputs.output[0], _max_actuators); /* convert to PWM values */ - for (unsigned i = 0; i < _max_actuators; i++) - _outputs.output[i] = 1500 + (600 * _outputs.output[i]); + for (unsigned i = 0; i < _max_actuators; i++) { + /* last resort: catch NaN, INF and out-of-band errors */ + if (isfinite(_outputs.output[i]) && _outputs.output[i] >= -1.0f && _outputs.output[i] <= 1.0f) { + _outputs.output[i] = 1500 + (600 * _outputs.output[i]); + } else { + /* + * Value is NaN, INF or out of band - set to the minimum value. + * This will be clearly visible on the servo status and will limit the risk of accidentally + * spinning motors. It would be deadly in flight. + */ + _outputs.output[i] = 900; + } + } /* and flag for update */ _send_needed = true; @@ -375,6 +425,11 @@ PX4IO::task_main() orb_copy(ORB_ID(actuator_armed), _t_armed, &_armed); _send_needed = true; } + + if (fds[3].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_status), _t_vstatus, &_vstatus); + _send_needed = true; + } } /* send an update to IO if required */ @@ -499,8 +554,14 @@ PX4IO::io_send() // XXX relays - /* armed and not locked down */ + /* armed and not locked down -> arming ok */ cmd.arm_ok = (_armed.armed && !_armed.lockdown); + /* indicate that full autonomous position control / vector flight mode is available */ + cmd.vector_flight_mode_ok = _vstatus.flag_vector_flight_mode_ok; + /* allow manual override on IO (not allowed for multirotors or other systems with SAS) */ + cmd.manual_override_ok = _vstatus.flag_external_manual_override_ok; + /* set desired PWM output rate */ + cmd.servo_rate = _update_rate; ret = hx_stream_send(_io_stream, &cmd, sizeof(cmd)); if (ret) @@ -665,6 +726,29 @@ test(void) exit(0); } +void +monitor(void) +{ + unsigned cancels = 3; + printf("Hit three times to exit monitor mode\n"); + + for (;;) { + pollfd fds[1]; + + fds[0].fd = 0; + fds[0].events = POLLIN; + poll(fds, 1, 500); + + if (fds[0].revents == POLLIN) { + int c; + read(0, &c, 1); + if (cancels-- == 0) + exit(0); + } + + if (g_dev != nullptr) + g_dev->dump_one = true; + } } int @@ -686,6 +770,16 @@ px4io_main(int argc, char *argv[]) errx(1, "driver init failed"); } + /* look for the optional pwm update rate for the supported modes */ + if (strcmp(argv[2], "-u") == 0 || strcmp(argv[2], "--update-rate") == 0) { + if (argc > 2 + 1) { + g_dev->set_pwm_rate(atoi(argv[2 + 1])); + } else { + fprintf(stderr, "missing argument for pwm update rate (-u)\n"); + return 1; + } + } + exit(0); } diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index 38f58ac33a..479ffd9a36 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -182,15 +182,45 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) gyro[1] = att.pitchspeed; gyro[2] = att.yawspeed; - /* Control */ + /* control */ if (vstatus.state_machine == SYSTEM_STATE_AUTO) { - /* Attitude Control */ - fixedwing_att_control_attitude(&att_sp, - &att, - &rates_sp); + /* attitude control */ + fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp); + /* publish rate setpoint */ + orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp); - /* Attitude Rate Control */ + /* angular rate control */ + fixedwing_att_control_rates(&rates_sp, gyro, &actuators); + + /* pass through throttle */ + actuators.control[3] = att_sp.thrust; + + } else if (vstatus.state_machine == SYSTEM_STATE_STABILIZED) { + + /* if the RC signal is lost, try to stay level and go slowly back down to ground */ + if(vstatus.rc_signal_lost) { + + // XXX define failsafe throttle param + //param_get(failsafe_throttle_handle, &failsafe_throttle); + att_sp.roll_body = 0.3f; + att_sp.pitch_body = 0.0f; + att_sp.thrust = 0.5f; + + // XXX disable yaw control, loiter + + } else { + + att_sp.roll_body = manual_sp.roll; + att_sp.pitch_body = manual_sp.pitch; + att_sp.yaw_body = 0; + att_sp.thrust = manual_sp.throttle; + att_sp.timestamp = hrt_absolute_time(); + } + + fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp); + + /* angular rate control */ fixedwing_att_control_rates(&rates_sp, gyro, &actuators); //REMOVEME XXX @@ -207,8 +237,17 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) actuators.control[3] = manual_sp.throttle; } - /* publish output */ - orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); + /* publish rates */ + orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp); + + /* sanity check and publish actuator outputs */ + if (isfinite(actuators.control[0]) && + isfinite(actuators.control[1]) && + isfinite(actuators.control[2]) && + isfinite(actuators.control[3])) + { + orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); + } } printf("[fixedwing_att_control] exiting, stopping all motors.\n"); diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c index dd011aeed6..a8894f059a 100644 --- a/apps/mavlink/mavlink_receiver.c +++ b/apps/mavlink/mavlink_receiver.c @@ -261,8 +261,8 @@ handle_message(mavlink_message_t *msg) offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid-1] / (float)INT16_MAX; offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid-1] / (float)INT16_MAX; - offboard_control_sp.p3= (float)quad_motors_setpoint.yaw[mavlink_system.sysid-1] / (float)INT16_MAX; - offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid-1]/(float)UINT16_MAX; + offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid-1] / (float)INT16_MAX; + offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid-1] / (float)UINT16_MAX; if (quad_motors_setpoint.thrust[mavlink_system.sysid-1] == 0) { ml_armed = false; @@ -298,6 +298,26 @@ handle_message(mavlink_message_t *msg) mavlink_hil_state_t hil_state; mavlink_msg_hil_state_decode(msg, &hil_state); + /* Calculate Rotation Matrix */ + //TODO: better clarification which app does this, atm we have a ekf for quadrotors which does this, but there is no such thing if fly in fixed wing mode + + if (mavlink_system.type == MAV_TYPE_FIXED_WING) { + //TODO: assuming low pitch and roll values for now + hil_attitude.R[0][0] = cosf(hil_state.yaw); + hil_attitude.R[0][1] = sinf(hil_state.yaw); + hil_attitude.R[0][2] = 0.0f; + + hil_attitude.R[1][0] = -sinf(hil_state.yaw); + hil_attitude.R[1][1] = cosf(hil_state.yaw); + hil_attitude.R[1][2] = 0.0f; + + hil_attitude.R[2][0] = 0.0f; + hil_attitude.R[2][1] = 0.0f; + hil_attitude.R[2][2] = 1.0f; + + hil_attitude.R_valid = true; + } + hil_global_pos.lat = hil_state.lat; hil_global_pos.lon = hil_state.lon; hil_global_pos.alt = hil_state.alt / 1000.0f; diff --git a/apps/px4io/comms.c b/apps/px4io/comms.c index 40ea38cf74..c522325ddd 100644 --- a/apps/px4io/comms.c +++ b/apps/px4io/comms.c @@ -130,15 +130,10 @@ comms_main(void) last_report_time = now; /* populate the report */ - for (int i = 0; i < system_state.rc_channels; i++) + for (unsigned i = 0; i < system_state.rc_channels; i++) { report.rc_channel[i] = system_state.rc_channel_data[i]; - - if (system_state.sbus_input_ok || system_state.dsm_input_ok || system_state.ppm_input_ok) { - report.channel_count = system_state.rc_channels; - } else { - report.channel_count = 0; } - + report.channel_count = system_state.rc_channels; report.armed = system_state.armed; /* and send it */ @@ -174,26 +169,41 @@ comms_handle_command(const void *buffer, size_t length) irqstate_t flags = irqsave(); /* fetch new PWM output values */ - for (unsigned i = 0; i < PX4IO_OUTPUT_CHANNELS; i++) + for (unsigned i = 0; i < PX4IO_OUTPUT_CHANNELS; i++) { system_state.fmu_channel_data[i] = cmd->servo_command[i]; + } - /* if the IO is armed and the FMU gets disarmed, the IO must also disarm */ - if(system_state.arm_ok && !cmd->arm_ok) { + /* if IO is armed and FMU gets disarmed, IO must also disarm */ + if (system_state.arm_ok && !cmd->arm_ok) { system_state.armed = false; } system_state.arm_ok = cmd->arm_ok; - system_state.mixer_use_fmu = true; + system_state.vector_flight_mode_ok = cmd->vector_flight_mode_ok; + system_state.manual_override_ok = cmd->manual_override_ok; + system_state.mixer_fmu_available = true; system_state.fmu_data_received = true; + /* set PWM update rate if changed (after limiting) */ + uint16_t new_servo_rate = cmd->servo_rate; - /* handle changes signalled by FMU */ -// if (!system_state.arm_ok && system_state.armed) -// system_state.armed = false; + /* reject faster than 500 Hz updates */ + if (new_servo_rate > 500) { + new_servo_rate = 500; + } + /* reject slower than 50 Hz updates */ + if (new_servo_rate < 50) { + new_servo_rate = 50; + } + if (system_state.servo_rate != new_servo_rate) { + up_pwm_servo_set_rate(new_servo_rate); + system_state.servo_rate = new_servo_rate; + } /* XXX do relay changes here */ - for (unsigned i = 0; i < PX4IO_RELAY_CHANNELS; i++) + for (unsigned i = 0; i < PX4IO_RELAY_CHANNELS; i++) { system_state.relays[i] = cmd->relay_state[i]; + } irqrestore(flags); } diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c index d4eace3df5..03c8182b20 100644 --- a/apps/px4io/controls.c +++ b/apps/px4io/controls.c @@ -78,7 +78,43 @@ controls_main(void) if (fds[0].revents & POLLIN) dsm_input(); if (fds[1].revents & POLLIN) +<<<<<<< Updated upstream sbus_input(); +======= + locked |= sbus_input(); + + /* + * If we don't have lock from one of the serial receivers, + * look for PPM. It shares an input with S.bus, so there's + * a possibility it will mis-parse an S.bus frame. + * + * XXX each S.bus frame will cause a PPM decoder interrupt + * storm (lots of edges). It might be sensible to actually + * disable the PPM decoder completely if we have an alternate + * receiver lock. + */ + if (!locked) + ppm_input(); + + /* check for manual override status */ + if (system_state.rc_channel_data[4] > RC_CHANNEL_HIGH_THRESH) { + /* force manual input override */ + system_state.mixer_manual_override = true; + } else { + /* override not engaged, use FMU */ + system_state.mixer_manual_override = false; + } + + /* + * If we haven't seen any new control data in 200ms, assume we + * have lost input and tell FMU. + */ + if ((hrt_absolute_time() - system_state.rc_channels_timestamp) > 200000) { + + /* set the number of channels to zero - no inputs */ + system_state.rc_channels = 0; + system_state.rc_lost = true; +>>>>>>> Stashed changes /* XXX do ppm processing, bypass mode, etc. here */ diff --git a/apps/px4io/mixer.c b/apps/px4io/mixer.c index 483e9fe4d4..4e0aecdd7f 100644 --- a/apps/px4io/mixer.c +++ b/apps/px4io/mixer.c @@ -97,7 +97,11 @@ mixer_tick(void) /* * Decide which set of inputs we're using. */ +<<<<<<< Updated upstream if (system_state.mixer_use_fmu) { +======= + if (!system_state.mixer_manual_override && system_state.mixer_fmu_available) { +>>>>>>> Stashed changes /* we have recent control data from the FMU */ control_count = PX4IO_OUTPUT_CHANNELS; control_values = &system_state.fmu_channel_data[0]; @@ -108,20 +112,24 @@ mixer_tick(void) /* too many frames without FMU input, time to go to failsafe */ if (fmu_input_drops >= FMU_INPUT_DROP_LIMIT) { - system_state.mixer_use_fmu = false; + system_state.mixer_manual_override = true; + system_state.mixer_fmu_available = false; } } else { fmu_input_drops = 0; system_state.fmu_data_received = false; } - } else if (system_state.rc_channels > 0) { + } else if (system_state.rc_channels > 0 && system_state.manual_override_ok) { /* we have control data from an R/C input */ control_count = system_state.rc_channels; control_values = &system_state.rc_channel_data[0]; - } else { /* we have no control input */ +<<<<<<< Updated upstream +======= + // XXX builtin failsafe would activate here +>>>>>>> Stashed changes control_count = 0; } /* diff --git a/apps/px4io/protocol.h b/apps/px4io/protocol.h index c704b12016..0bf6d49976 100644 --- a/apps/px4io/protocol.h +++ b/apps/px4io/protocol.h @@ -52,9 +52,12 @@ struct px4io_command { uint16_t f2i_magic; #define F2I_MAGIC 0x636d - uint16_t servo_command[PX4IO_OUTPUT_CHANNELS]; - bool relay_state[PX4IO_RELAY_CHANNELS]; - bool arm_ok; + uint16_t servo_command[PX4IO_OUTPUT_CHANNELS]; /**< servo output channels */ + uint16_t servo_rate; /**< PWM output rate in Hz */ + bool relay_state[PX4IO_RELAY_CHANNELS]; /**< relay states as requested by FMU */ + bool arm_ok; /**< FMU allows full arming */ + bool vector_flight_mode_ok; /**< FMU aquired a valid position lock, ready for pos control */ + bool manual_override_ok; /**< if true, IO performs a direct manual override */ }; /* config message from FMU to IO */ diff --git a/apps/px4io/px4io.c b/apps/px4io/px4io.c index 77524797ff..0eed5b011b 100644 --- a/apps/px4io/px4io.c +++ b/apps/px4io/px4io.c @@ -60,6 +60,8 @@ int user_start(int argc, char *argv[]) { /* reset all to zero */ memset(&system_state, 0, sizeof(system_state)); + /* default to 50 Hz PWM outputs */ + system_state.servo_rate = 50; /* configure the high-resolution time/callout interface */ hrt_init(); diff --git a/apps/px4io/px4io.h b/apps/px4io/px4io.h index 483b9bcc81..8a6cb48a94 100644 --- a/apps/px4io/px4io.h +++ b/apps/px4io/px4io.h @@ -69,8 +69,14 @@ struct sys_state_s { +<<<<<<< Updated upstream bool armed; /* IO armed */ bool arm_ok; /* FMU says OK to arm */ +======= + bool armed; /* IO armed */ + bool arm_ok; /* FMU says OK to arm */ + uint16_t servo_rate; /* output rate of servos in Hz */ +>>>>>>> Stashed changes bool ppm_input_ok; /* valid PPM input data */ bool dsm_input_ok; /* valid Spektrum DSM data */ @@ -96,7 +102,7 @@ struct sys_state_s /* * If true, we are using the FMU controls. */ - bool mixer_use_fmu; + bool mixer_manual_override; /* * If true, state that should be reported to FMU has been updated. @@ -113,6 +119,29 @@ struct sys_state_s * in the config packet. */ uint8_t serial_rx_mode; +<<<<<<< Updated upstream +======= + + /** + * If true, the RC signal has been lost for more than a timeout interval + */ + bool rc_lost; + + /** + * If true, the connection to FMU has been lost for more than a timeout interval + */ + bool fmu_lost; + + /** + * If true, FMU is ready for autonomous position control. Only used for LED indication + */ + bool vector_flight_mode_ok; + + /** + * If true, IO performs an on-board manual override with the RC channel values + */ + bool manual_override_ok; +>>>>>>> Stashed changes }; extern struct sys_state_s system_state; diff --git a/apps/px4io/safety.c b/apps/px4io/safety.c index 60d20905ab..52facfb617 100644 --- a/apps/px4io/safety.c +++ b/apps/px4io/safety.c @@ -63,10 +63,11 @@ static unsigned counter; /* * Define the various LED flash sequences for each system state. */ -#define LED_PATTERN_SAFE 0xffff // always on -#define LED_PATTERN_FMU_ARMED 0x4444 // slow blinking -#define LED_PATTERN_IO_ARMED 0x5555 // fast blinking -#define LED_PATTERN_IO_FMU_ARMED 0x5050 // long off then double blink +#define LED_PATTERN_SAFE 0xffff /**< always on */ +#define LED_PATTERN_VECTOR_FLIGHT_MODE_OK 0x3000 /**< always on with short break */ +#define LED_PATTERN_FMU_ARMED 0x4444 /**< slow blinking */ +#define LED_PATTERN_IO_ARMED 0x5555 /**< fast blinking */ +#define LED_PATTERN_IO_FMU_ARMED 0x5050 /**< long off then double blink */ static unsigned blink_counter = 0; @@ -139,6 +140,8 @@ safety_check_button(void *arg) } } else if (system_state.arm_ok) { pattern = LED_PATTERN_FMU_ARMED; + } else if (system_state.vector_flight_mode_ok) { + pattern = LED_PATTERN_VECTOR_FLIGHT_MODE_OK; } /* Turn the LED on if we have a 1 at the current bit position */ @@ -165,7 +168,7 @@ failsafe_blink(void *arg) static bool failsafe = false; /* blink the failsafe LED if we don't have FMU input */ - if (!system_state.mixer_use_fmu) { + if (!system_state.mixer_fmu_available) { failsafe = !failsafe; } else { failsafe = false; diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h index 23172d7cf1..d69befe961 100644 --- a/apps/uORB/topics/vehicle_status.h +++ b/apps/uORB/topics/vehicle_status.h @@ -116,6 +116,7 @@ struct vehicle_status_s commander_state_machine_t state_machine; /**< current flight state, main state machine */ enum VEHICLE_FLIGHT_MODE flight_mode; /**< current flight mode, as defined by mode switch */ enum VEHICLE_ATTITUDE_MODE attitute_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */ + int32_t system_type; /**< system type, inspired by MAVLinks MAV_TYPE enum */ // uint8_t mode; @@ -165,8 +166,10 @@ struct vehicle_status_s uint16_t errors_count4; // bool remote_manual; /**< set to true by the commander when the manual-switch on the remote is set to manual */ - bool gps_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */ - + bool flag_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */ + bool flag_local_position_valid; + bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */ + bool flag_external_manual_override_ok; }; /** From f81d00594c156c51ab976d3b6d101915377d7afa Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Dec 2012 23:28:03 +0100 Subject: [PATCH 172/206] Made PX4IO FMU timeout based on IOs HRT, updating mixers now on every FMU update and not at fixed rate, this is WIP and currently does not support mixing with RC-only --- apps/px4io/comms.c | 5 ++++- apps/px4io/controls.c | 7 +++---- apps/px4io/mixer.c | 19 ++++++------------- apps/px4io/px4io.h | 4 ++-- 4 files changed, 15 insertions(+), 20 deletions(-) diff --git a/apps/px4io/comms.c b/apps/px4io/comms.c index 0fcf952abc..9a786234ee 100644 --- a/apps/px4io/comms.c +++ b/apps/px4io/comms.c @@ -183,7 +183,7 @@ comms_handle_command(const void *buffer, size_t length) system_state.vector_flight_mode_ok = cmd->vector_flight_mode_ok; system_state.manual_override_ok = cmd->manual_override_ok; system_state.mixer_fmu_available = true; - system_state.fmu_data_received = true; + system_state.fmu_data_received_time = hrt_absolute_time(); /* set PWM update rate if changed (after limiting) */ uint16_t new_servo_rate = cmd->servo_rate; @@ -201,6 +201,9 @@ comms_handle_command(const void *buffer, size_t length) system_state.servo_rate = new_servo_rate; } + /* update servo values immediately */ + mixer_tick(); + /* XXX do relay changes here */ for (unsigned i = 0; i < PX4IO_RELAY_CHANNELS; i++) { system_state.relays[i] = cmd->relay_state[i]; diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c index 9db9a0fa55..4bd6fe1a0f 100644 --- a/apps/px4io/controls.c +++ b/apps/px4io/controls.c @@ -61,8 +61,8 @@ #include "px4io.h" #define RC_FAILSAFE_TIMEOUT 2000000 /**< two seconds failsafe timeout */ -#define RC_CHANNEL_HIGH_THRESH 1600 -#define RC_CHANNEL_LOW_THRESH 1400 +#define RC_CHANNEL_HIGH_THRESH 1700 +#define RC_CHANNEL_LOW_THRESH 1300 static void ppm_input(void); @@ -133,8 +133,7 @@ controls_main(void) system_state.fmu_report_due = true; } - /* do PWM output updates */ - mixer_tick(); + /* PWM output updates are performed directly on each comms update */ } } diff --git a/apps/px4io/mixer.c b/apps/px4io/mixer.c index 5a644906b9..318183ef54 100644 --- a/apps/px4io/mixer.c +++ b/apps/px4io/mixer.c @@ -53,10 +53,9 @@ #include "px4io.h" /* - * Count of periodic calls in which we have no FMU input. + * Maximum interval in us before FMU signal is considered lost */ -static unsigned fmu_input_drops; -#define FMU_INPUT_DROP_LIMIT 20 +#define FMU_INPUT_DROP_LIMIT_US 200000 /* * Update a mixer based on the current control signals. @@ -91,17 +90,11 @@ mixer_tick(void) control_values = &system_state.fmu_channel_data[0]; /* check that we are receiving fresh data from the FMU */ - if (!system_state.fmu_data_received) { - fmu_input_drops++; + if ((hrt_absolute_time() - system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) { /* too many frames without FMU input, time to go to failsafe */ - if (fmu_input_drops >= FMU_INPUT_DROP_LIMIT) { - system_state.mixer_manual_override = true; - system_state.mixer_fmu_available = false; - } - } else { - fmu_input_drops = 0; - system_state.fmu_data_received = false; + system_state.mixer_manual_override = true; + system_state.mixer_fmu_available = false; } } else if (system_state.rc_channels > 0 && system_state.manual_override_ok) { @@ -109,7 +102,7 @@ mixer_tick(void) control_count = system_state.rc_channels; control_values = &system_state.rc_channel_data[0]; } else { - /* we have no control input */ + /* we have no control input (no FMU, no RC) */ // XXX builtin failsafe would activate here control_count = 0; diff --git a/apps/px4io/px4io.h b/apps/px4io/px4io.h index 84f5ba029a..c8699c6c60 100644 --- a/apps/px4io/px4io.h +++ b/apps/px4io/px4io.h @@ -106,9 +106,9 @@ struct sys_state_s bool fmu_report_due; /** - * If true, new control data from the FMU has been received. + * Last FMU receive time, in microseconds since system boot */ - bool fmu_data_received; + uint64_t fmu_data_received_time; /** * Current serial interface mode, per the serial_rx_mode parameter From e56911bf2d637682f64fe93add114f8fef2682fd Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 16 Dec 2012 15:31:44 +0100 Subject: [PATCH 173/206] Fixed signal loss detection on S.Bus parsing, stripped PX4IO code parts from S.Bus parser to allow FMU / IO parser code sharing. Added S.Bus channels 17 and 18 if channel data struct has enough space. Tested with receiver and PX4FMU. --- apps/px4io/comms.c | 8 ++++++- apps/px4io/controls.c | 32 ++++++++++++++++++++----- apps/px4io/mixer.c | 4 ++++ apps/px4io/px4io.h | 3 ++- apps/px4io/sbus.c | 56 +++++++++++++++++++++++++------------------ 5 files changed, 72 insertions(+), 31 deletions(-) diff --git a/apps/px4io/comms.c b/apps/px4io/comms.c index 9a786234ee..bfdad019d2 100644 --- a/apps/px4io/comms.c +++ b/apps/px4io/comms.c @@ -52,6 +52,7 @@ #include #include +#include #include #include @@ -201,7 +202,12 @@ comms_handle_command(const void *buffer, size_t length) system_state.servo_rate = new_servo_rate; } - /* update servo values immediately */ + /* + * update servo values immediately. + * the updates are done in addition also + * in the mainloop, since this function will only + * update with a connected FMU. + */ mixer_tick(); /* XXX do relay changes here */ diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c index 4bd6fe1a0f..48370d9d0c 100644 --- a/apps/px4io/controls.c +++ b/apps/px4io/controls.c @@ -92,10 +92,22 @@ controls_main(void) */ bool locked = false; + /* + * Store RC channel count to detect switch to RC loss sooner + * than just by timeout + */ + unsigned rc_channels = system_state.rc_channels; + + /* + * Track if any input got an update in this round + */ + bool rc_updated; + if (fds[0].revents & POLLIN) locked |= dsm_input(); if (fds[1].revents & POLLIN) - locked |= sbus_input(); + locked |= sbus_input(fds[1].fd, PX4IO_INPUT_CHANNELS, &system_state.rc_channel_data, + &system_state.rc_channels, &system_state.rc_channels_timestamp, &rc_updated); /* * If we don't have lock from one of the serial receivers, @@ -127,13 +139,21 @@ controls_main(void) /* set the number of channels to zero - no inputs */ system_state.rc_channels = 0; - system_state.rc_lost = true; - - /* trigger an immediate report to the FMU */ - system_state.fmu_report_due = true; + rc_updated = true; } - /* PWM output updates are performed directly on each comms update */ + /* + * If there was a RC update OR the RC signal status (lost / present) has + * just changed, request an update immediately. + */ + system_state.fmu_report_due |= rc_updated; + + /* + * PWM output updates are performed in addition on each comm update. + * the updates here are required to ensure operation if FMU is not started + * or stopped responding. + */ + mixer_tick(); } } diff --git a/apps/px4io/mixer.c b/apps/px4io/mixer.c index 318183ef54..135d97bb34 100644 --- a/apps/px4io/mixer.c +++ b/apps/px4io/mixer.c @@ -48,7 +48,10 @@ #include #include +#include + #include +#include #include "px4io.h" @@ -95,6 +98,7 @@ mixer_tick(void) /* too many frames without FMU input, time to go to failsafe */ system_state.mixer_manual_override = true; system_state.mixer_fmu_available = false; + lib_lowprintf("\nRX timeout\n"); } } else if (system_state.rc_channels > 0 && system_state.manual_override_ok) { diff --git a/apps/px4io/px4io.h b/apps/px4io/px4io.h index c8699c6c60..9cfd8f716d 100644 --- a/apps/px4io/px4io.h +++ b/apps/px4io/px4io.h @@ -193,7 +193,8 @@ extern void controls_main(void); extern int dsm_init(const char *device); extern bool dsm_input(void); extern int sbus_init(const char *device); -extern bool sbus_input(void); +extern bool sbus_input(int fd, unsigned max_channels, uint16_t *channel_data, unsigned *channel_count, + uint64_t *receive_time, bool *updated); /* * Assertion codes diff --git a/apps/px4io/sbus.c b/apps/px4io/sbus.c index a8f628a84e..0de0593e7d 100644 --- a/apps/px4io/sbus.c +++ b/apps/px4io/sbus.c @@ -49,14 +49,11 @@ #define DEBUG #include "px4io.h" -#include "protocol.h" #include "debug.h" #define SBUS_FRAME_SIZE 25 #define SBUS_INPUT_CHANNELS 16 -static int sbus_fd = -1; - static hrt_abstime last_rx_time; static hrt_abstime last_frame_time; @@ -66,11 +63,14 @@ static unsigned partial_frame_count; unsigned sbus_frame_drops; -static void sbus_decode(hrt_abstime frame_time); +static int sbus_decode(hrt_abstime frame_time, unsigned max_channels, + uint16_t *channel_data, unsigned *channel_count, uint64_t *receive_time); int sbus_init(const char *device) { + static int sbus_fd = -1; + if (sbus_fd < 0) sbus_fd = open(device, O_RDONLY); @@ -96,7 +96,8 @@ sbus_init(const char *device) } bool -sbus_input(void) +sbus_input(int fd, unsigned max_channels, uint16_t *channel_data, unsigned *channel_count, + uint64_t *receive_time, bool *updated) { ssize_t ret; hrt_abstime now; @@ -128,7 +129,7 @@ sbus_input(void) * Fetch bytes, but no more than we would need to complete * the current frame. */ - ret = read(sbus_fd, &frame[partial_frame_count], SBUS_FRAME_SIZE - partial_frame_count); + ret = read(fd, &frame[partial_frame_count], SBUS_FRAME_SIZE - partial_frame_count); /* if the read failed for any reason, just give up here */ if (ret < 1) @@ -148,9 +149,9 @@ sbus_input(void) /* * Great, it looks like we might have a frame. Go ahead and - * decode it. + * decode it, report if the receiver got something. */ - sbus_decode(now); + *updated = (sbus_decode(now, max_channels, channel_data, channel_count, receive_time) == OK); partial_frame_count = 0; out: @@ -196,25 +197,32 @@ static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = { /* 15 */ { {20, 5, 0x07, 0},{21, 0, 0xff, 3},{ 0, 0, 0x00, 0} } }; -static void -sbus_decode(hrt_abstime frame_time) +static int +sbus_decode(hrt_abstime frame_time, unsigned max_channels, uint16_t *channel_data, unsigned *channel_count, uint64_t *receive_time) { /* check frame boundary markers to avoid out-of-sync cases */ if ((frame[0] != 0x0f) || (frame[24] != 0x00)) { sbus_frame_drops++; - return; + return 1; } - /* if the failsafe bit is set, we consider the frame invalid */ - if (frame[23] & (1 << 4)) { - return; + /* if the failsafe or connection lost bit is set, we consider the frame invalid */ + if ((frame[23] & (1 << 2)) && /* signal lost */ + (frame[23] & (1 << 3))) { /* failsafe */ + + /* actively announce signal loss */ + *channel_count = 0; + + return 1; } + /* decode failsafe and RC status */ + /* we have received something we think is a frame */ last_frame_time = frame_time; - unsigned chancount = (PX4IO_INPUT_CHANNELS > SBUS_INPUT_CHANNELS) ? - SBUS_INPUT_CHANNELS : PX4IO_INPUT_CHANNELS; + unsigned chancount = (max_channels > SBUS_INPUT_CHANNELS) ? + SBUS_INPUT_CHANNELS : max_channels; /* use the decoder matrix to extract channel data */ for (unsigned channel = 0; channel < chancount; channel++) { @@ -236,17 +244,19 @@ sbus_decode(hrt_abstime frame_time) system_state.rc_channel_data[channel] = (value / 2) + 998; } - if (PX4IO_INPUT_CHANNELS >= 18) { - chancount = 18; - /* XXX decode the two switch channels */ + /* decode switch channels if data fields are wide enough */ + if (chancount > 17) { + /* channel 17 (index 16) */ + system_state.rc_channel_data[16] = (frame[23] & (1 << 0)) * 1000 + 998; + /* channel 18 (index 17) */ + system_state.rc_channel_data[17] = (frame[23] & (1 << 1)) * 1000 + 998; } /* note the number of channels decoded */ - system_state.rc_channels = chancount; + *channel_count = chancount; /* and note that we have received data from the R/C controller */ - system_state.rc_channels_timestamp = frame_time; + *receive_time = frame_time; - /* trigger an immediate report to the FMU */ - system_state.fmu_report_due = true; + return 0; } From b9606d0d6ea1f0a87e408527a5838210dcbb931b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 16 Dec 2012 16:30:41 +0100 Subject: [PATCH 174/206] Reverted arming state machine back to its original state, operational again --- apps/px4io/safety.c | 23 +++++++++++++++++++---- 1 file changed, 19 insertions(+), 4 deletions(-) diff --git a/apps/px4io/safety.c b/apps/px4io/safety.c index 9ce4589b78..780a4331ae 100644 --- a/apps/px4io/safety.c +++ b/apps/px4io/safety.c @@ -71,8 +71,14 @@ static unsigned counter = 0; static unsigned blink_counter = 0; +/* + * IMPORTANT: The arming state machine critically + * depends on using the same threshold + * for arming and disarming. Since disarming + * is quite deadly for the system, a similar + * length can be justified. + */ #define ARM_COUNTER_THRESHOLD 10 -#define DISARM_COUNTER_THRESHOLD 4 static bool safety_button_pressed; @@ -102,8 +108,16 @@ safety_check_button(void *arg) */ safety_button_pressed = BUTTON_SAFETY; - /* Keep pressed for a while to arm */ + /* + * Keep pressed for a while to arm. + * + * Note that the counting sequence has to be same length + * for arming / disarming in order to end up as proper + * state machine, keep ARM_COUNTER_THRESHOLD the same + * length in all cases of the if/else struct below. + */ if (safety_button_pressed && !system_state.armed) { + if (counter < ARM_COUNTER_THRESHOLD) { counter++; } else if (counter == ARM_COUNTER_THRESHOLD) { @@ -114,9 +128,10 @@ safety_check_button(void *arg) } /* Disarm quickly */ } else if (safety_button_pressed && system_state.armed) { - if (counter < DISARM_COUNTER_THRESHOLD) { + + if (counter < ARM_COUNTER_THRESHOLD) { counter++; - } else if (counter == DISARM_COUNTER_THRESHOLD) { + } else if (counter == ARM_COUNTER_THRESHOLD) { /* change to disarmed state and notify the FMU */ system_state.armed = false; counter++; From df5c09ead1e69d2f3d01bab635c765531a6af1b2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 16 Dec 2012 16:31:02 +0100 Subject: [PATCH 175/206] Fixed MAVLink parameter initialization --- apps/mavlink/mavlink.c | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index 575b42b37b..3351d9cfdd 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -469,14 +469,15 @@ mavlink_message_t* mavlink_get_channel_buffer(uint8_t channel) void mavlink_update_system(void) { static bool initialized = false; - param_t param_system_id; - param_t param_component_id; - param_t param_system_type; + static param_t param_system_id; + static param_t param_component_id; + static param_t param_system_type; if (!initialized) { param_system_id = param_find("MAV_SYS_ID"); param_component_id = param_find("MAV_COMP_ID"); param_system_type = param_find("MAV_TYPE"); + initialized = true; } /* update system and component id */ From 97a94e3b899edf13aa6cf668e71895ef73004d03 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 16 Dec 2012 16:31:17 +0100 Subject: [PATCH 176/206] Fixed MAV_TYPE parameter readout --- apps/commander/commander.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 52412e20a6..43219c9f96 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -1324,7 +1324,9 @@ int commander_thread_main(int argc, char *argv[]) /* update parameters */ if (!current_status.flag_system_armed) { - current_status.system_type = param_get(_param_sys_type, &(current_status.system_type)); + if (param_get(_param_sys_type, &(current_status.system_type)) != OK) { + warnx("failed setting new system type"); + } /* disable manual override for all systems that rely on electronic stabilization */ if (current_status.system_type == MAV_TYPE_QUADROTOR || From f41e5728fc132a7cd2764f166e36ca4d2f5909ea Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 18 Dec 2012 13:18:36 +0100 Subject: [PATCH 177/206] Correct demixing scaling for v-tail mixers --- apps/sensors/sensors.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index b63bfb195a..94dbd0b21e 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -1001,7 +1001,7 @@ Sensors::ppm_poll() // XXX hardcoded for testing purposes, replace with inverted delta mixer from ROMFS /* roll input - mixed roll and pitch channels */ - manual_control.roll = _rc.chan[_rc.function[ROLL]].scaled - _rc.chan[_rc.function[PITCH]].scaled; + manual_control.roll = -0.5f * (_rc.chan[_rc.function[ROLL]].scaled - _rc.chan[_rc.function[PITCH]].scaled); /* pitch input - mixed roll and pitch channels */ manual_control.pitch = -0.5f * (_rc.chan[_rc.function[ROLL]].scaled + _rc.chan[_rc.function[PITCH]].scaled); /* yaw input - stick right is positive and positive rotation */ From bc3b66043f57adebdef3980f3a113d2d5362416a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 19 Dec 2012 11:34:51 +0100 Subject: [PATCH 178/206] Cleaned up HIL on FMU / IO combo --- apps/commander/commander.c | 16 ++++++++++++++-- apps/drivers/hil/hil.cpp | 1 - apps/drivers/px4io/px4io.cpp | 7 +++---- apps/mavlink/orb_listener.c | 19 ++----------------- apps/sensors/sensors.cpp | 4 ++-- 5 files changed, 21 insertions(+), 26 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 43219c9f96..f61fd053cd 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -1268,6 +1268,8 @@ int commander_thread_main(int argc, char *argv[]) int sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); struct sensor_combined_s sensors; memset(&sensors, 0, sizeof(sensors)); + sensors.battery_voltage_v = 0.0f; + sensors.battery_voltage_valid = false; /* Subscribe to command topic */ int cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); @@ -1305,7 +1307,13 @@ int commander_thread_main(int argc, char *argv[]) if (new_data) { orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard); } - orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors); + + orb_check(sensor_sub, &new_data); + if (new_data) { + orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors); + } else { + sensors.battery_voltage_valid = false; + } orb_check(cmd_sub, &new_data); if (new_data) { @@ -1434,7 +1442,11 @@ int commander_thread_main(int argc, char *argv[]) /* Check battery voltage */ /* write to sys_status */ - current_status.voltage_battery = battery_voltage; + if (battery_voltage_valid) { + current_status.voltage_battery = battery_voltage; + } else { + current_status.voltage_battery = 0.0f; + } /* if battery voltage is getting lower, warn using buzzer, etc. */ if (battery_voltage_valid && (bat_remain < 0.15f /* XXX MAGIC NUMBER */) && (false == low_battery_voltage_actions_done)) { //TODO: add filter, or call emergency after n measurements < VOLTAGE_BATTERY_MINIMAL_MILLIVOLTS diff --git a/apps/drivers/hil/hil.cpp b/apps/drivers/hil/hil.cpp index 67b16aa42f..cb4a48fab2 100644 --- a/apps/drivers/hil/hil.cpp +++ b/apps/drivers/hil/hil.cpp @@ -382,7 +382,6 @@ HIL::task_main() /* this would be bad... */ if (ret < 0) { log("poll error %d", errno); - usleep(1000000); continue; } diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index 1fb65413ab..6953049264 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -410,7 +410,6 @@ PX4IO::task_main() orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), _t_actuators_effective, &_controls_effective); - /* convert to PWM values */ for (unsigned i = 0; i < _max_actuators; i++) { /* last resort: catch NaN, INF and out-of-band errors */ @@ -426,6 +425,9 @@ PX4IO::task_main() } } + /* publish actuator outputs */ + orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &_outputs); + /* and flag for update */ _send_needed = true; } @@ -570,9 +572,6 @@ PX4IO::io_send() for (unsigned i = 0; i < _max_actuators; i++) cmd.servo_command[i] = _outputs.output[i]; - /* publish as we send */ - orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &_outputs); - // XXX relays /* armed and not locked down -> arming ok */ diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index b0aa401fc2..e763e642a1 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -506,28 +506,13 @@ l_actuator_outputs(struct listener *l) mavlink_mode, 0); } else { - float rudder, throttle; - - /* SCALING: PWM min: 900, PWM max: 2100, center: 1500 */ - - // XXX very ugly, needs rework - if (isfinite(act_outputs.output[3]) - && act_outputs.output[3] > 800 && act_outputs.output[3] < 2200) { - /* throttle is fourth output */ - rudder = (act_outputs.output[2] - 1500.0f) / 600.0f; - throttle = (((act_outputs.output[3] - 900.0f) / 600.0f) / 2.0f); - } else { - /* only three outputs, put throttle on position 4 / index 3 */ - rudder = 0; - throttle = (((act_outputs.output[2] - 900.0f) / 600.0f) / 2.0f); - } mavlink_msg_hil_controls_send(chan, hrt_absolute_time(), (act_outputs.output[0] - 1500.0f) / 600.0f, (act_outputs.output[1] - 1500.0f) / 600.0f, - rudder, - throttle, + 0.0f/*(act_outputs.output[2] - 1500.0f) / 600.0f*/, + (act_outputs.output[2] - 900.0f) / 1200.0f, (act_outputs.output[4] - 1500.0f) / 600.0f, (act_outputs.output[5] - 1500.0f) / 600.0f, (act_outputs.output[6] - 1500.0f) / 600.0f, diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index 94dbd0b21e..bcc383330c 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -1001,9 +1001,9 @@ Sensors::ppm_poll() // XXX hardcoded for testing purposes, replace with inverted delta mixer from ROMFS /* roll input - mixed roll and pitch channels */ - manual_control.roll = -0.5f * (_rc.chan[_rc.function[ROLL]].scaled - _rc.chan[_rc.function[PITCH]].scaled); + manual_control.roll = 0.5f * (_rc.chan[_rc.function[ROLL]].scaled - _rc.chan[_rc.function[PITCH]].scaled); /* pitch input - mixed roll and pitch channels */ - manual_control.pitch = -0.5f * (_rc.chan[_rc.function[ROLL]].scaled + _rc.chan[_rc.function[PITCH]].scaled); + manual_control.pitch = 0.5f * (_rc.chan[_rc.function[ROLL]].scaled + _rc.chan[_rc.function[PITCH]].scaled); /* yaw input - stick right is positive and positive rotation */ manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled; /* throttle input */ From 4676b71d8ade5b9ce27e63f1d204b8ffed58b325 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 19 Dec 2012 14:19:11 +0100 Subject: [PATCH 179/206] Cleanup in ADC driver, re-add all inputs that are present --- apps/drivers/boards/px4fmu/px4fmu_adc.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/apps/drivers/boards/px4fmu/px4fmu_adc.c b/apps/drivers/boards/px4fmu/px4fmu_adc.c index 9878941631..b55af486d5 100644 --- a/apps/drivers/boards/px4fmu/px4fmu_adc.c +++ b/apps/drivers/boards/px4fmu/px4fmu_adc.c @@ -67,10 +67,10 @@ /* Identifying number of each ADC channel: Variable Resistor. */ #ifdef CONFIG_STM32_ADC3 -static const uint8_t g_chanlist[ADC3_NCHANNELS] = {10, 11};// , 12, 13}; ADC12 and 13 are used by MPU on v1.5 boards +static const uint8_t g_chanlist[ADC3_NCHANNELS] = {10, 11, 12, 13}; /* Configurations of pins used byte each ADC channels */ -static const uint32_t g_pinlist[ADC3_NCHANNELS] = {GPIO_ADC3_IN10, GPIO_ADC3_IN11}; // ADC12 and 13 are used by MPU on v1.5 boards, GPIO_ADC3_IN12, GPIO_ADC3_IN13}; +static const uint32_t g_pinlist[ADC3_NCHANNELS] = {GPIO_ADC3_IN10, GPIO_ADC3_IN11, GPIO_ADC3_IN12, GPIO_ADC3_IN13}; #endif /************************************************************************************ From fe6496a04dd0a232bb530f57031cfb4f6e65bb44 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 19 Dec 2012 14:20:40 +0100 Subject: [PATCH 180/206] Correctly do position lock led signalling on IO and position lock measurement on FMU, tested with HIL. --- apps/commander/commander.c | 28 ++++++++++++++++++++++++++-- apps/px4io/safety.c | 2 +- 2 files changed, 27 insertions(+), 3 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index f61fd053cd..5dfdf83adb 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -1476,21 +1476,45 @@ int commander_thread_main(int argc, char *argv[]) /* End battery voltage check */ + + /* + * Check for valid position information. + * + * If the system has a valid position source from an onboard + * position estimator, it is safe to operate it autonomously. + * The flag_vector_flight_mode_ok flag indicates that a minimum + * set of position measurements is available. + */ + + /* store current state to reason later about a state change */ bool vector_flight_mode_ok = current_status.flag_vector_flight_mode_ok; bool global_pos_valid = current_status.flag_global_position_valid; bool local_pos_valid = current_status.flag_local_position_valid; /* check for global or local position updates, set a timeout of 2s */ if (hrt_absolute_time() - last_global_position_time < 2000000) { - current_status.flag_vector_flight_mode_ok = true; current_status.flag_global_position_valid = true; // XXX check for controller status and home position as well + } else { + current_status.flag_global_position_valid = false; } if (hrt_absolute_time() - last_local_position_time < 2000000) { - current_status.flag_vector_flight_mode_ok = true; current_status.flag_local_position_valid = true; // XXX check for controller status and home position as well + } else { + current_status.flag_local_position_valid = false; + } + + /* + * Consolidate global position and local position valid flags + * for vector flight mode. + */ + if (current_status.flag_local_position_valid || + current_status.flag_global_position_valid) { + current_status.flag_vector_flight_mode_ok = true; + } else { + current_status.flag_vector_flight_mode_ok = false; } /* consolidate state change, flag as changed if required */ diff --git a/apps/px4io/safety.c b/apps/px4io/safety.c index 780a4331ae..3314ef5137 100644 --- a/apps/px4io/safety.c +++ b/apps/px4io/safety.c @@ -64,7 +64,7 @@ static unsigned counter = 0; * Define the various LED flash sequences for each system state. */ #define LED_PATTERN_SAFE 0xffff /**< always on */ -#define LED_PATTERN_VECTOR_FLIGHT_MODE_OK 0x3000 /**< always on with short break */ +#define LED_PATTERN_VECTOR_FLIGHT_MODE_OK 0xFFFE /**< always on with short break */ #define LED_PATTERN_FMU_ARMED 0x4444 /**< slow blinking */ #define LED_PATTERN_IO_ARMED 0x5555 /**< fast blinking */ #define LED_PATTERN_IO_FMU_ARMED 0x5050 /**< long off then double blink */ From 28b3ecd9c6c3c64d5f6d6a7cb04f8a9bb5dcb27a Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 19 Dec 2012 17:06:01 -0800 Subject: [PATCH 181/206] I don't want a switch for failsafe for the copter --- apps/px4io/mixer.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/apps/px4io/mixer.c b/apps/px4io/mixer.c index 135d97bb34..56fc3ab380 100644 --- a/apps/px4io/mixer.c +++ b/apps/px4io/mixer.c @@ -84,6 +84,9 @@ mixer_tick(void) int i; bool should_arm; + // XXX for now + system_state.mixer_manual_override = false; + /* * Decide which set of inputs we're using. */ From 06407b166f262c40b9e1887e6b4b71466fe4e57a Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 19 Dec 2012 17:54:18 -0800 Subject: [PATCH 182/206] My PID integral part fixes --- .../multirotor_attitude_control.c | 9 +++- .../multirotor_rate_control.c | 44 ++++++++----------- apps/systemlib/pid/pid.c | 6 +++ apps/systemlib/pid/pid.h | 1 + 4 files changed, 33 insertions(+), 27 deletions(-) diff --git a/apps/multirotor_att_control/multirotor_attitude_control.c b/apps/multirotor_att_control/multirotor_attitude_control.c index e94d7c55d8..b98736cee9 100644 --- a/apps/multirotor_att_control/multirotor_attitude_control.c +++ b/apps/multirotor_att_control/multirotor_attitude_control.c @@ -197,7 +197,7 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s } /* load new parameters with lower rate */ - if (motor_skip_counter % 1000 == 0) { + if (motor_skip_counter % 500 == 0) { /* update parameters from storage */ parameters_update(&h, &p); @@ -206,6 +206,13 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s pid_set_parameters(&roll_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f); } + /* reset integral if on ground */ + if(att_sp->thrust < 0.1f) { + pid_reset_integral(&pitch_controller); + pid_reset_integral(&roll_controller); + } + + /* calculate current control outputs */ /* control pitch (forward) output */ diff --git a/apps/multirotor_att_control/multirotor_rate_control.c b/apps/multirotor_att_control/multirotor_rate_control.c index 93f7085aec..edb50a96e8 100644 --- a/apps/multirotor_att_control/multirotor_rate_control.c +++ b/apps/multirotor_att_control/multirotor_rate_control.c @@ -150,16 +150,13 @@ static int parameters_update(const struct mc_rate_control_param_handles *h, stru void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp, const float rates[], struct actuator_controls_s *actuators) { - static float roll_control_last = 0; - static float pitch_control_last = 0; static uint64_t last_run = 0; const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f; static uint64_t last_input = 0; - float dT_input = (hrt_absolute_time() - last_input) / 1000000.0f; - if (last_input != rate_sp->timestamp) { - last_input = rate_sp->timestamp; - } + static PID_t pitch_rate_controller; + static PID_t roll_rate_controller; + last_run = hrt_absolute_time(); @@ -175,37 +172,32 @@ void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp, parameters_init(&h); parameters_update(&h, &p); initialized = true; + + pid_init(&pitch_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1000.0f,1000.0f, PID_MODE_DERIVATIV_CALC); + pid_init(&roll_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1000.0f,1000.0f, PID_MODE_DERIVATIV_CALC); + } /* load new parameters with lower rate */ - if (motor_skip_counter % 2500 == 0) { + if (motor_skip_counter % 500 == 0) { /* update parameters from storage */ parameters_update(&h, &p); // warnx("rate ctrl: p.yawrate_p: %8.4f, loop: %d Hz, input: %d Hz", // (double)p.yawrate_p, (int)(1.0f/deltaT), (int)(1.0f/dT_input)); + + /* load new parameters with lower rate */ + parameters_update(&h, &p); + + /* apply parameters */ + pid_set_parameters(&pitch_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1000.0f, 1000.0f); + pid_set_parameters(&roll_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1000.0f, 1000.0f); } - /* calculate current control outputs */ - - /* control pitch (forward) output */ - float pitch_control = p.attrate_p * (rate_sp->pitch - rates[1]) - (p.attrate_d * pitch_control_last); - /* increase resilience to faulty control inputs */ - if (isfinite(pitch_control)) { - pitch_control_last = pitch_control; - } else { - pitch_control = 0.0f; - warnx("rej. NaN ctrl pitch"); - } /* control roll (left/right) output */ - float roll_control = p.attrate_p * (rate_sp->roll - rates[0]) - (p.attrate_d * roll_control_last); - /* increase resilience to faulty control inputs */ - if (isfinite(roll_control)) { - roll_control_last = roll_control; - } else { - roll_control = 0.0f; - warnx("rej. NaN ctrl roll"); - } + float roll_control = pid_calculate(&roll_rate_controller, rate_sp->roll , rates[0], 0.0f, deltaT); + float pitch_control = pid_calculate(&pitch_rate_controller, rate_sp->pitch , rates[1], 0.0f, deltaT); + /* control yaw rate */ float yaw_rate_control = p.yawrate_p * (rate_sp->yaw - rates[2]); diff --git a/apps/systemlib/pid/pid.c b/apps/systemlib/pid/pid.c index 0358caa250..49315cdc9f 100644 --- a/apps/systemlib/pid/pid.c +++ b/apps/systemlib/pid/pid.c @@ -183,3 +183,9 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo return pid->last_output; } + + +__EXPORT void pid_reset_integral(PID_t *pid) +{ + pid->integral = 0; +} diff --git a/apps/systemlib/pid/pid.h b/apps/systemlib/pid/pid.h index b51afef9ef..64d6688677 100644 --- a/apps/systemlib/pid/pid.h +++ b/apps/systemlib/pid/pid.h @@ -72,6 +72,7 @@ __EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float //void pid_set(PID_t *pid, float sp); __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, float dt); +__EXPORT void pid_reset_integral(PID_t *pid); #endif /* PID_H_ */ From 8053b4b9f78020ba569e37207800250348eba92b Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 20 Dec 2012 08:55:54 -0800 Subject: [PATCH 183/206] Revert "I don't want a switch for failsafe for the copter" This reverts commit 28b3ecd9c6c3c64d5f6d6a7cb04f8a9bb5dcb27a. --- apps/px4io/mixer.c | 3 --- 1 file changed, 3 deletions(-) diff --git a/apps/px4io/mixer.c b/apps/px4io/mixer.c index 56fc3ab380..135d97bb34 100644 --- a/apps/px4io/mixer.c +++ b/apps/px4io/mixer.c @@ -84,9 +84,6 @@ mixer_tick(void) int i; bool should_arm; - // XXX for now - system_state.mixer_manual_override = false; - /* * Decide which set of inputs we're using. */ From 5b92c517779500d79e6e5f5cff48336550ce5edb Mon Sep 17 00:00:00 2001 From: px4dev Date: Thu, 20 Dec 2012 21:31:02 -0800 Subject: [PATCH 184/206] Initial implementation of application access to the PX4IO relays. --- apps/drivers/drv_pwm_output.h | 2 +- apps/drivers/px4io/px4io.cpp | 32 +++++++++++++++++++++++++++++++- apps/px4io/comms.c | 25 +++++++++++++++++++++---- 3 files changed, 53 insertions(+), 6 deletions(-) diff --git a/apps/drivers/drv_pwm_output.h b/apps/drivers/drv_pwm_output.h index 97033f2cd1..b2fee65aca 100644 --- a/apps/drivers/drv_pwm_output.h +++ b/apps/drivers/drv_pwm_output.h @@ -95,7 +95,7 @@ ORB_DECLARE(output_pwm); * Note that ioctls and ObjDev updates should not be mixed, as the * behaviour of the system in this case is not defined. */ -#define _PWM_SERVO_BASE 0x2700 +#define _PWM_SERVO_BASE 0x2a00 /** arm all servo outputs handle by this driver */ #define PWM_SERVO_ARM _IOC(_PWM_SERVO_BASE, 0) diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index 456564ba73..d662e634f2 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -61,6 +61,7 @@ #include #include #include +#include #include #include @@ -114,6 +115,8 @@ private: bool _primary_pwm_device; ///< true if we are the default PWM output + uint32_t _relays; ///< state of the PX4IO relays, one bit per relay + volatile bool _switch_armed; ///< PX4IO switch armed state // XXX how should this work? @@ -185,6 +188,7 @@ PX4IO::PX4IO() : _t_outputs(-1), _mixers(nullptr), _primary_pwm_device(false), + _relays(0), _switch_armed(false), _send_needed(false), _config_needed(false) @@ -497,7 +501,9 @@ PX4IO::io_send() /* publish as we send */ orb_publish(ORB_ID_VEHICLE_CONTROLS, _t_outputs, &_outputs); - // XXX relays + /* update relays */ + for (unsigned i = 0; i < PX4IO_RELAY_CHANNELS; i++) + cmd.relay_state[i] = (_relays & (1<< i)) ? true : false; /* armed and not locked down */ cmd.arm_ok = (_armed.armed && !_armed.lockdown); @@ -559,6 +565,30 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) *(servo_position_t *)arg = _outputs.output[cmd - PWM_SERVO_GET(0)]; break; + case GPIO_RESET: + _relays = 0; + _send_needed = true; + break; + + case GPIO_SET: + case GPIO_CLEAR: + /* make sure only valid bits are being set */ + if ((arg & ((1UL << PX4IO_RELAY_CHANNELS) - 1)) != arg) { + ret = EINVAL; + break; + } + if (cmd == GPIO_SET) { + _relays |= arg; + } else { + _relays &= ~arg; + } + _send_needed = true; + break; + + case GPIO_GET: + *(uint32_t *)arg = _relays; + break; + case MIXERIOCGETOUTPUTCOUNT: *(unsigned *)arg = _max_actuators; break; diff --git a/apps/px4io/comms.c b/apps/px4io/comms.c index 40ea38cf74..ffb7fd6799 100644 --- a/apps/px4io/comms.c +++ b/apps/px4io/comms.c @@ -178,7 +178,7 @@ comms_handle_command(const void *buffer, size_t length) system_state.fmu_channel_data[i] = cmd->servo_command[i]; /* if the IO is armed and the FMU gets disarmed, the IO must also disarm */ - if(system_state.arm_ok && !cmd->arm_ok) { + if (system_state.arm_ok && !cmd->arm_ok) { system_state.armed = false; } @@ -191,9 +191,26 @@ comms_handle_command(const void *buffer, size_t length) // if (!system_state.arm_ok && system_state.armed) // system_state.armed = false; - /* XXX do relay changes here */ - for (unsigned i = 0; i < PX4IO_RELAY_CHANNELS; i++) - system_state.relays[i] = cmd->relay_state[i]; + /* handle relay state changes here */ + for (unsigned i = 0; i < PX4IO_RELAY_CHANNELS; i++) { + if (system_state.relays[i] != cmd->relay_state[i]) { + switch (i) { + case 0: + POWER_ACC1(cmd->relay_state[i]); + break; + case 1: + POWER_ACC2(cmd->relay_state[i]); + break; + case 2: + POWER_RELAY1(cmd->relay_state[i]); + break; + case 3: + POWER_RELAY2(cmd->relay_state[i]); + break; + } + } + system_state.relays[i] != cmd->relay_state[i] + } irqrestore(flags); } From 4cf2266b79a28445ad0b493c36cf125081900423 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 22 Dec 2012 00:47:52 +0100 Subject: [PATCH 185/206] Robustified actuator output topic, added number of mixed outputs --- apps/drivers/hil/hil.cpp | 27 +++++++++++++++++++-------- apps/drivers/px4fmu/fmu.cpp | 21 ++++++++++++++++++--- apps/drivers/px4io/px4io.cpp | 10 +++++++--- apps/mavlink/orb_listener.c | 18 ++++++++++++++++-- apps/uORB/topics/actuator_outputs.h | 5 +++-- 5 files changed, 63 insertions(+), 18 deletions(-) diff --git a/apps/drivers/hil/hil.cpp b/apps/drivers/hil/hil.cpp index cb4a48fab2..276a642fd0 100644 --- a/apps/drivers/hil/hil.cpp +++ b/apps/drivers/hil/hil.cpp @@ -68,11 +68,11 @@ #include #include #include -// #include +#include +#include #include #include -#include #include #include @@ -395,16 +395,27 @@ HIL::task_main() if (_mixers != nullptr) { /* do mixing */ - _mixers->mix(&outputs.output[0], num_outputs); + outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs); + outputs.timestamp = hrt_absolute_time(); /* iterate actuators */ for (unsigned i = 0; i < num_outputs; i++) { - /* scale for PWM output 900 - 2100us */ - outputs.output[i] = 1500 + (600 * outputs.output[i]); - - /* output to the servo */ - // up_pwm_servo_set(i, outputs.output[i]); + /* last resort: catch NaN, INF and out-of-band errors */ + if (i < (unsigned)outputs.noutputs && + isfinite(outputs.output[i]) && + outputs.output[i] >= -1.0f && + outputs.output[i] <= 1.0f) { + /* scale for PWM output 900 - 2100us */ + outputs.output[i] = 1500 + (600 * outputs.output[i]); + } else { + /* + * Value is NaN, INF or out of band - set to the minimum value. + * This will be clearly visible on the servo status and will limit the risk of accidentally + * spinning motors. It would be deadly in flight. + */ + outputs.output[i] = 900; + } } /* and publish for anyone that cares to see */ diff --git a/apps/drivers/px4fmu/fmu.cpp b/apps/drivers/px4fmu/fmu.cpp index 285516ed99..a672bd2fba 100644 --- a/apps/drivers/px4fmu/fmu.cpp +++ b/apps/drivers/px4fmu/fmu.cpp @@ -58,6 +58,7 @@ #include #include #include +#include #include #include @@ -382,7 +383,8 @@ PX4FMU::task_main() if (_mixers != nullptr) { /* do mixing */ - _mixers->mix(&outputs.output[0], num_outputs); + outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs); + outputs.timestamp = hrt_absolute_time(); // XXX output actual limited values memcpy(&controls_effective, &_controls, sizeof(controls_effective)); @@ -392,8 +394,21 @@ PX4FMU::task_main() /* iterate actuators */ for (unsigned i = 0; i < num_outputs; i++) { - /* scale for PWM output 900 - 2100us */ - outputs.output[i] = 1500 + (600 * outputs.output[i]); + /* last resort: catch NaN, INF and out-of-band errors */ + if (i < outputs.noutputs && + isfinite(outputs.output[i]) && + outputs.output[i] >= -1.0f && + outputs.output[i] <= 1.0f) { + /* scale for PWM output 900 - 2100us */ + outputs.output[i] = 1500 + (600 * outputs.output[i]); + } else { + /* + * Value is NaN, INF or out of band - set to the minimum value. + * This will be clearly visible on the servo status and will limit the risk of accidentally + * spinning motors. It would be deadly in flight. + */ + outputs.output[i] = 900; + } /* output to the servo */ up_pwm_servo_set(i, outputs.output[i]); diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index 6953049264..701955298f 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -402,8 +402,8 @@ PX4IO::task_main() /* mix */ if (_mixers != nullptr) { - /* XXX is this the right count? */ - _mixers->mix(&_outputs.output[0], _max_actuators); + _outputs.timestamp = hrt_absolute_time(); + _outputs.noutputs = _mixers->mix(&_outputs.output[0], _max_actuators); // XXX output actual limited values memcpy(&_controls_effective, &_controls, sizeof(_controls_effective)); @@ -413,7 +413,11 @@ PX4IO::task_main() /* convert to PWM values */ for (unsigned i = 0; i < _max_actuators; i++) { /* last resort: catch NaN, INF and out-of-band errors */ - if (isfinite(_outputs.output[i]) && _outputs.output[i] >= -1.0f && _outputs.output[i] <= 1.0f) { + if (i < _outputs.noutputs && + isfinite(_outputs.output[i]) && + _outputs.output[i] >= -1.0f && + _outputs.output[i] <= 1.0f) { + /* scale for PWM output 900 - 2100us */ _outputs.output[i] = 1500 + (600 * _outputs.output[i]); } else { /* diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index e763e642a1..971ba6a8ea 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -507,12 +507,26 @@ l_actuator_outputs(struct listener *l) 0); } else { + /* + * Catch the case where no rudder is in use and throttle is not + * on output four + */ + float rudder, throttle; + + if (act_outputs.noutputs < 4) { + rudder = 0.0f; + throttle = (act_outputs.output[2] - 900.0f) / 1200.0f; + } else { + rudder = (act_outputs.output[2] - 1500.0f) / 600.0f; + throttle = (act_outputs.output[3] - 900.0f) / 1200.0f; + } + mavlink_msg_hil_controls_send(chan, hrt_absolute_time(), (act_outputs.output[0] - 1500.0f) / 600.0f, (act_outputs.output[1] - 1500.0f) / 600.0f, - 0.0f/*(act_outputs.output[2] - 1500.0f) / 600.0f*/, - (act_outputs.output[2] - 900.0f) / 1200.0f, + rudder, + throttle, (act_outputs.output[4] - 1500.0f) / 600.0f, (act_outputs.output[5] - 1500.0f) / 600.0f, (act_outputs.output[6] - 1500.0f) / 600.0f, diff --git a/apps/uORB/topics/actuator_outputs.h b/apps/uORB/topics/actuator_outputs.h index accd560afb..bbe4290731 100644 --- a/apps/uORB/topics/actuator_outputs.h +++ b/apps/uORB/topics/actuator_outputs.h @@ -53,8 +53,9 @@ #define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */ struct actuator_outputs_s { - uint64_t timestamp; - float output[NUM_ACTUATOR_OUTPUTS]; + uint64_t timestamp; /**< output timestamp in us since system boot */ + float output[NUM_ACTUATOR_OUTPUTS]; /**< output data, in natural output units */ + int noutputs; /**< valid outputs */ }; /* actuator output sets; this list can be expanded as more drivers emerge */ From f2fb8c7960fa251cc4f30bc2b1065759b3ab09bf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 23 Dec 2012 18:10:00 +0100 Subject: [PATCH 186/206] Fix typo --- apps/commander/state_machine_helper.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c index aa916dafa3..c4b9fbb6ae 100644 --- a/apps/commander/state_machine_helper.c +++ b/apps/commander/state_machine_helper.c @@ -611,7 +611,7 @@ uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_ /* NEVER actually switch off HIL without reboot */ if (current_status->flag_hil_enabled && !(mode & VEHICLE_MODE_FLAG_HIL_ENABLED)) { - fprintf(stderr, "[commander] DENYING request to switch of HIL. Please power cycle (safety reasons)\n"); + fprintf(stderr, "[commander] DENYING request to switch off HIL. Please power cycle (safety reasons)\n"); ret = ERROR; } From d4edf2e85c4238387872eb5ee6bc1187117a280d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 23 Dec 2012 17:20:53 -0800 Subject: [PATCH 187/206] Override is now really disabled for multirotors, also I don't think the parameter got ever read by the commander but I might be wrong --- apps/commander/commander.c | 7 +++--- apps/px4io/mixer.c | 51 ++++++++++++++++++++++++-------------- 2 files changed, 36 insertions(+), 22 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 5dfdf83adb..bdf1976b7e 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -1293,6 +1293,8 @@ int commander_thread_main(int argc, char *argv[]) uint64_t failsave_ll_start_time = 0; bool state_changed = true; + bool param_init_forced = true; + while (!thread_should_exit) { @@ -1323,10 +1325,10 @@ int commander_thread_main(int argc, char *argv[]) /* handle it */ handle_command(stat_pub, ¤t_status, &cmd); } - /* update parameters */ orb_check(param_changed_sub, &new_data); - if (new_data) { + if (new_data || param_init_forced) { + param_init_forced = false; /* parameters changed */ orb_copy(ORB_ID(parameter_update), param_changed_sub, ¶m_changed); @@ -1335,7 +1337,6 @@ int commander_thread_main(int argc, char *argv[]) if (param_get(_param_sys_type, &(current_status.system_type)) != OK) { warnx("failed setting new system type"); } - /* disable manual override for all systems that rely on electronic stabilization */ if (current_status.system_type == MAV_TYPE_QUADROTOR || current_status.system_type == MAV_TYPE_HEXAROTOR || diff --git a/apps/px4io/mixer.c b/apps/px4io/mixer.c index 135d97bb34..9cdb98e23b 100644 --- a/apps/px4io/mixer.c +++ b/apps/px4io/mixer.c @@ -84,32 +84,45 @@ mixer_tick(void) int i; bool should_arm; + /* check that we are receiving fresh data from the FMU */ + if ((hrt_absolute_time() - system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) { + /* too many frames without FMU input, time to go to failsafe */ + system_state.mixer_manual_override = true; + system_state.mixer_fmu_available = false; + lib_lowprintf("\nRX timeout\n"); + } + /* * Decide which set of inputs we're using. */ - if (!system_state.mixer_manual_override && system_state.mixer_fmu_available) { - /* we have recent control data from the FMU */ - control_count = PX4IO_OUTPUT_CHANNELS; - control_values = &system_state.fmu_channel_data[0]; + /* this is for planes, where manual override makes sense */ + if(system_state.manual_override_ok) { + /* if everything is ok */ + if (!system_state.mixer_manual_override && system_state.mixer_fmu_available) { + /* we have recent control data from the FMU */ + control_count = PX4IO_OUTPUT_CHANNELS; + control_values = &system_state.fmu_channel_data[0]; + /* when override is on or the fmu is not available */ + } else if (system_state.rc_channels > 0) { + control_count = system_state.rc_channels; + control_values = &system_state.rc_channel_data[0]; + } else { + /* we have no control input (no FMU, no RC) */ - /* check that we are receiving fresh data from the FMU */ - if ((hrt_absolute_time() - system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) { - - /* too many frames without FMU input, time to go to failsafe */ - system_state.mixer_manual_override = true; - system_state.mixer_fmu_available = false; - lib_lowprintf("\nRX timeout\n"); + // XXX builtin failsafe would activate here + control_count = 0; } - } else if (system_state.rc_channels > 0 && system_state.manual_override_ok) { - /* we have control data from an R/C input */ - control_count = system_state.rc_channels; - control_values = &system_state.rc_channel_data[0]; + /* this is for multicopters, etc. where manual override does not make sense */ } else { - /* we have no control input (no FMU, no RC) */ - - // XXX builtin failsafe would activate here - control_count = 0; + /* if the fmu is available whe are good */ + if(system_state.mixer_fmu_available) { + control_count = PX4IO_OUTPUT_CHANNELS; + control_values = &system_state.fmu_channel_data[0]; + /* we better shut everything off */ + } else { + control_count = 0; + } } /* From c259a34a8261a2e2546a0b1bcb9edab1a901644b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 27 Dec 2012 13:17:43 +0100 Subject: [PATCH 188/206] Allowed rc.txt files as well --- ROMFS/scripts/rcS | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/ROMFS/scripts/rcS b/ROMFS/scripts/rcS index 4152494e0e..69d791da52 100755 --- a/ROMFS/scripts/rcS +++ b/ROMFS/scripts/rcS @@ -46,8 +46,12 @@ if [ -f /fs/microsd/etc/rc ] then echo "[init] reading /fs/microsd/etc/rc" sh /fs/microsd/etc/rc -else - echo "[init] script /fs/microsd/etc/rc not present" +fi +# Also consider rc.txt files +if [ -f /fs/microsd/etc/rc.txt ] +then + echo "[init] reading /fs/microsd/etc/rc.txt" + sh /fs/microsd/etc/rc.txt fi # From b2068b4e0e43b8ab5088bba3e84cff18178dfafa Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 27 Dec 2012 17:13:48 +0100 Subject: [PATCH 189/206] WIP on mode switching input --- apps/commander/commander.c | 201 +++++++++++++++++++++++++------------ 1 file changed, 135 insertions(+), 66 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 5dfdf83adb..80b392f99c 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -95,6 +95,9 @@ PARAM_DEFINE_INT32(SYS_FAILSAVE_LL, 0); /**< Go into low-level failsafe after 0 ms */ //PARAM_DEFINE_INT32(SYS_FAILSAVE_HL, 0); /**< Go into high-level failsafe after 0 ms */ +PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f); +PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f); +PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f); #include extern struct system_load_s system_load; @@ -152,6 +155,7 @@ static int led_on(int led); static int led_off(int led); static void do_gyro_calibration(int status_pub, struct vehicle_status_s *status); static void do_mag_calibration(int status_pub, struct vehicle_status_s *status); +static void do_rc_calibration(int status_pub, struct vehicle_status_s *status); static void do_accel_calibration(int status_pub, struct vehicle_status_s *status); static void handle_command(int status_pub, struct vehicle_status_s *current_status, struct vehicle_command_s *cmd); @@ -179,7 +183,7 @@ static int buzzer_init() buzzer = open("/dev/tone_alarm", O_WRONLY); if (buzzer < 0) { - fprintf(stderr, "[commander] Buzzer: open fail\n"); + fprintf(stderr, "[cmd] Buzzer: open fail\n"); return ERROR; } @@ -197,12 +201,12 @@ static int led_init() leds = open(LED_DEVICE_PATH, 0); if (leds < 0) { - fprintf(stderr, "[commander] LED: open fail\n"); + fprintf(stderr, "[cmd] LED: open fail\n"); return ERROR; } if (ioctl(leds, LED_ON, LED_BLUE) || ioctl(leds, LED_ON, LED_AMBER)) { - fprintf(stderr, "[commander] LED: ioctl fail\n"); + fprintf(stderr, "[cmd] LED: ioctl fail\n"); return ERROR; } @@ -268,6 +272,30 @@ void tune_confirm(void) { ioctl(buzzer, TONE_SET_ALARM, 3); } +void do_rc_calibration(int status_pub, struct vehicle_status_s *status) +{ + int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint)); + struct manual_control_setpoint_s sp; + orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp); + + /* set parameters */ + + float p = sp.roll; + param_set(param_find("TRIM_ROLL"), &p); + p = sp.pitch; + param_set(param_find("TRIM_PITCH"), &p); + p = sp.yaw; + param_set(param_find("TRIM_YAW"), &p); + + /* store to permanent storage */ + /* auto-save to EEPROM */ + int save_ret = param_save_default(); + if(save_ret != 0) { + mavlink_log_critical(mavlink_fd, "TRIM CAL: WARN: auto-save of params failed"); + } + mavlink_log_info(mavlink_fd, "[cmd] trim calibration done"); +} + void do_mag_calibration(int status_pub, struct vehicle_status_s *status) { @@ -310,7 +338,7 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status) }; if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null)) { warn("WARNING: failed to set scale / offsets for mag"); - mavlink_log_info(mavlink_fd, "[commander] failed to set scale / offsets for mag"); + mavlink_log_info(mavlink_fd, "[cmd] failed to set scale / offsets for mag"); } /* calibrate range */ @@ -358,7 +386,7 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status) axis_index++; char buf[50]; - sprintf(buf, "[commander] Please rotate around %c", axislabels[axis_index]); + sprintf(buf, "[cmd] Please rotate around %c", axislabels[axis_index]); mavlink_log_info(mavlink_fd, buf); tune_confirm(); @@ -373,7 +401,7 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status) // if ((axis_left / 1000) == 0 && axis_left > 0) { // char buf[50]; - // sprintf(buf, "[commander] %d seconds left for axis %c", axis_left, axislabels[axis_index]); + // sprintf(buf, "[cmd] %d seconds left for axis %c", axis_left, axislabels[axis_index]); // mavlink_log_info(mavlink_fd, buf); // } @@ -410,7 +438,7 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status) calibration_counter++; } else { /* any poll failure for 1s is a reason to abort */ - mavlink_log_info(mavlink_fd, "[commander] mag cal canceled"); + mavlink_log_info(mavlink_fd, "[cmd] mag cal canceled"); break; } } @@ -446,27 +474,27 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status) /* announce and set new offset */ if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) { - fprintf(stderr, "[commander] Setting X mag offset failed!\n"); + fprintf(stderr, "[cmd] Setting X mag offset failed!\n"); } if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) { - fprintf(stderr, "[commander] Setting Y mag offset failed!\n"); + fprintf(stderr, "[cmd] Setting Y mag offset failed!\n"); } if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) { - fprintf(stderr, "[commander] Setting Z mag offset failed!\n"); + fprintf(stderr, "[cmd] Setting Z mag offset failed!\n"); } if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) { - fprintf(stderr, "[commander] Setting X mag scale failed!\n"); + fprintf(stderr, "[cmd] Setting X mag scale failed!\n"); } if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) { - fprintf(stderr, "[commander] Setting Y mag scale failed!\n"); + fprintf(stderr, "[cmd] Setting Y mag scale failed!\n"); } if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) { - fprintf(stderr, "[commander] Setting Z mag scale failed!\n"); + fprintf(stderr, "[cmd] Setting Z mag scale failed!\n"); } /* auto-save to EEPROM */ @@ -489,7 +517,7 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status) (double)mscale.y_scale, (double)mscale.z_scale); mavlink_log_info(mavlink_fd, buf); - mavlink_log_info(mavlink_fd, "[commander] mag calibration done"); + mavlink_log_info(mavlink_fd, "[cmd] mag calibration done"); tune_confirm(); sleep(2); @@ -498,7 +526,7 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status) /* third beep by cal end routine */ } else { - mavlink_log_info(mavlink_fd, "[commander] mag calibration FAILED (NaN)"); + mavlink_log_info(mavlink_fd, "[cmd] mag calibration FAILED (NaN)"); } /* disable calibration mode */ @@ -549,7 +577,7 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status) calibration_counter++; } else { /* any poll failure for 1s is a reason to abort */ - mavlink_log_info(mavlink_fd, "[commander] gyro calibration aborted, retry"); + mavlink_log_info(mavlink_fd, "[cmd] gyro calibration aborted, retry"); return; } } @@ -565,15 +593,15 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status) if (isfinite(gyro_offset[0]) && isfinite(gyro_offset[1]) && isfinite(gyro_offset[2])) { if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_offset[0]))) { - mavlink_log_critical(mavlink_fd, "[commander] Setting X gyro offset failed!"); + mavlink_log_critical(mavlink_fd, "[cmd] Setting X gyro offset failed!"); } if (param_set(param_find("SENS_GYRO_YOFF"), &(gyro_offset[1]))) { - mavlink_log_critical(mavlink_fd, "[commander] Setting Y gyro offset failed!"); + mavlink_log_critical(mavlink_fd, "[cmd] Setting Y gyro offset failed!"); } if (param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_offset[2]))) { - mavlink_log_critical(mavlink_fd, "[commander] Setting Z gyro offset failed!"); + mavlink_log_critical(mavlink_fd, "[cmd] Setting Z gyro offset failed!"); } /* set offsets to actual value */ @@ -599,7 +627,7 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status) // char buf[50]; // sprintf(buf, "cal: x:%8.4f y:%8.4f z:%8.4f", (double)gyro_offset[0], (double)gyro_offset[1], (double)gyro_offset[2]); // mavlink_log_info(mavlink_fd, buf); - mavlink_log_info(mavlink_fd, "[commander] gyro calibration done"); + mavlink_log_info(mavlink_fd, "[cmd] gyro calibration done"); tune_confirm(); sleep(2); @@ -607,7 +635,7 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status) sleep(2); /* third beep by cal end routine */ } else { - mavlink_log_info(mavlink_fd, "[commander] gyro calibration FAILED (NaN)"); + mavlink_log_info(mavlink_fd, "[cmd] gyro calibration FAILED (NaN)"); } close(sub_sensor_combined); @@ -617,7 +645,7 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status) { /* announce change */ - mavlink_log_info(mavlink_fd, "[commander] keep it level and still"); + mavlink_log_info(mavlink_fd, "[cmd] keep it level and still"); /* set to accel calibration mode */ status->flag_preflight_accel_calibration = true; state_machine_publish(status_pub, status, mavlink_fd); @@ -655,7 +683,7 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status) calibration_counter++; } else { /* any poll failure for 1s is a reason to abort */ - mavlink_log_info(mavlink_fd, "[commander] acceleration calibration aborted"); + mavlink_log_info(mavlink_fd, "[cmd] acceleration calibration aborted"); return; } } @@ -674,27 +702,27 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status) float scale = 9.80665f / total_len; if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offset[0]))) { - mavlink_log_critical(mavlink_fd, "[commander] Setting X accel offset failed!"); + mavlink_log_critical(mavlink_fd, "[cmd] Setting X accel offset failed!"); } if (param_set(param_find("SENS_ACC_YOFF"), &(accel_offset[1]))) { - mavlink_log_critical(mavlink_fd, "[commander] Setting Y accel offset failed!"); + mavlink_log_critical(mavlink_fd, "[cmd] Setting Y accel offset failed!"); } if (param_set(param_find("SENS_ACC_ZOFF"), &(accel_offset[2]))) { - mavlink_log_critical(mavlink_fd, "[commander] Setting Z accel offset failed!"); + mavlink_log_critical(mavlink_fd, "[cmd] Setting Z accel offset failed!"); } if (param_set(param_find("SENS_ACC_XSCALE"), &(scale))) { - mavlink_log_critical(mavlink_fd, "[commander] Setting X accel offset failed!"); + mavlink_log_critical(mavlink_fd, "[cmd] Setting X accel offset failed!"); } if (param_set(param_find("SENS_ACC_YSCALE"), &(scale))) { - mavlink_log_critical(mavlink_fd, "[commander] Setting Y accel offset failed!"); + mavlink_log_critical(mavlink_fd, "[cmd] Setting Y accel offset failed!"); } if (param_set(param_find("SENS_ACC_ZSCALE"), &(scale))) { - mavlink_log_critical(mavlink_fd, "[commander] Setting Z accel offset failed!"); + mavlink_log_critical(mavlink_fd, "[cmd] Setting Z accel offset failed!"); } fd = open(ACCEL_DEVICE_PATH, 0); @@ -717,9 +745,9 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status) } //char buf[50]; - //sprintf(buf, "[commander] accel cal: x:%8.4f y:%8.4f z:%8.4f\n", (double)accel_offset[0], (double)accel_offset[1], (double)accel_offset[2]); + //sprintf(buf, "[cmd] accel cal: x:%8.4f y:%8.4f z:%8.4f\n", (double)accel_offset[0], (double)accel_offset[1], (double)accel_offset[2]); //mavlink_log_info(mavlink_fd, buf); - mavlink_log_info(mavlink_fd, "[commander] accel calibration done"); + mavlink_log_info(mavlink_fd, "[cmd] accel calibration done"); tune_confirm(); sleep(2); @@ -727,7 +755,7 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status) sleep(2); /* third beep by cal end routine */ } else { - mavlink_log_info(mavlink_fd, "[commander] accel calibration FAILED (NaN)"); + mavlink_log_info(mavlink_fd, "[cmd] accel calibration FAILED (NaN)"); } /* exit accel calibration mode */ @@ -853,15 +881,15 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT); if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { - mavlink_log_info(mavlink_fd, "[commander] CMD starting gyro calibration"); + mavlink_log_info(mavlink_fd, "[cmd] CMD starting gyro calibration"); tune_confirm(); do_gyro_calibration(status_pub, ¤t_status); - mavlink_log_info(mavlink_fd, "[commander] CMD finished gyro calibration"); + mavlink_log_info(mavlink_fd, "[cmd] CMD finished gyro calibration"); tune_confirm(); do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_STANDBY); result = MAV_RESULT_ACCEPTED; } else { - mavlink_log_critical(mavlink_fd, "[commander] REJECTING gyro calibration"); + mavlink_log_critical(mavlink_fd, "[cmd] REJECTING gyro calibration"); result = MAV_RESULT_DENIED; } handled = true; @@ -873,15 +901,50 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT); if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { - mavlink_log_info(mavlink_fd, "[commander] CMD starting mag calibration"); + mavlink_log_info(mavlink_fd, "[cmd] CMD starting mag calibration"); tune_confirm(); do_mag_calibration(status_pub, ¤t_status); - mavlink_log_info(mavlink_fd, "[commander] CMD finished mag calibration"); + mavlink_log_info(mavlink_fd, "[cmd] CMD finished mag calibration"); tune_confirm(); do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_STANDBY); result = MAV_RESULT_ACCEPTED; } else { - mavlink_log_critical(mavlink_fd, "[commander] CMD REJECTING mag calibration"); + mavlink_log_critical(mavlink_fd, "[cmd] CMD REJECTING mag calibration"); + result = MAV_RESULT_DENIED; + } + handled = true; + } + + /* zero-altitude pressure calibration */ + if ((int)(cmd->param3) == 1) { + /* transition to calibration state */ + do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT); + + if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { + mavlink_log_info(mavlink_fd, "[cmd] zero altitude not implemented"); + tune_confirm(); + } else { + mavlink_log_critical(mavlink_fd, "[cmd] CMD REJECTING mag calibration"); + result = MAV_RESULT_DENIED; + } + handled = true; + } + + /* trim calibration */ + if ((int)(cmd->param4) == 1) { + /* transition to calibration state */ + do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT); + + if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { + mavlink_log_info(mavlink_fd, "[cmd] CMD starting mag calibration"); + tune_confirm(); + do_rc_calibration(status_pub, ¤t_status); + mavlink_log_info(mavlink_fd, "[cmd] CMD finished mag calibration"); + tune_confirm(); + do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_STANDBY); + result = MAV_RESULT_ACCEPTED; + } else { + mavlink_log_critical(mavlink_fd, "[cmd] CMD REJECTING mag calibration"); result = MAV_RESULT_DENIED; } handled = true; @@ -893,15 +956,15 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT); if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { - mavlink_log_info(mavlink_fd, "[commander] CMD starting accel calibration"); + mavlink_log_info(mavlink_fd, "[cmd] CMD starting accel calibration"); tune_confirm(); do_accel_calibration(status_pub, ¤t_status); tune_confirm(); - mavlink_log_info(mavlink_fd, "[commander] CMD finished accel calibration"); + mavlink_log_info(mavlink_fd, "[cmd] CMD finished accel calibration"); do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_STANDBY); result = MAV_RESULT_ACCEPTED; } else { - mavlink_log_critical(mavlink_fd, "[commander] REJECTING accel calibration"); + mavlink_log_critical(mavlink_fd, "[cmd] REJECTING accel calibration"); result = MAV_RESULT_DENIED; } handled = true; @@ -909,8 +972,8 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta /* none found */ if (!handled) { - //fprintf(stderr, "[commander] refusing unsupported calibration request\n"); - mavlink_log_critical(mavlink_fd, "[commander] CMD refusing unsup. calib. request"); + //fprintf(stderr, "[cmd] refusing unsupported calibration request\n"); + mavlink_log_critical(mavlink_fd, "[cmd] CMD refusing unsup. calib. request"); result = MAV_RESULT_UNSUPPORTED; } } @@ -1172,7 +1235,7 @@ int commander_thread_main(int argc, char *argv[]) param_t _param_sys_type = param_find("MAV_TYPE"); /* welcome user */ - printf("[commander] I am in command now!\n"); + printf("[cmd] I am in command now!\n"); /* pthreads for command and subsystem info handling */ // pthread_t command_handling_thread; @@ -1180,17 +1243,17 @@ int commander_thread_main(int argc, char *argv[]) /* initialize */ if (led_init() != 0) { - fprintf(stderr, "[commander] ERROR: Failed to initialize leds\n"); + fprintf(stderr, "[cmd] ERROR: Failed to initialize leds\n"); } if (buzzer_init() != 0) { - fprintf(stderr, "[commander] ERROR: Failed to initialize buzzer\n"); + fprintf(stderr, "[cmd] ERROR: Failed to initialize buzzer\n"); } mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); if (mavlink_fd < 0) { - fprintf(stderr, "[commander] ERROR: Failed to open MAVLink log stream, start mavlink app first.\n"); + fprintf(stderr, "[cmd] ERROR: Failed to open MAVLink log stream, start mavlink app first.\n"); } /* make sure we are in preflight state */ @@ -1212,11 +1275,11 @@ int commander_thread_main(int argc, char *argv[]) state_machine_publish(stat_pub, ¤t_status, mavlink_fd); if (stat_pub < 0) { - printf("[commander] ERROR: orb_advertise for topic vehicle_status failed.\n"); + printf("[cmd] ERROR: orb_advertise for topic vehicle_status failed.\n"); exit(ERROR); } - mavlink_log_info(mavlink_fd, "[commander] system is running"); + mavlink_log_info(mavlink_fd, "[cmd] system is running"); /* create pthreads */ pthread_attr_t subsystem_info_attr; @@ -1344,7 +1407,6 @@ int commander_thread_main(int argc, char *argv[]) } else { current_status.flag_external_manual_override_ok = true; } - printf("param changed, val: %d, override: %s\n", current_status.system_type, (current_status.flag_external_manual_override_ok) ? "ON" : "OFF"); } else { printf("ARMED, rejecting sys type change\n"); } @@ -1453,7 +1515,7 @@ int commander_thread_main(int argc, char *argv[]) if (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT) { low_battery_voltage_actions_done = true; - mavlink_log_critical(mavlink_fd, "[commander] WARNING! LOW BATTERY!"); + mavlink_log_critical(mavlink_fd, "[cmd] WARNING! LOW BATTERY!"); } low_voltage_counter++; @@ -1463,7 +1525,7 @@ int commander_thread_main(int argc, char *argv[]) else if (battery_voltage_valid && (bat_remain < 0.1f /* XXX MAGIC NUMBER */) && (false == critical_battery_voltage_actions_done && true == low_battery_voltage_actions_done)) { if (critical_voltage_counter > CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT) { critical_battery_voltage_actions_done = true; - mavlink_log_critical(mavlink_fd, "[commander] EMERGENCY! CRITICAL BATTERY!"); + mavlink_log_critical(mavlink_fd, "[cmd] EMERGENCY! CRITICAL BATTERY!"); state_machine_emergency(stat_pub, ¤t_status, mavlink_fd); } @@ -1591,8 +1653,16 @@ int commander_thread_main(int argc, char *argv[]) if ((hrt_absolute_time() - sp_man.timestamp) < 100000) { - /* check if left stick is in lower left position --> switch to standby state */ - if ((sp_man.yaw < -STICK_ON_OFF_LIMIT) && sp_man.throttle < STICK_THRUST_RANGE*0.2f) { //TODO: remove hardcoded values + /* + * Check if left stick is in lower left position --> switch to standby state. + * Do this only for multirotors, not for fixed wing aircraft. + */ + if (((current_status.system_type == MAV_TYPE_QUADROTOR) || + (current_status.system_type == MAV_TYPE_HEXAROTOR) || + (current_status.system_type == MAV_TYPE_OCTOROTOR) + ) && + ((sp_man.yaw < -STICK_ON_OFF_LIMIT)) && + (sp_man.throttle < STICK_THRUST_RANGE * 0.2f)) { if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) { update_state_machine_disarm(stat_pub, ¤t_status, mavlink_fd); stick_on_counter = 0; @@ -1604,7 +1674,7 @@ int commander_thread_main(int argc, char *argv[]) } /* check if left stick is in lower right position --> arm */ - if (sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE*0.2f) { //TODO: remove hardcoded values + if (sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.2f) { if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) { update_state_machine_arm(stat_pub, ¤t_status, mavlink_fd); stick_on_counter = 0; @@ -1614,17 +1684,16 @@ int commander_thread_main(int argc, char *argv[]) stick_off_counter = 0; } } - //printf("RC: y:%i/t:%i s:%i chans: %i\n", rc_yaw_scale, rc_throttle_scale, mode_switch_rc_value, rc.chan_count); - if (sp_man.aux1_cam_pan_flaps > STICK_ON_OFF_LIMIT) { + if (sp_man.manual_override_switch > STICK_ON_OFF_LIMIT) { update_state_machine_mode_manual(stat_pub, ¤t_status, mavlink_fd); } else { - if (sp_man.override_mode_switch > STICK_ON_OFF_LIMIT) { + if (sp_man.auto_mode_switch > STICK_ON_OFF_LIMIT) { //update_state_machine_mode_manual(stat_pub, ¤t_status, mavlink_fd); // XXX hack update_state_machine_mode_stabilized(stat_pub, ¤t_status, mavlink_fd); - } else if (sp_man.override_mode_switch < -STICK_ON_OFF_LIMIT) { + } else if (sp_man.auto_mode_switch < -STICK_ON_OFF_LIMIT) { update_state_machine_mode_auto(stat_pub, ¤t_status, mavlink_fd); } else { @@ -1635,9 +1704,9 @@ int commander_thread_main(int argc, char *argv[]) /* handle the case where RC signal was regained */ if (!current_status.rc_signal_found_once) { current_status.rc_signal_found_once = true; - mavlink_log_critical(mavlink_fd, "[commander] DETECTED RC SIGNAL FIRST TIME."); + mavlink_log_critical(mavlink_fd, "[cmd] DETECTED RC SIGNAL FIRST TIME."); } else { - if (current_status.rc_signal_lost) mavlink_log_critical(mavlink_fd, "[commander] RECOVERY - RC SIGNAL GAINED!"); + if (current_status.rc_signal_lost) mavlink_log_critical(mavlink_fd, "[cmd] RECOVERY - RC SIGNAL GAINED!"); } current_status.rc_signal_cutting_off = false; @@ -1650,7 +1719,7 @@ int commander_thread_main(int argc, char *argv[]) if (!current_status.rc_signal_cutting_off || ((hrt_absolute_time() - last_print_time) > 5000000)) { /* only complain if the offboard control is NOT active */ current_status.rc_signal_cutting_off = true; - mavlink_log_critical(mavlink_fd, "[commander] CRITICAL - NO REMOTE SIGNAL!"); + mavlink_log_critical(mavlink_fd, "[cmd] CRITICAL - NO REMOTE SIGNAL!"); last_print_time = hrt_absolute_time(); } /* flag as lost and update interval since when the signal was lost (to initiate RTL after some time) */ @@ -1709,10 +1778,10 @@ int commander_thread_main(int argc, char *argv[]) state_changed = true; tune_confirm(); - mavlink_log_critical(mavlink_fd, "[commander] DETECTED OFFBOARD CONTROL SIGNAL FIRST"); + mavlink_log_critical(mavlink_fd, "[cmd] DETECTED OFFBOARD CONTROL SIGNAL FIRST"); } else { if (current_status.offboard_control_signal_lost) { - mavlink_log_critical(mavlink_fd, "[commander] OK:RECOVERY OFFBOARD CONTROL"); + mavlink_log_critical(mavlink_fd, "[cmd] OK:RECOVERY OFFBOARD CONTROL"); state_changed = true; tune_confirm(); } @@ -1736,7 +1805,7 @@ int commander_thread_main(int argc, char *argv[]) /* print error message for first RC glitch and then every 5 s / 5000 ms) */ if (!current_status.offboard_control_signal_weak || ((hrt_absolute_time() - last_print_time) > 5000000)) { current_status.offboard_control_signal_weak = true; - mavlink_log_critical(mavlink_fd, "[commander] CRIT:NO OFFBOARD CONTROL!"); + mavlink_log_critical(mavlink_fd, "[cmd] CRIT:NO OFFBOARD CONTROL!"); last_print_time = hrt_absolute_time(); } /* flag as lost and update interval since when the signal was lost (to initiate RTL after some time) */ @@ -1799,7 +1868,7 @@ int commander_thread_main(int argc, char *argv[]) close(sensor_sub); close(cmd_sub); - printf("[commander] exiting..\n"); + printf("[cmd] exiting..\n"); fflush(stdout); thread_running = false; From 61d7e1d28552ddd7652b1d1b888c51a2eae78967 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 27 Dec 2012 17:47:51 +0100 Subject: [PATCH 190/206] Reverted changes to multirotor rate controller, changing to a discrete derivative does not help --- .../multirotor_rate_control.c | 44 +++++++++++-------- 1 file changed, 26 insertions(+), 18 deletions(-) diff --git a/apps/multirotor_att_control/multirotor_rate_control.c b/apps/multirotor_att_control/multirotor_rate_control.c index edb50a96e8..93f7085aec 100644 --- a/apps/multirotor_att_control/multirotor_rate_control.c +++ b/apps/multirotor_att_control/multirotor_rate_control.c @@ -150,13 +150,16 @@ static int parameters_update(const struct mc_rate_control_param_handles *h, stru void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp, const float rates[], struct actuator_controls_s *actuators) { + static float roll_control_last = 0; + static float pitch_control_last = 0; static uint64_t last_run = 0; const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f; static uint64_t last_input = 0; - static PID_t pitch_rate_controller; - static PID_t roll_rate_controller; - + float dT_input = (hrt_absolute_time() - last_input) / 1000000.0f; + if (last_input != rate_sp->timestamp) { + last_input = rate_sp->timestamp; + } last_run = hrt_absolute_time(); @@ -172,32 +175,37 @@ void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp, parameters_init(&h); parameters_update(&h, &p); initialized = true; - - pid_init(&pitch_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1000.0f,1000.0f, PID_MODE_DERIVATIV_CALC); - pid_init(&roll_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1000.0f,1000.0f, PID_MODE_DERIVATIV_CALC); - } /* load new parameters with lower rate */ - if (motor_skip_counter % 500 == 0) { + if (motor_skip_counter % 2500 == 0) { /* update parameters from storage */ parameters_update(&h, &p); // warnx("rate ctrl: p.yawrate_p: %8.4f, loop: %d Hz, input: %d Hz", // (double)p.yawrate_p, (int)(1.0f/deltaT), (int)(1.0f/dT_input)); - - /* load new parameters with lower rate */ - parameters_update(&h, &p); - - /* apply parameters */ - pid_set_parameters(&pitch_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1000.0f, 1000.0f); - pid_set_parameters(&roll_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1000.0f, 1000.0f); } + /* calculate current control outputs */ + + /* control pitch (forward) output */ + float pitch_control = p.attrate_p * (rate_sp->pitch - rates[1]) - (p.attrate_d * pitch_control_last); + /* increase resilience to faulty control inputs */ + if (isfinite(pitch_control)) { + pitch_control_last = pitch_control; + } else { + pitch_control = 0.0f; + warnx("rej. NaN ctrl pitch"); + } /* control roll (left/right) output */ - float roll_control = pid_calculate(&roll_rate_controller, rate_sp->roll , rates[0], 0.0f, deltaT); - float pitch_control = pid_calculate(&pitch_rate_controller, rate_sp->pitch , rates[1], 0.0f, deltaT); - + float roll_control = p.attrate_p * (rate_sp->roll - rates[0]) - (p.attrate_d * roll_control_last); + /* increase resilience to faulty control inputs */ + if (isfinite(roll_control)) { + roll_control_last = roll_control; + } else { + roll_control = 0.0f; + warnx("rej. NaN ctrl roll"); + } /* control yaw rate */ float yaw_rate_control = p.yawrate_p * (rate_sp->yaw - rates[2]); From f5bad08bd0f4e0f6506deeac9d369b2b9c2d9e32 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 27 Dec 2012 18:27:08 +0100 Subject: [PATCH 191/206] Cleaned up control mode state machine / flight mode / navigation state machine still needs a bit cleaning up --- apps/commander/commander.c | 76 +++- apps/commander/state_machine_helper.c | 146 +++++--- apps/commander/state_machine_helper.h | 9 + .../fixedwing_att_control_main.c | 85 +++-- .../multirotor_att_control_main.c | 85 +++-- apps/sensors/sensor_params.c | 81 ++++- apps/sensors/sensors.cpp | 336 ++++++++++++------ apps/uORB/topics/manual_control_setpoint.h | 40 ++- apps/uORB/topics/rc_channels.h | 34 +- apps/uORB/topics/vehicle_status.h | 33 +- 10 files changed, 625 insertions(+), 300 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index a088ba1ba6..b5df8a8b34 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -1268,6 +1268,8 @@ int commander_thread_main(int argc, char *argv[]) current_status.offboard_control_signal_lost = true; /* allow manual override initially */ current_status.flag_external_manual_override_ok = true; + /* flag position info as bad, do not allow auto mode */ + current_status.flag_vector_flight_mode_ok = false; /* advertise to ORB */ stat_pub = orb_advertise(ORB_ID(vehicle_status), ¤t_status); @@ -1654,6 +1656,72 @@ int commander_thread_main(int argc, char *argv[]) if ((hrt_absolute_time() - sp_man.timestamp) < 100000) { + /* + * Check if manual control modes have to be switched + */ + if (!isfinite(sp_man.manual_mode_switch)) { + + /* this switch is not properly mapped, set default */ + if ((current_status.system_type == MAV_TYPE_QUADROTOR) || + (current_status.system_type == MAV_TYPE_HEXAROTOR) || + (current_status.system_type == MAV_TYPE_OCTOROTOR)) { + + /* assuming a rotary wing, fall back to SAS */ + current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + } else { + + /* assuming a fixed wing, fall back to direct pass-through */ + current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT; + } + + } else if (sp_man.manual_sas_switch < -STICK_ON_OFF_LIMIT) { + + /* bottom stick position, set direct mode for vehicles supporting it */ + if ((current_status.system_type == MAV_TYPE_QUADROTOR) || + (current_status.system_type == MAV_TYPE_HEXAROTOR) || + (current_status.system_type == MAV_TYPE_OCTOROTOR)) { + + /* assuming a rotary wing, fall back to SAS */ + current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + } else { + + /* assuming a fixed wing, fall back to direct pass-through */ + current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT; + } + + } else if (sp_man.manual_sas_switch > STICK_ON_OFF_LIMIT) { + + /* top stick position, set SAS for all vehicle types */ + current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + + } else { + /* center stick position, set rate control */ + current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_RATES; + } + + /* + * Check if manual stability control modes have to be switched + */ + if (!isfinite(sp_man.manual_sas_switch)) { + + /* this switch is not properly mapped, set default */ + current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS; + + } else if (sp_man.manual_sas_switch < -STICK_ON_OFF_LIMIT) { + + /* bottom stick position, set altitude hold */ + current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ALTITUDE; + + } else if (sp_man.manual_sas_switch > STICK_ON_OFF_LIMIT) { + + /* top stick position */ + current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_SIMPLE; + + } else { + /* center stick position, set default */ + current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS; + } + /* * Check if left stick is in lower left position --> switch to standby state. * Do this only for multirotors, not for fixed wing aircraft. @@ -1686,19 +1754,21 @@ int commander_thread_main(int argc, char *argv[]) } } + /* check manual override switch - switch to manual or auto mode */ if (sp_man.manual_override_switch > STICK_ON_OFF_LIMIT) { + /* enable manual override */ update_state_machine_mode_manual(stat_pub, ¤t_status, mavlink_fd); } else { + /* check auto mode switch for correct mode */ if (sp_man.auto_mode_switch > STICK_ON_OFF_LIMIT) { - //update_state_machine_mode_manual(stat_pub, ¤t_status, mavlink_fd); - // XXX hack + /* enable stabilized mode */ update_state_machine_mode_stabilized(stat_pub, ¤t_status, mavlink_fd); } else if (sp_man.auto_mode_switch < -STICK_ON_OFF_LIMIT) { update_state_machine_mode_auto(stat_pub, ¤t_status, mavlink_fd); } else { - update_state_machine_mode_stabilized(stat_pub, ¤t_status, mavlink_fd); + update_state_machine_mode_hold(stat_pub, ¤t_status, mavlink_fd); } } diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c index c4b9fbb6ae..4152142dfb 100644 --- a/apps/commander/state_machine_helper.c +++ b/apps/commander/state_machine_helper.c @@ -93,8 +93,8 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con /* set system flags according to state */ current_status->flag_system_armed = true; - fprintf(stderr, "[commander] EMERGENCY LANDING!\n"); - mavlink_log_critical(mavlink_fd, "[commander] EMERGENCY LANDING!"); + fprintf(stderr, "[cmd] EMERGENCY LANDING!\n"); + mavlink_log_critical(mavlink_fd, "[cmd] EMERGENCY LANDING!"); break; case SYSTEM_STATE_EMCY_CUTOFF: @@ -103,8 +103,8 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con /* set system flags according to state */ current_status->flag_system_armed = false; - fprintf(stderr, "[commander] EMERGENCY MOTOR CUTOFF!\n"); - mavlink_log_critical(mavlink_fd, "[commander] EMERGENCY MOTOR CUTOFF!"); + fprintf(stderr, "[cmd] EMERGENCY MOTOR CUTOFF!\n"); + mavlink_log_critical(mavlink_fd, "[cmd] EMERGENCY MOTOR CUTOFF!"); break; case SYSTEM_STATE_GROUND_ERROR: @@ -114,8 +114,8 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con /* prevent actuators from arming */ current_status->flag_system_armed = false; - fprintf(stderr, "[commander] GROUND ERROR, locking down propulsion system\n"); - mavlink_log_critical(mavlink_fd, "[commander] GROUND ERROR, locking down propulsion system"); + fprintf(stderr, "[cmd] GROUND ERROR, locking down propulsion system\n"); + mavlink_log_critical(mavlink_fd, "[cmd] GROUND ERROR, locking down propulsion system"); break; case SYSTEM_STATE_PREFLIGHT: @@ -123,10 +123,10 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) { /* set system flags according to state */ current_status->flag_system_armed = false; - mavlink_log_critical(mavlink_fd, "[commander] Switched to PREFLIGHT state"); + mavlink_log_critical(mavlink_fd, "[cmd] Switched to PREFLIGHT state"); } else { invalid_state = true; - mavlink_log_critical(mavlink_fd, "[commander] REFUSED to switch to PREFLIGHT state"); + mavlink_log_critical(mavlink_fd, "[cmd] REFUSED to switch to PREFLIGHT state"); } break; @@ -136,13 +136,13 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con invalid_state = false; /* set system flags according to state */ current_status->flag_system_armed = false; - mavlink_log_critical(mavlink_fd, "[commander] REBOOTING SYSTEM"); + mavlink_log_critical(mavlink_fd, "[cmd] REBOOTING SYSTEM"); usleep(500000); up_systemreset(); /* SPECIAL CASE: NEVER RETURNS FROM THIS FUNCTION CALL */ } else { invalid_state = true; - mavlink_log_critical(mavlink_fd, "[commander] REFUSED to REBOOT"); + mavlink_log_critical(mavlink_fd, "[cmd] REFUSED to REBOOT"); } break; @@ -152,7 +152,7 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con /* standby enforces disarmed */ current_status->flag_system_armed = false; - mavlink_log_critical(mavlink_fd, "[commander] Switched to STANDBY state"); + mavlink_log_critical(mavlink_fd, "[cmd] Switched to STANDBY state"); break; case SYSTEM_STATE_GROUND_READY: @@ -162,7 +162,7 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con /* ground ready has motors / actuators armed */ current_status->flag_system_armed = true; - mavlink_log_critical(mavlink_fd, "[commander] Switched to GROUND READY state"); + mavlink_log_critical(mavlink_fd, "[cmd] Switched to GROUND READY state"); break; case SYSTEM_STATE_AUTO: @@ -172,7 +172,7 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con /* auto is airborne and in auto mode, motors armed */ current_status->flag_system_armed = true; - mavlink_log_critical(mavlink_fd, "[commander] Switched to FLYING / AUTO mode"); + mavlink_log_critical(mavlink_fd, "[cmd] Switched to FLYING / AUTO mode"); break; case SYSTEM_STATE_STABILIZED: @@ -180,7 +180,7 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con /* set system flags according to state */ current_status->flag_system_armed = true; - mavlink_log_critical(mavlink_fd, "[commander] Switched to FLYING / STABILIZED mode"); + mavlink_log_critical(mavlink_fd, "[cmd] Switched to FLYING / STABILIZED mode"); break; case SYSTEM_STATE_MANUAL: @@ -188,7 +188,7 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con /* set system flags according to state */ current_status->flag_system_armed = true; - mavlink_log_critical(mavlink_fd, "[commander] Switched to FLYING / MANUAL mode"); + mavlink_log_critical(mavlink_fd, "[cmd] Switched to FLYING / MANUAL mode"); break; default: @@ -203,7 +203,7 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con ret = OK; } if (invalid_state) { - mavlink_log_critical(mavlink_fd, "[commander] REJECTING invalid state transition"); + mavlink_log_critical(mavlink_fd, "[cmd] REJECTING invalid state transition"); ret = ERROR; } return ret; @@ -232,7 +232,7 @@ void state_machine_publish(int status_pub, struct vehicle_status_s *current_stat current_status->onboard_control_sensors_enabled |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x4000 : 0; orb_publish(ORB_ID(vehicle_status), status_pub, current_status); - printf("[commander] new state: %s\n", system_state_txt[current_status->state_machine]); + printf("[cmd] new state: %s\n", system_state_txt[current_status->state_machine]); } void publish_armed_status(const struct vehicle_status_s *current_status) { @@ -250,7 +250,7 @@ void publish_armed_status(const struct vehicle_status_s *current_status) { */ void state_machine_emergency_always_critical(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd) { - fprintf(stderr, "[commander] EMERGENCY HANDLER\n"); + fprintf(stderr, "[cmd] EMERGENCY HANDLER\n"); /* Depending on the current state go to one of the error states */ if (current_status->state_machine == SYSTEM_STATE_PREFLIGHT || current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_GROUND_READY) { @@ -262,7 +262,7 @@ void state_machine_emergency_always_critical(int status_pub, struct vehicle_stat //do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MISSION_ABORT); } else { - fprintf(stderr, "[commander] Unknown system state: #%d\n", current_status->state_machine); + fprintf(stderr, "[cmd] Unknown system state: #%d\n", current_status->state_machine); } } @@ -272,7 +272,7 @@ void state_machine_emergency(int status_pub, struct vehicle_status_s *current_st state_machine_emergency_always_critical(status_pub, current_status, mavlink_fd); } else { - //global_data_send_mavlink_statustext_message_out("[commander] ERROR: take action immediately! (did not switch to error state because the system is in manual mode)", MAV_SEVERITY_CRITICAL); + //global_data_send_mavlink_statustext_message_out("[cmd] ERROR: take action immediately! (did not switch to error state because the system is in manual mode)", MAV_SEVERITY_CRITICAL); } } @@ -497,7 +497,7 @@ void update_state_machine_no_position_fix(int status_pub, struct vehicle_status_ void update_state_machine_arm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd) { if (current_status->state_machine == SYSTEM_STATE_STANDBY) { - printf("[commander] arming\n"); + printf("[cmd] arming\n"); do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY); } } @@ -505,11 +505,11 @@ void update_state_machine_arm(int status_pub, struct vehicle_status_s *current_s void update_state_machine_disarm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd) { if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) { - printf("[commander] going standby\n"); + printf("[cmd] going standby\n"); do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY); } else if (current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) { - printf("[commander] MISSION ABORT!\n"); + printf("[cmd] MISSION ABORT!\n"); do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY); } } @@ -518,6 +518,7 @@ void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *c { int old_mode = current_status->flight_mode; current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL; + current_status->flag_control_manual_enabled = true; /* enable attitude control per default */ current_status->flag_control_attitude_enabled = true; @@ -525,58 +526,91 @@ void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *c if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd); if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) { - printf("[commander] manual mode\n"); + printf("[cmd] manual mode\n"); do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MANUAL); } } void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd) { - int old_mode = current_status->flight_mode; - current_status->flight_mode = VEHICLE_FLIGHT_MODE_STABILIZED; - current_status->flag_control_manual_enabled = true; - current_status->flag_control_attitude_enabled = true; - current_status->flag_control_rates_enabled = true; - if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd); - + if (!current_status->flag_vector_flight_mode_ok) { + mavlink_log_critical(mavlink_fd, "NO POS LOCK, REJ. STAB MODE"); + return; + } if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_AUTO) { - printf("[commander] stabilized mode\n"); + printf("[cmd] stabilized mode\n"); + int old_mode = current_status->flight_mode; + current_status->flight_mode = VEHICLE_FLIGHT_MODE_STAB; + current_status->flag_control_manual_enabled = false; + current_status->flag_control_attitude_enabled = true; + current_status->flag_control_rates_enabled = true; do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STABILIZED); + if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd); + + } +} + +void update_state_machine_mode_hold(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd) +{ + if (!current_status->flag_vector_flight_mode_ok) { + mavlink_log_critical(mavlink_fd, "NO POS LOCK, REJ. HOLD MODE"); + return; + } + + if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_AUTO) { + printf("[cmd] stabilized mode\n"); + int old_mode = current_status->flight_mode; + current_status->flight_mode = VEHICLE_FLIGHT_MODE_HOLD; + current_status->flag_control_manual_enabled = false; + current_status->flag_control_attitude_enabled = true; + current_status->flag_control_rates_enabled = true; + do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STABILIZED); + if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd); } } void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd) { - int old_mode = current_status->flight_mode; - current_status->flight_mode = VEHICLE_FLIGHT_MODE_AUTO; - current_status->flag_control_manual_enabled = true; - current_status->flag_control_attitude_enabled = true; - current_status->flag_control_rates_enabled = true; - if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd); - + if (!current_status->flag_vector_flight_mode_ok) { + mavlink_log_critical(mavlink_fd, "NO POS LOCK, REJ. AUTO MODE"); + return; + } + if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_STABILIZED) { - printf("[commander] auto mode\n"); + printf("[cmd] auto mode\n"); + int old_mode = current_status->flight_mode; + current_status->flight_mode = VEHICLE_FLIGHT_MODE_AUTO; + current_status->flag_control_manual_enabled = false; + current_status->flag_control_attitude_enabled = true; + current_status->flag_control_rates_enabled = true; do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_AUTO); + if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd); } } uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode) { - printf("[commander] Requested new mode: %d\n", (int)mode); uint8_t ret = 1; - /* Switch on HIL if in standby and not already in HIL mode */ - if ((current_status->state_machine == SYSTEM_STATE_STANDBY) && (mode & VEHICLE_MODE_FLAG_HIL_ENABLED) + /* Switch on HIL if in standby and not already in HIL mode */ + if ((mode & VEHICLE_MODE_FLAG_HIL_ENABLED) && !current_status->flag_hil_enabled) { - /* Enable HIL on request */ - current_status->flag_hil_enabled = true; - ret = OK; - state_machine_publish(status_pub, current_status, mavlink_fd); - publish_armed_status(current_status); - printf("[commander] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n"); - } else if (current_status->state_machine != SYSTEM_STATE_STANDBY) { - mavlink_log_critical(mavlink_fd, "[commander] REJECTING HIL, not in standby.") + if ((current_status->state_machine == SYSTEM_STATE_STANDBY)) { + /* Enable HIL on request */ + current_status->flag_hil_enabled = true; + ret = OK; + state_machine_publish(status_pub, current_status, mavlink_fd); + publish_armed_status(current_status); + printf("[cmd] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n"); + } else if (current_status->state_machine != SYSTEM_STATE_STANDBY && + current_status->flag_system_armed) { + + mavlink_log_critical(mavlink_fd, "[cmd] REJECTING HIL, disarm first!") + } else { + + mavlink_log_critical(mavlink_fd, "[cmd] REJECTING HIL, not in standby.") + } } /* switch manual / auto */ @@ -595,7 +629,7 @@ uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_ if (current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) { do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY); ret = OK; - printf("[commander] arming due to command request\n"); + printf("[cmd] arming due to command request\n"); } } @@ -605,13 +639,14 @@ uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_ if (current_status->state_machine == SYSTEM_STATE_GROUND_READY) { do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY); ret = OK; - printf("[commander] disarming due to command request\n"); + printf("[cmd] disarming due to command request\n"); } } /* NEVER actually switch off HIL without reboot */ if (current_status->flag_hil_enabled && !(mode & VEHICLE_MODE_FLAG_HIL_ENABLED)) { - fprintf(stderr, "[commander] DENYING request to switch off HIL. Please power cycle (safety reasons)\n"); + fprintf(stderr, "[cmd] DENYING request to switch off HIL. Please power cycle (safety reasons)\n"); + mavlink_log_critical(mavlink_fd, "[cmd] Power-cycle to exit HIL"); ret = ERROR; } @@ -636,7 +671,8 @@ uint8_t update_state_machine_custom_mode_request(int status_pub, struct vehicle_ if (current_system_state == SYSTEM_STATE_STANDBY || current_system_state == SYSTEM_STATE_PREFLIGHT) { printf("system will reboot\n"); - //global_data_send_mavlink_statustext_message_out("Rebooting autopilot.. ", MAV_SEVERITY_INFO); + mavlink_log_critical(mavlink_fd, "[cmd] Rebooting.."); + usleep(200000); do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_REBOOT); ret = 0; } diff --git a/apps/commander/state_machine_helper.h b/apps/commander/state_machine_helper.h index c4d1b78a57..815645089a 100644 --- a/apps/commander/state_machine_helper.h +++ b/apps/commander/state_machine_helper.h @@ -127,6 +127,15 @@ void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *c */ void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd); +/** + * Handle state machine if mode switch is hold + * + * @param status_pub file descriptor for state update topic publication + * @param current_status pointer to the current state machine to operate on + * @param mavlink_fd file descriptor for MAVLink statustext messages + */ +void update_state_machine_mode_hold(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd); + /** * Handle state machine if mode switch is auto * diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index 3e1fc49526..9c450e68ec 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -195,44 +195,61 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) /* pass through throttle */ actuators.control[3] = att_sp.thrust; - } else if (vstatus.state_machine == SYSTEM_STATE_STABILIZED) { + /* set flaps to zero */ + actuators.control[4] = 0.0f; - /* if the RC signal is lost, try to stay level and go slowly back down to ground */ - if(vstatus.rc_signal_lost) { - - // XXX define failsafe throttle param - //param_get(failsafe_throttle_handle, &failsafe_throttle); - att_sp.roll_body = 0.3f; - att_sp.pitch_body = 0.0f; - att_sp.thrust = 0.5f; + } else { + if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { - // XXX disable yaw control, loiter + /* if the RC signal is lost, try to stay level and go slowly back down to ground */ + if(vstatus.rc_signal_lost) { + + // XXX define failsafe throttle param + //param_get(failsafe_throttle_handle, &failsafe_throttle); + att_sp.roll_body = 0.3f; + att_sp.pitch_body = 0.0f; + att_sp.thrust = 0.5f; - } else { - - att_sp.roll_body = manual_sp.roll; - att_sp.pitch_body = manual_sp.pitch; - att_sp.yaw_body = 0; - att_sp.thrust = manual_sp.throttle; - att_sp.timestamp = hrt_absolute_time(); + // XXX disable yaw control, loiter + + } else { + + att_sp.roll_body = manual_sp.roll; + att_sp.pitch_body = manual_sp.pitch; + att_sp.yaw_body = 0; + att_sp.thrust = manual_sp.throttle; + att_sp.timestamp = hrt_absolute_time(); + } + + /* attitude control */ + fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp); + + /* angular rate control */ + fixedwing_att_control_rates(&rates_sp, gyro, &actuators); + + /* pass through throttle */ + actuators.control[3] = att_sp.thrust; + + /* pass through flaps */ + if (isfinite(manual_sp.flaps)) { + actuators.control[4] = manual_sp.flaps; + } else { + actuators.control[4] = 0.0f; + } + + } else if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) { + /* directly pass through values */ + actuators.control[0] = manual_sp.roll; + /* positive pitch means negative actuator -> pull up */ + actuators.control[1] = manual_sp.pitch; + actuators.control[2] = manual_sp.yaw; + actuators.control[3] = manual_sp.throttle; + if (isfinite(manual_sp.flaps)) { + actuators.control[4] = manual_sp.flaps; + } else { + actuators.control[4] = 0.0f; + } } - - /* attitude control */ - fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp); - - /* angular rate control */ - fixedwing_att_control_rates(&rates_sp, gyro, &actuators); - - /* pass through throttle */ - actuators.control[3] = att_sp.thrust; - - } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) { - /* directly pass through values */ - actuators.control[0] = manual_sp.roll; - /* positive pitch means negative actuator -> pull up */ - actuators.control[1] = manual_sp.pitch; - actuators.control[2] = manual_sp.yaw; - actuators.control[3] = manual_sp.throttle; } /* publish rates */ diff --git a/apps/multirotor_att_control/multirotor_att_control_main.c b/apps/multirotor_att_control/multirotor_att_control_main.c index ce1e52c1ba..f184859a3f 100644 --- a/apps/multirotor_att_control/multirotor_att_control_main.c +++ b/apps/multirotor_att_control/multirotor_att_control_main.c @@ -232,19 +232,9 @@ mc_thread_main(int argc, char *argv[]) /* STEP 2: publish the result to the vehicle actuators */ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); } - /* decide wether we want rate or position input */ - } - else if (state.flag_control_manual_enabled) { + - /* manual inputs, from RC control or joystick */ - if (state.flag_control_rates_enabled && !state.flag_control_attitude_enabled) { - rates_sp.roll = manual.roll; - - rates_sp.pitch = manual.pitch; - rates_sp.yaw = manual.yaw; - rates_sp.thrust = manual.throttle; - rates_sp.timestamp = hrt_absolute_time(); - } + } else if (state.flag_control_manual_enabled) { if (state.flag_control_attitude_enabled) { @@ -258,7 +248,7 @@ mc_thread_main(int argc, char *argv[]) static bool rc_loss_first_time = true; /* if the RC signal is lost, try to stay level and go slowly back down to ground */ - if(state.rc_signal_lost) { + if (state.rc_signal_lost) { /* the failsafe throttle is stored as a parameter, as it depends on the copter and the payload */ param_get(failsafe_throttle_handle, &failsafe_throttle); att_sp.roll_body = 0.0f; @@ -285,41 +275,66 @@ mc_thread_main(int argc, char *argv[]) att_sp.yaw_body = att.yaw; } - /* only move setpoint if manual input is != 0 */ + /* act if stabilization is active or if the (nonsense) direct pass through mode is set */ + if (state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS || + state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) { - if(manual.mode == MANUAL_CONTROL_MODE_ATT_YAW_POS) { - if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) { + if (state.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE) { rates_sp.yaw = manual.yaw; control_yaw_position = false; - first_time_after_yaw_speed_control = true; } else { - if (first_time_after_yaw_speed_control) { - att_sp.yaw_body = att.yaw; - first_time_after_yaw_speed_control = false; + /* + * This mode SHOULD be the default mode, which is: + * VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS + * + * However, we fall back to this setting for all other (nonsense) + * settings as well. + */ + + /* only move setpoint if manual input is != 0 */ + if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) { + rates_sp.yaw = manual.yaw; + control_yaw_position = false; + first_time_after_yaw_speed_control = true; + } else { + if (first_time_after_yaw_speed_control) { + att_sp.yaw_body = att.yaw; + first_time_after_yaw_speed_control = false; + } + control_yaw_position = true; } - control_yaw_position = true; } - } else if (manual.mode == MANUAL_CONTROL_MODE_ATT_YAW_RATE) { - rates_sp.yaw = manual.yaw; - control_yaw_position = false; } att_sp.thrust = manual.throttle; att_sp.timestamp = hrt_absolute_time(); } - } - /* STEP 2: publish the result to the vehicle actuators */ - orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); - if (motor_test_mode) { - printf("testmode"); - att_sp.roll_body = 0.0f; - att_sp.pitch_body = 0.0f; - att_sp.yaw_body = 0.0f; - att_sp.thrust = 0.1f; - att_sp.timestamp = hrt_absolute_time(); - /* STEP 2: publish the result to the vehicle actuators */ + /* STEP 2: publish the controller output */ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); + + if (motor_test_mode) { + printf("testmode"); + att_sp.roll_body = 0.0f; + att_sp.pitch_body = 0.0f; + att_sp.yaw_body = 0.0f; + att_sp.thrust = 0.1f; + att_sp.timestamp = hrt_absolute_time(); + /* STEP 2: publish the result to the vehicle actuators */ + orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); + } + + } else { + /* manual rate inputs, from RC control or joystick */ + if (state.flag_control_rates_enabled && + state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_RATES) { + rates_sp.roll = manual.roll; + + rates_sp.pitch = manual.pitch; + rates_sp.yaw = manual.yaw; + rates_sp.thrust = manual.throttle; + rates_sp.timestamp = hrt_absolute_time(); + } } } diff --git a/apps/sensors/sensor_params.c b/apps/sensors/sensor_params.c index 37ba0ec3ef..1546fb56d2 100644 --- a/apps/sensors/sensor_params.c +++ b/apps/sensors/sensor_params.c @@ -69,60 +69,100 @@ PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f); PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f); PARAM_DEFINE_FLOAT(RC1_REV, 1.0f); PARAM_DEFINE_FLOAT(RC1_DZ, 0.0f); -PARAM_DEFINE_FLOAT(RC1_EXP, 0.0f); +// PARAM_DEFINE_FLOAT(RC1_EXP, 0.0f); PARAM_DEFINE_FLOAT(RC2_MIN, 1000); PARAM_DEFINE_FLOAT(RC2_TRIM, 1500); PARAM_DEFINE_FLOAT(RC2_MAX, 2000); PARAM_DEFINE_FLOAT(RC2_REV, 1.0f); PARAM_DEFINE_FLOAT(RC2_DZ, 0.0f); -PARAM_DEFINE_FLOAT(RC2_EXP, 0.0f); +// PARAM_DEFINE_FLOAT(RC2_EXP, 0.0f); PARAM_DEFINE_FLOAT(RC3_MIN, 1000); PARAM_DEFINE_FLOAT(RC3_TRIM, 1500); PARAM_DEFINE_FLOAT(RC3_MAX, 2000); PARAM_DEFINE_FLOAT(RC3_REV, 1.0f); PARAM_DEFINE_FLOAT(RC3_DZ, 0.0f); -PARAM_DEFINE_FLOAT(RC3_EXP, 0.0f); +// PARAM_DEFINE_FLOAT(RC3_EXP, 0.0f); PARAM_DEFINE_FLOAT(RC4_MIN, 1000); PARAM_DEFINE_FLOAT(RC4_TRIM, 1500); PARAM_DEFINE_FLOAT(RC4_MAX, 2000); PARAM_DEFINE_FLOAT(RC4_REV, 1.0f); PARAM_DEFINE_FLOAT(RC4_DZ, 0.0f); -PARAM_DEFINE_FLOAT(RC4_EXP, 0.0f); +// PARAM_DEFINE_FLOAT(RC4_EXP, 0.0f); PARAM_DEFINE_FLOAT(RC5_MIN, 1000); PARAM_DEFINE_FLOAT(RC5_TRIM, 1500); PARAM_DEFINE_FLOAT(RC5_MAX, 2000); PARAM_DEFINE_FLOAT(RC5_REV, 1.0f); PARAM_DEFINE_FLOAT(RC5_DZ, 0.0f); -PARAM_DEFINE_FLOAT(RC5_EXP, 0.0f); +// PARAM_DEFINE_FLOAT(RC5_EXP, 0.0f); PARAM_DEFINE_FLOAT(RC6_MIN, 1000); PARAM_DEFINE_FLOAT(RC6_TRIM, 1500); PARAM_DEFINE_FLOAT(RC6_MAX, 2000); PARAM_DEFINE_FLOAT(RC6_REV, 1.0f); PARAM_DEFINE_FLOAT(RC6_DZ, 0.0f); -PARAM_DEFINE_FLOAT(RC6_EXP, 0.0f); +// PARAM_DEFINE_FLOAT(RC6_EXP, 0.0f); PARAM_DEFINE_FLOAT(RC7_MIN, 1000); PARAM_DEFINE_FLOAT(RC7_TRIM, 1500); PARAM_DEFINE_FLOAT(RC7_MAX, 2000); PARAM_DEFINE_FLOAT(RC7_REV, 1.0f); PARAM_DEFINE_FLOAT(RC7_DZ, 0.0f); -PARAM_DEFINE_FLOAT(RC7_EXP, 0.0f); +// PARAM_DEFINE_FLOAT(RC7_EXP, 0.0f); PARAM_DEFINE_FLOAT(RC8_MIN, 1000); PARAM_DEFINE_FLOAT(RC8_TRIM, 1500); PARAM_DEFINE_FLOAT(RC8_MAX, 2000); PARAM_DEFINE_FLOAT(RC8_REV, 1.0f); PARAM_DEFINE_FLOAT(RC8_DZ, 0.0f); -PARAM_DEFINE_FLOAT(RC8_EXP, 0.0f); +// PARAM_DEFINE_FLOAT(RC8_EXP, 0.0f); -PARAM_DEFINE_INT32(RC_TYPE, 1); // 1 = FUTABA +PARAM_DEFINE_FLOAT(RC9_MIN, 1000); +PARAM_DEFINE_FLOAT(RC9_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC9_MAX, 2000); +PARAM_DEFINE_FLOAT(RC9_REV, 1.0f); +PARAM_DEFINE_FLOAT(RC9_DZ, 0.0f); +// PARAM_DEFINE_FLOAT(RC9_EXP, 0.0f); -PARAM_DEFINE_INT32(RC_DEMIX, 0); /**< 0 = off, 1 = auto, 2 = delta */ +PARAM_DEFINE_FLOAT(RC10_MIN, 1000); +PARAM_DEFINE_FLOAT(RC10_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC10_MAX, 2000); +PARAM_DEFINE_FLOAT(RC10_REV, 1.0f); +PARAM_DEFINE_FLOAT(RC10_DZ, 0.0f); +// PARAM_DEFINE_FLOAT(RC10_EXP, 0.0f); + +PARAM_DEFINE_FLOAT(RC11_MIN, 1000); +PARAM_DEFINE_FLOAT(RC11_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC11_MAX, 2000); +PARAM_DEFINE_FLOAT(RC11_REV, 1.0f); +PARAM_DEFINE_FLOAT(RC11_DZ, 0.0f); +// PARAM_DEFINE_FLOAT(RC11_EXP, 0.0f); + +PARAM_DEFINE_FLOAT(RC12_MIN, 1000); +PARAM_DEFINE_FLOAT(RC12_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC12_MAX, 2000); +PARAM_DEFINE_FLOAT(RC12_REV, 1.0f); +PARAM_DEFINE_FLOAT(RC12_DZ, 0.0f); +// PARAM_DEFINE_FLOAT(RC12_EXP, 0.0f); + +PARAM_DEFINE_FLOAT(RC13_MIN, 1000); +PARAM_DEFINE_FLOAT(RC13_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC13_MAX, 2000); +PARAM_DEFINE_FLOAT(RC13_REV, 1.0f); +PARAM_DEFINE_FLOAT(RC13_DZ, 0.0f); +// PARAM_DEFINE_FLOAT(RC13_EXP, 0.0f); + +PARAM_DEFINE_FLOAT(RC14_MIN, 1000); +PARAM_DEFINE_FLOAT(RC14_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC14_MAX, 2000); +PARAM_DEFINE_FLOAT(RC14_REV, 1.0f); +PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f); +// PARAM_DEFINE_FLOAT(RC12_EXP, 0.0f); + +PARAM_DEFINE_INT32(RC_TYPE, 1); /** 1 = FUTABA, 2 = Spektrum, 3 = Graupner HoTT, 4 = Turnigy 9x */ /* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */ PARAM_DEFINE_FLOAT(BAT_V_SCALING, (3.3f * 52.0f / 5.0f / 4095.0f)); @@ -131,12 +171,23 @@ PARAM_DEFINE_INT32(RC_MAP_ROLL, 1); PARAM_DEFINE_INT32(RC_MAP_PITCH, 2); PARAM_DEFINE_INT32(RC_MAP_THROTTLE, 3); PARAM_DEFINE_INT32(RC_MAP_YAW, 4); -PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 5); -PARAM_DEFINE_INT32(RC_MAP_AUX1, 6); -PARAM_DEFINE_INT32(RC_MAP_AUX2, 7); -PARAM_DEFINE_INT32(RC_MAP_AUX3, 8); + +PARAM_DEFINE_INT32(RC_MAP_OVER_SW, 5); +PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 6); + +PARAM_DEFINE_INT32(RC_MAP_MAN_SW, 0); +PARAM_DEFINE_INT32(RC_MAP_SAS_SW, 0); +PARAM_DEFINE_INT32(RC_MAP_RTL_SW, 0); +PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0); + +PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0); + +PARAM_DEFINE_INT32(RC_MAP_AUX1, 0); /**< default function: camera yaw / azimuth */ +PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera pitch / tilt */ +PARAM_DEFINE_INT32(RC_MAP_AUX3, 0); /**< default function: camera trigger */ +PARAM_DEFINE_INT32(RC_MAP_AUX4, 0); /**< default function: camera roll */ +PARAM_DEFINE_INT32(RC_MAP_AUX5, 0); /**< default function: payload drop */ PARAM_DEFINE_FLOAT(RC_SCALE_ROLL, 0.4f); PARAM_DEFINE_FLOAT(RC_SCALE_PITCH, 0.4f); PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 1.0f); - diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index bcc383330c..10d25d347d 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -95,11 +95,7 @@ #define PPM_INPUT_TIMEOUT_INTERVAL 50000 /**< 50 ms timeout / 20 Hz */ -enum RC_DEMIX { - RC_DEMIX_NONE = 0, - RC_DEMIX_AUTO = 1, - RC_DEMIX_DELTA = 2 -}; +#define limit_minus_one_to_one(arg) (arg < -1.0f) ? -1.0f : ((arg > 1.0f) ? 1.0f : arg) /** * Sensor app start / stop handling function @@ -129,7 +125,7 @@ public: int start(); private: - static const unsigned _rc_max_chan_count = 8; /**< maximum number of r/c channels we handle */ + static const unsigned _rc_max_chan_count = RC_CHANNELS_MAX; /**< maximum number of r/c channels we handle */ #if CONFIG_HRT_PPM hrt_abstime _ppm_last_valid; /**< last time we got a valid ppm signal */ @@ -173,7 +169,7 @@ private: float max[_rc_max_chan_count]; float rev[_rc_max_chan_count]; float dz[_rc_max_chan_count]; - float ex[_rc_max_chan_count]; + // float ex[_rc_max_chan_count]; float scaling_factor[_rc_max_chan_count]; float gyro_offset[3]; @@ -184,21 +180,31 @@ private: int rc_type; - int rc_demix; /**< enabled de-mixing of RC mixers */ - int rc_map_roll; int rc_map_pitch; int rc_map_yaw; int rc_map_throttle; - int rc_map_mode_sw; + + int rc_map_manual_override_sw; + int rc_map_auto_mode_sw; + + int rc_map_manual_mode_sw; + int rc_map_sas_mode_sw; + int rc_map_rtl_sw; + int rc_map_offboard_ctrl_mode_sw; + + int rc_map_flaps; int rc_map_aux1; int rc_map_aux2; int rc_map_aux3; + int rc_map_aux4; + int rc_map_aux5; float rc_scale_roll; float rc_scale_pitch; float rc_scale_yaw; + float rc_scale_flaps; float battery_voltage_scaling; } _parameters; /**< local copies of interesting parameters */ @@ -209,7 +215,7 @@ private: param_t max[_rc_max_chan_count]; param_t rev[_rc_max_chan_count]; param_t dz[_rc_max_chan_count]; - param_t ex[_rc_max_chan_count]; + // param_t ex[_rc_max_chan_count]; param_t rc_type; param_t rc_demix; @@ -224,15 +230,27 @@ private: param_t rc_map_pitch; param_t rc_map_yaw; param_t rc_map_throttle; - param_t rc_map_mode_sw; + + param_t rc_map_manual_override_sw; + param_t rc_map_auto_mode_sw; + + param_t rc_map_manual_mode_sw; + param_t rc_map_sas_mode_sw; + param_t rc_map_rtl_sw; + param_t rc_map_offboard_ctrl_mode_sw; + + param_t rc_map_flaps; param_t rc_map_aux1; param_t rc_map_aux2; param_t rc_map_aux3; + param_t rc_map_aux4; + param_t rc_map_aux5; param_t rc_scale_roll; param_t rc_scale_pitch; param_t rc_scale_yaw; + param_t rc_scale_flaps; param_t battery_voltage_scaling; } _parameter_handles; /**< handles for interesting parameters */ @@ -395,27 +413,43 @@ Sensors::Sensors() : sprintf(nbuf, "RC%d_DZ", i + 1); _parameter_handles.dz[i] = param_find(nbuf); - /* channel exponential gain */ - sprintf(nbuf, "RC%d_EXP", i + 1); - _parameter_handles.ex[i] = param_find(nbuf); + // /* channel exponential gain */ + // sprintf(nbuf, "RC%d_EXP", i + 1); + // _parameter_handles.ex[i] = param_find(nbuf); } _parameter_handles.rc_type = param_find("RC_TYPE"); - _parameter_handles.rc_demix = param_find("RC_DEMIX"); + // _parameter_handles.rc_demix = param_find("RC_DEMIX"); + /* mandatory input switched, mapped to channels 1-4 per default */ _parameter_handles.rc_map_roll = param_find("RC_MAP_ROLL"); _parameter_handles.rc_map_pitch = param_find("RC_MAP_PITCH"); _parameter_handles.rc_map_yaw = param_find("RC_MAP_YAW"); _parameter_handles.rc_map_throttle = param_find("RC_MAP_THROTTLE"); - _parameter_handles.rc_map_mode_sw = param_find("RC_MAP_MODE_SW"); + + /* mandatory mode switches, mapped to channel 5 and 6 per default */ + _parameter_handles.rc_map_manual_override_sw = param_find("RC_MAP_OVER_SW"); + _parameter_handles.rc_map_auto_mode_sw = param_find("RC_MAP_MODE_SW"); + + _parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS"); + + /* optional mode switches, not mapped per default */ + _parameter_handles.rc_map_manual_mode_sw = param_find("RC_MAP_MAN_SW"); + _parameter_handles.rc_map_sas_mode_sw = param_find("RC_MAP_SAS_SW"); + _parameter_handles.rc_map_rtl_sw = param_find("RC_MAP_RTL_SW"); + _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW"); + _parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1"); _parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2"); _parameter_handles.rc_map_aux3 = param_find("RC_MAP_AUX3"); + _parameter_handles.rc_map_aux4 = param_find("RC_MAP_AUX4"); + _parameter_handles.rc_map_aux5 = param_find("RC_MAP_AUX5"); _parameter_handles.rc_scale_roll = param_find("RC_SCALE_ROLL"); _parameter_handles.rc_scale_pitch = param_find("RC_SCALE_PITCH"); _parameter_handles.rc_scale_yaw = param_find("RC_SCALE_YAW"); + _parameter_handles.rc_scale_flaps = param_find("RC_SCALE_FLAPS"); /* gyro offsets */ _parameter_handles.gyro_offset[0] = param_find("SENS_GYRO_XOFF"); @@ -472,10 +506,10 @@ Sensors::~Sensors() int Sensors::parameters_update() { - const unsigned int nchans = 8; + bool rc_valid = true; /* rc values */ - for (unsigned int i = 0; i < nchans; i++) { + for (unsigned int i = 0; i < RC_CHANNELS_MAX; i++) { if (param_get(_parameter_handles.min[i], &(_parameters.min[i])) != OK) { warnx("Failed getting min for chan %d", i); @@ -492,32 +526,33 @@ Sensors::parameters_update() if (param_get(_parameter_handles.dz[i], &(_parameters.dz[i])) != OK) { warnx("Failed getting dead zone for chan %d", i); } - if (param_get(_parameter_handles.ex[i], &(_parameters.ex[i])) != OK) { - warnx("Failed getting exponential gain for chan %d", i); - } + // if (param_get(_parameter_handles.ex[i], &(_parameters.ex[i])) != OK) { + // warnx("Failed getting exponential gain for chan %d", i); + // } _parameters.scaling_factor[i] = (1.0f / ((_parameters.max[i] - _parameters.min[i]) / 2.0f) * _parameters.rev[i]); /* handle blowup in the scaling factor calculation */ - if (isnan(_parameters.scaling_factor[i]) || isinf(_parameters.scaling_factor[i])) { + if (!isfinite(_parameters.scaling_factor[i]) || + _parameters.scaling_factor[i] * _parameters.rev[i] < 0.000001f || + _parameters.scaling_factor[i] * _parameters.rev[i] > 0.2f) { + + /* scaling factors do not make sense, lock them down */ _parameters.scaling_factor[i] = 0; + rc_valid = false; } - /* handle wrong values */ - // XXX TODO - } + /* handle wrong values */ + if (!rc_valid) + warnx("WARNING WARNING WARNING\n\nRC CALIBRATION NOT SANE!\n\n"); + /* remote control type */ if (param_get(_parameter_handles.rc_type, &(_parameters.rc_type)) != OK) { warnx("Failed getting remote control type"); } - /* de-mixing */ - if (param_get(_parameter_handles.rc_demix, &(_parameters.rc_demix)) != OK) { - warnx("Failed getting demix setting"); - } - /* channel mapping */ if (param_get(_parameter_handles.rc_map_roll, &(_parameters.rc_map_roll)) != OK) { warnx("Failed getting roll chan index"); @@ -531,9 +566,30 @@ Sensors::parameters_update() if (param_get(_parameter_handles.rc_map_throttle, &(_parameters.rc_map_throttle)) != OK) { warnx("Failed getting throttle chan index"); } - if (param_get(_parameter_handles.rc_map_mode_sw, &(_parameters.rc_map_mode_sw)) != OK) { - warnx("Failed getting mode sw chan index"); + if (param_get(_parameter_handles.rc_map_manual_override_sw, &(_parameters.rc_map_manual_override_sw)) != OK) { + warnx("Failed getting override sw chan index"); } + if (param_get(_parameter_handles.rc_map_auto_mode_sw, &(_parameters.rc_map_auto_mode_sw)) != OK) { + warnx("Failed getting auto mode sw chan index"); + } + + if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) { + warnx("Failed getting flaps chan index"); + } + + if (param_get(_parameter_handles.rc_map_manual_mode_sw, &(_parameters.rc_map_manual_mode_sw)) != OK) { + warnx("Failed getting manual mode sw chan index"); + } + if (param_get(_parameter_handles.rc_map_rtl_sw, &(_parameters.rc_map_rtl_sw)) != OK) { + warnx("Failed getting rtl sw chan index"); + } + if (param_get(_parameter_handles.rc_map_sas_mode_sw, &(_parameters.rc_map_sas_mode_sw)) != OK) { + warnx("Failed getting sas mode sw chan index"); + } + if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) { + warnx("Failed getting offboard control mode sw chan index"); + } + if (param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1)) != OK) { warnx("Failed getting mode aux 1 index"); } @@ -543,6 +599,12 @@ Sensors::parameters_update() if (param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3)) != OK) { warnx("Failed getting mode aux 3 index"); } + if (param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4)) != OK) { + warnx("Failed getting mode aux 4 index"); + } + if (param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5)) != OK) { + warnx("Failed getting mode aux 5 index"); + } if (param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll)) != OK) { warnx("Failed getting rc scaling for roll"); @@ -553,16 +615,31 @@ Sensors::parameters_update() if (param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw)) != OK) { warnx("Failed getting rc scaling for yaw"); } + if (param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps)) != OK) { + warnx("Failed getting rc scaling for flaps"); + } /* update RC function mappings */ _rc.function[THROTTLE] = _parameters.rc_map_throttle - 1; _rc.function[ROLL] = _parameters.rc_map_roll - 1; _rc.function[PITCH] = _parameters.rc_map_pitch - 1; _rc.function[YAW] = _parameters.rc_map_yaw - 1; - _rc.function[OVERRIDE] = _parameters.rc_map_mode_sw - 1; - _rc.function[FUNC_0] = _parameters.rc_map_aux1 - 1; - _rc.function[FUNC_1] = _parameters.rc_map_aux2 - 1; - _rc.function[FUNC_2] = _parameters.rc_map_aux3 - 1; + + _rc.function[OVERRIDE] = _parameters.rc_map_manual_override_sw - 1; + _rc.function[AUTO_MODE] = _parameters.rc_map_auto_mode_sw - 1; + + _rc.function[FLAPS] = _parameters.rc_map_flaps - 1; + + _rc.function[MANUAL_MODE] = _parameters.rc_map_manual_mode_sw - 1; + _rc.function[RTL] = _parameters.rc_map_rtl_sw - 1; + _rc.function[SAS_MODE] = _parameters.rc_map_sas_mode_sw - 1; + _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_ctrl_mode_sw - 1; + + _rc.function[AUX_1] = _parameters.rc_map_aux1 - 1; + _rc.function[AUX_2] = _parameters.rc_map_aux2 - 1; + _rc.function[AUX_3] = _parameters.rc_map_aux3 - 1; + _rc.function[AUX_4] = _parameters.rc_map_aux4 - 1; + _rc.function[AUX_5] = _parameters.rc_map_aux5 - 1; /* gyro offsets */ param_get(_parameter_handles.gyro_offset[0], &(_parameters.gyro_offset[0])); @@ -948,8 +1025,23 @@ Sensors::ppm_poll() struct manual_control_setpoint_s manual_control; - /* get a copy first, to prevent altering values */ - orb_copy(ORB_ID(manual_control_setpoint), _manual_control_sub, &manual_control); + /* initialize to default values */ + manual_control.roll = NAN; + manual_control.pitch = NAN; + manual_control.yaw = NAN; + manual_control.throttle = NAN; + + manual_control.manual_mode_switch = NAN; + manual_control.manual_sas_switch = NAN; + manual_control.return_to_launch_switch = NAN; + manual_control.auto_offboard_input_switch = NAN; + + manual_control.flaps = NAN; + manual_control.aux1 = NAN; + manual_control.aux2 = NAN; + manual_control.aux3 = NAN; + manual_control.aux4 = NAN; + manual_control.aux5 = NAN; /* require at least four channels to consider the signal valid */ if (rc_input.channel_count < 4) @@ -996,79 +1088,116 @@ Sensors::ppm_poll() manual_control.timestamp = rc_input.timestamp; - /* check if input needs to be de-mixed */ - if (_parameters.rc_demix == (int)RC_DEMIX_DELTA) { - // XXX hardcoded for testing purposes, replace with inverted delta mixer from ROMFS + // /* check if input needs to be de-mixed */ + // if (_parameters.rc_demix == (int)RC_DEMIX_DELTA) { + // // XXX hardcoded for testing purposes, replace with inverted delta mixer from ROMFS - /* roll input - mixed roll and pitch channels */ - manual_control.roll = 0.5f * (_rc.chan[_rc.function[ROLL]].scaled - _rc.chan[_rc.function[PITCH]].scaled); - /* pitch input - mixed roll and pitch channels */ - manual_control.pitch = 0.5f * (_rc.chan[_rc.function[ROLL]].scaled + _rc.chan[_rc.function[PITCH]].scaled); - /* yaw input - stick right is positive and positive rotation */ - manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled; - /* throttle input */ - manual_control.throttle = _rc.chan[_rc.function[THROTTLE]].scaled; + // /* roll input - mixed roll and pitch channels */ + // manual_control.roll = 0.5f * (_rc.chan[_rc.function[ROLL]].scaled - _rc.chan[_rc.function[PITCH]].scaled); + // pitch input - mixed roll and pitch channels + // manual_control.pitch = 0.5f * (_rc.chan[_rc.function[ROLL]].scaled + _rc.chan[_rc.function[PITCH]].scaled); + // /* yaw input - stick right is positive and positive rotation */ + // manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled; + // /* throttle input */ + // manual_control.throttle = _rc.chan[_rc.function[THROTTLE]].scaled; - /* direct pass-through of manual input */ - } else { - /* roll input - rolling right is stick-wise and rotation-wise positive */ - manual_control.roll = _rc.chan[_rc.function[ROLL]].scaled; - /* - * pitch input - stick down is negative, but stick down is pitching up (pos) in NED, - * so reverse sign. - */ - manual_control.pitch = -1.0f * _rc.chan[_rc.function[PITCH]].scaled; - /* yaw input - stick right is positive and positive rotation */ - manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled; - /* throttle input */ - manual_control.throttle = _rc.chan[_rc.function[THROTTLE]].scaled; - } + // /* direct pass-through of manual input */ + // } else { - /* limit outputs */ - if (manual_control.roll < -1.0f) manual_control.roll = -1.0f; - if (manual_control.roll > 1.0f) manual_control.roll = 1.0f; + /* roll input - rolling right is stick-wise and rotation-wise positive */ + manual_control.roll = _rc.chan[_rc.function[ROLL]].scaled; + /* + * pitch input - stick down is negative, but stick down is pitching up (pos) in NED, + * so reverse sign. + */ + manual_control.pitch = limit_minus_one_to_one(-1.0f * _rc.chan[_rc.function[PITCH]].scaled); + /* yaw input - stick right is positive and positive rotation */ + manual_control.yaw = limit_minus_one_to_one(_rc.chan[_rc.function[YAW]].scaled); + /* throttle input */ + manual_control.throttle = _rc.chan[_rc.function[THROTTLE]].scaled; + if (manual_control.throttle < 0.0f) manual_control.throttle = 0.0f; + if (manual_control.throttle > 1.0f) manual_control.throttle = 1.0f; + + /* scale output */ if (isfinite(_parameters.rc_scale_roll) && _parameters.rc_scale_roll > 0.0f) { manual_control.roll *= _parameters.rc_scale_roll; } - - if (manual_control.pitch < -1.0f) manual_control.pitch = -1.0f; - if (manual_control.pitch > 1.0f) manual_control.pitch = 1.0f; if (isfinite(_parameters.rc_scale_pitch) && _parameters.rc_scale_pitch > 0.0f) { manual_control.pitch *= _parameters.rc_scale_pitch; } - if (manual_control.yaw < -1.0f) manual_control.yaw = -1.0f; - if (manual_control.yaw > 1.0f) manual_control.yaw = 1.0f; if (isfinite(_parameters.rc_scale_yaw) && _parameters.rc_scale_yaw > 0.0f) { manual_control.yaw *= _parameters.rc_scale_yaw; } - - if (manual_control.throttle < 0.0f) manual_control.throttle = 0.0f; - if (manual_control.throttle > 1.0f) manual_control.throttle = 1.0f; + + /* override switch input */ + manual_control.manual_override_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OVERRIDE]].scaled); /* mode switch input */ - manual_control.override_mode_switch = _rc.chan[_rc.function[OVERRIDE]].scaled; - if (manual_control.override_mode_switch < -1.0f) manual_control.override_mode_switch = -1.0f; - if (manual_control.override_mode_switch > 1.0f) manual_control.override_mode_switch = 1.0f; + manual_control.auto_mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[AUTO_MODE]].scaled); - /* aux functions */ - manual_control.aux1_cam_pan_flaps = _rc.chan[_rc.function[FUNC_0]].scaled; - if (manual_control.aux1_cam_pan_flaps < -1.0f) manual_control.aux1_cam_pan_flaps = -1.0f; - if (manual_control.aux1_cam_pan_flaps > 1.0f) manual_control.aux1_cam_pan_flaps = 1.0f; + /* flaps */ + if (_rc.function[FLAPS] >= 0) { - /* aux inputs */ - manual_control.aux2_cam_tilt = _rc.chan[_rc.function[FUNC_1]].scaled; - if (manual_control.aux2_cam_tilt < -1.0f) manual_control.aux2_cam_tilt = -1.0f; - if (manual_control.aux2_cam_tilt > 1.0f) manual_control.aux2_cam_tilt = 1.0f; + manual_control.flaps = limit_minus_one_to_one(_rc.chan[_rc.function[FLAPS]].scaled); - /* aux inputs */ - manual_control.aux3_cam_zoom = _rc.chan[_rc.function[FUNC_2]].scaled; - if (manual_control.aux3_cam_zoom < -1.0f) manual_control.aux3_cam_zoom = -1.0f; - if (manual_control.aux3_cam_zoom > 1.0f) manual_control.aux3_cam_zoom = 1.0f; + if (isfinite(_parameters.rc_scale_flaps) && _parameters.rc_scale_flaps > 0.0f) { + manual_control.flaps *= _parameters.rc_scale_flaps; + } + } - orb_publish(ORB_ID(rc_channels), _rc_pub, &_rc); - orb_publish(ORB_ID(manual_control_setpoint), _manual_control_pub, &manual_control); + if (_rc.function[MANUAL_MODE] >= 0) { + manual_control.manual_mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MANUAL_MODE]].scaled); + } + + if (_rc.function[SAS_MODE] >= 0) { + manual_control.manual_sas_switch = limit_minus_one_to_one(_rc.chan[_rc.function[SAS_MODE]].scaled); + } + + if (_rc.function[RTL] >= 0) { + manual_control.return_to_launch_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RTL]].scaled); + } + + if (_rc.function[OFFBOARD_MODE] >= 0) { + manual_control.auto_offboard_input_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled); + } + + /* aux functions, only assign if valid mapping is present */ + if (_rc.function[AUX_1] >= 0) { + manual_control.aux1 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_1]].scaled); + } + + if (_rc.function[AUX_2] >= 0) { + manual_control.aux2 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_2]].scaled); + } + + if (_rc.function[AUX_3] >= 0) { + manual_control.aux3 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_3]].scaled); + } + + if (_rc.function[AUX_4] >= 0) { + manual_control.aux4 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_4]].scaled); + } + + if (_rc.function[AUX_5] >= 0) { + manual_control.aux5 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_5]].scaled); + } + + /* check if ready for publishing */ + if (_rc_pub > 0) { + orb_publish(ORB_ID(rc_channels), _rc_pub, &_rc); + } else { + /* advertise the rc topic */ + _rc_pub = orb_advertise(ORB_ID(rc_channels), &_rc); + } + + /* check if ready for publishing */ + if (_manual_control_pub > 0) { + orb_publish(ORB_ID(manual_control_setpoint), _manual_control_pub, &manual_control); + } else { + _manual_control_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual_control); + } } } @@ -1117,7 +1246,7 @@ Sensors::task_main() memset(&raw, 0, sizeof(raw)); raw.timestamp = hrt_absolute_time(); raw.battery_voltage_v = BAT_VOL_INITIAL; - raw.adc_voltage_v[0] = 0.9f; + raw.adc_voltage_v[0] = 0.0f; raw.adc_voltage_v[1] = 0.0f; raw.adc_voltage_v[2] = 0.0f; raw.battery_voltage_counter = 0; @@ -1134,27 +1263,6 @@ Sensors::task_main() /* advertise the sensor_combined topic and make the initial publication */ _sensor_pub = orb_advertise(ORB_ID(sensor_combined), &raw); - /* advertise the manual_control topic */ - struct manual_control_setpoint_s manual_control; - manual_control.mode = MANUAL_CONTROL_MODE_ATT_YAW_POS; - manual_control.roll = 0.0f; - manual_control.pitch = 0.0f; - manual_control.yaw = 0.0f; - manual_control.throttle = 0.0f; - manual_control.aux1_cam_pan_flaps = 0.0f; - manual_control.aux2_cam_tilt = 0.0f; - manual_control.aux3_cam_zoom = 0.0f; - manual_control.aux4_cam_roll = 0.0f; - - _manual_control_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual_control); - - /* advertise the rc topic */ - { - struct rc_channels_s rc; - memset(&rc, 0, sizeof(rc)); - _rc_pub = orb_advertise(ORB_ID(rc_channels), &rc); - } - /* wakeup source(s) */ struct pollfd fds[1]; diff --git a/apps/uORB/topics/manual_control_setpoint.h b/apps/uORB/topics/manual_control_setpoint.h index 1368cb716f..261a8a4ad3 100644 --- a/apps/uORB/topics/manual_control_setpoint.h +++ b/apps/uORB/topics/manual_control_setpoint.h @@ -48,29 +48,33 @@ * @{ */ -enum MANUAL_CONTROL_MODE -{ - MANUAL_CONTROL_MODE_DIRECT = 0, - MANUAL_CONTROL_MODE_ATT_YAW_RATE = 1, - MANUAL_CONTROL_MODE_ATT_YAW_POS = 2, - MANUAL_CONTROL_MODE_MULTIROTOR_SIMPLE = 3 /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */ -}; - struct manual_control_setpoint_s { uint64_t timestamp; - enum MANUAL_CONTROL_MODE mode; /**< The current control inputs mode */ - float roll; /**< ailerons roll / roll rate input */ - float pitch; /**< elevator / pitch / pitch rate */ - float yaw; /**< rudder / yaw rate / yaw */ - float throttle; /**< throttle / collective thrust / altitude */ + float roll; /**< ailerons roll / roll rate input */ + float pitch; /**< elevator / pitch / pitch rate */ + float yaw; /**< rudder / yaw rate / yaw */ + float throttle; /**< throttle / collective thrust / altitude */ - float override_mode_switch; + float manual_override_switch; /**< manual override mode (mandatory) */ + float auto_mode_switch; /**< auto mode switch (mandatory) */ - float aux1_cam_pan_flaps; - float aux2_cam_tilt; - float aux3_cam_zoom; - float aux4_cam_roll; + /** + * Any of the channels below may not be available and be set to NaN + * to indicate that it does not contain valid data. + */ + float manual_mode_switch; /**< manual mode (man, sas, alt) switch (optional) */ + float manual_sas_switch; /**< sas mode (rates / attitude) switch (optional) */ + float return_to_launch_switch; /**< return to launch switch (0 = disabled, 1 = enabled) */ + float auto_offboard_input_switch; /**< controller setpoint source (0 = onboard, 1 = offboard) */ + + float flaps; /**< flap position */ + + float aux1; /**< default function: camera yaw / azimuth */ + float aux2; /**< default function: camera pitch / tilt */ + float aux3; /**< default function: camera trigger */ + float aux4; /**< default function: camera roll */ + float aux5; /**< default function: payload drop */ }; /**< manual control inputs */ diff --git a/apps/uORB/topics/rc_channels.h b/apps/uORB/topics/rc_channels.h index fef6ef2b33..9dd54df915 100644 --- a/apps/uORB/topics/rc_channels.h +++ b/apps/uORB/topics/rc_channels.h @@ -50,6 +50,13 @@ * @{ */ +/** + * The number of RC channel inputs supported. + * Current (Q1/2013) radios support up to 18 channels, + * leaving at a sane value of 14. + */ +#define RC_CHANNELS_MAX 14 + /** * This defines the mapping of the RC functions. * The value assigned to the specific function corresponds to the entry of @@ -62,14 +69,18 @@ enum RC_CHANNELS_FUNCTION PITCH = 2, YAW = 3, OVERRIDE = 4, - FUNC_0 = 5, - FUNC_1 = 6, - FUNC_2 = 7, - FUNC_3 = 8, - FUNC_4 = 9, - FUNC_5 = 10, - FUNC_6 = 11, - RC_CHANNELS_FUNCTION_MAX = 12 + AUTO_MODE = 5, + MANUAL_MODE = 6, + SAS_MODE = 7, + RTL = 8, + OFFBOARD_MODE = 9, + FLAPS = 10, + AUX_1 = 11, + AUX_2 = 12, + AUX_3 = 13, + AUX_4 = 14, + AUX_5 = 15, + RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */ }; struct rc_channels_s { @@ -78,14 +89,13 @@ struct rc_channels_s { uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */ struct { float scaled; /**< Scaled to -1..1 (throttle: 0..1) */ - } chan[RC_CHANNELS_FUNCTION_MAX]; - uint8_t chan_count; /**< maximum number of valid channels */ + } chan[RC_CHANNELS_MAX]; + uint8_t chan_count; /**< number of valid channels */ /*String array to store the names of the functions*/ char function_name[RC_CHANNELS_FUNCTION_MAX][20]; - uint8_t function[RC_CHANNELS_FUNCTION_MAX]; + int8_t function[RC_CHANNELS_FUNCTION_MAX]; uint8_t rssi; /**< Overall receive signal strength */ - bool is_valid; /**< Inputs are valid, no timeout */ }; /**< radio control channels. */ /** diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h index 738ca644fb..ed3fed1abe 100644 --- a/apps/uORB/topics/vehicle_status.h +++ b/apps/uORB/topics/vehicle_status.h @@ -87,16 +87,23 @@ enum VEHICLE_MODE_FLAG { }; /**< Same as MAV_MODE_FLAG of MAVLink 1.0 protocol */ enum VEHICLE_FLIGHT_MODE { - VEHICLE_FLIGHT_MODE_MANUAL = 0, /**< direct manual control, same as VEHICLE_FLIGHT_MODE_ATTITUDE for multirotors */ - VEHICLE_FLIGHT_MODE_ATTITUDE, /**< attitude or rate stabilization, as defined by VEHICLE_ATTITUDE_MODE */ - VEHICLE_FLIGHT_MODE_STABILIZED, /**< attitude or rate stabilization plus velocity or position stabilization */ - VEHICLE_FLIGHT_MODE_AUTO /**< attitude or rate stabilization plus absolute position control and waypoints */ + VEHICLE_FLIGHT_MODE_MANUAL = 0, /**< direct manual control, exact mode determined by VEHICLE_MANUAL_CONTROL_MODE */ + VEHICLE_FLIGHT_MODE_STAB, /**< attitude or rate stabilization plus velocity or position stabilization */ + VEHICLE_FLIGHT_MODE_HOLD, /**< hold current position (hover or loiter around position when switched) */ + VEHICLE_FLIGHT_MODE_AUTO /**< attitude or rate stabilization plus absolute position control and waypoints */ }; -enum VEHICLE_ATTITUDE_MODE { - VEHICLE_ATTITUDE_MODE_DIRECT, /**< no attitude control, direct stick input mixing (only fixed wing) */ - VEHICLE_ATTITUDE_MODE_RATES, /**< body rates control mode */ - VEHICLE_ATTITUDE_MODE_ATTITUDE /**< tait-bryan attitude control mode */ +enum VEHICLE_MANUAL_CONTROL_MODE { + VEHICLE_MANUAL_CONTROL_MODE_DIRECT = 0, /**< no attitude control, direct stick input mixing (only fixed wing) */ + VEHICLE_MANUAL_CONTROL_MODE_RATES, /**< body rates control mode */ + VEHICLE_MANUAL_CONTROL_MODE_SAS /**< stability augmented system (SAS) mode */ +}; + +enum VEHICLE_MANUAL_SAS_MODE { + VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS = 0, /**< roll, pitch and yaw absolute */ + VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE, /**< roll and pitch absolute, yaw rate */ + VEHICLE_MANUAL_SAS_MODE_SIMPLE, /**< simple mode (includes altitude hold) */ + VEHICLE_MANUAL_SAS_MODE_ALTITUDE /**< altitude hold */ }; /** @@ -115,12 +122,10 @@ struct vehicle_status_s commander_state_machine_t state_machine; /**< current flight state, main state machine */ enum VEHICLE_FLIGHT_MODE flight_mode; /**< current flight mode, as defined by mode switch */ - enum VEHICLE_ATTITUDE_MODE attitute_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */ + enum VEHICLE_MANUAL_CONTROL_MODE manual_control_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */ + enum VEHICLE_MANUAL_SAS_MODE manual_sas_mode; /**< current stabilization mode */ int32_t system_type; /**< system type, inspired by MAVLinks MAV_TYPE enum */ - // uint8_t mode; - - /* system flags - these represent the state predicates */ bool flag_system_armed; /**< true is motors / actuators are armed */ @@ -165,11 +170,11 @@ struct vehicle_status_s uint16_t errors_count3; uint16_t errors_count4; -// bool remote_manual; /**< set to true by the commander when the manual-switch on the remote is set to manual */ bool flag_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */ bool flag_local_position_valid; bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */ - bool flag_external_manual_override_ok; + bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */ + bool flag_valid_launch_position; /**< indicates a valid launch position */ }; /** From e2196bca4f574c783f2b1883e7a9cec20e8283e1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 27 Dec 2012 18:36:37 +0100 Subject: [PATCH 192/206] Added position lock check --- apps/commander/commander.c | 20 ++++++++++++++++++++ apps/uORB/topics/vehicle_status.h | 5 +++-- 2 files changed, 23 insertions(+), 2 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index b5df8a8b34..e0ee500dc2 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -1589,6 +1589,26 @@ int commander_thread_main(int argc, char *argv[]) state_changed = true; } + /* + * Mark the position of the first position lock as return to launch (RTL) + * position. The MAV will return here on command or emergency. + * + * Conditions: + * + * 1) The system aquired position lock just now + * 2) The system has not aquired position lock before + * 3) The system is not armed (on the ground) + */ + if (!current_status.flag_valid_launch_position && + !vector_flight_mode_ok && current_status.flag_vector_flight_mode_ok && + !current_status.flag_system_armed) { + /* first time a valid position, store it and emit it */ + + // XXX implement storage and publication of RTL position + current_status.flag_valid_launch_position = true; + current_status.flag_auto_flight_mode_ok = true; + state_changed = true; + } /* Check if last transition deserved an audio event */ diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h index ed3fed1abe..230521f536 100644 --- a/apps/uORB/topics/vehicle_status.h +++ b/apps/uORB/topics/vehicle_status.h @@ -170,9 +170,10 @@ struct vehicle_status_s uint16_t errors_count3; uint16_t errors_count4; - bool flag_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */ + bool flag_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */ bool flag_local_position_valid; - bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */ + bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */ + bool flag_auto_flight_mode_ok; /**< conditions of vector flight mode apply plus a valid takeoff position lock has been aquired */ bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */ bool flag_valid_launch_position; /**< indicates a valid launch position */ }; From 7526dd46a2ace594cbbb2c6ad9e9fa53c67c5ca8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 27 Dec 2012 19:01:00 +0100 Subject: [PATCH 193/206] Added header for common priority bands --- apps/drivers/px4io/px4io.cpp | 3 +- apps/systemlib/scheduling_priorities.h | 48 ++++++++++++++++++++++++++ 2 files changed, 50 insertions(+), 1 deletion(-) create mode 100644 apps/systemlib/scheduling_priorities.h diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index 701955298f..0ea1218e35 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -70,6 +70,7 @@ #include #include #include +#include #include #include @@ -255,7 +256,7 @@ PX4IO::init() } /* start the IO interface task */ - _task = task_create("px4io", SCHED_PRIORITY_DEFAULT, 4096, (main_t)&PX4IO::task_main_trampoline, nullptr); + _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 4096, (main_t)&PX4IO::task_main_trampoline, nullptr); if (_task < 0) { debug("task start failed: %d", errno); return -errno; diff --git a/apps/systemlib/scheduling_priorities.h b/apps/systemlib/scheduling_priorities.h new file mode 100644 index 0000000000..be1dbfcd88 --- /dev/null +++ b/apps/systemlib/scheduling_priorities.h @@ -0,0 +1,48 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * 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 PX4 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. + * + ****************************************************************************/ + +#pragma once + +#include + +/* SCHED_PRIORITY_MAX */ +#define SCHED_PRIORITY_FAST_DRIVER SCHED_PRIORITY_MAX +#define SCHED_PRIORITY_WATCHDOG (SCHED_PRIORITY_MAX - 5) +#define SCHED_PRIORITY_ACTUATOR_OUTPUTS (SCHED_PRIORITY_MAX - 15) +#define SCHED_PRIORITY_ATTITUDE_CONTROL (SCHED_PRIORITY_MAX - 25) +#define SCHED_PRIORITY_SLOW_DRIVER (SCHED_PRIORITY_MAX - 35) +#define SCHED_PRIORITY_POSITION_CONTROL (SCHED_PRIORITY_MAX - 40) +/* SCHED_PRIORITY_DEFAULT */ +#define SCHED_PRIORITY_LOGGING (SCHED_PRIORITY_DEFAULT - 10) +#define SCHED_PRIORITY_PARAMS (SCHED_PRIORITY_DEFAULT - 15) +/* SCHED_PRIORITY_IDLE */ From 8b8330a015b6c11f8f627c3659d63c6d85133e44 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 28 Dec 2012 13:10:06 +0100 Subject: [PATCH 194/206] Reverted nuttx merge, back to master --- apps/Makefile | 72 +- nuttx/COPYING | 51 - nuttx/ChangeLog | 198 +- nuttx/Kconfig | 112 +- nuttx/Makefile | 626 ++++++- nuttx/README.txt | 162 +- nuttx/ReleaseNotes | 78 - nuttx/TODO | 55 +- nuttx/arch/arm/Kconfig | 17 - nuttx/arch/arm/include/stm32/chip.h | 202 +- .../arch/arm/include/stm32/stm32f10xxx_irq.h | 58 +- nuttx/arch/arm/src/Makefile | 162 +- .../arm/src/armv7-m/up_fullcontextrestore.S | 0 nuttx/arch/arm/src/armv7-m/up_hardfault.c | 4 +- .../arch/arm/src/armv7-m/up_saveusercontext.S | 0 nuttx/arch/arm/src/armv7-m/up_switchcontext.S | 0 nuttx/arch/arm/src/stm32/Kconfig | 622 ++----- nuttx/arch/arm/src/stm32/Make.defs | 28 +- nuttx/arch/arm/src/stm32/chip/stm32_eth.h | 8 + .../arm/src/stm32/chip/stm32f100_pinmap.h | 190 +- .../arm/src/stm32/chip/stm32f103vc_pinmap.h | 2 +- .../arm/src/stm32/chip/stm32f103ze_pinmap.h | 94 +- .../arm/src/stm32/chip/stm32f105vb_pinmap.h | 2 +- .../arm/src/stm32/chip/stm32f107vc_pinmap.h | 2 +- .../arm/src/stm32/chip/stm32f10xxx_gpio.h | 23 - .../src/stm32/chip/stm32f10xxx_memorymap.h | 61 +- .../arch/arm/src/stm32/chip/stm32f10xxx_rcc.h | 78 +- .../arm/src/stm32/chip/stm32f10xxx_vectors.h | 72 +- .../arm/src/stm32/chip/stm32f20xxx_pinmap.h | 2 +- .../arm/src/stm32/chip/stm32f40xxx_pinmap.h | 2 +- nuttx/arch/arm/src/stm32/stm32_adc.c | 10 +- nuttx/arch/arm/src/stm32/stm32_adc.h | 2 +- nuttx/arch/arm/src/stm32/stm32_eth.c | 11 - nuttx/arch/arm/src/stm32/stm32_eth.h | 35 +- nuttx/arch/arm/src/stm32/stm32_lowputc.c | 75 +- nuttx/arch/arm/src/stm32/stm32_otgfsdev.c | 26 +- nuttx/arch/arm/src/stm32/stm32_qencoder.c | 1 - nuttx/arch/arm/src/stm32/stm32_serial.c | 132 +- nuttx/arch/arm/src/stm32/stm32_uart.h | 14 - nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c | 56 +- nuttx/binfmt/Kconfig | 42 - nuttx/binfmt/Makefile | 73 +- nuttx/binfmt/binfmt_dumpmodule.c | 12 +- nuttx/binfmt/binfmt_exec.c | 2 +- nuttx/binfmt/binfmt_execmodule.c | 62 +- nuttx/binfmt/binfmt_globals.c | 2 +- nuttx/binfmt/binfmt_internal.h | 2 +- nuttx/binfmt/binfmt_loadmodule.c | 2 +- nuttx/binfmt/binfmt_register.c | 2 +- nuttx/binfmt/binfmt_unloadmodule.c | 78 +- nuttx/binfmt/binfmt_unregister.c | 2 +- nuttx/binfmt/libnxflat/Kconfig | 5 - nuttx/binfmt/libnxflat/Make.defs | 25 +- nuttx/binfmt/libnxflat/libnxflat_bind.c | 50 +- nuttx/binfmt/libnxflat/libnxflat_init.c | 7 +- nuttx/binfmt/libnxflat/libnxflat_load.c | 20 +- nuttx/binfmt/libnxflat/libnxflat_read.c | 14 +- nuttx/binfmt/libnxflat/libnxflat_uninit.c | 7 +- nuttx/binfmt/libnxflat/libnxflat_unload.c | 2 +- nuttx/binfmt/libnxflat/libnxflat_verify.c | 9 +- nuttx/binfmt/nxflat.c | 20 +- nuttx/binfmt/symtab_findbyname.c | 2 +- nuttx/binfmt/symtab_findbyvalue.c | 2 +- nuttx/binfmt/symtab_findorderedbyname.c | 2 +- nuttx/binfmt/symtab_findorderedbyvalue.c | 2 +- nuttx/configs/README.txt | 179 +- nuttx/configs/px4fmu/common/Make.defs | 8 +- nuttx/configs/px4fmu/nsh/appconfig | 1 + nuttx/configs/px4fmu/nsh/defconfig | 5 - nuttx/configs/px4io/common/Make.defs | 8 +- nuttx/configs/px4io/io/defconfig | 3 - nuttx/configs/px4io/nsh/Make.defs | 3 + nuttx/configs/px4io/nsh/appconfig | 43 + nuttx/configs/px4io/nsh/defconfig | 565 ++++++ nuttx/configs/px4io/nsh/setenv.sh | 47 + nuttx/drivers/Kconfig | 76 +- nuttx/drivers/Makefile | 27 +- nuttx/drivers/analog/Make.defs | 6 +- nuttx/drivers/analog/adc.c | 15 +- nuttx/drivers/bch/Make.defs | 4 +- nuttx/drivers/input/Make.defs | 8 +- nuttx/drivers/lcd/Kconfig | 81 +- nuttx/drivers/lcd/Make.defs | 6 +- nuttx/drivers/lcd/ug-9664hswag01.c | 15 +- nuttx/drivers/mmcsd/Make.defs | 16 +- nuttx/drivers/mmcsd/mmcsd_sdio.c | 5 - nuttx/drivers/mmcsd/mmcsd_spi.c | 11 +- nuttx/drivers/net/e1000.c | 297 +-- nuttx/drivers/net/e1000.h | 4 +- nuttx/drivers/net/vnet.c | 327 ++-- nuttx/drivers/power/Make.defs | 4 +- nuttx/drivers/sensors/Make.defs | 4 +- nuttx/drivers/usbdev/Make.defs | 2 +- nuttx/drivers/usbdev/pl2303.c | 2 +- nuttx/drivers/usbdev/usbmsc.h | 2 +- nuttx/drivers/usbhost/Make.defs | 4 +- nuttx/drivers/wireless/Make.defs | 4 +- nuttx/fs/Makefile | 18 +- nuttx/fs/fs_stat.c | 7 +- nuttx/graphics/Makefile | 98 +- nuttx/graphics/nxfonts/Makefile.sources | 14 +- nuttx/graphics/nxglib/Makefile.sources | 52 +- nuttx/graphics/nxmu/nx_bitmap.c | 29 +- nuttx/graphics/nxmu/nx_block.c | 2 +- nuttx/graphics/nxmu/nx_getrectangle.c | 30 +- nuttx/graphics/nxmu/nxfe.h | 21 - nuttx/graphics/nxmu/nxmu_kbdin.c | 2 +- nuttx/graphics/nxmu/nxmu_mouse.c | 46 +- nuttx/graphics/nxmu/nxmu_redrawreq.c | 2 +- nuttx/graphics/nxmu/nxmu_reportposition.c | 2 +- nuttx/graphics/nxmu/nxmu_sendwindow.c | 44 - nuttx/graphics/nxmu/nxmu_server.c | 10 - nuttx/graphics/nxsu/nx_mousein.c | 30 +- nuttx/graphics/nxtk/nxtk_events.c | 39 +- nuttx/graphics/nxtk/nxtk_internal.h | 5 - nuttx/include/cxx/cmath | 59 - nuttx/include/cxx/cstdbool | 9 - nuttx/include/cxx/cstdio | 12 +- nuttx/include/net/if.h | 9 - nuttx/include/nuttx/arch.h | 22 - nuttx/include/nuttx/binfmt.h | 209 +++ nuttx/include/nuttx/compiler.h | 23 +- nuttx/include/nuttx/fs/fs.h | 15 +- nuttx/include/nuttx/lcd/ug-9664hswag01.h | 15 +- nuttx/include/nuttx/math.h | 262 +-- nuttx/include/nuttx/net/ioctl.h | 6 - nuttx/include/nuttx/net/uip/uip-arch.h | 4 - nuttx/include/nuttx/nxflat.h | 264 +++ nuttx/include/nuttx/power/pm.h | 6 +- nuttx/include/nuttx/sched.h | 6 +- nuttx/include/nuttx/symtab.h | 163 ++ nuttx/include/nuttx/usb/cdcacm.h | 2 +- nuttx/include/nuttx/usb/usbdev_trace.h | 4 + nuttx/include/nuttx/wqueue.h | 24 +- nuttx/include/stdio.h | 7 +- nuttx/include/termios.h | 2 +- nuttx/include/unistd.h | 1 - nuttx/lib/Kconfig | 194 ++ nuttx/lib/Makefile | 98 +- nuttx/lib/README.txt | 82 +- nuttx/lib/dirent/Make.defs | 48 + nuttx/lib/dirent/lib_readdirr.c | 122 ++ nuttx/lib/dirent/lib_telldir.c | 91 + nuttx/lib/lib.csv | 171 ++ nuttx/lib/lib_internal.h | 199 ++ nuttx/lib/libgen/Make.defs | 43 + nuttx/lib/libgen/lib_basename.c | 131 ++ nuttx/lib/libgen/lib_dirname.c | 144 ++ nuttx/lib/math/Make.defs | 43 + nuttx/lib/math/lib_b16atan2.c | 108 ++ nuttx/lib/math/lib_b16cos.c | 64 + nuttx/lib/math/lib_b16sin.c | 110 ++ nuttx/lib/math/lib_fixedmath.c | 272 +++ nuttx/lib/math/lib_rint.c | 135 ++ nuttx/lib/misc/Make.defs | 69 + nuttx/lib/misc/lib_crc32.c | 123 ++ nuttx/lib/misc/lib_dbg.c | 165 ++ nuttx/lib/misc/lib_dumpbuffer.c | 129 ++ nuttx/lib/misc/lib_filesem.c | 145 ++ nuttx/lib/misc/lib_init.c | 207 +++ nuttx/lib/misc/lib_match.c | 148 ++ nuttx/lib/misc/lib_sendfile.c | 297 +++ nuttx/lib/misc/lib_streamsem.c | 90 + nuttx/lib/mqueue/Make.defs | 48 + nuttx/lib/mqueue/mq_getattr.c | 104 ++ nuttx/lib/mqueue/mq_setattr.c | 118 ++ nuttx/lib/net/Make.defs | 44 + nuttx/lib/net/lib_etherntoa.c | 69 + nuttx/lib/net/lib_htonl.c | 68 + nuttx/lib/net/lib_htons.c | 65 + nuttx/lib/net/lib_inetaddr.c | 74 + nuttx/lib/net/lib_inetntoa.c | 79 + nuttx/lib/net/lib_inetntop.c | 202 ++ nuttx/lib/net/lib_inetpton.c | 338 ++++ nuttx/lib/pthread/Make.defs | 56 + nuttx/lib/pthread/pthread_attrdestroy.c | 108 ++ .../lib/pthread/pthread_attrgetinheritsched.c | 111 ++ nuttx/lib/pthread/pthread_attrgetschedparam.c | 110 ++ .../lib/pthread/pthread_attrgetschedpolicy.c | 105 ++ nuttx/lib/pthread/pthread_attrgetstacksize.c | 106 ++ nuttx/lib/pthread/pthread_attrinit.c | 123 ++ .../lib/pthread/pthread_attrsetinheritsched.c | 113 ++ nuttx/lib/pthread/pthread_attrsetschedparam.c | 108 ++ .../lib/pthread/pthread_attrsetschedpolicy.c | 111 ++ nuttx/lib/pthread/pthread_attrsetstacksize.c | 106 ++ .../lib/pthread/pthread_barrierattrdestroy.c | 102 + .../pthread/pthread_barrierattrgetpshared.c | 101 + nuttx/lib/pthread/pthread_barrierattrinit.c | 101 + .../pthread/pthread_barrierattrsetpshared.c | 111 ++ nuttx/lib/pthread/pthread_condattrdestroy.c | 82 + nuttx/lib/pthread/pthread_condattrinit.c | 85 + nuttx/lib/pthread/pthread_mutexattrdestroy.c | 104 ++ .../lib/pthread/pthread_mutexattrgetpshared.c | 104 ++ nuttx/lib/pthread/pthread_mutexattrgettype.c | 98 + nuttx/lib/pthread/pthread_mutexattrinit.c | 106 ++ .../lib/pthread/pthread_mutexattrsetpshared.c | 104 ++ nuttx/lib/pthread/pthread_mutexattrsettype.c | 98 + nuttx/lib/queue/Make.defs | 47 + nuttx/lib/queue/dq_addafter.c | 74 + nuttx/lib/queue/dq_addbefore.c | 69 + nuttx/lib/queue/dq_addfirst.c | 74 + nuttx/lib/queue/dq_addlast.c | 74 + nuttx/lib/queue/dq_rem.c | 84 + nuttx/lib/queue/dq_remfirst.c | 82 + nuttx/lib/queue/dq_remlast.c | 78 + nuttx/lib/queue/sq_addafter.c | 71 + nuttx/lib/queue/sq_addfirst.c | 67 + nuttx/lib/queue/sq_addlast.c | 72 + nuttx/lib/queue/sq_rem.c | 83 + nuttx/lib/queue/sq_remafter.c | 79 + nuttx/lib/queue/sq_remfirst.c | 76 + nuttx/lib/queue/sq_remlast.c | 87 + nuttx/lib/sched/Make.defs | 43 + nuttx/lib/sched/sched_getprioritymax.c | 100 + nuttx/lib/sched/sched_getprioritymin.c | 100 + nuttx/lib/semaphore/Make.defs | 43 + nuttx/lib/semaphore/sem_getvalue.c | 108 ++ nuttx/lib/semaphore/sem_init.c | 125 ++ nuttx/lib/signal/Make.defs | 47 + nuttx/lib/signal/sig_addset.c | 100 + nuttx/lib/signal/sig_delset.c | 100 + nuttx/lib/signal/sig_emptyset.c | 88 + nuttx/lib/signal/sig_fillset.c | 88 + nuttx/lib/signal/sig_ismember.c | 101 + nuttx/lib/stdio/Make.defs | 73 + nuttx/lib/stdio/lib_asprintf.c | 105 ++ nuttx/lib/stdio/lib_avsprintf.c | 146 ++ nuttx/lib/stdio/lib_dtoa.c | 1641 +++++++++++++++++ nuttx/lib/stdio/lib_fclose.c | 154 ++ nuttx/lib/stdio/lib_fflush.c | 132 ++ nuttx/lib/stdio/lib_fgetc.c | 101 + nuttx/lib/stdio/lib_fgetpos.c | 123 ++ nuttx/lib/stdio/lib_fgets.c | 207 +++ nuttx/lib/stdio/lib_fileno.c | 70 + nuttx/lib/stdio/lib_fopen.c | 299 +++ nuttx/lib/stdio/lib_fprintf.c | 93 + nuttx/lib/stdio/lib_fputc.c | 113 ++ nuttx/lib/stdio/lib_fputs.c | 220 +++ nuttx/lib/stdio/lib_fread.c | 101 + nuttx/lib/stdio/lib_fseek.c | 138 ++ nuttx/lib/stdio/lib_fsetpos.c | 116 ++ nuttx/lib/stdio/lib_ftell.c | 129 ++ nuttx/lib/stdio/lib_fwrite.c | 99 + nuttx/lib/stdio/lib_gets.c | 120 ++ nuttx/lib/stdio/lib_libdtoa.c | 304 +++ nuttx/lib/stdio/lib_libfflush.c | 202 ++ nuttx/lib/stdio/lib_libflushall.c | 137 ++ nuttx/lib/stdio/lib_libfread.c | 290 +++ nuttx/lib/stdio/lib_libfwrite.c | 179 ++ nuttx/lib/stdio/lib_libnoflush.c | 103 ++ nuttx/lib/stdio/lib_libsprintf.c | 90 + nuttx/lib/stdio/lib_libvsprintf.c | 1620 ++++++++++++++++ nuttx/lib/stdio/lib_lowinstream.c | 102 + nuttx/lib/stdio/lib_lowoutstream.c | 97 + nuttx/lib/stdio/lib_lowprintf.c | 128 ++ nuttx/lib/stdio/lib_meminstream.c | 104 ++ nuttx/lib/stdio/lib_memoutstream.c | 105 ++ nuttx/lib/stdio/lib_nullinstream.c | 79 + nuttx/lib/stdio/lib_nulloutstream.c | 84 + nuttx/lib/stdio/lib_perror.c | 99 + nuttx/lib/stdio/lib_printf.c | 109 ++ nuttx/lib/stdio/lib_puts.c | 130 ++ nuttx/lib/stdio/lib_rawinstream.c | 107 ++ nuttx/lib/stdio/lib_rawoutstream.c | 115 ++ nuttx/lib/stdio/lib_rawprintf.c | 151 ++ nuttx/lib/stdio/lib_rdflush.c | 144 ++ nuttx/lib/stdio/lib_snprintf.c | 99 + nuttx/lib/stdio/lib_sprintf.c | 95 + nuttx/lib/stdio/lib_sscanf.c | 507 +++++ nuttx/lib/stdio/lib_stdinstream.c | 99 + nuttx/lib/stdio/lib_stdoutstream.c | 147 ++ nuttx/lib/stdio/lib_syslogstream.c | 122 ++ nuttx/lib/stdio/lib_ungetc.c | 121 ++ nuttx/lib/stdio/lib_vfprintf.c | 102 + nuttx/lib/stdio/lib_vprintf.c | 92 + nuttx/lib/stdio/lib_vsnprintf.c | 96 + nuttx/lib/stdio/lib_vsprintf.c | 92 + nuttx/lib/stdio/lib_wrflush.c | 134 ++ nuttx/lib/stdio/lib_zeroinstream.c | 79 + nuttx/lib/stdlib/Make.defs | 44 + nuttx/lib/stdlib/lib_abort.c | 121 ++ nuttx/lib/stdlib/lib_abs.c | 54 + nuttx/lib/stdlib/lib_imaxabs.c | 54 + nuttx/lib/stdlib/lib_labs.c | 54 + nuttx/lib/stdlib/lib_llabs.c | 57 + nuttx/lib/stdlib/lib_qsort.c | 238 +++ nuttx/lib/stdlib/lib_rand.c | 220 +++ nuttx/lib/string/Make.defs | 50 + nuttx/lib/string/lib_checkbase.c | 115 ++ nuttx/lib/string/lib_isbasedigit.c | 105 ++ nuttx/lib/string/lib_memccpy.c | 99 + nuttx/lib/string/lib_memchr.c | 80 + nuttx/lib/string/lib_memcmp.c | 74 + nuttx/lib/string/lib_memcpy.c | 64 + nuttx/lib/string/lib_memmove.c | 72 + nuttx/lib/string/lib_memset.c | 59 + nuttx/lib/string/lib_skipspace.c | 69 + nuttx/lib/string/lib_strcasecmp.c | 65 + nuttx/lib/string/lib_strcasestr.c | 134 ++ nuttx/lib/string/lib_strcat.c | 62 + nuttx/lib/string/lib_strchr.c | 76 + nuttx/lib/string/lib_strcmp.c | 59 + nuttx/lib/string/lib_strcpy.c | 55 + nuttx/lib/string/lib_strcspn.c | 67 + nuttx/lib/string/lib_strdup.c | 62 + nuttx/lib/string/lib_strerror.c | 375 ++++ nuttx/lib/string/lib_strlen.c | 55 + nuttx/lib/string/lib_strncasecmp.c | 70 + nuttx/lib/string/lib_strncat.c | 62 + nuttx/lib/string/lib_strncmp.c | 65 + nuttx/lib/string/lib_strncpy.c | 57 + nuttx/lib/string/lib_strndup.c | 93 + nuttx/lib/string/lib_strnlen.c | 62 + nuttx/lib/string/lib_strpbrk.c | 85 + nuttx/lib/string/lib_strrchr.c | 68 + nuttx/lib/string/lib_strspn.c | 66 + nuttx/lib/string/lib_strstr.c | 104 ++ nuttx/lib/string/lib_strtod.c | 241 +++ nuttx/lib/string/lib_strtok.c | 87 + nuttx/lib/string/lib_strtokr.c | 157 ++ nuttx/lib/string/lib_strtol.c | 103 ++ nuttx/lib/string/lib_strtoll.c | 107 ++ nuttx/lib/string/lib_strtoul.c | 98 + nuttx/lib/string/lib_strtoull.c | 100 + nuttx/lib/termios/Make.defs | 54 + nuttx/lib/termios/lib_cfgetspeed.c | 93 + nuttx/lib/termios/lib_cfsetspeed.c | 121 ++ nuttx/lib/termios/lib_tcflush.c | 88 + nuttx/lib/termios/lib_tcgetattr.c | 93 + nuttx/lib/termios/lib_tcsetattr.c | 122 ++ nuttx/lib/time/Make.defs | 44 + nuttx/lib/time/lib_calendar2utc.c | 209 +++ nuttx/lib/time/lib_daysbeforemonth.c | 102 + nuttx/lib/time/lib_gmtime.c | 93 + nuttx/lib/time/lib_gmtimer.c | 355 ++++ nuttx/lib/time/lib_isleapyear.c | 88 + nuttx/lib/time/lib_mktime.c | 141 ++ nuttx/lib/time/lib_strftime.c | 398 ++++ nuttx/lib/time/lib_time.c | 110 ++ nuttx/lib/unistd/Make.defs | 49 + nuttx/lib/unistd/lib_chdir.c | 179 ++ nuttx/lib/unistd/lib_getcwd.c | 132 ++ nuttx/lib/unistd/lib_getopt.c | 269 +++ nuttx/lib/unistd/lib_getoptargp.c | 73 + nuttx/lib/unistd/lib_getoptindp.c | 73 + nuttx/lib/unistd/lib_getoptoptp.c | 73 + nuttx/libxx/Kconfig | 34 - nuttx/libxx/Makefile | 73 +- nuttx/libxx/README.txt | 5 - nuttx/libxx/libxx_eabi_atexit.cxx | 23 +- nuttx/mm/Makefile | 17 +- nuttx/mm/Makefile.test | 18 +- nuttx/mm/mm_initialize.c | 6 +- nuttx/net/Makefile | 14 +- nuttx/net/netdev_ioctl.c | 151 +- nuttx/net/uip/uip_icmpping.c | 2 - nuttx/sched/Kconfig | 11 +- nuttx/sched/Makefile | 16 +- nuttx/sched/atexit.c | 16 +- nuttx/sched/mq_open.c | 3 +- nuttx/sched/on_exit.c | 5 +- nuttx/sched/sched_getscheduler.c | 1 - nuttx/sched/sem_open.c | 3 +- nuttx/sched/sleep.c | 2 +- nuttx/sched/task_exithook.c | 4 +- nuttx/sched/usleep.c | 2 +- nuttx/syscall/Makefile | 45 +- nuttx/tools/Config.mk | 152 +- nuttx/tools/Makefile.export | 4 +- nuttx/tools/Makefile.host | 98 +- nuttx/tools/README.txt | 83 +- nuttx/tools/configure.sh | 92 +- nuttx/tools/define.sh | 8 +- nuttx/tools/incdir.sh | 3 - nuttx/tools/mkconfig.c | 2 +- nuttx/tools/mkdeps.sh | 2 +- nuttx/tools/mkromfsimg.sh | 2 +- nuttx/tools/mksymtab.c | 2 +- 378 files changed, 30204 insertions(+), 4660 deletions(-) mode change 100644 => 100755 nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S mode change 100644 => 100755 nuttx/arch/arm/src/armv7-m/up_saveusercontext.S mode change 100644 => 100755 nuttx/arch/arm/src/armv7-m/up_switchcontext.S create mode 100644 nuttx/configs/px4io/nsh/Make.defs create mode 100644 nuttx/configs/px4io/nsh/appconfig create mode 100755 nuttx/configs/px4io/nsh/defconfig create mode 100755 nuttx/configs/px4io/nsh/setenv.sh create mode 100644 nuttx/include/nuttx/binfmt.h create mode 100644 nuttx/include/nuttx/nxflat.h create mode 100644 nuttx/include/nuttx/symtab.h create mode 100644 nuttx/lib/Kconfig create mode 100644 nuttx/lib/dirent/Make.defs create mode 100644 nuttx/lib/dirent/lib_readdirr.c create mode 100644 nuttx/lib/dirent/lib_telldir.c create mode 100644 nuttx/lib/lib.csv create mode 100644 nuttx/lib/lib_internal.h create mode 100644 nuttx/lib/libgen/Make.defs create mode 100644 nuttx/lib/libgen/lib_basename.c create mode 100644 nuttx/lib/libgen/lib_dirname.c create mode 100644 nuttx/lib/math/Make.defs create mode 100644 nuttx/lib/math/lib_b16atan2.c create mode 100644 nuttx/lib/math/lib_b16cos.c create mode 100644 nuttx/lib/math/lib_b16sin.c create mode 100644 nuttx/lib/math/lib_fixedmath.c create mode 100644 nuttx/lib/math/lib_rint.c create mode 100644 nuttx/lib/misc/Make.defs create mode 100644 nuttx/lib/misc/lib_crc32.c create mode 100644 nuttx/lib/misc/lib_dbg.c create mode 100644 nuttx/lib/misc/lib_dumpbuffer.c create mode 100644 nuttx/lib/misc/lib_filesem.c create mode 100644 nuttx/lib/misc/lib_init.c create mode 100644 nuttx/lib/misc/lib_match.c create mode 100644 nuttx/lib/misc/lib_sendfile.c create mode 100644 nuttx/lib/misc/lib_streamsem.c create mode 100644 nuttx/lib/mqueue/Make.defs create mode 100644 nuttx/lib/mqueue/mq_getattr.c create mode 100644 nuttx/lib/mqueue/mq_setattr.c create mode 100644 nuttx/lib/net/Make.defs create mode 100644 nuttx/lib/net/lib_etherntoa.c create mode 100644 nuttx/lib/net/lib_htonl.c create mode 100644 nuttx/lib/net/lib_htons.c create mode 100644 nuttx/lib/net/lib_inetaddr.c create mode 100644 nuttx/lib/net/lib_inetntoa.c create mode 100644 nuttx/lib/net/lib_inetntop.c create mode 100644 nuttx/lib/net/lib_inetpton.c create mode 100644 nuttx/lib/pthread/Make.defs create mode 100644 nuttx/lib/pthread/pthread_attrdestroy.c create mode 100644 nuttx/lib/pthread/pthread_attrgetinheritsched.c create mode 100644 nuttx/lib/pthread/pthread_attrgetschedparam.c create mode 100644 nuttx/lib/pthread/pthread_attrgetschedpolicy.c create mode 100644 nuttx/lib/pthread/pthread_attrgetstacksize.c create mode 100644 nuttx/lib/pthread/pthread_attrinit.c create mode 100644 nuttx/lib/pthread/pthread_attrsetinheritsched.c create mode 100644 nuttx/lib/pthread/pthread_attrsetschedparam.c create mode 100644 nuttx/lib/pthread/pthread_attrsetschedpolicy.c create mode 100644 nuttx/lib/pthread/pthread_attrsetstacksize.c create mode 100644 nuttx/lib/pthread/pthread_barrierattrdestroy.c create mode 100644 nuttx/lib/pthread/pthread_barrierattrgetpshared.c create mode 100644 nuttx/lib/pthread/pthread_barrierattrinit.c create mode 100644 nuttx/lib/pthread/pthread_barrierattrsetpshared.c create mode 100644 nuttx/lib/pthread/pthread_condattrdestroy.c create mode 100644 nuttx/lib/pthread/pthread_condattrinit.c create mode 100644 nuttx/lib/pthread/pthread_mutexattrdestroy.c create mode 100644 nuttx/lib/pthread/pthread_mutexattrgetpshared.c create mode 100644 nuttx/lib/pthread/pthread_mutexattrgettype.c create mode 100644 nuttx/lib/pthread/pthread_mutexattrinit.c create mode 100644 nuttx/lib/pthread/pthread_mutexattrsetpshared.c create mode 100644 nuttx/lib/pthread/pthread_mutexattrsettype.c create mode 100644 nuttx/lib/queue/Make.defs create mode 100644 nuttx/lib/queue/dq_addafter.c create mode 100644 nuttx/lib/queue/dq_addbefore.c create mode 100644 nuttx/lib/queue/dq_addfirst.c create mode 100644 nuttx/lib/queue/dq_addlast.c create mode 100644 nuttx/lib/queue/dq_rem.c create mode 100644 nuttx/lib/queue/dq_remfirst.c create mode 100644 nuttx/lib/queue/dq_remlast.c create mode 100644 nuttx/lib/queue/sq_addafter.c create mode 100644 nuttx/lib/queue/sq_addfirst.c create mode 100644 nuttx/lib/queue/sq_addlast.c create mode 100644 nuttx/lib/queue/sq_rem.c create mode 100644 nuttx/lib/queue/sq_remafter.c create mode 100644 nuttx/lib/queue/sq_remfirst.c create mode 100644 nuttx/lib/queue/sq_remlast.c create mode 100644 nuttx/lib/sched/Make.defs create mode 100644 nuttx/lib/sched/sched_getprioritymax.c create mode 100644 nuttx/lib/sched/sched_getprioritymin.c create mode 100644 nuttx/lib/semaphore/Make.defs create mode 100644 nuttx/lib/semaphore/sem_getvalue.c create mode 100644 nuttx/lib/semaphore/sem_init.c create mode 100644 nuttx/lib/signal/Make.defs create mode 100644 nuttx/lib/signal/sig_addset.c create mode 100644 nuttx/lib/signal/sig_delset.c create mode 100644 nuttx/lib/signal/sig_emptyset.c create mode 100644 nuttx/lib/signal/sig_fillset.c create mode 100644 nuttx/lib/signal/sig_ismember.c create mode 100644 nuttx/lib/stdio/Make.defs create mode 100644 nuttx/lib/stdio/lib_asprintf.c create mode 100644 nuttx/lib/stdio/lib_avsprintf.c create mode 100644 nuttx/lib/stdio/lib_dtoa.c create mode 100644 nuttx/lib/stdio/lib_fclose.c create mode 100644 nuttx/lib/stdio/lib_fflush.c create mode 100644 nuttx/lib/stdio/lib_fgetc.c create mode 100644 nuttx/lib/stdio/lib_fgetpos.c create mode 100644 nuttx/lib/stdio/lib_fgets.c create mode 100644 nuttx/lib/stdio/lib_fileno.c create mode 100644 nuttx/lib/stdio/lib_fopen.c create mode 100644 nuttx/lib/stdio/lib_fprintf.c create mode 100644 nuttx/lib/stdio/lib_fputc.c create mode 100644 nuttx/lib/stdio/lib_fputs.c create mode 100644 nuttx/lib/stdio/lib_fread.c create mode 100644 nuttx/lib/stdio/lib_fseek.c create mode 100644 nuttx/lib/stdio/lib_fsetpos.c create mode 100644 nuttx/lib/stdio/lib_ftell.c create mode 100644 nuttx/lib/stdio/lib_fwrite.c create mode 100644 nuttx/lib/stdio/lib_gets.c create mode 100644 nuttx/lib/stdio/lib_libdtoa.c create mode 100644 nuttx/lib/stdio/lib_libfflush.c create mode 100644 nuttx/lib/stdio/lib_libflushall.c create mode 100644 nuttx/lib/stdio/lib_libfread.c create mode 100644 nuttx/lib/stdio/lib_libfwrite.c create mode 100644 nuttx/lib/stdio/lib_libnoflush.c create mode 100644 nuttx/lib/stdio/lib_libsprintf.c create mode 100644 nuttx/lib/stdio/lib_libvsprintf.c create mode 100644 nuttx/lib/stdio/lib_lowinstream.c create mode 100644 nuttx/lib/stdio/lib_lowoutstream.c create mode 100644 nuttx/lib/stdio/lib_lowprintf.c create mode 100644 nuttx/lib/stdio/lib_meminstream.c create mode 100644 nuttx/lib/stdio/lib_memoutstream.c create mode 100644 nuttx/lib/stdio/lib_nullinstream.c create mode 100644 nuttx/lib/stdio/lib_nulloutstream.c create mode 100644 nuttx/lib/stdio/lib_perror.c create mode 100644 nuttx/lib/stdio/lib_printf.c create mode 100644 nuttx/lib/stdio/lib_puts.c create mode 100644 nuttx/lib/stdio/lib_rawinstream.c create mode 100644 nuttx/lib/stdio/lib_rawoutstream.c create mode 100644 nuttx/lib/stdio/lib_rawprintf.c create mode 100644 nuttx/lib/stdio/lib_rdflush.c create mode 100644 nuttx/lib/stdio/lib_snprintf.c create mode 100644 nuttx/lib/stdio/lib_sprintf.c create mode 100644 nuttx/lib/stdio/lib_sscanf.c create mode 100644 nuttx/lib/stdio/lib_stdinstream.c create mode 100644 nuttx/lib/stdio/lib_stdoutstream.c create mode 100644 nuttx/lib/stdio/lib_syslogstream.c create mode 100644 nuttx/lib/stdio/lib_ungetc.c create mode 100644 nuttx/lib/stdio/lib_vfprintf.c create mode 100644 nuttx/lib/stdio/lib_vprintf.c create mode 100644 nuttx/lib/stdio/lib_vsnprintf.c create mode 100644 nuttx/lib/stdio/lib_vsprintf.c create mode 100644 nuttx/lib/stdio/lib_wrflush.c create mode 100644 nuttx/lib/stdio/lib_zeroinstream.c create mode 100644 nuttx/lib/stdlib/Make.defs create mode 100644 nuttx/lib/stdlib/lib_abort.c create mode 100644 nuttx/lib/stdlib/lib_abs.c create mode 100644 nuttx/lib/stdlib/lib_imaxabs.c create mode 100644 nuttx/lib/stdlib/lib_labs.c create mode 100644 nuttx/lib/stdlib/lib_llabs.c create mode 100644 nuttx/lib/stdlib/lib_qsort.c create mode 100644 nuttx/lib/stdlib/lib_rand.c create mode 100644 nuttx/lib/string/Make.defs create mode 100644 nuttx/lib/string/lib_checkbase.c create mode 100644 nuttx/lib/string/lib_isbasedigit.c create mode 100644 nuttx/lib/string/lib_memccpy.c create mode 100644 nuttx/lib/string/lib_memchr.c create mode 100644 nuttx/lib/string/lib_memcmp.c create mode 100644 nuttx/lib/string/lib_memcpy.c create mode 100644 nuttx/lib/string/lib_memmove.c create mode 100644 nuttx/lib/string/lib_memset.c create mode 100644 nuttx/lib/string/lib_skipspace.c create mode 100644 nuttx/lib/string/lib_strcasecmp.c create mode 100644 nuttx/lib/string/lib_strcasestr.c create mode 100644 nuttx/lib/string/lib_strcat.c create mode 100644 nuttx/lib/string/lib_strchr.c create mode 100644 nuttx/lib/string/lib_strcmp.c create mode 100644 nuttx/lib/string/lib_strcpy.c create mode 100644 nuttx/lib/string/lib_strcspn.c create mode 100644 nuttx/lib/string/lib_strdup.c create mode 100644 nuttx/lib/string/lib_strerror.c create mode 100644 nuttx/lib/string/lib_strlen.c create mode 100644 nuttx/lib/string/lib_strncasecmp.c create mode 100644 nuttx/lib/string/lib_strncat.c create mode 100644 nuttx/lib/string/lib_strncmp.c create mode 100644 nuttx/lib/string/lib_strncpy.c create mode 100644 nuttx/lib/string/lib_strndup.c create mode 100644 nuttx/lib/string/lib_strnlen.c create mode 100644 nuttx/lib/string/lib_strpbrk.c create mode 100644 nuttx/lib/string/lib_strrchr.c create mode 100644 nuttx/lib/string/lib_strspn.c create mode 100644 nuttx/lib/string/lib_strstr.c create mode 100644 nuttx/lib/string/lib_strtod.c create mode 100644 nuttx/lib/string/lib_strtok.c create mode 100644 nuttx/lib/string/lib_strtokr.c create mode 100644 nuttx/lib/string/lib_strtol.c create mode 100644 nuttx/lib/string/lib_strtoll.c create mode 100644 nuttx/lib/string/lib_strtoul.c create mode 100644 nuttx/lib/string/lib_strtoull.c create mode 100644 nuttx/lib/termios/Make.defs create mode 100644 nuttx/lib/termios/lib_cfgetspeed.c create mode 100644 nuttx/lib/termios/lib_cfsetspeed.c create mode 100644 nuttx/lib/termios/lib_tcflush.c create mode 100644 nuttx/lib/termios/lib_tcgetattr.c create mode 100644 nuttx/lib/termios/lib_tcsetattr.c create mode 100644 nuttx/lib/time/Make.defs create mode 100644 nuttx/lib/time/lib_calendar2utc.c create mode 100644 nuttx/lib/time/lib_daysbeforemonth.c create mode 100644 nuttx/lib/time/lib_gmtime.c create mode 100644 nuttx/lib/time/lib_gmtimer.c create mode 100644 nuttx/lib/time/lib_isleapyear.c create mode 100644 nuttx/lib/time/lib_mktime.c create mode 100644 nuttx/lib/time/lib_strftime.c create mode 100644 nuttx/lib/time/lib_time.c create mode 100644 nuttx/lib/unistd/Make.defs create mode 100644 nuttx/lib/unistd/lib_chdir.c create mode 100644 nuttx/lib/unistd/lib_getcwd.c create mode 100644 nuttx/lib/unistd/lib_getopt.c create mode 100644 nuttx/lib/unistd/lib_getoptargp.c create mode 100644 nuttx/lib/unistd/lib_getoptindp.c create mode 100644 nuttx/lib/unistd/lib_getoptoptp.c diff --git a/apps/Makefile b/apps/Makefile index 0a0a319547..19ad1c18bc 100644 --- a/apps/Makefile +++ b/apps/Makefile @@ -35,6 +35,7 @@ ############################################################################ -include $(TOPDIR)/Make.defs +-include $(TOPDIR)/.config APPDIR = ${shell pwd} @@ -106,7 +107,7 @@ endif # Create the list of available applications (INSTALLED_APPS) define ADD_BUILTIN - INSTALLED_APPS += $(if $(wildcard $1$(DELIM)Makefile),$1,) +INSTALLED_APPS += ${shell if [ -r $1/Makefile ]; then echo "$1"; fi} endef $(foreach BUILTIN, $(CONFIGURED_APPS), $(eval $(call ADD_BUILTIN,$(BUILTIN)))) @@ -116,10 +117,8 @@ $(foreach BUILTIN, $(CONFIGURED_APPS), $(eval $(call ADD_BUILTIN,$(BUILTIN)))) # provided by the user (possibly as a symbolic link) to add libraries and # applications to the standard build from the repository. -EXTERNAL_DIR := $(dir $(wildcard external$(DELIM)Makefile)) - -INSTALLED_APPS += $(EXTERNAL_DIR) -SUBDIRS += $(EXTERNAL_DIR) +INSTALLED_APPS += ${shell if [ -r external/Makefile ]; then echo "external"; fi} +SUBDIRS += ${shell if [ -r external/Makefile ]; then echo "external"; fi} # The final build target @@ -131,81 +130,48 @@ all: $(BIN) .PHONY: $(INSTALLED_APPS) context depend clean distclean $(INSTALLED_APPS): - $(Q) $(MAKE) -C $@ TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" + @$(MAKE) -C $@ TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; $(BIN): $(INSTALLED_APPS) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) .context: -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - $(Q) for %%G in ($(INSTALLED_APPS)) do ( \ - if exist %%G\.context del /f /q %%G\.context \ - $(MAKE) -C %%G TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" context \ - ) -else - $(Q) for dir in $(INSTALLED_APPS) ; do \ + @for dir in $(INSTALLED_APPS) ; do \ rm -f $$dir/.context ; \ - $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" context ; \ + $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" context ; \ done -endif - $(Q) touch $@ + @touch $@ context: .context .depend: context Makefile $(SRCS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - $(Q) for %%G in ($(INSTALLED_APPS)) do ( \ - if exist %%G\.depend del /f /q %%G\.depend \ - $(MAKE) -C %%G TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" depend \ - ) -else - $(Q) for dir in $(INSTALLED_APPS) ; do \ + @for dir in $(INSTALLED_APPS) ; do \ rm -f $$dir/.depend ; \ - $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" depend ; \ + $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" depend ; \ done -endif - $(Q) touch $@ + @touch $@ depend: .depend clean: -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - $(Q) for %%G in ($(SUBDIRS)) do ( \ - $(MAKE) -C %%G clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" \ - ) -else - $(Q) for dir in $(SUBDIRS) ; do \ + @for dir in $(SUBDIRS) ; do \ $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ done -endif - $(call DELFILE, $(BIN)) + @rm -f $(BIN) *~ .*.swp *.o $(call CLEAN) distclean: # clean -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - $(Q) for %%G in ($(SUBDIRS)) do ( \ - $(MAKE) -C %%G distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" \ - ) - $(call DELFILE, .config) - $(call DELFILE, .context) - $(call DELFILE, .depend) - $(Q) ( if exist external ( \ - echo ********************************************************" \ - echo * The external directory/link must be removed manually *" \ - echo ********************************************************" \ - ) -else - $(Q) for dir in $(SUBDIRS) ; do \ + @for dir in $(SUBDIRS) ; do \ $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ done - $(call DELFILE, .config) - $(call DELFILE, .context) - $(call DELFILE, .depend) - $(Q) ( if [ -e external ]; then \ + @rm -f .config .context .depend + @( if [ -e external ]; then \ echo "********************************************************"; \ echo "* The external directory/link must be removed manually *"; \ echo "********************************************************"; \ fi; \ ) -endif diff --git a/nuttx/COPYING b/nuttx/COPYING index b3655265d6..863b81a2fc 100644 --- a/nuttx/COPYING +++ b/nuttx/COPYING @@ -163,57 +163,6 @@ dtoa(): "This product includes software developed by the University of California, Berkeley and its contributors." -libc/string/lib_vikmemcpy.c -^^^^^^^^^^^^^^^^^^^^^^^^^^^ - - If you enable CONFIG_MEMCPY_VIK, then you will build with the optimized - version of memcpy from Daniel Vik. Licensing information for that version - of memcpy() follows: - - Copyright (C) 1999-2010 Daniel Vik - - This software is provided 'as-is', without any express or implied - warranty. In no event will the authors be held liable for any - damages arising from the use of this software. - Permission is granted to anyone to use this software for any - purpose, including commercial applications, and to alter it and - redistribute it freely, subject to the following restrictions: - - 1. The origin of this software must not be misrepresented; you - must not claim that you wrote the original software. If you - use this software in a product, an acknowledgment in the - use this software in a product, an acknowledgment in the - product documentation would be appreciated but is not - required. - - 2. Altered source versions must be plainly marked as such, and - must not be misrepresented as being the original software. - - 3. This notice may not be removed or altered from any source - distribution. - -libc/math -^^^^^^^^^ - - If you enable CONFIG_LIB, you will build the math library at libc/math. - This library was taken from the math library developed for the Rhombus - OS by Nick Johnson (https://github.com/nickbjohnson4224/rhombus). This - port was contributed by Darcy Gong. The Rhombus math library has this - compatible MIT license: - - Copyright (C) 2009-2011 Nick Johnson - - Permission to use, copy, modify, and distribute this software for any - purpose with or without fee is hereby granted, provided that the above - copyright notice and this permission notice appear in all copies. - - THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - Documents/rss.gif ^^^^^^^^^^^^^^^^^ diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 103c03de3e..a8e045616e 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3453,7 +3453,7 @@ * net/uip/uip_icmpping.c: Fix problem that prevented ping from going outside of local network. Submitted by Darcy Gong -6.23 2012-11-05 Gregory Nutt +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 @@ -3470,200 +3470,4 @@ * 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. - * configs/shenzhou/src/up_adc.c: Add ADC support for the Shenzhou - board (Darcy Gong). - * configs/shenzhou/thttpd: Add a THTTPD configuration for the - Shenzhou board (Darcy Gong). - * include/termios.h and lib/termios/libcf*speed.c: The non-standard, - "hidden" c_speed cannot be type const or else static instantiations - of termios will be required to initialize it (Mike Smith). - * drivers/input/max11802.c/h, and include/nuttx/input max11802.h: Adds - support for the Maxim MAX11802 touchscreen controller (contributed by - Petteri Aimonen). - * graphics/nxtk/nxtk_events.c: Missing implementation of the blocked - method. This is a critical bugfix for graphics support (contributed - by Petteri Aimonen). - * drivers/usbdev/pl2303.c, drivers/usbdev/usbmsc.h, and - include/nuttx/usb/cdcacm.h: USB_CONFIG_ATTR_SELFPOWER vs. - USB_CONFIG_ATT_SELFPOWER (contributed by Petteri Aimonen). - * arch/arm/src/armv7-m/up_memcpy.S: An optimized memcpy() function for - the ARMv7-M family contributed by Mike Smith. - * lib/strings/lib_vikmemcpy.c: As an option, the larger but faster - implemementation of memcpy from Daniel Vik is now available (this is - from http://www.danielvik.com/2010/02/fast-memcpy-in-c.html). - * lib/strings/lib_memset.c: CONFIG_MEMSET_OPTSPEED will select a - version of memset() optimized for speed. By default, memset() is - optimized for size. - * lib/strings/lib_memset.c: CONFIG_MEMSET_64BIT will perform 64-bit - aligned memset() operations. - * arch/arm/src/stm32/stm32_adc.c: Need to put the ADC back into the - initial reset in the open/setup logic. Opening the ADC driver works - the first time, but not the second because the device is left in a - powered down state on the last close. - * configs/olimex-lpc1766stck/scripts: Replace all of the identical - ld.script files with the common one in this directory. - * configs/stm3220g-eval/scripts: Replace all of the identical - ld.script files with the common one in this directory. - * configs/hymini-stm32v/scripts: Replace all of the identical - ld.script files with the common one in this directory. - * configs/lpcxpresso-lpc1768/scripts: Replace all of the identical - ld.script files with the common one in this directory. - * binfmt/elf.c, binfmt/libelf, include/elf.h, include/nuttx/elf.h: Add - basic framework for loadable ELF module support. The initial check- - in is non-functional and is simply the framework for ELF support. - * include/nuttx/binfmt.h, nxflat.h, elf.h, and symtab.h: Moved to - include/nuttx/binfmt/. - * arch/sim/src/up_elf.c and arch/x86/src/common/up_elf.c: Add - for ELF modules. - * arch/arm/include/elf.h: Added ARM ELF header file. - * include/elf32.h: Renamed elf.h to elf32.h. - * configs/stm32f4discovery/ostest: Converted to use the new - Kconfig-based configuration system. - * configs/stm32f4discovery/elf and configs/stm32f4discovery/scripts/gnu-elf.ld - Add a configuration for testing the ARM ELF loader. - * binfmt/libelf: Can't use fstat(). NuttX does not yet support it. Damn! - * binfmt/libelf: The basic ELF module execution appears fully functional. - * configs/shenzhou/src/up_relays.c: Add support for relays from the - Shenzhou board. Contributed by Darcy Gong. - * lib/fixedmath: Moved the old lib/math to lib/fixedmath to make room for - the math library from the Rhombus OS - * lib/math: Now contains the math library from the Rhombus OS by Nick Johnson - (submitted by Darcy Gong). - * include/float.h: Add a first cut at the float.h header file. This - really should be an architecture/toolchain-specific header file. It - is only used if CONFIG_ARCH_FLOAT_H is defined. - * lib/math: Files now conform to coding standards. Separated float, - double, and long double versions of code into separate files so that - they don't draw in so much un-necessary code when doing a dumb link. - * binfmt/libelf: The ELF loader is working correctly with C++ static - constructors and destructors and all. - * Documentation/NuttXBinfmt.html: Add documentation of the binary loader. - * configs/sim/ostest: Converted to use the mconfig configuration tool. - * configs/sim/cxxtest: New test that will be used to verify the uClibc++ - port (eventually). - * include/nuttx/fs/fs.h, lib/stdio/lib_libfread.c, lib_ferror.c, - lib_feof.c, and lib_clearerr.c: Add support for ferror(), feof(), - and clearerror(). ferror() support is bogus at the moment (it - is equivalent to !feof()); the others should be good. - * configs/stm32f4discovery/include/board.h: Correct timer 2-7 - base frequency (provided by Freddie Chopin). - * include/nuttx/sched.h, sched/atexit.c, and sched/task_deletehook.c: - If both atexit() and on_exit() are enabled, then implement atexit() - as just a special caseof on_exit(). This assumes that the ABI can - handle receipt of more call parameters than the receiving function - expects. That is usually the case if parameters are passed in - registers. - * libxx/libxx_cxa_atexit(): Implements __cxa_atexit() - * configs/stm32f4discovery/cxxtest: New test that will be used to - verify the uClibc++ port (eventually). The sim platform turned not - to be a good platform for testing uClibc++. The sim example will not - run because the simulator will attempt to execute the static - constructors before main() starts. BUT... NuttX is not initialized - and this results in a crash. On the STM324Discovery, I will have - better control over when the static constructors run. - * RGMP 4.0 updated from Qiany Yu. - * configs/*/Make.defs and configs/*/ld.script: Massive clean-up - and standardization of linker scripts from Freddie Chopin. - * net/netdev_ioctl.c: Add interface state flags and ioctl calls - to bring network interfaces up and down (from Darcy Gong). - * config/stm32f4discovery: Enable C++ exceptions. Now the entire - apps/examples/cxxtest works -- meaning the the uClibc++ is - complete and verified for the STM32 platform. - -6.24 2012-xx-xx Gregory Nutt - - * arch/arm/src/stm32: Support for STM32F100 high density chips - added by Freddie Chopin. - * configs/stm32f100_generic: Support for generic STM32F100RC board - contributed by Freddie Chopin. - * arch/arm/src/stm32_otgfsdev.c: Partial fix from Petteri Aimonen. - * drivers/lcd/ug-2864ambag01.c and include/nuttx/lcd/ug_2864ambag01.h: - LCD driver for the Univision OLED of the same name (untested on - initial check-in). - * configs/stm32f4discovery/nxlines: Configure to use mconf/Kconfig - tool. - * configs/stm32f4discovery/src/up_ug2864ambag01.c: Board-specific - initialization for UG-2864AMBAG01 OLED connecte to STM32F4Disovery. - * libxx/libxx_stdthrow.cxx: Exception stubs from Petteri Aimonen. - * configs/stm32f4discovery/src/up_ug2864ambag01.c: Driver has been - verified on the STM32F4Discovery platform. Some tuning of the - configuration could improve the presentation. Lower resolution displays - are also more subject to the "fat, flat line bug" that I need to fix - someday. See http://www.nuttx.org/doku.php?id=wiki:graphics:nxgraphics - for a description of the fat, flat line bug. - * libc: Renamed nuttx/lib to nuttx/libc to make space for a true lib/ - directory that will be forthcoming. Also rename libraries: liblib.a -> libc.a, - libulib.a -> libuc.a, libklib.a -> libkc.a, liblibxx.a ->libcxx.a. - (I will probably, eventually rename libxx to libcxx for consistency) - * Makefile, lib/: A new, empty directory that will hold generated libraries. - This simplifies the library patch calculations and lets me get rid of some - bash logic. The change is functional, but only partially complete; - additional logic is needed in the arch/*/src/Makefile's as well. Right - now that logic generate multiple library paths, all pointing to the lib/ - directory. - * arch/*/src/Makefile: Now uses only the libraries in lib/ - Replace bash fragments that test for board/Makefile. - * Makefile.win: The beginnings of a Windows-native build. This is just - the begining and not yet ready for prime time use. - * configs/stm32f4discovery/winbuild: This is a version of the standard - NuttX OS test, but configured to build natively on Windows. Its only - real purpose is to very the native Windows build logic. - * tools/mkdeps.bat and tools/mkdeps.c: mkdeps.bat is a failed attempt - to leverage mkdeps.sh to CMD.exe. It fails because the are certain - critical CFLAG values that cannot be passed on the CMD.exe command line - (line '='). mkdeps.c is a work in progress that will, hopefully, - replace both mkdeps.sh and mkdeps.bat. - * tools/Config.mk: Centralize the definition of the scrpt that will be - used to generated header file include paths for the compiler. This - needs to be centralized in order to support the Windows native build. - * tools/incdir.bat: A replaced for tools/incdir.sh for use with the - the Windows native build. - * Makefile.unix: The existing top-level Makefile has been renamed - Makefile.unix. - * Makefile: This is a new top-level Makefile that just includes - either Makefile.unix or Makefile.win - * configs/stm3240g-eval/src: Qencoder fixes from Ryan Sundberg. - * arch/arm/src/stm32/stm32_qencoder.c: TIM3 bug fix from Ryan Sundberg. - * tools/mkromfsimg.sh: Correct typo in an error message (Ryan Sundberg) - * arch/*/src/Makefile: Remove tftboot install and creation of System.map - for Windows native build. The fist is necessary, the second just needs - re-implemented. - * configs/mirtoo: Update Mirtoo pin definitions for Release 2. Provided - by Konstantin Dimitrov. - * Fixed an uninitialized variable in the file system that can cause - assertions if DEBUG on (contributed by Lorenz Meier). - * Config.mk: Defined DELIM to be either / or \, depending upon - CONFIG_WINDOWS_NATIVE. This will allow me to eliminate a lot of - conditional logic elsewhere. - * nuttx/graphics: One a mouse button is pressed, continue to report all - mouse button events to the first window that received the the initial - button down event, even if the mouse attempts to dray outside the - window. From Petteri Aimonen. - * nuttx/graphics/nxmu/nx_block.c: One more fixe to the NX block message - logic from Petteri Aimonen. - * include/nuttx/wqueue.h: Some basic definitions to support a user- - space work queue (someday in the future). - * graphics/nxmu: Add semaphores so buffers messages that send buffers - will block until the buffer data has been acted upon. - * graphics/nxmw: Extended the blocked messages to cover mouse movement - and redraw events. These will also cause problems if sent to a window - while it is closing. - * arch/several: Change UARTs are enabled for i.MX, LM3S, ez80, and M16C to - match how they are enabled for other architectures. - * configs/ez80f910200kitg: Convert to use mconf configuration. - * sched/pause.c: Implements the POSIX pause() function. - * ez80: Lots of changes to ez80 configurations and build logic as I - struggle to get a clean Windows build (still not working). - * tools/prebuild.py: A Python script for Darcy Gong that can automate - many build/configuration operations. - * configs/cloudctrl: Darcy Gong's CloudController board. This is a - small network relay development board. Based on the Shenzhou IV development - board design. It is based on the STM32F107VC MCU. - * Lots of build files: ARMv7-M and MIPS32 Make.defs now include a common - Toolchain.defs file that can be used to manage toolchains in a more - configurable way. Contributed by Mike Smith - * configs/stm32f4discovery/winbuild and configs/cloudctrl: Adapted to use - Mike's Toolchain.defs. - * tools/configure.sh: Adapted to handle paths and setenv.bat files correctly - for native Windows builds. diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 10d624efb8..0fe6eb0f7c 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -20,75 +20,10 @@ menu "Build Setup" config EXPERIMENTAL bool "Prompt for development and/or incomplete code/drivers" -choice - prompt "Build Host Platform" - default HOST_LINUX - -config HOST_LINUX - bool "Linux" - -config HOST_OSX - bool "OSX" - -config HOST_WINDOWS - bool "Windows" - -config HOST_OTHER - bool "Other" - -endchoice - -choice - prompt "Windows Build Environment" - default WINDOWS_CYGWIN - depends on HOST_WINDOWS - -config WINDOWS_NATIVE - bool "Windows Native" - ---help--- - Build natively in a CMD.exe environment with Windows style paths (like C:\cgywin\home) - -config WINDOWS_CYGWIN - bool "Cygwin" -- --help--- - Build natively in a Cygwin environment with POSIX style paths (like /cygdrive/c/cgywin/home) - -config WINDOWS_MSYS - bool "MSYS" - ---help--- - Build natively in a Cygwin environment with POSIX style paths (like /cygdrive/c/cgywin/home) - -config WINDOWS_OTHER - bool "Windows POSIX-like environment" - ---help--- - Build natively in another POSIX-like environment. Additional support may be necessary - -endchoice - -config WINDOWS_MKLINK - bool "Use mklink" - default n - depends on WINDOWS_NATIVE - ---help--- - Use the mklink command to set up symbolic links when NuttX is - configured. Otherwise, configuration directories will be copied to - establish the configuration. - - If directories are copied, then some confusion can result ("Which - version of the file did I modify?"). In that case, it is recommended - that you re-build using 'make clean_context all'. That will cause the - configured directories to be recopied on each build. - - NOTE: This option also (1) that you have administrator privileges, (2) - that you are using Windows 2000 or better, and (3) that you are using - the NTFS file system. Select 'n' is that is not the case. - menu "Build Configuration" - config APPS_DIR string "Application directory" - default "../apps" if !WINDOWS_NATIVE - default "..\apps" if WINDOWS_NATIVE + default "../apps" ---help--- Identifies the directory that builds the application to link with NuttX. Default: ../apps This symbol must be assigned @@ -257,17 +192,6 @@ config ARCH_MATH_H that don't select ARCH_MATH_H, the redirecting math.h header file will stay out-of-the-way in include/nuttx/. -config ARCH_FLOAT_H - bool "float.h" - default n - ---help--- - The float.h header file defines the properties of your floating - point implementation. It would always be best to use your - toolchain's float.h header file but if none is avaiable, a default - float.h header file will provided if this option is selected. However - there is no assurance that the settings in this float.h are actually - correct for your platform! - config ARCH_STDARG_H bool "stdarg.h" default n @@ -320,24 +244,17 @@ config DEBUG_ENABLE comment "Subsystem Debug Options" -config DEBUG_MM - bool "Enable Memory Manager Debug Output" - default n - ---help--- - Enable memory management debug output (disabled by default) - config DEBUG_SCHED bool "Enable Scheduler Debug Output" default n ---help--- Enable OS debug output (disabled by default) -config DEBUG_PAGING - bool "Enable Demand Paging Debug Output" +config DEBUG_MM + bool "Enable Memory Manager Debug Output" default n - depends on PAGING ---help--- - Enable demand paging debug output (disabled by default) + Enable memory management debug output (disabled by default) config DEBUG_NET bool "Enable Network Debug Output" @@ -394,13 +311,6 @@ config DEBUG_INPUT Enable low level debug output from the input device drivers such as mice and touchscreens (disabled by default) -config DEBUG_ANALOG - bool "Enable Analog Device Debug Output" - default n - ---help--- - Enable low level debug output from the analog device drivers such as - A/D and D/A converters (disabled by default) - config DEBUG_I2C bool "Enable I2C Debug Output" default n @@ -415,18 +325,12 @@ config DEBUG_SPI ---help--- Enable I2C driver debug output (disabled by default) -config DEBUG_DMA - bool "Enable DMA Debug Output" - default n - ---help--- - Enable DMA-releated debug output (disabled by default) - config DEBUG_WATCHDOG bool "Enable Watchdog Timer Debug Output" default n depends on WATCHDOG ---help--- - Enable watchdog timer debug output (disabled by default) + Enable watchdog timer debug output (disabled by default) endif @@ -471,12 +375,8 @@ menu "Memory Management" source mm/Kconfig endmenu -menu "Binary Formats" -source binfmt/Kconfig -endmenu - menu "Library Routines" -source libc/Kconfig +source lib/Kconfig source libxx/Kconfig endmenu diff --git a/nuttx/Makefile b/nuttx/Makefile index cf7a57c83d..7a058d88e9 100644 --- a/nuttx/Makefile +++ b/nuttx/Makefile @@ -1,7 +1,7 @@ ############################################################################ # Makefile # -# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -33,17 +33,619 @@ # ############################################################################ -# This is a top-level "kludge" Makefile that just includes the correct -# Makefile. If you already know the Makefile that you want, you can skip -# this nonsense using: -# -# make -f Makefile.unix, OR -# make -f Makefile.win -# +TOPDIR := ${shell pwd | sed -e 's/ /\\ /g'} +-include ${TOPDIR}/.config +-include ${TOPDIR}/tools/Config.mk +-include ${TOPDIR}/Make.defs --include .config -ifeq ($(CONFIG_WINDOWS_NATIVE),y) -include Makefile.win +# Control build verbosity + +ifeq ($(V),1) +export Q := else -include Makefile.unix +export Q := @ endif + +# Default tools + +ifeq ($(DIRLINK),) +DIRLINK = $(TOPDIR)/tools/link.sh +DIRUNLINK = $(TOPDIR)/tools/unlink.sh +endif + +# This define is passed as EXTRADEFINES for kernel-mode builds. It is also passed +# during PASS1 (but not PASS2) context and depend targets. + +KDEFINE = ${shell $(TOPDIR)/tools/define.sh $(CC) __KERNEL__} + +# Process architecture and board-specific directories + +ARCH_DIR = arch/$(CONFIG_ARCH) +ARCH_SRC = $(ARCH_DIR)/src +ARCH_INC = $(ARCH_DIR)/include +BOARD_DIR = configs/$(CONFIG_ARCH_BOARD) + +# Add-on directories. These may or may not be in place in the +# NuttX source tree (they must be specifically installed) +# +# CONFIG_APPS_DIR can be over-ridden from the command line or in the .config file. +# The default value of CONFIG_APPS_DIR is ../apps. Ultimately, the application +# will be built if APPDIR is defined. APPDIR will be defined if a directory containing +# a Makefile is found at the path provided by CONFIG_APPS_DIR + +ifeq ($(CONFIG_APPS_DIR),) +CONFIG_APPS_DIR = ../apps +endif +APPDIR := ${shell if [ -r $(CONFIG_APPS_DIR)/Makefile ]; then echo "$(CONFIG_APPS_DIR)"; fi} + +# All add-on directories. +# +# NUTTX_ADDONS is the list of directories built into the NuttX kernel. +# USER_ADDONS is the list of directories that will be built into the user application + +NUTTX_ADDONS := $(NX_DIR) +USER_ADDONS := + +ifeq ($(CONFIG_NUTTX_KERNEL),y) +USER_ADDONS += $(APPDIR) +else +NUTTX_ADDONS += $(APPDIR) +endif + +# Lists of build directories. +# +# FSDIRS depend on file descriptor support; NONFSDIRS do not (except for parts +# of FSDIRS). We will exclude FSDIRS from the build if file descriptor +# support is disabled +# CONTEXTDIRS include directories that have special, one-time pre-build +# requirements. Normally this includes things like auto-generation of +# configuration specific files or creation of configurable symbolic links +# USERDIRS - When NuttX is build is a monolithic kernel, this provides the +# list of directories that must be built +# OTHERDIRS - These are directories that are not built but probably should +# be cleaned to prevent garbarge from collecting in them when changing +# configurations. + +NONFSDIRS = sched $(ARCH_SRC) $(NUTTX_ADDONS) +FSDIRS = fs drivers binfmt +CONTEXTDIRS = $(APPDIR) +USERDIRS = + +ifeq ($(CONFIG_NUTTX_KERNEL),y) + +NONFSDIRS += syscall +CONTEXTDIRS += syscall +USERDIRS += syscall lib mm $(USER_ADDONS) +ifeq ($(CONFIG_HAVE_CXX),y) +USERDIRS += libxx +endif + +else + +NONFSDIRS += lib mm +OTHERDIRS += syscall $(USER_ADDONS) +ifeq ($(CONFIG_HAVE_CXX),y) +NONFSDIRS += libxx +else +OTHERDIRS += libxx +endif + +endif + +ifeq ($(CONFIG_NX),y) +NONFSDIRS += graphics +CONTEXTDIRS += graphics +else +OTHERDIRS += graphics +endif + +# CLEANDIRS are the directories that will clean in. These are +# all directories that we know about. +# KERNDEPDIRS are the directories in which we will build target dependencies. +# If NuttX and applications are built separately (CONFIG_NUTTX_KERNEL), +# then this holds only the directories containing kernel files. +# USERDEPDIRS. If NuttX and applications are built separately (CONFIG_NUTTX_KERNEL), +# then this holds only the directories containing user files. + +CLEANDIRS = $(NONFSDIRS) $(FSDIRS) $(USERDIRS) $(OTHERDIRS) +KERNDEPDIRS = $(NONFSDIRS) +USERDEPDIRS = $(USERDIRS) + +# Add file system directories to KERNDEPDIRS (they are already in CLEANDIRS) + +ifeq ($(CONFIG_NFILE_DESCRIPTORS),0) +ifeq ($(CONFIG_NET),y) +ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0) +KERNDEPDIRS += fs +endif +KERNDEPDIRS += drivers +endif +else +KERNDEPDIRS += $(FSDIRS) +endif + +# Add networking directories to KERNDEPDIRS and CLEANDIRS + +ifeq ($(CONFIG_NET),y) +KERNDEPDIRS += net +endif +CLEANDIRS += net + +# +# Extra objects used in the final link. +# +# Pass 1 1ncremental (relative) link objects should be put into the +# processor-specific source directory (where other link objects will +# be created). If the pass1 obect is an archive, it could go anywhere. + +ifeq ($(CONFIG_BUILD_2PASS),y) +EXTRA_OBJS += $(CONFIG_PASS1_OBJECT) +endif + +# NUTTXLIBS is the list of NuttX libraries that is passed to the +# processor-specific Makefile to build the final NuttX target. +# Libraries in FSDIRS are excluded if file descriptor support +# is disabled. +# USERLIBS is the list of libraries used to build the final user-space +# application + +NUTTXLIBS = sched/libsched$(LIBEXT) $(ARCH_SRC)/libarch$(LIBEXT) +USERLIBS = + +# Add libraries for syscall support. The C library will be needed by +# both the kernel- and user-space builds. For now, the memory manager (mm) +# is placed in user space (only). + +ifeq ($(CONFIG_NUTTX_KERNEL),y) +NUTTXLIBS += syscall/libstubs$(LIBEXT) lib/libklib$(LIBEXT) +USERLIBS += syscall/libproxies$(LIBEXT) lib/libulib$(LIBEXT) mm/libmm$(LIBEXT) +else +NUTTXLIBS += mm/libmm$(LIBEXT) lib/liblib$(LIBEXT) +endif + +# Add libraries for C++ support. CXX, CXXFLAGS, and COMPILEXX must +# be defined in Make.defs for this to work! + +ifeq ($(CONFIG_HAVE_CXX),y) +ifeq ($(CONFIG_NUTTX_KERNEL),y) +USERLIBS += libxx/liblibxx$(LIBEXT) +else +NUTTXLIBS += libxx/liblibxx$(LIBEXT) +endif +endif + +# Add library for application support. + +ifneq ($(APPDIR),) +ifeq ($(CONFIG_NUTTX_KERNEL),y) +USERLIBS += $(APPDIR)/libapps$(LIBEXT) +else +NUTTXLIBS += $(APPDIR)/libapps$(LIBEXT) +endif +endif + +# Add libraries for network support + +ifeq ($(CONFIG_NET),y) +NUTTXLIBS += net/libnet$(LIBEXT) +endif + +# Add libraries for file system support + +ifeq ($(CONFIG_NFILE_DESCRIPTORS),0) +ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0) +NUTTXLIBS += fs/libfs$(LIBEXT) +endif +ifeq ($(CONFIG_NET),y) +NUTTXLIBS += drivers/libdrivers$(LIBEXT) +endif +else +NUTTXLIBS += fs/libfs$(LIBEXT) drivers/libdrivers$(LIBEXT) binfmt/libbinfmt$(LIBEXT) +endif + +# Add libraries for the NX graphics sub-system + +ifneq ($(NX_DIR),) +NUTTXLIBS += $(NX_DIR)/libnx$(LIBEXT) +endif + +ifeq ($(CONFIG_NX),y) +NUTTXLIBS += graphics/libgraphics$(LIBEXT) +endif + +# This is the name of the final target (relative to the top level directorty) + +BIN = nuttx$(EXEEXT) + +all: $(BIN) +.PHONY: context clean_context check_context export subdir_clean clean subdir_distclean distclean apps_clean apps_distclean + +# Target used to copy include/nuttx/math.h. If CONFIG_ARCH_MATH_H is +# defined, then there is an architecture specific math.h header file +# that will be included indirectly from include/math.h. But first, we +# have to copy math.h from include/nuttx/. to include/. + +ifeq ($(CONFIG_ARCH_MATH_H),y) +include/math.h: include/nuttx/math.h + @cp -f include/nuttx/math.h include/math.h +else +include/math.h: +endif + +# Target used to copy include/nuttx/stdarg.h. If CONFIG_ARCH_STDARG_H is +# defined, then there is an architecture specific stdarg.h header file +# that will be included indirectly from include/stdarg.h. But first, we +# have to copy stdarg.h from include/nuttx/. to include/. + +ifeq ($(CONFIG_ARCH_STDARG_H),y) +include/stdarg.h: include/nuttx/stdarg.h + @cp -f include/nuttx/stdarg.h include/stdarg.h +else +include/stdarg.h: +endif + +# Targets used to build include/nuttx/version.h. Creation of version.h is +# part of the overall NuttX configuration sequence. Notice that the +# tools/mkversion tool is built and used to create include/nuttx/version.h + +tools/mkversion: + @$(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkversion + +$(TOPDIR)/.version: + @if [ ! -f .version ]; then \ + echo "No .version file found, creating one"; \ + tools/version.sh -v 0.0 -b 0 .version; \ + chmod 755 .version; \ + fi + +include/nuttx/version.h: $(TOPDIR)/.version tools/mkversion + @tools/mkversion $(TOPDIR) > include/nuttx/version.h + +# Targets used to build include/nuttx/config.h. Creation of config.h is +# part of the overall NuttX configuration sequence. Notice that the +# tools/mkconfig tool is built and used to create include/nuttx/config.h + +tools/mkconfig: + @$(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkconfig + +include/nuttx/config.h: $(TOPDIR)/.config tools/mkconfig + @tools/mkconfig $(TOPDIR) > include/nuttx/config.h + +# dirlinks, and helpers +# +# Directories links. Most of establishing the NuttX configuration involves +# setting up symbolic links with 'generic' directory names to specific, +# configured directories. +# +# Link the apps/include directory to include/apps + +include/apps: Make.defs +ifneq ($(APPDIR),) + @if [ -d $(TOPDIR)/$(APPDIR)/include ]; then \ + $(DIRLINK) $(TOPDIR)/$(APPDIR)/include include/apps; \ + fi +endif + +# Link the arch//include directory to include/arch + +include/arch: Make.defs + @$(DIRLINK) $(TOPDIR)/$(ARCH_DIR)/include include/arch + +# Link the configs//include directory to include/arch/board + +include/arch/board: include/arch Make.defs include/arch + @$(DIRLINK) $(TOPDIR)/$(BOARD_DIR)/include include/arch/board + +# Link the configs//src dir to arch//src/board + +$(ARCH_SRC)/board: Make.defs + @$(DIRLINK) $(TOPDIR)/$(BOARD_DIR)/src $(ARCH_SRC)/board + +# Link arch//include/ to arch//include/chip + +$(ARCH_SRC)/chip: Make.defs +ifneq ($(CONFIG_ARCH_CHIP),) + @$(DIRLINK) $(TOPDIR)/$(ARCH_SRC)/$(CONFIG_ARCH_CHIP) $(ARCH_SRC)/chip +endif + +# Link arch//src/ to arch//src/chip + +include/arch/chip: include/arch Make.defs +ifneq ($(CONFIG_ARCH_CHIP),) + @$(DIRLINK) $(TOPDIR)/$(ARCH_INC)/$(CONFIG_ARCH_CHIP) include/arch/chip +endif + +dirlinks: include/arch include/arch/board include/arch/chip $(ARCH_SRC)/board $(ARCH_SRC)/chip include/apps + +# context +# +# The context target is invoked on each target build to assure that NuttX is +# properly configured. The basic configuration steps include creation of the +# the config.h and version.h header files in the include/nuttx directory and +# the establishment of symbolic links to configured directories. + +context: check_context include/nuttx/config.h include/nuttx/version.h include/math.h include/stdarg.h dirlinks + @for dir in $(CONTEXTDIRS) ; do \ + $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" context; \ + done + +# clean_context +# +# This is part of the distclean target. It removes all of the header files +# and symbolic links created by the context target. + +clean_context: + @rm -f include/nuttx/config.h + @rm -f include/nuttx/version.h + @rm -f include/math.h + @rm -f include/stdarg.h + @$(DIRUNLINK) include/arch/board + @$(DIRUNLINK) include/arch/chip + @$(DIRUNLINK) include/arch + @$(DIRUNLINK) $(ARCH_SRC)/board + @$(DIRUNLINK) $(ARCH_SRC)/chip + @$(DIRUNLINK) include/apps + +# check_context +# +# This target checks if NuttX has been configured. NuttX is configured using +# the script tools/configure.sh. That script will install certain files in +# the top-level NuttX build directory. This target verifies that those +# configuration files have been installed and that NuttX is ready to be built. + +check_context: + @if [ ! -e ${TOPDIR}/.config -o ! -e ${TOPDIR}/Make.defs ]; then \ + echo "" ; echo "Nuttx has not been configured:" ; \ + echo " cd tools; ./configure.sh " ; echo "" ; \ + exit 1 ; \ + fi + +# Archive targets. The target build sequency will first create a series of +# libraries, one per configured source file directory. The final NuttX +# execution will then be built from those libraries. The following targets +# built those libraries. +# +# Possible kernel-mode builds + +lib/libklib$(LIBEXT): context + @$(MAKE) -C lib TOPDIR="$(TOPDIR)" libklib$(LIBEXT) EXTRADEFINES=$(KDEFINE) + +sched/libsched$(LIBEXT): context + @$(MAKE) -C sched TOPDIR="$(TOPDIR)" libsched$(LIBEXT) EXTRADEFINES=$(KDEFINE) + +$(ARCH_SRC)/libarch$(LIBEXT): context + @$(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" libarch$(LIBEXT) EXTRADEFINES=$(KDEFINE) + +net/libnet$(LIBEXT): context + @$(MAKE) -C net TOPDIR="$(TOPDIR)" libnet$(LIBEXT) EXTRADEFINES=$(KDEFINE) + +fs/libfs$(LIBEXT): context + @$(MAKE) -C fs TOPDIR="$(TOPDIR)" libfs$(LIBEXT) EXTRADEFINES=$(KDEFINE) + +drivers/libdrivers$(LIBEXT): context + @$(MAKE) -C drivers TOPDIR="$(TOPDIR)" libdrivers$(LIBEXT) EXTRADEFINES=$(KDEFINE) + +binfmt/libbinfmt$(LIBEXT): context + @$(MAKE) -C binfmt TOPDIR="$(TOPDIR)" libbinfmt$(LIBEXT) EXTRADEFINES=$(KDEFINE) + +graphics/libgraphics$(LIBEXT): context + @$(MAKE) -C graphics TOPDIR="$(TOPDIR)" libgraphics$(LIBEXT) EXTRADEFINES=$(KDEFINE) + +syscall/libstubs$(LIBEXT): context + @$(MAKE) -C syscall TOPDIR="$(TOPDIR)" libstubs$(LIBEXT) EXTRADEFINES=$(KDEFINE) + +# Possible user-mode builds + +lib/libulib$(LIBEXT): context + @$(MAKE) -C lib TOPDIR="$(TOPDIR)" libulib$(LIBEXT) + +libxx/liblibxx$(LIBEXT): context + @$(MAKE) -C libxx TOPDIR="$(TOPDIR)" liblibxx$(LIBEXT) + +mm/libmm$(LIBEXT): context + @$(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) EXTRADEFINES=$(KDEFINE) + +$(APPDIR)/libapps$(LIBEXT): context + @$(MAKE) -C $(APPDIR) TOPDIR="$(TOPDIR)" libapps$(LIBEXT) + +syscall/libproxies$(LIBEXT): context + @$(MAKE) -C syscall TOPDIR="$(TOPDIR)" libproxies$(LIBEXT) + +# Possible non-kernel builds + +lib/liblib$(LIBEXT): context + @$(MAKE) -C lib TOPDIR="$(TOPDIR)" liblib$(LIBEXT) + +# pass1 and pass2 +# +# If the 2 pass build option is selected, then this pass1 target is +# configured to built before the pass2 target. This pass1 target may, as an +# example, build an extra link object (CONFIG_PASS1_OBJECT) which may be an +# incremental (relative) link object, but could be a static library (archive); +# some modification to this Makefile would be required if CONFIG_PASS1_OBJECT +# is an archive. Exactly what is performed during pass1 or what it generates +# is unknown to this makefule unless CONFIG_PASS1_OBJECT is defined. + +pass1deps: context pass1dep $(USERLIBS) + +pass1: pass1deps +ifeq ($(CONFIG_BUILD_2PASS),y) + @if [ -z "$(CONFIG_PASS1_BUILDIR)" ]; then \ + echo "ERROR: CONFIG_PASS1_BUILDIR not defined"; \ + exit 1; \ + fi + @if [ ! -d "$(CONFIG_PASS1_BUILDIR)" ]; then \ + echo "ERROR: CONFIG_PASS1_BUILDIR does not exist"; \ + exit 1; \ + fi + @if [ ! -f "$(CONFIG_PASS1_BUILDIR)/Makefile" ]; then \ + echo "ERROR: No Makefile in CONFIG_PASS1_BUILDIR"; \ + exit 1; \ + fi + @$(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" LINKLIBS="$(NUTTXLIBS)" USERLIBS="$(USERLIBS)" "$(CONFIG_PASS1_TARGET)" +endif + +pass2deps: context pass2dep $(NUTTXLIBS) + +pass2: pass2deps + @$(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(NUTTXLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN) + @if [ -w /tftpboot ] ; then \ + cp -f $(BIN) /tftpboot/$(BIN).${CONFIG_ARCH}; \ + fi +ifeq ($(CONFIG_RRLOAD_BINARY),y) + @echo "MK: $(BIN).rr" + @$(TOPDIR)/tools/mkimage.sh --Prefix $(CROSSDEV) $(BIN) $(BIN).rr + @if [ -w /tftpboot ] ; then \ + cp -f $(BIN).rr /tftpboot/$\(BIN).rr.$(CONFIG_ARCH); \ + fi +endif +ifeq ($(CONFIG_INTELHEX_BINARY),y) + @echo "CP: $(BIN).hex" + @$(OBJCOPY) $(OBJCOPYARGS) -O ihex $(BIN) $(BIN).hex +endif +ifeq ($(CONFIG_MOTOROLA_SREC),y) + @echo "CP: $(BIN).srec" + @$(OBJCOPY) $(OBJCOPYARGS) -O srec $(BIN) $(BIN).srec +endif +ifeq ($(CONFIG_RAW_BINARY),y) + @echo "CP: $(BIN).bin" + @$(OBJCOPY) $(OBJCOPYARGS) -O binary $(BIN) $(BIN).bin +endif + +# $(BIN) +# +# Create the final NuttX executable in a two pass build process. In the +# normal case, all pass1 and pass2 dependencies are created then pass1 +# and pass2 targets are built. However, in some cases, you may need to build +# pass1 depenencies and pass1 first, then build pass2 dependencies and pass2. +# in that case, execute 'make pass1 pass2' from the command line. + +$(BIN): pass1deps pass2deps pass1 pass2 + +# download +# +# This is a helper target that will rebuild NuttX and download it to the target +# system in one step. The operation of this target depends completely upon +# implementation of the DOWNLOAD command in the user Make.defs file. It will +# generate an error an error if the DOWNLOAD command is not defined. + +download: $(BIN) + $(call DOWNLOAD, $<) + +# pass1dep: Create pass1 build dependencies +# pass2dep: Create pass2 build dependencies + +pass1dep: context + @for dir in $(USERDEPDIRS) ; do \ + $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" depend ; \ + done + +pass2dep: context + @for dir in $(KERNDEPDIRS) ; do \ + $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" EXTRADEFINES=$(KDEFINE) depend; \ + done + +# Configuration targets +# +# These targets depend on the kconfig-frontends packages. To use these, you +# must first download and install the kconfig-frontends package from this +# location: http://ymorin.is-a-geek.org/projects/kconfig-frontends. See +# misc/tools/README.txt for additional information. + +config: + @APPSDIR=${CONFIG_APPS_DIR} conf Kconfig + +oldconfig: + @APPSDIR=${CONFIG_APPS_DIR} conf --oldconfig Kconfig + +menuconfig: + @APPSDIR=${CONFIG_APPS_DIR} mconf Kconfig + +# export +# +# The export target will package the NuttX libraries and header files into +# an exportable package. Caveats: (1) These needs some extension for the KERNEL +# build; it needs to receive USERLIBS and create a libuser.a). (2) The logic +# in tools/mkexport.sh only supports GCC and, for example, explicitly assumes +# that the archiver is 'ar' + +export: pass2deps + @tools/mkexport.sh -w$(WINTOOL) -t "$(TOPDIR)" -l "$(NUTTXLIBS)" + +# General housekeeping targets: dependencies, cleaning, etc. +# +# depend: Create both PASS1 and PASS2 dependencies +# clean: Removes derived object files, archives, executables, and +# temporary files, but retains the configuration and context +# files and directories. +# distclean: Does 'clean' then also removes all configuration and context +# files. This essentially restores the directory structure +# to its original, unconfigured stated. + +depend: pass1dep pass2dep + +subdir_clean: + @for dir in $(CLEANDIRS) ; do \ + if [ -e $$dir/Makefile ]; then \ + $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" clean ; \ + fi \ + done + @$(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" clean + @$(MAKE) -C mm -f Makefile.test TOPDIR="$(TOPDIR)" clean +ifeq ($(CONFIG_BUILD_2PASS),y) + @$(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" clean +endif + +clean: subdir_clean + @rm -f $(BIN) nuttx.* mm_test *.map _SAVED_APPS_config *~ + @rm -f nuttx-export* + +subdir_distclean: + @for dir in $(CLEANDIRS) ; do \ + if [ -e $$dir/Makefile ]; then \ + $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" distclean ; \ + fi \ + done + +distclean: clean subdir_distclean clean_context +ifeq ($(CONFIG_BUILD_2PASS),y) + @$(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean +endif + @rm -f Make.defs setenv.sh .config .config.old + +# Application housekeeping targets. The APPDIR variable refers to the user +# application directory. A sample apps/ directory is included with NuttX, +# however, this is not treated as part of NuttX and may be replaced with a +# different application directory. For the most part, the application +# directory is treated like any other build directory in this script. However, +# as a convenience, the following targets are included to support housekeeping +# functions in the user application directory from the NuttX build directory. +# +# apps_clean: Perform the clean operation only in the user application +# directory +# apps_distclean: Perform the distclean operation only in the user application +# directory. Note that the apps/.config file (inf any) is +# preserved so that this is not a "full" distclean but more of a +# configuration "reset." (There willnot be an apps/.config +# file if the configuration was generated via make menuconfig). + +apps_clean: +ifneq ($(APPDIR),) + @$(MAKE) -C "$(TOPDIR)/$(APPDIR)" TOPDIR="$(TOPDIR)" clean +endif + +apps_distclean: +ifneq ($(APPDIR),) + @if [ -r "$(TOPDIR)/$(APPDIR)/.config" ]; then \ + cp "$(TOPDIR)/$(APPDIR)/.config" _SAVED_APPS_config || \ + { echo "Copy of $(APPDIR)/.config failed" ; exit 1 ; } \ + else \ + rm -f _SAVED_APPS_config; \ + fi + @$(MAKE) -C "$(TOPDIR)/$(APPDIR)" TOPDIR="$(TOPDIR)" distclean + @if [ -r _SAVED_APPS_config ]; then \ + @mv _SAVED_APPS_config "$(TOPDIR)/$(APPDIR)/.config" || \ + { echo "Copy of _SAVED_APPS_config failed" ; exit 1 ; } \ + fi +endif + diff --git a/nuttx/README.txt b/nuttx/README.txt index a133f209a6..d60da2d889 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -18,8 +18,6 @@ README - Building - Re-building - Build Targets and Options - - Native Windows Build - - Installing GNUWin32 o Cygwin Build Problems - Strange Path Problems - Window Native Toolchain Issues @@ -156,15 +154,9 @@ Notes about Header Files Even though you should not use a foreign C-Library, you may still need to use other, external libraries with NuttX. In particular, you may - need to use the math library, libm.a. NuttX supports a generic, built-in - math library that can be enabled using CONFIG_LIBM=y. However, you may - still want to use a higher performance external math library that has - been tuned for your CPU. Sometimes such such tuned math libraries are - bundled with your toolchain. - - The math libary header file, math.h, is a then special case. If you do - nothing, the standard math.h header file that is provided with your - toolchain will be used. + need to use the math library, libm.a. The math libary header file, + math.h, is a special case. If you do nothing, the standard math.h + header file that is provided with your toolchain will be used. If you have a custom, architecture specific math.h header file, then that header file should be placed at arch//include/math.h. There @@ -179,16 +171,6 @@ Notes about Header Files than to include that archicture-specific math.h header file as the system math.h header file. - float.h - - If you enable the generic, built-in math library, then that math library - will expect your toolchain to provide the standard float.h header file. - The float.h header file defines the properties of your floating point - implementation. It would always be best to use your toolchain's float.h - header file but if none is avaiable, a default float.h header file will - provided if this option is selected. However, there is no assurance that - the settings in this float.h are actually correct for your platform! - stdarg.h In most cases, the correct version of stdarg.h is the version provided with your toolchain. However, sometimes there are issues with with using your toolchains stdarg.h. For example, it may attempt to draw in header files that do not exist in NuttX or perhaps the header files that is uses are not compatible with the NuttX header files. In those cases, you can use an architecture-specific stdarg.h header file by defining CONFIG_ARCH_STDARG_H=y. @@ -207,8 +189,7 @@ Instantiating "Canned" Configurations Where is the name of your development board and . Configuring NuttX requires only copying three files from the -to the directory where you installed NuttX (TOPDIR) (and sometimes one -additional file to the directory the NuttX application package (APPSDIR)): +to the directly where you installed NuttX (TOPDIR): Copy configs///Make.def to ${TOPDIR}/Make.defs @@ -230,14 +211,6 @@ additional file to the directory the NuttX application package (APPSDIR)): included in the build and what is not. This file is also used to generate a C configuration header at include/nuttx/config.h. - Copy configs///appconfig to ${APPSDIR}/.config - - The appconfig file describes the applications that need to be - built in the appliction directory (APPSDIR). Not all configurations - have an appconfig file. This file is deprecated and will not be - used with new defconfig files produced with the mconf configuration - tool. - General information about configuring NuttX can be found in: ${TOPDIR}/configs/README.txt @@ -495,101 +468,6 @@ Build Targets and Options useful when adding new boards or tracking down compile time errors and warnings (Contributed by Richard Cochran). -Native Windows Build --------------------- - - The beginnings of a Windows native build are in place but still not full - usable as of this writing. The windows native build logic is currently - separate and must be started by: - - make -f Makefile.win - - This build: - - - Uses all Windows style paths - - Uses primarily Windows batch commands from cmd.exe, with - - A few extensions from GNUWin32 (or MSYS is you prefer) - - In this build, you cannot use a Cygwin or MSYS shell. Rather the build must - be performed in a Windows CMD shell. Here is a better shell than than the - standard issue, CMD shell: ConEmu which can be downloaded from: - http://code.google.com/p/conemu-maximus5/ - - Build Tools. The build still relies on some Unix-like commands. I use - the GNUWin32 tools that can be downloaded from http://gnuwin32.sourceforge.net/. - The MSYS tools are probably also a option but are likely lower performance - since they are based on Cygwin 1.3. - - Host Compiler: I use the MingGW compiler which can be downloaded from - http://www.mingw.org/. If you are using GNUWin32, then it is recommended - the you not install the optional MSYS components as there may be conflicts. - -Installing GNUWin32 -------------------- - -The Windows native build will depend upon a few Unix-like tools that can be -provided either by MSYS or GNUWin32. The GNUWin32 are available from -http://gnuwin32.sourceforge.net/. GNUWin32 provides ports of tools with a -GPL or similar open source license to modern MS-Windows (Microsoft Windows -2000 / XP / 2003 / Vista / 2008 / 7). See -http://gnuwin32.sourceforge.net/packages.html for a list of all of the tools -available in the GNUWin32 package. - -The SourceForge project is located here: -http://sourceforge.net/projects/gnuwin32/. The project is still being -actively supported (although some of the Windows ports have gotten very old). - -Some commercial toolchains include a subset of the GNUWin32 tools in the -installation. My recommendation is that you download the GNUWin32 tools -directly from the sourceforge.net website so that you will know what you are -using and can reproduce your build environment. - -GNUWin32 Installation Steps: - -The following steps will download and execute the GNUWin32 installer. - -1. Download GetGNUWin32-x.x.x.exe from - http://sourceforge.net/projects/getgnuwin32/files/. This is the - installer. The current version as of this writing is 0.6.3. - -2. Run the installer. - -3. Accept the license. - -4. Select the installation directory. My recommendation is the - directory that contains this README file (). - -5. After running GetGNUWin32-0.x.x.exe, you will have a new directory - /GetGNUWin32 - -Note the the GNUWin32 installer didn't install GNUWin32. Instead, it -installed another, smarter downloader. That downloader is the GNUWin32 -package management tool developed by the Open SSL project. - -The following steps probably should be performed from inside a DOS shell. - -6. Change to the directory created by GetGNUWin32-x.x.x.exe - - cd GetGNUWin32 - -7. Execute the download.bat script. The download.bat script will download - about 446 packages! Enough to have a very complete Linux-like environment - under the DOS shell. This will take awhile. This step only downloads - the packages and the next step will install the packages. - - download - -8. This step will install the downloaded packages. The argument of the - install.bat script is the installation location. C:\gnuwin32 is the - standard install location: - - install C:\gnuwin32 - -NOTE: This installation step will install *all* GNUWin32 packages... far -more than you will ever need. If disc space is a problem for you, you might -need to perform a manual installation of the individual ZIP files that you -will find in the /GetGNUWin32/packages directory. - CYGWIN BUILD PROBLEMS ^^^^^^^^^^^^^^^^^^^^^ @@ -645,16 +523,18 @@ Window Native Toolchain Issues is not a long as you might think because there is no dependency checking if you are using a native Windows toolchain. That bring us to #3: - 3. Dependencies are not made when using Windows versions of the GCC on a POSIX - platform (i.e., Cygwin). This is because the dependencies are generated - using Windows paths which do not work with the Cygwin make. + 3. Dependencies are not made when using Windows versions of the GCC. This is + because the dependencies are generated using Windows pathes which do not + work with the Cygwin make. - MKDEP = $(TOPDIR)/tools/mknulldeps.sh + Support has been added for making dependencies with the windows-native toolchains. + That support can be enabled by modifying your Make.defs file as follows: - If you are building natively on Windows, then no such conflict exists - and the best selection is: + - MKDEP = $(TOPDIR)/tools/mknulldeps.sh + + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - MKDEP = $(TOPDIR)/tools/mkdeps.exe + If you have problems with the dependency build (for example, if you are not + building on C:), then you may need to modify tools/mkdeps.sh General Pre-built Toolchain Issues @@ -885,8 +765,6 @@ nuttx | | `- README.txt | |- stm3240g-eval/ | | `- README.txt - | |- stm32f100rc_generic/ - | | `- README.txt | |- stm32f4discovery/ | | `- README.txt | |- sure-pic32mx/ @@ -939,8 +817,6 @@ nuttx | `- README.txt |- lib/ | `- README.txt - |- libc/ - | `- README.txt |- libxx/ | `- README.txt |- mm/ @@ -952,7 +828,6 @@ nuttx apps |- examples/ - | |- json/README.txt | |- pashello/README.txt | `- README.txt |- graphics/ @@ -968,8 +843,6 @@ apps | | `- README.txt | |- ftpc | | `- README.txt - | |- json - | | `- README.txt | |- telnetd | | `- README.txt | `- README.txt @@ -991,12 +864,3 @@ apps | `- sysinfo | `- README.txt `- README.txt - - NxWidgets - |- Doxygen - | `- README.txt - |- tools - | `- README.txt - |- UnitTests - | `- README.txt - `- README.txt diff --git a/nuttx/ReleaseNotes b/nuttx/ReleaseNotes index 5fe67a663e..b1d5f6064c 100644 --- a/nuttx/ReleaseNotes +++ b/nuttx/ReleaseNotes @@ -3171,81 +3171,3 @@ Bugfixes (see the change log for details). Some of these are very important Vainish). Fix some field-width handling issues in sscanf() As well as other, less critical bugs (see the ChangeLog for details) - -NuttX-6.23 -^^^^^^^^^^ - -The 90th release of NuttX, Version 6.23, was made on November 5, 2012, -and is available for download from the SourceForge website. Note -that release consists of two tarballs: nuttx-6.23.tar.gz and -apps-6.23.tar.gz. Both may be needed (see the top-level nuttx/README.txt -file for build information). - -This release corresponds with SVN release number: r5313 - -Note that all SVN information has been stripped from the tarballs. If you -r5313 the SVN configuration, you should check out directly from SVN. Revision -r5206 should equivalent to release 6.22 of NuttX 6.22: - - svn checkout -r5313 svn://svn.code.sf.net/p/nuttx/code/trunk nuttx-code - -Or - - svn checkout -r5313 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code - -Additional new features and extended functionality: - - * RTOS: If both atexit() and on_exit() are enabled, use on_exit() to - implement atexit(). Updates for RGMP 4.0. - - * Binfmt: Add support for loading and executing ELF binary modules from - a file system. - - * Drivers: Maxim MAX11802 touchscreen controller (Petteri Aimonen) - - * STM32 Driver: Implementation of /dev/random using the STM32 Random Number - Generator (RNG). - - * STM32 Boards: ADC support for the Shenzhou IV board. Relay support for - the Shenzhou IV board. - - * C Library: Support is now included for the add-on uClibc++ C++ - standard library support. This includes support for iostreams, strings, - STL, RTTI, exceptions -- the complete C++ environment. (uClibc++ is - provided as a separate add-on package due to licensing issues). - - Optimized generic and ARM-specific memcpy() function. Optimized - memset() function. - - Add support for ferror(), feof(), and clearerror(). Add support for - __cxa_atexit(). - - Math Library: Port of the math library from Rhombus OS by Nick Johnson - (Darcy Gong). - - * Applications: New NSH commands: ifup, ifdown, urlencode, urldecode, - base64enc, bas64dec, md5 (Darcy Gong). Add support for NSH telnet login - (Darcy Gong). Enancements to NSH ping command to support pinging hosts - with very long round-trip times. Extensions to the ifconfig command - Darcy Gong), - - Many extensions to the webclient/wget and DNS resolver logic from Darcy - Gong. JSON, Base64, URL encoding, and MD5 libraries contributed by Darcy - Gong. - - New examples: ELF loader, JSON, wgetjson, cxxtest, relays. - -Bugfixes (see the change log for details). Some of these are very important -(marked *critical*): - - * Drivers: W25 SPI FLASH - - * STM32 Drivers: ADC reset - - * Graphics: Missing implementation of the blocked method (*critical*, - Petteri Aimonen). - - * C Library: Floating point numbers in printf and related formatting functions - (Mike Smith), cf[get|set]speed() (Mike Smith) - -As well as other, less critical bugs (see the ChangeLog for details) diff --git a/nuttx/TODO b/nuttx/TODO index 28ffa1387f..906601192c 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -14,8 +14,8 @@ nuttx/ (2) C++ Support (6) Binary loaders (binfmt/) (17) Network (net/, drivers/net) - (4) USB (drivers/usbdev, drivers/usbhost) - (11) Libraries (libc/, ) + (3) USB (drivers/usbdev, drivers/usbhost) + (11) Libraries (lib/) (9) File system/Generic drivers (fs/, drivers/) (5) Graphics subystem (graphics/) (1) Pascal add-on (pcode/) @@ -32,7 +32,7 @@ nuttx/ (0) ARM/LPC43x (arch/arm/src/lpc43xx/) (3) ARM/STR71x (arch/arm/src/str71x/) (3) ARM/LM3S6918 (arch/arm/src/lm3s/) - (4) ARM/STM32 (arch/arm/src/stm32/) + (7) ARM/STM32 (arch/arm/src/stm32/) (3) AVR (arch/avr) (0) Intel x86 (arch/x86) (4) 8051 / MCS51 (arch/8051/) @@ -421,7 +421,7 @@ o Binary loaders (binfmt/) .word .LC3-(.LPIC4+4) .word .LC4-(.LPIC5+4) - This is good and bad. This is good because it means that .rodata.str1.1 can now + 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 @@ -629,13 +629,8 @@ o USB (drivers/usbdev, drivers/usbhost) CDC/ACM serial driver might need the line coding data (that data is not used currenly, but it might be). - Title: USB HUB SUPPORT - Description: Add support for USB hubs - Status: Open - Priority: Low/Unknown. This is a feature enhancement. - -o Libraries (libc/) - ^^^^^^^^^^^^^^^^^ +o Libraries (lib/) + ^^^^^^^^^^^^^^^^ Title: ENVIRON Description: The definition of environ in stdlib.h is bogus and will not @@ -648,7 +643,7 @@ o Libraries (libc/) Description: Need some minimal termios support... at a minimum, enough to switch between raw and "normal" modes to support behavior like that needed for readline(). - UPDATE: There is growing functionality in libc/termios/ and in the + UPDATE: There is growing functionality in lib/termios/ and in the ioctl methods of several MCU serial drivers (stm32, lpc43, lpc17, pic32). However, as phrased, this bug cannot yet be closed since this "growing functionality" does not address all termios.h @@ -713,7 +708,7 @@ o Libraries (libc/) Priority: Title: OLD dtoa NEEDS TO BE UPDATED - Description: This implementation of dtoa in libc/stdio is old and will not + Description: This implementation of dtoa in lib/stdio is old and will not work with some newer compilers. See http://patrakov.blogspot.com/2009/03/dont-use-old-dtoac.html Status: Open @@ -721,7 +716,7 @@ o Libraries (libc/) Title: SYSLOG INTEGRATION Description: There are the beginnings of some system logging capabilities (see - drivers/syslog, fs/fs_syslog.c, and libc/stdio/lib_librawprintf.c and + drivers/syslog, fs/fs_syslog.c, and lib/stdio/lib_librawprintf.c and lib_liblowprintf.c. For NuttX, SYSLOG is a concept and includes, extends, and replaces the legacy NuttX debug ouput. Some additional integration is required to formalized this. For example: @@ -958,7 +953,7 @@ o Build system built configuration, only the multiple user mode can be supported with the NX server residing inside of the kernel space. In this case, most of the user end functions in graphics/nxmu - must be moved to libc/nx and those functions must be built into + must be moved to lib/nx and those functions must be built into libuser.a to be linked with the user-space code. A similar issue exists in NSH that uses some internal OS interfaces that would not be available in a kernel build @@ -1349,6 +1344,11 @@ o ARM/LM3S6918 (arch/arm/src/lm3s/) o ARM/STM32 (arch/arm/src/stm32/) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + Title: NOR FLASH DRIVER + Description: NOR Flash driver with FTL layer to support a file system. + Status: Open + Priority: Low + Title: USBSERIAL ISSUES Description A USB device-side driver is in place but not well tested. At present, the apps/examples/usbserial test sometimes fails. The situation @@ -1371,6 +1371,11 @@ o ARM/STM32 (arch/arm/src/stm32/) Status: Open Priority: Medium-High + Title: FSMC EXTERNAL MEMORY UNTESTED + Description: FSMC external memory support is untested + Status: Open + Priority: Low + Title: DMA EXTENSIONS Description: DMA logic needs to be extended. DMA2, Channel 5, will not work because the DMA2 channels 4 & 5 share the same interrupt. @@ -1378,6 +1383,12 @@ o ARM/STM32 (arch/arm/src/stm32/) Priority: Low until someone needs DMA1, Channel 5 (ADC3, UART4_TX, TIM5_CH1, or TIM8_CH2). + Title: UNFINISHED DRIVERS + Description: The following drivers are incomplete: DAC. The following drivers + are untested: DMA on the F4, CAN. + Status: Open + Priority: Medium + Title: F4 SDIO MULTI-BLOCK TRANSFER FAILURES Description: If you use a large I/O buffer to access the file system, then the MMCSD driver will perform multiple block SD transfers. With DMA @@ -1401,15 +1412,13 @@ o ARM/STM32 (arch/arm/src/stm32/) Status: Open Priority: Low (I am not even sure if this is a problem yet). - Title: DMA FROM EXTERNAL, FSMC MEMORY - Description: I have seen a problem on F1 where all SDIO DMAs work exist for - write DMAs from FSMC memory (i.e., from FSMC memory to SDIO). - Read transfers work fine (SDIO to FSMC memory). The failure is - a data underrun error with zero bytes of data transferred. The - workaround for now is to use DMA buffers allocted from internal - SRAM. + Status: UNFINISHED STM32 F4 OTG FS HOST DRIVER + Description: A quick-n-dirty leverage of the the LPC17xx host driver was put into + the STM32 source to support development of the STM32 F4 OTG FS host + driver. It is non-functional and still waiting for STM32 F4 logic + to be added. Don't use it! Status: Open - Priority: Low + Priority: Low (unless you need a host driver). o AVR (arch/avr) ^^^^^^^^^^^^^^ diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig index eb3bfe85b3..2a7ea10b59 100644 --- a/nuttx/arch/arm/Kconfig +++ b/nuttx/arch/arm/Kconfig @@ -4,8 +4,6 @@ # if ARCH_ARM -comment "ARM Options" - choice prompt "ARM chip selection" default ARCH_CHIP_STM32 @@ -155,9 +153,6 @@ config ARCH_CHIP default "stm32" if ARCH_CHIP_STM32 default "str71x" if ARCH_CHIP_STR71X -config ARCH_HAVE_CMNVECTOR - bool - config ARMV7M_CMNVECTOR bool "Use common ARMv7-M vectors" default n @@ -244,18 +239,6 @@ config ARCH_CALIBRATION watch to measure the 100 second delay then adjust BOARD_LOOPSPERMSEC until the delay actually is 100 seconds. -config DEBUG_HARDFAULT - bool "Verbose Hard-Fault Debug" - default n - depends on DEBUG && (ARCH_CORTEXM3 || ARCH_CORTEXM4) - ---help--- - Enables verbose debug output when a hard fault is occurs. This verbose - output is sometimes helpful when debugging difficult hard fault problems, - but may be more than you typcially want to see. - -if ARCH_CORTEXM3 || ARCH_CORTEXM4 -source arch/arm/src/armv7-m/Kconfig -endif if ARCH_CHIP_C5471 source arch/arm/src/c5471/Kconfig endif diff --git a/nuttx/arch/arm/include/stm32/chip.h b/nuttx/arch/arm/include/stm32/chip.h index d34c2eb4f0..d01929e1ca 100644 --- a/nuttx/arch/arm/include/stm32/chip.h +++ b/nuttx/arch/arm/include/stm32/chip.h @@ -59,11 +59,12 @@ /* STM32 F100 Value Line ************************************************************/ #if defined(CONFIG_ARCH_CHIP_STM32F100C8) || defined(CONFIG_ARCH_CHIP_STM32F100CB) \ - || defined(CONFIG_ARCH_CHIP_STM32F100R8) || defined(CONFIG_ARCH_CHIP_STM32F100RB) + || defined(CONFIG_ARCH_CHIP_STM32F100R8) || defined(CONFIG_ARCH_CHIP_STM32F100RB) \ + || defined(CONFIG_ARCH_CHIP_STM32F100V8) || defined(CONFIG_ARCH_CHIP_STM32F100VB) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# define CONFIG_STM32_MEDIUMDENSITY 1 /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# define CONFIG_STM32_MEDIUMDENSITY 1 /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # define CONFIG_STM32_VALUELINE 1 /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -71,106 +72,11 @@ # define STM32_NFSMC 0 /* FSMC */ # define STM32_NATIM 1 /* One advanced timer TIM1 */ # define STM32_NGTIM 3 /* 16-bit general timers TIM2,3,4 with DMA */ -# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ -// TODO: there are also 3 additional timers (15-17) that don't fit any existing category -# define STM32_NDMA 1 /* DMA1 */ -# define STM32_NSPI 2 /* SPI1-2 */ -# define STM32_NI2S 0 /* No I2S */ -# define STM32_NUSART 3 /* USART1-3 */ -# define STM32_NI2C 2 /* I2C1-2 */ -# define STM32_NCAN 0 /* No CAN */ -# define STM32_NSDIO 0 /* No SDIO */ -# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */ -# define STM32_NGPIO 64 /* GPIOA-D */ -# define STM32_NADC 1 /* ADC1 */ -# define STM32_NDAC 2 /* DAC 1-2 */ -# define STM32_NCRC 1 /* CRC1 */ -# define STM32_NETHERNET 0 /* No ethernet */ -# define STM32_NRNG 0 /* No random number generator (RNG) */ -# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */ - -#elif defined(CONFIG_ARCH_CHIP_STM32F100V8) || defined(CONFIG_ARCH_CHIP_STM32F100VB) -# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# define CONFIG_STM32_MEDIUMDENSITY 1 /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ -# define CONFIG_STM32_VALUELINE 1 /* STM32F100x */ -# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ -# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ -# undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */ -# define STM32_NFSMC 0 /* FSMC */ -# define STM32_NATIM 1 /* One advanced timer TIM1 */ -# define STM32_NGTIM 3 /* 16-bit general timers TIM2,3,4 with DMA */ -# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ -// TODO: there are also 3 additional timers (15-17) that don't fit any existing category -# define STM32_NDMA 1 /* DMA1 */ -# define STM32_NSPI 2 /* SPI1-2 */ -# define STM32_NI2S 0 /* No I2S */ -# define STM32_NUSART 3 /* USART1-3 */ -# define STM32_NI2C 2 /* I2C1-2 */ -# define STM32_NCAN 0 /* No CAN */ -# define STM32_NSDIO 0 /* No SDIO */ -# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */ -# define STM32_NGPIO 80 /* GPIOA-E */ -# define STM32_NADC 1 /* ADC1 */ -# define STM32_NDAC 2 /* DAC 1-2 */ -# define STM32_NCRC 1 /* CRC1 */ -# define STM32_NETHERNET 0 /* No ethernet */ -# define STM32_NRNG 0 /* No random number generator (RNG) */ -# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */ - -/* STM32 F100 High-density value Line ************************************************************/ - -#elif defined(CONFIG_ARCH_CHIP_STM32F100RC) || defined(CONFIG_ARCH_CHIP_STM32F100RD) \ - || defined(CONFIG_ARCH_CHIP_STM32F100RE) -# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ -# define CONFIG_STM32_VALUELINE 1 /* STM32F100x */ -# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ -# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ -# undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */ -# define STM32_NFSMC 0 /* FSMC */ -# define STM32_NATIM 1 /* One advanced timer TIM1 */ -# define STM32_NGTIM 4 /* 16-bit general timers TIM2,3,4,5 with DMA */ -# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ -// TODO: there are also 6 additional timers (12-17) that don't fit any existing category +# define STM32_NBTIM 0 /* No basic timers */ # define STM32_NDMA 2 /* DMA1-2 */ -# define STM32_NSPI 3 /* SPI1-3 */ -# define STM32_NI2S 0 /* No I2S */ -# define STM32_NUSART 5 /* USART1-5 */ -# define STM32_NI2C 2 /* I2C1-2 */ -# define STM32_NCAN 0 /* No CAN */ -# define STM32_NSDIO 0 /* No SDIO */ -# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */ -# define STM32_NGPIO 64 /* GPIOA-D */ -# define STM32_NADC 1 /* ADC1 */ -# define STM32_NDAC 2 /* DAC 1-2 */ -# define STM32_NCRC 1 /* CRC1 */ -# define STM32_NETHERNET 0 /* No ethernet */ -# define STM32_NRNG 0 /* No random number generator (RNG) */ -# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */ - -#elif defined(CONFIG_ARCH_CHIP_STM32F100VC) || defined(CONFIG_ARCH_CHIP_STM32F100VD) \ - || defined(CONFIG_ARCH_CHIP_STM32F100VE) -# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ -# define CONFIG_STM32_VALUELINE 1 /* STM32F100x */ -# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ -# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ -# undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */ -# define STM32_NFSMC 1 /* FSMC */ -# define STM32_NATIM 1 /* One advanced timer TIM1 */ -# define STM32_NGTIM 4 /* 16-bit general timers TIM2,3,4,5 with DMA */ -# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ -// TODO: there are also 6 additional timers (12-17) that don't fit any existing category -# define STM32_NDMA 2 /* DMA1-2 */ -# define STM32_NSPI 3 /* SPI1-3 */ -# define STM32_NI2S 0 /* No I2S */ -# define STM32_NUSART 5 /* USART1-5 */ +# define STM32_NSPI 2 /* SPI1-2 */ +# define STM32_NI2S 0 /* No I2S (?) */ +# define STM32_NUSART 3 /* USART1-3 */ # define STM32_NI2C 2 /* I2C1-2 */ # define STM32_NCAN 0 /* No CAN */ # define STM32_NSDIO 0 /* No SDIO */ @@ -190,9 +96,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F103RET6) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -223,9 +129,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F103VCT6) || defined(CONFIG_ARCH_CHIP_STM32F103VET6) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -256,9 +162,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F103ZET6) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -286,9 +192,9 @@ /* STM32 F105/F107 Connectivity Line *******************************************************/ #elif defined(CONFIG_ARCH_CHIP_STM32F105VBT7) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # define CONFIG_STM32_CONNECTIVITYLINE 1 /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -315,9 +221,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F107VC) # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # define CONFIG_STM32_CONNECTIVITYLINE 1 /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -345,9 +251,9 @@ /* STM32 F2 Family ******************************************************************/ #elif defined(CONFIG_ARCH_CHIP_STM32F207IG) /* UFBGA-176 1024Kb FLASH 128Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # define CONFIG_STM32_STM32F20XX 1 /* STM32F205x and STM32F207x */ @@ -377,9 +283,9 @@ /* STM23 F4 Family ******************************************************************/ #elif defined(CONFIG_ARCH_CHIP_STM32F405RG) /* LQFP 64 10x10x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -408,9 +314,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F405VG) /* LQFP 100 14x14x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -439,9 +345,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F405ZG) /* LQFP 144 20x20x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -470,9 +376,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407VE) /* LQFP-100 512Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -501,9 +407,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407VG) /* LQFP-100 14x14x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -532,9 +438,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407ZE) /* LQFP-144 512Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -563,9 +469,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407ZG) /* LQFP 144 20x20x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -594,9 +500,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407IE) /* LQFP 176 24x24x1.4 512Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ @@ -625,9 +531,9 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F407IG) /* BGA 176; LQFP 176 24x24x1.4 1024Kb FLASH 192Kb SRAM */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ -# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ -# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ diff --git a/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h b/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h index 7c3f7cf958..67f4ba436b 100644 --- a/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h +++ b/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h @@ -61,13 +61,11 @@ * External interrupts (vectors >= 16) */ - /* Value line devices */ - -#if defined(CONFIG_STM32_VALUELINE) +#if defined(CONFIG_STM32_VALUELINE) && defined(CONFIG_STM32_MEDIUMDENSITY) # define STM32_IRQ_WWDG (16) /* 0: Window Watchdog interrupt */ # define STM32_IRQ_PVD (17) /* 1: PVD through EXTI Line detection interrupt */ # define STM32_IRQ_TAMPER (18) /* 2: Tamper interrupt */ -# define STM32_IRQ_RTC (19) /* 3: RTC Wakeup through EXTI line interrupt */ +# define STM32_IRQ_RTC (19) /* 3: RTC global interrupt */ # define STM32_IRQ_FLASH (20) /* 4: Flash global interrupt */ # define STM32_IRQ_RCC (21) /* 5: RCC global interrupt */ # define STM32_IRQ_EXTI0 (22) /* 6: EXTI Line 0 interrupt */ @@ -82,18 +80,12 @@ # define STM32_IRQ_DMA1CH5 (31) /* 15: DMA1 Channel 5 global interrupt */ # define STM32_IRQ_DMA1CH6 (32) /* 16: DMA1 Channel 6 global interrupt */ # define STM32_IRQ_DMA1CH7 (33) /* 17: DMA1 Channel 7 global interrupt */ -# define STM32_IRQ_ADC1 (34) /* 18: ADC1 global interrupt */ -# define STM32_IRQ_RESERVED0 (35) /* 19: Reserved 0 */ -# define STM32_IRQ_RESERVED1 (36) /* 20: Reserved 1 */ -# define STM32_IRQ_RESERVED2 (37) /* 21: Reserved 2 */ -# define STM32_IRQ_RESERVED3 (38) /* 22: Reserved 3 */ +# define STM32_IRQ_ADC12 (34) /* 18: ADC1 and ADC2 global interrupt */ + /* 19-22: reserved */ # define STM32_IRQ_EXTI95 (39) /* 23: EXTI Line[9:5] interrupts */ # define STM32_IRQ_TIM1BRK (40) /* 24: TIM1 Break interrupt */ -# define STM32_IRQ_TIM15 (40) /* TIM15 global interrupt */ -# define STM32_IRQ_TIM1UP (41) /* 25: TIM1 Update interrupt */ -# define STM32_IRQ_TIM16 (41) /* TIM16 global interrupt */ -# define STM32_IRQ_TIM1TRGCOM (42) /* 26: TIM1 Trigger and Commutation interrupts */ -# define STM32_IRQ_TIM17 (42) /* TIM17 global interrupt */ +# define STM32_IRQ_TIM1UP (41) /* 25: TIM1 Update interrupt (TIM16 global interrupt) */ +# define STM32_IRQ_TIM1TRGCOM (42) /* 26: TIM1 Trigger and Commutation interrupts (TIM17 global interrupt) */ # define STM32_IRQ_TIM1CC (43) /* 27: TIM1 Capture Compare interrupt */ # define STM32_IRQ_TIM2 (44) /* 28: TIM2 global interrupt */ # define STM32_IRQ_TIM3 (45) /* 29: TIM3 global interrupt */ @@ -108,30 +100,29 @@ # define STM32_IRQ_USART2 (54) /* 38: USART2 global interrupt */ # define STM32_IRQ_USART3 (55) /* 39: USART3 global interrupt */ # define STM32_IRQ_EXTI1510 (56) /* 40: EXTI Line[15:10] interrupts */ -# define STM32_IRQ_RTCALR (57) /* 41: RTC alarms (A and B) through EXTI line interrupt */ +# define STM32_IRQ_RTCALR (57) /* 41: RTC alarm through EXTI line interrupt */ # define STM32_IRQ_CEC (58) /* 42: CEC global interrupt */ -# define STM32_IRQ_TIM12 (59) /* 43: TIM12 global interrupt */ -# define STM32_IRQ_TIM13 (60) /* 44: TIM13 global interrupt */ -# define STM32_IRQ_TIM14 (61) /* 45: TIM14 global interrupt */ -# define STM32_IRQ_RESERVED4 (62) /* 46: Reserved 4 */ -# define STM32_IRQ_RESERVED5 (63) /* 47: Reserved 5 */ -# define STM32_IRQ_FSMC (64) /* 48: FSMC global interrupt */ -# define STM32_IRQ_RESERVED6 (65) /* 49: Reserved 6 */ -# define STM32_IRQ_TIM5 (66) /* 50: TIM5 global interrupt */ -# define STM32_IRQ_SPI3 (67) /* 51: SPI3 global interrupt */ -# define STM32_IRQ_UART4 (68) /* 52: USART2 global interrupt */ -# define STM32_IRQ_UART5 (69) /* 53: USART5 global interrupt */ +# if defined(CONFIG_STM32_HIGHDENSITY) +# define STM32_IRQ_TIM12 (59) /* 43: TIM12 global interrupt */ +# define STM32_IRQ_TIM13 (60) /* 44: TIM13 global interrupt */ +# define STM32_IRQ_TIM14 (61) /* 45: TIM14 global interrupt */ + /* 46-47: reserved */ +# define STM32_IRQ_FSMC (64) /* 48: FSMC global interrupt */ + /* 49: reserved */ +# define STM32_IRQ_TIM5 (66) /* 50: TIM5 global interrupt */ +# define STM32_IRQ_SPI3 (67) /* 51: SPI1 global interrupt */ +# define STM32_IRQ_UART4 (68) /* 52: USART2 global interrupt */ +# define STM32_IRQ_UART5 (69) /* 53: USART3 global interrupt */ +# else + /* 43-53: reserved */ +# endif # define STM32_IRQ_TIM6 (70) /* 54: TIM6 global interrupt */ # define STM32_IRQ_TIM7 (71) /* 55: TIM7 global interrupt */ # define STM32_IRQ_DMA2CH1 (72) /* 56: DMA2 Channel 1 global interrupt */ # define STM32_IRQ_DMA2CH2 (73) /* 57: DMA2 Channel 2 global interrupt */ # define STM32_IRQ_DMA2CH3 (74) /* 58: DMA2 Channel 3 global interrupt */ -# define STM32_IRQ_DMA2CH45 (75) /* 59: DMA2 Channel 4 and 5 global interrupt */ -# define STM32_IRQ_DMA2CH5 (76) /* 60: DMA2 Channel 5 global interrupt */ -# define NR_IRQS (77) - -/* Connectivity Line Devices */ - +# define STM32_IRQ_DMA2CH45 (75) /* 59: DMA2 Channel 4 global interrupt */ +# define NR_IRQS (76) #elif defined(CONFIG_STM32_CONNECTIVITYLINE) # define STM32_IRQ_WWDG (16) /* 0: Window Watchdog interrupt */ # define STM32_IRQ_PVD (17) /* 1: PVD through EXTI Line detection interrupt */ @@ -202,9 +193,6 @@ # define STM32_IRQ_CAN2SCE (82) /* 66: CAN2 SCE interrupt */ # define STM32_IRQ_OTGFS (83) /* 67: USB On The Go FS global interrupt */ # define NR_IRQS (84) - -/* Medium and High Density Devices */ - #else # define STM32_IRQ_WWDG (16) /* 0: Window Watchdog interrupt */ # define STM32_IRQ_PVD (17) /* 1: PVD through EXTI Line detection interrupt */ diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index e44def30c0..74be6c18d1 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -36,90 +36,58 @@ -include $(TOPDIR)/Make.defs -include chip/Make.defs +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(CONFIG_ARCH_CORTEXM3),y) # Cortex-M3 is ARMv7-M -ARCH_SUBDIR = armv7-m +ARCH_SUBDIR = armv7-m else ifeq ($(CONFIG_ARCH_CORTEXM4),y) # Cortex-M4 is ARMv7E-M -ARCH_SUBDIR = armv7-m +ARCH_SUBDIR = armv7-m else -ARCH_SUBDIR = arm +ARCH_SUBDIR = arm endif endif -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - ARCH_SRCDIR = $(TOPDIR)\arch\$(CONFIG_ARCH)\src - NUTTX = "$(TOPDIR)\nuttx$(EXEEXT)" - CFLAGS += -I$(ARCH_SRCDIR)\chip - CFLAGS += -I$(ARCH_SRCDIR)\common - CFLAGS += -I$(ARCH_SRCDIR)\$(ARCH_SUBDIR) - CFLAGS += -I$(TOPDIR)\sched -else - ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src -ifeq ($(WINTOOL),y) - NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx$(EXEEXT)}" - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" - CFLAGS += -I "${shell cygpath -w $(TOPDIR)/sched}" -else - NUTTX = "$(TOPDIR)/nuttx$(EXEEXT)" - CFLAGS += -I$(ARCH_SRCDIR)/chip - CFLAGS += -I$(ARCH_SRCDIR)/common - CFLAGS += -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) - CFLAGS += -I$(TOPDIR)/sched -endif -endif - -HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT)) - -ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS) -AOBJS = $(ASRCS:.S=$(OBJEXT)) - -CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS) -COBJS = $(CSRCS:.c=$(OBJEXT)) - -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) - -LDFLAGS += $(ARCHSCRIPT) - -EXTRA_LIBS ?= -EXTRA_LIBPATHS ?= -LINKLIBS ?= - -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BOARDMAKE = $(if $(wildcard .\board\Makefile),y,) - LIBPATHS += -L"$(TOPDIR)\lib" -ifeq ($(BOARDMAKE),y) - LIBPATHS += -L"$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board" -endif - -else - BOARDMAKE = $(if $(wildcard ./board/Makefile),y,) - ifeq ($(WINTOOL),y) - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}" -ifeq ($(BOARDMAKE),y) - LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}" -endif - + NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \ + -I "${shell cygpath -w $(TOPDIR)/sched}" else - LIBPATHS += -L"$(TOPDIR)/lib" -ifeq ($(BOARDMAKE),y) - LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board" -endif -endif + NUTTX = $(TOPDIR)/nuttx + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \ + -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched endif -LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS))) -ifeq ($(BOARDMAKE),y) - LDLIBS += -lboard +HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT)) + +ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS) +AOBJS = $(ASRCS:.S=$(OBJEXT)) + +CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS) +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +LDFLAGS = $(ARCHSCRIPT) +EXTRA_LIBS ?= + +LINKLIBS = +ifeq ($(WINTOOL),y) + LIBPATHS = ${shell for path in $(LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done} + LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}" +else + LIBPATHS = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS))) + LIBPATHS += -L"$(BOARDDIR)" endif +LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS)))) -LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}" -GCC_LIBDIR := ${shell dirname $(LIBGCC)} +BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board -VPATH = chip:common:$(ARCH_SUBDIR) +LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}" + +VPATH = chip:common:$(ARCH_SUBDIR) all: $(HEAD_OBJ) libarch$(LIBEXT) @@ -132,21 +100,20 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) libarch$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) board/libboard$(LIBEXT): - $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES) -nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT) - $(Q) echo "LD: nuttx" - $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) $(EXTRA_LIBPATHS) \ - -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ - --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group -ifneq ($(CONFIG_WINDOWS_NATIVE),y) - $(Q) $(NM) $(NUTTX)$(EXEEXT) | \ +nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT) + @echo "LD: nuttx" + @$(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \ + --start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group + @$(NM) $(NUTTX)$(EXEEXT) | \ grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \ sort > $(TOPDIR)/System.map -endif # This is part of the top-level export target # Note that there may not be a head object if layout is handled @@ -154,38 +121,37 @@ endif export_head: board/libboard$(LIBEXT) $(HEAD_OBJ) ifneq ($(HEAD_OBJ),) - $(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \ + @if [ -d "$(EXPORT_DIR)/startup" ]; then \ cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \ else \ echo "$(EXPORT_DIR)/startup does not exist"; \ - exit 1; \ - fi + exit 1; \ + fi endif # Dependencies .depend: Makefile chip/Make.defs $(SRCS) -ifeq ($(BOARDMAKE),y) - $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend -endif - $(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \ - "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @if [ -e board/Makefile ]; then \ + $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \ + fi + @$(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \ + $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: -ifeq ($(BOARDMAKE),y) - $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean -endif - $(call DELFILE, libarch$(LIBEXT)) + @if [ -e board/Makefile ]; then \ + $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ + fi + @rm -f libarch$(LIBEXT) *~ .*.swp $(call CLEAN) distclean: clean -ifeq ($(BOARDMAKE),y) - $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean -endif - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @if [ -e board/Makefile ]; then \ + $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \ + fi + @rm -f Make.dep .depend -include Make.dep diff --git a/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S b/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S old mode 100644 new mode 100755 diff --git a/nuttx/arch/arm/src/armv7-m/up_hardfault.c b/nuttx/arch/arm/src/armv7-m/up_hardfault.c index c30015ad22..cb3ce9e8a9 100644 --- a/nuttx/arch/arm/src/armv7-m/up_hardfault.c +++ b/nuttx/arch/arm/src/armv7-m/up_hardfault.c @@ -57,7 +57,9 @@ /* Debug output from this file may interfere with context switching! */ -#ifdef CONFIG_DEBUG_HARDFAULT +#undef DEBUG_HARDFAULTS /* Define to debug hard faults */ + +#ifdef DEBUG_HARDFAULTS # define hfdbg(format, arg...) lldbg(format, ##arg) #else # define hfdbg(x...) diff --git a/nuttx/arch/arm/src/armv7-m/up_saveusercontext.S b/nuttx/arch/arm/src/armv7-m/up_saveusercontext.S old mode 100644 new mode 100755 diff --git a/nuttx/arch/arm/src/armv7-m/up_switchcontext.S b/nuttx/arch/arm/src/armv7-m/up_switchcontext.S old mode 100644 new mode 100755 diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 2807e1a47a..2f91002360 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -34,27 +34,6 @@ config ARCH_CHIP_STM32F100RB select STM32_STM32F10XX select STM32_VALUELINE -config ARCH_CHIP_STM32F100RC - bool "STM32F100RC" - select ARCH_CORTEXM3 - select STM32_STM32F10XX - select STM32_VALUELINE - select STM32_HIGHDENSITY - -config ARCH_CHIP_STM32F100RD - bool "STM32F100RD" - select ARCH_CORTEXM3 - select STM32_STM32F10XX - select STM32_VALUELINE - select STM32_HIGHDENSITY - -config ARCH_CHIP_STM32F100RE - bool "STM32F100RE" - select ARCH_CORTEXM3 - select STM32_STM32F10XX - select STM32_VALUELINE - select STM32_HIGHDENSITY - config ARCH_CHIP_STM32F100V8 bool "STM32F100V8" select ARCH_CORTEXM3 @@ -67,27 +46,6 @@ config ARCH_CHIP_STM32F100VB select STM32_STM32F10XX select STM32_VALUELINE -config ARCH_CHIP_STM32F100VC - bool "STM32F100VC" - select ARCH_CORTEXM3 - select STM32_STM32F10XX - select STM32_VALUELINE - select STM32_HIGHDENSITY - -config ARCH_CHIP_STM32F100VD - bool "STM32F100VD" - select ARCH_CORTEXM3 - select STM32_STM32F10XX - select STM32_VALUELINE - select STM32_HIGHDENSITY - -config ARCH_CHIP_STM32F100VE - bool "STM32F100VE" - select ARCH_CORTEXM3 - select STM32_STM32F10XX - select STM32_VALUELINE - select STM32_HIGHDENSITY - config ARCH_CHIP_STM32F103RET6 bool "STM32F103RET6" select ARCH_CORTEXM3 @@ -150,7 +108,7 @@ config ARCH_CHIP_STM32F407VE config ARCH_CHIP_STM32F407VG bool "STM32F407VG" - select ARCH_CORTEXM4 + select ARCH_CORTEXM3 select STM32_STM32F40XX config ARCH_CHIP_STM32F407ZE @@ -193,10 +151,37 @@ config STM32_STM32F20XX config STM32_STM32F40XX bool +choice + prompt "Toolchain Selection" + default STM32_CODESOURCERYW + depends on ARCH_CHIP_STM32 + +config STM32_CODESOURCERYW + bool "CodeSourcery for Windows" + +config STM32_CODESOURCERYL + bool "CodeSourcery for Linux" + +config STM32_ATOLLIC_LITE + bool "Atollic Lite for Windows" + +config STM32_ATOLLIC_PRO + bool "Atollic Pro for Windows" + +config STM32_DEVKITARM + bool "DevkitARM (Windows)" + +config STM32_RAISONANCE + bool "STMicro Raisonance for Windows" + +config STM32_BUILDROOT + bool "NuttX buildroot (Cygwin or Linux)" + +endchoice + config STM32_DFU bool "DFU bootloader" default n - depends on !STM32_VALUELINE ---help--- Configure and position code for use with the STMicro DFU bootloader. Do not select this option if you will load code using JTAG/SWM. @@ -212,13 +197,25 @@ config STM32_ADC2 bool "ADC2" default n select STM32_ADC - depends on !STM32_VALUELINE config STM32_ADC3 bool "ADC3" default n select STM32_ADC - depends on !STM32_VALUELINE + +config STM32_CRC + bool "CRC" + default n + +config STM32_DMA1 + bool "DMA1" + default n + select ARCH_DMA + +config STM32_DMA2 + bool "DMA2" + default n + select ARCH_DMA config STM32_BKP bool "BKP" @@ -235,7 +232,6 @@ config STM32_CAN1 default n select CAN select STM32_CAN - depends on !STM32_VALUELINE config STM32_CAN2 bool "CAN2" @@ -249,31 +245,11 @@ config STM32_CCMDATARAM default n depends on STM32_STM32F40XX -config STM32_CEC - bool "CEC" - default n - depends on STM32_VALUELINE - -config STM32_CRC - bool "CRC" - default n - config STM32_CRYP bool "CRYP" default n depends on STM32_STM32F20XX || STM32_STM32F40XX -config STM32_DMA1 - bool "DMA1" - default n - select ARCH_DMA - -config STM32_DMA2 - bool "DMA2" - default n - select ARCH_DMA - depends on !STM32_VALUELINE || (STM32_VALUELINE && STM32_HIGHDENSITY) - config STM32_DAC1 bool "DAC1" default n @@ -298,7 +274,7 @@ config STM32_ETHMAC config STM32_FSMC bool "FSMC" default n - depends on !STM32_CONNECTIVITYLINE && (STM32_HIGHDENSITY || STM32_STM32F20XX || STM32_STM32F40XX) + depends on !STM32_CONNECTIVITYLINE config STM32_HASH bool "HASH" @@ -349,7 +325,7 @@ config STM32_RNG config STM32_SDIO bool "SDIO" default n - depends on !STM32_CONNECTIVITYLINE && !STM32_VALUELINE + depends on !STM32_CONNECTIVITYLINE config STM32_SPI1 bool "SPI1" @@ -366,7 +342,7 @@ config STM32_SPI2 config STM32_SPI3 bool "SPI3" default n - depends on STM32_CONNECTIVITYLINE || STM32_STM32F20XX || STM32_STM32F40XX || (STM32_VALUELINE && STM32_HIGHDENSITY) + depends on STM32_CONNECTIVITYLINE || STM32_STM32F20XX || STM32_STM32F40XX select SPI select STM32_SPI @@ -406,7 +382,6 @@ config STM32_TIM7 config STM32_TIM8 bool "TIM8" default n - depends on !STM32_VALUELINE config STM32_TIM9 bool "TIM9" @@ -426,32 +401,17 @@ config STM32_TIM11 config STM32_TIM12 bool "TIM12" default n - depends on STM32_STM32F20XX || STM32_STM32F40XX || STM32_VALUELINE + depends on STM32_STM32F20XX || STM32_STM32F40XX config STM32_TIM13 bool "TIM13" default n - depends on STM32_STM32F20XX || STM32_STM32F40XX || STM32_VALUELINE + depends on STM32_STM32F20XX || STM32_STM32F40XX config STM32_TIM14 bool "TIM14" default n - depends on STM32_STM32F20XX || STM32_STM32F40XX || STM32_VALUELINE - -config STM32_TIM15 - bool "TIM15" - default n - depends on STM32_VALUELINE - -config STM32_TIM16 - bool "TIM16" - default n - depends on STM32_VALUELINE - -config STM32_TIM17 - bool "TIM17" - default n - depends on STM32_VALUELINE + depends on STM32_STM32F20XX || STM32_STM32F40XX config STM32_USART1 bool "USART1" @@ -487,7 +447,7 @@ config STM32_USART6 config STM32_USB bool "USB Device" default n - depends on STM32_STM32F10XX && !STM32_VALUELINE + depends on STM32_STM32F10XX select USBDEV config STM32_WWDG @@ -514,52 +474,6 @@ config STM32_CAN menu "Alternate Pin Mapping" -choice - prompt "CAN1 Alternate Pin Mappings" - depends on STM32_STM32F10XX && STM32_CAN1 - default STM32_CAN1_NO_REMAP - -config STM32_CAN1_NO_REMAP - bool "No pin remapping" - -config STM32_CAN1_REMAP1 - bool "CAN1 alternate pin remapping #1" - -config STM32_CAN1_REMAP2 - bool "CAN1 alternate pin remapping #2" - -endchoice - -config STM32_CAN2_REMAP - bool "CAN2 Alternate Pin Mapping" - default n - depends on STM32_CONNECTIVITYLINE && STM32_CAN2 - -config STM32_CEC_REMAP - bool "CEC Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_CEC - -config STM32_ETH_REMAP - bool "Ethernet Alternate Pin Mapping" - default n - depends on STM32_CONNECTIVITYLINE && STM32_ETHMAC - -config STM32_I2C1_REMAP - bool "I2C1 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_I2C1 - -config STM32_SPI1_REMAP - bool "SPI1 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_SPI1 - -config STM32_SPI3_REMAP - bool "SPI3 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_SPI3 && !STM32_VALUELINE - choice prompt "TIM1 Alternate Pin Mappings" depends on STM32_STM32F10XX && STM32_TIM1 @@ -616,51 +530,6 @@ config STM32_TIM4_REMAP default n depends on STM32_STM32F10XX && STM32_TIM4 -config STM32_TIM9_REMAP - bool "TIM9 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_TIM9 - -config STM32_TIM10_REMAP - bool "TIM10 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_TIM10 - -config STM32_TIM11_REMAP - bool "TIM11 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_TIM11 - -config STM32_TIM12_REMAP - bool "TIM12 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_TIM12 - -config STM32_TIM13_REMAP - bool "TIM13 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_TIM13 - -config STM32_TIM14_REMAP - bool "TIM14 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_TIM14 - -config STM32_TIM15_REMAP - bool "TIM15 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_TIM15 - -config STM32_TIM16_REMAP - bool "TIM16 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_TIM16 - -config STM32_TIM17_REMAP - bool "TIM17 Alternate Pin Mapping" - default n - depends on STM32_STM32F10XX && STM32_TIM17 - config STM32_USART1_REMAP bool "USART1 Alternate Pin Mapping" default n @@ -687,6 +556,47 @@ config STM32_USART3_PARTIAL_REMAP endchoice +config STM32_SPI1_REMAP + bool "SPI1 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_SPI1 + +config STM32_SPI3_REMAP + bool "SPI3 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_SPI3 + +config STM32_I2C1_REMAP + bool "I2C1 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_I2C1 + +choice + prompt "CAN1 Alternate Pin Mappings" + depends on STM32_STM32F10XX && STM32_CAN1 + default STM32_CAN1_NO_REMAP + +config STM32_CAN1_NO_REMAP + bool "No pin remapping" + +config STM32_CAN1_REMAP1 + bool "CAN1 alternate pin remapping #1" + +config STM32_CAN1_REMAP2 + bool "CAN1 alternate pin remapping #2" + +endchoice + +config STM32_CAN2_REMAP + bool "CAN2 Alternate Pin Mapping" + default n + depends on STM32_CONNECTIVITYLINE && STM32_CAN2 + +config STM32_ETH_REMAP + bool "Ethernet Alternate Pin Mapping" + default n + depends on STM32_CONNECTIVITYLINE && STM32_ETHMAC + endmenu choice @@ -726,11 +636,9 @@ config ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG config STM32_CCMEXCLUDE bool "Exclude CCM SRAM from the heap" depends on STM32_STM32F20XX || STM32_STM32F40XX - default y if ARCH_DMA || ELF + default y if ARCH_DMA ---help--- - Exclude CCM SRAM from the HEAP because (1) it cannot be used for DMA - and (2) it appears to be impossible to execute ELF modules from CCM - RAM. + Exclude CCM SRAM from the HEAP because it cannot be used for DMA. config STM32_FSMC_SRAM bool "External SRAM on FSMC" @@ -755,7 +663,6 @@ config STM32_TIM1_PWM config STM32_TIM1_CHANNEL int "TIM1 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM1_PWM ---help--- If TIM1 is enabled for PWM usage, you also need specifies the timer output @@ -766,7 +673,7 @@ config STM32_TIM2_PWM default n depends on STM32_TIM2 ---help--- - Reserve timer 2 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM2 @@ -776,7 +683,6 @@ config STM32_TIM2_PWM config STM32_TIM2_CHANNEL int "TIM2 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM2_PWM ---help--- If TIM2 is enabled for PWM usage, you also need specifies the timer output @@ -787,7 +693,7 @@ config STM32_TIM3_PWM default n depends on STM32_TIM3 ---help--- - Reserve timer 3 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM3 @@ -797,7 +703,6 @@ config STM32_TIM3_PWM config STM32_TIM3_CHANNEL int "TIM3 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM3_PWM ---help--- If TIM3 is enabled for PWM usage, you also need specifies the timer output @@ -808,7 +713,7 @@ config STM32_TIM4_PWM default n depends on STM32_TIM4 ---help--- - Reserve timer 4 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM4 @@ -818,7 +723,6 @@ config STM32_TIM4_PWM config STM32_TIM4_CHANNEL int "TIM4 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM4_PWM ---help--- If TIM4 is enabled for PWM usage, you also need specifies the timer output @@ -829,7 +733,7 @@ config STM32_TIM5_PWM default n depends on STM32_TIM5 ---help--- - Reserve timer 5 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM5 @@ -839,7 +743,6 @@ config STM32_TIM5_PWM config STM32_TIM5_CHANNEL int "TIM5 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM5_PWM ---help--- If TIM5 is enabled for PWM usage, you also need specifies the timer output @@ -850,7 +753,7 @@ config STM32_TIM8_PWM default n depends on STM32_TIM8 ---help--- - Reserve timer 8 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM8 @@ -860,7 +763,6 @@ config STM32_TIM8_PWM config STM32_TIM8_CHANNEL int "TIM8 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM8_PWM ---help--- If TIM8 is enabled for PWM usage, you also need specifies the timer output @@ -871,7 +773,7 @@ config STM32_TIM9_PWM default n depends on STM32_TIM9 ---help--- - Reserve timer 9 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM9 @@ -881,7 +783,6 @@ config STM32_TIM9_PWM config STM32_TIM9_CHANNEL int "TIM9 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM9_PWM ---help--- If TIM9 is enabled for PWM usage, you also need specifies the timer output @@ -892,7 +793,7 @@ config STM32_TIM10_PWM default n depends on STM32_TIM10 ---help--- - Reserve timer 10 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM10 @@ -902,7 +803,6 @@ config STM32_TIM10_PWM config STM32_TIM10_CHANNEL int "TIM10 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM10_PWM ---help--- If TIM10 is enabled for PWM usage, you also need specifies the timer output @@ -913,7 +813,7 @@ config STM32_TIM11_PWM default n depends on STM32_TIM11 ---help--- - Reserve timer 11 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM11 @@ -923,7 +823,6 @@ config STM32_TIM11_PWM config STM32_TIM11_CHANNEL int "TIM11 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM11_PWM ---help--- If TIM11 is enabled for PWM usage, you also need specifies the timer output @@ -934,7 +833,7 @@ config STM32_TIM12_PWM default n depends on STM32_TIM12 ---help--- - Reserve timer 12 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM12 @@ -944,7 +843,6 @@ config STM32_TIM12_PWM config STM32_TIM12_CHANNEL int "TIM12 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM12_PWM ---help--- If TIM12 is enabled for PWM usage, you also need specifies the timer output @@ -955,7 +853,7 @@ config STM32_TIM13_PWM default n depends on STM32_TIM13 ---help--- - Reserve timer 13 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM13 @@ -965,7 +863,6 @@ config STM32_TIM13_PWM config STM32_TIM13_CHANNEL int "TIM13 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM13_PWM ---help--- If TIM13 is enabled for PWM usage, you also need specifies the timer output @@ -976,7 +873,7 @@ config STM32_TIM14_PWM default n depends on STM32_TIM14 ---help--- - Reserve timer 14 for use by PWM + Reserve timer 1 for use by PWM Timer devices may be used for different purposes. One special purpose is to generate modulated outputs for such things as motor control. If STM32_TIM14 @@ -986,75 +883,11 @@ config STM32_TIM14_PWM config STM32_TIM14_CHANNEL int "TIM14 PWM Output Channel" default 1 - range 1 4 depends on STM32_TIM14_PWM ---help--- If TIM14 is enabled for PWM usage, you also need specifies the timer output channel {1,..,4} -config STM32_TIM15_PWM - bool "TIM15 PWM" - default n - depends on STM32_TIM15 - ---help--- - Reserve timer 15 for use by PWM - - Timer devices may be used for different purposes. One special purpose is - to generate modulated outputs for such things as motor control. If STM32_TIM15 - is defined then THIS following may also be defined to indicate that - the timer is intended to be used for pulsed output modulation. - -config STM32_TIM15_CHANNEL - int "TIM15 PWM Output Channel" - default 1 - range 1 2 - depends on STM32_TIM15_PWM - ---help--- - If TIM15 is enabled for PWM usage, you also need specifies the timer output - channel {1,2} - -config STM32_TIM16_PWM - bool "TIM16 PWM" - default n - depends on STM32_TIM16 - ---help--- - Reserve timer 16 for use by PWM - - Timer devices may be used for different purposes. One special purpose is - to generate modulated outputs for such things as motor control. If STM32_TIM16 - is defined then THIS following may also be defined to indicate that - the timer is intended to be used for pulsed output modulation. - -config STM32_TIM16_CHANNEL - int "TIM16 PWM Output Channel" - default 1 - range 1 1 - depends on STM32_TIM16_PWM - ---help--- - If TIM16 is enabled for PWM usage, you also need specifies the timer output - channel {1} - -config STM32_TIM17_PWM - bool "TIM17 PWM" - default n - depends on STM32_TIM17 - ---help--- - Reserve timer 17 for use by PWM - - Timer devices may be used for different purposes. One special purpose is - to generate modulated outputs for such things as motor control. If STM32_TIM17 - is defined then THIS following may also be defined to indicate that - the timer is intended to be used for pulsed output modulation. - -config STM32_TIM17_CHANNEL - int "TIM17 PWM Output Channel" - default 1 - range 1 1 - depends on STM32_TIM17_PWM - ---help--- - If TIM17 is enabled for PWM usage, you also need specifies the timer output - channel {1} - config STM32_TIM1_ADC bool "TIM1 ADC" default n @@ -1076,22 +909,16 @@ choice config STM32_TIM1_ADC1 bool "TIM1 ADC channel 1" - depends on STM32_ADC1 - select HAVE_ADC1_TIMER ---help--- Reserve TIM1 to trigger ADC1 config STM32_TIM1_ADC2 bool "TIM1 ADC channel 2" - depends on STM32_ADC2 - select HAVE_ADC2_TIMER ---help--- Reserve TIM1 to trigger ADC2 config STM32_TIM1_ADC3 bool "TIM1 ADC channel 3" - depends on STM32_ADC3 - select HAVE_ADC3_TIMER ---help--- Reserve TIM1 to trigger ADC3 @@ -1118,22 +945,16 @@ choice config STM32_TIM2_ADC1 bool "TIM2 ADC channel 1" - depends on STM32_ADC1 - select HAVE_ADC1_TIMER ---help--- Reserve TIM2 to trigger ADC1 config STM32_TIM2_ADC2 bool "TIM2 ADC channel 2" - depends on STM32_ADC2 - select HAVE_ADC2_TIMER ---help--- Reserve TIM2 to trigger ADC2 config STM32_TIM2_ADC3 bool "TIM2 ADC channel 3" - depends on STM32_ADC3 - select HAVE_ADC3_TIMER ---help--- Reserve TIM2 to trigger ADC3 @@ -1160,22 +981,16 @@ choice config STM32_TIM3_ADC1 bool "TIM3 ADC channel 1" - depends on STM32_ADC1 - select HAVE_ADC1_TIMER ---help--- Reserve TIM3 to trigger ADC1 config STM32_TIM3_ADC2 bool "TIM3 ADC channel 2" - depends on STM32_ADC2 - select HAVE_ADC2_TIMER ---help--- Reserve TIM3 to trigger ADC2 config STM32_TIM3_ADC3 bool "TIM3 ADC channel 3" - depends on STM32_ADC3 - select HAVE_ADC3_TIMER ---help--- Reserve TIM3 to trigger ADC3 @@ -1202,22 +1017,16 @@ choice config STM32_TIM4_ADC1 bool "TIM4 ADC channel 1" - depends on STM32_ADC1 - select HAVE_ADC1_TIMER ---help--- Reserve TIM4 to trigger ADC1 config STM32_TIM4_ADC2 bool "TIM4 ADC channel 2" - depends on STM32_ADC2 - select HAVE_ADC2_TIMER ---help--- Reserve TIM4 to trigger ADC2 config STM32_TIM4_ADC3 bool "TIM4 ADC channel 3" - depends on STM32_ADC3 - select HAVE_ADC3_TIMER ---help--- Reserve TIM4 to trigger ADC3 @@ -1244,22 +1053,16 @@ choice config STM32_TIM5_ADC1 bool "TIM5 ADC channel 1" - depends on STM32_ADC1 - select HAVE_ADC1_TIMER ---help--- Reserve TIM5 to trigger ADC1 config STM32_TIM5_ADC2 bool "TIM5 ADC channel 2" - depends on STM32_ADC2 - select HAVE_ADC2_TIMER ---help--- Reserve TIM5 to trigger ADC2 config STM32_TIM5_ADC3 bool "TIM5 ADC channel 3" - depends on STM32_ADC3 - select HAVE_ADC3_TIMER ---help--- Reserve TIM5 to trigger ADC3 @@ -1286,81 +1089,21 @@ choice config STM32_TIM8_ADC1 bool "TIM8 ADC channel 1" - depends on STM32_ADC1 - select HAVE_ADC1_TIMER ---help--- Reserve TIM8 to trigger ADC1 config STM32_TIM8_ADC2 bool "TIM8 ADC channel 2" - depends on STM32_ADC2 - select HAVE_ADC2_TIMER ---help--- Reserve TIM8 to trigger ADC2 config STM32_TIM8_ADC3 bool "TIM8 ADC channel 3" - depends on STM32_ADC3 - select HAVE_ADC3_TIMER ---help--- Reserve TIM8 to trigger ADC3 endchoice -config HAVE_ADC1_TIMER - bool - -config HAVE_ADC2_TIMER - bool - -config HAVE_ADC3_TIMER - bool - -config STM32_ADC1_SAMPLE_FREQUENCY - int "ADC1 Sampling Frequency" - default 100 - depends on HAVE_ADC1_TIMER - ---help--- - ADC1 sampling frequency. Default: 100Hz - -config STM32_ADC1_TIMTRIG - int "ADC1 Timer Trigger" - default 0 - range 0 4 - depends on HAVE_ADC1_TIMER - ---help--- - Values 0:CC1 1:CC2 2:CC3 3:CC4 4:TRGO - -config STM32_ADC2_SAMPLE_FREQUENCY - int "ADC2 Sampling Frequency" - default 100 - depends on HAVE_ADC2_TIMER - ---help--- - ADC2 sampling frequency. Default: 100Hz - -config STM32_ADC2_TIMTRIG - int "ADC2 Timer Trigger" - default 0 - range 0 4 - depends on HAVE_ADC2_TIMER - ---help--- - Values 0:CC1 1:CC2 2:CC3 3:CC4 4:TRGO - -config STM32_ADC3_SAMPLE_FREQUENCY - int "ADC3 Sampling Frequency" - default 100 - depends on HAVE_ADC3_TIMER - ---help--- - ADC3 sampling frequency. Default: 100Hz - -config STM32_ADC3_TIMTRIG - int "ADC3 Timer Trigger" - default 0 - range 0 4 - depends on HAVE_ADC3_TIMER - ---help--- - Values 0:CC1 1:CC2 2:CC3 3:CC4 4:TRGO - config STM32_TIM1_DAC bool "TIM1 DAC" default n @@ -1397,7 +1140,7 @@ config STM32_TIM2_DAC default n depends on STM32_TIM2 && STM32_DAC ---help--- - Reserve timer 2 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM2 is defined then the following may also be defined to indicate that the @@ -1428,7 +1171,7 @@ config STM32_TIM3_DAC default n depends on STM32_TIM3 && STM32_DAC ---help--- - Reserve timer 3 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM3 is defined then the following may also be defined to indicate that the @@ -1459,7 +1202,7 @@ config STM32_TIM4_DAC default n depends on STM32_TIM4 && STM32_DAC ---help--- - Reserve timer 4 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM4 is defined then the following may also be defined to indicate that the @@ -1490,7 +1233,7 @@ config STM32_TIM5_DAC default n depends on STM32_TIM5 && STM32_DAC ---help--- - Reserve timer 5 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM5 is defined then the following may also be defined to indicate that the @@ -1521,7 +1264,7 @@ config STM32_TIM6_DAC default n depends on STM32_TIM6 && STM32_DAC ---help--- - Reserve timer 6 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM6 is defined then the following may also be defined to indicate that the @@ -1552,7 +1295,7 @@ config STM32_TIM7_DAC default n depends on STM32_TIM7 && STM32_DAC ---help--- - Reserve timer 7 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM7 is defined then the following may also be defined to indicate that the @@ -1583,7 +1326,7 @@ config STM32_TIM8_DAC default n depends on STM32_TIM8 && STM32_DAC ---help--- - Reserve timer 8 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM8 is defined then the following may also be defined to indicate that the @@ -1614,7 +1357,7 @@ config STM32_TIM9_DAC default n depends on STM32_TIM9 && STM32_DAC ---help--- - Reserve timer 9 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM9 is defined then the following may also be defined to indicate that the @@ -1645,7 +1388,7 @@ config STM32_TIM10_DAC default n depends on STM32_TIM10 && STM32_DAC ---help--- - Reserve timer 10 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM10 is defined then the following may also be defined to indicate that the @@ -1676,7 +1419,7 @@ config STM32_TIM11_DAC default n depends on STM32_TIM11 && STM32_DAC ---help--- - Reserve timer 11 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM11 is defined then the following may also be defined to indicate that the @@ -1707,7 +1450,7 @@ config STM32_TIM12_DAC default n depends on STM32_TIM12 && STM32_DAC ---help--- - Reserve timer 12 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM12 is defined then the following may also be defined to indicate that the @@ -1738,7 +1481,7 @@ config STM32_TIM13_DAC default n depends on STM32_TIM13 && STM32_DAC ---help--- - Reserve timer 13 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM13 is defined then the following may also be defined to indicate that the @@ -1769,7 +1512,7 @@ config STM32_TIM14_DAC default n depends on STM32_TIM14 && STM32_DAC ---help--- - Reserve timer 14 for use by DAC + Reserve timer 1 for use by DAC Timer devices may be used for different purposes. If STM32_TIM14 is defined then the following may also be defined to indicate that the @@ -1795,27 +1538,6 @@ config STM32_TIM14_DAC2 endchoice -menu "U[S]ART Configuration" - depends on STM32_USART1 || STM32_USART2 || STM32_USART3 || STM32_USART4 || STM32_USART5 || STM32_USART6 - -config USART1_RS485 - bool "RS-485 on USART1" - default n - depends on STM32_USART1 - ---help--- - Enable RS-485 interface on USART1. Your board config will have to - provide GPIO_USART1_RS485_DIR pin definition. Currently it cannot be - used with USART1_RXDMA. - -config USART1_RS485_DIR_POLARITY - int "USART1 RS-485 DIR pin polarity" - default 1 - range 0 1 - depends on USART1_RS485 - ---help--- - Polarity of DIR pin for RS-485 on USART1. Set to state on DIR pin which - enables TX (0 - low / nTXEN, 1 - high / TXEN). - config USART1_RXDMA bool "USART1 Rx DMA" default n @@ -1823,24 +1545,6 @@ config USART1_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors -config USART2_RS485 - bool "RS-485 on USART2" - default n - depends on STM32_USART2 - ---help--- - Enable RS-485 interface on USART2. Your board config will have to - provide GPIO_USART2_RS485_DIR pin definition. Currently it cannot be - used with USART2_RXDMA. - -config USART2_RS485_DIR_POLARITY - int "USART2 RS-485 DIR pin polarity" - default 1 - range 0 1 - depends on USART2_RS485 - ---help--- - Polarity of DIR pin for RS-485 on USART2. Set to state on DIR pin which - enables TX (0 - low / nTXEN, 1 - high / TXEN). - config USART2_RXDMA bool "USART2 Rx DMA" default n @@ -1848,24 +1552,6 @@ config USART2_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors -config USART3_RS485 - bool "RS-485 on USART3" - default n - depends on STM32_USART3 - ---help--- - Enable RS-485 interface on USART3. Your board config will have to - provide GPIO_USART3_RS485_DIR pin definition. Currently it cannot be - used with USART3_RXDMA. - -config USART3_RS485_DIR_POLARITY - int "USART3 RS-485 DIR pin polarity" - default 1 - range 0 1 - depends on USART3_RS485 - ---help--- - Polarity of DIR pin for RS-485 on USART3. Set to state on DIR pin which - enables TX (0 - low / nTXEN, 1 - high / TXEN). - config USART3_RXDMA bool "USART3 Rx DMA" default n @@ -1873,24 +1559,6 @@ config USART3_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors -config UART4_RS485 - bool "RS-485 on UART4" - default n - depends on STM32_UART4 - ---help--- - Enable RS-485 interface on UART4. Your board config will have to - provide GPIO_UART4_RS485_DIR pin definition. Currently it cannot be - used with UART4_RXDMA. - -config UART4_RS485_DIR_POLARITY - int "UART4 RS-485 DIR pin polarity" - default 1 - range 0 1 - depends on UART4_RS485 - ---help--- - Polarity of DIR pin for RS-485 on UART4. Set to state on DIR pin which - enables TX (0 - low / nTXEN, 1 - high / TXEN). - config UART4_RXDMA bool "UART4 Rx DMA" default n @@ -1898,24 +1566,6 @@ config UART4_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors -config UART5_RS485 - bool "RS-485 on UART5" - default n - depends on STM32_UART5 - ---help--- - Enable RS-485 interface on UART5. Your board config will have to - provide GPIO_UART5_RS485_DIR pin definition. Currently it cannot be - used with UART5_RXDMA. - -config UART5_RS485_DIR_POLARITY - int "UART5 RS-485 DIR pin polarity" - default 1 - range 0 1 - depends on UART5_RS485 - ---help--- - Polarity of DIR pin for RS-485 on UART5. Set to state on DIR pin which - enables TX (0 - low / nTXEN, 1 - high / TXEN). - config UART5_RXDMA bool "UART5 Rx DMA" default n @@ -1923,24 +1573,6 @@ config UART5_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors -config USART6_RS485 - bool "RS-485 on USART6" - default n - depends on STM32_USART6 - ---help--- - Enable RS-485 interface on USART6. Your board config will have to - provide GPIO_USART6_RS485_DIR pin definition. Currently it cannot be - used with USART6_RXDMA. - -config USART6_RS485_DIR_POLARITY - int "USART6 RS-485 DIR pin polarity" - default 1 - range 0 1 - depends on USART6_RS485 - ---help--- - Polarity of DIR pin for RS-485 on USART6. Set to state on DIR pin which - enables TX (0 - low / nTXEN, 1 - high / TXEN). - config USART6_RXDMA bool "USART6 Rx DMA" default n @@ -1957,8 +1589,6 @@ config SERIAL_TERMIOS If this is not defined, then the terminal settings (baud, parity, etc). are not configurable at runtime; serial streams cannot be flushed, etc.. -endmenu - menu "SPI Configuration" depends on STM32_SPI @@ -2058,16 +1688,6 @@ config STM32_PHYADDR ---help--- The 5-bit address of the PHY on the board. Default: 1 -config STM32_PHYINIT - bool "Board-specific PHY Initialization" - default n - ---help--- - Some boards require specialized initialization of the PHY before it can be used. - This may include such things as configuring GPIOs, resetting the PHY, etc. If - STM32_PHYINIT is defined in the configuration then the board specific logic must - provide stm32_phyinitialize(); The STM32 Ethernet driver will call this function - one time before it first uses the PHY. - config STM32_MII bool "Use MII interface" default n @@ -2279,14 +1899,14 @@ config STM32_OTGFS_NPTXFIFO_SIZE depends on USBHOST && STM32_OTGFS ---help--- Size of the non-periodic Tx FIFO in 32-bit words. Default 96 (384 bytes) - + config STM32_OTGFS_PTXFIFO_SIZE int "Periodic Tx FIFO size" default 128 depends on USBHOST && STM32_OTGFS ---help--- Size of the periodic Tx FIFO in 32-bit words. Default 96 (384 bytes) - + config STM32_OTGFS_DESCSIZE int "Descriptor Size" default 128 @@ -2300,14 +1920,14 @@ config STM32_OTGFS_SOFINTR depends on USBHOST && STM32_OTGFS ---help--- Enable SOF interrupts. Why would you ever want to do that? - + config STM32_USBHOST_REGDEBUG bool "Register-Level Debug" default n depends on USBHOST && STM32_OTGFS ---help--- Enable very low-level register access debug. Depends on DEBUG. - + config STM32_USBHOST_PKTDUMP bool "Packet Dump Debug" default n diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs index 5776f5357c..54067a1687 100644 --- a/nuttx/arch/arm/src/stm32/Make.defs +++ b/nuttx/arch/arm/src/stm32/Make.defs @@ -41,31 +41,23 @@ endif CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \ - up_createstack.c up_mdelay.c up_udelay.c up_exit.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_systemreset.c \ - up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c up_svcall.c \ - up_stackcheck.c + up_createstack.c up_mdelay.c up_udelay.c up_exit.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_systemreset.c \ + up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c up_svcall.c \ + up_stackcheck.c ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y) CMN_ASRCS += up_exception.S CMN_CSRCS += up_vectors.c endif -ifeq ($(CONFIG_ARCH_MEMCPY),y) -CMN_ASRCS += up_memcpy.S -endif - ifeq ($(CONFIG_DEBUG_STACK),y) CMN_CSRCS += up_checkstack.c endif -ifeq ($(CONFIG_ELF),y) -CMN_CSRCS += up_elf.c -endif - ifeq ($(CONFIG_ARCH_FPU),y) CMN_ASRCS += up_fpu.S endif @@ -76,9 +68,9 @@ endif CHIP_ASRCS = CHIP_CSRCS = stm32_allocateheap.c stm32_start.c stm32_rcc.c stm32_lse.c \ - stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c stm32_irq.c \ - stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c \ - stm32_spi.c stm32_sdio.c stm32_tim.c stm32_i2c.c stm32_waste.c + stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c stm32_irq.c \ + stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c \ + stm32_spi.c stm32_sdio.c stm32_tim.c stm32_i2c.c stm32_waste.c ifeq ($(CONFIG_USBDEV),y) ifeq ($(CONFIG_STM32_USB),y) diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_eth.h b/nuttx/arch/arm/src/stm32/chip/stm32_eth.h index 92a229cccd..a4a109d016 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32_eth.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32_eth.h @@ -835,6 +835,14 @@ struct eth_rxdesc_s * Public Functions ****************************************************************************************************/ +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + #endif /* __ASSEMBLY__ */ #endif /* STM32_NETHERNET > 0 */ #endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32_ETH_H */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h index addef02656..01d6e1ce06 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h @@ -6,8 +6,6 @@ * Copyright (C) 2012 Michael Smith. All Rights reserved. * Author: Gregory Nutt * Uros Platise - * Michael Smith - * Freddie Chopin * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -51,87 +49,6 @@ * Pre-processor Definitions ************************************************************************************/ -/* Alternate Pin Functions: */ - -/* ADC */ - -#define GPIO_ADC1_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -#define GPIO_ADC1_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) -#define GPIO_ADC1_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -#define GPIO_ADC1_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -#define GPIO_ADC1_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) -#define GPIO_ADC1_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) -#define GPIO_ADC1_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) -#define GPIO_ADC1_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) -#define GPIO_ADC1_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) -#define GPIO_ADC1_IN9 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) -#define GPIO_ADC1_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) -#define GPIO_ADC1_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) -#define GPIO_ADC1_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) -#define GPIO_ADC1_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) -#define GPIO_ADC1_IN14 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) -#define GPIO_ADC1_IN15 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) - -/* CEC */ -#if defined(CONFIG_STM32_CEC_REMAP) -# define GPIO_CEC (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) -#else -# define GPIO_CEC (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8) -#endif - -/* DAC - * Note from RM0041, 11.2: "Once the DAC channelx is enabled, the corresponding - * GPIO pin (PA4 or PA5) is automatically connected to the analog converter - * output (DAC_OUTx). In order to avoid parasitic consumption, the PA4 or PA5 - * pin should first be configured to analog (AIN)." - */ - -#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) -#define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) - -/* FSMC */ - -/* TODO - VL devices in 100- and 144-pin packages have FSMC */ - -/* I2C */ - -#if defined(CONFIG_STM32_I2C1_REMAP) -# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8) -# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9) -#else -# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6) -# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7) -#endif -#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) - -#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) -#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11) -#define GPIO_I2C2_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) - -/* SPI */ - -#if defined(CONFIG_STM32_SPI1_REMAP) -# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) -# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3) -# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4) -# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) -#else -# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4) -# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN5) -# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6) -# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7) -#endif - -#define GPIO_SPI2_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) -#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13) -#define GPIO_SPI2_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) -#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15) - -#define GPIO_SPI3_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15) -#define GPIO_SPI3_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3) -#define GPIO_SPI3_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN4) -#define GPIO_SPI3_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) - /* TIMERS */ #if defined(CONFIG_STM32_TIM1_FULL_REMAP) @@ -269,77 +186,6 @@ # define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9) #endif -#define GPIO_TIM5_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -#define GPIO_TIM5_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0) -#define GPIO_TIM5_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) -#define GPIO_TIM5_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1) -#define GPIO_TIM5_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -#define GPIO_TIM5_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2) -#define GPIO_TIM5_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -#define GPIO_TIM5_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3) - -#if defined(CONFIG_STM32_TIM12_REMAP) -# define GPIO_TIM12_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN12) -# define GPIO_TIM12_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) -# define GPIO_TIM12_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13) -# define GPIO_TIM12_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13) -#else -# define GPIO_TIM12_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) -# define GPIO_TIM12_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN4) -# define GPIO_TIM12_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) -# define GPIO_TIM12_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN5) -#endif - -#if defined(CONFIG_STM32_TIM13_REMAP) -# define GPIO_TIM13_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) -# define GPIO_TIM13_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0) -#else -# define GPIO_TIM13_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN8) -# define GPIO_TIM13_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN8) -#endif - -#if defined(CONFIG_STM32_TIM14_REMAP) -# define GPIO_TIM14_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) -# define GPIO_TIM14_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1) -#else -# define GPIO_TIM14_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN9) -# define GPIO_TIM14_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN9) -#endif - -#if defined(CONFIG_STM32_TIM15_REMAP) -# define GPIO_TIM15_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN14) -# define GPIO_TIM15_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) -# define GPIO_TIM15_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN15) -# define GPIO_TIM15_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15) -#else -# define GPIO_TIM15_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -# define GPIO_TIM15_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2) -# define GPIO_TIM15_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -# define GPIO_TIM15_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3) -#endif -#define GPIO_TIM15_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9) -#define GPIO_TIM15_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15) - -#if defined(CONFIG_STM32_TIM16_REMAP) -# define GPIO_TIM16_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) -# define GPIO_TIM16_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6) -#else -# define GPIO_TIM16_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN8) -# define GPIO_TIM16_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8) -#endif -#define GPIO_TIM16_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5) -#define GPIO_TIM16_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6) - -#if defined(CONFIG_STM32_TIM17_REMAP) -# define GPIO_TIM17_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) -# define GPIO_TIM17_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7) -#else -# define GPIO_TIM17_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9) -# define GPIO_TIM17_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9) -#endif -#define GPIO_TIM17_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10) -#define GPIO_TIM17_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7) - /* USART */ #if defined(CONFIG_STM32_USART1_REMAP) @@ -384,10 +230,38 @@ # define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) #endif -#define GPIO_UART4_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10) -#define GPIO_UART4_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN11) +/* SPI */ -#define GPIO_UART5_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12) -#define GPIO_UART5_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN2) +#if defined(CONFIG_STM32_SPI1_REMAP) +# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15) +# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3) +# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4) +# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) +#else +# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4) +# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN5) +# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6) +# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7) +#endif + +#define GPIO_SPI2_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) +#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13) +#define GPIO_SPI2_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14) +#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15) + +/* I2C */ + +#if defined(CONFIG_STM32_I2C1_REMAP) +# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8) +# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9) +#else +# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6) +# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7) +#endif +#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5) + +#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11) +#define GPIO_I2C2_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12) #endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F100_PINMAP_H */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h index 52a513215d..1606768025 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h @@ -129,7 +129,7 @@ #if 0 /* Needs further investigation */ -#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUTz|GPIO_PORTA|GPIO_PIN4) #define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) #endif diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h index 581b026a09..9bcee49f57 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h @@ -50,53 +50,53 @@ /* ADC */ -#define GPIO_ADC1_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -#define GPIO_ADC1_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) -#define GPIO_ADC1_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -#define GPIO_ADC1_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -#define GPIO_ADC1_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) -#define GPIO_ADC1_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) -#define GPIO_ADC1_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) -#define GPIO_ADC1_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) -#define GPIO_ADC1_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) -#define GPIO_ADC1_IN9 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) -#define GPIO_ADC1_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) -#define GPIO_ADC1_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) -#define GPIO_ADC1_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) -#define GPIO_ADC1_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) -#define GPIO_ADC1_IN14 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) -#define GPIO_ADC1_IN15 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) +#define GPIO_ADC1_IN0 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC1_IN1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC1_IN2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC1_IN3 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC1_IN4 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC1_IN5 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC1_IN6 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC1_IN7 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC1_IN8 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC1_IN9 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) +#define GPIO_ADC1_IN10 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC1_IN11 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC1_IN12 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC1_IN13 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC1_IN14 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC1_IN15 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) -#define GPIO_ADC2_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -#define GPIO_ADC2_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) -#define GPIO_ADC2_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -#define GPIO_ADC2_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -#define GPIO_ADC2_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) -#define GPIO_ADC2_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) -#define GPIO_ADC2_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) -#define GPIO_ADC2_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) -#define GPIO_ADC2_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) -#define GPIO_ADC2_IN9 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) -#define GPIO_ADC2_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) -#define GPIO_ADC2_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) -#define GPIO_ADC2_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) -#define GPIO_ADC2_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) -#define GPIO_ADC2_IN14 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) -#define GPIO_ADC2_IN15 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) +#define GPIO_ADC2_IN0 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC2_IN1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC2_IN2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC2_IN3 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC2_IN4 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC2_IN5 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC2_IN6 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC2_IN7 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC2_IN8 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC2_IN9 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1) +#define GPIO_ADC2_IN10 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC2_IN11 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC2_IN12 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC2_IN13 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC2_IN14 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC2_IN15 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) -#define GPIO_ADC3_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) -#define GPIO_ADC3_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) -#define GPIO_ADC3_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) -#define GPIO_ADC3_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) -#define GPIO_ADC3_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN6) -#define GPIO_ADC3_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN7) -#define GPIO_ADC3_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN8) -#define GPIO_ADC3_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN9) -#define GPIO_ADC3_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN10) -#define GPIO_ADC3_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) -#define GPIO_ADC3_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) -#define GPIO_ADC3_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) -#define GPIO_ADC3_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC3_IN0 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC3_IN1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC3_IN2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC3_IN3 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC3_IN4 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN6) +#define GPIO_ADC3_IN5 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN7) +#define GPIO_ADC3_IN6 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN8) +#define GPIO_ADC3_IN7 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN9) +#define GPIO_ADC3_IN8 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN10) +#define GPIO_ADC3_IN10 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC3_IN11 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC3_IN12 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC3_IN13 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3) /* DAC - "Once the DAC channelx is enabled, the corresponding GPIO pin * (PA4 or PA5) is automatically connected to the analog converter output @@ -104,8 +104,8 @@ * should first be configured to analog (AIN)." */ -#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) -#define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) +#define GPIO_DAC_OUT1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN10) +#define GPIO_DAC_OUT2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PIN10) /* TIMERS */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h index 054a7337db..7a5ec3381e 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h @@ -85,7 +85,7 @@ #endif #if 0 /* Needs further investigation */ -#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUTz|GPIO_PORTA|GPIO_PIN4) #define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) #endif diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h index 2419620fc4..9bbc214798 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h @@ -85,7 +85,7 @@ #endif #if 0 /* Needs further investigation */ -#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUTz|GPIO_PORTA|GPIO_PIN4) #define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) #endif diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h index d339fc15ef..a95d13100e 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h @@ -59,7 +59,6 @@ #define STM32_AFIO_EXTICR2_OFFSET 0x000c /* External interrupt configuration register 2 */ #define STM32_AFIO_EXTICR3_OFFSET 0x0010 /* External interrupt configuration register 3 */ #define STM32_AFIO_EXTICR4_OFFSET 0x0014 /* External interrupt configuration register 4 */ -#define STM32_AFIO_MAPR2_OFFSET 0x001c /* AF remap and debug I/O configuration register 2 */ /* Register Addresses ***************************************************************/ @@ -374,27 +373,5 @@ #define AFIO_EXTICR4_EXTI15_SHIFT (12) /* Bits 15-12: EXTI 15 configuration */ #define AFIO_EXTICR4_EXTI15_MASK (AFIO_EXTICR_PORT_MASK << AFIO_EXTICR4_EXTI15_SHIFT) -/* AF remap and debug I/O configuration register 2 */ - -#ifdef CONFIG_STM32_VALUELINE -# define AFIO_MAPR2_TIM15_REMAP (1 << 0) /* Bit 0: TIM15 remapping */ -# define AFIO_MAPR2_TIM16_REMAP (1 << 1) /* Bit 1: TIM16 remapping */ -# define AFIO_MAPR2_TIM17_REMAP (1 << 2) /* Bit 2: TIM17 remapping */ -# define AFIO_MAPR2_CEC_REMAP (1 << 3) /* Bit 3: CEC remapping */ -# define AFIO_MAPR2_TIM1_DMA_REMAP (1 << 4) /* Bit 4: TIM1 DMA remapping */ -#else -# define AFIO_MAPR2_TIM9_REMAP (1 << 5) /* Bit 5: TIM9 remapping */ -# define AFIO_MAPR2_TIM10_REMAP (1 << 6) /* Bit 6: TIM10 remapping */ -# define AFIO_MAPR2_TIM11_REMAP (1 << 7) /* Bit 7: TIM11 remapping */ -#endif -#define AFIO_MAPR2_TIM13_REMAP (1 << 8) /* Bit 8: TIM13 remapping */ -#define AFIO_MAPR2_TIM14_REMAP (1 << 9) /* Bit 9: TIM14 remapping */ -#define AFIO_MAPR2_FSMC_NADV (1 << 10) /* Bit 10: NADV connect/disconnect */ -#ifdef CONFIG_STM32_VALUELINE -# define AFIO_MAPR2_TIM67_DAC_DMA_REMAP (1 << 11) /* Bit 11: TIM67_DAC DMA remapping */ -# define AFIO_MAPR2_TIM12_REMAP (1 << 12) /* Bit 12: TIM12 remapping */ -# define AFIO_MAPR2_MISC_REMAP (1 << 13) /* Bit 13: Miscellaneous features remapping */ -#endif - #endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F10XXX_GPIO_H */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h index a1d2e26d30..ed1bc26259 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h @@ -60,9 +60,7 @@ #define STM32_TIM5_BASE 0x40000c00 /* 0x40000c00 - 0x40000fff: TIM5 timer */ #define STM32_TIM6_BASE 0x40001000 /* 0x40001000 - 0x400013ff: TIM6 timer */ #define STM32_TIM7_BASE 0x40001400 /* 0x40001400 - 0x400007ff: TIM7 timer */ -#define STM32_TIM12_BASE 0x40001800 /* 0x40001800 - 0x40001bff: TIM12 timer */ -#define STM32_TIM13_BASE 0x40001c00 /* 0x40001c00 - 0x40001fff: TIM13 timer */ -#define STM32_TIM14_BASE 0x40002000 /* 0x40002000 - 0x400023ff: TIM14 timer */ + /* 0x40001800 - 0x40000fff: Reserved */ #define STM32_RTC_BASE 0x40002800 /* 0x40002800 - 0x40002bff: RTC */ #define STM32_WWDG_BASE 0x40002c00 /* 0x40002C00 - 0x40002fff: Window watchdog (WWDG) */ #define STM32_IWDG_BASE 0x40003000 /* 0x40003000 - 0x400033ff: Independent watchdog (IWDG) */ @@ -85,8 +83,8 @@ #define STM32_BKP_BASE 0x40006c00 /* 0x40006c00 - 0x40006fff: Backup registers (BKP) */ #define STM32_PWR_BASE 0x40007000 /* 0x40007000 - 0x400073ff: Power control PWR */ #define STM32_DAC_BASE 0x40007400 /* 0x40007400 - 0x400077ff: DAC */ -#define STM32_CEC_BASE 0x40007800 /* 0x40007800 - 0x40007bff: CEC */ - /* 0x40007c00 - 0x4000ffff: Reserved */ + /* 0x40007800 - 0x4000ffff: Reserved */ + /* APB2 bus */ #define STM32_AFIO_BASE 0x40010000 /* 0x40010000 - 0x400103ff: AFIO */ @@ -104,49 +102,44 @@ #define STM32_SPI1_BASE 0x40013000 /* 0x40013000 - 0x400133ff: SPI1 */ #define STM32_TIM8_BASE 0x40013400 /* 0x40013400 - 0x400137ff: TIM8 timer */ #define STM32_USART1_BASE 0x40013800 /* 0x40013800 - 0x40013bff: USART1 */ -#define STM32_ADC3_BASE 0x40012800 /* 0x40012800 - 0x40013c00: ADC3 */ - /* 0x40013c00 - 0x40013fff: Reserved */ -#define STM32_TIM15_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM15 */ -#define STM32_TIM16_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM16 */ -#define STM32_TIM17_BASE 0x40014800 /* 0x40014800 - 0x40014bff: TIM17 */ - /* 0x40014c00 - 0x4001ffff: Reserved */ - +#define STM32_ADC3_BASE 0x40012800 /* 0x40012800 - 0x40013fff: ADC3 */ + /* 0x40014000 - 0x40017fff: Reserved */ /* AHB bus */ -#define STM32_SDIO_BASE 0x40018000 /* 0x40018000 - 0x400183ff: SDIO */ - /* 0x40018400 - 0x40017fff: Reserved */ -#define STM32_DMA1_BASE 0x40020000 /* 0x40020000 - 0x400203ff: DMA1 */ -#define STM32_DMA2_BASE 0x40020400 /* 0x40020000 - 0x400207ff: DMA2 */ - /* 0x40020800 - 0x40020fff: Reserved */ -#define STM32_RCC_BASE 0x40021000 /* 0x40021000 - 0x400213ff: Reset and Clock control RCC */ - /* 0x40021400 - 0x40021fff: Reserved */ -#define STM32_OTGFS_BASE 0x50000000 /* 0x50000000 - 0x500003ff: USB OTG FS */ -#define STM32_FLASHIF_BASE 0x40022000 /* 0x40022000 - 0x400223ff: Flash memory interface */ -#define STM32_CRC_BASE 0x40028000 /* 0x40023000 - 0x400233ff: CRC */ - /* 0x40023400 - 0x40027fff: Reserved */ -#define STM32_ETHERNET_BASE 0x40028000 /* 0x40028000 - 0x40029fff: Ethernet */ - /* 0x40030000 - 0x4fffffff: Reserved */ +#define STM32_SDIO_BASE 0x40018000 /* 0x40018000 - 0x400183ff: SDIO */ + /* 0x40018400 - 0x40017fff: Reserved */ +#define STM32_DMA1_BASE 0x40020000 /* 0x40020000 - 0x400203ff: DMA1 */ +#define STM32_DMA2_BASE 0x40020400 /* 0x40020000 - 0x400207ff: DMA2 */ + /* 0x40020800 - 0x40020fff: Reserved */ +#define STM32_RCC_BASE 0x40021000 /* 0x40021000 - 0x400213ff: Reset and Clock control RCC */ + /* 0x40021400 - 0x40021fff: Reserved */ +#define STM32_OTGFS_BASE 0x50000000 /* 0x50000000 - 0x500003ff: USB OTG FS */ +#define STM32_FLASHIF_BASE 0x40022000 /* 0x40022000 - 0x400223ff: Flash memory interface */ +#define STM32_CRC_BASE 0x40028000 /* 0x40023000 - 0x400233ff: CRC */ + /* 0x40023400 - 0x40027fff: Reserved */ +#define STM32_ETHERNET_BASE 0x40028000 /* 0x40028000 - 0x40029fff: Ethernet */ + /* 0x40030000 - 0x4fffffff: Reserved */ /* Peripheral BB base */ -#define STM32_PERIPHBB_BASE 0x42000000 +#define STM32_PERIPHBB_BASE 0x42000000 /* Flexible SRAM controller (FSMC) */ -#define STM32_FSMC_BANK1 0x60000000 /* 0x60000000-0x6fffffff: 256Mb NOR/SRAM */ -#define STM32_FSMC_BANK2 0x70000000 /* 0x70000000-0x7fffffff: 256Mb NAND FLASH */ -#define STM32_FSMC_BANK3 0x80000000 /* 0x80000000-0x8fffffff: 256Mb NAND FLASH */ -#define STM32_FSMC_BANK4 0x90000000 /* 0x90000000-0x9fffffff: 256Mb PC CARD*/ -#define STM32_IS_EXTSRAM(a) ((((uint32_t)(a)) & STM32_REGION_MASK) == STM32_FSMC_BANK1) +#define STM32_FSMC_BANK1 0x60000000 /* 0x60000000-0x6fffffff: 256Mb NOR/SRAM */ +#define STM32_FSMC_BANK2 0x70000000 /* 0x70000000-0x7fffffff: 256Mb NAND FLASH */ +#define STM32_FSMC_BANK3 0x80000000 /* 0x80000000-0x8fffffff: 256Mb NAND FLASH */ +#define STM32_FSMC_BANK4 0x90000000 /* 0x90000000-0x9fffffff: 256Mb PC CARD*/ +#define STM32_IS_EXTSRAM(a) ((((uint32_t)(a)) & STM32_REGION_MASK) == STM32_FSMC_BANK1) -#define STM32_FSMC_BASE 0xa0000000 /* 0xa0000000-0xbfffffff: 512Mb FSMC register block */ +#define STM32_FSMC_BASE 0xa0000000 /* 0xa0000000-0xbfffffff: 512Mb FSMC register block */ /* Other registers -- see armv7-m/nvic.h for standard Cortex-M3 registers in this * address range */ -#define STM32_SCS_BASE 0xe000e000 -#define STM32_DEBUGMCU_BASE 0xe0042000 +#define STM32_SCS_BASE 0xe000e000 +#define STM32_DEBUGMCU_BASE 0xe0042000 #endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F10XXX_MEMORYMAP_H */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h index 1a792b7ebc..60365b9218 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h @@ -163,9 +163,7 @@ # define RCC_CFGR_PLLMUL_CLKx14 (12 << RCC_CFGR_PLLMUL_SHIFT) /* 1100: PLL input clock x 14 */ # define RCC_CFGR_PLLMUL_CLKx15 (13 << RCC_CFGR_PLLMUL_SHIFT) /* 1101: PLL input clock x 15 */ # define RCC_CFGR_PLLMUL_CLKx16 (14 << RCC_CFGR_PLLMUL_SHIFT) /* 111x: PLL input clock x 16 */ -#ifndef CONFIG_STM32_VALUELINE -# define RCC_CFGR_USBPRE (1 << 22) /* Bit 22: USB prescaler */ -#endif +#define RCC_CFGR_USBPRE (1 << 22) /* Bit 22: USB prescaler */ #define RCC_CFGR_MCO_SHIFT (24) /* Bits 26-24: Microcontroller Clock Output */ #define RCC_CFGR_MCO_MASK (0x0f << RCC_CFGR_MCO_SHIFT) # define RCC_CFGR_NOCLK (0 << RCC_CFGR_MCO_SHIFT) /* 0xx: No clock */ @@ -209,22 +207,12 @@ #define TCC_APB2RSTR_IOPFRST (1 << 7) /* Bit 7: IO port F reset */ #define TCC_APB2RSTR_IOPGRST (1 << 8) /* Bit 8: IO port G reset */ #define RCC_APB2RSTR_ADC1RST (1 << 9) /* Bit 9: ADC 1 interface reset */ -#ifndef CONFIG_STM32_VALUELINE -# define RCC_APB2RSTR_ADC2RST (1 << 10) /* Bit 10: ADC 2 interface reset */ -#endif +#define RCC_APB2RSTR_ADC2RST (1 << 10) /* Bit 10: ADC 2 interface reset */ #define RCC_APB2RSTR_TIM1RST (1 << 11) /* Bit 11: TIM1 Timer reset */ #define RCC_APB2RSTR_SPI1RST (1 << 12) /* Bit 12: SPI 1 reset */ -#ifndef CONFIG_STM32_VALUELINE -# define RCC_APB2RSTR_TIM8RST (1 << 13) /* Bit 13: TIM8 Timer reset */ -#endif +#define RCC_APB2RSTR_TIM8RST (1 << 13) /* Bit 13: TIM8 Timer reset */ #define RCC_APB2RSTR_USART1RST (1 << 14) /* Bit 14: USART1 reset */ -#ifndef CONFIG_STM32_VALUELINE -# define RCC_APB2RSTR_ADC3RST (1 << 15) /* Bit 15: ADC3 interface reset */ -#else -# define RCC_APB2RSTR_TIM15RST (1 << 16) /* Bit 16: TIM15 reset */ -# define RCC_APB2RSTR_TIM16RST (1 << 17) /* Bit 17: TIM16 reset */ -# define RCC_APB2RSTR_TIM17RST (1 << 18) /* Bit 18: TIM17 reset */ -#endif +#define RCC_APB2RSTR_ADC3RST (1 << 15) /* Bit 15: ADC3 interface reset */ /* APB1 Peripheral reset register */ @@ -234,11 +222,6 @@ #define RCC_APB1RSTR_TIM5RST (1 << 3) /* Bit 3: Timer 5 reset */ #define RCC_APB1RSTR_TIM6RST (1 << 4) /* Bit 4: Timer 6 reset */ #define RCC_APB1RSTR_TIM7RST (1 << 5) /* Bit 5: Timer 7 reset */ -#ifdef CONFIG_STM32_VALUELINE -# define RCC_APB1RSTR_TIM12RST (1 << 6) /* Bit 6: TIM12 reset */ -# define RCC_APB1RSTR_TIM13RST (1 << 7) /* Bit 7: TIM13 reset */ -# define RCC_APB1RSTR_TIM14RST (1 << 8) /* Bit 8: TIM14 reset */ -#endif #define RCC_APB1RSTR_WWDGRST (1 << 11) /* Bit 11: Window Watchdog reset */ #define RCC_APB1RSTR_SPI2RST (1 << 14) /* Bit 14: SPI 2 reset */ #define RCC_APB1RSTR_SPI3RST (1 << 15) /* Bit 15: SPI 3 reset */ @@ -248,17 +231,12 @@ #define RCC_APB1RSTR_UART5RST (1 << 20) /* Bit 18: UART 5 reset */ #define RCC_APB1RSTR_I2C1RST (1 << 21) /* Bit 21: I2C 1 reset */ #define RCC_APB1RSTR_I2C2RST (1 << 22) /* Bit 22: I2C 2 reset */ -#ifndef CONFIG_STM32_VALUELINE -# define RCC_APB1RSTR_USBRST (1 << 23) /* Bit 23: USB reset */ -# define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ -# define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */ -#endif +#define RCC_APB1RSTR_USBRST (1 << 23) /* Bit 23: USB reset */ +#define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ +#define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */ #define RCC_APB1RSTR_BKPRST (1 << 27) /* Bit 27: Backup interface reset */ #define RCC_APB1RSTR_PWRRST (1 << 28) /* Bit 28: Power interface reset */ #define RCC_APB1RSTR_DACRST (1 << 29) /* Bit 29: DAC interface reset */ -#ifdef CONFIG_STM32_VALUELINE -# define RCC_APB1RSTR_CECRST (1 << 30) /* Bit 30: CEC reset */ -#endif /* AHB Peripheral Clock enable register */ @@ -268,9 +246,7 @@ #define RCC_AHBENR_FLITFEN (1 << 4) /* Bit 4: FLITF clock enable */ #define RCC_AHBENR_CRCEN (1 << 6) /* Bit 6: CRC clock enable */ #define RCC_AHBENR_FSMCEN (1 << 8) /* Bit 8: FSMC clock enable */ -#ifndef CONFIG_STM32_VALUELINE -# define RCC_AHBENR_SDIOEN (1 << 10) /* Bit 10: SDIO clock enable */ -#endif +#define RCC_AHBENR_SDIOEN (1 << 10) /* Bit 10: SDIO clock enable */ #ifdef CONFIG_STM32_CONNECTIVITYLINE # define RCC_AHBENR_ETHMACEN (1 << 14) /* Bit 14: Ethernet MAC clock enable */ # define RCC_AHBENR_ETHMACTXEN (1 << 15) /* Bit 15: Ethernet MAC TX clock enable */ @@ -296,22 +272,12 @@ #define RCC_APB2ENR_IOPFEN (1 << 7) /* Bit 7: I/O port F clock enable */ #define RCC_APB2ENR_IOPGEN (1 << 8) /* Bit 8: I/O port G clock enable */ #define RCC_APB2ENR_ADC1EN (1 << 9) /* Bit 9: ADC 1 interface clock enable */ -#ifndef CONFIG_STM32_VALUELINE -# define RCC_APB2ENR_ADC2EN (1 << 10) /* Bit 10: ADC 2 interface clock enable */ -#endif +#define RCC_APB2ENR_ADC2EN (1 << 10) /* Bit 10: ADC 2 interface clock enable */ #define RCC_APB2ENR_TIM1EN (1 << 11) /* Bit 11: TIM1 Timer clock enable */ #define RCC_APB2ENR_SPI1EN (1 << 12) /* Bit 12: SPI 1 clock enable */ -#ifndef CONFIG_STM32_VALUELINE -# define RCC_APB2ENR_TIM8EN (1 << 13) /* Bit 13: TIM8 Timer clock enable */ -#endif +#define RCC_APB2ENR_TIM8EN (1 << 13) /* Bit 13: TIM8 Timer clock enable */ #define RCC_APB2ENR_USART1EN (1 << 14) /* Bit 14: USART1 clock enable */ -#ifndef CONFIG_STM32_VALUELINE -# define RCC_APB2ENR_ADC3EN (1 << 15) /* Bit 14: ADC3 interface clock enable */ -#else -# define RCC_APB2ENR_TIM15EN (1 << 16) /* Bit 16: TIM15 clock enable */ -# define RCC_APB2ENR_TIM16EN (1 << 17) /* Bit 17: TIM16 clock enable */ -# define RCC_APB2ENR_TIM17EN (1 << 18) /* Bit 18: TIM17 clock enable */ -#endif +#define RCC_APB2ENR_ADC3EN (1 << 15) /* Bit 14: ADC3 interface clock enable */ /* APB1 Peripheral Clock enable register */ @@ -321,11 +287,6 @@ #define RCC_APB1ENR_TIM5EN (1 << 3) /* Bit 3: Timer 5 clock enable */ #define RCC_APB1ENR_TIM6EN (1 << 4) /* Bit 4: Timer 6 clock enable */ #define RCC_APB1ENR_TIM7EN (1 << 5) /* Bit 5: Timer 7 clock enable */ -#ifdef CONFIG_STM32_VALUELINE -# define RCC_APB1ENR_TIM12EN (1 << 6) /* Bit 6: Timer 12 clock enable */ -# define RCC_APB1ENR_TIM13EN (1 << 7) /* Bit 7: Timer 13 clock enable */ -# define RCC_APB1ENR_TIM14EN (1 << 8) /* Bit 8: Timer 14 clock enable */ -#endif #define RCC_APB1ENR_WWDGEN (1 << 11) /* Bit 11: Window Watchdog clock enable */ #define RCC_APB1ENR_SPI2EN (1 << 14) /* Bit 14: SPI 2 clock enable */ #define RCC_APB1ENR_SPI3EN (1 << 15) /* Bit 15: SPI 3 clock enable */ @@ -335,17 +296,12 @@ #define RCC_APB1ENR_UART5EN (1 << 20) /* Bit 20: UART 5 clock enable */ #define RCC_APB1ENR_I2C1EN (1 << 21) /* Bit 21: I2C 1 clock enable */ #define RCC_APB1ENR_I2C2EN (1 << 22) /* Bit 22: I2C 2 clock enable */ -#ifndef CONFIG_STM32_VALUELINE -# define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */ -# define RCC_APB1ENR_CAN1EN (1 << 25) /* Bit 25: CAN1 clock enable */ -# define RCC_APB1ENR_CAN2EN (1 << 26) /* Bit 25: CAN2 clock enable */ -#endif +#define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */ +#define RCC_APB1ENR_CAN1EN (1 << 25) /* Bit 25: CAN1 clock enable */ +#define RCC_APB1ENR_CAN2EN (1 << 26) /* Bit 25: CAN2 clock enable */ #define RCC_APB1ENR_BKPEN (1 << 27) /* Bit 27: Backup interface clock enable */ #define RCC_APB1ENR_PWREN (1 << 28) /* Bit 28: Power interface clock enable */ #define RCC_APB1ENR_DACEN (1 << 29) /* Bit 29: DAC interface clock enable */ -#ifdef CONFIG_STM32_VALUELINE -# define RCC_APB1ENR_CECEN (1 << 30) /* Bit 30: CEC clock enable */ -#endif /* Backup domain control register */ @@ -375,7 +331,7 @@ #if defined(CONFIG_STM32_VALUELINE) || defined(CONFIG_STM32_CONNECTIVITYLINE) -/* Clock configuration register 2 (For value line and connectivity line only) */ +/* Clock configuration register 2 (For connectivity line only) */ #define RCC_CFGR2_PREDIV1_SHIFT (0) #define RCC_CFGR2_PREDIV1_MASK (0x0f << RCC_CFGR2_PREDIV1_SHIFT) @@ -396,10 +352,6 @@ # define RCC_CFGR2_PREDIV1d15 (14 << RCC_CFGR2_PREDIV1_SHIFT) # define RCC_CFGR2_PREDIV1d16 (15 << RCC_CFGR2_PREDIV1_SHIFT) -#endif - -#ifdef CONFIG_STM32_CONNECTIVITYLINE - #define RCC_CFGR2_PREDIV2_SHIFT (4) #define RCC_CFGR2_PREDIV2_MASK (0x0f << RCC_CFGR2_PREDIV2_SHIFT) # define RCC_CFGR2_PREDIV2d1 (0 << RCC_CFGR2_PREDIV2_SHIFT) diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h index 24822c37d3..b8d71799fe 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h @@ -49,77 +49,15 @@ * definition that provides the number of supported vectors. */ -# ifdef CONFIG_ARMV7M_CMNVECTOR +#ifdef CONFIG_ARMV7M_CMNVECTOR -/* Reserve 61 interrupt table entries for I/O interrupts. */ +/* Reserve 60 interrupt table entries for I/O interrupts. */ -# define ARMV7M_PERIPHERAL_INTERRUPTS 61 +# define ARMV7M_PERIPHERAL_INTERRUPTS 60 #else - -VECTOR(stm32_wwdg, STM32_IRQ_WWDG) /* Vector 16+0: Window Watchdog interrupt */ -VECTOR(stm32_pvd, STM32_IRQ_PVD) /* Vector 16+1: PVD through EXTI Line detection interrupt */ -VECTOR(stm32_tamper, STM32_IRQ_TAMPER) /* Vector 16+2: Tamper interrupt */ -VECTOR(stm32_rtc, STM32_IRQ_RTC) /* Vector 16+3: RTC Wakeup through EXTI line interrupt */ -VECTOR(stm32_flash, STM32_IRQ_FLASH) /* Vector 16+4: Flash global interrupt */ -VECTOR(stm32_rcc, STM32_IRQ_RCC) /* Vector 16+5: RCC global interrupt */ -VECTOR(stm32_exti0, STM32_IRQ_EXTI0) /* Vector 16+6: EXTI Line 0 interrupt */ -VECTOR(stm32_exti1, STM32_IRQ_EXTI1) /* Vector 16+7: EXTI Line 1 interrupt */ -VECTOR(stm32_exti2, STM32_IRQ_EXTI2) /* Vector 16+8: EXTI Line 2 interrupt */ -VECTOR(stm32_exti3, STM32_IRQ_EXTI3) /* Vector 16+9: EXTI Line 3 interrupt */ -VECTOR(stm32_exti4, STM32_IRQ_EXTI4) /* Vector 16+10: EXTI Line 4 interrupt */ -VECTOR(stm32_dma1ch1, STM32_IRQ_DMA1CH1) /* Vector 16+11: DMA1 Channel 1 global interrupt */ -VECTOR(stm32_dma1ch2, STM32_IRQ_DMA1CH2) /* Vector 16+12: DMA1 Channel 2 global interrupt */ -VECTOR(stm32_dma1ch3, STM32_IRQ_DMA1CH3) /* Vector 16+13: DMA1 Channel 3 global interrupt */ -VECTOR(stm32_dma1ch4, STM32_IRQ_DMA1CH4) /* Vector 16+14: DMA1 Channel 4 global interrupt */ -VECTOR(stm32_dma1ch5, STM32_IRQ_DMA1CH5) /* Vector 16+15: DMA1 Channel 5 global interrupt */ -VECTOR(stm32_dma1ch6, STM32_IRQ_DMA1CH6) /* Vector 16+16: DMA1 Channel 6 global interrupt */ -VECTOR(stm32_dma1ch7, STM32_IRQ_DMA1CH7) /* Vector 16+17: DMA1 Channel 7 global interrupt */ -VECTOR(stm32_adc1, STM32_IRQ_ADC1) /* Vector 16+18: ADC1 global interrupt */ -UNUSED(STM32_IRQ_RESERVED0) /* Vector 16+19: Reserved 0 */ -UNUSED(STM32_IRQ_RESERVED1) /* Vector 16+20: Reserved 1 */ -UNUSED(STM32_IRQ_RESERVED2) /* Vector 16+21: Reserved 2 */ -UNUSED(STM32_IRQ_RESERVED3) /* Vector 16+22: Reserved 3 */ -VECTOR(stm32_exti95, STM32_IRQ_EXTI95) /* Vector 16+23: EXTI Line[9:5] interrupts */ -VECTOR(stm32_tim1brk, STM32_IRQ_TIM1BRK) /* Vector 16+24: TIM1 Break interrupt; TIM15 global interrupt */ -VECTOR(stm32_tim1up, STM32_IRQ_TIM1UP) /* Vector 16+25: TIM1 Update interrupt; TIM16 global interrupt */ -VECTOR(stm32_tim1trgcom, STM32_IRQ_TIM1TRGCOM) /* Vector 16+26: TIM1 Trigger and Commutation interrupts; TIM17 global interrupt */ -VECTOR(stm32_tim1cc, STM32_IRQ_TIM1CC) /* Vector 16+27: TIM1 Capture Compare interrupt */ -VECTOR(stm32_tim2, STM32_IRQ_TIM2) /* Vector 16+28: TIM2 global interrupt */ -VECTOR(stm32_tim3, STM32_IRQ_TIM3) /* Vector 16+29: TIM3 global interrupt */ -VECTOR(stm32_tim4, STM32_IRQ_TIM4) /* Vector 16+30: TIM4 global interrupt */ -VECTOR(stm32_i2c1ev, STM32_IRQ_I2C1EV) /* Vector 16+31: I2C1 event interrupt */ -VECTOR(stm32_i2c1er, STM32_IRQ_I2C1ER) /* Vector 16+32: I2C1 error interrupt */ -VECTOR(stm32_i2c2ev, STM32_IRQ_I2C2EV) /* Vector 16+33: I2C2 event interrupt */ -VECTOR(stm32_i2c2er, STM32_IRQ_I2C2ER) /* Vector 16+34: I2C2 error interrupt */ -VECTOR(stm32_spi1, STM32_IRQ_SPI1) /* Vector 16+35: SPI1 global interrupt */ -VECTOR(stm32_spi2, STM32_IRQ_SPI2) /* Vector 16+36: SPI2 global interrupt */ -VECTOR(stm32_usart1, STM32_IRQ_USART1) /* Vector 16+37: USART1 global interrupt */ -VECTOR(stm32_usart2, STM32_IRQ_USART2) /* Vector 16+38: USART2 global interrupt */ -VECTOR(stm32_usart3, STM32_IRQ_USART3) /* Vector 16+39: USART3 global interrupt */ -VECTOR(stm32_exti1510, STM32_IRQ_EXTI1510) /* Vector 16+40: EXTI Line[15:10] interrupts */ -VECTOR(stm32_rtcalr, STM32_IRQ_RTCALR) /* Vector 16+41: RTC alarms (A and B) through EXTI line interrupt */ -VECTOR(stm32_cec, STM32_IRQ_CEC) /* Vector 16+42: CEC global interrupt */ -VECTOR(stm32_tim12, STM32_IRQ_TIM12) /* Vector 16+43: TIM12 global interrupt */ -VECTOR(stm32_tim13, STM32_IRQ_TIM13) /* Vector 16+44: TIM13 global interrupt */ -VECTOR(stm32_tim14, STM32_IRQ_TIM14) /* Vector 16+45: TIM14 global interrupt */ -UNUSED(STM32_IRQ_RESERVED4) /* Vector 16+46: Reserved 4 */ -UNUSED(STM32_IRQ_RESERVED5) /* Vector 16+47: Reserved 5 */ -VECTOR(stm32_fsmc, STM32_IRQ_FSMC) /* Vector 16+48: FSMC global interrupt */ -UNUSED(STM32_IRQ_RESERVED6) /* Vector 16+49: Reserved 6 */ -VECTOR(stm32_tim5, STM32_IRQ_TIM5) /* Vector 16+50: TIM5 global interrupt */ -VECTOR(stm32_spi3, STM32_IRQ_SPI3) /* Vector 16+51: SPI3 global interrupt */ -VECTOR(stm32_uart4, STM32_IRQ_UART4) /* Vector 16+52: USART2 global interrupt */ -VECTOR(stm32_uart5, STM32_IRQ_UART5) /* Vector 16+53: USART5 global interrupt */ -VECTOR(stm32_tim6, STM32_IRQ_TIM6) /* Vector 16+54: TIM6 global interrupt */ -VECTOR(stm32_tim7, STM32_IRQ_TIM7) /* Vector 16+55: TIM7 global interrupt */ -VECTOR(stm32_dma2ch1, STM32_IRQ_DMA2CH1) /* Vector 16+56: DMA2 Channel 1 global interrupt */ -VECTOR(stm32_dma2ch2, STM32_IRQ_DMA2CH2) /* Vector 16+57: DMA2 Channel 2 global interrupt */ -VECTOR(stm32_dma2ch3, STM32_IRQ_DMA2CH3) /* Vector 16+58: DMA2 Channel 3 global interrupt */ -VECTOR(stm32_dma2ch45, STM32_IRQ_DMA2CH45) /* Vector 16+59: DMA2 Channel 4 and 5 global interrupt */ -VECTOR(stm32_dma2ch5, STM32_IRQ_DMA2CH5) /* Vector 16+60: DMA2 Channel 5 global interrupt */ - -# endif /* CONFIG_ARMV7M_CMNVECTOR */ +# error This target requires CONFIG_ARMV7M_CMNVECTOR +#endif /* CONFIG_ARMV7M_CMNVECTOR */ #elif defined(CONFIG_STM32_CONNECTIVITYLINE) diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h index 699ca4fdc4..817e747f71 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h @@ -222,7 +222,7 @@ #define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) #define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) #define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN8) -#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULLGPIO_PORTA|GPIO_PIN7) #define GPIO_ETH_RMII_REF_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) #define GPIO_ETH_RMII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4) #define GPIO_ETH_RMII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5) diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h index 31e51caf07..ae2436a70f 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h @@ -222,7 +222,7 @@ #define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) #define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) #define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN8) -#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULLGPIO_PORTA|GPIO_PIN7) #define GPIO_ETH_RMII_REF_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) #define GPIO_ETH_RMII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4) #define GPIO_ETH_RMII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5) diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.c b/nuttx/arch/arm/src/stm32/stm32_adc.c index a7275e7349..844f1fd0fa 100644 --- a/nuttx/arch/arm/src/stm32/stm32_adc.c +++ b/nuttx/arch/arm/src/stm32/stm32_adc.c @@ -720,10 +720,10 @@ static int adc_timinit(FAR struct stm32_dev_s *priv) case 4: /* TimerX TRGO event */ { - /* TODO: TRGO support not yet implemented */ +#warning "TRGO support not yet implemented" + /* Set the event TRGO */ - ccenable = 0; egr = GTIM_EGR_TG; /* Set the duty cycle by writing to the CCR register for this channel */ @@ -1128,7 +1128,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) avdbg("intf: ADC%d\n", priv->intf); flags = irqsave(); - /* Enable ADC reset state */ + /* Enable ADC reset state */ adc_rccreset(priv, true); @@ -1326,10 +1326,6 @@ static int adc_setup(FAR struct adc_dev_s *dev) ret = irq_attach(priv->irq, priv->isr); if (ret == OK) { - /* Make sure that the ADC device is in the powered up, reset state */ - - adc_reset(dev); - /* Enable the ADC interrupt */ avdbg("Enable the ADC interrupt: irq=%d\n", priv->irq); diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.h b/nuttx/arch/arm/src/stm32/stm32_adc.h index 7b6c13b338..c25da38305 100644 --- a/nuttx/arch/arm/src/stm32/stm32_adc.h +++ b/nuttx/arch/arm/src/stm32/stm32_adc.h @@ -281,7 +281,7 @@ #if defined(ADC1_HAVE_TIMER) || defined(ADC2_HAVE_TIMER) || defined(ADC3_HAVE_TIMER) # define ADC_HAVE_TIMER 1 -# if defined(CONFIG_STM32_STM32F10XX) && !defined(CONFIG_STM32_FORCEPOWER) +# if defined(CONFIG_STM32_STM32F10XX) && defined(CONFIG_STM32_FORCEPOWER) # warning "CONFIG_STM32_FORCEPOWER must be defined to enable the timer(s)" # endif #else diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c index 006f67142b..3054142ce8 100644 --- a/nuttx/arch/arm/src/stm32/stm32_eth.c +++ b/nuttx/arch/arm/src/stm32/stm32_eth.c @@ -2594,17 +2594,6 @@ static int stm32_phyinit(FAR struct stm32_ethmac_s *priv) } up_mdelay(PHY_RESET_DELAY); - /* Perform any necessary, board-specific PHY initialization */ - -#ifdef CONFIG_STM32_PHYINIT - ret = stm32_phy_boardinitialize(0); - if (ret < 0) - { - ndbg("Failed to initialize the PHY: %d\n", ret); - return ret; - } -#endif - /* Special workaround for the Davicom DM9161 PHY is required. */ #ifdef CONFIG_PHY_DM9161 diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.h b/nuttx/arch/arm/src/stm32/stm32_eth.h index 4501712b14..f0c14b5b1f 100644 --- a/nuttx/arch/arm/src/stm32/stm32_eth.h +++ b/nuttx/arch/arm/src/stm32/stm32_eth.h @@ -66,13 +66,14 @@ extern "C" { * Function: stm32_ethinitialize * * Description: - * Initialize the Ethernet driver for one interface. If the STM32 chip supports - * multiple Ethernet controllers, then board specific logic must implement - * up_netinitialize() and call this function to initialize the desired interfaces. + * Initialize the Ethernet driver for one interface. If the STM32 chip + * supports multiple Ethernet controllers, then board specific logic + * must implement up_netinitialize() and call this function to initialize + * the desired interfaces. * * Parameters: - * intf - In the case where there are multiple EMACs, this value identifies which - * EMAC is to be initialized. + * intf - In the case where there are multiple EMACs, this value + * identifies which EMAC is to be initialized. * * Returned Value: * OK on success; Negated errno on failure. @@ -85,30 +86,6 @@ extern "C" { EXTERN int stm32_ethinitialize(int intf); #endif -/************************************************************************************ - * Function: stm32_phy_boardinitialize - * - * Description: - * Some boards require specialized initialization of the PHY before it can be used. - * This may include such things as configuring GPIOs, resetting the PHY, etc. If - * CONFIG_STM32_PHYINIT is defined in the configuration then the board specific - * logic must provide stm32_phyinitialize(); The STM32 Ethernet driver will call - * this function one time before it first uses the PHY. - * - * Parameters: - * intf - Always zero for now. - * - * Returned Value: - * OK on success; Negated errno on failure. - * - * Assumptions: - * - ************************************************************************************/ - -#ifdef CONFIG_STM32_PHYINIT -EXTERN int stm32_phy_boardinitialize(int intf); -#endif - #undef EXTERN #if defined(__cplusplus) } diff --git a/nuttx/arch/arm/src/stm32/stm32_lowputc.c b/nuttx/arch/arm/src/stm32/stm32_lowputc.c index 6cb07dad93..7f72056729 100644 --- a/nuttx/arch/arm/src/stm32/stm32_lowputc.c +++ b/nuttx/arch/arm/src/stm32/stm32_lowputc.c @@ -67,14 +67,6 @@ # define STM32_CONSOLE_2STOP CONFIG_USART1_2STOP # define STM32_CONSOLE_TX GPIO_USART1_TX # define STM32_CONSOLE_RX GPIO_USART1_RX -# ifdef CONFIG_USART1_RS485 -# define STM32_CONSOLE_RS485_DIR GPIO_USART1_RS485_DIR -# if (CONFIG_USART1_RS485_DIR_POLARITY == 0) -# define STM32_CONSOLE_RS485_DIR_POLARITY false -# else -# define STM32_CONSOLE_RS485_DIR_POLARITY true -# endif -# endif #elif defined(CONFIG_USART2_SERIAL_CONSOLE) # define STM32_CONSOLE_BASE STM32_USART2_BASE # define STM32_APBCLOCK STM32_PCLK1_FREQUENCY @@ -84,14 +76,6 @@ # define STM32_CONSOLE_2STOP CONFIG_USART2_2STOP # define STM32_CONSOLE_TX GPIO_USART2_TX # define STM32_CONSOLE_RX GPIO_USART2_RX -# ifdef CONFIG_USART2_RS485 -# define STM32_CONSOLE_RS485_DIR GPIO_USART2_RS485_DIR -# if (CONFIG_USART2_RS485_DIR_POLARITY == 0) -# define STM32_CONSOLE_RS485_DIR_POLARITY false -# else -# define STM32_CONSOLE_RS485_DIR_POLARITY true -# endif -# endif #elif defined(CONFIG_USART3_SERIAL_CONSOLE) # define STM32_CONSOLE_BASE STM32_USART3_BASE # define STM32_APBCLOCK STM32_PCLK1_FREQUENCY @@ -101,14 +85,6 @@ # define STM32_CONSOLE_2STOP CONFIG_USART3_2STOP # define STM32_CONSOLE_TX GPIO_USART3_TX # define STM32_CONSOLE_RX GPIO_USART3_RX -# ifdef CONFIG_USART3_RS485 -# define STM32_CONSOLE_RS485_DIR GPIO_USART3_RS485_DIR -# if (CONFIG_USART3_RS485_DIR_POLARITY == 0) -# define STM32_CONSOLE_RS485_DIR_POLARITY false -# else -# define STM32_CONSOLE_RS485_DIR_POLARITY true -# endif -# endif #elif defined(CONFIG_UART4_SERIAL_CONSOLE) # define STM32_CONSOLE_BASE STM32_UART4_BASE # define STM32_APBCLOCK STM32_PCLK1_FREQUENCY @@ -118,14 +94,6 @@ # define STM32_CONSOLE_2STOP CONFIG_UART4_2STOP # define STM32_CONSOLE_TX GPIO_UART4_TX # define STM32_CONSOLE_RX GPIO_UART4_RX -# ifdef CONFIG_UART4_RS485 -# define STM32_CONSOLE_RS485_DIR GPIO_UART4_RS485_DIR -# if (CONFIG_UART4_RS485_DIR_POLARITY == 0) -# define STM32_CONSOLE_RS485_DIR_POLARITY false -# else -# define STM32_CONSOLE_RS485_DIR_POLARITY true -# endif -# endif #elif defined(CONFIG_UART5_SERIAL_CONSOLE) # define STM32_CONSOLE_BASE STM32_UART5_BASE # define STM32_APBCLOCK STM32_PCLK1_FREQUENCY @@ -135,14 +103,6 @@ # define STM32_CONSOLE_2STOP CONFIG_UART5_2STOP # define STM32_CONSOLE_TX GPIO_UART5_TX # define STM32_CONSOLE_RX GPIO_UART5_RX -# ifdef CONFIG_UART5_RS485 -# define STM32_CONSOLE_RS485_DIR GPIO_UART5_RS485_DIR -# if (CONFIG_UART5_RS485_DIR_POLARITY == 0) -# define STM32_CONSOLE_RS485_DIR_POLARITY false -# else -# define STM32_CONSOLE_RS485_DIR_POLARITY true -# endif -# endif #elif defined(CONFIG_USART6_SERIAL_CONSOLE) # define STM32_CONSOLE_BASE STM32_USART6_BASE # define STM32_APBCLOCK STM32_PCLK2_FREQUENCY @@ -152,14 +112,6 @@ # define STM32_CONSOLE_2STOP CONFIG_USART6_2STOP # define STM32_CONSOLE_TX GPIO_USART6_TX # define STM32_CONSOLE_RX GPIO_USART6_RX -# ifdef CONFIG_USART6_RS485 -# define STM32_CONSOLE_RS485_DIR GPIO_USART6_RS485_DIR -# if (CONFIG_USART6_RS485_DIR_POLARITY == 0) -# define STM32_CONSOLE_RS485_DIR_POLARITY false -# else -# define STM32_CONSOLE_RS485_DIR_POLARITY true -# endif -# endif #endif /* CR1 settings */ @@ -278,19 +230,10 @@ void up_lowputc(char ch) /* Wait until the TX data register is empty */ while ((getreg32(STM32_CONSOLE_BASE + STM32_USART_SR_OFFSET) & USART_SR_TXE) == 0); -#if STM32_CONSOLE_RS485_DIR - stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, STM32_CONSOLE_RS485_DIR_POLARITY); -#endif /* Then send the character */ putreg32((uint32_t)ch, STM32_CONSOLE_BASE + STM32_USART_DR_OFFSET); - -#if STM32_CONSOLE_RS485_DIR - while ((getreg32(STM32_CONSOLE_BASE + STM32_USART_SR_OFFSET) & USART_SR_TC) == 0); - stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY); -#endif - #endif } @@ -385,14 +328,7 @@ void stm32_lowsetup(void) #ifdef STM32_CONSOLE_TX stm32_configgpio(STM32_CONSOLE_TX); -#endif -#ifdef STM32_CONSOLE_RX - stm32_configgpio(STM32_CONSOLE_RX); -#endif - -#if STM32_CONSOLE_RS485_DIR - stm32_configgpio(STM32_CONSOLE_RS485_DIR); - stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY); + stm32_configgpio(STM32_CONSOLE_TX); #endif /* Enable and configure the selected console device */ @@ -446,14 +382,7 @@ void stm32_lowsetup(void) #ifdef STM32_CONSOLE_TX stm32_configgpio(STM32_CONSOLE_TX); -#endif -#ifdef STM32_CONSOLE_RX - stm32_configgpio(STM32_CONSOLE_RX); -#endif - -#if STM32_CONSOLE_RS485_DIR - stm32_configgpio(STM32_CONSOLE_RS485_DIR); - stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY); + stm32_configgpio(STM32_CONSOLE_TX); #endif /* Enable and configure the selected console device */ diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c index 94772b693f..461d500ad1 100644 --- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c +++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c @@ -3651,14 +3651,10 @@ static int stm32_epout_configure(FAR struct stm32_ep_s *privep, uint8_t eptype, regval = stm32_getreg(regaddr); if ((regval & OTGFS_DOEPCTL_USBAEP) == 0) { - if (regval & OTGFS_DOEPCTL_NAKSTS) - { - regval |= OTGFS_DOEPCTL_CNAK; - } - - regval &= ~(OTGFS_DOEPCTL_MPSIZ_MASK | OTGFS_DOEPCTL_EPTYP_MASK); + regval &= ~(OTGFS_DOEPCTL_MPSIZ_MASK | OTGFS_DIEPCTL_EPTYP_MASK | OTGFS_DIEPCTL_TXFNUM_MASK); regval |= mpsiz; regval |= (eptype << OTGFS_DOEPCTL_EPTYP_SHIFT); + regval |= (eptype << OTGFS_DIEPCTL_TXFNUM_SHIFT); regval |= (OTGFS_DOEPCTL_SD0PID | OTGFS_DOEPCTL_USBAEP); stm32_putreg(regval, regaddr); @@ -3747,11 +3743,6 @@ static int stm32_epin_configure(FAR struct stm32_ep_s *privep, uint8_t eptype, regval = stm32_getreg(regaddr); if ((regval & OTGFS_DIEPCTL_USBAEP) == 0) { - if (regval & OTGFS_DIEPCTL_NAKSTS) - { - regval |= OTGFS_DIEPCTL_CNAK; - } - regval &= ~(OTGFS_DIEPCTL_MPSIZ_MASK | OTGFS_DIEPCTL_EPTYP_MASK | OTGFS_DIEPCTL_TXFNUM_MASK); regval |= mpsiz; regval |= (eptype << OTGFS_DIEPCTL_EPTYP_SHIFT); @@ -3909,7 +3900,7 @@ static void stm32_epout_disable(FAR struct stm32_ep_s *privep) * Name: stm32_epin_disable * * Description: - * Disable an IN endpoint when it will no longer be used + * Diable an IN endpoint will no longer be used * *******************************************************************************/ @@ -3921,17 +3912,6 @@ static void stm32_epin_disable(FAR struct stm32_ep_s *privep) usbtrace(TRACE_EPDISABLE, privep->epphy); - /* After USB reset, the endpoint will already be deactivated by the - * hardware. Trying to disable again will just hang in the wait. - */ - - regaddr = STM32_OTGFS_DIEPCTL(privep->epphy); - regval = stm32_getreg(regaddr); - if ((regval & OTGFS_DIEPCTL_USBAEP) == 0) - { - return; - } - /* Make sure that there is no pending IPEPNE interrupt (because we are * to poll this bit below). */ diff --git a/nuttx/arch/arm/src/stm32/stm32_qencoder.c b/nuttx/arch/arm/src/stm32/stm32_qencoder.c index d37614c03c..8553296f93 100644 --- a/nuttx/arch/arm/src/stm32/stm32_qencoder.c +++ b/nuttx/arch/arm/src/stm32/stm32_qencoder.c @@ -607,7 +607,6 @@ static FAR struct stm32_lowerhalf_s *stm32_tim2lower(int tim) #endif #ifdef CONFIG_STM32_TIM3_QE case 3: - return &g_tim3lower; #endif #ifdef CONFIG_STM32_TIM4_QE case 4: diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c index bf3c753f32..0868c3cd3d 100644 --- a/nuttx/arch/arm/src/stm32/stm32_serial.c +++ b/nuttx/arch/arm/src/stm32/stm32_serial.c @@ -96,19 +96,6 @@ # endif # endif -/* Currently RS-485 support cannot be enabled when RXDMA is in use due to lack - * of testing - RS-485 support was developed on STM32F1x - */ - -# if (defined(CONFIG_USART1_RXDMA) && defined(CONFIG_USART1_RS485)) || \ - (defined(CONFIG_USART2_RXDMA) && defined(CONFIG_USART2_RS485)) || \ - (defined(CONFIG_USART3_RXDMA) && defined(CONFIG_USART3_RS485)) || \ - (defined(CONFIG_UART4_RXDMA) && defined(CONFIG_UART4_RS485)) || \ - (defined(CONFIG_UART5_RXDMA) && defined(CONFIG_UART5_RS485)) || \ - (defined(CONFIG_USART6_RXDMA) && defined(CONFIG_USART6_RS485)) -# error "RXDMA and RS-485 cannot be enabled at the same time for the same U[S]ART" -# endif - /* For the F4, there are alternate DMA channels for USART1 and 6. * Logic in the board.h file make the DMA channel selection by defining * the following in the board.h file. @@ -232,11 +219,6 @@ struct up_dev_s uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */ char *const rxfifo; /* Receive DMA buffer */ #endif - -#ifdef HAVE_RS485 - const uint32_t rs485_dir_gpio; /* U[S]ART RS-485 DIR GPIO pin configuration */ - const bool rs485_dir_polarity; /* U[S]ART RS-485 DIR pin state for TX enabled */ -#endif }; /**************************************************************************** @@ -433,15 +415,6 @@ static struct up_dev_s g_usart1priv = .rxfifo = g_usart1rxfifo, #endif .vector = up_interrupt_usart1, - -#ifdef CONFIG_USART1_RS485 - .rs485_dir_gpio = GPIO_USART1_RS485_DIR, -# if (CONFIG_USART1_RS485_DIR_POLARITY == 0) - .rs485_dir_polarity = false, -# else - .rs485_dir_polarity = true, -# endif -#endif }; #endif @@ -495,15 +468,6 @@ static struct up_dev_s g_usart2priv = .rxfifo = g_usart2rxfifo, #endif .vector = up_interrupt_usart2, - -#ifdef CONFIG_USART2_RS485 - .rs485_dir_gpio = GPIO_USART2_RS485_DIR, -# if (CONFIG_USART2_RS485_DIR_POLARITY == 0) - .rs485_dir_polarity = false, -# else - .rs485_dir_polarity = true, -# endif -#endif }; #endif @@ -557,15 +521,6 @@ static struct up_dev_s g_usart3priv = .rxfifo = g_usart3rxfifo, #endif .vector = up_interrupt_usart3, - -#ifdef CONFIG_USART3_RS485 - .rs485_dir_gpio = GPIO_USART3_RS485_DIR, -# if (CONFIG_USART3_RS485_DIR_POLARITY == 0) - .rs485_dir_polarity = false, -# else - .rs485_dir_polarity = true, -# endif -#endif }; #endif @@ -615,15 +570,6 @@ static struct up_dev_s g_uart4priv = .rxfifo = g_uart4rxfifo, #endif .vector = up_interrupt_uart4, - -#ifdef CONFIG_UART4_RS485 - .rs485_dir_gpio = GPIO_UART4_RS485_DIR, -# if (CONFIG_UART4_RS485_DIR_POLARITY == 0) - .rs485_dir_polarity = false, -# else - .rs485_dir_polarity = true, -# endif -#endif }; #endif @@ -673,15 +619,6 @@ static struct up_dev_s g_uart5priv = .rxfifo = g_uart5rxfifo, #endif .vector = up_interrupt_uart5, - -#ifdef CONFIG_UART5_RS485 - .rs485_dir_gpio = GPIO_UART5_RS485_DIR, -# if (CONFIG_UART5_RS485_DIR_POLARITY == 0) - .rs485_dir_polarity = false, -# else - .rs485_dir_polarity = true, -# endif -#endif }; #endif @@ -735,15 +672,6 @@ static struct up_dev_s g_usart6priv = .rxfifo = g_usart6rxfifo, #endif .vector = up_interrupt_usart6, - -#ifdef CONFIG_USART6_RS485 - .rs485_dir_gpio = GPIO_USART6_RS485_DIR, -# if (CONFIG_USART6_RS485_DIR_POLARITY == 0) - .rs485_dir_polarity = false, -# else - .rs485_dir_polarity = true, -# endif -#endif }; #endif @@ -816,8 +744,8 @@ static void up_restoreusartint(struct up_dev_s *priv, uint16_t ie) /* And restore the interrupt state (see the interrupt enable/usage table above) */ cr = up_serialin(priv, STM32_USART_CR1_OFFSET); - cr &= ~(USART_CR1_USED_INTS); - cr |= (ie & (USART_CR1_USED_INTS)); + cr &= ~(USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE); + cr |= (ie & (USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE)); up_serialout(priv, STM32_USART_CR1_OFFSET, cr); cr = up_serialin(priv, STM32_USART_CR3_OFFSET); @@ -844,7 +772,7 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie) * USART_CR1_IDLEIE 4 USART_SR_IDLE Idle Line Detected (not used) * USART_CR1_RXNEIE 5 USART_SR_RXNE Received Data Ready to be Read * " " USART_SR_ORE Overrun Error Detected - * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485) + * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used) * USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty * USART_CR1_PEIE 8 USART_SR_PE Parity Error * @@ -863,7 +791,7 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie) * overlap. This logic would fail if we needed the break interrupt! */ - *ie = (cr1 & (USART_CR1_USED_INTS)) | (cr3 & USART_CR3_EIE); + *ie = (cr1 & (USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE)) | (cr3 & USART_CR3_EIE); } /* Disable all interrupts */ @@ -1018,14 +946,6 @@ static int up_setup(struct uart_dev_s *dev) stm32_configgpio(priv->rts_gpio); } -#if HAVE_RS485 - if (priv->rs485_dir_gpio != 0) - { - stm32_configgpio(priv->rs485_dir_gpio); - stm32_gpiowrite(priv->rs485_dir_gpio, !priv->rs485_dir_polarity); - } -#endif - /* Configure CR2 */ /* Clear CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */ @@ -1297,7 +1217,7 @@ static int up_interrupt_common(struct up_dev_s *priv) * USART_CR1_IDLEIE 4 USART_SR_IDLE Idle Line Detected (not used) * USART_CR1_RXNEIE 5 USART_SR_RXNE Received Data Ready to be Read * " " USART_SR_ORE Overrun Error Detected - * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485) + * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used) * USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty * USART_CR1_PEIE 8 USART_SR_PE Parity Error * @@ -1312,21 +1232,6 @@ static int up_interrupt_common(struct up_dev_s *priv) * being used. */ -#ifdef HAVE_RS485 - /* Transmission of whole buffer is over - TC is set, TXEIE is cleared. - * Note - this should be first, to have the most recent TC bit value from - * SR register - sending data affects TC, but without refresh we will not - * know that... - */ - - if ((priv->sr & USART_SR_TC) != 0 && (priv->ie & USART_CR1_TCIE) != 0 && - (priv->ie & USART_CR1_TXEIE) == 0) - { - stm32_gpiowrite(priv->rs485_dir_gpio, !priv->rs485_dir_polarity); - up_restoreusartint(priv, priv->ie & ~USART_CR1_TCIE); - } -#endif - /* Handle incoming, receive bytes. */ if ((priv->sr & USART_SR_RXNE) != 0 && (priv->ie & USART_CR1_RXNEIE) != 0) @@ -1360,14 +1265,13 @@ static int up_interrupt_common(struct up_dev_s *priv) if ((priv->sr & USART_SR_TXE) != 0 && (priv->ie & USART_CR1_TXEIE) != 0) { - /* Transmit data register empty ... process outgoing bytes */ + /* Transmit data regiser empty ... process outgoing bytes */ uart_xmitchars(&priv->dev); handled = true; } } - - return OK; + return OK; } /**************************************************************************** @@ -1707,10 +1611,6 @@ static bool up_dma_rxavailable(struct uart_dev_s *dev) static void up_send(struct uart_dev_s *dev, int ch) { struct up_dev_s *priv = (struct up_dev_s*)dev->priv; -#ifdef HAVE_RS485 - if (priv->rs485_dir_gpio != 0) - stm32_gpiowrite(priv->rs485_dir_gpio, priv->rs485_dir_polarity); -#endif up_serialout(priv, STM32_USART_DR_OFFSET, (uint32_t)ch); } @@ -1731,7 +1631,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable) * * Enable Bit Status Meaning Usage * ------------------ --- --------------- ---------------------------- ---------- - * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485) + * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used) * USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty * USART_CR3_CTSIE 10 USART_SR_CTS CTS flag (not used) */ @@ -1742,20 +1642,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable) /* Set to receive an interrupt when the TX data register is empty */ #ifndef CONFIG_SUPPRESS_SERIAL_INTS - uint16_t ie = priv->ie | USART_CR1_TXEIE; - - /* If RS-485 is supported on this U[S]ART, then also enable the - * transmission complete interrupt. - */ - -# ifdef HAVE_RS485 - if (priv->rs485_dir_gpio != 0) - { - ie |= USART_CR1_TCIE; - } -# endif - - up_restoreusartint(priv, ie); + up_restoreusartint(priv, priv->ie | USART_CR1_TXEIE); /* Fake a TX interrupt here by just calling uart_xmitchars() with * interrupts disabled (note this may recurse). @@ -1770,7 +1657,6 @@ static void up_txint(struct uart_dev_s *dev, bool enable) up_restoreusartint(priv, priv->ie & ~USART_CR1_TXEIE); } - irqrestore(flags); } diff --git a/nuttx/arch/arm/src/stm32/stm32_uart.h b/nuttx/arch/arm/src/stm32/stm32_uart.h index 8ff6a9975f..a70923cbf9 100644 --- a/nuttx/arch/arm/src/stm32/stm32_uart.h +++ b/nuttx/arch/arm/src/stm32/stm32_uart.h @@ -223,20 +223,6 @@ # undef SERIAL_HAVE_ONLY_DMA #endif -/* Is RS-485 used? */ - -#if defined(CONFIG_USART1_RS485) || defined(CONFIG_USART2_RS485) || \ - defined(CONFIG_USART3_RS485) || defined(CONFIG_UART4_RS485) || \ - defined(CONFIG_UART5_RS485) || defined(CONFIG_USART6_RS485) -# define HAVE_RS485 1 -#endif - -#ifdef HAVE_RS485 -# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE | USART_CR1_TCIE) -#else -# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE) -#endif - /************************************************************************************ * Public Types ************************************************************************************/ diff --git a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c index ae3fa516ea..47ed5e016b 100644 --- a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c +++ b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c @@ -92,11 +92,7 @@ static inline void rcc_reset(void) putreg32(regval, STM32_RCC_CR); regval = getreg32(STM32_RCC_CFGR); /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */ - regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK -#ifndef CONFIG_STM32_VALUELINE - |RCC_CFGR_USBPRE -#endif - ); + regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK|RCC_CFGR_USBPRE); putreg32(regval, STM32_RCC_CFGR); putreg32(0, STM32_RCC_CIR); /* Disable all interrupts */ @@ -228,27 +224,6 @@ static inline void rcc_enableapb1(void) #endif #endif -#ifdef CONFIG_STM32_TIM12 - /* Timer 12 clock enable */ -#ifdef CONFIG_STM32_FORCEPOWER - regval |= RCC_APB1ENR_TIM12EN; -#endif -#endif - -#ifdef CONFIG_STM32_TIM13 - /* Timer 13 clock enable */ -#ifdef CONFIG_STM32_FORCEPOWER - regval |= RCC_APB1ENR_TIM13EN; -#endif -#endif - -#ifdef CONFIG_STM32_TIM14 - /* Timer 14 clock enable */ -#ifdef CONFIG_STM32_FORCEPOWER - regval |= RCC_APB1ENR_TIM14EN; -#endif -#endif - #ifdef CONFIG_STM32_WWDG /* Window Watchdog clock enable */ @@ -340,13 +315,6 @@ static inline void rcc_enableapb1(void) regval |= RCC_APB1ENR_DACEN; #endif - -#ifdef CONFIG_STM32_CEC - /* CEC clock enable */ - - regval |= RCC_APB1ENR_CECEN; -#endif - putreg32(regval, STM32_RCC_APB1ENR); } @@ -436,28 +404,6 @@ static inline void rcc_enableapb2(void) regval |= RCC_APB2ENR_ADC3EN; #endif - -#ifdef CONFIG_STM32_TIM15 - /* TIM15 Timer clock enable */ -#ifdef CONFIG_STM32_FORCEPOWER - regval |= RCC_APB2ENR_TIM15EN; -#endif -#endif - -#ifdef CONFIG_STM32_TIM16 - /* TIM16 Timer clock enable */ -#ifdef CONFIG_STM32_FORCEPOWER - regval |= RCC_APB2ENR_TIM16EN; -#endif -#endif - -#ifdef CONFIG_STM32_TIM17 - /* TIM17 Timer clock enable */ -#ifdef CONFIG_STM32_FORCEPOWER - regval |= RCC_APB2ENR_TIM17EN; -#endif -#endif - putreg32(regval, STM32_RCC_APB2ENR); } diff --git a/nuttx/binfmt/Kconfig b/nuttx/binfmt/Kconfig index ae02c276a1..ae2bf31307 100644 --- a/nuttx/binfmt/Kconfig +++ b/nuttx/binfmt/Kconfig @@ -2,45 +2,3 @@ # For a description of the syntax of this configuration file, # see misc/tools/kconfig-language.txt. # - -config BINFMT_DISABLE - bool "Disble BINFMT support" - default n - ---help--- - By default, support for loadable binary formats is built. This logic - may be suppressed be defining this setting. - -if !BINFMT_DISABLE - -config NXFLAT - bool "Enable the NXFLAT Binary Format" - default n - ---help--- - Enable support for the NXFLAT binary format. Default: n - -if NXFLAT -source binfmt/libnxflat/Kconfig -endif - -config ELF - bool "Enable the ELF Binary Format" - default n - ---help--- - Enable support for the ELF binary format. Default: n - -if ELF -source binfmt/libelf/Kconfig -endif - -endif - -config BINFMT_CONSTRUCTORS - bool "C++ Static Constructor Support" - default n - depends on HAVE_CXX && ELF # FIX ME: Currently only supported for ELF - ---help--- - Build in support for C++ constructors in loaded modules. - -config SYMTAB_ORDEREDBYNAME - bool "Symbol Tables Ordered by Name" - default n diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile index 932a5ec13b..b3a9269b30 100644 --- a/nuttx/binfmt/Makefile +++ b/nuttx/binfmt/Makefile @@ -1,7 +1,7 @@ ############################################################################ # nxflat/Makefile # -# Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -36,62 +36,67 @@ -include $(TOPDIR)/Make.defs ifeq ($(WINTOOL),y) -INCDIROPT = -w +INCDIROPT = -w endif -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" "$(TOPDIR)$(DELIM)sched"} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/sched} -# Basic BINFMT source files +ifeq ($(CONFIG_NXFLAT),y) +include libnxflat/Make.defs +LIBNXFLAT_CSRCS += nxflat.c +endif -BINFMT_ASRCS = -BINFMT_CSRCS = binfmt_globals.c binfmt_register.c binfmt_unregister.c \ - binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_execmodule.c \ - binfmt_exec.c binfmt_dumpmodule.c +BINFMT_ASRCS = +BINFMT_CSRCS = binfmt_globals.c binfmt_register.c binfmt_unregister.c \ + binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_execmodule.c \ + binfmt_exec.c binfmt_dumpmodule.c -# Symbol table source files +SYMTAB_ASRCS = +SYMTAB_CSRCS = symtab_findbyname.c symtab_findbyvalue.c \ + symtab_findorderedbyname.c symtab_findorderedbyvalue.c -BINFMT_CSRCS += symtab_findbyname.c symtab_findbyvalue.c \ - symtab_findorderedbyname.c symtab_findorderedbyvalue.c +SUBDIRS = libnxflat -# Add configured binary modules +ASRCS = $(BINFMT_ASRCS) $(SYMTAB_ASRCS) $(LIBNXFLAT_ASRCS) +AOBJS = $(ASRCS:.S=$(OBJEXT)) -VPATH = -SUBDIRS = -DEPPATH = --dep-path . +CSRCS = $(BINFMT_CSRCS) $(SYMTAB_CSRCS) $(LIBNXFLAT_CSRCS) +COBJS = $(CSRCS:.c=$(OBJEXT)) -include libnxflat$(DELIM)Make.defs -include libelf$(DELIM)Make.defs +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) -BINFMT_AOBJS = $(BINFMT_ASRCS:.S=$(OBJEXT)) -BINFMT_COBJS = $(BINFMT_CSRCS:.c=$(OBJEXT)) +BIN = libbinfmt$(LIBEXT) -BINFMT_SRCS = $(BINFMT_ASRCS) $(BINFMT_CSRCS) -BINFMT_OBJS = $(BINFMT_AOBJS) $(BINFMT_COBJS) +VPATH = libnxflat -BIN = libbinfmt$(LIBEXT) +all: $(BIN) -all: $(BIN) - -$(BINFMT_AOBJS): %$(OBJEXT): %.S +$(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) -$(BINFMT_COBJS): %$(OBJEXT): %.c +$(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) -$(BIN): $(BINFMT_OBJS) - $(call ARCHIVE, $@, $(BINFMT_OBJS)) +$(BIN): $(OBJS) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) -.depend: Makefile $(BINFMT_SRCS) - $(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep - $(Q) touch $@ +.depend: Makefile $(SRCS) + @$(MKDEP) --dep-path . --dep-path libnxflat \ + $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, $(BIN)) + @rm -f $(BIN) *~ .*.swp $(call CLEAN) + @( for dir in $(SUBDIRS); do \ + rm -f $${dir}/*~ $${dir}/.*.swp; \ + done ; ) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/nuttx/binfmt/binfmt_dumpmodule.c b/nuttx/binfmt/binfmt_dumpmodule.c index 40cbe4b213..32a3fef3e3 100644 --- a/nuttx/binfmt/binfmt_dumpmodule.c +++ b/nuttx/binfmt/binfmt_dumpmodule.c @@ -1,7 +1,7 @@ /**************************************************************************** * binfmt/binfmt_dumpmodule.c * - * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -43,7 +43,7 @@ #include #include -#include +#include #include "binfmt_internal.h" @@ -90,12 +90,8 @@ int dump_module(FAR const struct binary_s *bin) bdbg(" filename: %s\n", bin->filename); bdbg(" argv: %p\n", bin->argv); bdbg(" entrypt: %p\n", bin->entrypt); - bdbg(" mapped: %p size=%d\n", bin->mapped, bin->mapsize); - bdbg(" alloc: %p %p %p\n", bin->alloc[0], bin->alloc[1], bin->alloc[2]); -#ifdef CONFIG_BINFMT_CONSTRUCTORS - bdbg(" ctors: %p nctors=%d\n", bin->ctors, bin->nctors); - bdbg(" dtors: %p ndtors=%d\n", bin->dtors, bin->ndtors); -#endif + bdbg(" ispace: %p size=%d\n", bin->ispace, bin->isize); + bdbg(" dspace: %p\n", bin->dspace); bdbg(" stacksize: %d\n", bin->stacksize); } return OK; diff --git a/nuttx/binfmt/binfmt_exec.c b/nuttx/binfmt/binfmt_exec.c index 60e8d8efde..c070324c31 100644 --- a/nuttx/binfmt/binfmt_exec.c +++ b/nuttx/binfmt/binfmt_exec.c @@ -44,7 +44,7 @@ #include #include -#include +#include #include "binfmt_internal.h" diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c index 37f4459660..1b511b0cb8 100644 --- a/nuttx/binfmt/binfmt_execmodule.c +++ b/nuttx/binfmt/binfmt_execmodule.c @@ -47,7 +47,7 @@ #include #include -#include +#include #include "os_internal.h" #include "binfmt_internal.h" @@ -70,39 +70,6 @@ * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: exec_ctors - * - * Description: - * Execute C++ static constructors. - * - * Input Parameters: - * loadinfo - Load state information - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -#ifdef CONFIG_BINFMT_CONSTRUCTORS -static inline void exec_ctors(FAR const struct binary_s *binp) -{ - binfmt_ctor_t *ctor = binp->ctors; - int i; - - /* Execute each constructor */ - - for (i = 0; i < binp->nctors; i++) - { - bvdbg("Calling ctor %d at %p\n", i, (FAR void *)ctor); - - (*ctor)(); - ctor++; - } -} -#endif - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -120,7 +87,7 @@ static inline void exec_ctors(FAR const struct binary_s *binp) * ****************************************************************************/ -int exec_module(FAR const struct binary_s *binp, int priority) +int exec_module(FAR const struct binary_s *bin, int priority) { FAR _TCB *tcb; #ifndef CONFIG_CUSTOM_STACK @@ -133,14 +100,14 @@ int exec_module(FAR const struct binary_s *binp, int priority) /* Sanity checking */ #ifdef CONFIG_DEBUG - if (!binp || !binp->entrypt || binp->stacksize <= 0) + if (!bin || !bin->ispace || !bin->entrypt || bin->stacksize <= 0) { err = EINVAL; goto errout; } #endif - bdbg("Executing %s\n", binp->filename); + bdbg("Executing %s\n", bin->filename); /* Allocate a TCB for the new task. */ @@ -154,7 +121,7 @@ int exec_module(FAR const struct binary_s *binp, int priority) /* Allocate the stack for the new task */ #ifndef CONFIG_CUSTOM_STACK - stack = (FAR uint32_t*)malloc(binp->stacksize); + stack = (FAR uint32_t*)malloc(bin->stacksize); if (!tcb) { err = ENOMEM; @@ -163,13 +130,11 @@ int exec_module(FAR const struct binary_s *binp, int priority) /* Initialize the task */ - ret = task_init(tcb, binp->filename, priority, stack, - binp->stacksize, binp->entrypt, binp->argv); + ret = task_init(tcb, bin->filename, priority, stack, bin->stacksize, bin->entrypt, bin->argv); #else /* Initialize the task */ - ret = task_init(tcb, binp->filename, priority, stack, - binp->entrypt, binp->argv); + ret = task_init(tcb, bin->filename, priority, stack, bin->entrypt, bin->argv); #endif if (ret < 0) { @@ -178,12 +143,10 @@ int exec_module(FAR const struct binary_s *binp, int priority) goto errout_with_stack; } - /* Add the D-Space address as the PIC base address. By convention, this - * must be the first allocated address space. - */ + /* Add the DSpace address as the PIC base address */ #ifdef CONFIG_PIC - tcb->dspace = binp->alloc[0]; + tcb->dspace = bin->dspace; /* Re-initialize the task's initial state to account for the new PIC base */ @@ -194,12 +157,6 @@ int exec_module(FAR const struct binary_s *binp, int priority) pid = tcb->pid; - /* Execute all of the C++ static constructors */ - -#ifdef CONFIG_BINFMT_CONSTRUCTORS - exec_ctors(binp); -#endif - /* Then activate the task at the provided priority */ ret = task_activate(tcb); @@ -209,7 +166,6 @@ int exec_module(FAR const struct binary_s *binp, int priority) bdbg("task_activate() failed: %d\n", err); goto errout_with_stack; } - return (int)pid; errout_with_stack: diff --git a/nuttx/binfmt/binfmt_globals.c b/nuttx/binfmt/binfmt_globals.c index d3246bd506..069d3a2aa9 100644 --- a/nuttx/binfmt/binfmt_globals.c +++ b/nuttx/binfmt/binfmt_globals.c @@ -39,7 +39,7 @@ #include -#include +#include #ifndef CONFIG_BINFMT_DISABLE diff --git a/nuttx/binfmt/binfmt_internal.h b/nuttx/binfmt/binfmt_internal.h index 4fab9724d4..da67f5350b 100644 --- a/nuttx/binfmt/binfmt_internal.h +++ b/nuttx/binfmt/binfmt_internal.h @@ -42,7 +42,7 @@ #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/binfmt_loadmodule.c b/nuttx/binfmt/binfmt_loadmodule.c index e87075aa90..01ab8cc883 100644 --- a/nuttx/binfmt/binfmt_loadmodule.c +++ b/nuttx/binfmt/binfmt_loadmodule.c @@ -43,7 +43,7 @@ #include #include -#include +#include #include "binfmt_internal.h" diff --git a/nuttx/binfmt/binfmt_register.c b/nuttx/binfmt/binfmt_register.c index 925f29353f..7f6eef671a 100644 --- a/nuttx/binfmt/binfmt_register.c +++ b/nuttx/binfmt/binfmt_register.c @@ -44,7 +44,7 @@ #include #include -#include +#include #include "binfmt_internal.h" diff --git a/nuttx/binfmt/binfmt_unloadmodule.c b/nuttx/binfmt/binfmt_unloadmodule.c index 52243fcf78..04859a2910 100644 --- a/nuttx/binfmt/binfmt_unloadmodule.c +++ b/nuttx/binfmt/binfmt_unloadmodule.c @@ -1,7 +1,7 @@ /**************************************************************************** * binfmt/binfmt_loadmodule.c * - * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -45,7 +45,7 @@ #include #include -#include +#include #include "binfmt_internal.h" @@ -67,39 +67,6 @@ * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: exec_dtors - * - * Description: - * Execute C++ static constructors. - * - * Input Parameters: - * loadinfo - Load state information - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -#ifdef CONFIG_BINFMT_CONSTRUCTORS -static inline void exec_dtors(FAR const struct binary_s *binp) -{ - binfmt_dtor_t *dtor = binp->dtors; - int i; - - /* Execute each destructor */ - - for (i = 0; i < binp->ndtors; i++) - { - bvdbg("Calling dtor %d at %p\n", i, (FAR void *)dtor); - - (*dtor)(); - dtor++; - } -} -#endif - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -109,12 +76,7 @@ static inline void exec_dtors(FAR const struct binary_s *binp) * * Description: * Unload a (non-executing) module from memory. If the module has - * been started (via exec_module) and has not exited, calling this will - * be fatal. - * - * However, this function must be called after the module exist. How - * this is done is up to your logic. Perhaps you register it to be - * called by on_exit()? + * been started (via exec_module), calling this will be fatal. * * Returned Value: * This is a NuttX internal function so it follows the convention that @@ -123,40 +85,22 @@ static inline void exec_dtors(FAR const struct binary_s *binp) * ****************************************************************************/ -int unload_module(FAR const struct binary_s *binp) +int unload_module(FAR const struct binary_s *bin) { - int i; - - if (binp) + if (bin) { - - /* Execute C++ desctructors */ - -#ifdef CONFIG_BINFMT_CONSTRUCTORS - exec_dtors(binp); -#endif - - /* Unmap mapped address spaces */ - - if (binp->mapped) + if (bin->ispace) { - bvdbg("Unmapping address space: %p\n", binp->mapped); - - munmap(binp->mapped, binp->mapsize); + bvdbg("Unmapping ISpace: %p\n", bin->ispace); + munmap(bin->ispace, bin->isize); } - /* Free allocated address spaces */ - - for (i = 0; i < BINFMT_NALLOC; i++) + if (bin->dspace) { - if (binp->alloc[i]) - { - bvdbg("Freeing alloc[%d]: %p\n", i, binp->alloc[i]); - free(binp->alloc[i]); - } + bvdbg("Freeing DSpace: %p\n", bin->dspace); + free(bin->dspace); } } - return OK; } diff --git a/nuttx/binfmt/binfmt_unregister.c b/nuttx/binfmt/binfmt_unregister.c index f895e354d0..b97b9b67dd 100644 --- a/nuttx/binfmt/binfmt_unregister.c +++ b/nuttx/binfmt/binfmt_unregister.c @@ -44,7 +44,7 @@ #include #include -#include +#include #include "binfmt_internal.h" diff --git a/nuttx/binfmt/libnxflat/Kconfig b/nuttx/binfmt/libnxflat/Kconfig index fdb270cfb2..ae2bf31307 100644 --- a/nuttx/binfmt/libnxflat/Kconfig +++ b/nuttx/binfmt/libnxflat/Kconfig @@ -2,8 +2,3 @@ # For a description of the syntax of this configuration file, # see misc/tools/kconfig-language.txt. # - -config NXFLAT_DUMPBUFFER - bool "Dump NXFLAT buffers" - default n - depends on DEBUG && DEBUG_VERBOSE diff --git a/nuttx/binfmt/libnxflat/Make.defs b/nuttx/binfmt/libnxflat/Make.defs index 4f522e52b2..f979741e51 100644 --- a/nuttx/binfmt/libnxflat/Make.defs +++ b/nuttx/binfmt/libnxflat/Make.defs @@ -1,5 +1,5 @@ ############################################################################ -# binfmt/libnxflat/Make.defs +# nxflat/lib/Make.defs # # Copyright (C) 2009 Gregory Nutt. All rights reserved. # Author: Gregory Nutt @@ -33,22 +33,7 @@ # ############################################################################ -ifeq ($(CONFIG_NXFLAT),y) - -# NXFLAT application interfaces - -BINFMT_CSRCS += nxflat.c - -# NXFLAT library - -BINFMT_CSRCS += libnxflat_init.c libnxflat_uninit.c libnxflat_load.c \ - libnxflat_unload.c libnxflat_verify.c libnxflat_read.c \ - libnxflat_bind.c - -# Hook the libnxflat subdirectory into the build - -VPATH += libnxflat -SUBDIRS += libnxflat -DEPPATH += --dep-path libnxflat - -endif +LIBNXFLAT_ASRCS = +LIBNXFLAT_CSRCS = libnxflat_init.c libnxflat_uninit.c libnxflat_load.c \ + libnxflat_unload.c libnxflat_verify.c libnxflat_read.c \ + libnxflat_bind.c diff --git a/nuttx/binfmt/libnxflat/libnxflat_bind.c b/nuttx/binfmt/libnxflat/libnxflat_bind.c index 2b9f647159..ca348178dd 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_bind.c +++ b/nuttx/binfmt/libnxflat/libnxflat_bind.c @@ -47,8 +47,8 @@ #include #include -#include -#include +#include +#include /**************************************************************************** * Pre-processor Definitions @@ -263,6 +263,7 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo) result = OK; switch (NXFLAT_RELOC_TYPE(reloc.r_info)) { + /* NXFLAT_RELOC_TYPE_REL32I Meaning: Object file contains a 32-bit offset * into I-Space at the offset. * Fixup: Add mapped I-Space address to the offset. @@ -328,7 +329,6 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo) nxflat_dumpbuffer("GOT", (FAR const uint8_t*)relocs, nrelocs * sizeof(struct nxflat_reloc_s)); } #endif - return ret; } @@ -388,7 +388,7 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo, offset < loadinfo->isize + loadinfo->dsize); imports = (struct nxflat_import_s*) - (offset - loadinfo->isize + loadinfo->dspace->region); + (offset - loadinfo->isize + loadinfo->dspace->region); /* Now, traverse the list of imported symbols and attempt to bind * each symbol to the value exported by from the exported symbol @@ -396,41 +396,41 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo, */ for (i = 0; i < nimports; i++) - { - bvdbg("Import[%d] (%08p) offset: %08x func: %08x\n", - i, &imports[i], imports[i].i_funcname, imports[i].i_funcaddress); + { + bvdbg("Import[%d] (%08p) offset: %08x func: %08x\n", + i, &imports[i], imports[i].i_funcname, imports[i].i_funcaddress); - /* Get a pointer to the imported symbol name. The name itself - * lies in the TEXT segment. But the reference to the name - * lies in DATA segment. Therefore, the name reference should - * have been relocated when the module was loaded. - */ + /* Get a pointer to the imported symbol name. The name itself + * lies in the TEXT segment. But the reference to the name + * lies in DATA segment. Therefore, the name reference should + * have been relocated when the module was loaded. + */ offset = imports[i].i_funcname; DEBUGASSERT(offset < loadinfo->isize); - symname = (char*)(offset + loadinfo->ispace + sizeof(struct nxflat_hdr_s)); + symname = (char*)(offset + loadinfo->ispace + sizeof(struct nxflat_hdr_s)); - /* Find the exported symbol value for this this symbol name. */ + /* Find the exported symbol value for this this symbol name. */ #ifdef CONFIG_SYMTAB_ORDEREDBYNAME symbol = symtab_findorderedbyname(exports, symname, nexports); #else symbol = symtab_findbyname(exports, symname, nexports); #endif - if (!symbol) - { - bdbg("Exported symbol \"%s\" not found\n", symname); + if (!symbol) + { + bdbg("Exported symbol \"%s\" not found\n", symname); return -ENOENT; - } + } - /* And put this into the module's import structure. */ + /* And put this into the module's import structure. */ - imports[i].i_funcaddress = (uint32_t)symbol->sym_value; + imports[i].i_funcaddress = (uint32_t)symbol->sym_value; - bvdbg("Bound import[%d] (%08p) to export '%s' (%08x)\n", - i, &imports[i], symname, imports[i].i_funcaddress); - } + bvdbg("Bound import[%d] (%08p) to export '%s' (%08x)\n", + i, &imports[i], symname, imports[i].i_funcaddress); + } } /* Dump the relocation import table */ @@ -441,7 +441,6 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo, nxflat_dumpbuffer("Imports", (FAR const uint8_t*)imports, nimports * sizeof(struct nxflat_import_s)); } #endif - return OK; } @@ -485,10 +484,9 @@ int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo, */ memset((void*)(loadinfo->dspace->region + loadinfo->datasize), - 0, loadinfo->bsssize); + 0, loadinfo->bsssize); } } - return ret; } diff --git a/nuttx/binfmt/libnxflat/libnxflat_init.c b/nuttx/binfmt/libnxflat/libnxflat_init.c index b7cac8d866..5b6375ff16 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_init.c +++ b/nuttx/binfmt/libnxflat/libnxflat_init.c @@ -48,7 +48,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions @@ -112,9 +112,8 @@ int nxflat_init(const char *filename, struct nxflat_loadinfo_s *loadinfo) loadinfo->filfd = open(filename, O_RDONLY); if (loadinfo->filfd < 0) { - int errval = errno; - bdbg("Failed to open NXFLAT binary %s: %d\n", filename, errval); - return -errval; + bdbg("Failed to open NXFLAT binary %s: %d\n", filename, ret); + return -errno; } /* Read the NXFLAT header from offset 0 */ diff --git a/nuttx/binfmt/libnxflat/libnxflat_load.c b/nuttx/binfmt/libnxflat/libnxflat_load.c index b6693ea36a..0991d0c2d7 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_load.c +++ b/nuttx/binfmt/libnxflat/libnxflat_load.c @@ -48,7 +48,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions @@ -62,6 +62,24 @@ * Private Constant Data ****************************************************************************/ +#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_BINFMT) +static const char g_relocrel32i[] = "RELOC_REL32I"; +static const char g_relocrel32d[] = "RELOC_REL32D"; +static const char g_relocabs32[] = "RELOC_AB32"; +static const char g_undefined[] = "UNDEFINED"; + +static const char *g_reloctype[] = +{ + g_relocrel32i, + g_relocrel32d, + g_relocabs32, + g_undefined +}; +# define RELONAME(rl) g_reloctype[NXFLAT_RELOC_TYPE(rl)] +#else +# define RELONAME(rl) "(no name)" +#endif + /**************************************************************************** * Private Functions ****************************************************************************/ diff --git a/nuttx/binfmt/libnxflat/libnxflat_read.c b/nuttx/binfmt/libnxflat/libnxflat_read.c index 8deeb0805e..dbcd542791 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_read.c +++ b/nuttx/binfmt/libnxflat/libnxflat_read.c @@ -48,7 +48,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions @@ -129,9 +129,8 @@ int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, int readsize, rpos = lseek(loadinfo->filfd, offset, SEEK_SET); if (rpos != offset) { - int errval = errno; - bdbg("Failed to seek to position %d: %d\n", offset, errval); - return -errval; + bdbg("Failed to seek to position %d: %d\n", offset, errno); + return -errno; } /* Read the file data at offset into the user buffer */ @@ -139,11 +138,10 @@ int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, int readsize, nbytes = read(loadinfo->filfd, bufptr, bytesleft); if (nbytes < 0) { - int errval = errno; - if (errval != EINTR) + if (errno != EINTR) { - bdbg("Read of .data failed: %d\n", errval); - return -errval; + bdbg("Read of .data failed: %d\n", errno); + return -errno; } } else if (nbytes == 0) diff --git a/nuttx/binfmt/libnxflat/libnxflat_uninit.c b/nuttx/binfmt/libnxflat/libnxflat_uninit.c index b9715196b9..5d06296c79 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_uninit.c +++ b/nuttx/binfmt/libnxflat/libnxflat_uninit.c @@ -42,8 +42,7 @@ #include #include #include - -#include +#include /**************************************************************************** * Pre-Processor Definitions @@ -57,6 +56,10 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: nxflat_swap32 + ****************************************************************************/ + /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/nuttx/binfmt/libnxflat/libnxflat_unload.c b/nuttx/binfmt/libnxflat/libnxflat_unload.c index 47c30bd55f..55a2e45e60 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_unload.c +++ b/nuttx/binfmt/libnxflat/libnxflat_unload.c @@ -43,7 +43,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/nuttx/binfmt/libnxflat/libnxflat_verify.c b/nuttx/binfmt/libnxflat/libnxflat_verify.c index 20af5d2f74..f799aca4f6 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_verify.c +++ b/nuttx/binfmt/libnxflat/libnxflat_verify.c @@ -42,9 +42,8 @@ #include #include #include - #include -#include +#include /**************************************************************************** * Pre-processor Definitions @@ -92,10 +91,10 @@ int nxflat_verifyheader(const struct nxflat_hdr_s *header) if (strncmp(header->h_magic, NXFLAT_MAGIC, 4) != 0) { bdbg("Unrecognized magic=\"%c%c%c%c\"\n", - header->h_magic[0], header->h_magic[1], - header->h_magic[2], header->h_magic[3]); + header->h_magic[0], header->h_magic[1], + header->h_magic[2], header->h_magic[3]); return -ENOEXEC; } - return OK; } + diff --git a/nuttx/binfmt/nxflat.c b/nuttx/binfmt/nxflat.c index 5973a96a98..4f5869bd92 100644 --- a/nuttx/binfmt/nxflat.c +++ b/nuttx/binfmt/nxflat.c @@ -47,8 +47,8 @@ #include #include -#include -#include +#include +#include #ifdef CONFIG_NXFLAT @@ -158,7 +158,7 @@ static int nxflat_loadbinary(struct binary_s *binp) nxflat_dumploadinfo(&loadinfo); if (ret != 0) { - bdbg("Failed to initialize for load of NXFLAT program: %d\n", ret); + bdbg("Failed to initialize for load of NXFLT program: %d\n", ret); goto errout; } @@ -168,7 +168,7 @@ static int nxflat_loadbinary(struct binary_s *binp) nxflat_dumploadinfo(&loadinfo); if (ret != 0) { - bdbg("Failed to load NXFLAT program binary: %d\n", ret); + bdbg("Failed to load NXFLT program binary: %d\n", ret); goto errout_with_init; } @@ -181,18 +181,16 @@ static int nxflat_loadbinary(struct binary_s *binp) goto errout_with_load; } - /* Return the load information. By convention, D-space address - * space is stored as the first allocated memory. - */ + /* Return the load information */ binp->entrypt = (main_t)(loadinfo.ispace + loadinfo.entryoffs); - binp->mapped = (void*)loadinfo.ispace; - binp->alloc[0] = (void*)loadinfo.dspace; - binp->mapsize = loadinfo.isize; + binp->ispace = (void*)loadinfo.ispace; + binp->dspace = (void*)loadinfo.dspace; + binp->isize = loadinfo.isize; binp->stacksize = loadinfo.stacksize; nxflat_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt, - MIN(loadinfo.isize - loadinfo.entryoffs, 512)); + MIN(binp->isize - loadinfo.entryoffs,512)); nxflat_uninit(&loadinfo); return OK; diff --git a/nuttx/binfmt/symtab_findbyname.c b/nuttx/binfmt/symtab_findbyname.c index c0343e2708..201d7ba07d 100644 --- a/nuttx/binfmt/symtab_findbyname.c +++ b/nuttx/binfmt/symtab_findbyname.c @@ -44,7 +44,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/symtab_findbyvalue.c b/nuttx/binfmt/symtab_findbyvalue.c index c47d5c7518..4382ed5d8d 100644 --- a/nuttx/binfmt/symtab_findbyvalue.c +++ b/nuttx/binfmt/symtab_findbyvalue.c @@ -44,7 +44,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/symtab_findorderedbyname.c b/nuttx/binfmt/symtab_findorderedbyname.c index a678788e78..61decf49ad 100644 --- a/nuttx/binfmt/symtab_findorderedbyname.c +++ b/nuttx/binfmt/symtab_findorderedbyname.c @@ -44,7 +44,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/binfmt/symtab_findorderedbyvalue.c b/nuttx/binfmt/symtab_findorderedbyvalue.c index bad4bf8cd7..92b107856d 100644 --- a/nuttx/binfmt/symtab_findorderedbyvalue.c +++ b/nuttx/binfmt/symtab_findorderedbyvalue.c @@ -44,7 +44,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index b7d9f84d1e..e6bde645d1 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -103,23 +103,14 @@ Make.defs -- This makefile fragment provides architecture and Tools: CC, LD, AR, NM, OBJCOPY, OBJDUMP Tool options: CFLAGS, LDFLAGS + COMPILE, ASSEMBLE, ARCHIVE, CLEAN, and MKDEP macros When this makefile fragment runs, it will be passed TOPDIR which is the path to the root directory of the build. This makefile - fragment should include: - - $(TOPDIR)/.config : Nuttx configuration - $(TOPDIR)/tools/Config.mk : Common definitions - - Definitions in the Make.defs file probably depend on some of the - settings in the .config file. For example, the CFLAGS will most likely be + fragment may include ${TOPDIR}/.config to perform configuration + specific settings. For example, the CFLAGS will most likely be different if CONFIG_DEBUG=y. - The included tools/Config.mk file contains additional definitions that may - be overriden in the architecture-specific Make.defs file as necessary: - - COMPILE, ASSEMBLE, ARCHIVE, CLEAN, and MKDEP macros - defconfig -- This is a configuration file similar to the Linux configuration file. In contains variable/value pairs like: @@ -180,6 +171,7 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_RAW_BINARY - make a raw binary format file used with many different loaders using the GNU objcopy program. This option should not be selected if you are not using the GNU toolchain. + CONFIG_HAVE_LIBM - toolchain supports libm.a CONFIG_HAVE_CXX - toolchain supports C++ and CXX, CXXFLAGS, and COMPILEXX have been defined in the configurations Make.defs file. @@ -326,7 +318,7 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_RR_INTERVAL - The round robin timeslice will be set this number of milliseconds; Round robin scheduling can be disabled by setting this value to zero. - CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in + CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in scheduler to monitor system performance CONFIG_TASK_NAME_SIZE - Specifies that maximum size of a task name to save in the TCB. Useful if scheduler @@ -354,7 +346,7 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority inheritance is enabled. It defines the maximum number of different threads (minus one) that can take counts on a - semaphore with priority inheritance support. This may be + semaphore with priority inheritance support. This may be set to zero if priority inheritance is disabled OR if you are only using semaphores as mutexes (only one holder) OR if no more than two threads participate using a counting @@ -380,6 +372,9 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_SDCLONE_DISABLE. Disable cloning of all socket desciptors by task_create() when a new task is started. If set, all sockets will appear to be closed in the new task. + CONFIG_NXFLAT. Enable support for the NXFLAT binary format. + This format will support execution of NuttX binaries located + in a ROMFS filesystem (see examples/nxflat). CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to handle delayed processing from interrupt handlers. This feature is required for some drivers but, if there are not complaints, @@ -423,39 +418,6 @@ defconfig -- This is a configuration file similar to the Linux where 'app' is the application name. If not defined, CONFIG_USER_ENTRYPOINT defaults to user_start. - Binary Loaders: - CONFIG_BINFMT_DISABLE - By default, support for loadable binary formats - is built. - This logic may be suppressed be defining this setting. - CONFIG_BINFMT_CONSTRUCTORS - Build in support for C++ constructors in - loaded modules. - CONFIG_SYMTAB_ORDEREDBYNAME - Symbol tables are order by name (rather - than value). - CONFIG_NXFLAT. Enable support for the NXFLAT binary format. This format - will support execution of NuttX binaries located in a ROMFS filesystem - (see apps/examples/nxflat). - CONFIG_ELF - Enable support for the ELF binary format. This format will - support execution of ELF binaries copied from a file system and - relocated into RAM (see apps/examples/elf). - - If CONFIG_ELF is selected, then these additional options are available: - - CONFIG_ELF_ALIGN_LOG2 - Align all sections to this Log2 value: 0->1, - 1->2, 2->4, etc. - CONFIG_ELF_STACKSIZE - This is the default stack size that will will - be used when starting ELF binaries. - CONFIG_ELF_BUFFERSIZE - This is an I/O buffer that is used to access - the ELF file. Variable length items will need to be read (such as - symbol names). This is really just this initial size of the buffer; - it will be reallocated as necessary to hold large symbol names). - Default: 128 - CONFIG_ELF_BUFFERINCR - This is an I/O buffer that is used to access - the ELF file. Variable length items will need to be read (such as - symbol names). This value specifies the size increment to use each - time the buffer is reallocated. Default: 32 - CONFIG_ELF_DUMPBUFFER - Dump various ELF buffers for debug purposes. - This option requires CONFIG_DEBUG and CONFIG_DEBUG_VERBOSE. - System Logging: CONFIG_SYSLOG enables general system logging support. CONFIG_SYSLOG_DEVPATH - The full path to the system logging device. Default @@ -541,7 +503,7 @@ defconfig -- This is a configuration file similar to the Linux from the end of RAM for page tables or other system usage. The configuration settings and linker directives must be cognizant of that: CONFIG_PAGING_NDATA should be defined to prevent the data region from - extending all the way to the end of memory. + extending all the way to the end of memory. CONFIG_PAGING_DEFPRIO - The default, minimum priority of the page fill worker thread. The priority of the page fill work thread will be boosted boosted dynmically so that it matches the priority of the task on behalf @@ -555,7 +517,7 @@ defconfig -- This is a configuration file similar to the Linux transfer is completed. Default: Undefined (non-blocking). CONFIG_PAGING_WORKPERIOD - The page fill worker thread will wake periodically even if there is no mapping to do. This selection controls that wake-up - period (in microseconds). This wake-up a failsafe that will handle any + period (in microseconds). This wake-up a failsafe that will handle any cases where a single is lost (that would really be a bug and shouldn't happen!) and also supports timeouts for case of non-blocking, asynchronous fills (see CONFIG_PAGING_TIMEOUT_TICKS). @@ -567,7 +529,7 @@ defconfig -- This is a configuration file similar to the Linux Some architecture-specific settings. Defaults are architecture specific. If you don't know what you are doing, it is best to leave these undefined and try the system defaults: - + CONFIG_PAGING_VECPPAGE - This the physical address of the page in memory to be mapped to the vector address. CONFIG_PAGING_VECL2PADDR - This is the physical address of the L2 @@ -590,7 +552,7 @@ defconfig -- This is a configuration file similar to the Linux devices. CONFIG_PAGING_SDSLOT identifies the slot number of the SD device to initialize. This must be undefined if SD is not being used. This should be defined to be zero for the typical device that has - only a single slot (See CONFIG_MMCSD_NSLOTS). If defined, + only a single slot (See CONFIG_MMCSD_NSLOTS). If defined, CONFIG_PAGING_SDSLOT will instruct certain board-specific logic to initialize the media in this SD slot. CONFIG_PAGING_M25PX - Use the m25px.c FLASH driver. If this is selected, @@ -659,37 +621,6 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_ARCH_STRNCPY, CONFIG_ARCH_STRLEN, CONFIG_ARCH_STRNLEN CONFIG_ARCH_BZERO - If CONFIG_ARCH_MEMCPY is not selected, then you make also select Daniel - Vik's optimized implementation of memcpy(): - - CONFIG_MEMCPY_VIK - Select this option to use the optimized memcpy() - function by Daniel Vik. Select this option for improved performance - at the expense of increased size. See licensing information in the - top-level COPYING file. Default: n - - And if CONFIG_MEMCPY_VIK is selected, the following tuning options are available: - - CONFIG_MEMCPY_PRE_INC_PTRS - Use pre-increment of pointers. Default is - post increment of pointers. - - CONFIG_MEMCPY_INDEXED_COPY - Copying data using array indexing. Using - this option, disables the CONFIG_MEMCPY_PRE_INC_PTRS option. - - CONFIG_MEMCPY_64BIT - Compiles memcpy for architectures that suppport - 64-bit operations efficiently. - - If CONFIG_ARCH_MEMSET is not selected, then the following option is - also available: - - CONFIG_MEMSET_OPTSPEED - Select this option to use a version of memcpy() - optimized for speed. Default: memcpy() is optimized for size. - - And if CONFIG_MEMSET_OPTSPEED is selected, the following tuning option is - available: - - CONFIG_MEMSET_64BIT - Compiles memset() for architectures that suppport - 64-bit operations efficiently. - The architecture may provide custom versions of certain standard header files: @@ -732,15 +663,6 @@ defconfig -- This is a configuration file similar to the Linux don't select CONFIG_ARCH_MATH_H, the redirecting math.h header file will stay out-of-the-way in include/nuttx/. - CONFIG_ARCH_FLOAT_H - If you enable the generic, built-in math library, then that math library - will expect your toolchain to provide the standard float.h header file. - The float.h header file defines the properties of your floating point - implementation. It would always be best to use your toolchain's float.h - header file but if none is avaiable, a default float.h header file will - provided if this option is selected. However, there is no assurance that - the settings in this float.h are actually correct for your platform! - CONFIG_ARCH_STDARG_H - There is also a redirecting version of stdarg.h in the source tree as well. It also resides out-of-the-way at include/nuttx/stdarg.h. This is because you should normally use your toolchain's stdarg.h file. But @@ -771,7 +693,7 @@ defconfig -- This is a configuration file similar to the Linux If CONFIG_ARCH_ROMGETC is defined, then the architecture logic must export the function up_romgetc(). up_romgetc() will simply read one byte of data from the instruction space. - + If CONFIG_ARCH_ROMGETC, certain C stdio functions are effected: (1) All format strings in printf, fprintf, sprintf, etc. are assumed to lie in FLASH (string arguments for %s are still assumed @@ -841,7 +763,7 @@ defconfig -- This is a configuration file similar to the Linux much sense in supporting FAT date and time unless you have a hardware RTC or other way to get the time and date. CONFIG_FS_NXFFS: Enable NuttX FLASH file system (NXFF) support. - CONFIG_NXFFS_ERASEDSTATE: The erased state of FLASH. + CONFIG_NXFFS_ERASEDSTATE: The erased state of FLASH. This must have one of the values of 0xff or 0x00. Default: 0xff. CONFIG_NXFFS_PACKTHRESHOLD: When packing flash file data, @@ -995,7 +917,7 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_INPUT Enables general support for input devices - + CONFIG_INPUT_TSC2007 If CONFIG_INPUT is selected, then this setting will enable building of the TI TSC2007 touchscreen driver. @@ -1010,14 +932,14 @@ defconfig -- This is a configuration file similar to the Linux Enables support for the SPI interface (not currenly supported) CONFIG_STMPE811_I2C Enables support for the I2C interface - CONFIG_STMPE811_MULTIPLE + CONFIG_STMPE811_MULTIPLE Can be defined to support multiple STMPE811 devices on board. CONFIG_STMPE811_ACTIVELOW Interrupt is generated by an active low signal (or falling edge). CONFIG_STMPE811_EDGE Interrupt is generated on an edge (vs. on the active level) CONFIG_STMPE811_NPOLLWAITERS - Maximum number of threads that can be waiting on poll() (ignored if + Maximum number of threads that can be waiting on poll() (ignored if CONFIG_DISABLE_POLL is set). CONFIG_STMPE811_TSC_DISABLE Disable driver touchscreen functionality. @@ -1126,21 +1048,21 @@ defconfig -- This is a configuration file similar to the Linux port. The default data link layer for uIP is Ethernet. If CONFIG_NET_SLIP is defined in the NuttX configuration file, then SLIP will be supported. The basic differences between the SLIP and Ethernet configurations is that - when SLIP is selected: + when SLIP is selected: - * The link level header (that comes before the IP header) is omitted. - * All MAC address processing is suppressed. + * The link level header (that comes before the IP header) is omitted. + * All MAC address processing is suppressed. * ARP is disabled. If CONFIG_NET_SLIP is not selected, then Ethernet will be used (there is no need to define anything special in the configuration file to use - Ethernet -- it is the default). + Ethernet -- it is the default). CONFIG_NET_SLIP -- Enables building of the SLIP driver. SLIP requires at least one IP protocols selected and the following additional network settings: CONFIG_NET_NOINTS and CONFIG_NET_MULTIBUFFER. CONFIG_NET_BUFSIZE *must* be set to 296. Other optional configuration - settings that affect the SLIP driver: CONFIG_NET_STATISTICS. + settings that affect the SLIP driver: CONFIG_NET_STATISTICS. Default: Ethernet If SLIP is selected, then the following SLIP options are available: @@ -1156,10 +1078,6 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries - CONFIG_NET_RESOLV_MAXRESPONSE - This setting determines the maximum - size of response message that can be received by the DNS resolver. - The default is 96 but may need to be larger on enterprise networks - (perhaps 176). THTTPD @@ -1181,7 +1099,7 @@ defconfig -- This is a configuration file similar to the Linux to run before killing them. CONFIG_THTTPD_CHARSET- The default character set name to use with text MIME types. - CONFIG_THTTPD_IOBUFFERSIZE - + CONFIG_THTTPD_IOBUFFERSIZE - CONFIG_THTTPD_INDEX_NAMES - A list of index filenames to check. The files are searched for in this order. CONFIG_AUTH_FILE - The file to use for authentication. If this is @@ -1213,7 +1131,7 @@ defconfig -- This is a configuration file similar to the Linux You can also leave both options undefined, and thttpd will not do anything special about tildes. Enabling both options is an error. Typical values, if they're defined, are "users" for - CONFIG_THTTPD_TILDE_MAP1 and "public_html"forCONFIG_THTTPD_TILDE_MAP2. + CONFIG_THTTPD_TILDE_MAP1 and "public_html"forCONFIG_THTTPD_TILDE_MAP2. CONFIG_THTTPD_GENERATE_INDICES CONFIG_THTTPD_URLPATTERN - If defined, then it will be used to match and verify referrers. @@ -1271,7 +1189,7 @@ defconfig -- This is a configuration file similar to the Linux USB host HID class driver. Requires CONFIG_USBHOST=y, CONFIG_USBHOST_INT_DISABLE=n, CONFIG_NFILE_DESCRIPTORS > 0, CONFIG_SCHED_WORKQUEUE=y, and CONFIG_DISABLE_SIGNALS=n. - + CONFIG_HIDKBD_POLLUSEC Device poll rate in microseconds. Default: 100 milliseconds. CONFIG_HIDKBD_DEFPRIO @@ -1290,7 +1208,7 @@ defconfig -- This is a configuration file similar to the Linux If set to y all 231 possible scancodes will be converted to something. Default: 104 key US keyboard. CONFIG_HIDKBD_NODEBOUNCE - If set to y normal debouncing is disabled. Default: + If set to y normal debouncing is disabled. Default: Debounce enabled (No repeat keys). USB host mass storage class driver. Requires CONFIG_USBHOST=y, @@ -1327,12 +1245,12 @@ defconfig -- This is a configuration file similar to the Linux Configure the CDC serial driver as part of a composite driver (only if CONFIG_USBDEV_COMPOSITE is also defined) CONFIG_CDCACM_IFNOBASE - If the CDC driver is part of a composite device, then this may need to + If the CDC driver is part of a composite device, then this may need to be defined to offset the CDC/ACM interface numbers so that they are unique and contiguous. When used with the Mass Storage driver, the correct value for this offset is zero. CONFIG_CDCACM_STRBASE - If the CDC driver is part of a composite device, then this may need to + If the CDC driver is part of a composite device, then this may need to be defined to offset the CDC/ACM string numbers so that they are unique and contiguous. When used with the Mass Storage driver, the correct value for this offset is four (this value actuallly only needs @@ -1391,13 +1309,13 @@ defconfig -- This is a configuration file similar to the Linux Configure the mass storage driver as part of a composite driver (only if CONFIG_USBDEV_COMPOSITE is also defined) CONFIG_USBMSC_IFNOBASE - If the CDC driver is part of a composite device, then this may need to + If the CDC driver is part of a composite device, then this may need to be defined to offset the mass storage interface number so that it is unique and contiguous. When used with the CDC/ACM driver, the correct value for this offset is two (because of the two CDC/ACM interfaces that will precede it). CONFIG_USBMSC_STRBASE - If the CDC driver is part of a composite device, then this may need to + If the CDC driver is part of a composite device, then this may need to be defined to offset the mass storage string numbers so that they are unique and contiguous. When used with the CDC/ACM driver, the correct value for this offset is four (or perhaps 5 or 6, depending @@ -1605,15 +1523,10 @@ configs/avr32dev1 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. + 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-nuttx-elf toolchain*. This port is complete and verified. -configs/cloudctrl - Darcy's CloudController board. This is a small network relay development - board. Based on the Shenzhou IV development board design. It is based on - the STM32F107VC MCU. - configs/compal_e88 and compal_e99 These directories contain the board support for compal e88 and e99 phones. These ports are based on patches contributed by Denis Carikli for both the @@ -1626,23 +1539,23 @@ configs/demo9s12ne64 is code complete but has not yet been verified. configs/ea3131 - Embedded Artists EA3131 Development board. This board is based on the + Embedded Artists EA3131 Development board. This board is based on the 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 + Embedded Artists EA3152 Development board. This board is based on the 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 + 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-nuttx-elf toolchain*. STATUS: This port is complete and mature. configs/ekk-lm3s9b96 - TI/Stellaris EKK-LM3S9B96 board. This board is based on the + TI/Stellaris EKK-LM3S9B96 board. This board is based on the an EKK-LM3S9B96 which is a Cortex-M3. configs/ez80f0910200kitg @@ -1670,13 +1583,13 @@ configs/kwikstik-k40. configs/lincoln60 NuttX port to the Micromint Lincoln 60 board. - + configs/lm3s6432-s2e Stellaris RDK-S2E Reference Design Kit and the MDL-S2E Ethernet to Serial module. configs/lm3s6965-ek - Stellaris LM3S6965 Evaluation Kit. This board is based on the + 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-nuttx-elf toolchain*. STATUS: This port is complete and mature. @@ -1733,7 +1646,7 @@ configs/ntosd-dm320 toolchain*: see http://wiki.neurostechnology.com/index.php/OSD_1.0_Developer_Home - + There are some differences between the Dev Board and the currently available commercial v1.0 Boards. See @@ -1803,7 +1716,7 @@ configs/qemu-i486 hardwared (Google the Bifferboard). configs/rgmp - RGMP stands for RTOS and GPOS on Multi-Processor. RGMP is a project for + RGMP stands for RTOS and GPOS on Multi-Processor. RGMP is a project for running GPOS and RTOS simultaneously on multi-processor platforms. You can port your favorite RTOS to RGMP together with an unmodified Linux to form a hybrid operating system. This makes your application able to use both RTOS @@ -1844,14 +1757,8 @@ configs/stm3240g-eval microcontroller (ARM Cortex-M4 with FPU). This port uses a GNU Cortex-M4 toolchain (such as CodeSourcery). -configs/stm32f100rc_generic - STMicro STM32F100RC generic board based on STM32F100RC high-density value line - chip. This "generic" configuration is not very usable out-of-box, but can be - used as a starting point to creating new configs with similar STM32 - high-density value line chips. - configs/stm32f4discovery - STMicro STM32F4-Discovery board based on the STMIcro STM32F407VGT6 MCU. + STMicro STM32F4-Discovery board boased on the STMIcro STM32F407VGT6 MCU. configs/sure-pic32mx The "Advanced USB Storage Demo Board," Model DB-DP11215, from Sure @@ -1888,7 +1795,7 @@ configs/vsn configs/xtrs TRS80 Model 3. This port uses a vintage computer based on the Z80. - An emulator for this computer is available to run TRS80 programs on a + An emulator for this computer is available to run TRS80 programs on a linux platform (http://www.tim-mann.org/xtrs.html). configs/z16f2800100zcog @@ -1939,7 +1846,7 @@ And if configs///appconfig exists and your application directory is not in the standard loction (../apps), then you should also specify the location of the application directory on the command line like: - + cd tools ./configure.sh -a / diff --git a/nuttx/configs/px4fmu/common/Make.defs b/nuttx/configs/px4fmu/common/Make.defs index 8ffe5223ba..ff2e4c5fac 100644 --- a/nuttx/configs/px4fmu/common/Make.defs +++ b/nuttx/configs/px4fmu/common/Make.defs @@ -39,8 +39,12 @@ # Make.defs in the per-config directories. # -include ${TOPDIR}/tools/Config.mk -include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs +# +# We only support building with the ARM bare-metal toolchain from +# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. +# + +CROSSDEV = arm-none-eabi- CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig index 5e2a32a460..0959687ded 100644 --- a/nuttx/configs/px4fmu/nsh/appconfig +++ b/nuttx/configs/px4fmu/nsh/appconfig @@ -77,6 +77,7 @@ CONFIGURED_APPS += sensors CONFIGURED_APPS += ardrone_interface CONFIGURED_APPS += multirotor_att_control CONFIGURED_APPS += multirotor_pos_control +#CONFIGURED_APPS += fixedwing_control CONFIGURED_APPS += fixedwing_att_control CONFIGURED_APPS += fixedwing_pos_control CONFIGURED_APPS += position_estimator diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig index 90eeda50f1..bc724c0063 100755 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -93,9 +93,6 @@ CONFIG_ARCH_MATH_H=y CONFIG_ARMV7M_CMNVECTOR=y -# default to a generic arm-none-eabi toolchain -CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y - # # JTAG Enable settings (by default JTAG-DP and SW-DP are enabled): # @@ -770,8 +767,6 @@ CONFIG_FS_ROMFS=y # CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card. # Default is 20MHz, current setting 24 MHz # -CONFIG_MMCSD=y -CONFIG_MMCSD_SPI=y CONFIG_MMCSD_NSLOTS=1 CONFIG_MMCSD_READONLY=n CONFIG_MMCSD_SPICLOCK=24000000 diff --git a/nuttx/configs/px4io/common/Make.defs b/nuttx/configs/px4io/common/Make.defs index a7cdd9d50a..a3996a9ed3 100644 --- a/nuttx/configs/px4io/common/Make.defs +++ b/nuttx/configs/px4io/common/Make.defs @@ -39,8 +39,12 @@ # Make.defs in the per-config directories. # -include ${TOPDIR}/tools/Config.mk -include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs +# +# We only support building with the ARM bare-metal toolchain from +# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. +# + +CROSSDEV = arm-none-eabi- CC = $(CROSSDEV)gcc CXX = $(CROSSDEV)g++ diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig index 38df856eb9..1ac70f8abf 100755 --- a/nuttx/configs/px4io/io/defconfig +++ b/nuttx/configs/px4io/io/defconfig @@ -89,9 +89,6 @@ CONFIG_ARCH_CALIBRATION=n CONFIG_ARCH_DMA=n CONFIG_ARMV7M_CMNVECTOR=y -# default to a generic arm-none-eabi toolchain -CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y - # # JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): # diff --git a/nuttx/configs/px4io/nsh/Make.defs b/nuttx/configs/px4io/nsh/Make.defs new file mode 100644 index 0000000000..87508e22ec --- /dev/null +++ b/nuttx/configs/px4io/nsh/Make.defs @@ -0,0 +1,3 @@ +include ${TOPDIR}/.config + +include $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/Make.defs diff --git a/nuttx/configs/px4io/nsh/appconfig b/nuttx/configs/px4io/nsh/appconfig new file mode 100644 index 0000000000..d5809a9391 --- /dev/null +++ b/nuttx/configs/px4io/nsh/appconfig @@ -0,0 +1,43 @@ +############################################################################ +# configs/stm3210e-eval/nsh/appconfig +# +# 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. +# +############################################################################ + +# Path to example in apps/examples containing the user_start entry point + +CONFIGURED_APPS += examples/nsh + +CONFIGURED_APPS += system/readline +CONFIGURED_APPS += nshlib +CONFIGURED_APPS += reboot + diff --git a/nuttx/configs/px4io/nsh/defconfig b/nuttx/configs/px4io/nsh/defconfig new file mode 100755 index 0000000000..6f4e208691 --- /dev/null +++ b/nuttx/configs/px4io/nsh/defconfig @@ -0,0 +1,565 @@ +############################################################################ +# configs/px4io/nsh/defconfig +# +# 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. +# +############################################################################ +# +# architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_family - for use in C code. This identifies the +# particular chip family that the architecture is implemented +# in. +# CONFIG_ARCH_architecture - for use in C code. This identifies the +# specific architecture within the chip familyl. +# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory +# CONFIG_ARCH_CHIP_name - For use in C code +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# CONFIG_BOARD_LOOPSPERMSEC - for delay loops +# CONFIG_DRAM_SIZE - Describes the installed DRAM. +# CONFIG_DRAM_START - The start address of DRAM (physical) +# CONFIG_DRAM_END - Last address+1 of installed RAM +# CONFIG_ARCH_IRQPRIO - The ST32F100CB 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_STACKDUMP - Do stack dumps after assertions +# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. +# 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_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 calibrate +# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure +# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until +# the delay actually is 100 seconds. +# CONFIG_ARCH_DMA - Support DMA initialization +# +CONFIG_ARCH=arm +CONFIG_ARCH_ARM=y +CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_CHIP=stm32 +CONFIG_ARCH_CHIP_STM32F100C8=y +CONFIG_ARCH_BOARD=px4io +CONFIG_ARCH_BOARD_PX4IO=y +CONFIG_BOARD_LOOPSPERMSEC=24000 +CONFIG_DRAM_SIZE=0x00002000 +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE) +CONFIG_ARCH_IRQPRIO=y +CONFIG_ARCH_INTERRUPTSTACK=n +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARCH_BOOTLOADER=n +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CALIBRATION=n +CONFIG_ARCH_DMA=n +CONFIG_ARMV7M_CMNVECTOR=y + +# +# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): +# +# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG +# +# JTAG Enable options: +# +# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# but without JNTRST. +# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled +# +CONFIG_STM32_DFU=n +CONFIG_STM32_JTAG_FULL_ENABLE=y +CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n +CONFIG_STM32_JTAG_SW_ENABLE=n + +# +# Individual subsystems can be enabled: +# AHB: +CONFIG_STM32_DMA1=n +CONFIG_STM32_DMA2=n +CONFIG_STM32_CRC=n +# APB1: +# Timers 2,3 and 4 are owned by the PWM driver +CONFIG_STM32_TIM2=n +CONFIG_STM32_TIM3=n +CONFIG_STM32_TIM4=n +CONFIG_STM32_TIM5=n +CONFIG_STM32_TIM6=n +CONFIG_STM32_TIM7=n +CONFIG_STM32_WWDG=n +CONFIG_STM32_SPI2=n +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=n +CONFIG_STM32_BKP=n +CONFIG_STM32_PWR=n +CONFIG_STM32_DAC=n +# APB2: +CONFIG_STM32_ADC1=y +CONFIG_STM32_ADC2=n +# TIM1 is owned by the HRT +CONFIG_STM32_TIM1=n +CONFIG_STM32_SPI1=n +CONFIG_STM32_TIM8=n +CONFIG_STM32_USART1=y +CONFIG_STM32_ADC3=n + +# +# Timer and I2C devices may need to the following to force power to be applied: +# +#CONFIG_STM32_FORCEPOWER=y + +# +# STM32F100 specific serial device driver settings +# +# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the +# console and ttys0 (default is the USART1). +# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received. +# This specific the size of the receive buffer +# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before +# being sent. This specific the size of the transmit buffer +# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be +# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8. +# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity +# CONFIG_USARTn_2STOP - Two stop bits +# +CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART2_SERIAL_CONSOLE=n +CONFIG_USART3_SERIAL_CONSOLE=n + +CONFIG_USART1_TXBUFSIZE=64 +CONFIG_USART2_TXBUFSIZE=64 +CONFIG_USART3_TXBUFSIZE=64 + +CONFIG_USART1_RXBUFSIZE=64 +CONFIG_USART2_RXBUFSIZE=64 +CONFIG_USART3_RXBUFSIZE=64 + +CONFIG_USART1_BAUD=57600 +CONFIG_USART2_BAUD=115200 +CONFIG_USART3_BAUD=115200 + +CONFIG_USART1_BITS=8 +CONFIG_USART2_BITS=8 +CONFIG_USART3_BITS=8 + +CONFIG_USART1_PARITY=0 +CONFIG_USART2_PARITY=0 +CONFIG_USART3_PARITY=0 + +CONFIG_USART1_2STOP=0 +CONFIG_USART2_2STOP=0 +CONFIG_USART3_2STOP=0 + +# +# PX4IO specific driver settings +# +# CONFIG_HRT_TIMER +# Enables the high-resolution timer. The board definition must +# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/ +# compare channels to be used. +# CONFIG_HRT_PPM +# Enables R/C PPM input using the HRT. The board definition must +# set HRT_PPM_CHANNEL to the timer capture/compare channel to be +# used, and define GPIO_PPM_IN to configure the appropriate timer +# GPIO. +# CONFIG_PWM_SERVO +# Enables the PWM servo driver. The driver configuration must be +# supplied by the board support at initialisation time. +# Note that USART2 must be disabled on the PX4 board for this to +# be available. +# +# +CONFIG_HRT_TIMER=y +CONFIG_HRT_PPM=y +CONFIG_PWM_SERVO=y + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_MOTOROLA_SREC=n +CONFIG_RAW_BINARY=y +CONFIG_HAVE_LIBM=n + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_DEBUG_SYMBOLS - build without optimization and with +# debug symbols (needed for use with a debugger). +# CONFIG_HAVE_CXX - Enable support for C++ +# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support +# for initialization of static C++ instances for this architecture +# and for the selected toolchain (via up_cxxinitialize()). +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. +# You would only need this if you are concerned about accurate +# time conversions in the past or in the distant future. +# CONFIG_JULIAN_TIME - Enables Julian time conversions. You +# would only need this if you are concerned about accurate +# time conversion in the distand past. You must also define +# CONFIG_GREGORIAN_TIME in order to use Julian time. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket +# desciptors by task_create() when a new task is started. If +# set, all sockets will appear to be closed in the new task. +# CONFIG_NXFLAT. Enable support for the NXFLAT binary format. +# This format will support execution of NuttX binaries located +# in a ROMFS filesystem (see examples/nxflat). +# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to +# handle delayed processing from interrupt handlers. This feature +# is required for some drivers but, if there are not complaints, +# can be safely disabled. The worker thread also performs +# garbage collection -- completing any delayed memory deallocations +# from interrupt handlers. If the worker thread is disabled, +# then that clean will be performed by the IDLE thread instead +# (which runs at the lowest of priority and may not be appropriate +# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE +# is enabled, then the following options can also be used: +# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker +# thread. Default: 50 +# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for +# work in units of microseconds. Default: 50*1000 (50 MS). +# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker +# thread. Default: CONFIG_IDLETHREAD_STACKSIZE. +# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up +# the worker thread. Default: 4 +# +#CONFIG_APPS_DIR= +CONFIG_DEBUG=n +CONFIG_DEBUG_VERBOSE=n +CONFIG_DEBUG_SYMBOLS=y +CONFIG_HAVE_CXX=n +CONFIG_HAVE_CXXINITIALIZE=n +CONFIG_MM_REGIONS=1 +CONFIG_MM_SMALL=y +CONFIG_ARCH_LOWPUTC=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=0 +CONFIG_START_YEAR=2009 +CONFIG_START_MONTH=9 +CONFIG_START_DAY=21 +CONFIG_GREGORIAN_TIME=n +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=n +CONFIG_FDCLONE_STDIO=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_NXFLAT=n +CONFIG_SCHED_WORKQUEUE=n +CONFIG_SCHED_WORKPRIORITY=50 +CONFIG_SCHED_WORKPERIOD=(50*1000) +CONFIG_SCHED_WORKSTACKSIZE=512 +CONFIG_SIG_SIGWORK=4 + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=y +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve system performance +# +CONFIG_ARCH_MEMCPY=n +CONFIG_ARCH_MEMCMP=n +CONFIG_ARCH_MEMMOVE=n +CONFIG_ARCH_MEMSET=n +CONFIG_ARCH_STRCMP=n +CONFIG_ARCH_STRCPY=n +CONFIG_ARCH_STRNCPY=n +CONFIG_ARCH_STRLEN=n +CONFIG_ARCH_STRNLEN=n +CONFIG_ARCH_BZERO=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=4 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=2 +CONFIG_NFILE_DESCRIPTORS=6 +CONFIG_NFILE_STREAMS=4 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=1 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=3 +CONFIG_PREALLOC_TIMERS=1 + + +# +# Settings for apps/nshlib +# +# CONFIG_NSH_BUILTIN_APPS - Support external registered, +# "named" applications that can be executed from the NSH +# command line (see apps/README.txt for more information). +# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer +# CONFIG_NSH_STRERROR - Use strerror(errno) +# CONFIG_NSH_LINELEN - Maximum length of one command line +# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi +# CONFIG_NSH_DISABLESCRIPT - Disable scripting support +# CONFIG_NSH_DISABLEBG - Disable background commands +# CONFIG_NSH_ROMFSETC - Use startup script in /etc +# CONFIG_NSH_CONSOLE - Use serial console front end +# CONFIG_NSH_TELNET - Use telnetd console front end +# CONFIG_NSH_ARCHINIT - Platform provides architecture +# specific initialization (nsh_archinitialize()). +# +# If CONFIG_NSH_TELNET is selected: +# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size +# CONFIG_NSH_DHCPC - Obtain address using DHCP +# CONFIG_NSH_IPADDR - Provides static IP address +# CONFIG_NSH_DRIPADDR - Provides static router IP address +# CONFIG_NSH_NETMASK - Provides static network mask +# CONFIG_NSH_NOMAC - Use a bogus MAC address +# +# If CONFIG_NSH_ROMFSETC is selected: +# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint +# CONFIG_NSH_INITSCRIPT - Relative path to init script +# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor +# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size +# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor +# CONFIG_NSH_FATSECTSIZE - FAT FS sector size +# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors +# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint +# +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=64 +CONFIG_NSH_STRERROR=n +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_NESTDEPTH=1 +CONFIG_NSH_DISABLESCRIPT=y +CONFIG_NSH_DISABLEBG=n +CONFIG_NSH_ROMFSETC=n +CONFIG_NSH_CONSOLE=y +CONFIG_NSH_TELNET=n +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_IOBUFFER_SIZE=256 +#CONFIG_NSH_STACKSIZE=1024 +CONFIG_NSH_DHCPC=n +CONFIG_NSH_NOMAC=n +CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) +CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) +CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_NSH_ROMFSMOUNTPT="/etc" +CONFIG_NSH_INITSCRIPT="init.d/rcS" +CONFIG_NSH_ROMFSDEVNO=0 +CONFIG_NSH_ROMFSSECTSIZE=64 +CONFIG_NSH_FATDEVNO=1 +CONFIG_NSH_FATSECTSIZE=512 +CONFIG_NSH_FATNSECTORS=1024 +CONFIG_NSH_FATMOUNTPT=/tmp + +# +# Architecture-specific NSH options +# +CONFIG_NSH_MMCSDSPIPORTNO=0 +CONFIG_NSH_MMCSDSLOTNO=0 +CONFIG_NSH_MMCSDMINOR=0 + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# (should also be =n for the STM3210E-EVAL which always runs from flash) +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only) +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2) there after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_STACK_POINTER= +CONFIG_IDLETHREAD_STACKSIZE=800 +CONFIG_USERMAIN_STACKSIZE=1024 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=512 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= diff --git a/nuttx/configs/px4io/nsh/setenv.sh b/nuttx/configs/px4io/nsh/setenv.sh new file mode 100755 index 0000000000..d836851921 --- /dev/null +++ b/nuttx/configs/px4io/nsh/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# configs/stm3210e-eval/dfu/setenv.sh +# +# 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; 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` +export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" +export BUILDROOT_BIN="${WD}/../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/drivers/Kconfig b/nuttx/drivers/Kconfig index 8302d21b71..1d263ec145 100644 --- a/nuttx/drivers/Kconfig +++ b/nuttx/drivers/Kconfig @@ -47,8 +47,7 @@ config CAN_EXTID bool "CAN extended IDs" default n ---help--- - Enables support for the 29-bit extended ID. Default Standard 11-bit - IDs. + Enables support for the 29-bit extended ID. Default Standard 11-bit IDs. config CAN_FIFOSIZE int "CAN driver I/O buffer size" @@ -84,10 +83,10 @@ config PWM_PULSECOUNT bool "PWM Pulse Count Support" default n ---help--- - Some hardware will support generation of a fixed number of pulses. - This might be used, for example to support a stepper motor. If the - hardware will support a fixed pulse count, then this configuration - should be set to enable the capability. + Some hardware will support generation of a fixed number of pulses. This + might be used, for example to support a stepper motor. If the hardware + will support a fixed pulse count, then this configuration should be set to + enable the capability. endif @@ -148,25 +147,23 @@ config SPI_OWNBUS bool "SPI single device" default n ---help--- - Set if there is only one active device on the SPI bus. No locking or - SPI configuration will be performed. It is not necessary for clients to - lock, re-configure, etc.. + Set if there is only one active device on the SPI bus. No locking or SPI + configuration will be performed. It is not necessary for clients to lock, + re-configure, etc.. config SPI_EXCHANGE bool "SPI exchange" default y ---help--- - Driver supports a single exchange method (vs a recvblock() and - sndblock() methods). + Driver supports a single exchange method (vs a recvblock() and sndblock ()methods). config SPI_CMDDATA bool "SPI CMD/DATA" default n ---help--- - Devices on the SPI bus require out-of-band support to distinguish - command transfers from data transfers. Such devices will often support - either 9-bit SPI (yech) or 8-bit SPI and a GPIO output that selects - between command and data. + Devices on the SPI bus require out-of-band support to distinguish command + transfers from data transfers. Such devices will often support either 9-bit + SPI (yech) or 8-bit SPI and a GPIO output that selects between command and data. endif @@ -176,36 +173,35 @@ menuconfig RTC ---help--- This selection enables configuration of a real time clock (RTCdriver. See include/nuttx/rtc.h for further watchdog timer driver information. - Most RTC drivers are MCU specific and may require other specific - settings. + Most RTC drivers are MCU specific and may require other specific settings. config RTC_DATETIME bool "Date/Time RTC Support" default n depends on RTC ---help--- - There are two general types of RTC: (1) A simple battery backed - counter that keeps the time when power is down, and (2) a full - date / time RTC the provides the date and time information, often in - BCD format. If RTC_DATETIME is selected, it specifies this second kind - of RTC. In this case, the RTC is used to "seed" the normal NuttX timer - and the NuttX system timer provides for higher resolution time. + There are two general types of RTC: (1) A simple battery backed counter + that keeps the time when power is down, and (2) a full date / time RTC the + provides the date and time information, often in BCD format. If + RTC_DATETIME is selected, it specifies this second kind of RTC. In this + case, the RTC is used to "seed" the normal NuttX timer and the NuttX system + timer provides for higher resolution time. config RTC_HIRES bool "Hi-Res RTC Support" default n depends on RTC && !RTC_DATETIME ---help--- - If RTC_DATETIME not selected, then the simple, battery backed counter - is used. There are two different implementations of such simple - counters based on the time resolution of the counter: The typical RTC - keeps time to resolution of 1 second, usually supporting a 32-bit - time_t value. In this case, the RTC is used to "seed" the normal NuttX - timer and the NuttX timer provides for higherresoution time. + If RTC_DATETIME not selected, then the simple, battery backed counter is + used. There are two different implementations of such simple counters + based on the time resolution of the counter: The typical RTC keeps time + to resolution of 1 second, usually supporting a 32-bit time_t value. In + this case, the RTC is used to "seed" the normal NuttX timer and the NuttX + timer provides for higherresoution time. - If RTC_HIRES is enabled in the NuttX configuration, then the RTC - provides higher resolution time and completely replaces the system - timer for purpose of date and time. + If RTC_HIRES is enabled in the NuttX configuration, then the RTC provides + higher resolution time and completely replaces the system timer for purpose + of date and time. config RTC_FREQUENCY int "Hi-Res RTC frequency" @@ -213,8 +209,8 @@ config RTC_FREQUENCY depends on RTC && !RTC_DATETIME && RTC_HIRES ---help--- If RTC_HIRES is defined, then the frequency of the high resolution RTC - must be provided. If RTC_HIRES is not defined, RTC_FREQUENCY is - assumed to be one Hz. + must be provided. If RTC_HIRES is not defined, RTC_FREQUENCY is assumed + to be one Hz. config RTC_ALARM bool "RTC Alarm Support" @@ -228,9 +224,8 @@ menuconfig WATCHDOG bool "Watchdog Timer Support" default n ---help--- - This selection enables building of the "upper-half" watchdog timer - driver. See include/nuttx/watchdog.h for further watchdog timer driver - information. + This selection enables building of the "upper-half" watchdog timer driver. + See include/nuttx/watchdog.h for further watchdog timer driver information. if WATCHDOG endif @@ -353,8 +348,7 @@ menuconfig POWER bool "Power Management Support" default n ---help--- - Enable building of power-related devices (battery monitors, chargers, - etc). + Enable building of power-related devices (battery monitors, chargers, etc). if POWER source drivers/power/Kconfig @@ -392,8 +386,8 @@ menuconfig SERIAL default y ---help--- Front-end character drivers for chip-specific UARTs. This provide - some TTY-like functionality and are commonly used (but not required - for) the NuttX system console. See also include/nuttx/serial/serial.h + some TTY-like functionality and are commonly used (but not required for) + the NuttX system console. See also include/nuttx/serial/serial.h if SERIAL source drivers/serial/Kconfig diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile index 13a5078236..26a2ea9923 100644 --- a/nuttx/drivers/Makefile +++ b/nuttx/drivers/Makefile @@ -85,15 +85,15 @@ ifeq ($(CONFIG_WATCHDOG),y) endif endif -AOBJS = $(ASRCS:.S=$(OBJEXT)) -COBJS = $(CSRCS:.c=$(OBJEXT)) +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) -BIN = libdrivers$(LIBEXT) +BIN = libdrivers$(LIBEXT) -all: $(BIN) +all: $(BIN) $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -101,21 +101,22 @@ $(AOBJS): %$(OBJEXT): %.S $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) -$(BIN): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) +$(BIN): $(OBJS) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) .depend: Makefile $(SRCS) - $(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, $(BIN)) + @rm -f $(BIN) *~ .*.swp $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/nuttx/drivers/analog/Make.defs b/nuttx/drivers/analog/Make.defs index 425193f7e5..d94e397587 100644 --- a/nuttx/drivers/analog/Make.defs +++ b/nuttx/drivers/analog/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/analog/Make.defs # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -76,12 +76,12 @@ endif ifeq ($(CONFIG_DAC),y) DEPPATH += --dep-path analog VPATH += :analog - CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/analog} + CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/analog} else ifeq ($(CONFIG_ADC),y) DEPPATH += --dep-path analog VPATH += :analog - CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/analog} + CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/analog} endif endif diff --git a/nuttx/drivers/analog/adc.c b/nuttx/drivers/analog/adc.c index 72f19452a4..84070f162a 100644 --- a/nuttx/drivers/analog/adc.c +++ b/nuttx/drivers/analog/adc.c @@ -143,7 +143,7 @@ static int adc_open(FAR struct file *filep) dev->ad_recv.af_head = 0; dev->ad_recv.af_tail = 0; - /* Finally, Enable the ADC RX interrupt */ + /* Finally, Enable the CAN RX interrupt */ dev->ad_ops->ao_rxint(dev, true); @@ -151,11 +151,9 @@ static int adc_open(FAR struct file *filep) dev->ad_ocount = tmp; } - irqrestore(flags); } } - sem_post(&dev->ad_closesem); } return ret; @@ -372,10 +370,6 @@ static int adc_ioctl(FAR struct file *filep, int cmd, unsigned long arg) * Public Functions ****************************************************************************/ -/**************************************************************************** - * Name: adc_receive - ****************************************************************************/ - int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data) { FAR struct adc_fifo_s *fifo = &dev->ad_recv; @@ -396,7 +390,7 @@ int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data) if (nexttail != fifo->af_head) { - /* Add the new, decoded ADC sample at the tail of the FIFO */ + /* Add the new, decoded CAN message at the tail of the FIFO */ fifo->af_buffer[fifo->af_tail].am_channel = ch; fifo->af_buffer[fifo->af_tail].am_data = data; @@ -409,16 +403,11 @@ int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data) { sem_post(&fifo->af_sem); } - err = OK; } return err; } -/**************************************************************************** - * Name: adc_register - ****************************************************************************/ - int adc_register(FAR const char *path, FAR struct adc_dev_s *dev) { /* Initialize the ADC device structure */ diff --git a/nuttx/drivers/bch/Make.defs b/nuttx/drivers/bch/Make.defs index 2745fcfff0..bc22df8e26 100644 --- a/nuttx/drivers/bch/Make.defs +++ b/nuttx/drivers/bch/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/bch/Make.defs # -# Copyright (C) 2008, 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -46,7 +46,7 @@ CSRCS += bchlib_setup.c bchlib_teardown.c bchlib_read.c bchlib_write.c \ DEPPATH += --dep-path bch VPATH += :bch -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/bch} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/bch} endif endif diff --git a/nuttx/drivers/input/Make.defs b/nuttx/drivers/input/Make.defs index 8afd76f89e..6dbae268e5 100644 --- a/nuttx/drivers/input/Make.defs +++ b/nuttx/drivers/input/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/input/Make.defs # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -47,10 +47,6 @@ ifeq ($(CONFIG_INPUT_ADS7843E),y) CSRCS += ads7843e.c endif -ifeq ($(CONFIG_INPUT_MAX11802),y) - CSRCS += max11802.c -endif - ifeq ($(CONFIG_INPUT_STMPE811),y) CSRCS += stmpe811_base.c ifneq ($(CONFIG_INPUT_STMPE811_TSC_DISABLE),y) @@ -71,6 +67,6 @@ endif DEPPATH += --dep-path input VPATH += :input -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/input} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/input} endif diff --git a/nuttx/drivers/lcd/Kconfig b/nuttx/drivers/lcd/Kconfig index 2d20003ac5..640239e637 100644 --- a/nuttx/drivers/lcd/Kconfig +++ b/nuttx/drivers/lcd/Kconfig @@ -183,85 +183,12 @@ config NOKIA6100_RGBORD endif config LCD_UG9664HSWAG01 - bool "UG-9664HSWAG01 OLED Display Module" + bool "9664HSWAG01 OLED Display Module" default n ---help--- - OLED Display Module, UG-9664HSWAG01, Univision Technology Inc. Used - with the LPCXpresso and Embedded Artists base board. - - Required LCD driver settings: - LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. - LCD_MAXPOWER should be 1: 0=off, 1=on - - Required SPI driver settings: - SPI_CMDDATA - Include support for cmd/data selection. - -if LCD_UG9664HSWAG01 - -config UG9664HSWAG01_SPIMODE - int "UG-9664HSWAG01 SPI Mode" - default 0 - ---help--- - Controls the SPI mode - -config UG9664HSWAG01_FREQUENCY - int "UG-9664HSWAG01 SPI Frequency" - default 3500000 - ---help--- - Define to use a different bus frequency - -config UG9664HSWAG01_NINTERFACES - int "Number of UG-9664HSWAG01 Devices" - default 1 - ---help--- - Specifies the number of physical UG-9664HSWAG01 devices that will be - supported. NOTE: At present, this must be undefined or defined to be 1. - -config UG9664HSWAG01_POWER - bool "Power control" - default n - ---help--- - If the hardware supports a controllable OLED a power supply, this - configuration should be defined. In this case the system must - provide an interface ug_power(). - -endif - -config LCD_UG2864AMBAG01 - bool "UG-2864AMBAG01 OLED Display Module" - default n - ---help--- - OLED Display Module, UG-2864AMBAG01, Univision Technology Inc. - - Required LCD driver settings: - LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. - LCD_MAXPOWER should be 1: 0=off, 1=on - - Required SPI driver settings: - SPI_CMDDATA - Include support for cmd/data selection. - -if LCD_UG2864AMBAG01 - - config UG2864AMBAG01_SPIMODE - int "UG-2864AMBAG01 SPI Mode" - default 3 - ---help--- - Controls the SPI mode - -config UG2864AMBAG01_FREQUENCY - int "UG-2864AMBAG01 SPI Frequency" - default 3500000 - ---help--- - Define to use a different bus frequency - -config UG2864AMBAG01_NINTERFACES - int "Number of UG-2864AMBAG01 Devices" - default 1 - ---help--- - Specifies the number of physical UG-9664HSWAG01 devices that will be - supported. NOTE: At present, this must be undefined or defined to be 1. - -endif + ug-9664hswag01.c. OLED Display Module, UG-9664HSWAG01", Univision + Technology Inc. Used with the LPC Xpresso and Embedded Artists + base board. config LCD_SSD1289 bool "LCD Based on SSD1289 Controller" diff --git a/nuttx/drivers/lcd/Make.defs b/nuttx/drivers/lcd/Make.defs index 8b6d300523..26b169391f 100644 --- a/nuttx/drivers/lcd/Make.defs +++ b/nuttx/drivers/lcd/Make.defs @@ -47,10 +47,6 @@ ifeq ($(CONFIG_LCD_NOKIA6100),y) CSRCS += nokia6100.c endif -ifeq ($(CONFIG_LCD_UG2864AMBAG01),y) - CSRCS += ug-2864ambag01.c -endif - ifeq ($(CONFIG_LCD_UG9664HSWAG01),y) CSRCS += ug-9664hswag01.c endif @@ -67,6 +63,6 @@ endif DEPPATH += --dep-path lcd VPATH += :lcd -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/lcd} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/lcd} endif diff --git a/nuttx/drivers/lcd/ug-9664hswag01.c b/nuttx/drivers/lcd/ug-9664hswag01.c index 6ef78fca6e..e0e8e8e3a0 100644 --- a/nuttx/drivers/lcd/ug-9664hswag01.c +++ b/nuttx/drivers/lcd/ug-9664hswag01.c @@ -73,6 +73,8 @@ * CONFIG_UG9664HSWAG01_POWER * If the hardware supports a controllable OLED a power supply, this * configuration shold be defined. (See ug_power() below). + * CONFIG_LCD_UGDEBUG - Enable detailed UG-9664HSWAG01 debug output + * (CONFIG_DEBUG and CONFIG_VERBOSE must also be enabled). * * Required LCD driver settings: * CONFIG_LCD_UG9664HSWAG01 - Enable UG-9664HSWAG01 support @@ -117,10 +119,11 @@ #ifndef CONFIG_DEBUG # undef CONFIG_DEBUG_VERBOSE +# undef CONFIG_DEBUG_GRAPHICS #endif #ifndef CONFIG_DEBUG_VERBOSE -# undef CONFIG_DEBUG_LCD +# undef CONFIG_LCD_UGDEBUG #endif /* Check contrast selection */ @@ -179,7 +182,7 @@ #define UG_BPP 1 #define UG_COLORFMT FB_FMT_Y1 -/* Bytes per logical row and actual device row */ +/* Bytes per logical row andactual device row */ #define UG_XSTRIDE (UG_XRES >> 3) /* Pixels arrange "horizontally for user" */ #define UG_YSTRIDE (UG_YRES >> 3) /* But actual device arrangement is "vertical" */ @@ -195,10 +198,10 @@ /* Debug ******************************************************************************/ -#ifdef CONFIG_DEBUG_LCD -# define lcddbg(format, arg...) vdbg(format, ##arg) +#ifdef CONFIG_LCD_UGDEBUG +# define ugdbg(format, arg...) vdbg(format, ##arg) #else -# define lcddbg(x...) +# define ugdbg(x...) #endif /************************************************************************************** @@ -994,7 +997,7 @@ FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devn SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); - /* Configure the device */ + /* Set the starting position for the run */ (void)SPI_SEND(spi, SSD1305_SETCOLL + 2); /* Set low column address */ (void)SPI_SEND(spi, SSD1305_SETCOLH + 2); /* Set high column address */ diff --git a/nuttx/drivers/mmcsd/Make.defs b/nuttx/drivers/mmcsd/Make.defs index 0ba5efb7f1..8504565972 100644 --- a/nuttx/drivers/mmcsd/Make.defs +++ b/nuttx/drivers/mmcsd/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/mmcsd/Make.defs # -# Copyright (C) 2008, 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -33,24 +33,14 @@ # ############################################################################ -ifeq ($(CONFIG_MMCSD),y) - # Include MMC/SD drivers -ifeq ($(CONFIG_MMCSD_SDIO),y) -CSRCS += mmcsd_sdio.c -endif - -ifeq ($(CONFIG_MMCSD_SPI),y) -CSRCS += mmcsd_spi.c mmcsd_debug.c -endif +CSRCS += mmcsd_sdio.c mmcsd_spi.c mmcsd_debug.c # Include MMC/SD driver build support DEPPATH += --dep-path mmcsd VPATH += :mmcsd -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/mmcsd} - -endif +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/mmcsd} diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.c b/nuttx/drivers/mmcsd/mmcsd_sdio.c index 64b045bc27..d0bc6659cb 100644 --- a/nuttx/drivers/mmcsd/mmcsd_sdio.c +++ b/nuttx/drivers/mmcsd/mmcsd_sdio.c @@ -38,9 +38,6 @@ ****************************************************************************/ #include - -#if defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SDIO) - #include #include @@ -3181,5 +3178,3 @@ errout_with_alloc: kfree(priv); return ret; } - -#endif /* defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SDIO) */ diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c index d437b7feaa..7dbadc55fe 100644 --- a/nuttx/drivers/mmcsd/mmcsd_spi.c +++ b/nuttx/drivers/mmcsd/mmcsd_spi.c @@ -38,9 +38,6 @@ ****************************************************************************/ #include - -#if defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SPI) - #include #include @@ -511,7 +508,7 @@ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot, } break; - /* The R3 response is 5 bytes long. The first byte is identical to R1. */ + /* The R3 response is 5 bytes long */ case MMCSD_CMDRESP_R3: { @@ -523,10 +520,8 @@ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot, fvdbg("CMD%d[%08x] R1=%02x OCR=%08x\n", cmd->cmd & 0x3f, arg, response, slot->ocr); } - break; - - /* The R7 response is 5 bytes long. The first byte is identical to R1. */ + /* The R7 response is 5 bytes long */ case MMCSD_CMDRESP_R7: default: { @@ -1881,5 +1876,3 @@ int mmcsd_spislotinitialize(int minor, int slotno, FAR struct spi_dev_s *spi) (void)SPI_REGISTERCALLBACK(spi, mmcsd_mediachanged, (void*)slot); return OK; } - -#endif /* defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SPI) */ diff --git a/nuttx/drivers/net/e1000.c b/nuttx/drivers/net/e1000.c index cae6f39b40..ec2b29b6ad 100644 --- a/nuttx/drivers/net/e1000.c +++ b/nuttx/drivers/net/e1000.c @@ -60,7 +60,6 @@ #include #include #include -#include #include #include #include "e1000.h" @@ -105,9 +104,9 @@ struct e1000_dev { uint32_t io_mem_base; uint32_t mem_size; int pci_dev_id; - uint16_t pci_addr; unsigned char src_mac[6]; unsigned char dst_mac[6]; + int irq; struct irq_action int_desc; struct tx_ring tx_ring; struct rx_ring rx_ring; @@ -309,16 +308,16 @@ void e1000_init(struct e1000_dev *dev) e1000_outl(dev, E1000_FCRTH, pba*9/10); // setup tx rings - txd_phys = PADDR((uintptr_t)dev->tx_ring.desc); - kmem_phys = PADDR((uintptr_t)dev->tx_ring.buf); + txd_phys = PADDR(dev->tx_ring.desc); + kmem_phys = PADDR(dev->tx_ring.buf); for (i=0; itx_ring.desc[i].base_address = kmem_phys; - dev->tx_ring.desc[i].packet_length = 0; - dev->tx_ring.desc[i].cksum_offset = 0; - dev->tx_ring.desc[i].cksum_origin = 0; - dev->tx_ring.desc[i].desc_status = 1; - dev->tx_ring.desc[i].desc_command = (1<<0)|(1<<1)|(1<<3); - dev->tx_ring.desc[i].special_info = 0; + dev->tx_ring.desc[i].base_address = kmem_phys; + dev->tx_ring.desc[i].packet_length = 0; + dev->tx_ring.desc[i].cksum_offset = 0; + dev->tx_ring.desc[i].cksum_origin = 0; + dev->tx_ring.desc[i].desc_status = 1; + dev->tx_ring.desc[i].desc_command = (1<<0)|(1<<1)|(1<<3); + dev->tx_ring.desc[i].special_info = 0; } dev->tx_ring.tail = 0; e1000_outl(dev, E1000_TDT, 0); @@ -330,15 +329,15 @@ void e1000_init(struct e1000_dev *dev) e1000_outl(dev, E1000_TXDCTL, 0x01010000); // setup rx rings - rxd_phys = PADDR((uintptr_t)dev->rx_ring.desc); - kmem_phys = PADDR((uintptr_t)dev->rx_ring.buf); + rxd_phys = PADDR(dev->rx_ring.desc); + kmem_phys = PADDR(dev->rx_ring.buf); for (i=0; irx_ring.desc[i].base_address = kmem_phys; - dev->rx_ring.desc[i].packet_length = 0; - dev->rx_ring.desc[i].packet_cksum = 0; - dev->rx_ring.desc[i].desc_status = 0; - dev->rx_ring.desc[i].desc_errors = 0; - dev->rx_ring.desc[i].vlan_tag = 0; + dev->rx_ring.desc[i].base_address = kmem_phys; + dev->rx_ring.desc[i].packet_length = 0; + dev->rx_ring.desc[i].packet_cksum = 0; + dev->rx_ring.desc[i].desc_status = 0; + dev->rx_ring.desc[i].desc_errors = 0; + dev->rx_ring.desc[i].vlan_tag = 0; } dev->rx_ring.head = 0; dev->rx_ring.tail = CONFIG_E1000_N_RX_DESC-1; @@ -379,7 +378,7 @@ static int e1000_transmit(struct e1000_dev *e1000) { int tail = e1000->tx_ring.tail; unsigned char *cp = (unsigned char *) - (e1000->tx_ring.buf + tail * CONFIG_E1000_BUFF_SIZE); + (e1000->tx_ring.buf + tail * CONFIG_E1000_BUFF_SIZE); int count = e1000->uip_dev.d_len; /* Verify that the hardware is ready to send another packet. If we get @@ -388,7 +387,7 @@ static int e1000_transmit(struct e1000_dev *e1000) */ if (!e1000->tx_ring.desc[tail].desc_status) - return -1; + return -1; /* Increment statistics */ @@ -446,14 +445,14 @@ static int e1000_uiptxpoll(struct uip_driver_s *dev) */ if (e1000->uip_dev.d_len > 0) { - uip_arp_out(&e1000->uip_dev); - e1000_transmit(e1000); + uip_arp_out(&e1000->uip_dev); + e1000_transmit(e1000); - /* Check if there is room in the device to hold another packet. If not, - * return a non-zero value to terminate the poll. - */ - if (!e1000->tx_ring.desc[tail].desc_status) - return -1; + /* Check if there is room in the device to hold another packet. If not, + * return a non-zero value to terminate the poll. + */ + if (!e1000->tx_ring.desc[tail].desc_status) + return -1; } /* If zero is returned, the polling will continue until all connections have @@ -484,75 +483,75 @@ static void e1000_receive(struct e1000_dev *e1000) { int head = e1000->rx_ring.head; unsigned char *cp = (unsigned char *) - (e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); + (e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); int cnt; while (e1000->rx_ring.desc[head].desc_status) { - /* Check for errors and update statistics */ + /* Check for errors and update statistics */ - // Here we do not handle packets that exceed packet-buffer size - if ((e1000->rx_ring.desc[head].desc_status & 3) == 1) { - cprintf("NIC READ: Oversized packet\n"); - goto next; - } + // Here we do not handle packets that exceed packet-buffer size + if ((e1000->rx_ring.desc[head].desc_status & 3) == 1) { + cprintf("NIC READ: Oversized packet\n"); + goto next; + } - /* Check if the packet is a valid size for the uIP buffer configuration */ + /* Check if the packet is a valid size for the uIP buffer configuration */ - // get the number of actual data-bytes in this packet - cnt = e1000->rx_ring.desc[head].packet_length; + // get the number of actual data-bytes in this packet + cnt = e1000->rx_ring.desc[head].packet_length; - if (cnt > CONFIG_NET_BUFSIZE || cnt < 14) { - cprintf("NIC READ: invalid package size\n"); - goto next; - } + if (cnt > CONFIG_NET_BUFSIZE || cnt < 14) { + cprintf("NIC READ: invalid package size\n"); + goto next; + } - /* Copy the data data from the hardware to e1000->uip_dev.d_buf. Set - * amount of data in e1000->uip_dev.d_len - */ + /* Copy the data data from the hardware to e1000->uip_dev.d_buf. Set + * amount of data in e1000->uip_dev.d_len + */ - // now we try to copy these data-bytes to the UIP buffer - memcpy(e1000->uip_dev.d_buf, cp, cnt); - e1000->uip_dev.d_len = cnt; + // now we try to copy these data-bytes to the UIP buffer + memcpy(e1000->uip_dev.d_buf, cp, cnt); + e1000->uip_dev.d_len = cnt; - /* We only accept IP packets of the configured type and ARP packets */ + /* We only accept IP packets of the configured type and ARP packets */ #ifdef CONFIG_NET_IPv6 - if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) #else - if (BUF->type == HTONS(UIP_ETHTYPE_IP)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP)) #endif - { - uip_arp_ipin(&e1000->uip_dev); - uip_input(&e1000->uip_dev); + { + uip_arp_ipin(&e1000->uip_dev); + uip_input(&e1000->uip_dev); - /* If the above function invocation resulted in data that should be - * sent out on the network, the field d_len will set to a value > 0. - */ + /* If the above function invocation resulted in data that should be + * sent out on the network, the field d_len will set to a value > 0. + */ - if (e1000->uip_dev.d_len > 0) { - uip_arp_out(&e1000->uip_dev); - e1000_transmit(e1000); - } - } - else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { - uip_arp_arpin(&e1000->uip_dev); + if (e1000->uip_dev.d_len > 0) { + uip_arp_out(&e1000->uip_dev); + e1000_transmit(e1000); + } + } + else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { + uip_arp_arpin(&e1000->uip_dev); - /* If the above function invocation resulted in data that should be - * sent out on the network, the field d_len will set to a value > 0. - */ + /* If the above function invocation resulted in data that should be + * sent out on the network, the field d_len will set to a value > 0. + */ - if (e1000->uip_dev.d_len > 0) { - e1000_transmit(e1000); - } - } + if (e1000->uip_dev.d_len > 0) { + e1000_transmit(e1000); + } + } next: - e1000->rx_ring.desc[head].desc_status = 0; - e1000->rx_ring.head = (head + 1) % CONFIG_E1000_N_RX_DESC; - e1000->rx_ring.free++; - head = e1000->rx_ring.head; - cp = (unsigned char *)(e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); + e1000->rx_ring.desc[head].desc_status = 0; + e1000->rx_ring.head = (head + 1) % CONFIG_E1000_N_RX_DESC; + e1000->rx_ring.free++; + head = e1000->rx_ring.head; + cp = (unsigned char *)(e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); } } @@ -616,7 +615,7 @@ static void e1000_polltimer(int argc, uint32_t arg, ...) * the TX poll if he are unable to accept another packet for transmission. */ if (!e1000->tx_ring.desc[tail].desc_status) - return; + return; /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm.. * might be bug here. Does this mean if there is a transmit in progress, @@ -652,8 +651,8 @@ static int e1000_ifup(struct uip_driver_s *dev) struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; ndbg("Bringing up: %d.%d.%d.%d\n", - dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, - (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); + dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, + (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ e1000_init(e1000); @@ -663,9 +662,9 @@ static int e1000_ifup(struct uip_driver_s *dev) (void)wd_start(e1000->txpoll, E1000_WDDELAY, e1000_polltimer, 1, (uint32_t)e1000); if (e1000_inl(e1000, E1000_STATUS) & 2) - e1000->bifup = true; + e1000->bifup = true; else - e1000->bifup = false; + e1000->bifup = false; return OK; } @@ -750,9 +749,9 @@ static int e1000_txavail(struct uip_driver_s *dev) /* Ignore the notification if the interface is not yet up */ if (e1000->bifup) { - /* Check if there is room in the hardware to hold another outgoing packet. */ - if (e1000->tx_ring.desc[tail].desc_status) - (void)uip_poll(&e1000->uip_dev, e1000_uiptxpoll); + /* Check if there is room in the hardware to hold another outgoing packet. */ + if (e1000->tx_ring.desc[tail].desc_status) + (void)uip_poll(&e1000->uip_dev, e1000_uiptxpoll); } irqrestore(flags); @@ -780,11 +779,11 @@ static int e1000_txavail(struct uip_driver_s *dev) #ifdef CONFIG_NET_IGMP static int e1000_addmac(struct uip_driver_s *dev, const uint8_t *mac) { - struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; + struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif @@ -809,15 +808,15 @@ static int e1000_addmac(struct uip_driver_s *dev, const uint8_t *mac) #ifdef CONFIG_NET_IGMP static int e1000_rmmac(struct uip_driver_s *dev, const uint8_t *mac) { - struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; + struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif -static irqreturn_t e1000_interrupt_handler(int irq, void *dev_id) +irqreturn_t e1000_interrupt_handler(struct Trapframe *tf, void *dev_id) { struct e1000_dev *e1000 = (struct e1000_dev *)dev_id; @@ -827,27 +826,27 @@ static irqreturn_t e1000_interrupt_handler(int irq, void *dev_id) // not for me if (intr_cause == 0) - return IRQ_NONE; + return IRQ_NONE; /* Handle interrupts according to status bit settings */ // Link status change if (intr_cause & (1<<2)) { - if (e1000_inl(e1000, E1000_STATUS) & 2) - e1000->bifup = true; - else - e1000->bifup = false; + if (e1000_inl(e1000, E1000_STATUS) & 2) + e1000->bifup = true; + else + e1000->bifup = false; } /* Check if we received an incoming packet, if so, call skel_receive() */ // Rx-descriptor Timer expired if (intr_cause & (1<<7)) - e1000_receive(e1000); + e1000_receive(e1000); // Tx queue empty if (intr_cause & (1<<1)) - wd_cancel(e1000->txtimeout); + wd_cancel(e1000->txtimeout); /* Check is a packet transmission just completed. If so, call skel_txdone. * This may disable further Tx interrupts if there are no pending @@ -856,17 +855,17 @@ static irqreturn_t e1000_interrupt_handler(int irq, void *dev_id) // Tx-descriptor Written back if (intr_cause & (1<<0)) - uip_poll(&e1000->uip_dev, e1000_uiptxpoll); + uip_poll(&e1000->uip_dev, e1000_uiptxpoll); // Rx-Descriptors Low if (intr_cause & (1<<4)) { - int tail; - tail = e1000->rx_ring.tail + e1000->rx_ring.free; - tail %= CONFIG_E1000_N_RX_DESC; - e1000->rx_ring.tail = tail; - e1000->rx_ring.free = 0; - e1000_outl(e1000, E1000_RDT, tail); + int tail; + tail = e1000->rx_ring.tail + e1000->rx_ring.free; + tail %= CONFIG_E1000_N_RX_DESC; + e1000->rx_ring.tail = tail; + e1000->rx_ring.free = 0; + e1000_outl(e1000, E1000_RDT, tail); } return IRQ_HANDLED; @@ -886,21 +885,20 @@ static pci_id_t e1000_id_table[] = { static int e1000_probe(uint16_t addr, pci_id_t id) { uint32_t mmio_base, mmio_size; - uint32_t size; - int err; + uint32_t pci_cmd, size; + int err, irq, flags; void *kmem, *omem; struct e1000_dev *dev; // alloc e1000_dev memory - if ((dev = kzalloc(sizeof(struct e1000_dev))) == NULL) - return -1; - - // save pci addr - dev->pci_addr = addr; + dev = kzalloc(sizeof(struct e1000_dev)); + if (dev == NULL) + return -1; // enable device - if ((err = pci_enable_device(addr, PCI_BUS_MASTER)) < 0) - goto error; + err = pci_enable_device(addr, PCI_RESOURCE_MEM); + if (err) + goto error; // get e1000 device type dev->pci_dev_id = id.join; @@ -910,20 +908,33 @@ static int e1000_probe(uint16_t addr, pci_id_t id) mmio_size = pci_resource_len(addr, 0); err = rgmp_memmap_nocache(mmio_base, mmio_size, mmio_base); if (err) - goto error; + goto error; dev->phy_mem_base = mmio_base; dev->io_mem_base = mmio_base; dev->mem_size = mmio_size; + // make sure the controller's Bus Master capability is enabled + pci_cmd = pci_config_readl(addr, PCI_COMMAND); + pci_cmd |= (1<<2); + pci_config_writel(addr, PCI_COMMAND, pci_cmd); + // MAC address memset(dev->dst_mac, 0xFF, 6); memcpy(dev->src_mac, (void *)(dev->io_mem_base+E1000_RA), 6); - // IRQ setup + // get e1000 IRQ + flags = 0; + irq = pci_enable_msi(addr); + if (irq == 0) { + irq = pci_read_irq(addr); + flags |= IDC_SHARE; + } + dev->irq = irq; dev->int_desc.handler = e1000_interrupt_handler; dev->int_desc.dev_id = dev; - if ((err = pci_request_irq(addr, &dev->int_desc, 0)) < 0) - goto err0; + err = rgmp_request_irq(irq, &dev->int_desc, flags); + if (err) + goto err0; // Here we alloc a big block of memory once and make it // aligned to page boundary and multiple of page size. This @@ -931,19 +942,15 @@ static int e1000_probe(uint16_t addr, pci_id_t id) // should be mapped no-cache which will hugely reduce memory // access performance. The page size alloc will restrict // this bad effect only within the memory we alloc here. - // - // NEED FIX: the memalign may alloc memory continous in - // virtual address but dis-continous in physical address - // due to RGMP memory setup. size = CONFIG_E1000_N_TX_DESC * sizeof(struct tx_desc) + - CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + - CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + - CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; + CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + + CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + + CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; size = ROUNDUP(size, PGSIZE); omem = kmem = memalign(PGSIZE, size); if (kmem == NULL) { - err = -ENOMEM; - goto err1; + err = -ENOMEM; + goto err1; } rgmp_memremap_nocache((uintptr_t)kmem, size); @@ -984,7 +991,7 @@ static int e1000_probe(uint16_t addr, pci_id_t id) /* Register the device with the OS so that socket IOCTLs can be performed */ err = netdev_register(&dev->uip_dev); if (err) - goto err2; + goto err2; // insert into e1000_list dev->next = e1000_list.next; @@ -993,14 +1000,14 @@ static int e1000_probe(uint16_t addr, pci_id_t id) return 0; -err2: + err2: rgmp_memremap((uintptr_t)omem, size); free(omem); -err1: - pci_free_irq(addr); -err0: + err1: + rgmp_free_irq(irq, &dev->int_desc); + err0: rgmp_memunmap(mmio_base, mmio_size); -error: + error: kfree(dev); cprintf("e1000 device probe fail: %d\n", err); return err; @@ -1021,21 +1028,21 @@ void e1000_mod_exit(void) struct e1000_dev *dev; size = CONFIG_E1000_N_TX_DESC * sizeof(struct tx_desc) + - CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + - CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + - CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; + CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + + CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + + CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; size = ROUNDUP(size, PGSIZE); for (dev=e1000_list.next; dev!=NULL; dev=dev->next) { - netdev_unregister(&dev->uip_dev); - e1000_reset(dev); - wd_delete(dev->txpoll); - wd_delete(dev->txtimeout); - rgmp_memremap((uintptr_t)dev->tx_ring.desc, size); - free(dev->tx_ring.desc); - pci_free_irq(dev->pci_addr); - rgmp_memunmap((uintptr_t)dev->io_mem_base, dev->mem_size); - kfree(dev); + netdev_unregister(&dev->uip_dev); + e1000_reset(dev); + wd_delete(dev->txpoll); + wd_delete(dev->txtimeout); + rgmp_memremap((uintptr_t)dev->tx_ring.desc, size); + free(dev->tx_ring.desc); + rgmp_free_irq(dev->irq, &dev->int_desc); + rgmp_memunmap((uintptr_t)dev->io_mem_base, dev->mem_size); + kfree(dev); } e1000_list.next = NULL; diff --git a/nuttx/drivers/net/e1000.h b/nuttx/drivers/net/e1000.h index 63ff53e3c3..6614ad77ec 100644 --- a/nuttx/drivers/net/e1000.h +++ b/nuttx/drivers/net/e1000.h @@ -44,7 +44,9 @@ * Included Files ****************************************************************************/ -#include +#include +#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/drivers/net/vnet.c b/nuttx/drivers/net/vnet.c index e05a39675c..f1e2465b96 100644 --- a/nuttx/drivers/net/vnet.c +++ b/nuttx/drivers/net/vnet.c @@ -168,30 +168,30 @@ static int vnet_transmit(FAR struct vnet_driver_s *vnet) { int err; - /* Verify that the hardware is ready to send another packet. If we get - * here, then we are committed to sending a packet; Higher level logic - * must have assured that there is not transmission in progress. - */ + /* Verify that the hardware is ready to send another packet. If we get + * here, then we are committed to sending a packet; Higher level logic + * must have assured that there is not transmission in progress. + */ - /* Increment statistics */ + /* Increment statistics */ - /* Send the packet: address=vnet->sk_dev.d_buf, length=vnet->sk_dev.d_len */ + /* Send the packet: address=vnet->sk_dev.d_buf, length=vnet->sk_dev.d_len */ err = vnet_xmit(vnet->vnet, (char *)vnet->sk_dev.d_buf, vnet->sk_dev.d_len); if (err) { - /* Setup the TX timeout watchdog (perhaps restarting the timer) */ - //(void)wd_start(vnet->sk_txtimeout, VNET_TXTIMEOUT, vnet_txtimeout, 1, (uint32_t)vnet); + /* Setup the TX timeout watchdog (perhaps restarting the timer) */ + //(void)wd_start(vnet->sk_txtimeout, VNET_TXTIMEOUT, vnet_txtimeout, 1, (uint32_t)vnet); - // When vnet_xmit fail, it means TX buffer is full. Watchdog - // is of no use here because no TX done INT will happen. So - // we reset the TX buffer directly. + // When vnet_xmit fail, it means TX buffer is full. Watchdog + // is of no use here because no TX done INT will happen. So + // we reset the TX buffer directly. #ifdef CONFIG_DEBUG - cprintf("VNET: TX buffer is full\n"); + cprintf("VNET: TX buffer is full\n"); #endif - return ERROR; + return ERROR; } else { - // this step may be unnecessary here - vnet_txdone(vnet); + // this step may be unnecessary here + vnet_txdone(vnet); } return OK; @@ -223,29 +223,29 @@ static int vnet_transmit(FAR struct vnet_driver_s *vnet) static int vnet_uiptxpoll(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - /* If the polling resulted in data that should be sent out on the network, - * the field d_len is set to a value > 0. - */ + /* If the polling resulted in data that should be sent out on the network, + * the field d_len is set to a value > 0. + */ - if (vnet->sk_dev.d_len > 0) + if (vnet->sk_dev.d_len > 0) { - uip_arp_out(&vnet->sk_dev); - vnet_transmit(vnet); + uip_arp_out(&vnet->sk_dev); + vnet_transmit(vnet); - /* Check if there is room in the device to hold another packet. If not, - * return a non-zero value to terminate the poll. - */ - if (vnet_is_txbuff_full(vnet->vnet)) - return 1; + /* Check if there is room in the device to hold another packet. If not, + * return a non-zero value to terminate the poll. + */ + if (vnet_is_txbuff_full(vnet->vnet)) + return 1; } - /* If zero is returned, the polling will continue until all connections have - * been examined. - */ + /* If zero is returned, the polling will continue until all connections have + * been examined. + */ - return 0; + return 0; } /**************************************************************************** @@ -265,53 +265,54 @@ static int vnet_uiptxpoll(struct uip_driver_s *dev) * ****************************************************************************/ -void rtos_vnet_recv(struct rgmp_vnet *rgmp_vnet, char *data, int len) +void rtos_vnet_recv(struct rgmp_vnet *vnet_dummy, char *data, int len) { - struct vnet_driver_s *vnet = rgmp_vnet->priv; + // now only support 1 vnet + struct vnet_driver_s *vnet = &g_vnet[0]; do { - /* Check for errors and update statistics */ + /* Check for errors and update statistics */ - /* Check if the packet is a valid size for the uIP buffer configuration */ - if (len > CONFIG_NET_BUFSIZE || len < 14) { + /* Check if the packet is a valid size for the uIP buffer configuration */ + if (len > CONFIG_NET_BUFSIZE || len < 14) { #ifdef CONFIG_DEBUG - cprintf("VNET: receive invalid packet of size %d\n", len); + cprintf("VNET: receive invalid packet of size %d\n", len); #endif - return; - } + return; + } - // Copy the data data from the hardware to vnet->sk_dev.d_buf. Set - // amount of data in vnet->sk_dev.d_len - memcpy(vnet->sk_dev.d_buf, data, len); - vnet->sk_dev.d_len = len; + // Copy the data data from the hardware to vnet->sk_dev.d_buf. Set + // amount of data in vnet->sk_dev.d_len + memcpy(vnet->sk_dev.d_buf, data, len); + vnet->sk_dev.d_len = len; - /* We only accept IP packets of the configured type and ARP packets */ + /* We only accept IP packets of the configured type and ARP packets */ #ifdef CONFIG_NET_IPv6 - if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) #else - if (BUF->type == HTONS(UIP_ETHTYPE_IP)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP)) #endif - { - uip_arp_ipin(&vnet->sk_dev); - uip_input(&vnet->sk_dev); + { + uip_arp_ipin(&vnet->sk_dev); + uip_input(&vnet->sk_dev); - // If the above function invocation resulted in data that should be - // sent out on the network, the field d_len will set to a value > 0. - if (vnet->sk_dev.d_len > 0) { - uip_arp_out(&vnet->sk_dev); - vnet_transmit(vnet); - } - } - else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { - uip_arp_arpin(&vnet->sk_dev); + // If the above function invocation resulted in data that should be + // sent out on the network, the field d_len will set to a value > 0. + if (vnet->sk_dev.d_len > 0) { + uip_arp_out(&vnet->sk_dev); + vnet_transmit(vnet); + } + } + else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { + uip_arp_arpin(&vnet->sk_dev); - // If the above function invocation resulted in data that should be - // sent out on the network, the field d_len will set to a value > 0. - if (vnet->sk_dev.d_len > 0) { - vnet_transmit(vnet); - } - } + // If the above function invocation resulted in data that should be + // sent out on the network, the field d_len will set to a value > 0. + if (vnet->sk_dev.d_len > 0) { + vnet_transmit(vnet); + } + } } while (0); /* While there are more packets to be processed */ } @@ -335,17 +336,17 @@ void rtos_vnet_recv(struct rgmp_vnet *rgmp_vnet, char *data, int len) static void vnet_txdone(FAR struct vnet_driver_s *vnet) { - /* Check for errors and update statistics */ + /* Check for errors and update statistics */ - /* If no further xmits are pending, then cancel the TX timeout and - * disable further Tx interrupts. - */ + /* If no further xmits are pending, then cancel the TX timeout and + * disable further Tx interrupts. + */ - //wd_cancel(vnet->sk_txtimeout); + //wd_cancel(vnet->sk_txtimeout); - /* Then poll uIP for new XMIT data */ + /* Then poll uIP for new XMIT data */ - (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); + (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); } /**************************************************************************** @@ -369,15 +370,15 @@ static void vnet_txdone(FAR struct vnet_driver_s *vnet) static void vnet_txtimeout(int argc, uint32_t arg, ...) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; - /* Increment statistics and dump debug info */ + /* Increment statistics and dump debug info */ - /* Then reset the hardware */ + /* Then reset the hardware */ - /* Then poll uIP for new XMIT data */ + /* Then poll uIP for new XMIT data */ - (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); + (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); } /**************************************************************************** @@ -400,28 +401,28 @@ static void vnet_txtimeout(int argc, uint32_t arg, ...) static void vnet_polltimer(int argc, uint32_t arg, ...) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; - /* Check if there is room in the send another TX packet. We cannot perform - * the TX poll if he are unable to accept another packet for transmission. - */ - if (vnet_is_txbuff_full(vnet->vnet)) { + /* Check if there is room in the send another TX packet. We cannot perform + * the TX poll if he are unable to accept another packet for transmission. + */ + if (vnet_is_txbuff_full(vnet->vnet)) { #ifdef CONFIG_DEBUG - cprintf("VNET: TX buffer is full\n"); + cprintf("VNET: TX buffer is full\n"); #endif - return; - } + return; + } - /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm.. - * might be bug here. Does this mean if there is a transmit in progress, - * we will missing TCP time state updates? - */ + /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm.. + * might be bug here. Does this mean if there is a transmit in progress, + * we will missing TCP time state updates? + */ - (void)uip_timer(&vnet->sk_dev, vnet_uiptxpoll, VNET_POLLHSEC); + (void)uip_timer(&vnet->sk_dev, vnet_uiptxpoll, VNET_POLLHSEC); - /* Setup the watchdog poll timer again */ + /* Setup the watchdog poll timer again */ - (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, arg); + (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, arg); } /**************************************************************************** @@ -443,20 +444,20 @@ static void vnet_polltimer(int argc, uint32_t arg, ...) static int vnet_ifup(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - ndbg("Bringing up: %d.%d.%d.%d\n", - dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, - (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); + ndbg("Bringing up: %d.%d.%d.%d\n", + dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, + (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); - /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ + /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ - /* Set and activate a timer process */ + /* Set and activate a timer process */ - (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, (uint32_t)vnet); + (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, (uint32_t)vnet); - vnet->sk_bifup = true; - return OK; + vnet->sk_bifup = true; + return OK; } /**************************************************************************** @@ -477,28 +478,28 @@ static int vnet_ifup(struct uip_driver_s *dev) static int vnet_ifdown(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - irqstate_t flags; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + irqstate_t flags; - /* Disable the Ethernet interrupt */ + /* Disable the Ethernet interrupt */ - flags = irqsave(); + flags = irqsave(); - /* Cancel the TX poll timer and TX timeout timers */ + /* Cancel the TX poll timer and TX timeout timers */ - wd_cancel(vnet->sk_txpoll); - //wd_cancel(vnet->sk_txtimeout); + wd_cancel(vnet->sk_txpoll); + //wd_cancel(vnet->sk_txtimeout); - /* Put the the EMAC is its reset, non-operational state. This should be - * a known configuration that will guarantee the vnet_ifup() always - * successfully brings the interface back up. - */ + /* Put the the EMAC is its reset, non-operational state. This should be + * a known configuration that will guarantee the vnet_ifup() always + * successfully brings the interface back up. + */ - /* Mark the device "down" */ + /* Mark the device "down" */ - vnet->sk_bifup = false; - irqrestore(flags); - return OK; + vnet->sk_bifup = false; + irqrestore(flags); + return OK; } /**************************************************************************** @@ -522,35 +523,35 @@ static int vnet_ifdown(struct uip_driver_s *dev) static int vnet_txavail(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - irqstate_t flags; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + irqstate_t flags; - /* Disable interrupts because this function may be called from interrupt - * level processing. - */ + /* Disable interrupts because this function may be called from interrupt + * level processing. + */ - flags = irqsave(); + flags = irqsave(); - /* Ignore the notification if the interface is not yet up */ + /* Ignore the notification if the interface is not yet up */ - if (vnet->sk_bifup) + if (vnet->sk_bifup) { - /* Check if there is room in the hardware to hold another outgoing packet. */ - if (vnet_is_txbuff_full(vnet->vnet)) { + /* Check if there is room in the hardware to hold another outgoing packet. */ + if (vnet_is_txbuff_full(vnet->vnet)) { #ifdef CONFIG_DEBUG - cprintf("VNET: TX buffer is full\n"); + cprintf("VNET: TX buffer is full\n"); #endif - goto out; - } + goto out; + } - /* If so, then poll uIP for new XMIT data */ + /* If so, then poll uIP for new XMIT data */ - (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); + (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); } -out: - irqrestore(flags); - return OK; + out: + irqrestore(flags); + return OK; } /**************************************************************************** @@ -574,11 +575,11 @@ out: #ifdef CONFIG_NET_IGMP static int vnet_addmac(struct uip_driver_s *dev, FAR const uint8_t *mac) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif @@ -603,11 +604,11 @@ static int vnet_addmac(struct uip_driver_s *dev, FAR const uint8_t *mac) #ifdef CONFIG_NET_IGMP static int vnet_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif @@ -632,41 +633,41 @@ static int vnet_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac) * ****************************************************************************/ -int vnet_init(struct rgmp_vnet *vnet) +void vnet_initialize(void) { - struct vnet_driver_s *priv; - static int i = 0; + struct vnet_driver_s *priv; + struct rgmp_vnet *vnet = vnet_list.next; + int i; - if (i >= CONFIG_VNET_NINTERFACES) - return -1; + for (i=0; isk_dev.d_ifup = vnet_ifup; /* I/F down callback */ - priv->sk_dev.d_ifdown = vnet_ifdown; /* I/F up (new IP address) callback */ - priv->sk_dev.d_txavail = vnet_txavail; /* New TX data callback */ + memset(priv, 0, sizeof(struct vnet_driver_s)); + priv->sk_dev.d_ifup = vnet_ifup; /* I/F down callback */ + priv->sk_dev.d_ifdown = vnet_ifdown; /* I/F up (new IP address) callback */ + priv->sk_dev.d_txavail = vnet_txavail; /* New TX data callback */ #ifdef CONFIG_NET_IGMP - priv->sk_dev.d_addmac = vnet_addmac; /* Add multicast MAC address */ - priv->sk_dev.d_rmmac = vnet_rmmac; /* Remove multicast MAC address */ + priv->sk_dev.d_addmac = vnet_addmac; /* Add multicast MAC address */ + priv->sk_dev.d_rmmac = vnet_rmmac; /* Remove multicast MAC address */ #endif - priv->sk_dev.d_private = (void*)priv; /* Used to recover private state from dev */ + priv->sk_dev.d_private = (void*)g_vnet; /* Used to recover private state from dev */ - /* Create a watchdog for timing polling for and timing of transmisstions */ + /* Create a watchdog for timing polling for and timing of transmisstions */ - priv->sk_txpoll = wd_create(); /* Create periodic poll timer */ - //priv->sk_txtimeout = wd_create(); /* Create TX timeout timer */ + priv->sk_txpoll = wd_create(); /* Create periodic poll timer */ + //priv->sk_txtimeout = wd_create(); /* Create TX timeout timer */ - priv->vnet = vnet; - vnet->priv = priv; + priv->vnet = vnet; - /* Register the device with the OS */ + /* Register the device with the OS */ - (void)netdev_register(&priv->sk_dev); - - return 0; + (void)netdev_register(&priv->sk_dev); + vnet = vnet->next; + } } #endif /* CONFIG_NET && CONFIG_NET_VNET */ diff --git a/nuttx/drivers/power/Make.defs b/nuttx/drivers/power/Make.defs index 9e6307ae21..45c6aebc32 100644 --- a/nuttx/drivers/power/Make.defs +++ b/nuttx/drivers/power/Make.defs @@ -47,7 +47,7 @@ CSRCS += pm_activity.c pm_changestate.c pm_checkstate.c pm_initialize.c pm_regis POWER_DEPPATH := --dep-path power POWER_VPATH := :power -POWER_CFLAGS := ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power} +POWER_CFLAGS := ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power} endif @@ -73,7 +73,7 @@ endif POWER_DEPPATH := --dep-path power POWER_VPATH := :power -POWER_CFLAGS := ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power} +POWER_CFLAGS := ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power} endif diff --git a/nuttx/drivers/sensors/Make.defs b/nuttx/drivers/sensors/Make.defs index 17750831ec..866ccb0536 100644 --- a/nuttx/drivers/sensors/Make.defs +++ b/nuttx/drivers/sensors/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/sensors/Make.defs # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -57,4 +57,4 @@ endif DEPPATH += --dep-path sensors VPATH += :sensors -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/sensors} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/sensors} diff --git a/nuttx/drivers/usbdev/Make.defs b/nuttx/drivers/usbdev/Make.defs index 782c185452..f1b3c405ae 100644 --- a/nuttx/drivers/usbdev/Make.defs +++ b/nuttx/drivers/usbdev/Make.defs @@ -59,5 +59,5 @@ CSRCS += usbdev_trace.c usbdev_trprintf.c DEPPATH += --dep-path usbdev VPATH += :usbdev -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbdev} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbdev} endif diff --git a/nuttx/drivers/usbdev/pl2303.c b/nuttx/drivers/usbdev/pl2303.c index 95f26c1854..69bf879656 100644 --- a/nuttx/drivers/usbdev/pl2303.c +++ b/nuttx/drivers/usbdev/pl2303.c @@ -132,7 +132,7 @@ /* USB Controller */ #ifndef CONFIG_USBDEV_SELFPOWERED -# define SELFPOWERED USB_CONFIG_ATTR_SELFPOWER +# define SELFPOWERED USB_CONFIG_ATT_SELFPOWER #else # define SELFPOWERED (0) #endif diff --git a/nuttx/drivers/usbdev/usbmsc.h b/nuttx/drivers/usbdev/usbmsc.h index 883a499517..6a5530d9d9 100644 --- a/nuttx/drivers/usbdev/usbmsc.h +++ b/nuttx/drivers/usbdev/usbmsc.h @@ -227,7 +227,7 @@ /* USB Controller */ #ifndef CONFIG_USBDEV_SELFPOWERED -# define SELFPOWERED USB_CONFIG_ATTR_SELFPOWER +# define SELFPOWERED USB_CONFIG_ATT_SELFPOWER #else # define SELFPOWERED (0) #endif diff --git a/nuttx/drivers/usbhost/Make.defs b/nuttx/drivers/usbhost/Make.defs index 91753ef318..fd54ab53e7 100644 --- a/nuttx/drivers/usbhost/Make.defs +++ b/nuttx/drivers/usbhost/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/usbhost/Make.defs # -# Copyright (C) 2010-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -54,4 +54,4 @@ endif DEPPATH += --dep-path usbhost VPATH += :usbhost -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbhost} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbhost} diff --git a/nuttx/drivers/wireless/Make.defs b/nuttx/drivers/wireless/Make.defs index 86ea90e25e..f47f7666a5 100644 --- a/nuttx/drivers/wireless/Make.defs +++ b/nuttx/drivers/wireless/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/wireless/Make.defs # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -43,5 +43,5 @@ CSRCS += cc1101.c ISM1_868MHzGFSK100kbps.c ISM2_905MHzGFSK250kbps.c DEPPATH += --dep-path wireless/cc1101 VPATH += :wireless/cc1101 -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/wireless/cc1101} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/wireless/cc1101} endif diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile index 6955c164b5..ce952e06f9 100644 --- a/nuttx/fs/Makefile +++ b/nuttx/fs/Makefile @@ -120,21 +120,25 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) .depend: Makefile $(SRCS) - $(Q) $(MKDEP) --dep-path . $(MMAPDEPPATH) $(FATDEPPATH) $(ROMFSDEPPATH) $(NXFFSDEPPATH) $(NFSDEPPATH) \ - "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) --dep-path . $(MMAPDEPPATH) $(FATDEPPATH) $(ROMFSDEPPATH) $(NXFFSDEPPATH) $(NFSDEPPATH) \ + $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, $(BIN)) + @rm -f $(BIN) *~ .*.swp $(call CLEAN) + @( for dir in $(SUBDIRS); do \ + rm -f $${dir}/*~ $${dir}/.*.swp; \ + done ; ) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/nuttx/fs/fs_stat.c b/nuttx/fs/fs_stat.c index 4df25028f3..cf27e87a6c 100644 --- a/nuttx/fs/fs_stat.c +++ b/nuttx/fs/fs_stat.c @@ -1,7 +1,7 @@ /**************************************************************************** * fs/fs_stat.c * - * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009 , 2012Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -122,8 +122,7 @@ static inline int statroot(FAR struct stat *buf) /**************************************************************************** * Name: stat * - * Returned Value: - * Zero on success; -1 on failure with errno set: + * Return: Zero on success; -1 on failure with errno set: * * EACCES Search permission is denied for one of the directories in the * path prefix of path. @@ -135,7 +134,7 @@ static inline int statroot(FAR struct stat *buf) * ****************************************************************************/ -int stat(FAR const char *path, FAR struct stat *buf) +int stat(const char *path, FAR struct stat *buf) { FAR struct inode *inode; const char *relpath = NULL; diff --git a/nuttx/graphics/Makefile b/nuttx/graphics/Makefile index 238e14df42..6e549c1dd7 100644 --- a/nuttx/graphics/Makefile +++ b/nuttx/graphics/Makefile @@ -33,6 +33,7 @@ # ############################################################################ +-include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs DEPPATH = --dep-path . @@ -43,34 +44,34 @@ endif include nxglib/Make.defs DEPPATH += --dep-path nxglib -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxglib} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxglib} include nxbe/Make.defs DEPPATH += --dep-path nxbe -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxbe} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxbe} ifeq ($(CONFIG_NX_MULTIUSER),y) include nxmu/Make.defs DEPPATH += --dep-path nxmu -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxmu} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxmu} else include nxsu/Make.defs DEPPATH += --dep-path nxsu -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxsu} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxsu} endif include nxtk/Make.defs DEPPATH += --dep-path nxtk -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxtk} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxtk} include nxfonts/Make.defs DEPPATH += --dep-path nxfonts -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxfonts} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxfonts} ifeq ($(CONFIG_NXCONSOLE),y) include nxconsole/Make.defs DEPPATH += --dep-path nxconsole -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxconsole} +CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/graphics/nxconsole} endif ASRCS = $(NXGLIB_ASRCS) $(NXBE_ASRCS) $(NX_ASRCS) $(NXTK_ASRCS) $(NXFONTS_ASRCS) $(NXCON_ASRCS) @@ -96,84 +97,84 @@ all: mklibgraphics gen32bppsources genfontsources gen1bppsources: - $(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=1 EXTRADEFINES=$(EXTRADEFINES) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=1 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=1 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=1 EXTRADEFINES=$(EXTRADEFINES) gen2bppsource: - $(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=2 EXTRADEFINES=$(EXTRADEFINES) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=2 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=2 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=2 EXTRADEFINES=$(EXTRADEFINES) gen4bppsource: - $(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=4 EXTRADEFINES=$(EXTRADEFINES) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=4 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=4 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=4 EXTRADEFINES=$(EXTRADEFINES) gen8bppsource: - $(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=8 EXTRADEFINES=$(EXTRADEFINES) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=8 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=8 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=8 EXTRADEFINES=$(EXTRADEFINES) gen16bppsource: - $(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=16 EXTRADEFINES=$(EXTRADEFINES) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=16 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=16 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=16 EXTRADEFINES=$(EXTRADEFINES) gen24bppsource: - $(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=24 EXTRADEFINES=$(EXTRADEFINES) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=24 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=24 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=24 EXTRADEFINES=$(EXTRADEFINES) gen32bppsources: - $(Q) $(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=32 EXTRADEFINES=$(EXTRADEFINES) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=32 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxglib -f Makefile.sources TOPDIR=$(TOPDIR) NXGLIB_BITSPERPIXEL=32 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_BITSPERPIXEL=32 EXTRADEFINES=$(EXTRADEFINES) genfontsources: ifeq ($(CONFIG_NXFONT_SANS23X27),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=1 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=1 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SANS22X29),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=2 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=2 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SANS28X37),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=3 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=3 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SANS39X48),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=4 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=4 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SANS17X23B),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=16 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=16 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SANS20X27B),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=17 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=17 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SANS22X29B),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=5 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=5 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SANS28X37B),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=6 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=6 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SANS40X49B),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=7 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=7 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SERIF22X29),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=8 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=8 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SERIF29X37),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=9 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=9 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SERIF38X48),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=10 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=10 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SERIF22X28B),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=11 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=11 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SERIF27X38B),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=12 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=12 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SERIF38X49B),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=13 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=13 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SANS17X22),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=14 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=14 EXTRADEFINES=$(EXTRADEFINES) endif ifeq ($(CONFIG_NXFONT_SANS20X26),y) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=15 EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources TOPDIR=$(TOPDIR) NXFONTS_FONTID=15 EXTRADEFINES=$(EXTRADEFINES) endif gensources: gen1bppsources gen2bppsource gen4bppsource gen8bppsource gen16bppsource gen24bppsource gen32bppsources genfontsources @@ -185,29 +186,30 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) mklibgraphics: gensources $(BIN) .depend: gensources Makefile $(SRCS) - $(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend context: gensources clean: - $(Q) $(MAKE) -C nxglib -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) - $(call DELFILE, $(BIN)) + @$(MAKE) -C nxglib -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources clean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) + @rm -f $(BIN) *~ .*.swp $(call CLEAN) distclean: clean - $(Q) $(MAKE) -C nxglib -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) - $(Q) $(MAKE) -C nxfonts -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @$(MAKE) -C nxglib -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) + @$(MAKE) -C nxfonts -f Makefile.sources distclean TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) + @rm -f Make.dep .depend -include Make.dep diff --git a/nuttx/graphics/nxfonts/Makefile.sources b/nuttx/graphics/nxfonts/Makefile.sources index 76a099dcbe..f2aa87cafd 100644 --- a/nuttx/graphics/nxfonts/Makefile.sources +++ b/nuttx/graphics/nxfonts/Makefile.sources @@ -33,6 +33,7 @@ # ############################################################################ +-include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs ifdef NXFONTS_BITSPERPIXEL @@ -176,14 +177,13 @@ all: $(GEN_CSRC) .PHONY : clean distclean $(GEN_CSRC) : $(DEPENDENCY) - $(call PREPROCESS, $<, $(GEN_TMP)) - $(Q) cat $(GEN_TMP) | sed -e "/^#/d" >$@ - $(Q) rm -f $(GEN_TMP) + @$(call PREPROCESS, $<, $(GEN_TMP)) + @cat $(GEN_TMP) | sed -e "/^#/d" >$@ + @rm -f $(GEN_TMP) clean: - $(call DELFILE, *.i) - $(call CLEAN) + @rm -f *~ .*.swp *.i distclean: clean - $(call DELFILE, nxfonts_convert_*bpp.c) - $(call DELFILE, nxfonts_bitmaps_*.c) + @rm -f nxfonts_convert_*bpp.c + @rm -f nxfonts_bitmaps_*.c diff --git a/nuttx/graphics/nxglib/Makefile.sources b/nuttx/graphics/nxglib/Makefile.sources index 71d6e0661b..67f8defc31 100644 --- a/nuttx/graphics/nxglib/Makefile.sources +++ b/nuttx/graphics/nxglib/Makefile.sources @@ -33,6 +33,7 @@ # ############################################################################ +-include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs ifeq ($(NXGLIB_BITSPERPIXEL),1) @@ -122,54 +123,53 @@ all: $(GEN_CSRCS) $(SETP_CSRC) : $(BLITDIR)/nxglib_setpixel.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - $(call PREPROCESS, $(BLITDIR)/nxglib_setpixel.c, $(SETP_TMP)) - $(Q) cat $(SETP_TMP) | sed -e "/^#/d" >$@ - $(Q) rm -f $(SETP_TMP) + @$(call PREPROCESS, $(BLITDIR)/nxglib_setpixel.c, $(SETP_TMP)) + @cat $(SETP_TMP) | sed -e "/^#/d" >$@ + @rm -f $(SETP_TMP) endif $(RFILL_CSRC) : $(BLITDIR)/nxglib_fillrectangle.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - $(call PREPROCESS, $(BLITDIR)/nxglib_fillrectangle.c, $(RFILL_TMP)) - $(Q) cat $(RFILL_TMP) | sed -e "/^#/d" >$@ - $(Q) rm -f $(RFILL_TMP) + @$(call PREPROCESS, $(BLITDIR)/nxglib_fillrectangle.c, $(RFILL_TMP)) + @cat $(RFILL_TMP) | sed -e "/^#/d" >$@ + @rm -f $(RFILL_TMP) endif $(RGET_CSRC) : $(BLITDIR)/nxglib_getrectangle.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - $(call PREPROCESS, $(BLITDIR)/nxglib_getrectangle.c, $(RGET_TMP)) - $(Q) cat $(RGET_TMP) | sed -e "/^#/d" >$@ - $(Q) rm -f $(RGET_TMP) + @$(call PREPROCESS, $(BLITDIR)/nxglib_getrectangle.c, $(RGET_TMP)) + @cat $(RGET_TMP) | sed -e "/^#/d" >$@ + @rm -f $(RGET_TMP) endif $(TFILL_CSRC) : $(BLITDIR)/nxglib_filltrapezoid.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - $(call PREPROCESS, $(BLITDIR)/nxglib_filltrapezoid.c, $(TFILL_TMP)) - $(Q) cat $(TFILL_TMP) | sed -e "/^#/d" >$@ - $(Q) rm -f $(TFILL_TMP) + @$(call PREPROCESS, $(BLITDIR)/nxglib_filltrapezoid.c, $(TFILL_TMP)) + @cat $(TFILL_TMP) | sed -e "/^#/d" >$@ + @rm -f $(TFILL_TMP) endif $(RMOVE_CSRC) : $(BLITDIR)/nxglib_moverectangle.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - $(call PREPROCESS, $(BLITDIR)/nxglib_moverectangle.c, $(RMOVE_TMP)) - $(Q) cat $(RMOVE_TMP) | sed -e "/^#/d" >$@ - $(Q) rm -f $(RMOVE_TMP) + @$(call PREPROCESS, $(BLITDIR)/nxglib_moverectangle.c, $(RMOVE_TMP)) + @cat $(RMOVE_TMP) | sed -e "/^#/d" >$@ + @rm -f $(RMOVE_TMP) endif $(RCOPY_CSRC) : $(BLITDIR)/nxglib_copyrectangle.c nxglib_bitblit.h ifneq ($(NXGLIB_BITSPERPIXEL),) - $(call PREPROCESS, $(BLITDIR)/nxglib_copyrectangle.c, $(RCOPY_TMP)) - $(Q) cat $(RCOPY_TMP) | sed -e "/^#/d" >$@ - $(Q) rm -f $(RCOPY_TMP) + @$(call PREPROCESS, $(BLITDIR)/nxglib_copyrectangle.c, $(RCOPY_TMP)) + @cat $(RCOPY_TMP) | sed -e "/^#/d" >$@ + @rm -f $(RCOPY_TMP) endif clean: - $(call DELFILE, *.i) - $(call CLEAN) + @rm -f *~ .*.swp *.i distclean: clean - $(call DELFILE, nxglib_setpixel_*bpp.c) - $(call DELFILE, nxglib_fillrectangle_*bpp.c) - $(call DELFILE, nxglib_getrectangle_*bpp.c) - $(call DELFILE, nxglib_filltrapezoid_*bpp.c) - $(call DELFILE, nxglib_moverectangle_*bpp.c) - $(call DELFILE, nxglib_copyrectangle_*bpp.c) + @rm -f nxglib_setpixel_*bpp.c + @rm -f nxglib_fillrectangle_*bpp.c + @rm -f nxglib_getrectangle_*bpp.c + @rm -f nxglib_filltrapezoid_*bpp.c + @rm -f nxglib_moverectangle_*bpp.c + @rm -f nxglib_copyrectangle_*bpp.c diff --git a/nuttx/graphics/nxmu/nx_bitmap.c b/nuttx/graphics/nxmu/nx_bitmap.c index a0bd748b09..a86eda96ac 100644 --- a/nuttx/graphics/nxmu/nx_bitmap.c +++ b/nuttx/graphics/nxmu/nx_bitmap.c @@ -100,8 +100,6 @@ int nx_bitmap(NXWINDOW hwnd, FAR const struct nxgl_rect_s *dest, FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; struct nxsvrmsg_bitmap_s outmsg; int i; - int ret; - sem_t sem_done; #ifdef CONFIG_DEBUG if (!wnd || !dest || !src || !origin) @@ -126,32 +124,7 @@ int nx_bitmap(NXWINDOW hwnd, FAR const struct nxgl_rect_s *dest, outmsg.origin.y = origin->y; nxgl_rectcopy(&outmsg.dest, dest); - - /* Create a semaphore for tracking command completion */ - - outmsg.sem_done = &sem_done; - ret = sem_init(&sem_done, 0, 0); - - if (ret != OK) - { - gdbg("sem_init failed: %d\n", errno); - return ret; - } - /* Forward the fill command to the server */ - ret = nxmu_sendwindow(wnd, &outmsg, sizeof(struct nxsvrmsg_bitmap_s)); - - /* Wait that the command is completed, so that caller can release the buffer. */ - - if (ret == OK) - { - ret = sem_wait(&sem_done); - } - - /* Destroy the semaphore and return. */ - - sem_destroy(&sem_done); - - return ret; + return nxmu_sendwindow(wnd, &outmsg, sizeof(struct nxsvrmsg_bitmap_s)); } diff --git a/nuttx/graphics/nxmu/nx_block.c b/nuttx/graphics/nxmu/nx_block.c index 7b198613c6..3a051f9d7d 100644 --- a/nuttx/graphics/nxmu/nx_block.c +++ b/nuttx/graphics/nxmu/nx_block.c @@ -140,7 +140,7 @@ int nx_block(NXWINDOW hwnd, FAR void *arg) * that it will not be blocked. */ - ret = nxmu_sendserver(wnd->conn, &outmsg, sizeof(struct nxsvrmsg_blocked_s)); + ret = nxmu_sendserver(wnd->conn, &outmsg, sizeof(struct nxbe_window_s)); } return ret; diff --git a/nuttx/graphics/nxmu/nx_getrectangle.c b/nuttx/graphics/nxmu/nx_getrectangle.c index 9b7d3679c4..f32065129c 100644 --- a/nuttx/graphics/nxmu/nx_getrectangle.c +++ b/nuttx/graphics/nxmu/nx_getrectangle.c @@ -98,9 +98,7 @@ int nx_getrectangle(NXWINDOW hwnd, FAR const struct nxgl_rect_s *rect, { FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; struct nxsvrmsg_getrectangle_s outmsg; - int ret; - sem_t sem_done; - + #ifdef CONFIG_DEBUG if (!hwnd || !rect || !dest) { @@ -120,31 +118,7 @@ int nx_getrectangle(NXWINDOW hwnd, FAR const struct nxgl_rect_s *rect, nxgl_rectcopy(&outmsg.rect, rect); - /* Create a semaphore for tracking command completion */ - - outmsg.sem_done = &sem_done; - ret = sem_init(&sem_done, 0, 0); - - if (ret != OK) - { - gdbg("sem_init failed: %d\n", errno); - return ret; - } - /* Forward the fill command to the server */ - ret = nxmu_sendwindow(wnd, &outmsg, sizeof(struct nxsvrmsg_getrectangle_s)); - - /* Wait that the command is completed, so that caller can release the buffer. */ - - if (ret == OK) - { - ret = sem_wait(&sem_done); - } - - /* Destroy the semaphore and return. */ - - sem_destroy(&sem_done); - - return ret; + return nxmu_sendwindow(wnd, &outmsg, sizeof(struct nxsvrmsg_getrectangle_s)); } diff --git a/nuttx/graphics/nxmu/nxfe.h b/nuttx/graphics/nxmu/nxfe.h index b9e02616ce..8b6a21ef48 100644 --- a/nuttx/graphics/nxmu/nxfe.h +++ b/nuttx/graphics/nxmu/nxfe.h @@ -392,7 +392,6 @@ struct nxsvrmsg_getrectangle_s unsigned int plane; /* The plane number to read */ FAR uint8_t *dest; /* Memory location in which to store the graphics data */ unsigned int deststride; /* Width of the destination memory in bytes */ - sem_t *sem_done; /* Semaphore to report when command is done. */ }; /* Fill a trapezoidal region in the window with a color */ @@ -426,7 +425,6 @@ struct nxsvrmsg_bitmap_s FAR const void *src[CONFIG_NX_NPLANES]; /* The start of the source image. */ struct nxgl_point_s origin; /* Offset into the source image data */ unsigned int stride; /* The width of the full source image in pixels. */ - sem_t *sem_done; /* Semaphore to report when command is done. */ }; /* Set the color of the background */ @@ -588,25 +586,6 @@ EXTERN int nxmu_sendwindow(FAR struct nxbe_window_s *wnd, FAR const void *msg, EXTERN int nxmu_sendclient(FAR struct nxfe_conn_s *conn, FAR const void *msg, size_t msglen); -/**************************************************************************** - * Name: nxmu_sendclientwindow - * - * Description: - * Send a message to the client at NX_CLIMSG_PRIO priority - * - * Input Parameters: - * wnd - A pointer to the back-end window structure - * msg - A pointer to the message to send - * msglen - The length of the message in bytes. - * - * Return: - * OK on success; ERROR on failure with errno set appropriately - * - ****************************************************************************/ - -int nxmu_sendclientwindow(FAR struct nxbe_window_s *wnd, FAR const void *msg, - size_t msglen); - /**************************************************************************** * Name: nxmu_openwindow * diff --git a/nuttx/graphics/nxmu/nxmu_kbdin.c b/nuttx/graphics/nxmu/nxmu_kbdin.c index 0308c2bfa8..2c658009bc 100644 --- a/nuttx/graphics/nxmu/nxmu_kbdin.c +++ b/nuttx/graphics/nxmu/nxmu_kbdin.c @@ -108,7 +108,7 @@ void nxmu_kbdin(FAR struct nxfe_state_s *fe, uint8_t nch, FAR uint8_t *ch) outmsg->ch[i] = ch[i]; } - (void)nxmu_sendclientwindow(fe->be.topwnd, outmsg, size); + (void)nxmu_sendclient(fe->be.topwnd->conn, outmsg, size); free(outmsg); } } diff --git a/nuttx/graphics/nxmu/nxmu_mouse.c b/nuttx/graphics/nxmu/nxmu_mouse.c index 1b8f4a5921..3ebe062d29 100644 --- a/nuttx/graphics/nxmu/nxmu_mouse.c +++ b/nuttx/graphics/nxmu/nxmu_mouse.c @@ -61,10 +61,9 @@ * Private Data ****************************************************************************/ -static struct nxgl_point_s g_mpos; -static struct nxgl_point_s g_mrange; -static uint8_t g_mbutton; -static struct nxbe_window_s *g_mwnd; +static struct nxgl_point_s g_mpos; +static struct nxgl_point_s g_mrange; +static uint8_t g_mbutton; /**************************************************************************** * Public Data @@ -130,7 +129,7 @@ int nxmu_mousereport(struct nxbe_window_s *wnd) outmsg.buttons = g_mbutton; nxgl_vectsubtract(&outmsg.pos, &g_mpos, &wnd->bounds.pt1); - return nxmu_sendclientwindow(wnd, &outmsg, sizeof(struct nxclimsg_mousein_s)); + return nxmu_sendclient(wnd->conn, &outmsg, sizeof(struct nxclimsg_mousein_s)); } } @@ -155,7 +154,6 @@ int nxmu_mousein(FAR struct nxfe_state_s *fe, struct nxbe_window_s *wnd; nxgl_coord_t x = pos->x; nxgl_coord_t y = pos->y; - uint8_t oldbuttons; int ret; /* Clip x and y to within the bounding rectangle */ @@ -184,36 +182,20 @@ int nxmu_mousein(FAR struct nxfe_state_s *fe, { /* Update the mouse value */ - oldbuttons = g_mbutton; - g_mpos.x = x; - g_mpos.y = y; - g_mbutton = buttons; + g_mpos.x = x; + g_mpos.y = y; + g_mbutton = buttons; - /* If a button is already down, regard this as part of a mouse drag - * event. Pass all the following events to the window where the drag - * started in. - */ - - if (oldbuttons && g_mwnd && g_mwnd->cb->mousein) - { - struct nxclimsg_mousein_s outmsg; - outmsg.msgid = NX_CLIMSG_MOUSEIN; - outmsg.wnd = g_mwnd; - outmsg.buttons = g_mbutton; - nxgl_vectsubtract(&outmsg.pos, &g_mpos, &g_mwnd->bounds.pt1); - - return nxmu_sendclientwindow(g_mwnd, &outmsg, sizeof(struct nxclimsg_mousein_s)); - } - - /* Pick the window to receive the mouse event. Start with the top - * window and go down. Stop with the first window that gets the mouse - * report + /* Pick the window to receive the mouse event. Start with + * the top window and go down. Stop with the first window + * that gets the mouse report */ for (wnd = fe->be.topwnd; wnd; wnd = wnd->below) { - /* The background window normally has no callback structure (unless - * a client has taken control of the background via nx_requestbkgd()). + /* The background window normally has no callback structure + * (unless a client has taken control of the background via + * nx_requestbkgd()). */ if (wnd->cb) @@ -225,8 +207,6 @@ int nxmu_mousein(FAR struct nxfe_state_s *fe, } } } - - g_mwnd = wnd; } return OK; diff --git a/nuttx/graphics/nxmu/nxmu_redrawreq.c b/nuttx/graphics/nxmu/nxmu_redrawreq.c index f54aa85a7e..32ca477a26 100644 --- a/nuttx/graphics/nxmu/nxmu_redrawreq.c +++ b/nuttx/graphics/nxmu/nxmu_redrawreq.c @@ -87,7 +87,7 @@ void nxfe_redrawreq(FAR struct nxbe_window_s *wnd, FAR const struct nxgl_rect_s outmsg.more = false; nxgl_rectoffset(&outmsg.rect, rect, -wnd->bounds.pt1.x, -wnd->bounds.pt1.y); - (void)nxmu_sendclientwindow(wnd, &outmsg, sizeof(struct nxclimsg_redraw_s)); + (void)nxmu_sendclient(wnd->conn, &outmsg, sizeof(struct nxclimsg_redraw_s)); } diff --git a/nuttx/graphics/nxmu/nxmu_reportposition.c b/nuttx/graphics/nxmu/nxmu_reportposition.c index 6ffb3f4ee7..f9b5f9dafa 100644 --- a/nuttx/graphics/nxmu/nxmu_reportposition.c +++ b/nuttx/graphics/nxmu/nxmu_reportposition.c @@ -100,7 +100,7 @@ void nxfe_reportposition(FAR struct nxbe_window_s *wnd) /* And provide this to the client */ - ret = nxmu_sendclientwindow(wnd, &outmsg, sizeof(struct nxclimsg_newposition_s)); + ret = nxmu_sendclient(wnd->conn, &outmsg, sizeof(struct nxclimsg_newposition_s)); if (ret < 0) { gdbg("nxmu_sendclient failed: %d\n", errno); diff --git a/nuttx/graphics/nxmu/nxmu_sendwindow.c b/nuttx/graphics/nxmu/nxmu_sendwindow.c index 0826a45bc9..6f64ffff2c 100644 --- a/nuttx/graphics/nxmu/nxmu_sendwindow.c +++ b/nuttx/graphics/nxmu/nxmu_sendwindow.c @@ -112,47 +112,3 @@ int nxmu_sendwindow(FAR struct nxbe_window_s *wnd, FAR const void *msg, return ret; } - -/**************************************************************************** - * Name: nxmu_sendclientwindow - * - * Description: - * Send a message to the client at NX_CLIMSG_PRIO priority - * - * Input Parameters: - * wnd - A pointer to the back-end window structure - * msg - A pointer to the message to send - * msglen - The length of the message in bytes. - * - * Return: - * OK on success; ERROR on failure with errno set appropriately - * - ****************************************************************************/ - -int nxmu_sendclientwindow(FAR struct nxbe_window_s *wnd, FAR const void *msg, - size_t msglen) -{ - int ret = OK; - - /* Sanity checking */ - -#ifdef CONFIG_DEBUG - if (!wnd || !wnd->conn) - { - errno = EINVAL; - return ERROR; - } -#endif - - /* Ignore messages destined to a blocked window (no errors reported) */ - - if (!NXBE_ISBLOCKED(wnd)) - { - /* Send the message to the server */ - - ret = nxmu_sendclient(wnd->conn, msg, msglen); - } - - return ret; -} - diff --git a/nuttx/graphics/nxmu/nxmu_server.c b/nuttx/graphics/nxmu/nxmu_server.c index cfaa5bbf5d..2730e0ea28 100644 --- a/nuttx/graphics/nxmu/nxmu_server.c +++ b/nuttx/graphics/nxmu/nxmu_server.c @@ -451,11 +451,6 @@ int nx_runinstance(FAR const char *mqname, FAR NX_DRIVERTYPE *dev) { FAR struct nxsvrmsg_getrectangle_s *getmsg = (FAR struct nxsvrmsg_getrectangle_s *)buffer; nxbe_getrectangle(getmsg->wnd, &getmsg->rect, getmsg->plane, getmsg->dest, getmsg->deststride); - - if (getmsg->sem_done) - { - sem_post(getmsg->sem_done); - } } break; @@ -476,11 +471,6 @@ int nx_runinstance(FAR const char *mqname, FAR NX_DRIVERTYPE *dev) { FAR struct nxsvrmsg_bitmap_s *bmpmsg = (FAR struct nxsvrmsg_bitmap_s *)buffer; nxbe_bitmap(bmpmsg->wnd, &bmpmsg->dest, bmpmsg->src, &bmpmsg->origin, bmpmsg->stride); - - if (bmpmsg->sem_done) - { - sem_post(bmpmsg->sem_done); - } } break; diff --git a/nuttx/graphics/nxsu/nx_mousein.c b/nuttx/graphics/nxsu/nx_mousein.c index 5b268358bf..bee4a22650 100644 --- a/nuttx/graphics/nxsu/nx_mousein.c +++ b/nuttx/graphics/nxsu/nx_mousein.c @@ -62,10 +62,9 @@ * Private Data ****************************************************************************/ -static struct nxgl_point_s g_mpos; -static struct nxgl_point_s g_mrange; -static uint8_t g_mbutton; -static struct nxbe_window_s *g_mwnd; +static struct nxgl_point_s g_mpos; +static struct nxgl_point_s g_mrange; +static uint8_t g_mbutton; /**************************************************************************** * Public Data @@ -149,7 +148,6 @@ int nx_mousein(NXHANDLE handle, nxgl_coord_t x, nxgl_coord_t y, uint8_t buttons) { FAR struct nxfe_state_s *fe = (FAR struct nxfe_state_s *)handle; struct nxbe_window_s *wnd; - uint8_t oldbuttons; int ret; /* Clip x and y to within the bounding rectangle */ @@ -178,27 +176,13 @@ int nx_mousein(NXHANDLE handle, nxgl_coord_t x, nxgl_coord_t y, uint8_t buttons) { /* Update the mouse value */ - oldbuttons = g_mbutton; g_mpos.x = x; g_mpos.y = y; g_mbutton = buttons; - /* If a button is already down, regard this as part of a mouse drag - * event. Pass all the following events to the window where the drag - * started in. - */ - - if (oldbuttons && g_mwnd && g_mwnd->cb->mousein) - { - struct nxgl_point_s relpos; - nxgl_vectsubtract(&relpos, &g_mpos, &g_mwnd->bounds.pt1); - g_mwnd->cb->mousein((NXWINDOW)g_mwnd, &relpos, g_mbutton, g_mwnd->arg); - return OK; - } - - /* Pick the window to receive the mouse event. Start with the top - * window and go down. Step with the first window that gets the mouse - * report + /* Pick the window to receive the mouse event. Start with + * the top window and go down. Step with the first window + * that gets the mouse report */ for (wnd = fe->be.topwnd; wnd; wnd = wnd->below) @@ -209,8 +193,6 @@ int nx_mousein(NXHANDLE handle, nxgl_coord_t x, nxgl_coord_t y, uint8_t buttons) break; } } - - g_mwnd = wnd; } return OK; } diff --git a/nuttx/graphics/nxtk/nxtk_events.c b/nuttx/graphics/nxtk/nxtk_events.c index facf921762..33c50b7f90 100644 --- a/nuttx/graphics/nxtk/nxtk_events.c +++ b/nuttx/graphics/nxtk/nxtk_events.c @@ -76,9 +76,6 @@ static void nxtk_mousein(NXWINDOW hwnd, FAR const struct nxgl_point_s *pos, static void nxtk_kbdin(NXWINDOW hwnd, uint8_t nch, const uint8_t *ch, FAR void *arg); #endif -#ifdef CONFIG_NX_MULTIUSER -static void nxtk_blocked(NXWINDOW hwnd, FAR void *arg1, FAR void *arg2); -#endif /**************************************************************************** * Private Data @@ -98,9 +95,6 @@ const struct nx_callback_s g_nxtkcb = #ifdef CONFIG_NX_KBD , nxtk_kbdin /* kbdin */ #endif -#ifdef CONFIG_NX_MULTIUSER - , nxtk_blocked -#endif }; /**************************************************************************** @@ -261,20 +255,9 @@ static void nxtk_mousein(NXWINDOW hwnd, FAR const struct nxgl_point_s *pos, nxgl_vectoradd(&abspos, pos, &fwnd->wnd.bounds.pt1); - /* In order to deliver mouse release events to the same window where the - * mouse down event happened, we store the initial mouse down location. - */ - - if (fwnd->mbutton == 0 && buttons != 0) - { - fwnd->mpos = abspos; - } - - fwnd->mbutton = buttons; - /* Is the mouse position inside of the client window region? */ - if (fwnd->fwcb->mousein && nxgl_rectinside(&fwnd->fwrect, &fwnd->mpos)) + if (fwnd->fwcb->mousein && nxgl_rectinside(&fwnd->fwrect, &abspos)) { nxgl_vectsubtract(&relpos, &abspos, &fwnd->fwrect.pt1); fwnd->fwcb->mousein((NXTKWINDOW)fwnd, &relpos, buttons, fwnd->fwarg); @@ -282,7 +265,7 @@ static void nxtk_mousein(NXWINDOW hwnd, FAR const struct nxgl_point_s *pos, /* If the mouse position inside the toobar region? */ - else if (fwnd->tbcb->mousein && nxgl_rectinside(&fwnd->tbrect, &fwnd->mpos)) + else if (fwnd->tbcb->mousein && nxgl_rectinside(&fwnd->tbrect, &abspos)) { nxgl_vectsubtract(&relpos, &abspos, &fwnd->tbrect.pt1); fwnd->tbcb->mousein((NXTKWINDOW)fwnd, &relpos, buttons, fwnd->tbarg); @@ -309,24 +292,6 @@ static void nxtk_kbdin(NXWINDOW hwnd, uint8_t nch, const uint8_t *ch, } #endif -/**************************************************************************** - * Name: nxtk_blocked - ****************************************************************************/ - -#ifdef CONFIG_NX_MULTIUSER -static void nxtk_blocked(NXWINDOW hwnd, FAR void *arg1, FAR void *arg2) -{ - FAR struct nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)hwnd; - - /* Only the client window gets keyboard input */ - - if (fwnd->fwcb->blocked) - { - fwnd->fwcb->blocked((NXTKWINDOW)fwnd, fwnd->fwarg, arg2); - } -} -#endif - /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/nuttx/graphics/nxtk/nxtk_internal.h b/nuttx/graphics/nxtk/nxtk_internal.h index 3a31215d83..87a098845a 100644 --- a/nuttx/graphics/nxtk/nxtk_internal.h +++ b/nuttx/graphics/nxtk/nxtk_internal.h @@ -72,11 +72,6 @@ struct nxtk_framedwindow_s struct nxgl_rect_s fwrect; FAR const struct nx_callback_s *fwcb; FAR void *fwarg; - - /* Initial mouse down location */ - - uint8_t mbutton; - struct nxgl_point_s mpos; }; /**************************************************************************** diff --git a/nuttx/include/cxx/cmath b/nuttx/include/cxx/cmath index 55c7c1dcc7..7cb3a2109a 100644 --- a/nuttx/include/cxx/cmath +++ b/nuttx/include/cxx/cmath @@ -40,9 +40,6 @@ // Included Files //*************************************************************************** -#include -#include - #include //*************************************************************************** @@ -51,33 +48,6 @@ namespace std { -#if CONFIG_HAVE_FLOAT - using ::acosf; - using ::asinf; - using ::atanf; - using ::atan2f; - using ::ceilf; - using ::cosf; - using ::coshf; - using ::expf; - using ::fabsf; - using ::floorf; - using ::fmodf; - using ::frexpf; - using ::ldexpf; - using ::logf; - using ::log10f; - using ::log2f; - using ::modff; - using ::powf; - using ::sinf; - using ::sinhf; - using ::sqrtf; - using ::tanf; - using ::tanhf; -#endif - -#if CONFIG_HAVE_DOUBLE using ::acos; using ::asin; using ::atan; @@ -93,7 +63,6 @@ namespace std using ::ldexp; using ::log; using ::log10; - using ::log2; using ::modf; using ::pow; using ::sin; @@ -101,34 +70,6 @@ namespace std using ::sqrt; using ::tan; using ::tanh; -#endif - -#ifdef CONFIG_HAVE_LONG_DOUBLE - using ::acosl; - using ::asinl; - using ::atanl; - using ::atan2l; - using ::ceill; - using ::cosl; - using ::coshl; - using ::expl; - using ::fabsl; - using ::floorl; - using ::fmodl; - using ::frexpl; - using ::ldexpl; - using ::logl; - using ::log10l; - using ::log2l; - using ::modfl; - using ::powl; - using ::sinl; - using ::sinhl; - using ::sqrtl; - using ::tanl; - using ::tanhl; -#endif - } #endif // __INCLUDE_CXX_CMATH diff --git a/nuttx/include/cxx/cstdbool b/nuttx/include/cxx/cstdbool index 192fde490b..d2f0639d21 100644 --- a/nuttx/include/cxx/cstdbool +++ b/nuttx/include/cxx/cstdbool @@ -46,13 +46,4 @@ // Namespace //*************************************************************************** -//*************************************************************************** -// Namespace -//*************************************************************************** - -namespace std -{ - using ::_Bool8; -} - #endif // __INCLUDE_CXX_CSTDBOOL diff --git a/nuttx/include/cxx/cstdio b/nuttx/include/cxx/cstdio index 6a9620e1ad..900d429cb9 100644 --- a/nuttx/include/cxx/cstdio +++ b/nuttx/include/cxx/cstdio @@ -52,8 +52,6 @@ namespace std using ::FILE; using ::fpos_t; using ::size_t; - - using ::clearerr; using ::fclose; using ::fflush; using ::feof; @@ -71,24 +69,16 @@ namespace std using ::ftell; using ::fwrite; using ::gets; - using ::ungetc; - using ::printf; using ::puts; using ::rename; using ::sprintf; - using ::asprintf; using ::snprintf; - using ::sscanf; - using ::perror; - + using ::ungetc; using ::vprintf; using ::vfprintf; using ::vsprintf; - using ::avsprintf; using ::vsnprintf; - using ::vsscanf; - using ::fdopen; using ::statfs; } diff --git a/nuttx/include/net/if.h b/nuttx/include/net/if.h index 1ff8ebc383..e64b58563f 100644 --- a/nuttx/include/net/if.h +++ b/nuttx/include/net/if.h @@ -52,10 +52,6 @@ #define IF_NAMESIZE 6 /* Newer naming standard */ #define IFHWADDRLEN 6 -#define IFF_RUNNING (1 << 0) -#define IF_FLAG_IFUP (1 << 0) -#define IF_FLAG_IFDOWN (2 << 0) - /******************************************************************************************* * Public Type Definitions *******************************************************************************************/ @@ -76,7 +72,6 @@ struct lifreq struct sockaddr lifru_hwaddr; /* MAC address */ int lifru_count; /* Number of devices */ int lifru_mtu; /* MTU size */ - uint8_t lifru_flags; /* Interface flags */ } lifr_ifru; }; @@ -87,7 +82,6 @@ struct lifreq #define lifr_hwaddr lifr_ifru.lifru_hwaddr /* MAC address */ #define lifr_mtu lifr_ifru.lifru_mtu /* MTU */ #define lifr_count lifr_ifru.lifru_count /* Number of devices */ -#define lifr_flags lifr_ifru.lifru_flags /* interface flags */ /* This is the older I/F request that should only be used with IPv4. However, since * NuttX only supports IPv4 or 6 (not both), we can force the older structure to @@ -107,7 +101,6 @@ struct ifreq struct sockaddr ifru_hwaddr; /* MAC address */ int ifru_count; /* Number of devices */ int ifru_mtu; /* MTU size */ - uint8_t ifru_flags; /* Interface flags */ } ifr_ifru; }; @@ -118,7 +111,6 @@ struct ifreq #define ifr_hwaddr ifr_ifru.ifru_hwaddr /* MAC address */ #define ifr_mtu ifr_ifru.ifru_mtu /* MTU */ #define ifr_count ifr_ifru.ifru_count /* Number of devices */ -#define ifr_flags ifr_ifru.ifru_flags /* interface flags */ #else /* CONFIG_NET_IPv6 */ @@ -131,7 +123,6 @@ struct ifreq #define ifr_hwaddr lifr_ifru.lifru_hwaddr /* MAC address */ #define ifr_mtu lifr_ifru.lifru_mtu /* MTU */ #define ifr_count lifr_ifru.lifru_count /* Number of devices */ -#define ifr_flags lifr_ifru.lifru_flags /* interface flags */ #endif /* CONFIG_NET_IPv6 */ diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h index c836a75573..bf6be1ce08 100644 --- a/nuttx/include/nuttx/arch.h +++ b/nuttx/include/nuttx/arch.h @@ -616,28 +616,6 @@ EXTERN uint8_t up_buttons(void); EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler); #endif -/************************************************************************************ - * Relay control functions - * - * Description: - * Non-standard functions for relay control. - * - ************************************************************************************/ - -#ifdef CONFIG_ARCH_RELAYS -EXTERN void up_relaysinit(void); -EXTERN void relays_setstat(int relays, bool stat); -EXTERN bool relays_getstat(int relays); -EXTERN void relays_setstats(uint32_t relays_stat); -EXTERN uint32_t relays_getstats(void); -EXTERN void relays_onoff(int relays, uint32_t mdelay); -EXTERN void relays_onoffs(uint32_t relays_stat, uint32_t mdelay); -EXTERN void relays_resetmode(int relays); -EXTERN void relays_powermode(int relays); -EXTERN void relays_resetmodes(uint32_t relays_stat); -EXTERN void relays_powermodes(uint32_t relays_stat); -#endif - /**************************************************************************** * Debug interfaces exported by the architecture-specific logic ****************************************************************************/ diff --git a/nuttx/include/nuttx/binfmt.h b/nuttx/include/nuttx/binfmt.h new file mode 100644 index 0000000000..70beda3933 --- /dev/null +++ b/nuttx/include/nuttx/binfmt.h @@ -0,0 +1,209 @@ +/**************************************************************************** + * include/nuttx/binfmt.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __INCLUDE_NUTTX_BINFMT_H +#define __INCLUDE_NUTTX_BINFMT_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* This describes the file to be loaded */ + +struct symtab_s; +struct binary_s +{ + /* Information provided to the loader to load and bind a module */ + + FAR const char *filename; /* Full path to the binary to be loaded */ + FAR const char **argv; /* Argument list */ + FAR const struct symtab_s *exports; /* Table of exported symbols */ + int nexports; /* The number of symbols in exports[] */ + + /* Information provided from the loader (if successful) describing the + * resources used by the loaded module. + */ + + main_t entrypt; /* Entry point into a program module */ + FAR void *ispace; /* Memory-mapped, I-space (.text) address */ + FAR struct dspace_s *dspace; /* Address of the allocated .data/.bss space */ + size_t isize; /* Size of the I-space region (needed for munmap) */ + size_t stacksize; /* Size of the stack in bytes (unallocated) */ +}; + +/* This describes one binary format handler */ + +struct binfmt_s +{ + FAR struct binfmt_s *next; /* Supports a singly-linked list */ + int (*load)(FAR struct binary_s *bin); /* Verify and load binary into memory */ +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: register_binfmt + * + * Description: + * Register a loader for a binary format + * + * Returned Value: + * This is a NuttX internal function so it follows the convention that + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +EXTERN int register_binfmt(FAR struct binfmt_s *binfmt); + +/**************************************************************************** + * Name: unregister_binfmt + * + * Description: + * Register a loader for a binary format + * + * Returned Value: + * This is a NuttX internal function so it follows the convention that + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +EXTERN int unregister_binfmt(FAR struct binfmt_s *binfmt); + +/**************************************************************************** + * Name: load_module + * + * Description: + * Load a module into memory, bind it to an exported symbol take, and + * prep the module for execution. + * + * Returned Value: + * This is an end-user function, so it follows the normal convention: + * Returns 0 (OK) on success. On failure, it returns -1 (ERROR) with + * errno set appropriately. + * + ****************************************************************************/ + +EXTERN int load_module(FAR struct binary_s *bin); + +/**************************************************************************** + * Name: unload_module + * + * Description: + * Unload a (non-executing) module from memory. If the module has + * been started (via exec_module), calling this will be fatal. + * + * Returned Value: + * This is a NuttX internal function so it follows the convention that + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ****************************************************************************/ + +EXTERN int unload_module(FAR const struct binary_s *bin); + +/**************************************************************************** + * Name: exec_module + * + * Description: + * Execute a module that has been loaded into memory by load_module(). + * + * Returned Value: + * This is an end-user function, so it follows the normal convention: + * Returns the PID of the exec'ed module. On failure, it.returns + * -1 (ERROR) and sets errno appropriately. + * + ****************************************************************************/ + +EXTERN int exec_module(FAR const struct binary_s *bin, int priority); + +/**************************************************************************** + * Name: exec + * + * Description: + * This is a convenience function that wraps load_ and exec_module into + * one call. + * + * Input Parameter: + * filename - Fulll path to the binary to be loaded + * argv - Argument list + * exports - Table of exported symbols + * nexports - The number of symbols in exports + * + * Returned Value: + * This is an end-user function, so it follows the normal convention: + * Returns the PID of the exec'ed module. On failure, it.returns + * -1 (ERROR) and sets errno appropriately. + * + ****************************************************************************/ + +EXTERN int exec(FAR const char *filename, FAR const char **argv, + FAR const struct symtab_s *exports, int nexports); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __INCLUDE_NUTTX_BINFMT_H */ + diff --git a/nuttx/include/nuttx/compiler.h b/nuttx/include/nuttx/compiler.h index e6a525a372..d74fcbea08 100644 --- a/nuttx/include/nuttx/compiler.h +++ b/nuttx/include/nuttx/compiler.h @@ -87,16 +87,11 @@ # define packed_struct __attribute__ ((packed)) -/* GCC does not support the reentrant attribute */ +/* GCC does not support the reentrant or naked attributes */ # define reentrant_function +# define naked_function -/* The naked attribute informs GCC that the programmer will take care of - * the function prolog and epilog. - */ - -# define naked_function __attribute__ ((naked,no_instrument_function)) - /* The inline_function attribute informs GCC that the function should always * be inlined, regardless of the level of optimization. The noinline_function * indicates that the function should never be inlined. @@ -196,10 +191,8 @@ /* GCC supports both types double and long long */ -# define CONFIG_HAVE_LONG_LONG 1 -# define CONFIG_HAVE_FLOAT 1 # define CONFIG_HAVE_DOUBLE 1 -# define CONFIG_HAVE_LONG_DOUBLE 1 +# define CONFIG_HAVE_LONG_LONG 1 /* Structures and unions can be assigned and passed as values */ @@ -302,9 +295,7 @@ /* SDCC does not support type long long or type double */ # undef CONFIG_HAVE_LONG_LONG -# define CONFIG_HAVE_FLOAT 1 # undef CONFIG_HAVE_DOUBLE -# undef CONFIG_HAVE_LONG_DOUBLE /* Structures and unions cannot be passed as values or used * in assignments. @@ -407,10 +398,8 @@ * simply do not support long long or double. */ -# undef CONFIG_HAVE_LONG_LONG -# define CONFIG_HAVE_FLOAT 1 # undef CONFIG_HAVE_DOUBLE -# undef CONFIG_HAVE_LONG_DOUBLE +# undef CONFIG_HAVE_LONG_LONG /* Structures and unions can be assigned and passed as values */ @@ -444,11 +433,9 @@ # undef CONFIG_LONG_IS_NOT_INT # undef CONFIG_PTR_IS_NOT_INT # undef CONFIG_HAVE_INLINE -# define inline 1 +# define inline # undef CONFIG_HAVE_LONG_LONG -# define CONFIG_HAVE_FLOAT 1 # undef CONFIG_HAVE_DOUBLE -# undef CONFIG_HAVE_LONG_DOUBLE # undef CONFIG_CAN_PASS_STRUCTS #endif diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h index aab4ae4be8..81f81622f6 100644 --- a/nuttx/include/nuttx/fs/fs.h +++ b/nuttx/include/nuttx/fs/fs.h @@ -51,10 +51,6 @@ /**************************************************************************** * Definitions ****************************************************************************/ -/* Stream flags for the fs_flags field of in struct file_struct */ - -#define __FS_FLAG_EOF (1 << 0) /* EOF detected by a read operation */ -#define __FS_FLAG_ERROR (1 << 1) /* Error detected by any operation */ /**************************************************************************** * Type Definitions @@ -274,6 +270,11 @@ struct filelist struct file_struct { int fs_filedes; /* File descriptor associated with stream */ + uint16_t fs_oflags; /* Open mode flags */ +#if CONFIG_NUNGET_CHARS > 0 + uint8_t fs_nungotten; /* The number of characters buffered for ungetc */ + unsigned char fs_ungotten[CONFIG_NUNGET_CHARS]; +#endif #if CONFIG_STDIO_BUFFER_SIZE > 0 sem_t fs_sem; /* For thread safety */ pid_t fs_holder; /* Holder of sem */ @@ -282,12 +283,6 @@ struct file_struct FAR unsigned char *fs_bufend; /* Pointer to 1 past end of buffer */ FAR unsigned char *fs_bufpos; /* Current position in buffer */ FAR unsigned char *fs_bufread; /* Pointer to 1 past last buffered read char. */ -#endif - uint16_t fs_oflags; /* Open mode flags */ - uint8_t fs_flags; /* Stream flags */ -#if CONFIG_NUNGET_CHARS > 0 - uint8_t fs_nungotten; /* The number of characters buffered for ungetc */ - unsigned char fs_ungotten[CONFIG_NUNGET_CHARS]; #endif }; diff --git a/nuttx/include/nuttx/lcd/ug-9664hswag01.h b/nuttx/include/nuttx/lcd/ug-9664hswag01.h index b470e0895e..696005b5d0 100644 --- a/nuttx/include/nuttx/lcd/ug-9664hswag01.h +++ b/nuttx/include/nuttx/lcd/ug-9664hswag01.h @@ -3,7 +3,7 @@ * Driver for the Univision UG-9664HSWAG01 Display with the Solomon Systech * SSD1305 LCD controller. * - * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -58,6 +58,8 @@ * CONFIG_UG9664HSWAG01_POWER * If the hardware supports a controllable OLED a power supply, this * configuration shold be defined. (See ug_power() below). + * CONFIG_LCD_UGDEBUG - Enable detailed UG-9664HSWAG01 debug output + * (CONFIG_DEBUG and CONFIG_VERBOSE must also be enabled). * * Required LCD driver settings: * CONFIG_LCD_UG9664HSWAG01 - Enable UG-9664HSWAG01 support @@ -88,8 +90,10 @@ ****************************************************************************/ #ifdef __cplusplus -extern "C" -{ +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern #endif /**************************************************************************** @@ -119,7 +123,7 @@ extern "C" struct lcd_dev_s; /* see nuttx/lcd.h */ struct spi_dev_s; /* see nuttx/spi.h */ -FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devno); +EXTERN FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devno); /**************************************************************************** * Name: ug_power @@ -141,11 +145,12 @@ FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devn **************************************************************************************/ #ifdef CONFIG_UG9664HSWAG01_POWER -void ug_power(unsigned int devno, bool on); +EXTERN void ug_power(unsigned int devno, bool on); #else # define ug_power(a,b) #endif +#undef EXTERN #ifdef __cplusplus } #endif diff --git a/nuttx/include/nuttx/math.h b/nuttx/include/nuttx/math.h index 160926d070..84dbea6e03 100644 --- a/nuttx/include/nuttx/math.h +++ b/nuttx/include/nuttx/math.h @@ -50,272 +50,14 @@ #ifdef CONFIG_ARCH_MATH_H # include - -/* If CONFIG_LIB is enabled, then the math library at lib/math will be - * built. This library was taken from the math library developed for the - * Rhombus OS by Nick Johnson (https://github.com/nickbjohnson4224/rhombus). - * The port or the Rhombus math library was contributed by Darcy Gong. - */ - -#else if defined CONFIG_LIBM +#endif /**************************************************************************** - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * + * Type Definitions ****************************************************************************/ -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* General Constants ********************************************************/ - -#define INFINITY (1.0/0.0) -#define NAN (0.0/0.0) -#define HUGE_VAL INFINITY - -#define isnan(x) ((x) != (x)) -#define isinf(x) (((x) == INFINITY) || ((x) == -INFINITY)) - -/* Exponential and Logarithmic constants ************************************/ - -#define M_E 2.7182818284590452353602874713526625 -#define M_SQRT2 1.4142135623730950488016887242096981 -#define M_SQRT1_2 0.7071067811865475244008443621048490 -#define M_LOG2E 1.4426950408889634073599246810018921 -#define M_LOG10E 0.4342944819032518276511289189166051 -#define M_LN2 0.6931471805599453094172321214581765 -#define M_LN10 2.3025850929940456840179914546843642 - -/* Trigonometric Constants **************************************************/ - -#define M_PI 3.1415926535897932384626433832795029 -#define M_PI_2 1.5707963267948966192313216916397514 -#define M_PI_4 0.7853981633974483096156608458198757 -#define M_1_PI 0.3183098861837906715377675267450287 -#define M_2_PI 0.6366197723675813430755350534900574 -#define M_2_SQRTPI 1.1283791670955125738961589031215452 - /**************************************************************************** * Public Function Prototypes ****************************************************************************/ -#if defined(__cplusplus) -extern "C" { -#endif - -/* General Functions ********************************************************/ - -float ceilf (float x); -#if CONFIG_HAVE_DOUBLE -double ceil (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double ceill (long double x); -#endif - -float floorf(float x); -#if CONFIG_HAVE_DOUBLE -double floor (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double floorl(long double x); -#endif - -float fabsf (float x); -#if CONFIG_HAVE_DOUBLE -double fabs (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double fabsl (long double x); -#endif - -float modff (float x, float *iptr); -#if CONFIG_HAVE_DOUBLE -double modf (double x, double *iptr); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double modfl (long double x, long double *iptr); -#endif - -float fmodf (float x, float div); -#if CONFIG_HAVE_DOUBLE -double fmod (double x, double div); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double fmodl (long double x, long double div); -#endif - -/* Exponential and Logarithmic Functions ************************************/ - -float powf (float b, float e); -#if CONFIG_HAVE_DOUBLE -double pow (double b, double e); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double powl (long double b, long double e); -#endif - -float expf (float x); -#if CONFIG_HAVE_DOUBLE -double exp (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double expl (long double x); -#endif - -float logf (float x); -#if CONFIG_HAVE_DOUBLE -double log (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double logl (long double x); -#endif - -float log10f(float x); -#if CONFIG_HAVE_DOUBLE -double log10 (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double log10l(long double x); -#endif - -float log2f (float x); -#if CONFIG_HAVE_DOUBLE -double log2 (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double log2l (long double x); -#endif - -float sqrtf (float x); -#if CONFIG_HAVE_DOUBLE -double sqrt (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double sqrtl (long double x); -#endif - -float ldexpf(float x, int n); -#if CONFIG_HAVE_DOUBLE -double ldexp (double x, int n); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double ldexpl(long double x, int n); -#endif - -float frexpf(float x, int *exp); -#if CONFIG_HAVE_DOUBLE -double frexp (double x, int *exp); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double frexpl(long double x, int *exp); -#endif - -/* Trigonometric Functions **************************************************/ - -float sinf (float x); -#if CONFIG_HAVE_DOUBLE -double sin (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double sinl (long double x); -#endif - -float cosf (float x); -#if CONFIG_HAVE_DOUBLE -double cos (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double cosl (long double x); -#endif - -float tanf (float x); -#if CONFIG_HAVE_DOUBLE -double tan (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double tanl (long double x); -#endif - -float asinf (float x); -#if CONFIG_HAVE_DOUBLE -double asin (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double asinl (long double x); -#endif - -float acosf (float x); -#if CONFIG_HAVE_DOUBLE -double acos (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double acosl (long double x); -#endif - -float atanf (float x); -#if CONFIG_HAVE_DOUBLE -double atan (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double atanl (long double x); -#endif - -float atan2f(float y, float x); -#if CONFIG_HAVE_DOUBLE -double atan2 (double y, double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double atan2l(long double y, long double x); -#endif - -float sinhf (float x); -#if CONFIG_HAVE_DOUBLE -double sinh (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double sinhl (long double x); -#endif - -float coshf (float x); -#if CONFIG_HAVE_DOUBLE -double cosh (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double coshl (long double x); -#endif - -float tanhf (float x); -#if CONFIG_HAVE_DOUBLE -double tanh (double x); -#endif -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double tanhl (long double x); -#endif - -#if defined(__cplusplus) -} -#endif - -#endif /* CONFIG_LIBM */ #endif /* __INCLUDE_NUTTX_MATH_H */ diff --git a/nuttx/include/nuttx/net/ioctl.h b/nuttx/include/nuttx/net/ioctl.h index d5d1a001c8..be3f597f47 100644 --- a/nuttx/include/nuttx/net/ioctl.h +++ b/nuttx/include/nuttx/net/ioctl.h @@ -146,15 +146,9 @@ #define SIOCSIWPMKSA _SIOC(0x0036) /* PMKSA cache operation */ -/* Interface flags */ - -#define SIOCSIFFLAGS _SIOC(0x0037) /* Sets the interface flags */ -#define SIOCGIFFLAGS _SIOC(0x0038) /* Gets the interface flags */ - /**************************************************************************** * Type Definitions ****************************************************************************/ - /* See include/net/if.h */ /**************************************************************************** diff --git a/nuttx/include/nuttx/net/uip/uip-arch.h b/nuttx/include/nuttx/net/uip/uip-arch.h index 73805c6fb1..9546de04eb 100644 --- a/nuttx/include/nuttx/net/uip/uip-arch.h +++ b/nuttx/include/nuttx/net/uip/uip-arch.h @@ -90,10 +90,6 @@ struct uip_driver_s char d_ifname[IFNAMSIZ]; #endif - /* Drivers interface flags. See IFF_* definitions in include/net/if.h */ - - uint8_t d_flags; - /* Ethernet device identity */ #ifdef CONFIG_NET_ETHERNET diff --git a/nuttx/include/nuttx/nxflat.h b/nuttx/include/nuttx/nxflat.h new file mode 100644 index 0000000000..b6501522ef --- /dev/null +++ b/nuttx/include/nuttx/nxflat.h @@ -0,0 +1,264 @@ +/**************************************************************************** + * include/nuttx/nxflat.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __INCLUDE_NUTTX_NXFLAT_H +#define __INCLUDE_NUTTX_NXFLAT_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* This struct provides a desciption of the currently loaded instantiation + * of an nxflat binary. + */ + +struct nxflat_loadinfo_s +{ + /* Instruction Space (ISpace): This region contains the nxflat file header + * plus everything from the text section. Ideally, will have only one mmap'ed + * text section instance in the system for each module. + */ + + uint32_t ispace; /* Address where hdr/text is loaded */ + uint32_t entryoffs; /* Offset from ispace to entry point */ + uint32_t isize; /* Size of ispace. */ + + /* Data Space (DSpace): This region contains all information that in referenced + * as data (other than the stack which is separately allocated). There will be + * a unique instance of DSpace (and stack) for each instance of a process. + */ + + struct dspace_s *dspace; /* Allocated D-Space (data/bss/etc) */ + uint32_t datasize; /* Size of data segment in dspace */ + uint32_t bsssize; /* Size of bss segment in dspace */ + uint32_t stacksize; /* Size of stack (not allocated) */ + uint32_t dsize; /* Size of dspace (may be large than parts) */ + + /* This is temporary memory where relocation records will be loaded. */ + + uint32_t relocstart; /* Start of array of struct flat_reloc */ + uint16_t reloccount; /* Number of elements in reloc array */ + + /* File descriptors */ + + int filfd; /* Descriptor for the file being loaded */ + + /* This is a copy of the NXFLAT header (still in network order) */ + + struct nxflat_hdr_s header; +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * These are APIs exported by libnxflat (and may be used outside of NuttX): + ****************************************************************************/ + +/*********************************************************************** + * Name: nxflat_verifyheader + * + * Description: + * Given the header from a possible NXFLAT executable, verify that it + * is an NXFLAT executable. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ***********************************************************************/ + +EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header); + +/*********************************************************************** + * Name: nxflat_init + * + * Description: + * This function is called to configure the library to process an NXFLAT + * program binary. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ***********************************************************************/ + +EXTERN int nxflat_init(const char *filename, + struct nxflat_loadinfo_s *loadinfo); + +/*********************************************************************** + * Name: nxflat_uninit + * + * Description: + * Releases any resources committed by nxflat_init(). This essentially + * undoes the actions of nxflat_init. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ***********************************************************************/ + +EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo); + +/*********************************************************************** + * Name: nxflat_load + * + * Description: + * Loads the binary specified by nxflat_init into memory, mapping + * the I-space executable regions, allocating the D-Space region, + * and inializing the data segment (relocation information is + * temporarily loaded into the BSS region. BSS will be cleared + * by nxflat_bind() after the relocation data has been processed). + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ***********************************************************************/ + +EXTERN int nxflat_load(struct nxflat_loadinfo_s *loadinfo); + +/*********************************************************************** + * Name: nxflat_read + * + * Description: + * Read 'readsize' bytes from the object file at 'offset' + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ***********************************************************************/ + +EXTERN int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, + int readsize, int offset); + +/*********************************************************************** + * Name: nxflat_bind + * + * Description: + * Bind the imported symbol names in the loaded module described by + * 'loadinfo' using the exported symbol values provided by 'symtab' + * After binding the module, clear the BSS region (which held the relocation + * data) in preparation for execution. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ***********************************************************************/ + +struct symtab_s; +EXTERN int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo, + FAR const struct symtab_s *exports, int nexports); + +/*********************************************************************** + * Name: nxflat_unload + * + * Description: + * This function unloads the object from memory. This essentially + * undoes the actions of nxflat_load. + * + * Returned Value: + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ***********************************************************************/ + +EXTERN int nxflat_unload(struct nxflat_loadinfo_s *loadinfo); + +/**************************************************************************** + * These are APIs used internally only by NuttX: + ****************************************************************************/ +/*********************************************************************** + * Name: nxflat_initialize + * + * Description: + * NXFLAT support is built unconditionally. However, it order to + * use this binary format, this function must be called during system + * format in order to register the NXFLAT binary format. + * + * Returned Value: + * This is a NuttX internal function so it follows the convention that + * 0 (OK) is returned on success and a negated errno is returned on + * failure. + * + ***********************************************************************/ + +EXTERN int nxflat_initialize(void); + +/**************************************************************************** + * Name: nxflat_uninitialize + * + * Description: + * Unregister the NXFLAT binary loader + * + * Returned Value: + * None + * + ****************************************************************************/ + +EXTERN void nxflat_uninitialize(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __INCLUDE_NUTTX_NXFLAT_H */ diff --git a/nuttx/include/nuttx/power/pm.h b/nuttx/include/nuttx/power/pm.h index 9c0568b2dd..86e23f090e 100644 --- a/nuttx/include/nuttx/power/pm.h +++ b/nuttx/include/nuttx/power/pm.h @@ -163,7 +163,7 @@ #endif #if CONFIG_PM_IDLEENTER_THRESH >= CONFIG_PM_IDLEEXIT_THRESH -# error "Must have CONFIG_PM_IDLEENTER_THRESH < CONFIG_PM_IDLEEXIT_THRESH" +# error "Must have CONFIG_PM_IDLEENTER_THRESH < CONFIG_PM_IDLEEXIT_THRESH #endif #ifndef CONFIG_PM_IDLEENTER_COUNT @@ -181,7 +181,7 @@ #endif #if CONFIG_PM_STANDBYENTER_THRESH >= CONFIG_PM_STANDBYEXIT_THRESH -# error "Must have CONFIG_PM_STANDBYENTER_THRESH < CONFIG_PM_STANDBYEXIT_THRESH" +# error "Must have CONFIG_PM_STANDBYENTER_THRESH < CONFIG_PM_STANDBYEXIT_THRESH #endif #ifndef CONFIG_PM_STANDBYENTER_COUNT @@ -199,7 +199,7 @@ #endif #if CONFIG_PM_SLEEPENTER_THRESH >= CONFIG_PM_SLEEPEXIT_THRESH -# error "Must have CONFIG_PM_SLEEPENTER_THRESH < CONFIG_PM_SLEEPEXIT_THRESH" +# error "Must have CONFIG_PM_SLEEPENTER_THRESH < CONFIG_PM_SLEEPEXIT_THRESH #endif #ifndef CONFIG_PM_SLEEPENTER_COUNT diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 172f469011..241af6210c 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -138,11 +138,11 @@ typedef union entry_u entry_t; */ #ifdef CONFIG_SCHED_ATEXIT -typedef CODE void (*atexitfunc_t)(void); +typedef void (*atexitfunc_t)(void); #endif #ifdef CONFIG_SCHED_ONEXIT -typedef CODE void (*onexitfunc_t)(int exitcode, FAR void *arg); +typedef void (*onexitfunc_t)(int exitcode, FAR void *arg); #endif /* POSIX Message queue */ @@ -189,7 +189,7 @@ struct _TCB start_t start; /* Thread start function */ entry_t entry; /* Entry Point into the thread */ -#if defined(CONFIG_SCHED_ATEXIT) && !defined(CONFIG_SCHED_ONEXIT) +#ifdef CONFIG_SCHED_ATEXIT # if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1 atexitfunc_t atexitfunc[CONFIG_SCHED_ATEXIT_MAX]; # else diff --git a/nuttx/include/nuttx/symtab.h b/nuttx/include/nuttx/symtab.h new file mode 100644 index 0000000000..b302ab20a9 --- /dev/null +++ b/nuttx/include/nuttx/symtab.h @@ -0,0 +1,163 @@ +/**************************************************************************** + * include/nuttx/symtab.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __INCLUDE_NUTTX_SYMTAB_H +#define __INCLUDE_NUTTX_SYMTAB_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* struct symbtab_s describes one entry in the symbol table. A symbol table + * is a fixed size array of struct symtab_s. The information is intentionally + * minimal and supports only: + * + * 1. Function points as sym_values. Of other kinds of values need to be + * supported, then typing information would also need to be included in + * the structure. + * + * 2. Fixed size arrays. There is no explicit provisional for dyanamically + * adding or removing entries from the symbol table (realloc might be + * used for that purpose if needed). The intention is to support only + * fixed size arrays completely defined at compilation or link time. + */ + +struct symtab_s +{ + FAR const char *sym_name; /* A pointer to the symbol name string */ + FAR const void *sym_value; /* The value associated witht the string */ +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Name: symtab_findbyname + * + * Description: + * Find the symbol in the symbol table with the matching name. + * This version assumes that table is not ordered with respect to symbol + * name and, hence, access time will be linear with respect to nsyms. + * + * Returned Value: + * A reference to the symbol table entry if an entry with the matching + * name is found; NULL is returned if the entry is not found. + * + ****************************************************************************/ + +EXTERN FAR const struct symtab_s * +symtab_findbyname(FAR const struct symtab_s *symtab, + FAR const char *name, int nsyms); + +/**************************************************************************** + * Name: symtab_findorderedbyname + * + * Description: + * Find the symbol in the symbol table with the matching name. + * This version assumes that table ordered with respect to symbol name. + * + * Returned Value: + * A reference to the symbol table entry if an entry with the matching + * name is found; NULL is returned if the entry is not found. + * + ****************************************************************************/ + +EXTERN FAR const struct symtab_s * +symtab_findorderedbyname(FAR const struct symtab_s *symtab, + FAR const char *name, int nsyms); + +/**************************************************************************** + * Name: symtab_findbyvalue + * + * Description: + * Find the symbol in the symbol table whose value closest (but not greater + * than), the provided value. This version assumes that table is not ordered + * with respect to symbol name and, hence, access time will be linear with + * respect to nsyms. + * + * Returned Value: + * A reference to the symbol table entry if an entry with the matching + * name is found; NULL is returned if the entry is not found. + * + ****************************************************************************/ + +EXTERN FAR const struct symtab_s * +symtab_findbyvalue(FAR const struct symtab_s *symtab, + FAR void *value, int nsyms); + +/**************************************************************************** + * Name: symtab_findorderedbyvalue + * + * Description: + * Find the symbol in the symbol table whose value closest (but not greater + * than), the provided value. This version assumes that table is ordered + * with respect to symbol name. + * + * Returned Value: + * A reference to the symbol table entry if an entry with the matching + * name is found; NULL is returned if the entry is not found. + * + ****************************************************************************/ + +EXTERN FAR const struct symtab_s * +symtab_findorderedbyvalue(FAR const struct symtab_s *symtab, + FAR void *value, int nsyms); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __INCLUDE_NUTTX_SYMTAB_H */ + diff --git a/nuttx/include/nuttx/usb/cdcacm.h b/nuttx/include/nuttx/usb/cdcacm.h index 1dca050c4b..307f2a5977 100644 --- a/nuttx/include/nuttx/usb/cdcacm.h +++ b/nuttx/include/nuttx/usb/cdcacm.h @@ -205,7 +205,7 @@ /* USB Controller */ #ifndef CONFIG_USBDEV_SELFPOWERED -# define SELFPOWERED USB_CONFIG_ATTR_SELFPOWER +# define SELFPOWERED USB_CONFIG_ATT_SELFPOWER #else # define SELFPOWERED (0) #endif diff --git a/nuttx/include/nuttx/usb/usbdev_trace.h b/nuttx/include/nuttx/usb/usbdev_trace.h index ab3a5f4bea..ae8e13c3a4 100644 --- a/nuttx/include/nuttx/usb/usbdev_trace.h +++ b/nuttx/include/nuttx/usb/usbdev_trace.h @@ -238,6 +238,10 @@ #define USBCOMPOSITE_TRACEERR_ALLOCDEVSTRUCT 0x000a #define USBCOMPOSITE_TRACEERR_CLASSOBJECT 0x000b #define USBCOMPOSITE_TRACEERR_DEVREGISTER 0x000c +#define USBCOMPOSITE_TRACEERR_INVALIDARG 0x000d +#define USBCOMPOSITE_TRACEERR_INVALIDARG 0x000f +#define USBCOMPOSITE_TRACEERR_INVALIDARG 0x0010 +#define USBCOMPOSITE_TRACEERR_INVALIDARG 0x0011 /* USB Storage driver class events ******************************************/ diff --git a/nuttx/include/nuttx/wqueue.h b/nuttx/include/nuttx/wqueue.h index c509bf197b..644585c56f 100644 --- a/nuttx/include/nuttx/wqueue.h +++ b/nuttx/include/nuttx/wqueue.h @@ -109,35 +109,17 @@ # endif #endif -/* Work queue IDs (indices): - * - * Kernel Work Queues: - * HPWORK: This ID of the high priority work queue that should only be used for - * hi-priority, time-critical, driver bottom-half functions. - * - * LPWORK: This is the ID of the low priority work queue that can be used for any - * purpose. if CONFIG_SCHED_LPWORK is not defined, then there is only one kernel - * work queue and LPWORK == HPWORK. - * - * User Work Queue: - * USRWORK: CONFIG_NUTTX_KERNEL and CONFIG_SCHED_USRWORK are defined, then NuttX - * will also support a user-accessible work queue. Otherwise, USRWORK == LPWORK. +/* Work queue IDs (indices). These are both zero if there is only one work + * queue. */ #define HPWORK 0 #ifdef CONFIG_SCHED_LPWORK -# define LPWORK (HPWORK+1) +# define LPWORK 1 #else # define LPWORK HPWORK #endif -#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_SCHED_USRWORK) -# warning "Feature not implemented" -# define USRWORK (LPWORK+1) -#else -# define USRWORK LPWORK -#endif - /**************************************************************************** * Public Types ****************************************************************************/ diff --git a/nuttx/include/stdio.h b/nuttx/include/stdio.h index 8796861a40..e9218046c5 100644 --- a/nuttx/include/stdio.h +++ b/nuttx/include/stdio.h @@ -102,9 +102,6 @@ extern "C" { /* ANSI-like File System Interfaces */ -/* Operations on streams (FILE) */ - -EXTERN void clearerr(register FILE *stream); EXTERN int fclose(FAR FILE *stream); EXTERN int fflush(FAR FILE *stream); EXTERN int feof(FAR FILE *stream); @@ -123,9 +120,6 @@ EXTERN int fsetpos(FAR FILE *stream, FAR fpos_t *pos); EXTERN long ftell(FAR FILE *stream); EXTERN size_t fwrite(FAR const void *ptr, size_t size, size_t n_items, FAR FILE *stream); EXTERN FAR char *gets(FAR char *s); -EXTERN int ungetc(int c, FAR FILE *stream); - -/* Operations on the stdout stream, buffers, paths, and the whole printf-family */ EXTERN int printf(const char *format, ...); EXTERN int puts(FAR const char *s); @@ -136,6 +130,7 @@ EXTERN int snprintf(FAR char *buf, size_t size, const char *format, ...); EXTERN int sscanf(const char *buf, const char *fmt, ...); EXTERN void perror(FAR const char *s); +EXTERN int ungetc(int c, FAR FILE *stream); EXTERN int vprintf(FAR const char *format, va_list ap); EXTERN int vfprintf(FAR FILE *stream, const char *format, va_list ap); EXTERN int vsprintf(FAR char *buf, const char *format, va_list ap); diff --git a/nuttx/include/termios.h b/nuttx/include/termios.h index 0ca8a6614b..c8f590a5b4 100644 --- a/nuttx/include/termios.h +++ b/nuttx/include/termios.h @@ -232,7 +232,7 @@ struct termios * cf[set|get][o|i]speed() POSIX interfaces. */ - speed_t c_speed; /* Input/output speed (non-POSIX)*/ + speed_t c_speed; /* Input/output speed (non-POSIX)*/ }; /**************************************************************************** diff --git a/nuttx/include/unistd.h b/nuttx/include/unistd.h index 681ce9e632..e2ad6ff826 100644 --- a/nuttx/include/unistd.h +++ b/nuttx/include/unistd.h @@ -133,7 +133,6 @@ EXTERN pid_t getpid(void); EXTERN void _exit(int status) noreturn_function; EXTERN unsigned int sleep(unsigned int seconds); EXTERN int usleep(useconds_t usec); -EXTERN int pause(void); /* File descriptor operations */ diff --git a/nuttx/lib/Kconfig b/nuttx/lib/Kconfig new file mode 100644 index 0000000000..69a55d09cf --- /dev/null +++ b/nuttx/lib/Kconfig @@ -0,0 +1,194 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config STDIO_BUFFER_SIZE + int "C STDIO buffer size" + default 64 + ---help--- + Size of buffers using within the C buffered I/O interfaces. + (printf, putchar, fwrite, etc.). + +config STDIO_LINEBUFFER + bool "STDIO line buffering" + default y + ---help--- + Flush buffer I/O whenever a newline character is found in + the output data stream. + +config NUNGET_CHARS + int "Number unget() characters" + default 2 + ---help--- + Number of characters that can be buffered by ungetc() (Only if NFILE_STREAMS > 0) + +config LIB_HOMEDIR + string "Home directory" + default "/" + depends on !DISABLE_ENVIRON + ---help--- + The home directory to use with operations like such as 'cd ~' + +config HAVE_LIBM + bool "Architecture-specific libm.a" + default n + ---help--- + Architecture specific logic provides an implementation of libm.a + and a math.h header file that can be found at include/arch/math.h. + +config NOPRINTF_FIELDWIDTH + bool "Disable sprintf support fieldwidth" + default n + ---help--- + sprintf-related logic is a + little smaller if we do not support fieldwidthes + +config LIBC_FLOATINGPOINT + bool "Enable floating point in printf" + default n + ---help--- + By default, floating point + support in printf, sscanf, etc. is disabled. + +choice + prompt "Newline Options" + default EOL_IS_EITHER_CRLF + ---help--- + This selection determines the line terminating character that is used. + Some environments may return CR as end-of-line, others LF, and others + both. If not specified, the default is either CR or LF (but not both) + as the line terminating charactor. + +config EOL_IS_CR + bool "EOL is CR" + +config EOL_IS_LF + bool "EOL is LF" + +config EOL_IS_BOTH_CRLF + bool "EOL is CR and LF" + +config EOL_IS_EITHER_CRLF + bool "EOL is CR or LF" + +endchoice + +config LIBC_STRERROR + bool "Enable strerror" + default n + ---help--- + strerror() is useful because it decodes 'errno' values into a human readable + strings. But it can also require a lot of memory. If this option is selected, + strerror() will still exist in the build but it will not decode error values. + This option should be used by other logic to decide if it should use strerror() + or not. For example, the NSH application will not use strerror() if this + option is not selected; perror() will not use strerror() is this option is not + selected (see also NSH_STRERROR). + +config LIBC_STRERROR_SHORT + bool "Use short error descriptions in strerror()" + default n + depends on LIBC_STRERROR + ---help--- + If this option is selected, then strerror() will use a shortened string when + it decodes the error. Specifically, strerror() is simply use the string that + is the common name for the error. For example, the 'errno' value of 2 will + produce the string "No such file or directory" is LIBC_STRERROR_SHORT + is not defined but the string "ENOENT" is LIBC_STRERROR_SHORT is defined. + +config LIBC_PERROR_STDOUT + bool "perror() to stdout" + default n + ---help--- + POSIX requires that perror() provide its output on stderr. This option may + be defined, however, to provide perror() output that is serialized with + other stdout messages. + +config ARCH_LOWPUTC + bool "Low-level console output" + default "y" + ---help--- + architecture supports low-level, boot time console output + +config LIB_SENDFILE_BUFSIZE + int "sendfile() buffer size" + default 512 + ---help--- + Size of the I/O buffer to allocate in sendfile(). Default: 512b + +config ARCH_ROMGETC + bool "Support for ROM string access" + default n + ---help--- + In Harvard architectures, data accesses and instruction accesses + occur on different busses, perhaps concurrently. All data accesses + are performed on the data bus unless special machine instructions + are used to read data from the instruction address space. Also, in + the typical MCU, the available SRAM data memory is much smaller that + the non-volatile FLASH instruction memory. So if the application + requires many constant strings, the only practical solution may be + to store those constant strings in FLASH memory where they can only + be accessed using architecture-specific machine instructions. + + If ARCH_ROMGETC is defined, then the architecture logic must export + the function up_romgetc(). up_romgetc() will simply read one byte + of data from the instruction space. + + If ARCH_ROMGETC, certain C stdio functions are effected: (1) All + format strings in printf, fprintf, sprintf, etc. are assumed to lie + in FLASH (string arguments for %s are still assumed to reside in SRAM). + And (2), the string argument to puts and fputs is assumed to reside + in FLASH. Clearly, these assumptions may have to modified for the + particular needs of your environment. There is no "one-size-fits-all" + solution for this problem. + +config ARCH_OPTIMIZED_FUNCTIONS + bool "Enable arch optimized functions" + default n + ---help--- + Allow for architecture optimized implementations of certain library + functions. Architecture-specific implementations can improve overall + system performance. + +if ARCH_OPTIMIZED_FUNCTIONS +config ARCH_MEMCPY + bool "memcpy" + default n + +config ARCH_MEMCMP + bool "memcmp" + default n + +config ARCH_MEMMOVE + bool "memmove" + default n + +config ARCH_MEMSET + bool "memset" + default n + +config ARCH_STRCMP + bool "strcmp" + default n + +config ARCH_STRCPY + bool "strcpy" + default n + +config ARCH_STRNCPY + bool "strncpy" + default n + +config ARCH_STRLEN + bool "strlen" + default n + +config ARCH_STRNLEN + bool "strlen" + default n + +config ARCH_BZERO + bool "bzero" + default n +endif diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile index 58857dbd41..fc8f0c4dda 100644 --- a/nuttx/lib/Makefile +++ b/nuttx/lib/Makefile @@ -1,7 +1,7 @@ ############################################################################ # lib/Makefile # -# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -35,11 +35,101 @@ -include $(TOPDIR)/Make.defs -all: +ASRCS = +CSRCS = -depend: +DEPPATH := --dep-path . +VPATH := . -clean: +include stdio/Make.defs +include stdlib/Make.defs +include unistd/Make.defs +include sched/Make.defs +include string/Make.defs +include pthread/Make.defs +include semaphore/Make.defs +include signal/Make.defs +include mqueue/Make.defs +include math/Make.defs +include net/Make.defs +include time/Make.defs +include libgen/Make.defs +include dirent/Make.defs +include termios/Make.defs +include queue/Make.defs +include misc/Make.defs + +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +UBIN = libulib$(LIBEXT) +KBIN = libklib$(LIBEXT) +BIN = liblib$(LIBEXT) + +all: $(BIN) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +$(BIN): $(OBJS) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) + +ifneq ($(BIN),$(UBIN)) +.userlib: + @$(MAKE) $(UBIN) BIN=$(UBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) + @touch .userlib + +$(UBIN): kclean .userlib +endif + +ifneq ($(BIN),$(KBIN)) +.kernlib: + @$(MAKE) $(KBIN) BIN=$(KBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) + @touch .kernlib + +$(KBIN): uclean .kernlib +endif + +.depend: Makefile $(SRCS) + @$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ + +depend: .depend + +# Clean Targets: +# Clean user-mode temporary files (retaining the UBIN binary) + +uclean: +ifneq ($(OBJEXT),) + @( if [ -f .userlib ]; then rm -f *$(OBJEXT); fi ) +endif + @rm -f .userlib *~ .*.swp + +# Clean kernel-mode temporary files (retaining the KBIN binary) + +kclean: +ifneq ($(OBJEXT),) + @( if [ -f .kernlib ]; then rm -f *$(OBJEXT); fi ) +endif + @rm -f .kernlib *~ .*.swp + +# Really clean everything + +clean: uclean kclean + @rm -f $(BIN) $(UBIN) $(KBIN) *~ .*.swp $(call CLEAN) +# Deep clean -- removes all traces of the configuration + distclean: clean + @rm -f Make.dep .depend + +-include Make.dep diff --git a/nuttx/lib/README.txt b/nuttx/lib/README.txt index f742b9a243..63d1c343c0 100644 --- a/nuttx/lib/README.txt +++ b/nuttx/lib/README.txt @@ -1,6 +1,84 @@ -lib/ README File +lib +=== + +This directory contains numerous, small functions typically associated with +what you would expect to find in a standard C library. The sub-directories +in this directory contain standard interface that can be executed by user- +mode programs. + +Normally, NuttX is built with no protection and all threads running in kerne- +mode. In that model, there is no real architectural distinction between +what is a kernel-mode program and what is a user-mode program; the system is +more like on multi-threaded program that all runs in kernel-mode. + +But if the CONFIG_NUTTX_KERNEL option is selected, NuttX will be built into +distinct user-mode and kernel-mode sections. In that case, most of the +code in the nuttx/ directory will run in kernel-mode with with exceptions +of (1) the user-mode "proxies" found in syscall/proxies, and (2) the +standard C library functions found in this directory. In this build model, +it is critical to separate the user-mode OS interfaces in this way. + +Sub-Directories +=============== + +The files in the lib/ directory are organized (mostly) according which file +in the include/ directory provides the prototype for library functions. So +we have: + + libgen - libgen.h + math - math.h and fixedmath.h + mqueue - pthread.h + net - Various network-related header files: netinet/ether.h, arpa/inet.h + pthread - pthread.h + queue - queue.h + sched - sched.h + semaphore - semaphore.h + stdio - stdio.h + stdlib - stdlib.h + string - string.h + time - time.h + unistd - unistd.h + +There is also a misc/ subdirectory that contains various internal functions +and interfaces from header files that are too few to warrant their own sub- +directory: + + misc - Nonstandard "glue" logic, debug.h, crc32.h, dirent.h + +Library Database ================ -This directory is reserved for libraries generated during the NuttX build process +Information about functions available in the NuttX C library information is +maintained in a database. That "database" is implemented as a simple comma- +separated-value file, lib.csv. Most spreadsheets programs will accept this +format and can be used to maintain the library database. +This library database will (eventually) be used to generate symbol library +symbol table information that can be exported to external applications. +The format of the CSV file for each line is: + + Field 1: Function name + Field 2: The header file that contains the function prototype + Field 3: Condition for compilation + Field 4: The type of function return value. + Field 5 - N+5: The type of each of the N formal parameters of the function + +Each type field has a format as follows: + + type name: + For all simpler types + formal type | actual type: + For array types where the form of the formal (eg. int parm[2]) + differs from the type of actual passed parameter (eg. int*). This + is necessary because you cannot do simple casts to array types. + formal type | union member actual type | union member fieldname: + A similar situation exists for unions. For example, the formal + parameter type union sigval -- You cannot cast a uintptr_t to + a union sigval, but you can cast to the type of one of the union + member types when passing the actual paramter. Similarly, we + cannot cast a union sigval to a uinptr_t either. Rather, we need + to cast a specific union member fieldname to uintptr_t. + +NOTE: The tool mksymtab can be used to generate a symbol table from this CSV +file. See nuttx/tools/README.txt for further details about the use of mksymtab. diff --git a/nuttx/lib/dirent/Make.defs b/nuttx/lib/dirent/Make.defs new file mode 100644 index 0000000000..cc1d6b7839 --- /dev/null +++ b/nuttx/lib/dirent/Make.defs @@ -0,0 +1,48 @@ +############################################################################ +# lib/dirent/Make.defs +# +# 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. +# +############################################################################ + +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) + +# Add the dirent C files to the build + +CSRCS += lib_readdirr.c lib_telldir.c + +# Add the dirent directory to the build + +DEPPATH += --dep-path dirent +VPATH += :dirent + +endif + diff --git a/nuttx/lib/dirent/lib_readdirr.c b/nuttx/lib/dirent/lib_readdirr.c new file mode 100644 index 0000000000..47c5b9a7bd --- /dev/null +++ b/nuttx/lib/dirent/lib_readdirr.c @@ -0,0 +1,122 @@ +/**************************************************************************** + * lib/dirent/lib_readdirr.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: readdir_r + * + * Description: + * The readdir() function returns a pointer to a dirent + * structure representing the next directory entry in the + * directory stream pointed to by dir. It returns NULL on + * reaching the end-of-file or if an error occurred. + * + * Inputs: + * dirp -- An instance of type DIR created by a previous + * call to opendir(); + * entry -- The storage pointed to by entry must be large + * enough for a dirent with an array of char d_name + * members containing at least {NAME_MAX}+1 elements. + * result -- Upon successful return, the pointer returned + * at *result shall have the same value as the + * argument entry. Upon reaching the end of the directory + * stream, this pointer shall have the value NULL. + * + * Return: + * If successful, the readdir_r() function return s zero; + * otherwise, an error number is returned to indicate the + * error. + * + * EBADF - Invalid directory stream descriptor dir + * + ****************************************************************************/ + +int readdir_r(FAR DIR *dirp, FAR struct dirent *entry, + FAR struct dirent **result) +{ + struct dirent *tmp; + + /* NOTE: The following use or errno is *not* thread-safe */ + + set_errno(0); + tmp = readdir(dirp); + if (!tmp) + { + int error = get_errno(); + if (!error) + { + if (result) + { + *result = NULL; + } + return 0; + } + else + { + return error; + } + } + + if (entry) + { + memcpy(entry, tmp, sizeof(struct dirent)); + } + + if (result) + { + *result = entry; + } + return 0; +} + diff --git a/nuttx/lib/dirent/lib_telldir.c b/nuttx/lib/dirent/lib_telldir.c new file mode 100644 index 0000000000..3753b326e9 --- /dev/null +++ b/nuttx/lib/dirent/lib_telldir.c @@ -0,0 +1,91 @@ +/**************************************************************************** + * lib/dirent/fs_telldir.c + * + * Copyright (C) 2007-2008, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: telldir + * + * Description: + * The telldir() function returns the current location + * associated with the directory stream dirp. + * + * Inputs: + * dirp -- An instance of type DIR created by a previous + * call to opendir(); + * + * Return: + * On success, the telldir() function returns the current + * location in the directory stream. On error, -1 is + * returned, and errno is set appropriately. + * + * EBADF - Invalid directory stream descriptor dir + * + ****************************************************************************/ + +off_t telldir(FAR DIR *dirp) +{ + struct fs_dirent_s *idir = (struct fs_dirent_s *)dirp; + + if (!idir || !idir->fd_root) + { + set_errno(EBADF); + return (off_t)-1; + } + + /* Just return the current position */ + + return idir->fd_position; +} + diff --git a/nuttx/lib/lib.csv b/nuttx/lib/lib.csv new file mode 100644 index 0000000000..171f64e9b7 --- /dev/null +++ b/nuttx/lib/lib.csv @@ -0,0 +1,171 @@ +"_inet_ntoa","arpa/inet.h","!defined(CONFIG_NET_IPv6) && !defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","in_addr_t" +"abort","stdlib.h","","void" +"abs","stdlib.h","","int","int" +"asprintf","stdio.h","","int","FAR char **","const char *","..." +"avsprintf","stdio.h","","int","FAR char **","const char *","va_list" +"b16atan2","fixedmath.h","","b16_t","b16_t","b16_t" +"b16cos","fixedmath.h","","b16_t","b16_t" +"b16divb16","fixedmath.h","","b16_t","b16_t","b16_t" +"b16mulb16","fixedmath.h","","b16_t","b16_t","b16_t" +"b16sin","fixedmath.h","","b16_t","b16_t" +"b16sqr","fixedmath.h","","b16_t","b16_t" +"basename","libgen.h","","FAR char","FAR char *" +"cfgetspeed","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","speed_t","FAR const struct termios *" +"cfsetspeed","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","FAR struct termios *","speed_t" +"chdir","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)","int","FAR const char *" +"crc32","crc32.h","","uint32_t","FAR const uint8_t *","size_t" +"crc32part","crc32.h","","uint32_t","FAR const uint8_t *","size_t","uint32_t" +"dbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG)","int","const char *","..." +"dbg_enable","debug.h","defined(CONFIG_DEBUG_ENABLE)","void","bool" +"dirname","libgen.h","","FAR char","FAR char *" +"dq_addafter","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *" +"dq_addbefore","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *" +"dq_addfirst","queue.h","","void","FAR dq_entry_t *","dq_queue_t *" +"dq_addlast","queue.h","","void","FAR dq_entry_t *","dq_queue_t *" +"dq_rem","queue.h","","void","FAR dq_entry_t *","dq_queue_t *" +"dq_remfirst","queue.h","","FAR dq_entry_t","dq_queue_t *" +"dq_remlast","queue.h","","FAR dq_entry_t","dq_queue_t *" +"ether_ntoa","netinet/ether.h","","FAR char","FAR const struct ether_addr *" +"fclose","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *" +"fdopen","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR FILE","int","FAR const char *" +"fflush","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *" +"fgetc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *" +"fgetpos","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR fpos_t *" +"fgets","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR char","FAR char *","int","FAR FILE *" +"fileno","stdio.h","","int","FAR FILE *" +"fopen","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR FILE","FAR const char *","FAR const char *" +"fprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR const char *","..." +"fputc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","int c","FAR FILE *" +"fputs","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *","FAR FILE *" +"fread","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","size_t","FAR void *","size_t","size_t","FAR FILE *" +"fseek","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","long int","int" +"fsetpos","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR fpos_t *" +"ftell","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","long","FAR FILE *" +"fwrite","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","size_t","FAR const void *","size_t","size_t","FAR FILE *" +"getcwd","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)","FAR char","FAR char *","size_t" +"getopt","unistd.h","","int","int","FAR char *const[]","FAR const char *" +"getoptargp","unistd.h","","FAR char *" +"getoptindp","unistd.h","","int" +"getoptoptp","unistd.h","","int" +"gets","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR char","FAR char *" +"gmtime","time.h","","struct tm","const time_t *" +"gmtime_r","time.h","","FAR struct tm","FAR const time_t *","FAR struct tm *" +"htonl","arpa/inet.h","","uint32_t","uint32_t" +"htons","arpa/inet.h","","uint16_t","uint16_t" +"imaxabs","stdlib.h","","intmax_t","intmax_t" +"inet_addr","arpa/inet.h","","in_addr_t","FAR const char " +"inet_ntoa","arpa/inet.h","!defined(CONFIG_NET_IPv6) && defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","struct in_addr" +"inet_ntop","arpa/inet.h","","FAR const char","int","FAR const void *","FAR char *","socklen_t" +"inet_pton","arpa/inet.h","","int","int","FAR const char *","FAR void *" +"labs","stdlib.h","","long int","long int" +"lib_dumpbuffer","debug.h","","void","FAR const char *","FAR const uint8_t *","unsigned int" +"lib_lowprintf","debug.h","","int","FAR const char *","..." +"lib_rawprintf","debug.h","","int","FAR const char *","..." +"llabs","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long int","long long int" +"lldbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..." +"llvdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..." +"match","","","int","const char *","const char *" +"memccpy","string.h","","FAR void","FAR void *","FAR const void *","int c","size_t" +"memchr","string.h","","FAR void","FAR const void *","int c","size_t" +"memcmp","string.h","","int","FAR const void *","FAR const void *","size_t" +"memcpy","string.h","","FAR void","FAR void *","FAR const void *","size_t" +"memmove","string.h","","FAR void","FAR void *","FAR const void *","size_t" +"memset","string.h","","FAR void","FAR void *","int c","size_t" +"mktime","time.h","","time_t","const struct tm *" +"mq_getattr","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","struct mq_attr *" +"mq_setattr","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","const struct mq_attr *","struct mq_attr *" +"ntohl","arpa/inet.h","","uint32_t","uint32_t" +"ntohs","arpa/inet.h","","uint16_t","uint16_t" +"perror","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","void","FAR const char *" +"printf","stdio.h","","int","const char *","..." +"pthread_attr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *" +"pthread_attr_getinheritsched","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_attr_t *","FAR int *" +"pthread_attr_getschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR struct sched_param *" +"pthread_attr_getschedpolicy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int *" +"pthread_attr_getstacksize","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR long *" +"pthread_attr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *" +"pthread_attr_setinheritsched","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int" +"pthread_attr_setschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR const struct sched_param *" +"pthread_attr_setschedpolicy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int" +"pthread_attr_setstacksize","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","long" +"pthread_barrierattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *" +"pthread_barrierattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_barrierattr_t *","FAR int *" +"pthread_barrierattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *" +"pthread_barrierattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *","int" +"pthread_condattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *" +"pthread_condattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *" +"pthread_mutexattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *" +"pthread_mutexattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","FAR int *" +"pthread_mutexattr_gettype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","const pthread_mutexattr_t *","int *" +"pthread_mutexattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *" +"pthread_mutexattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","int " +"pthread_mutexattr_settype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","pthread_mutexattr_t *","int" +"puts","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *" +"qsort","stdlib.h","","void","void *","size_t","size_t","int(*)(const void *","const void *)" +"rand","stdlib.h","","int" +"readdir_r","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","int","FAR DIR *","FAR struct dirent *","FAR struct dirent **" +"rint","","","double_t","double_t" +"sched_get_priority_max","sched.h","","int","int" +"sched_get_priority_min","sched.h","","int","int" +"sem_getvalue","semaphore.h","","int","FAR sem_t *","FAR int *" +"sem_init","semaphore.h","","int","FAR sem_t *","int","unsigned int" +"sendfile","sys/sendfile.h","CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0","ssize_t","int","int","off_t","size_t" +"sigaddset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *","int" +"sigdelset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *","int" +"sigemptyset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *" +"sigfillset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *" +"sigismember","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR const sigset_t *","int" +"snprintf","stdio.h","","int","FAR char *","size_t","const char *","..." +"sprintf","stdio.h","","int","FAR char *","const char *","..." +"sq_addafter","queue.h","","void","FAR sq_entry_t *","FAR sq_entry_t *","FAR sq_queue_t *" +"sq_addfirst","queue.h","","void","FAR sq_entry_t *","sq_queue_t *" +"sq_addlast","queue.h","","void","FAR sq_entry_t *","sq_queue_t *" +"sq_rem","queue.h","","void","FAR sq_entry_t *","sq_queue_t *" +"sq_remafter","queue.h","","FAR sq_entry_t","FAR sq_entry_t *","sq_queue_t *" +"sq_remfirst","queue.h","","FAR sq_entry_t","sq_queue_t *" +"sq_remlast","queue.h","","FAR sq_entry_t","sq_queue_t *" +"srand","stdlib.h","","void","unsigned int" +"sscanf","stdio.h","","int","const char *","const char *","..." +"strcasecmp","string.h","","int","FAR const char *","FAR const char *" +"strcasestr","string.h","","FAR char","FAR const char *","FAR const char *" +"strcat","string.h","","FAR char","FAR char *","FAR const char *" +"strchr","string.h","","FAR char","FAR const char *","int" +"strcmp","string.h","","int","FAR const char *","FAR const char *" +"strcpy","string.h","","FAR char","char *","FAR const char *" +"strcspn","string.h","","size_t","FAR const char *","FAR const char *" +"strdup","string.h","","FAR char","FAR const char *" +"strerror","string.h","","FAR const char","int" +"strftime","time.h","","size_t","char *","size_t","const char *","const struct tm *" +"strlen","string.h","","size_t","FAR const char *" +"strncasecmp","string.h","","int","FAR const char *","FAR const char *","size_t" +"strncat","string.h","","FAR char","FAR char *","FAR const char *","size_t" +"strncmp","string.h","","int","FAR const char *","FAR const char *","size_t" +"strncpy","string.h","","FAR char","char *","FAR const char *","size_t" +"strndup","string.h","","FAR char","FAR const char *","size_t" +"strnlen","string.h","","size_t","FAR const char *","size_t" +"strpbrk","string.h","","FAR char","FAR const char *","FAR const char *" +"strrchr","string.h","","FAR char","FAR const char *","int" +"strspn","string.h","","size_t","FAR const char *","FAR const char *" +"strstr","string.h","","FAR char","FAR const char *","FAR const char *" +"strtod","stdlib.h","","double_t","const char *str","char **endptr" +"strtok","string.h","","FAR char","FAR char *","FAR const char *" +"strtok_r","string.h","","FAR char","FAR char *","FAR const char *","FAR char **" +"strtol","string.h","","long","const char *","char **","int" +"strtoll","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long","const char *nptr","char **endptr","int base" +"strtoul","stdlib.h","","unsigned long","const char *","char **","int" +"strtoull","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","unsigned long long","const char *","char **","int" +"tcflush","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int" +"tcgetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","FAR struct termios *" +"tcsetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int","FAR const struct termios *" +"telldir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","off_t","FAR DIR *" +"time","time.h","","time_t","time_t *" +"ub16divub16","fixedmath.h","","ub16_t","ub16_t","ub16_t" +"ub16mulub16","fixedmath.h","","ub16_t","ub16_t","ub16_t" +"ub16sqr","fixedmath.h","","ub16_t","ub16_t" +"ungetc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","int","FAR FILE *" +"vdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE)","int","const char *","..." +"vfprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","const char *","va_list" +"vprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *","va_list" +"vsnprintf","stdio.h","","int","FAR char *","size_t","const char *","va_list" +"vsprintf","stdio.h","","int","FAR char *","const char *","va_list" +"vsscanf","stdio.h","","int","char *","const char *","va_list" diff --git a/nuttx/lib/lib_internal.h b/nuttx/lib/lib_internal.h new file mode 100644 index 0000000000..c3d9bfd18e --- /dev/null +++ b/nuttx/lib/lib_internal.h @@ -0,0 +1,199 @@ +/**************************************************************************** + * lib/lib_internal.h + * + * Copyright (C) 2007-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. + * + ****************************************************************************/ + +#ifndef __LIB_LIB_INTERNAL_H +#define __LIB_LIB_INTERNAL_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ +/* This configuration directory is used in environment variable processing + * when we need to reference the user's home directory. There are no user + * directories in NuttX so, by default, this always refers to the root + * directory. + */ + +#ifndef CONFIG_LIB_HOMEDIR +# define CONFIG_LIB_HOMEDIR "/" +#endif + +/* If C std I/O buffering is not supported, then we don't need its semaphore + * protection. + */ + +#if CONFIG_STDIO_BUFFER_SIZE <= 0 +# define lib_sem_initialize(s) +# define lib_take_semaphore(s) +# define lib_give_semaphore(s) +#endif + +/* The NuttX C library an be build in two modes: (1) as a standard, C-libary + * that can be used by normal, user-space applications, or (2) as a special, + * kernel-mode C-library only used within the OS. If NuttX is not being + * built as separated kernel- and user-space modules, then only the first + * mode is supported. + */ + +#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__) +# include +# define lib_malloc(s) kmalloc(s) +# define lib_zalloc(s) kzalloc(s) +# define lib_realloc(p,s) krealloc(p,s) +# define lib_free(p) kfree(p) +#else +# include +# define lib_malloc(s) malloc(s) +# define lib_zalloc(s) zalloc(s) +# define lib_realloc(p,s) realloc(p,s) +# define lib_free(p) free(p) +#endif + +#define LIB_BUFLEN_UNKNOWN INT_MAX + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/* Debug output is initially disabled */ + +#ifdef CONFIG_DEBUG_ENABLE +extern bool g_dbgenable; +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/* Defined in lib_streamsem.c */ + +#if CONFIG_NFILE_STREAMS > 0 +extern void stream_semtake(FAR struct streamlist *list); +extern void stream_semgive(FAR struct streamlist *list); +#endif + +/* Defined in lib_libnoflush.c */ + +#ifdef CONFIG_STDIO_LINEBUFFER +extern int lib_noflush(FAR struct lib_outstream_s *this); +#endif + +/* Defined in lib_libsprintf.c */ + +extern int lib_sprintf(FAR struct lib_outstream_s *obj, + const char *fmt, ...); + +/* Defined lib_libvsprintf.c */ + +extern int lib_vsprintf(FAR struct lib_outstream_s *obj, + FAR const char *src, va_list ap); + +/* Defined lib_rawprintf.c */ + +extern int lib_rawvprintf(const char *src, va_list ap); + +/* Defined lib_lowprintf.c */ + +extern int lib_lowvprintf(const char *src, va_list ap); + +/* Defined in lib_dtoa.c */ + +#ifdef CONFIG_LIBC_FLOATINGPOINT +extern char *__dtoa(double d, int mode, int ndigits, + int *decpt, int *sign, char **rve); +#endif + +/* Defined in lib_libwrite.c */ + +extern ssize_t lib_fwrite(FAR const void *ptr, size_t count, FAR FILE *stream); + +/* Defined in lib_libfread.c */ + +extern ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream); + +/* Defined in lib_libfflush.c */ + +extern ssize_t lib_fflush(FAR FILE *stream, bool bforce); + +/* Defined in lib_rdflush.c */ + +extern int lib_rdflush(FAR FILE *stream); + +/* Defined in lib_wrflush.c */ + +int lib_wrflush(FAR FILE *stream); + +/* Defined in lib_sem.c */ + +#if CONFIG_STDIO_BUFFER_SIZE > 0 +extern void lib_sem_initialize(FAR struct file_struct *stream); +extern void lib_take_semaphore(FAR struct file_struct *stream); +extern void lib_give_semaphore(FAR struct file_struct *stream); +#endif + +/* Defined in lib_libgetbase.c */ + +extern int lib_getbase(const char *nptr, const char **endptr); + +/* Defined in lib_skipspace.c */ + +extern void lib_skipspace(const char **pptr); + +/* Defined in lib_isbasedigit.c */ + +extern bool lib_isbasedigit(int ch, int base, int *value); + +/* Defined in lib_checkbase.c */ + +extern int lib_checkbase(int base, const char **pptr); + +#endif /* __LIB_LIB_INTERNAL_H */ diff --git a/nuttx/lib/libgen/Make.defs b/nuttx/lib/libgen/Make.defs new file mode 100644 index 0000000000..f126455124 --- /dev/null +++ b/nuttx/lib/libgen/Make.defs @@ -0,0 +1,43 @@ +############################################################################ +# lib/libgen/Make.defs +# +# 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. +# +############################################################################ + +# Add the libgen C files to the build + +CSRCS += lib_basename.c lib_dirname.c + +# Add the libgen directory to the build + +DEPPATH += --dep-path libgen +VPATH += :libgen diff --git a/nuttx/lib/libgen/lib_basename.c b/nuttx/lib/libgen/lib_basename.c new file mode 100644 index 0000000000..986c6b8520 --- /dev/null +++ b/nuttx/lib/libgen/lib_basename.c @@ -0,0 +1,131 @@ +/**************************************************************************** + * lib/libgen/lib_basename.c + * + * Copyright (C) 2007, 2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static char g_retchar[2]; + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: basename + * + * Description: + * basename() extracts the filename component from a null-terminated + * pathname string. In the usual case, basename() returns the component + * following the final '/'. Trailing '/' characters are not counted as + * part of the pathname. + * + * If path does not contain a slash, basename() returns a copy of path. + * If path is the string "/", then basename() returns the string "/". If + * path is a NULL pointer or points to an empty string, then basename() + * return the string ".". + * + * basename() may modify the contents of path, so copies should be passed. + * basename() may return pointers to statically allocated memory which may + * be overwritten by subsequent calls. + * + * Parameter: + * path The null-terminated string referring to the path to be decomposed + * + * Return: + * On success the filename component of the path is returned. + * + ****************************************************************************/ + +FAR char *basename(FAR char *path) +{ + char *p; + int len; + int ch; + + /* Handle some corner cases */ + + if (!path || *path == '\0') + { + ch = '.'; + goto out_retchar; + } + + /* Check for trailing slash characters */ + + len = strlen(path); + while (path[len-1] == '/') + { + /* Remove trailing '/' UNLESS this would make a zero length string */ + if (len > 1) + { + path[len-1] = '\0'; + len--; + } + else + { + ch = '/'; + goto out_retchar; + } + } + + /* Get the address of the last '/' which is not at the end of the path and, + * therefor, must be just before the beginning of the filename component. + */ + + p = strrchr(path, '/'); + if (p) + { + return p + 1; + } + + /* There is no '/' in the path */ + + return path; + +out_retchar: + g_retchar[0] = ch; + g_retchar[1] = '\0'; + return g_retchar; +} diff --git a/nuttx/lib/libgen/lib_dirname.c b/nuttx/lib/libgen/lib_dirname.c new file mode 100644 index 0000000000..248293a605 --- /dev/null +++ b/nuttx/lib/libgen/lib_dirname.c @@ -0,0 +1,144 @@ +/**************************************************************************** + * lib/libgen/lib_dirname.c + * + * Copyright (C) 2007, 2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static char g_retchar[2]; + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: dirname + * + * Description: + * dirname() extracts the directory component from a null-terminated + * pathname string. In the usual case, dirname() returns the string up + * to, but not including, the final '/'. Trailing '/' characters are not + * counted as part of the pathname. + * + * If path does not contain a slash, dirname() returns the string ".". If + * path is the string "/", then dirname() returns the string "/". If path + * is a NULL pointer or points to an empty string, then dirname() returns + * the string ".". + * + * dirname() may modify the contents of path, so copies should be passed. + * dirname() may return pointers to statically allocated memory which may + * be overwritten by subsequent calls. + * + * Parameter: + * path The null-terminated string referring to the path to be decomposed + * + * Return: + * On success the directory component of the path is returned. + * + ****************************************************************************/ + +FAR char *dirname(FAR char *path) +{ + char *p; + int len; + int ch; + + /* Handle some corner cases */ + + if (!path || *path == '\0') + { + ch = '.'; + goto out_retchar; + } + + /* Check for trailing slash characters */ + + len = strlen(path); + while (path[len-1] == '/') + { + /* Remove trailing '/' UNLESS this would make a zero length string */ + if (len > 1) + { + path[len-1] = '\0'; + len--; + } + else + { + ch = '/'; + goto out_retchar; + } + } + + /* Get the address of the last '/' which is not at the end of the path and, + * therefor, must be the end of the directory component. + */ + + p = strrchr(path, '/'); + if (p) + { + /* Handle the case where the only '/' in the string is the at the beginning + * of the path. + */ + + if (p == path) + { + ch = '/'; + goto out_retchar; + } + + /* No, the directory component is the substring before the '/'. */ + + *p = '\0'; + return path; + } + + /* There is no '/' in the path */ + + ch = '.'; + +out_retchar: + g_retchar[0] = ch; + g_retchar[1] = '\0'; + return g_retchar; +} diff --git a/nuttx/lib/math/Make.defs b/nuttx/lib/math/Make.defs new file mode 100644 index 0000000000..126cd2f471 --- /dev/null +++ b/nuttx/lib/math/Make.defs @@ -0,0 +1,43 @@ +############################################################################ +# lib/math/Make.defs +# +# 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. +# +############################################################################ + +# Add the math C files to the build + +CSRCS += lib_rint.c lib_fixedmath.c lib_b16sin.c lib_b16cos.c lib_b16atan2.c + +# Add the math directory to the build + +DEPPATH += --dep-path math +VPATH += :math diff --git a/nuttx/lib/math/lib_b16atan2.c b/nuttx/lib/math/lib_b16atan2.c new file mode 100644 index 0000000000..8792fa0879 --- /dev/null +++ b/nuttx/lib/math/lib_b16atan2.c @@ -0,0 +1,108 @@ +/**************************************************************************** + * lib/math/lib_b16atan2.c + * + * Copyright (C) 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define B16_C1 0x00000373 /* 0.013480470 */ +#define B16_C2 0x00000eb7 /* 0.057477314 */ +#define B16_C3 0x00001f0a /* 0.121239071 */ +#define B16_C4 0x00003215 /* 0.195635925 */ +#define B16_C5 0x0000553f /* 0.332994597 */ +#define B16_C6 0x00010000 /* 0.999995630 */ +#define B16_HALFPI 0x00019220 /* 1.570796327 */ +#define B16_PI 0x00032440 /* 3.141592654 */ + +#ifndef MAX +# define MAX(a,b) (a > b ? a : b) +#endif + +#ifndef MIN +# define MIN(a,b) (a < b ? a : b) +#endif + +#ifndef ABS +# define ABS(a) (a < 0 ? -a : a) +#endif + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: b16atan2 + * + * Description: + * atan2 calculates the arctangent of y/x. (Based on a algorithm I saw + * posted on the internet... now I have lost the link -- sorry). + * + ****************************************************************************/ + +b16_t b16atan2(b16_t y, b16_t x) +{ + b16_t t0; + b16_t t1; + b16_t t2; + b16_t t3; + + t2 = ABS(x); + t1 = ABS(y); + t0 = MAX(t2, t1); + t1 = MIN(t2, t1); + t2 = ub16inv(t0); + t2 = b16mulb16(t1, t2); + + t3 = b16mulb16(t2, t2); + t0 = - B16_C1; + t0 = b16mulb16(t0, t3) + B16_C2; + t0 = b16mulb16(t0, t3) - B16_C3; + t0 = b16mulb16(t0, t3) + B16_C4; + t0 = b16mulb16(t0, t3) - B16_C5; + t0 = b16mulb16(t0, t3) + B16_C6; + t2 = b16mulb16(t0, t2); + + t2 = (ABS(y) > ABS(x)) ? B16_HALFPI - t2 : t2; + t2 = (x < 0) ? B16_PI - t2 : t2; + t2 = (y < 0) ? -t2 : t2; + + return t2; +} diff --git a/nuttx/lib/math/lib_b16cos.c b/nuttx/lib/math/lib_b16cos.c new file mode 100644 index 0000000000..7547871f63 --- /dev/null +++ b/nuttx/lib/math/lib_b16cos.c @@ -0,0 +1,64 @@ +/**************************************************************************** + * lib/math/lib_b16cos.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: b16cos + ****************************************************************************/ + +b16_t b16cos(b16_t rad) +{ + /* Compute cosine: sin(rad + PI/2) = cos(rad) */ + + rad += b16HALFPI; + if (rad > b16PI) + { + rad -= b16TWOPI; + } + return b16sin(rad); +} diff --git a/nuttx/lib/math/lib_b16sin.c b/nuttx/lib/math/lib_b16sin.c new file mode 100644 index 0000000000..1eee179934 --- /dev/null +++ b/nuttx/lib/math/lib_b16sin.c @@ -0,0 +1,110 @@ +/**************************************************************************** + * lib/math/lib_b16sin.c + * + * Copyright (C) 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define b16_P225 0x0000399a +#define b16_P405284735 0x000067c1 +#define b16_1P27323954 0x000145f3 + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: b16sin + * Ref: http://lab.polygonal.de/2007/07/18/fast-and-accurate-sinecosine-approximation/ + ****************************************************************************/ + +b16_t b16sin(b16_t rad) +{ + b16_t tmp1; + b16_t tmp2; + b16_t tmp3; + + /* Force angle into the good range */ + + if (rad < -b16PI) + { + rad += b16TWOPI; + } + else if (rad > b16PI) + { + rad -= b16TWOPI; + } + + /* tmp1 = 1.27323954 * rad + * tmp2 = .405284735 * rad * rad + */ + + + tmp1 = b16mulb16(b16_1P27323954, rad); + tmp2 = b16mulb16(b16_P405284735, b16sqr(rad)); + + if (rad < 0) + { + /* tmp3 = 1.27323954 * rad + .405284735 * rad * rad */ + + tmp3 = tmp1 + tmp2; + } + else + { + /* tmp3 = 1.27323954 * rad - 0.405284735 * rad * rad */ + + tmp3 = tmp1 - tmp2; + } + + /* tmp1 = tmp3*tmp3 */ + + tmp1 = b16sqr(tmp3); + if (tmp3 < 0) + { + /* tmp1 = tmp3 * -tmp3 */ + + tmp1 = -tmp1; + } + + /* Return sin = .225 * (tmp3 * (+/-tmp3) - tmp3) + tmp3 */ + + return b16mulb16(b16_P225, (tmp1 - tmp3)) + tmp3; +} diff --git a/nuttx/lib/math/lib_fixedmath.c b/nuttx/lib/math/lib_fixedmath.c new file mode 100644 index 0000000000..c1a710e739 --- /dev/null +++ b/nuttx/lib/math/lib_fixedmath.c @@ -0,0 +1,272 @@ +/**************************************************************************** + * lib/math/lib_fixedmath.c + * + * Copyright (C) 2008-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#ifndef CONFIG_HAVE_LONG_LONG + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Name: fixsign + ****************************************************************************/ + +static void fixsign(b16_t *parg1, b16_t *parg2, bool *pnegate) +{ + bool negate = false; + b16_t arg; + + arg = *parg1; + if (arg < 0) + { + *parg1 = -arg; + negate = true; + } + + arg = *parg2; + if (arg < 0) + { + *parg2 = -arg; + negate ^= true; + } + + *pnegate = negate; +} + +/**************************************************************************** + * Name: adjustsign + ****************************************************************************/ + +static b16_t adjustsign(b16_t result, bool negate) +{ + /* If the product is negative, then we overflowed */ + + if (result < 0) + { + if (result) + { + return b16MIN; + } + else + { + return b16MAX; + } + } + + /* correct the sign of the result */ + + if (negate) + { + return -result; + } + return result; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: b16mulb16 + ****************************************************************************/ + +b16_t b16mulb16(b16_t m1, b16_t m2) +{ + bool negate; + b16_t product; + + fixsign(&m1, &m2, &negate); + product = (b16_t)ub16mulub16((ub16_t)m1, (ub16_t)m2); + return adjustsign(product, negate); +} + +/**************************************************************************** + * Name: ub16mulub16 + **************************************************************************/ + +ub16_t ub16mulub16(ub16_t m1, ub16_t m2) +{ + /* Let: + * + * m1 = m1i*2**16 + m1f (b16) + * m2 = m2i*2**16 + m2f (b16) + * + * Then: + * + * m1*m2 = (m1i*m2i)*2**32 + (m1i*m2f + m2i*m1f)*2**16 + m1f*m2f (b32) + * = (m1i*m2i)*2**16 + (m1i*m2f + m2i*m1f) + m1f*m2f*2**-16 (b16) + * = a*2**16 + b + c*2**-16 + */ + + uint32_t m1i = ((uint32_t)m1 >> 16); + uint32_t m2i = ((uint32_t)m1 >> 16); + uint32_t m1f = ((uint32_t)m1 & 0x0000ffff); + uint32_t m2f = ((uint32_t)m2 & 0x0000ffff); + + return (m1i*m2i << 16) + m1i*m2f + m2i*m1f + (((m1f*m2f) + b16HALF) >> 16); +} + +/**************************************************************************** + * Name: b16sqr + **************************************************************************/ + +b16_t b16sqr(b16_t a) +{ + b16_t sq; + + /* The result is always positive. Just take the absolute value */ + + if (a < 0) + { + a = -a; + } + + /* Overflow occurred if the result is negative */ + + sq = (b16_t)ub16sqr(a); + if (sq < 0) + { + sq = b16MAX; + } + return sq; +} + +/**************************************************************************** + * Name: b16divb16 + **************************************************************************/ + +ub16_t ub16sqr(ub16_t a) +{ + /* Let: + * + * m = mi*2**16 + mf (b16) + * + * Then: + * + * m*m = (mi*mi)*2**32 + 2*(m1*m2)*2**16 + mf*mf (b32) + * = (mi*mi)*2**16 + 2*(mi*mf) + mf*mf*2**-16 (b16) + */ + + uint32_t mi = ((uint32_t)a >> 16); + uint32_t mf = ((uint32_t)a & 0x0000ffff); + + return (mi*mi << 16) + (mi*mf << 1) + ((mf*mf + b16HALF) >> 16); +} + +/**************************************************************************** + * Name: b16divb16 + **************************************************************************/ + +b16_t b16divb16(b16_t num, b16_t denom) +{ + bool negate; + b16_t quotient; + + fixsign(&num, &denom, &negate); + quotient = (b16_t)ub16divub16((ub16_t)num, (ub16_t)denom); + return adjustsign(quotient, negate); +} + +/**************************************************************************** + * Name: ub16divub16 + **************************************************************************/ + +ub16_t ub16divub16(ub16_t num, ub16_t denom) +{ + uint32_t term1; + uint32_t numf; + uint32_t product; + + /* Let: + * + * num = numi*2**16 + numf (b16) + * den = deni*2**16 + denf (b16) + * + * Then: + * + * num/den = numi*2**16 / den + numf / den (b0) + * = numi*2**32 / den + numf*2**16 /den (b16) + */ + + /* Check for overflow in the first part of the quotient */ + + term1 = ((uint32_t)num & 0xffff0000) / denom; + if (term1 >= 0x00010000) + { + return ub16MAX; /* Will overflow */ + } + + /* Finish the division */ + + numf = num - term1 * denom; + term1 <<= 16; + product = term1 + (numf + (denom >> 1)) / denom; + + /* Check for overflow */ + + if (product < term1) + { + return ub16MAX; /* Overflowed */ + } + return product; +} + +#endif diff --git a/nuttx/lib/math/lib_rint.c b/nuttx/lib/math/lib_rint.c new file mode 100644 index 0000000000..bd861ecedc --- /dev/null +++ b/nuttx/lib/math/lib_rint.c @@ -0,0 +1,135 @@ +/************************************************************ + * lib/math/lib_rint.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include +#include +#include + +/************************************************************ + * Definitions + ************************************************************/ + +/************************************************************ + * Private Type Declarations + ************************************************************/ + +/************************************************************ + * Private Function Prototypes + ************************************************************/ + +/********************************************************** + * Global Constant Data + **********************************************************/ + +/************************************************************ + * Global Variables + ************************************************************/ + +/********************************************************** + * Private Constant Data + **********************************************************/ + +/************************************************************ + * Private Variables + ************************************************************/ + +double_t rint(double_t x) +{ + double_t ret; + + /* If the current rounding mode rounds toward negative + * infinity, rint() is identical to floor(). If the current + * rounding mode rounds toward positive infinity, rint() is + * identical to ceil(). + */ + +#if defined(CONFIG_FP_ROUND_POSITIVE) && CONFIG_FP_ROUNDING_POSITIVE != 0 + + ret = ceil(x); + +#elif defined(CONFIG_FP_ROUND_NEGATIVE) && CONFIG_FP_ROUNDING_NEGATIVE != 0 + + ret = floor(x); + +#else + + /* In the default rounding mode (round to nearest), rint(x) is the + * integer nearest x with the additional stipulation that if + * |rint(x)-x|=1/2, then rint(x) is even. + */ + + long dwinteger = (long)x; + double_t fremainder = x - (double_t)dwinteger; + + if (x < 0.0) + { + /* fremainder should be in range 0 .. -1 */ + + if (fremainder == -0.5) + { + dwinteger = ((dwinteger+1)&~1); + } + else if (fremainder < -0.5) + { + dwinteger--; + } + } + else + { + /* fremainder should be in range 0 .. 1 */ + + if (fremainder == 0.5) + { + dwinteger = ((dwinteger+1)&~1); + } + else if (fremainder > 0.5) + { + dwinteger++; + } + } + + ret = (double_t)dwinteger; +#endif + + return ret; +} diff --git a/nuttx/lib/misc/Make.defs b/nuttx/lib/misc/Make.defs new file mode 100644 index 0000000000..c12533f754 --- /dev/null +++ b/nuttx/lib/misc/Make.defs @@ -0,0 +1,69 @@ +############################################################################ +# lib/misc/Make.defs +# +# 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. +# +############################################################################ + +# Add the internal C files to the build + +CSRCS += lib_init.c lib_filesem.c + +# Add C files that depend on file OR socket descriptors + +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) + +CSRCS += lib_sendfile.c +ifneq ($(CONFIG_NFILE_STREAMS),0) +CSRCS += lib_streamsem.c +endif + +else +ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0) + +CSRCS += lib_sendfile.c +ifneq ($(CONFIG_NFILE_STREAMS),0) +CSRCS += lib_streamsem.c +endif + +endif +endif + +# Add the miscellaneous C files to the build + +CSRCS += lib_match.c +CSRCS += lib_crc32.c +CSRCS += lib_dbg.c lib_dumpbuffer.c + +# Add the misc directory to the build + +DEPPATH += --dep-path misc +VPATH += :misc diff --git a/nuttx/lib/misc/lib_crc32.c b/nuttx/lib/misc/lib_crc32.c new file mode 100644 index 0000000000..f851598e01 --- /dev/null +++ b/nuttx/lib/misc/lib_crc32.c @@ -0,0 +1,123 @@ +/************************************************************************************************ + * lib/misc/lib_crc32.c + * + * This file is a part of NuttX: + * + * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. + * + * The logic in this file was developed by Gary S. Brown: + * + * COPYRIGHT (C) 1986 Gary S. Brown. You may use this program, or code or tables + * extracted from it, as desired without restriction. + * + * First, the polynomial itself and its table of feedback terms. The polynomial is: + * + * X^32+X^26+X^23+X^22+X^16+X^12+X^11+X^10+X^8+X^7+X^5+X^4+X^2+X^1+X^0 + * + * Note that we take it "backwards" and put the highest-order term in the lowest-order bit. + * The X^32 term is "implied"; the LSB is the X^31 term, etc. The X^0 term (usually shown + * as "+1") results in the MSB being 1 + * + * Note that the usual hardware shift register implementation, which is what we're using + * (we're merely optimizing it by doing eight-bit chunks at a time) shifts bits into the + * lowest-order term. In our implementation, that means shifting towards the right. Why + * do we do it this way? Because the calculated CRC must be transmitted in order from + * highest-order term to lowest-order term. UARTs transmit characters in order from LSB + * to MSB. By storing the CRC this way we hand it to the UART in the order low-byte to + * high-byte; the UART sends each low-bit to hight-bit; and the result is transmission bit + * by bit from highest- to lowest-order term without requiring any bit shuffling on our + * part. Reception works similarly + * + * The feedback terms table consists of 256, 32-bit entries. Notes + * + * - The table can be generated at runtime if desired; code to do so is shown later. It + * might not be obvious, but the feedback terms simply represent the results of eight + * shift/xor operations for all combinations of data and CRC register values + * + * - The values must be right-shifted by eight bits by the updcrc logic; the shift must + * be u_(bring in zeroes). On some hardware you could probably optimize the shift in + * assembler by using byte-swap instructions polynomial $edb88320 + ************************************************************************************************/ + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include +#include + +/************************************************************************************************ + * Private Data + ************************************************************************************************/ + +static const uint32_t crc32_tab[] = +{ + 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3, + 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91, + 0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7, + 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5, + 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b, + 0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59, + 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f, + 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d, + 0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433, + 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01, + 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457, + 0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65, + 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb, + 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9, + 0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f, + 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad, + 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683, + 0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1, + 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7, + 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5, + 0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b, + 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79, + 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f, + 0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d, + 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713, + 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21, + 0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777, + 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45, + 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db, + 0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9, + 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf, + 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d +}; + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ +/************************************************************************************************ + * Name: crc32part + * + * Description: + * Continue CRC calculation on a part of the buffer. + * + ************************************************************************************************/ + +uint32_t crc32part(FAR const uint8_t *src, size_t len, uint32_t crc32val) +{ + size_t i; + + for (i = 0; i < len; i++) + { + crc32val = crc32_tab[(crc32val ^ src[i]) & 0xff] ^ (crc32val >> 8); + } + return crc32val; +} + +/************************************************************************************************ + * Name: crc32 + * + * Description: + * Return a 32-bit CRC of the contents of the 'src' buffer, length 'len' + * + ************************************************************************************************/ + +uint32_t crc32(FAR const uint8_t *src, size_t len) +{ + return crc32part(src, len, 0); +} diff --git a/nuttx/lib/misc/lib_dbg.c b/nuttx/lib/misc/lib_dbg.c new file mode 100644 index 0000000000..aacdaa30a9 --- /dev/null +++ b/nuttx/lib/misc/lib_dbg.c @@ -0,0 +1,165 @@ +/**************************************************************************** + * lib/misc/lib_dbg.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/* Debug output is initially disabled */ + +#ifdef CONFIG_DEBUG_ENABLE +bool g_dbgenable; +#endif + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: dbg_enable + * + * Description: + * Enable or disable debug output. + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_ENABLE +void dbg_enable(bool enable) +{ + g_dbgenable = enable; +} +#endif + +/**************************************************************************** + * Name: dbg, lldbg, vdbg + * + * Description: + * If the cross-compiler's pre-processor does not support variable + * length arguments, then these additional APIs will be built. + * + ****************************************************************************/ + +#ifndef CONFIG_CPP_HAVE_VARARGS +#ifdef CONFIG_DEBUG +int dbg(const char *format, ...) +{ + va_list ap; + int ret; + +#ifdef CONFIG_DEBUG_ENABLE + ret = 0; + if (g_dbgenable) +#endif + { + va_start(ap, format); + ret = lib_rawvprintf(format, ap); + va_end(ap); + } + + return ret; +} + +#ifdef CONFIG_ARCH_LOWPUTC +int lldbg(const char *format, ...) +{ + va_list ap; + int ret; + +#ifdef CONFIG_DEBUG_ENABLE + ret = 0; + if (g_dbgenable) +#endif + { + va_start(ap, format); + ret = lib_lowvprintf(format, ap); + va_end(ap); + } + + return ret; +} +#endif + +#ifdef CONFIG_DEBUG_VERBOSE +int vdbg(const char *format, ...) +{ + va_list ap; + int ret; + +#ifdef CONFIG_DEBUG_ENABLE + ret = 0; + if (g_dbgenable) +#endif + { + va_start(ap, format); + ret = lib_rawvprintf(format, ap); + va_end(ap); + } + + return ret; +} + +#ifdef CONFIG_ARCH_LOWPUTC +int llvdbg(const char *format, ...) +{ + va_list ap; + int ret; + +#ifdef CONFIG_DEBUG_ENABLE + ret = 0; + if (g_dbgenable) +#endif + { + va_start(ap, format); + ret = lib_lowvprintf(format, ap); + va_end(ap); + } + + return ret; +} +#endif /* CONFIG_ARCH_LOWPUTC */ +#endif /* CONFIG_DEBUG_VERBOSE */ +#endif /* CONFIG_DEBUG */ +#endif /* CONFIG_CPP_HAVE_VARARGS */ diff --git a/nuttx/lib/misc/lib_dumpbuffer.c b/nuttx/lib/misc/lib_dumpbuffer.c new file mode 100644 index 0000000000..155468ca12 --- /dev/null +++ b/nuttx/lib/misc/lib_dumpbuffer.c @@ -0,0 +1,129 @@ +/**************************************************************************** + * lib/misc/lib_dumpbuffer.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include + +/**************************************************************************** + * Pre-processor definitions + ****************************************************************************/ + +/* Select the lowest level debug interface available */ + +#ifdef CONFIG_CPP_HAVE_VARARGS +# ifdef CONFIG_ARCH_LOWPUTC +# define message(format, arg...) lib_lowprintf(format, ##arg) +# else +# define message(format, arg...) lib_rawprintf(format, ##arg) +# endif +#else +# ifdef CONFIG_ARCH_LOWPUTC +# define message lib_lowprintf +# else +# define message lib_rawprintf +# endif +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_dumpbuffer + * + * Description: + * Do a pretty buffer dump + * + ****************************************************************************/ + +void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer, unsigned int buflen) +{ + int i, j, k; + + message("%s (%p):\n", msg, buffer); + for (i = 0; i < buflen; i += 32) + { + message("%04x: ", i); + for (j = 0; j < 32; j++) + { + k = i + j; + + if (j == 16) + { + message(" "); + } + + if (k < buflen) + { + message("%02x", buffer[k]); + } + else + { + message(" "); + } + } + + message(" "); + for (j = 0; j < 32; j++) + { + k = i + j; + + if (j == 16) + { + message(" "); + } + + if (k < buflen) + { + if (buffer[k] >= 0x20 && buffer[k] < 0x7f) + { + message("%c", buffer[k]); + } + else + { + message("."); + } + } + } + message("\n"); + } +} diff --git a/nuttx/lib/misc/lib_filesem.c b/nuttx/lib/misc/lib_filesem.c new file mode 100644 index 0000000000..1d1f25c2fd --- /dev/null +++ b/nuttx/lib/misc/lib_filesem.c @@ -0,0 +1,145 @@ +/************************************************************************ + * lib/misc/lib_filesem.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +#if CONFIG_STDIO_BUFFER_SIZE > 0 + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +/************************************************************************ + * Private Data + ************************************************************************/ + +/************************************************************************ + * Global Functions + ************************************************************************/ + +/************************************************************************ + * lib_sem_initialize + ************************************************************************/ + +void lib_sem_initialize(FAR struct file_struct *stream) +{ + /* Initialize the LIB semaphore to one (to support one-at- + * a-time access to private data sets. + */ + + (void)sem_init(&stream->fs_sem, 0, 1); + + stream->fs_holder = -1; + stream->fs_counts = 0; +} + +/************************************************************************ + * lib_take_semaphore + ************************************************************************/ + +void lib_take_semaphore(FAR struct file_struct *stream) +{ + pid_t my_pid = getpid(); + + /* Do I already have the semaphore? */ + + if (stream->fs_holder == my_pid) + { + /* Yes, just increment the number of references that I have */ + + stream->fs_counts++; + } + else + { + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&stream->fs_sem) != 0) + { + /* The only case that an error should occr here is if + * the wait was awakened by a signal. + */ + + ASSERT(get_errno() == EINTR); + } + + /* We have it. Claim the stak and return */ + + stream->fs_holder = my_pid; + stream->fs_counts = 1; + } +} + +/************************************************************************ + * lib_give_semaphore + ************************************************************************/ + +void lib_give_semaphore(FAR struct file_struct *stream) +{ + pid_t my_pid = getpid(); + + /* I better be holding at least one reference to the semaphore */ + + ASSERT(stream->fs_holder == my_pid); + + /* Do I hold multiple references to the semphore */ + + if (stream->fs_counts > 1) + { + /* Yes, just release one count and return */ + + stream->fs_counts--; + } + else + { + /* Nope, this is the last reference I have */ + + stream->fs_holder = -1; + stream->fs_counts = 0; + ASSERT(sem_post(&stream->fs_sem) == 0); + } +} +#endif /* CONFIG_STDIO_BUFFER_SIZE */ diff --git a/nuttx/lib/misc/lib_init.c b/nuttx/lib/misc/lib_init.c new file mode 100644 index 0000000000..3403a837b9 --- /dev/null +++ b/nuttx/lib/misc/lib_init.c @@ -0,0 +1,207 @@ +/************************************************************ + * lib/misc/lib_init.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +#include +#include +#include + +#include +#include +#include + +#include "lib_internal.h" + +/************************************************************ + * Definitions + ************************************************************/ + +/************************************************************ + * Private Variables + ************************************************************/ + +/************************************************************ + * Private Functions + ************************************************************/ + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * lib_initialize + ************************************************************/ + +/* General library initialization hook */ + +void weak_const_function lib_initialize(void) +{ +} + +#if CONFIG_NFILE_STREAMS > 0 +/* The following function is called when a new TCB is allocated. It + * creates the streamlist instance that is stored in the TCB. + */ + +FAR struct streamlist *lib_alloclist(void) +{ + FAR struct streamlist *list; + list = (FAR struct streamlist*)lib_zalloc(sizeof(struct streamlist)); + if (list) + { + int i; + + /* Start with a reference count of one */ + + list->sl_crefs = 1; + + /* Initialize the list access mutex */ + + (void)sem_init(&list->sl_sem, 0, 1); + + /* Initialize each FILE structure */ + + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + { + /* Clear the IOB */ + + memset(&list->sl_streams[i], 0, sizeof(FILE)); + + /* Indicate not opened */ + + list->sl_streams[i].fs_filedes = -1; + + /* Initialize the stream semaphore to one to support one-at- + * a-time access to private data sets. + */ + + lib_sem_initialize(&list->sl_streams[i]); + } + } + return list; + +} + +/* This function is called when a TCB is closed (such as with + * pthread_create(). It increases the reference count on the stream + * list. + */ + +void lib_addreflist(FAR struct streamlist *list) +{ + if (list) + { + /* Increment the reference count on the list. + * NOTE: that we disable interrupts to do this + * (vs. taking the list semaphore). We do this + * because file cleanup operations often must be + * done from the IDLE task which cannot wait + * on semaphores. + */ + + register irqstate_t flags = irqsave(); + list->sl_crefs++; + irqrestore(flags); + } +} + +/* this function is called when a TCB is destroyed. Note that is + * does not close the file by release this inode. This happens + * separately when the file descriptor list is freed. + */ + +void lib_releaselist(FAR struct streamlist *list) +{ + int crefs; + if (list) + { + /* Decrement the reference count on the list. + * NOTE: that we disable interrupts to do this + * (vs. taking the list semaphore). We do this + * because file cleanup operations often must be + * done from the IDLE task which cannot wait + * on semaphores. + */ + + register irqstate_t flags = irqsave(); + crefs = --(list->sl_crefs); + irqrestore(flags); + + /* If the count decrements to zero, then there is no reference + * to the structure and it should be deallocated. Since there + * are references, it would be an error if any task still held + * a reference to the list's semaphore. + */ + + if (crefs <= 0) + { +#if CONFIG_STDIO_BUFFER_SIZE > 0 + int i; +#endif + /* Destroy the semaphore and release the filelist */ + + (void)sem_destroy(&list->sl_sem); + + /* Release each stream in the list */ + +#if CONFIG_STDIO_BUFFER_SIZE > 0 + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + { + /* Destroy the semaphore that protects the IO buffer */ + + (void)sem_destroy(&list->sl_streams[i].fs_sem); + + /* Release the IO buffer */ + if (list->sl_streams[i].fs_bufstart) + { + sched_free(list->sl_streams[i].fs_bufstart); + } + } +#endif + /* Finally, release the list itself */ + + sched_free(list); + } + } +} + +#endif /* CONFIG_NFILE_STREAMS */ + + diff --git a/nuttx/lib/misc/lib_match.c b/nuttx/lib/misc/lib_match.c new file mode 100644 index 0000000000..18e0632ec6 --- /dev/null +++ b/nuttx/lib/misc/lib_match.c @@ -0,0 +1,148 @@ +/**************************************************************************** + * lib/misc/lib_match.c - simple shell-style filename matcher + * + * Simple shell-style filename pattern matcher written by Jef Poskanzer + * This pattern matcher only handles '?', '*' and '**', and multiple + * patterns separated by '|'. + * + * Copyright © 1995,2000 by Jef Poskanzer . + * All rights reserved. + * + * 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. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: match_one + * + * Description: + * Does all of the work for one '|' delimited pattern + * + * Returned Value: + * Returns 1 (match) or 0 (no-match). + * + ****************************************************************************/ + +static int match_one(const char *pattern, int patlen, const char *string) +{ + const char *p; + int pl; + int i; + + for (p = pattern; p - pattern < patlen; p++, string++) + { + if (*p == '?' && *string != '\0') + { + continue; + } + + if (*p == '*') + { + p++; + if (*p == '*') + { + /* Double-wildcard matches anything. */ + + p++; + i = strlen(string); + } + else + { + /* Single-wildcard matches anything but slash. */ + + i = strcspn(string, "/"); + } + + pl = patlen - (p - pattern); + for (; i >= 0; i--) + { + if (match_one(p, pl, &(string[i]))) + { + return 1; + } + } + return 0; + } + + if (*p != *string) + { + return 0; + } + } + + if (*string == '\0') + { + return 1; + } + return 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: match + * + * Description: + * Simple shell-style filename pattern matcher written by Jef Poskanzer + * This pattern matcher only handles '?', '*' and '**', and multiple + * patterns separated by '|'. + * + * Returned Value: + * Returns 1 (match) or 0 (no-match). + * + ****************************************************************************/ + +int match(const char *pattern, const char *string) +{ + const char *or; + + for (;;) + { + or = strchr(pattern, '|'); + if (or == (char *)0) + { + return match_one(pattern, strlen(pattern), string); + } + + if (match_one(pattern, or - pattern, string)) + { + return 1; + } + + pattern = or + 1; + } +} + diff --git a/nuttx/lib/misc/lib_sendfile.c b/nuttx/lib/misc/lib_sendfile.c new file mode 100644 index 0000000000..a82eb325e7 --- /dev/null +++ b/nuttx/lib/misc/lib_sendfile.c @@ -0,0 +1,297 @@ +/************************************************************************ + * lib/misc/lib_streamsem.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0 + +/************************************************************************ + * Private types + ************************************************************************/ + +/************************************************************************ + * Private Variables + ************************************************************************/ + +/************************************************************************ + * Public Variables + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: sendfile + * + * Description: + * sendfile() copies data between one file descriptor and another. + * sendfile() basically just wraps a sequence of reads() and writes() + * to perform a copy. It serves a purpose in systems where there is + * a penalty for copies to between user and kernal space, but really + * nothing in NuttX but provide some Linux compatible (and adding + * another 'almost standard' interface). + * + * NOTE: This interface is *not* specified in POSIX.1-2001, or other + * standards. The implementation here is very similar to the Linux + * sendfile interface. Other UNIX systems implement sendfile() with + * different semantics and prototypes. sendfile() should not be used + * in portable programs. + * + * Input Parmeters: + * infd - A file (or socket) descriptor opened for reading + * outfd - A descriptor opened for writing. + * offset - If 'offset' is not NULL, then it points to a variable + * holding the file offset from which sendfile() will start + * reading data from 'infd'. When sendfile() returns, this + * variable will be set to the offset of the byte following + * the last byte that was read. If 'offset' is not NULL, + * then sendfile() does not modify the current file offset of + * 'infd'; otherwise the current file offset is adjusted to + * reflect the number of bytes read from 'infd.' + * + * If 'offset' is NULL, then data will be read from 'infd' + * starting at the current file offset, and the file offset + * will be updated by the call. + * count - The number of bytes to copy between the file descriptors. + * + * Returned Value: + * If the transfer was successful, the number of bytes written to outfd is + * returned. On error, -1 is returned, and errno is set appropriately. + * There error values are those returned by read() or write() plus: + * + * EINVAL - Bad input parameters. + * ENOMEM - Could not allocated an I/O buffer + * + ************************************************************************/ + +ssize_t sendfile(int outfd, int infd, off_t *offset, size_t count) +{ + FAR uint8_t *iobuffer; + FAR uint8_t *wrbuffer; + off_t startpos = 0; + ssize_t nbytesread; + ssize_t nbyteswritten; + size_t ntransferred; + bool endxfr; + + /* Get the current file position. */ + + if (offset) + { + /* Use lseek to get the current file position */ + + startpos = lseek(infd, 0, SEEK_CUR); + if (startpos == (off_t)-1) + { + return ERROR; + } + + /* Use lseek again to set the new file position */ + + if (lseek(infd, *offset, SEEK_SET) == (off_t)-1) + { + return ERROR; + } + } + + /* Allocate an I/O buffer */ + + iobuffer = (FAR void *)malloc(CONFIG_LIB_SENDFILE_BUFSIZE); + if (!iobuffer) + { + set_errno(ENOMEM); + return ERROR; + } + + /* Now transfer 'count' bytes from the infd to the outfd */ + + for (ntransferred = 0, endxfr = false; ntransferred < count && !endxfr; ) + { + /* Loop until the read side of the transfer comes to some conclusion */ + + do + { + /* Read a buffer of data from the infd */ + + nbytesread = read(infd, iobuffer, CONFIG_LIB_SENDFILE_BUFSIZE); + + /* Check for end of file */ + + if (nbytesread == 0) + { + /* End of file. Break out and return current number of bytes + * transferred. + */ + + endxfr = true; + break; + } + + /* Check for a read ERROR. EINTR is a special case. This function + * should break out and return an error if EINTR is returned and + * no data has been transferred. But what should it do if some + * data has been transferred? I suppose just continue? + */ + + else if (nbytesread < 0) + { + /* EINTR is not an error (but will still stop the copy) */ + +#ifndef CONFIG_DISABLE_SIGNALS + if (errno != EINTR || ntransferred == 0) +#endif + { + /* Read error. Break out and return the error condition. */ + + ntransferred = ERROR; + endxfr = true; + break; + } + } + } + while (nbytesread < 0); + + /* Was anything read? */ + + if (!endxfr) + { + /* Yes.. Loop until the read side of the transfer comes to some + * conclusion. + */ + + wrbuffer = iobuffer; + do + { + /* Write the buffer of data to the outfd */ + + nbyteswritten = write(outfd, wrbuffer, nbytesread); + + /* Check for a complete (or parial) write. write() should not + * return zero. + */ + + if (nbyteswritten >= 0) + { + /* Advance the buffer pointer and decrement the number of bytes + * remaining in the iobuffer. Typically, nbytesread will now + * be zero. + */ + + wrbuffer += nbyteswritten; + nbytesread -= nbyteswritten; + + /* Increment the total number of bytes successfully transferred. */ + + ntransferred += nbyteswritten; + } + + /* Otherwise an error occurred */ + + else + { + /* Check for a read ERROR. EINTR is a special case. This + * function should break out and return an error if EINTR + * is returned and no data has been transferred. But what + * should it do if some data has been transferred? I + * suppose just continue? + */ + +#ifndef CONFIG_DISABLE_SIGNALS + if (errno != EINTR || ntransferred == 0) +#endif + { + /* Write error. Break out and return the error condition */ + + ntransferred = ERROR; + endxfr = true; + break; + } + } + } + while (nbytesread > 0); + } + } + + /* Release the I/O buffer */ + + free(iobuffer); + + /* Return the current file position */ + + if (offset) + { + /* Use lseek to get the current file position */ + + off_t curpos = lseek(infd, 0, SEEK_CUR); + if (curpos == (off_t)-1) + { + return ERROR; + } + + /* Return the current file position */ + + *offset = curpos; + + /* Use lseek again to restore the original file position */ + + if (lseek(infd, startpos, SEEK_SET) == (off_t)-1) + { + return ERROR; + } + } + + /* Finally return the number of bytes actually transferred (or ERROR + * if any failure occurred). + */ + + return ntransferred; +} + +#endif /* CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0 */ diff --git a/nuttx/lib/misc/lib_streamsem.c b/nuttx/lib/misc/lib_streamsem.c new file mode 100644 index 0000000000..fdf494e751 --- /dev/null +++ b/nuttx/lib/misc/lib_streamsem.c @@ -0,0 +1,90 @@ +/************************************************************************ + * lib/misc/lib_streamsem.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +/************************************************************************ + * Private types + ************************************************************************/ + +/************************************************************************ + * Private Variables + ************************************************************************/ + +/************************************************************************ + * Public Variables + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +void stream_semtake(FAR struct streamlist *list) +{ + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&list->sl_sem) != 0) + { + /* The only case that an error should occr here is if + * the wait was awakened by a signal. + */ + + ASSERT(get_errno() == EINTR); + } +} + +void stream_semgive(FAR struct streamlist *list) +{ + sem_post(&list->sl_sem); +} + + diff --git a/nuttx/lib/mqueue/Make.defs b/nuttx/lib/mqueue/Make.defs new file mode 100644 index 0000000000..40dc6c13e6 --- /dev/null +++ b/nuttx/lib/mqueue/Make.defs @@ -0,0 +1,48 @@ +############################################################################ +# lib/mqueue/Make.defs +# +# 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. +# +############################################################################ + +ifneq ($(CONFIG_DISABLE_MQUEUE),y) + +# Add the mqueue C files to the build + +CSRCS += mq_setattr.c mq_getattr.c + +# Add the mqueue directory to the build + +DEPPATH += --dep-path mqueue +VPATH += :mqueue + +endif + diff --git a/nuttx/lib/mqueue/mq_getattr.c b/nuttx/lib/mqueue/mq_getattr.c new file mode 100644 index 0000000000..9c9f47fdce --- /dev/null +++ b/nuttx/lib/mqueue/mq_getattr.c @@ -0,0 +1,104 @@ +/************************************************************************ + * lib/mqueue/mq_getattr.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include +#include + +/************************************************************************ + * Definitions + ************************************************************************/ + +/************************************************************************ + * Private Type Declarations + ************************************************************************/ + +/************************************************************************ + * Global Variables + ************************************************************************/ + +/************************************************************************ + * Private Variables + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Function: mq_getattr + * + * Description: + * This functions gets status information and attributes + * associated with the specified message queue. + * + * Parameters: + * mqdes - Message queue descriptor + * mq_stat - Buffer in which to return attributes + * + * Return Value: + * 0 (OK) if attributes provided, -1 (ERROR) otherwise. + * + * Assumptions: + * + ************************************************************************/ + +int mq_getattr(mqd_t mqdes, struct mq_attr *mq_stat) +{ + int ret = ERROR; + + if (mqdes && mq_stat) + { + /* Return the attributes */ + + mq_stat->mq_maxmsg = mqdes->msgq->maxmsgs; + mq_stat->mq_msgsize = mqdes->msgq->maxmsgsize; + mq_stat->mq_flags = mqdes->oflags; + mq_stat->mq_curmsgs = mqdes->msgq->nmsgs; + + ret = OK; + } + + return ret; +} diff --git a/nuttx/lib/mqueue/mq_setattr.c b/nuttx/lib/mqueue/mq_setattr.c new file mode 100644 index 0000000000..1276d64e8a --- /dev/null +++ b/nuttx/lib/mqueue/mq_setattr.c @@ -0,0 +1,118 @@ +/************************************************************************ + * lib/mqueue/mq_setattr.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include /* O_NONBLOCK */ +#include + +#include + +/************************************************************************ + * Definitions + ************************************************************************/ + +/************************************************************************ + * Private Type Declarations + ************************************************************************/ + +/************************************************************************ + * Global Variables + ************************************************************************/ + +/************************************************************************ + * Private Variables + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Function: mq_setattr + * + * Description: + * This function sets the attributes associated with the + * specified message queue "mqdes." Only the "O_NONBLOCK" + * bit of the "mq_flags" can be changed. + * + * If "oldstat" is non-null, mq_setattr() will store the + * previous message queue attributes at that location (just + * as would have been returned by mq_getattr()). + * + * Parameters: + * mqdes - Message queue descriptor + * mq_stat - New attributes + * oldstate - Old attributes + * + * Return Value: + * 0 (OK) if attributes are set successfully, otherwise + * -1 (ERROR). + * + * Assumptions: + * + ************************************************************************/ + +int mq_setattr(mqd_t mqdes, const struct mq_attr *mq_stat, + struct mq_attr *oldstat) +{ + int ret = ERROR; + + if (mqdes && mq_stat) + { + /* Return the attributes if so requested */ + + if (oldstat) + { + (void)mq_getattr(mqdes, oldstat); + } + + /* Set the new value of the O_NONBLOCK flag. */ + + mqdes->oflags = ((mq_stat->mq_flags & O_NONBLOCK) | + (mqdes->oflags & (~O_NONBLOCK))); + ret = OK; + } + + return ret; +} diff --git a/nuttx/lib/net/Make.defs b/nuttx/lib/net/Make.defs new file mode 100644 index 0000000000..ae041bd2c5 --- /dev/null +++ b/nuttx/lib/net/Make.defs @@ -0,0 +1,44 @@ +############################################################################ +# lib/net/Make.defs +# +# 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. +# +############################################################################ + +# Add the networking C files to the build + +CSRCS += lib_etherntoa.c lib_htons.c lib_htonl.c lib_inetaddr.c +CSRCS += lib_inetntoa.c lib_inetntop.c lib_inetpton.c + +# Add the net directory to the build + +DEPPATH += --dep-path net +VPATH += :net diff --git a/nuttx/lib/net/lib_etherntoa.c b/nuttx/lib/net/lib_etherntoa.c new file mode 100644 index 0000000000..f89f205a2e --- /dev/null +++ b/nuttx/lib/net/lib_etherntoa.c @@ -0,0 +1,69 @@ +/**************************************************************************** + * lib/net/lib_etherntoa.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: ether_ntoa + * + * Description: + * The ether_ntoa() function converts the Ethernet host address addr given + * in network byte order to a string in standard hex-digits-and-colons + * notation. The string is returned in a statically allocated buffer, which + * subsequent calls will overwrite. + * + ****************************************************************************/ + +FAR char *ether_ntoa(FAR const struct ether_addr *addr) +{ + static char buffer[20]; + sprintf(buffer, "%02x:%02x:%02x:%02x:%02x:%02x", + addr->ether_addr_octet[0], addr->ether_addr_octet[1], + addr->ether_addr_octet[2], addr->ether_addr_octet[3], + addr->ether_addr_octet[4], addr->ether_addr_octet[5]); + return buffer; +} diff --git a/nuttx/lib/net/lib_htonl.c b/nuttx/lib/net/lib_htonl.c new file mode 100644 index 0000000000..e4c3e53838 --- /dev/null +++ b/nuttx/lib/net/lib_htonl.c @@ -0,0 +1,68 @@ +/************************************************************ + * lib/net/lib_ntohl.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +#include +#include + +/************************************************************ + * Global Functions + ************************************************************/ + +uint32_t htonl(uint32_t hl) +{ +#ifdef CONFIG_ENDIAN_BIG + return hl; +#else + return (( (hl) >> 24) | + (((hl) >> 8) & 0x0000ff00) | + (((hl) << 8) & 0x00ff0000) | + ( (hl) << 24)); +#endif +} + +uint32_t ntohl(uint32_t nl) +{ +#ifdef CONFIG_ENDIAN_BIG + return nl; +#else + return htonl(nl); +#endif +} diff --git a/nuttx/lib/net/lib_htons.c b/nuttx/lib/net/lib_htons.c new file mode 100644 index 0000000000..b4117e1dc2 --- /dev/null +++ b/nuttx/lib/net/lib_htons.c @@ -0,0 +1,65 @@ +/*************************************************************************** + * lib/net/lib_htons.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ***************************************************************************/ + +/*************************************************************************** + * Compilation Switches + ***************************************************************************/ + +/*************************************************************************** + * Included Files + ***************************************************************************/ + +#include + +#include +#include + +/*************************************************************************** + * Global Functions + ***************************************************************************/ + +uint16_t htons(uint16_t hs) +{ + return HTONS(hs); +} + +uint16_t ntohs(uint16_t ns) +{ +#ifdef CONFIG_ENDIAN_BIG + return ns; +#else + return htons(ns); +#endif +} diff --git a/nuttx/lib/net/lib_inetaddr.c b/nuttx/lib/net/lib_inetaddr.c new file mode 100644 index 0000000000..48b01d682f --- /dev/null +++ b/nuttx/lib/net/lib_inetaddr.c @@ -0,0 +1,74 @@ +/**************************************************************************** + * lib/net/lib_inetaddr.c + * + * Copyright (C) 2011 Yu Qiang. All rights reserved. + * Author: Yu Qiang + * + * This file is a part of NuttX: + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * + * 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 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * name inet_addr + * + * Description: + * The inet_addr() function converts the string pointed to by cp, in the + * standard IPv4 dotted decimal notation, to an integer value suitable for + * use as an Internet address. + + ****************************************************************************/ + +in_addr_t inet_addr(FAR const char *cp) +{ + unsigned int a, b, c, d; + uint32_t result; + + sscanf(cp, "%u.%u.%u.%u", &a, &b, &c, &d); + result = a << 8; + result |= b; + result <<= 8; + result |= c; + result <<= 8; + result |= d; + return HTONL(result); +} diff --git a/nuttx/lib/net/lib_inetntoa.c b/nuttx/lib/net/lib_inetntoa.c new file mode 100644 index 0000000000..0f4fb61df6 --- /dev/null +++ b/nuttx/lib/net/lib_inetntoa.c @@ -0,0 +1,79 @@ +/**************************************************************************** + * lib/net/lib_inetntoa.c + * + * Copyright (C) 2007-2008, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#ifndef CONFIG_NET_IPv6 + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: inet_ntoa + * + * Description: + * The inet_ntoa() function converts the Internet host address in given in + * network byte order to a string in standard numbers-and-dots notation. + * The string is returned in a statically allocated buffer, which subsequent + * calls will overwrite. + * + ****************************************************************************/ + +#ifdef CONFIG_CAN_PASS_STRUCTS +FAR char *inet_ntoa(struct in_addr in) +{ + static char buffer[INET_ADDRSTRLEN+2]; + FAR char *ptr = (FAR char*)&in.s_addr; + sprintf(buffer, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]); + return buffer; +} +#else +FAR char *_inet_ntoa(in_addr_t in) +{ + static char buffer[INET_ADDRSTRLEN+2]; + FAR char *ptr = (FAR char*)∈ + sprintf(buffer, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]); + return buffer; +} +#endif +#endif /* !CONFIG_NET_IPv6 */ + diff --git a/nuttx/lib/net/lib_inetntop.c b/nuttx/lib/net/lib_inetntop.c new file mode 100644 index 0000000000..dc6a2d0d79 --- /dev/null +++ b/nuttx/lib/net/lib_inetntop.c @@ -0,0 +1,202 @@ +/**************************************************************************** + * lib/net/lib_inetntop.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Includes some logic extracted from hwport_ftpd, written by Jaehyuk Cho + * which was released under the BSD license. + * + * Copyright (C) HWPORT.COM. All rights reserved. + * Author: JAEHYUK CHO + * + * 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 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: inet_ntop + * + * Description: + * The inet_ntop() function converts a numeric address into a text string + * suitable for presentation. + * + * Input Parameters: + * af - The af argument specifies the family of the address. This can be + * AF_INET or AF_INET6. + * src - The src argument points to a buffer holding an address of the + * specified type. The address must be in network byte order. + * dst - The dst argument points to a buffer where the function stores + * the resulting text string; it shall not be NULL. + * size - The size argument specifies the size of this buffer, which must + * be large enough to hold the text string (INET_ADDRSTRLEN + * characters for IPv4, INET6_ADDRSTRLEN characters for IPv6). + * + * Returned Value: + * inet_ntop() returns a pointer to the buffer containing the text string + * if the conversion succeeds. Otherwise, NULL is returned and the errno + * is set to indicate the error. There follow errno values may be set: + * + * EAFNOSUPPORT - The af argument is invalid. + * ENOSPC - The size of the inet_ntop() result buffer is inadequate + * + ****************************************************************************/ + +FAR const char *inet_ntop(int af, FAR const void *src, FAR char *dst, socklen_t size) +{ + int errval; +#ifndef CONFIG_NET_IPv6 + FAR char *ptr; + + DEBUGASSERT(src && dst); + + if (af != AF_INET) + { + errval = EAFNOSUPPORT; + goto errout; + } + + if (size < INET_ADDRSTRLEN) + { + errval = ENOSPC; + goto errout; + } + + ptr = (FAR char*)src; + sprintf(dst, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]); + return dst; +#else + FAR const struct in6_addr *in6_addr; + uint16_t warray[8]; + int offset; + int entry; + int count; + int maxentry; + int maxcount; + + DEBUGASSERT(src && dst); + + if (af != AF_INET6) + { + errval = EAFNOSUPPORT; + goto errout; + } + + if (size < INET6_ADDRSTRLEN) + { + errval = ENOSPC; + goto errout; + } + + in6_addr = (FAR const struct in6_addr *)src; + entry = -1; + maxentry = -1; + maxcount = 0; + offset = 0; + + while (offset < 8) + { + warray[offset] = ntohs(in6_addr->s6_addr16[offset]); + if (warray[offset] == 0) + { + entry = offset; + count = 1; + offset++; + + while (offset < 8) + { + warray[offset] = ntohs(in6_addr->s6_addr16[offset]); + if (warray[offset] != 0) + { + break; + } + offset++; + count++; + } + + if (count > maxcount) + { + maxentry = entry; + maxcount = count; + } + } + offset++; + } + + offset = 0; + dst[0] = '\0'; + + while (offset < 8) + { + if (offset == maxentry) + { + size -= snprintf(&dst[strlen(dst)], size, ":"); + offset += maxcount; + if (offset >= 8) + { + size -= snprintf(&dst[strlen(dst)], size, ":"); + } + } + else + { + if (offset > 0) + { + size -= snprintf(&dst[strlen(dst)], size, ":"); + } + + size -= snprintf(&dst[strlen(dst)], size, "%x", warray[offset]); + offset++; + } + } + + return dst; +#endif + +errout: + set_errno(errval); + memset(dst, 0, size); + return NULL; +} diff --git a/nuttx/lib/net/lib_inetpton.c b/nuttx/lib/net/lib_inetpton.c new file mode 100644 index 0000000000..5371cd3f21 --- /dev/null +++ b/nuttx/lib/net/lib_inetpton.c @@ -0,0 +1,338 @@ +/**************************************************************************** + * lib/net/lib_inetpton.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Includes some logic extracted from hwport_ftpd, written by Jaehyuk Cho + * which was released under the BSD license. + * + * Copyright (C) HWPORT.COM. All rights reserved. + * Author: JAEHYUK CHO + * + * 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 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: inet_pton + * + * Description: + * The inet_pton() function converts an address in its standard text + * presentation form into its numeric binary form. + * + * If the af argument of inet_pton() is AF_INET, the src string will be + * in the standard IPv4 dotted-decimal form: + * + * ddd.ddd.ddd.ddd + * + * where "ddd" is a one to three digit decimal number between 0 and 255. + * + * If the af argument of inet_pton() is AF_INET6, the src string will be in + * one of the following standard IPv6 text forms: + * + * 1. The preferred form is "x:x:x:x:x:x:x:x", where the 'x' s are the + * hexadecimal values of the eight 16-bit pieces of the address. Leading + * zeros in individual fields can be omitted, but there must be at least + * one numeral in every field. + * + * 2. A string of contiguous zero fields in the preferred form can be shown + * as "::". The "::" can only appear once in an address. Unspecified + * addresses ( "0:0:0:0:0:0:0:0" ) may be represented simply as "::". + * + * 3. A third form that is sometimes more convenient when dealing with a + * mixed environment of IPv4 and IPv6 nodes is "x:x:x:x:x:x:d.d.d.d", + * where the 'x' s are the hexadecimal values of the six high-order + * 16-bit pieces of the address, and the 'd' s are the decimal values + * of the four low-order 8-bit pieces of the address (standard IPv4 + * representation). + * + * Input Parameters: + * af - The af argument specifies the family of the address. This can be + * AF_INET or AF_INET6. + * src - The src argument points to the string being passed in. + * dst - The dst argument points to a numstr into which the function stores + * the numeric address; this must be large enough to hold the numeric + * address (32 bits for AF_INET, 128 bits for AF_INET6). + * + * Returned Value: + * The inet_pton() function returns 1 if the conversion succeeds, with the + * address pointed to by dst in network byte order. It will return 0 if the + * input is not a valid IPv4 dotted-decimal string or a valid IPv6 address + * string, or -1 with errno set to EAFNOSUPPOR] if the af argument is unknown. + * + ****************************************************************************/ + +int inet_pton(int af, FAR const char *src, FAR void *dst) +{ +#ifndef CONFIG_NET_IPv6 + size_t srcoffset; + size_t numoffset; + int value; + int ndots; + uint8_t ch; + char numstr[4]; + uint8_t *ip; + + DEBUGASSERT(src && dst); + + if (af != AF_INET) + { + set_errno(EAFNOSUPPORT); + return -1; + } + + (void)memset(dst, 0, sizeof(struct in_addr)); + + ip = (uint8_t *)dst; + srcoffset = 0; + numoffset = 0; + ndots = 0; + + for(;;) + { + ch = (uint8_t)src[srcoffset++]; + + if (ch == '.' || ch == '\0') + { + if (ch == '.' && ndots >= 4) + { + /* Too many dots */ + + break; + } + + if (numoffset <= 0) + { + /* Empty numeric string */ + + break; + } + + numstr[numoffset] = '\0'; + numoffset = 0; + + value = atoi(numstr); + if (value < 0 || value > 255) + { + /* Out of range value */ + + break; + } + + ip[ndots] = (uint8_t)value; + + if (ch == '\0') + { + if (ndots != 3) + { + /* Not enough dots */ + + break; + } + + /* Return 1 if the conversion succeeds */ + + return 1; + } + + ndots++; + } + else if (ch >= '0' && ch <= '9') + { + numstr[numoffset++] = ch; + if (numoffset >= 4) + { + /* Number is too long */ + + break; + } + } + else + { + /* Illegal character */ + + break; + } + } + + /* Return zero if there is any problem parsing the input */ + + return 0; +#else + size_t srcoffset; + size_t numoffset; + long value; + int nsep; + int nrsep; + uint8_t ch; + char numstr[5]; + uint8_t ip[sizeof(struct in6_addr)]; + uint8_t rip[sizeof(struct in6_addr)]; + bool rtime; + + DEBUGASSERT(src && dst); + + if (af != AF_INET6) + { + set_errno(EAFNOSUPPORT); + return -1; + } + + (void)memset(dst, 0, sizeof(struct in6_addr)); + + srcoffset = 0; + numoffset = 0; + nsep = 0; + nrsep = 0; + rtime = false; + + for(;;) + { + ch = (uint8_t)src[srcoffset++]; + + if (ch == ':' || ch == '\0') + { + if (ch == ':' && (nsep + nrsep) >= 8) + { + /* Too many separators */ + + break; + } + + if (ch != '\0' && numoffset <= 0) + { + /* Empty numeric string */ + + if (rtime && nrsep > 1) + { + /* dup simple */ + + break; + } + + numoffset = 0; + rtime = true; + continue; + } + + numstr[numoffset] = '\0'; + numoffset = 0; + + value = strtol(numstr, NULL, 16); + if (value < 0 || value > 0xffff) + { + /* Out of range value */ + + break; + } + + if (!rtime) + { + ip[(nsep << 1) + 0] = (uint8_t)((value >> 8) & 0xff); + ip[(nsep << 1) + 1] = (uint8_t)((value >> 0) & 0xff); + nsep++; + } + else + { + rip[(nrsep << 1) + 0] = (uint8_t)((value >> 8) & 0xff); + rip[(nrsep << 1) + 1] = (uint8_t)((value >> 0) & 0xff); + nrsep++; + } + + if (ch == '\0' /* || ch == '/' */) + { + if ((nsep <= 1 && nrsep <= 0) || + (nsep + nrsep) < 1 || + (nsep + nrsep) > 8) + { + /* Separator count problem */ + + break; + } + + if (nsep > 0) + { + memcpy(dst, &ip[0], nsep << 1); + } + + if (nrsep > 0) + { + memcpy(dst + (16 - (nrsep << 1)), &rip[0], nrsep << 1); + } + + /* Return 1 if the conversion succeeds */ + + return 1; + } + } + else if ((ch >= '0' && ch <= '9') || + (ch >= 'a' && ch <= 'f') || + (ch >= 'A' && ch <= 'F')) + { + numstr[numoffset++] = ch; + if (numoffset >= 5) + { + /* Numeric string is too long */ + + break; + } + } + else + { + /* Illegal character */ + + break; + } + } + + + /* Return zero if there is any problem parsing the input */ + + return 0; +#endif +} diff --git a/nuttx/lib/pthread/Make.defs b/nuttx/lib/pthread/Make.defs new file mode 100644 index 0000000000..a1eba7bb0a --- /dev/null +++ b/nuttx/lib/pthread/Make.defs @@ -0,0 +1,56 @@ +############################################################################ +# lib/pthread/Make.defs +# +# 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. +# +############################################################################ + +# Add the pthread C files to the build + +CSRCS += pthread_attrinit.c pthread_attrdestroy.c \ + pthread_attrsetschedpolicy.c pthread_attrgetschedpolicy.c \ + pthread_attrsetinheritsched.c pthread_attrgetinheritsched.c \ + pthread_attrsetstacksize.c pthread_attrgetstacksize.c \ + pthread_attrsetschedparam.c pthread_attrgetschedparam.c \ + pthread_barrierattrinit.c pthread_barrierattrdestroy.c \ + pthread_barrierattrgetpshared.c pthread_barrierattrsetpshared.c \ + pthread_condattrinit.c pthread_condattrdestroy.c \ + pthread_mutexattrinit.c pthread_mutexattrdestroy.c \ + pthread_mutexattrgetpshared.c pthread_mutexattrsetpshared.c + +ifeq ($(CONFIG_MUTEX_TYPES),y) +CSRCS += pthread_mutexattrsettype.c pthread_mutexattrgettype.c +endif + +# Add the pthread directory to the build + +DEPPATH += --dep-path pthread +VPATH += :pthread diff --git a/nuttx/lib/pthread/pthread_attrdestroy.c b/nuttx/lib/pthread/pthread_attrdestroy.c new file mode 100644 index 0000000000..103528c7e1 --- /dev/null +++ b/nuttx/lib/pthread/pthread_attrdestroy.c @@ -0,0 +1,108 @@ +/**************************************************************************** + * lib/pthread/pthread_attrdestroy.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_attr_destroy + * + * Description: + * An attributes object can be deleted when it is no longer + * needed. + * + * Parameters: + * attr + * + * Return Value: + * 0 meaning success + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_attr_destroy(FAR pthread_attr_t *attr) +{ + int ret; + + sdbg("attr=0x%p\n", attr); + + if (!attr) + { + ret = EINVAL; + } + else + { + memset(attr, 0, sizeof(pthread_attr_t)); + ret = OK; + } + + sdbg("Returning %d\n", ret); + return ret; +} + + diff --git a/nuttx/lib/pthread/pthread_attrgetinheritsched.c b/nuttx/lib/pthread/pthread_attrgetinheritsched.c new file mode 100644 index 0000000000..02d6e0b7c0 --- /dev/null +++ b/nuttx/lib/pthread/pthread_attrgetinheritsched.c @@ -0,0 +1,111 @@ +/**************************************************************************** + * lib/pthread/pthread_attrgetinheritsched.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_attr_getinheritsched + * + * Description: + * Report whether the scheduling info in the pthread + * attributes will be used or if the thread will + * inherit the properties of the parent. + * + * Parameters: + * attr + * inheritsched + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_attr_getinheritsched(FAR const pthread_attr_t *attr, + FAR int *inheritsched) +{ + int ret; + + sdbg("attr=0x%p inheritsched=0x%p\n", attr, inheritsched); + + if (!attr || !inheritsched) + { + ret = EINVAL; + } + else + { + *inheritsched = (int)attr->inheritsched; + ret = OK; + } + + sdbg("Returning %d\n", ret); + return ret; +} + + diff --git a/nuttx/lib/pthread/pthread_attrgetschedparam.c b/nuttx/lib/pthread/pthread_attrgetschedparam.c new file mode 100644 index 0000000000..c6bf55dea8 --- /dev/null +++ b/nuttx/lib/pthread/pthread_attrgetschedparam.c @@ -0,0 +1,110 @@ +/**************************************************************************** + * lib/pthread/pthread_attrgetschedparam.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_attr_getschedparam + * + * Description: + * + * Parameters: + * attr + * param + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_attr_getschedparam(FAR pthread_attr_t *attr, + FAR struct sched_param *param) +{ + int ret; + + sdbg("attr=0x%p param=0x%p\n", attr, param); + + if (!attr || !param) + { + ret = EINVAL; + } + else + { + param->sched_priority = attr->priority; + ret = OK; + } + + sdbg("Returning %d\n", ret); + return ret; +} + + + diff --git a/nuttx/lib/pthread/pthread_attrgetschedpolicy.c b/nuttx/lib/pthread/pthread_attrgetschedpolicy.c new file mode 100644 index 0000000000..c42b828c96 --- /dev/null +++ b/nuttx/lib/pthread/pthread_attrgetschedpolicy.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * lib/pthread/pthread_attrgetschedpolicy.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_attr_getschedpolicy + * + * Description: + * Obtain the scheduling algorithm attribute. + * + * Parameters: + * attr + * policy + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_attr_getschedpolicy(FAR pthread_attr_t *attr, int *policy) +{ + int ret; + + sdbg("attr=0x%p policy=0x%p\n", attr, policy); + + if (!attr || !policy) + { + ret = EINVAL; + } + else + { + *policy = attr->policy; + ret = OK; + } + + sdbg("Returning %d\n", ret); + return ret; +} diff --git a/nuttx/lib/pthread/pthread_attrgetstacksize.c b/nuttx/lib/pthread/pthread_attrgetstacksize.c new file mode 100644 index 0000000000..2faa586ba8 --- /dev/null +++ b/nuttx/lib/pthread/pthread_attrgetstacksize.c @@ -0,0 +1,106 @@ +/**************************************************************************** + * lib/pthread/pthread_attrgetstacksize.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_attr_getstacksize + * + * Description: + * + * Parameters: + * attr + * stacksize + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_attr_getstacksize(FAR pthread_attr_t *attr, FAR long *stacksize) +{ + int ret; + + sdbg("attr=0x%p stacksize=0x%p\n", attr, stacksize); + + if (!stacksize) + { + ret = EINVAL; + } + else + { + *stacksize = attr->stacksize; + ret = OK; + } + + sdbg("Returning %d\n", ret); + return ret; +} + + diff --git a/nuttx/lib/pthread/pthread_attrinit.c b/nuttx/lib/pthread/pthread_attrinit.c new file mode 100644 index 0000000000..d06a535d78 --- /dev/null +++ b/nuttx/lib/pthread/pthread_attrinit.c @@ -0,0 +1,123 @@ +/**************************************************************************** + * lib/pthread/pthread_attrinit.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/* Default pthread attributes (see included/nuttx/pthread.h). When configured + * to build separate kernel- and user-address spaces, this global is + * duplicated in each address spaced. This copy can only be shared within + * the user address space. + */ + +#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__) +pthread_attr_t g_default_pthread_attr = PTHREAD_ATTR_INITIALIZER; +#endif + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_attr_init + * + * Description: + * Initializes a thread attributes object (attr) with + * default values for all of the individual attributes + * used by a given implementation. + * + * Parameters: + * attr + * + * Return Value: + * 0 on success, otherwise an error number + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_attr_init(FAR pthread_attr_t *attr) +{ + int ret = OK; + + sdbg("attr=0x%p\n", attr); + if (!attr) + { + ret = ENOMEM; + } + else + { + /* Set the child thread priority to be the default + * priority. Set the child stack size to some arbitrary + * default value. + */ + + memcpy(attr, &g_default_pthread_attr, sizeof(pthread_attr_t)); + } + + sdbg("Returning %d\n", ret); + return ret; +} + diff --git a/nuttx/lib/pthread/pthread_attrsetinheritsched.c b/nuttx/lib/pthread/pthread_attrsetinheritsched.c new file mode 100644 index 0000000000..df2c2fba33 --- /dev/null +++ b/nuttx/lib/pthread/pthread_attrsetinheritsched.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * lib/pthread/pthread_attrsetinheritsched.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_attr_setinheritsched + * + * Description: + * Indicate whether the scheduling info in the pthread + * attributes will be used or if the thread will + * inherit the properties of the parent. + * + * Parameters: + * attr + * policy + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_attr_setinheritsched(FAR pthread_attr_t *attr, + int inheritsched) +{ + int ret; + + sdbg("inheritsched=%d\n", inheritsched); + + if (!attr || + (inheritsched != PTHREAD_INHERIT_SCHED && + inheritsched != PTHREAD_EXPLICIT_SCHED)) + { + ret = EINVAL; + } + else + { + attr->inheritsched = (uint8_t)inheritsched; + ret = OK; + } + + sdbg("Returning %d\n", ret); + return ret; +} + diff --git a/nuttx/lib/pthread/pthread_attrsetschedparam.c b/nuttx/lib/pthread/pthread_attrsetschedparam.c new file mode 100644 index 0000000000..c2ab4d1c41 --- /dev/null +++ b/nuttx/lib/pthread/pthread_attrsetschedparam.c @@ -0,0 +1,108 @@ +/**************************************************************************** + * lib/pthread/pthread_attrsetschedparam.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_attr_setschedparam + * + * Description: + * + * Parameters: + * attr + * param + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_attr_setschedparam(FAR pthread_attr_t *attr, + FAR const struct sched_param *param) +{ + int ret; + + sdbg("attr=0x%p param=0x%p\n", attr, param); + + if (!attr || !param) + { + ret = EINVAL; + } + else + { + attr->priority = (short)param->sched_priority; + ret = OK; + } + sdbg("Returning %d\n", ret); + return ret; +} + + diff --git a/nuttx/lib/pthread/pthread_attrsetschedpolicy.c b/nuttx/lib/pthread/pthread_attrsetschedpolicy.c new file mode 100644 index 0000000000..4e43e635de --- /dev/null +++ b/nuttx/lib/pthread/pthread_attrsetschedpolicy.c @@ -0,0 +1,111 @@ +/**************************************************************************** + * lib/pthread/pthread_attrsetschedpolicy.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_attr_setschedpolicy + * + * Description: + * Set the scheduling algorithm attribute. + * + * Parameters: + * attr + * policy + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_attr_setschedpolicy(FAR pthread_attr_t *attr, int policy) +{ + int ret; + + sdbg("attr=0x%p policy=%d\n", attr, policy); + +#if CONFIG_RR_INTERVAL > 0 + if (!attr || (policy != SCHED_FIFO && policy != SCHED_RR)) +#else + if (!attr || policy != SCHED_FIFO ) +#endif + { + ret = EINVAL; + } + else + { + attr->policy = policy; + ret = OK; + } + + sdbg("Returning %d\n", ret); + return ret; +} diff --git a/nuttx/lib/pthread/pthread_attrsetstacksize.c b/nuttx/lib/pthread/pthread_attrsetstacksize.c new file mode 100644 index 0000000000..8a826dd3ac --- /dev/null +++ b/nuttx/lib/pthread/pthread_attrsetstacksize.c @@ -0,0 +1,106 @@ +/**************************************************************************** + * lib/pthread/pthread_attrsetstacksize.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_attr_setstacksize + * + * Description: + * + * Parameters: + * attr + * stacksize + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_attr_setstacksize(FAR pthread_attr_t *attr, long stacksize) +{ + int ret; + + sdbg("attr=0x%p stacksize=%ld\n", attr, stacksize); + + if (!attr || stacksize < PTHREAD_STACK_MIN) + { + ret = EINVAL; + } + else + { + attr->stacksize = stacksize; + ret = OK; + } + + sdbg("Returning %d\n", ret); + return ret; +} + diff --git a/nuttx/lib/pthread/pthread_barrierattrdestroy.c b/nuttx/lib/pthread/pthread_barrierattrdestroy.c new file mode 100644 index 0000000000..6d16b9cff8 --- /dev/null +++ b/nuttx/lib/pthread/pthread_barrierattrdestroy.c @@ -0,0 +1,102 @@ +/******************************************************************************** + * lib/pthread/pthread_barrierattrdestroy.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ********************************************************************************/ + +/******************************************************************************** + * Included Files + ********************************************************************************/ + +#include + +#include +#include +#include + +/******************************************************************************** + * Definitions + ********************************************************************************/ + +/******************************************************************************** + * Private Type Declarations + ********************************************************************************/ + +/******************************************************************************** + * Global Variables + ********************************************************************************/ + +/******************************************************************************** + * Private Variables + ********************************************************************************/ + +/******************************************************************************** + * Private Function Prototypes + ********************************************************************************/ + +/******************************************************************************** + * Public Functions + ********************************************************************************/ + +/******************************************************************************** + * Function: pthread_barrierattr_destroy + * + * Description: + * The pthread_barrierattr_destroy() function will destroy a barrier attributes + * object. A destroyed attr attributes object can be reinitialized using + * pthread_barrierattr_init(); the results of otherwise referencing the object + * after it has been destroyed are undefined. + * + * Parameters: + * attr - barrier attributes to be destroyed. + * + * Return Value: + * 0 (OK) on success or EINVAL if attr is invalid. + * + * Assumptions: + * + ********************************************************************************/ + +int pthread_barrierattr_destroy(FAR pthread_barrierattr_t *attr) +{ + int ret = OK; + + if (!attr) + { + ret = EINVAL; + } + else + { + attr->pshared = PTHREAD_PROCESS_PRIVATE; + } + return ret; +} diff --git a/nuttx/lib/pthread/pthread_barrierattrgetpshared.c b/nuttx/lib/pthread/pthread_barrierattrgetpshared.c new file mode 100644 index 0000000000..d29bc6dfc8 --- /dev/null +++ b/nuttx/lib/pthread/pthread_barrierattrgetpshared.c @@ -0,0 +1,101 @@ +/******************************************************************************** + * lib/pthread/pthread_barrierattrgetpshared.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ********************************************************************************/ + +/******************************************************************************** + * Included Files + ********************************************************************************/ + +#include + +#include +#include +#include + +/******************************************************************************** + * Definitions + ********************************************************************************/ + +/******************************************************************************** + * Private Type Declarations + ********************************************************************************/ + +/******************************************************************************** + * Global Variables + ********************************************************************************/ + +/******************************************************************************** + * Private Variables + ********************************************************************************/ + +/******************************************************************************** + * Private Function Prototypes + ********************************************************************************/ + +/******************************************************************************** + * Public Functions + ********************************************************************************/ + +/******************************************************************************** + * Function: pthread_barrierattr_getpshared + * + * Description: + * The pthread_barrierattr_getpshared() function will obtain the value of the + * process-shared attribute from the attributes object referenced by attr. + * + * Parameters: + * attr - barrier attributes to be queried. + * pshared - the location to stored the current value of the pshared attribute. + * + * Return Value: + * 0 (OK) on success or EINVAL if either attr or pshared is invalid. + * + * Assumptions: + * + ********************************************************************************/ + +int pthread_barrierattr_getpshared(FAR const pthread_barrierattr_t *attr, FAR int *pshared) +{ + int ret = OK; + + if (!attr || !pshared) + { + ret = EINVAL; + } + else + { + *pshared = attr->pshared; + } + return ret; +} diff --git a/nuttx/lib/pthread/pthread_barrierattrinit.c b/nuttx/lib/pthread/pthread_barrierattrinit.c new file mode 100644 index 0000000000..b5f35ca917 --- /dev/null +++ b/nuttx/lib/pthread/pthread_barrierattrinit.c @@ -0,0 +1,101 @@ +/******************************************************************************** + * lib/pthread/pthread_barrierattrinit.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ********************************************************************************/ + +/******************************************************************************** + * Included Files + ********************************************************************************/ + +#include + +#include +#include +#include + +/******************************************************************************** + * Definitions + ********************************************************************************/ + +/******************************************************************************** + * Private Type Declarations + ********************************************************************************/ + +/******************************************************************************** + * Global Variables + ********************************************************************************/ + +/******************************************************************************** + * Private Variables + ********************************************************************************/ + +/******************************************************************************** + * Private Function Prototypes + ********************************************************************************/ + +/******************************************************************************** + * Public Functions + ********************************************************************************/ + +/******************************************************************************** + * Function: pthread_barrierattr_init + * + * Description: + * The pthread_barrierattr_init() function will initialize a barrier attribute + * object attr with the default value for all of the attributes defined by the + * implementation. + * + * Parameters: + * attr - barrier attributes to be initialized. + * + * Return Value: + * 0 (OK) on success or EINVAL if attr is invalid. + * + * Assumptions: + * + ********************************************************************************/ + +int pthread_barrierattr_init(FAR pthread_barrierattr_t *attr) +{ + int ret = OK; + + if (!attr) + { + ret = EINVAL; + } + else + { + attr->pshared = PTHREAD_PROCESS_PRIVATE; + } + return ret; +} diff --git a/nuttx/lib/pthread/pthread_barrierattrsetpshared.c b/nuttx/lib/pthread/pthread_barrierattrsetpshared.c new file mode 100644 index 0000000000..d0eecbf5a4 --- /dev/null +++ b/nuttx/lib/pthread/pthread_barrierattrsetpshared.c @@ -0,0 +1,111 @@ +/******************************************************************************** + * lib/pthread/pthread_barrierattrsetpshared.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ********************************************************************************/ + +/******************************************************************************** + * Included Files + ********************************************************************************/ + +#include + +#include +#include +#include + +/******************************************************************************** + * Definitions + ********************************************************************************/ + +/******************************************************************************** + * Private Type Declarations + ********************************************************************************/ + +/******************************************************************************** + * Global Variables + ********************************************************************************/ + +/******************************************************************************** + * Private Variables + ********************************************************************************/ + +/******************************************************************************** + * Private Function Prototypes + ********************************************************************************/ + +/******************************************************************************** + * Public Functions + ********************************************************************************/ + +/******************************************************************************** + * Function: pthread_barrierattr_setpshared + * + * Description: + * The process-shared attribute is set to PTHREAD_PROCESS_SHARED to permit a + * barrier to be operated upon by any thread that has access to the memory where + * the barrier is allocated. If the process-shared attribute is + * PTHREAD_PROCESS_PRIVATE, the barrier can only be operated upon by threads + * created within the same process as the thread that initialized the barrier. + * If threads of different processes attempt to operate on such a barrier, the + * behavior is undefined. The default value of the attribute is + * PTHREAD_PROCESS_PRIVATE. + * + * Both constants PTHREAD_PROCESS_SHARED and PTHREAD_PROCESS_PRIVATE are defined + * in pthread.h. + * + * Parameters: + * attr - barrier attributes to be modified. + * pshared - the new value of the pshared attribute. + * + * Return Value: + * 0 (OK) on success or EINVAL if either attr is invalid or pshared is not one + * of PTHREAD_PROCESS_SHARED or PTHREAD_PROCESS_PRIVATE. + * + * Assumptions: + * + ********************************************************************************/ + +int pthread_barrierattr_setpshared(FAR pthread_barrierattr_t *attr, int pshared) +{ + int ret = OK; + + if (!attr || (pshared != PTHREAD_PROCESS_SHARED && pshared != PTHREAD_PROCESS_PRIVATE)) + { + ret = EINVAL; + } + else + { + attr->pshared = pshared; + } + return ret; +} diff --git a/nuttx/lib/pthread/pthread_condattrdestroy.c b/nuttx/lib/pthread/pthread_condattrdestroy.c new file mode 100644 index 0000000000..d6c3df5d1a --- /dev/null +++ b/nuttx/lib/pthread/pthread_condattrdestroy.c @@ -0,0 +1,82 @@ +/**************************************************************************** + * lib/pthread/pthread_condattrdestroy.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_condattr_destroy + * + * Description: + * Operations on condition variable attributes + * + * Parameters: + * None + * + * Return Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_condattr_destroy(FAR pthread_condattr_t *attr) +{ + int ret = OK; + + sdbg("attr=0x%p\n", attr); + + if (!attr) + { + ret = EINVAL; + } + + sdbg("Returning %d\n", ret); + return ret; +} + + + diff --git a/nuttx/lib/pthread/pthread_condattrinit.c b/nuttx/lib/pthread/pthread_condattrinit.c new file mode 100644 index 0000000000..5721c61593 --- /dev/null +++ b/nuttx/lib/pthread/pthread_condattrinit.c @@ -0,0 +1,85 @@ +/**************************************************************************** + * lib/pthread/pthread_condattrinit.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_condattr_init + * + * Description: + * Operations on condition variable attributes + * + * Parameters: + * None + * + * Return Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_condattr_init(FAR pthread_condattr_t *attr) +{ + int ret = OK; + + sdbg("attr=0x%p\n", attr); + + if (!attr) + { + ret = EINVAL; + } + else + { + *attr = 0; + } + + sdbg("Returning %d\n", ret); + return ret; +} + + diff --git a/nuttx/lib/pthread/pthread_mutexattrdestroy.c b/nuttx/lib/pthread/pthread_mutexattrdestroy.c new file mode 100644 index 0000000000..e9868df68b --- /dev/null +++ b/nuttx/lib/pthread/pthread_mutexattrdestroy.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * lib/pthread/pthread_mutexattrdestroy.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_mutexattr_destroy + * + * Description: + * Destroy mutex attributes. + * + * Parameters: + * attr + * pshared + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_mutexattr_destroy(FAR pthread_mutexattr_t *attr) +{ + int ret = OK; + + sdbg("attr=0x%p\n", attr); + + if (!attr) + { + ret = EINVAL; + } + else + { + attr->pshared = 0; + } + + sdbg("Returning %d\n", ret); + return ret; +} diff --git a/nuttx/lib/pthread/pthread_mutexattrgetpshared.c b/nuttx/lib/pthread/pthread_mutexattrgetpshared.c new file mode 100644 index 0000000000..bc6379db5f --- /dev/null +++ b/nuttx/lib/pthread/pthread_mutexattrgetpshared.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * lib/pthread/pthread_mutexattrgetpshared.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_mutexattr_getpshared + * + * Description: + * Get pshared mutex attribute. + * + * Parameters: + * attr + * pshared + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_mutexattr_getpshared(FAR pthread_mutexattr_t *attr, FAR int *pshared) +{ + int ret = OK; + + sdbg("attr=0x%p pshared=0x%p\n", attr, pshared); + + if (!attr || !pshared) + { + ret = EINVAL; + } + else + { + *pshared = attr->pshared; + } + + sdbg("Returning %d\n", ret); + return ret; +} diff --git a/nuttx/lib/pthread/pthread_mutexattrgettype.c b/nuttx/lib/pthread/pthread_mutexattrgettype.c new file mode 100644 index 0000000000..5fb10f3015 --- /dev/null +++ b/nuttx/lib/pthread/pthread_mutexattrgettype.c @@ -0,0 +1,98 @@ +/**************************************************************************** + * lib/pthread/pthread_mutexattrgettype.c + * + * Copyright (C) 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#ifdef CONFIG_MUTEX_TYPES + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_mutexattr_gettype + * + * Description: + * Return the mutex type from the mutex attributes. + * + * Parameters: + * attr - The mutex attributes to query + * type - Location to return the mutex type + * + * Return Value: + * 0, if the mutex type was successfully return in 'type', or + * EINVAL, if any NULL pointers provided. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_mutexattr_gettype(const pthread_mutexattr_t *attr, int *type) +{ + if (attr && type) + { + *type = attr->type; + return 0; + } + return EINVAL; +} + +#endif /* CONFIG_MUTEX_TYPES */ diff --git a/nuttx/lib/pthread/pthread_mutexattrinit.c b/nuttx/lib/pthread/pthread_mutexattrinit.c new file mode 100644 index 0000000000..f815bf16c1 --- /dev/null +++ b/nuttx/lib/pthread/pthread_mutexattrinit.c @@ -0,0 +1,106 @@ +/**************************************************************************** + * lib/pthread/pthread_mutexattrinit.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_mutexattr_init + * + * Description: + * Create mutex attributes. + * + * Parameters: + * attr + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_mutexattr_init(FAR pthread_mutexattr_t *attr) +{ + int ret = OK; + + sdbg("attr=0x%p\n", attr); + + if (!attr) + { + ret = EINVAL; + } + else + { + attr->pshared = 0; +#ifdef CONFIG_MUTEX_TYPES + attr->type = PTHREAD_MUTEX_DEFAULT; +#endif + } + + sdbg("Returning %d\n", ret); + return ret; +} diff --git a/nuttx/lib/pthread/pthread_mutexattrsetpshared.c b/nuttx/lib/pthread/pthread_mutexattrsetpshared.c new file mode 100644 index 0000000000..900476fdd2 --- /dev/null +++ b/nuttx/lib/pthread/pthread_mutexattrsetpshared.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * lib/pthread/pthread_mutexattrsetpshared.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_mutexattr_setpshared + * + * Description: + * Set pshared mutex attribute. + * + * Parameters: + * attr + * pshared + * + * Return Value: + * 0 if successful. Otherwise, an error code. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_mutexattr_setpshared(FAR pthread_mutexattr_t *attr, int pshared) +{ + int ret = OK; + + sdbg("attr=0x%p pshared=%d\n", attr, pshared); + + if (!attr || (pshared != 0 && pshared != 1)) + { + ret = EINVAL; + } + else + { + attr->pshared = pshared; + } + + sdbg("Returning %d\n", ret); + return ret; +} diff --git a/nuttx/lib/pthread/pthread_mutexattrsettype.c b/nuttx/lib/pthread/pthread_mutexattrsettype.c new file mode 100644 index 0000000000..81427c757e --- /dev/null +++ b/nuttx/lib/pthread/pthread_mutexattrsettype.c @@ -0,0 +1,98 @@ +/**************************************************************************** + * lib/pthread/pthread_mutexattrsettype.c + * + * Copyright (C) 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#ifdef CONFIG_MUTEX_TYPES + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_mutexattr_settype + * + * Description: + * Set the mutex type in the mutex attributes. + * + * Parameters: + * attr - The mutex attributes in which to set the mutex type. + * type - The mutex type value to set. + * + * Return Value: + * 0, if the mutex type was successfully set in 'attr', or + * EINVAL, if 'attr' is NULL or 'type' unrecognized. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_mutexattr_settype(pthread_mutexattr_t *attr, int type) +{ + if (attr && type >= PTHREAD_MUTEX_NORMAL && type <= PTHREAD_MUTEX_RECURSIVE) + { + attr->type = type; + return OK; + } + return EINVAL; +} + +#endif /* CONFIG_MUTEX_TYPES */ diff --git a/nuttx/lib/queue/Make.defs b/nuttx/lib/queue/Make.defs new file mode 100644 index 0000000000..976e7a2b87 --- /dev/null +++ b/nuttx/lib/queue/Make.defs @@ -0,0 +1,47 @@ +############################################################################ +# lib/queue/Make.defs +# +# 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. +# +############################################################################ + +# Add the queue C files to the build + +CSRCS += sq_addlast.c sq_addfirst.c sq_addafter.c \ + sq_rem.c sq_remlast.c sq_remfirst.c sq_remafter.c + +CSRCS += dq_addlast.c dq_addfirst.c dq_addafter.c dq_addbefore.c \ + dq_rem.c dq_remlast.c dq_remfirst.c + +# Add the queue directory to the build + +DEPPATH += --dep-path queue +VPATH += :queue diff --git a/nuttx/lib/queue/dq_addafter.c b/nuttx/lib/queue/dq_addafter.c new file mode 100644 index 0000000000..bfbe0052d8 --- /dev/null +++ b/nuttx/lib/queue/dq_addafter.c @@ -0,0 +1,74 @@ +/************************************************************ + * lib/queue/dq_addafter.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: dq_addafter + * + * Description: + * dq_addafter function adds 'node' after 'qqqq' in the + * 'queue.' + * + ************************************************************/ + +void dq_addafter(FAR dq_entry_t *prev, FAR dq_entry_t *node, + dq_queue_t *queue) +{ + if (!queue->head || prev == queue->tail) + { + dq_addlast(node, queue); + } + else + { + FAR dq_entry_t *next = prev->flink; + node->blink = prev; + node->flink = next; + next->blink = node; + prev->flink = node; + } +} diff --git a/nuttx/lib/queue/dq_addbefore.c b/nuttx/lib/queue/dq_addbefore.c new file mode 100644 index 0000000000..d740ea8309 --- /dev/null +++ b/nuttx/lib/queue/dq_addbefore.c @@ -0,0 +1,69 @@ +/**************************************************************************** + * lib/queue/dq_addbefore.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: dq_addbefore + * + * Description: + * dq_addbefore adds 'node' before 'next' in 'queue' + * + ****************************************************************************/ + +void dq_addbefore(FAR dq_entry_t *next, FAR dq_entry_t *node, + dq_queue_t *queue) +{ + if (!queue->head || next == queue->head) + { + dq_addfirst(node, queue); + } + else + { + FAR dq_entry_t *prev = next->blink; + node->flink = next; + node->blink = prev; + prev->flink = node; + next->blink = node; + } +} diff --git a/nuttx/lib/queue/dq_addfirst.c b/nuttx/lib/queue/dq_addfirst.c new file mode 100644 index 0000000000..7c7312de3b --- /dev/null +++ b/nuttx/lib/queue/dq_addfirst.c @@ -0,0 +1,74 @@ +/************************************************************ + * lib/queue/dq_addfirst.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: dq_addfirst + * + * Description: + * dq_addfirst affs 'node' at the beginning of 'queue' + * + ************************************************************/ + +void dq_addfirst(FAR dq_entry_t *node, dq_queue_t *queue) +{ + node->blink = NULL; + node->flink = queue->head; + + if (!queue->head) + { + queue->head = node; + queue->tail = node; + } + else + { + queue->head->blink = node; + queue->head = node; + } +} + diff --git a/nuttx/lib/queue/dq_addlast.c b/nuttx/lib/queue/dq_addlast.c new file mode 100644 index 0000000000..745deb27d1 --- /dev/null +++ b/nuttx/lib/queue/dq_addlast.c @@ -0,0 +1,74 @@ +/************************************************************ + * lib/queue/dq_addlast.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: dq_addlast + * + * Description + * dq_addlast adds 'node' to the end of 'queue' + * + ************************************************************/ + +void dq_addlast(FAR dq_entry_t *node, dq_queue_t *queue) +{ + node->flink = NULL; + node->blink = queue->tail; + + if (!queue->head) + { + queue->head = node; + queue->tail = node; + } + else + { + queue->tail->flink = node; + queue->tail = node; + } +} + diff --git a/nuttx/lib/queue/dq_rem.c b/nuttx/lib/queue/dq_rem.c new file mode 100644 index 0000000000..218427bf84 --- /dev/null +++ b/nuttx/lib/queue/dq_rem.c @@ -0,0 +1,84 @@ +/************************************************************ + * lib/queue/dq_rem.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: dq_rem + * + * Descripton: + * dq_rem removes 'node' from 'queue' + * + ************************************************************/ + +void dq_rem(FAR dq_entry_t *node, dq_queue_t *queue) +{ + FAR dq_entry_t *prev = node->blink; + FAR dq_entry_t *next = node->flink; + + if (!prev) + { + queue->head = next; + } + else + { + prev->flink = next; + } + + if (!next) + { + queue->tail = prev; + } + else + { + next->blink = prev; + } + + node->flink = NULL; + node->blink = NULL; +} + diff --git a/nuttx/lib/queue/dq_remfirst.c b/nuttx/lib/queue/dq_remfirst.c new file mode 100644 index 0000000000..26c5fd7a67 --- /dev/null +++ b/nuttx/lib/queue/dq_remfirst.c @@ -0,0 +1,82 @@ +/************************************************************ + * lib/queue/dq_remfirst.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: dq_remfirst + * + * Description: + * dq_remfirst removes 'node' from the head of 'queue' + * + ************************************************************/ + +FAR dq_entry_t *dq_remfirst(dq_queue_t *queue) +{ + FAR dq_entry_t *ret = queue->head; + + if (ret) + { + FAR dq_entry_t *next = ret->flink; + if (!next) + { + queue->head = NULL; + queue->tail = NULL; + } + else + { + queue->head = next; + next->blink = NULL; + } + + ret->flink = NULL; + ret->blink = NULL; + } + + return ret; +} + diff --git a/nuttx/lib/queue/dq_remlast.c b/nuttx/lib/queue/dq_remlast.c new file mode 100644 index 0000000000..35adc73e2d --- /dev/null +++ b/nuttx/lib/queue/dq_remlast.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * lib/queue/dq_remlast.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/***************************************************(************************ + * Name: dq_remlast + * + * Description: + * dq_remlast removes the last entry from 'queue' + * + ****************************************************************************/ + +FAR dq_entry_t *dq_remlast(dq_queue_t *queue) +{ + FAR dq_entry_t *ret = queue->tail; + + if (ret) + { + FAR dq_entry_t *prev = ret->blink; + if (!prev) + { + queue->head = NULL; + queue->tail = NULL; + } + else + { + queue->tail = prev; + prev->flink = NULL; + } + + ret->flink = NULL; + ret->blink = NULL; + } + + return ret; +} + diff --git a/nuttx/lib/queue/sq_addafter.c b/nuttx/lib/queue/sq_addafter.c new file mode 100644 index 0000000000..965ac28444 --- /dev/null +++ b/nuttx/lib/queue/sq_addafter.c @@ -0,0 +1,71 @@ +/************************************************************ + * lib/queue/sq_addafter.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: sq_addafter.c + * + * Description: + * The sq_addafter function adds 'node' after 'prev' in the + * 'queue.' + * + ************************************************************/ + +void sq_addafter(FAR sq_entry_t *prev, FAR sq_entry_t *node, + sq_queue_t *queue) +{ + if (!queue->head || prev == queue->tail) + { + sq_addlast(node, queue); + } + else + { + node->flink = prev->flink; + prev->flink = node; + } +} diff --git a/nuttx/lib/queue/sq_addfirst.c b/nuttx/lib/queue/sq_addfirst.c new file mode 100644 index 0000000000..8fc8e06199 --- /dev/null +++ b/nuttx/lib/queue/sq_addfirst.c @@ -0,0 +1,67 @@ +/************************************************************ + * lib/queue/sq_addfirst.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: sq_addfirst + * + * Description: + * The sq_addfirst function places the 'node' at the head + * of the 'queue' + * + ************************************************************/ + +void sq_addfirst(FAR sq_entry_t *node, sq_queue_t *queue) +{ + node->flink = queue->head; + if (!queue->head) + { + queue->tail = node; + } + queue->head = node; +} diff --git a/nuttx/lib/queue/sq_addlast.c b/nuttx/lib/queue/sq_addlast.c new file mode 100644 index 0000000000..f9f9625cc0 --- /dev/null +++ b/nuttx/lib/queue/sq_addlast.c @@ -0,0 +1,72 @@ +/************************************************************ + * lib/queue/sq_addlast.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: sq_addlast + * + * Description: + * The sq_addlast function places the 'node' at the tail of + * the 'queue' + ************************************************************/ + +void sq_addlast(FAR sq_entry_t *node, sq_queue_t *queue) +{ + node->flink = NULL; + if (!queue->head) + { + queue->head = node; + queue->tail = node; + } + else + { + queue->tail->flink = node; + queue->tail = node; + } +} + diff --git a/nuttx/lib/queue/sq_rem.c b/nuttx/lib/queue/sq_rem.c new file mode 100644 index 0000000000..6ba52354d4 --- /dev/null +++ b/nuttx/lib/queue/sq_rem.c @@ -0,0 +1,83 @@ +/************************************************************ + * lib/queue/sq_rem.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * public Functions + ************************************************************/ + +/************************************************************ + * Name: sq_rem + * + * Description: + * sq_rem removes a 'node' for 'queue.' + * + ************************************************************/ + +void sq_rem(FAR sq_entry_t *node, sq_queue_t *queue) +{ + if (queue->head && node) + { + if (node == queue->head) + { + queue->head = node->flink; + if (node == queue->tail) + { + queue->tail = NULL; + } + } + else + { + FAR sq_entry_t *prev; + for(prev = (FAR sq_entry_t*)queue->head; + prev && prev->flink != node; + prev = prev->flink); + + if (prev) + { + sq_remafter(prev, queue); + } + } + } +} diff --git a/nuttx/lib/queue/sq_remafter.c b/nuttx/lib/queue/sq_remafter.c new file mode 100644 index 0000000000..4dcfb06e44 --- /dev/null +++ b/nuttx/lib/queue/sq_remafter.c @@ -0,0 +1,79 @@ +/************************************************************ + * lib/queue/sq_remafter.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: + * + * Description: + * sq_remafter removes the entry following 'node; from the + * 'queue' Returns a reference to the removed entry. + * + ************************************************************/ + +FAR sq_entry_t *sq_remafter(FAR sq_entry_t *node, sq_queue_t *queue) +{ + FAR sq_entry_t *ret = node->flink; + if (queue->head && ret) + { + if (queue->tail == ret) + { + queue->tail = node; + node->flink = NULL; + } + else + { + node->flink = ret->flink; + } + + ret->flink = NULL; + } + + return ret; +} + diff --git a/nuttx/lib/queue/sq_remfirst.c b/nuttx/lib/queue/sq_remfirst.c new file mode 100644 index 0000000000..43df6de417 --- /dev/null +++ b/nuttx/lib/queue/sq_remfirst.c @@ -0,0 +1,76 @@ +/************************************************************ + * lib/queue/sq_remfirst.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: sq_remfirst + * + * Description: + * sq_remfirst function removes the first entry from + * 'queue' + * + ************************************************************/ + +FAR sq_entry_t *sq_remfirst(sq_queue_t *queue) +{ + FAR sq_entry_t *ret = queue->head; + + if (ret) + { + queue->head = ret->flink; + if (!queue->head) + { + queue->tail = NULL; + } + + ret->flink = NULL; + } + + return ret; +} + diff --git a/nuttx/lib/queue/sq_remlast.c b/nuttx/lib/queue/sq_remlast.c new file mode 100644 index 0000000000..92cdbde985 --- /dev/null +++ b/nuttx/lib/queue/sq_remlast.c @@ -0,0 +1,87 @@ +/************************************************************ + * lib/queue/sq_remlast.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include + +/************************************************************ + * Public Functions + ************************************************************/ + +/************************************************************ + * Name: sq_remlast + * + * Description: + * Removes the last entry in a singly-linked queue. + * + ************************************************************/ + +FAR sq_entry_t *sq_remlast(sq_queue_t *queue) +{ + FAR sq_entry_t *ret = queue->tail; + + if (ret) + { + if (queue->head == queue->tail) + { + queue->head = NULL; + queue->tail = NULL; + } + else + { + FAR sq_entry_t *prev; + for(prev = queue->head; + prev && prev->flink != ret; + prev = prev->flink); + + if (prev) + { + prev->flink = NULL; + queue->tail = prev; + } + } + + ret->flink = NULL; + } + + return ret; +} diff --git a/nuttx/lib/sched/Make.defs b/nuttx/lib/sched/Make.defs new file mode 100644 index 0000000000..f398b755e0 --- /dev/null +++ b/nuttx/lib/sched/Make.defs @@ -0,0 +1,43 @@ +############################################################################ +# lib/sched/Make.defs +# +# 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. +# +############################################################################ + +# Add the sched C files to the build + +CSRCS += sched_getprioritymax.c sched_getprioritymin.c + +# Add the sched directory to the build + +DEPPATH += --dep-path sched +VPATH += :sched diff --git a/nuttx/lib/sched/sched_getprioritymax.c b/nuttx/lib/sched/sched_getprioritymax.c new file mode 100644 index 0000000000..14b368dfc0 --- /dev/null +++ b/nuttx/lib/sched/sched_getprioritymax.c @@ -0,0 +1,100 @@ +/************************************************************************ + * lib/sched/sched_getprioritymax.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include + +/************************************************************************ + * Definitions + ************************************************************************/ + +/************************************************************************ + * Private Type Declarations + ************************************************************************/ + +/************************************************************************ + * Global Variables + ************************************************************************/ + +/************************************************************************ + * Private Variables + ************************************************************************/ + +/************************************************************************ + * Private Function Prototypes + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: ched_get_priority_max + * + * Description: + * This function returns the value of the highest possible + * task priority for a specified scheduling policy. + * + * Inputs: + * policy - Scheduling policy requested. + * + * Return Value: + * The maximum priority value or -1 (ERROR) + * (errno is not set) + * + * Assumptions: + * + ************************************************************************/ + +int sched_get_priority_max(int policy) +{ + if (policy != SCHED_FIFO && policy != SCHED_RR) + { + return ERROR; + } + else + { + return SCHED_PRIORITY_MAX; + } +} diff --git a/nuttx/lib/sched/sched_getprioritymin.c b/nuttx/lib/sched/sched_getprioritymin.c new file mode 100644 index 0000000000..86410cb0f6 --- /dev/null +++ b/nuttx/lib/sched/sched_getprioritymin.c @@ -0,0 +1,100 @@ +/************************************************************************ + * lib/sched/sched_getprioritymin.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include + +/************************************************************************ + * Definitions + ************************************************************************/ + +/************************************************************************ + * Private Type Declarations + ************************************************************************/ + +/************************************************************************ + * Global Variables + ************************************************************************/ + +/************************************************************************ + * Private Variables + ************************************************************************/ + +/************************************************************************ + * Private Function Prototypes + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: sched_get_priority_min + * + * Description: + * This function returns the value of the lowest possible + * task priority for a specified scheduling policy. + * + * Inputs: + * policy - Scheduling policy requested. + * + * Return Value: + * The minimum priority value or -1 (ERROR) + * (errno is not set) + * + * Assumptions: + * + ************************************************************************/ + +int sched_get_priority_min(int policy) +{ + if (policy != SCHED_FIFO && policy != SCHED_RR) + { + return ERROR; + } + else + { + return SCHED_PRIORITY_MIN; + } +} diff --git a/nuttx/lib/semaphore/Make.defs b/nuttx/lib/semaphore/Make.defs new file mode 100644 index 0000000000..fdc0fe7d54 --- /dev/null +++ b/nuttx/lib/semaphore/Make.defs @@ -0,0 +1,43 @@ +############################################################################ +# lib/semaphore/Make.defs +# +# 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. +# +############################################################################ + +# Add the semaphore C files to the build + +CSRCS += sem_init.c sem_getvalue.c + +# Add the semaphore directory to the build + +DEPPATH += --dep-path semaphore +VPATH += :semaphore diff --git a/nuttx/lib/semaphore/sem_getvalue.c b/nuttx/lib/semaphore/sem_getvalue.c new file mode 100644 index 0000000000..31c6bb7e06 --- /dev/null +++ b/nuttx/lib/semaphore/sem_getvalue.c @@ -0,0 +1,108 @@ +/**************************************************************************** + * lib/semaphore/sem_getvalue.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sem_getvalue + * + * Description: + * This function updates the location referenced by 'sval' argument to + * have the value of the semaphore referenced by 'sem' without effecting + * the state of the semaphore. The updated value represents the actual + * semaphore value that occurred at some unspecified time during the call, + * but may not reflect the actual value of the semaphore when it is + * returned to the calling task. + * + * If 'sem' is locked, the value return by sem_getvalue() will either be + * zero or a negative number whose absolute value represents the number + * of tasks waiting for the semaphore. + * + * Parameters: + * sem - Semaphore descriptor + * sval - Buffer by which the value is returned + * + * Return Value: + * 0 (OK), or -1 (ERROR) if unsuccessful + * + * Assumptions: + * + ****************************************************************************/ + +int sem_getvalue(FAR sem_t *sem, FAR int *sval) +{ + if (sem && sval) + { + *sval = sem->semcount; + return OK; + } + else + { + set_errno(EINVAL); + return ERROR; + } +} diff --git a/nuttx/lib/semaphore/sem_init.c b/nuttx/lib/semaphore/sem_init.c new file mode 100644 index 0000000000..bc14415f97 --- /dev/null +++ b/nuttx/lib/semaphore/sem_init.c @@ -0,0 +1,125 @@ +/**************************************************************************** + * lib/sem/sem_init.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sem_init + * + * Description: + * This function initializes the UNAMED semaphore sem. Following a + * successful call to sem_init(), the semaophore may be used in subsequent + * calls to sem_wait(), sem_post(), and sem_trywait(). The semaphore + * remains usable until it is destroyed. + * + * Only sem itself may be used for performing synchronization. The result + * of referring to copies of sem in calls to sem_wait(), sem_trywait(), + * sem_post(), and sem_destroy() is undefined. + * + * Parameters: + * sem - Semaphore to be initialized + * pshared - Process sharing (not used) + * value - Semaphore initialization value + * + * Return Value: + * 0 (OK), or -1 (ERROR) if unsuccessful. + * + * Assumptions: + * + ****************************************************************************/ + +int sem_init(FAR sem_t *sem, int pshared, unsigned int value) +{ + /* Verify that a semaphore was provided and the count is within the valid + * range. + */ + + if (sem && value <= SEM_VALUE_MAX) + { + /* Initialize the seamphore count */ + + sem->semcount = (int16_t)value; + + /* Initialize to support priority inheritance */ + +#ifdef CONFIG_PRIORITY_INHERITANCE +# if CONFIG_SEM_PREALLOCHOLDERS > 0 + sem->hhead = NULL; +# else + sem->holder.htcb = NULL; + sem->holder.counts = 0; +# endif +#endif + return OK; + } + else + { + set_errno(EINVAL); + return ERROR; + } +} diff --git a/nuttx/lib/signal/Make.defs b/nuttx/lib/signal/Make.defs new file mode 100644 index 0000000000..e27da9b2e8 --- /dev/null +++ b/nuttx/lib/signal/Make.defs @@ -0,0 +1,47 @@ +############################################################################ +# lib/signal/Make.defs +# +# 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. +# +############################################################################ + +ifneq ($(CONFIG_DISABLE_SIGNALS),y) + +# Add the signal C files to the build + +CSRCS += sig_emptyset.c sig_fillset.c sig_addset.c sig_delset.c sig_ismember.c + +# Add the signal directory to the build + +DEPPATH += --dep-path signal +VPATH += :signal + +endif diff --git a/nuttx/lib/signal/sig_addset.c b/nuttx/lib/signal/sig_addset.c new file mode 100644 index 0000000000..19ba0cb6b6 --- /dev/null +++ b/nuttx/lib/signal/sig_addset.c @@ -0,0 +1,100 @@ +/**************************************************************************** + * lib/signal/sig_addset.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sigaddset + * + * Description: + * This function adds the signal specified by signo to the signal set + * specified by set. + * + * Parameters: + * set - Signal set to add signal to + * signo - Signal to add + * + * Return Value: + * 0 (OK), or -1 (ERROR) if the signal number is invalid. + * + * Assumptions: + * + ****************************************************************************/ + +int sigaddset(FAR sigset_t *set, int signo) +{ + int ret = ERROR; + + /* Verify the signal */ + + if (GOOD_SIGNO(signo)) + { + /* Add the signal to the set */ + + *set |= SIGNO2SET(signo); + ret = OK; + } + + return ret; +} + diff --git a/nuttx/lib/signal/sig_delset.c b/nuttx/lib/signal/sig_delset.c new file mode 100644 index 0000000000..1c661d37f6 --- /dev/null +++ b/nuttx/lib/signal/sig_delset.c @@ -0,0 +1,100 @@ +/**************************************************************************** + * lib/signal/sig_delset.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sigdelset + * + * Description: + * This function deletes the signal specified by signo from the signal + * set specified by the 'set' argument. + * + * Parameters: + * set - Signal set to delete the signal from + * signo - Signal to delete + * + * Return Value: + * 0 (OK), or -1 (ERROR) if the signal number is invalid. + * + * Assumptions: + * + ****************************************************************************/ + +int sigdelset(FAR sigset_t *set, int signo) +{ + int ret = ERROR; + + /* Verify the signal */ + + if (GOOD_SIGNO(signo)) + { + /* Delete the signal to the set */ + + *set &= ~SIGNO2SET(signo); + ret = OK; + } + + return ret; +} + diff --git a/nuttx/lib/signal/sig_emptyset.c b/nuttx/lib/signal/sig_emptyset.c new file mode 100644 index 0000000000..ac0c6b3e89 --- /dev/null +++ b/nuttx/lib/signal/sig_emptyset.c @@ -0,0 +1,88 @@ +/**************************************************************************** + * lib/signal/sig_emptyset.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sigemptyset + * + * Description: + * This function initializes the signal set specified by set such that all + * signals are excluded. + * + * Parameters: + * set - Signal set to initalize + * + * Return Value: + * 0 (OK), or -1 (ERROR) if the signal set cannot be initialized. + * + * Assumptions: + * + ****************************************************************************/ + +int sigemptyset(FAR sigset_t *set) +{ + *set = NULL_SIGNAL_SET; + return OK; +} + diff --git a/nuttx/lib/signal/sig_fillset.c b/nuttx/lib/signal/sig_fillset.c new file mode 100644 index 0000000000..8697d7577f --- /dev/null +++ b/nuttx/lib/signal/sig_fillset.c @@ -0,0 +1,88 @@ +/**************************************************************************** + * lib/signal/sig_fillset.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Publics Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sigfillset + * + * Description: + * This function initializes the signal set specified by set such that all + * signals are included. + * + * Parameters: + * set - Signal set to initalize + * + * Return Value: + * 0 (OK), or -1 (ERROR) if the signal set cannot be initialized. + * + * Assumptions: + * + ****************************************************************************/ + +int sigfillset(FAR sigset_t *set) +{ + *set = ALL_SIGNAL_SET; + return OK; +} + diff --git a/nuttx/lib/signal/sig_ismember.c b/nuttx/lib/signal/sig_ismember.c new file mode 100644 index 0000000000..c5bb091b7b --- /dev/null +++ b/nuttx/lib/signal/sig_ismember.c @@ -0,0 +1,101 @@ +/**************************************************************************** + * lib/signal/sig_ismember.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sigismember + * + * Description: + * This function tests whether the signal specified by signo is a member + * of the set specified by set. + * + * Parameters: + * set - Signal set to test + * signo - Signal to test for + * + * Return Value: + * 1 (true), if the specified signal is a member of the set, + * 0 (OK or FALSE), if it is not, or + * -1 (ERROR) if the signal number is invalid. + * + * Assumptions: + * + ****************************************************************************/ + +int sigismember(FAR const sigset_t *set, int signo) +{ + int ret = ERROR; + + /* Verify the signal */ + + if (GOOD_SIGNO(signo)) + { + /* Check if the signal is in the set */ + + ret = ((*set & SIGNO2SET(signo)) != 0); + } + + return ret; +} + diff --git a/nuttx/lib/stdio/Make.defs b/nuttx/lib/stdio/Make.defs new file mode 100644 index 0000000000..f88a5edd9e --- /dev/null +++ b/nuttx/lib/stdio/Make.defs @@ -0,0 +1,73 @@ +############################################################################ +# lib/stdio/Make.defs +# +# 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. +# +############################################################################ + +# Add the stdio C files to the build + +CSRCS += lib_fileno.c lib_printf.c lib_rawprintf.c lib_lowprintf.c \ + lib_sprintf.c lib_asprintf.c lib_snprintf.c lib_libsprintf.c \ + lib_vsprintf.c lib_avsprintf.c lib_vsnprintf.c lib_libvsprintf.c \ + lib_meminstream.c lib_memoutstream.c lib_lowinstream.c \ + lib_lowoutstream.c lib_zeroinstream.c lib_nullinstream.c \ + lib_nulloutstream.c lib_sscanf.c + +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) +CSRCS += lib_rawinstream.c lib_rawoutstream.c +ifneq ($(CONFIG_NFILE_STREAMS),0) +CSRCS += lib_fopen.c lib_fclose.c lib_fread.c lib_libfread.c lib_fseek.c \ + lib_ftell.c lib_fsetpos.c lib_fgetpos.c lib_fgetc.c lib_fgets.c \ + lib_gets.c lib_fwrite.c lib_libfwrite.c lib_fflush.c \ + lib_libflushall.c lib_libfflush.c lib_rdflush.c lib_wrflush.c \ + lib_fputc.c lib_puts.c lib_fputs.c lib_ungetc.c lib_vprintf.c \ + lib_fprintf.c lib_vfprintf.c lib_stdinstream.c lib_stdoutstream.c \ + lib_perror.c +endif +endif + +ifeq ($(CONFIG_SYSLOG),y) +CSRCS += lib_syslogstream.c +endif + +ifeq ($(CONFIG_LIBC_FLOATINGPOINT),y) +CSRCS += lib_dtoa.c +endif + +ifeq ($(CONFIG_STDIO_LINEBUFFER),y) +CSRCS += lib_libnoflush.c +endif + +# Add the stdio directory to the build + +DEPPATH += --dep-path stdio +VPATH += :stdio diff --git a/nuttx/lib/stdio/lib_asprintf.c b/nuttx/lib/stdio/lib_asprintf.c new file mode 100644 index 0000000000..84aaafa462 --- /dev/null +++ b/nuttx/lib/stdio/lib_asprintf.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * lib/stdio/lib_asprintf.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: asprintf + * + * Description: + * This function is similar to sprintf, except that it dynamically + * allocates a string (as with malloc) to hold the output, instead of + * putting the output in a buffer you allocate in advance. The ptr + * argument should be the address of a char * object, and a successful + * call to asprintf stores a pointer to the newly allocated string at that + * location. + * + * Returned Value: + * The returned value is the number of characters allocated for the buffer, + * or less than zero if an error occurred. Usually this means that the buffer + * could not be allocated. + * + ****************************************************************************/ + +int asprintf (FAR char **ptr, const char *fmt, ...) +{ + va_list ap; + int ret; + + /* Let avsprintf do all of the work */ + + va_start(ap, fmt); + ret = avsprintf(ptr, fmt, ap); + va_end(ap); + + return ret; +} diff --git a/nuttx/lib/stdio/lib_avsprintf.c b/nuttx/lib/stdio/lib_avsprintf.c new file mode 100644 index 0000000000..8561b97c21 --- /dev/null +++ b/nuttx/lib/stdio/lib_avsprintf.c @@ -0,0 +1,146 @@ +/**************************************************************************** + * lib/stdio/lib_avsprintf.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: avsprintf + * + * Description: + * This function is similar to vsprintf, except that it dynamically + * allocates a string (as with malloc) to hold the output, instead of + * putting the output in a buffer you allocate in advance. The ptr + * argument should be the address of a char * object, and a successful + * call to avsprintf stores a pointer to the newly allocated string at that + * location. + * + * Returned Value: + * The returned value is the number of characters allocated for the buffer, + * or less than zero if an error occurred. Usually this means that the buffer + * could not be allocated. + * + ****************************************************************************/ + +int avsprintf(FAR char **ptr, const char *fmt, va_list ap) +{ + struct lib_outstream_s nulloutstream; + struct lib_memoutstream_s memoutstream; + FAR char *buf; + int nbytes; + + DEBUGASSERT(ptr && fmt); + + /* First, use a nullstream to get the size of the buffer. The number + * of bytes returned may or may not include the null terminator. + */ + + lib_nulloutstream(&nulloutstream); + nbytes = lib_vsprintf((FAR struct lib_outstream_s *)&nulloutstream, fmt, ap); + + /* Then allocate a buffer to hold that number of characters, adding one + * for the null terminator. + */ + + buf = (FAR char *)malloc(nulloutstream.nput + 1); + if (!buf) + { + return ERROR; + } + + /* Initialize a memory stream to write into the allocated buffer. The + * memory stream will reserve one byte at the end of the buffer for the + * null terminator and will not report this in the number of output bytes. + */ + + lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, + buf, nulloutstream.nput + 1); + + /* Then let lib_vsprintf do it's real thing */ + + nbytes = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, fmt, ap); + + /* Return a pointer to the string to the caller. NOTE: the memstream put() + * method has already added the NUL terminator to the end of the string (not + * included in the nput count). + * + * Hmmm.. looks like the memory would be stranded if lib_vsprintf() returned + * an error. Does that ever happen? + */ + + DEBUGASSERT(nbytes < 0 || nbytes == nulloutstream.nput); + *ptr = buf; + return nbytes; +} diff --git a/nuttx/lib/stdio/lib_dtoa.c b/nuttx/lib/stdio/lib_dtoa.c new file mode 100644 index 0000000000..b8c7db9803 --- /dev/null +++ b/nuttx/lib/stdio/lib_dtoa.c @@ -0,0 +1,1641 @@ +/**************************************************************************** + * lib/stdio/lib_dtoa.c + * + * This file was ported to NuttX by Yolande Cates. + * + * Copyright (c) 1990, 1993 + * The Regents of the University of California. All rights reserved. + * + * This code is derived from software contributed to Berkeley by + * Chris Torek. + * + * 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * This product includes software developed by the University of + * California, Berkeley and its contributors. + * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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 "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifdef Unsigned_Shifts +# define Sign_Extend(a,b) if (b < 0) a |= 0xffff0000; +#else +# define Sign_Extend(a,b) /* no-op */ +#endif + +#ifdef CONFIG_ENDIAN_BIG +# define word0(x) ((uint32_t *)&x)[0] +# define word1(x) ((uint32_t *)&x)[1] +#else +# define word0(x) ((uint32_t *)&x)[1] +# define word1(x) ((uint32_t *)&x)[0] +#endif + +#ifdef CONFIG_ENDIAN_BIG +# define Storeinc(a,b,c) (((unsigned short *)a)[0] = (unsigned short)b, \ + ((unsigned short *)a)[1] = (unsigned short)c, a++) +#else +# define Storeinc(a,b,c) (((unsigned short *)a)[1] = (unsigned short)b, \ + ((unsigned short *)a)[0] = (unsigned short)c, a++) +#endif + +#define Exp_shift 20 +#define Exp_shift1 20 +#define Exp_msk1 0x100000 +#define Exp_msk11 0x100000 +#define Exp_mask 0x7ff00000 +#define P 53 +#define Bias 1023 +#define IEEE_Arith +#define Emin (-1022) +#define Exp_1 0x3ff00000 +#define Exp_11 0x3ff00000 +#define Ebits 11 +#define Frac_mask 0xfffff +#define Frac_mask1 0xfffff +#define Ten_pmax 22 +#define Bletch 0x10 +#define Bndry_mask 0xfffff +#define Bndry_mask1 0xfffff +#define LSB 1 +#define Sign_bit 0x80000000 +#define Log2P 1 +#define Tiny0 0 +#define Tiny1 1 +#define Quick_max 14 +#define Int_max 14 +#define Infinite(x) (word0(x) == 0x7ff00000) /* sufficient test for here */ + +#define Kmax 15 + +#define Bcopy(x,y) memcpy((char *)&x->sign, (char *)&y->sign, \ + y->wds*sizeof(long) + 2*sizeof(int)) + +/**************************************************************************** + * Private Type Definitions + ****************************************************************************/ + +struct Bigint +{ + struct Bigint *next; + int k, maxwds, sign, wds; + unsigned long x[1]; +}; + +typedef struct Bigint Bigint; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static Bigint *freelist[Kmax + 1]; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static Bigint *Balloc(int k) +{ + int x; + Bigint *rv; + + if ((rv = freelist[k])) + { + freelist[k] = rv->next; + } + else + { + x = 1 << k; + rv = (Bigint *)lib_malloc(sizeof(Bigint) + (x - 1) * sizeof(long)); + rv->k = k; + rv->maxwds = x; + } + rv->sign = rv->wds = 0; + return rv; +} + +static void Bfree(Bigint * v) +{ + if (v) + { + v->next = freelist[v->k]; + freelist[v->k] = v; + } +} + +/* multiply by m and add a */ + +static Bigint *multadd(Bigint * b, int m, int a) +{ + int i, wds; + unsigned long *x, y; +#ifdef Pack_32 + unsigned long xi, z; +#endif + Bigint *b1; + + wds = b->wds; + x = b->x; + i = 0; + do + { +#ifdef Pack_32 + xi = *x; + y = (xi & 0xffff) * m + a; + z = (xi >> 16) * m + (y >> 16); + a = (int)(z >> 16); + *x++ = (z << 16) + (y & 0xffff); +#else + y = *x * m + a; + a = (int)(y >> 16); + *x++ = y & 0xffff; +#endif + } + while (++i < wds); + if (a) + { + if (wds >= b->maxwds) + { + b1 = Balloc(b->k + 1); + Bcopy(b1, b); + Bfree(b); + b = b1; + } + b->x[wds++] = a; + b->wds = wds; + } + return b; +} + +static int hi0bits(unsigned long x) +{ + int k = 0; + + if (!(x & 0xffff0000)) + { + k = 16; + x <<= 16; + } + + if (!(x & 0xff000000)) + { + k += 8; + x <<= 8; + } + + if (!(x & 0xf0000000)) + { + k += 4; + x <<= 4; + } + + if (!(x & 0xc0000000)) + { + k += 2; + x <<= 2; + } + + if (!(x & 0x80000000)) + { + k++; + if (!(x & 0x40000000)) + { + return 32; + } + } + return k; +} + +static int lo0bits(unsigned long *y) +{ + int k; + unsigned long x = *y; + + if (x & 7) + { + if (x & 1) + { + return 0; + } + if (x & 2) + { + *y = x >> 1; + return 1; + } + *y = x >> 2; + return 2; + } + + k = 0; + if (!(x & 0xffff)) + { + k = 16; + x >>= 16; + } + + if (!(x & 0xff)) + { + k += 8; + x >>= 8; + } + + if (!(x & 0xf)) + { + k += 4; + x >>= 4; + } + + if (!(x & 0x3)) + { + k += 2; + x >>= 2; + } + + if (!(x & 1)) + { + k++; + x >>= 1; + if (!x & 1) + { + return 32; + } + } + *y = x; + return k; +} + +static Bigint *i2b(int i) +{ + Bigint *b; + + b = Balloc(1); + b->x[0] = i; + b->wds = 1; + return b; +} + +static Bigint *mult(Bigint * a, Bigint * b) +{ + Bigint *c; + int k, wa, wb, wc; + unsigned long carry, y, z; + unsigned long *x, *xa, *xae, *xb, *xbe, *xc, *xc0; +#ifdef Pack_32 + uint32_t z2; +#endif + + if (a->wds < b->wds) + { + c = a; + a = b; + b = c; + } + + k = a->k; + wa = a->wds; + wb = b->wds; + wc = wa + wb; + if (wc > a->maxwds) + { + k++; + } + c = Balloc(k); + for (x = c->x, xa = x + wc; x < xa; x++) + { + *x = 0; + } + xa = a->x; + xae = xa + wa; + xb = b->x; + xbe = xb + wb; + xc0 = c->x; +#ifdef Pack_32 + for (; xb < xbe; xb++, xc0++) + { + if ((y = *xb & 0xffff)) + { + x = xa; + xc = xc0; + carry = 0; + do + { + z = (*x & 0xffff) * y + (*xc & 0xffff) + carry; + carry = z >> 16; + z2 = (*x++ >> 16) * y + (*xc >> 16) + carry; + carry = z2 >> 16; + Storeinc(xc, z2, z); + } + while (x < xae); + *xc = carry; + } + if ((y = *xb >> 16)) + { + x = xa; + xc = xc0; + carry = 0; + z2 = *xc; + do + { + z = (*x & 0xffff) * y + (*xc >> 16) + carry; + carry = z >> 16; + Storeinc(xc, z, z2); + z2 = (*x++ >> 16) * y + (*xc & 0xffff) + carry; + carry = z2 >> 16; + } + while (x < xae); + *xc = z2; + } + } +#else + for (; xb < xbe; xc0++) + { + if ((y = *xb++)) + { + x = xa; + xc = xc0; + carry = 0; + do + { + z = *x++ * y + *xc + carry; + carry = z >> 16; + *xc++ = z & 0xffff; + } + while (x < xae); + *xc = carry; + } + } +#endif + for (xc0 = c->x, xc = xc0 + wc; wc > 0 && !*--xc; --wc); + c->wds = wc; + return c; +} + +static Bigint *p5s; + +static Bigint *pow5mult(Bigint * b, int k) +{ + Bigint *b1, *p5, *p51; + int i; + static int p05[3] = { 5, 25, 125 }; + + if ((i = k & 3)) + b = multadd(b, p05[i - 1], 0); + + if (!(k >>= 2)) + { + return b; + } + + if (!(p5 = p5s)) + { + /* first time */ + p5 = p5s = i2b(625); + p5->next = 0; + } + + for (;;) + { + if (k & 1) + { + b1 = mult(b, p5); + Bfree(b); + b = b1; + } + if (!(k >>= 1)) + { + break; + } + + if (!(p51 = p5->next)) + { + p51 = p5->next = mult(p5, p5); + p51->next = 0; + } + p5 = p51; + } + return b; +} + +static Bigint *lshift(Bigint * b, int k) +{ + int i, k1, n, n1; + Bigint *b1; + unsigned long *x, *x1, *xe, z; + +#ifdef Pack_32 + n = k >> 5; +#else + n = k >> 4; +#endif + k1 = b->k; + n1 = n + b->wds + 1; + for (i = b->maxwds; n1 > i; i <<= 1) + { + k1++; + } + b1 = Balloc(k1); + x1 = b1->x; + for (i = 0; i < n; i++) + { + *x1++ = 0; + } + x = b->x; + xe = x + b->wds; +#ifdef Pack_32 + if (k &= 0x1f) + { + k1 = 32 - k; + z = 0; + do + { + *x1++ = *x << k | z; + z = *x++ >> k1; + } + while (x < xe); + if ((*x1 = z)) + { + ++n1; + } + } +#else + if (k &= 0xf) + { + k1 = 16 - k; + z = 0; + do + { + *x1++ = ((*x << k) & 0xffff) | z; + z = *x++ >> k1; + } + while (x < xe); + if ((*x1 = z)) + { + ++n1; + } + } +#endif + else + do + { + *x1++ = *x++; + } + while (x < xe); + b1->wds = n1 - 1; + Bfree(b); + return b1; +} + +static int cmp(Bigint * a, Bigint * b) +{ + unsigned long *xa, *xa0, *xb, *xb0; + int i, j; + + i = a->wds; + j = b->wds; +#ifdef CONFIG_DEBUG_LIB + if (i > 1 && !a->x[i - 1]) + { + ldbg("cmp called with a->x[a->wds-1] == 0\n"); + } + if (j > 1 && !b->x[j - 1]) + { + ldbg("cmp called with b->x[b->wds-1] == 0\n"); + } +#endif + if (i -= j) + return i; + xa0 = a->x; + xa = xa0 + j; + xb0 = b->x; + xb = xb0 + j; + for (;;) + { + if (*--xa != *--xb) + return *xa < *xb ? -1 : 1; + if (xa <= xa0) + break; + } + return 0; +} + +static Bigint *diff(Bigint * a, Bigint * b) +{ + Bigint *c; + int i, wa, wb; + long borrow, y; /* We need signed shifts here. */ + unsigned long *xa, *xae, *xb, *xbe, *xc; +#ifdef Pack_32 + int32_t z; +#endif + + i = cmp(a, b); + if (!i) + { + c = Balloc(0); + c->wds = 1; + c->x[0] = 0; + return c; + } + if (i < 0) + { + c = a; + a = b; + b = c; + i = 1; + } + else + i = 0; + c = Balloc(a->k); + c->sign = i; + wa = a->wds; + xa = a->x; + xae = xa + wa; + wb = b->wds; + xb = b->x; + xbe = xb + wb; + xc = c->x; + borrow = 0; +#ifdef Pack_32 + do + { + y = (*xa & 0xffff) - (*xb & 0xffff) + borrow; + borrow = y >> 16; + Sign_Extend(borrow, y); + z = (*xa++ >> 16) - (*xb++ >> 16) + borrow; + borrow = z >> 16; + Sign_Extend(borrow, z); + Storeinc(xc, z, y); + } + while (xb < xbe); + while (xa < xae) + { + y = (*xa & 0xffff) + borrow; + borrow = y >> 16; + Sign_Extend(borrow, y); + z = (*xa++ >> 16) + borrow; + borrow = z >> 16; + Sign_Extend(borrow, z); + Storeinc(xc, z, y); + } +#else + do + { + y = *xa++ - *xb++ + borrow; + borrow = y >> 16; + Sign_Extend(borrow, y); + *xc++ = y & 0xffff; + } + while (xb < xbe); + while (xa < xae) + { + y = *xa++ + borrow; + borrow = y >> 16; + Sign_Extend(borrow, y); + *xc++ = y & 0xffff; + } +#endif + while (!*--xc) + wa--; + c->wds = wa; + return c; +} + +static Bigint *d2b(double d, int *e, int *bits) +{ + Bigint *b; + int de, i, k; + unsigned long *x, y, z; + +#ifdef Pack_32 + b = Balloc(1); +#else + b = Balloc(2); +#endif + x = b->x; + + z = word0(d) & Frac_mask; + word0(d) &= 0x7fffffff; /* clear sign bit, which we ignore */ + if ((de = (int)(word0(d) >> Exp_shift))) + z |= Exp_msk1; +#ifdef Pack_32 + if ((y = word1(d))) + { + if ((k = lo0bits(&y))) + { + x[0] = y | z << (32 - k); + z >>= k; + } + else + x[0] = y; + i = b->wds = (x[1] = z) ? 2 : 1; + } + else + { +#ifdef CONFIG_DEBUG_LIB + if (!z) + { + ldbg("Zero passed to d2b\n"); + } +#endif + k = lo0bits(&z); + x[0] = z; + i = b->wds = 1; + k += 32; + } +#else + if ((y = word1(d))) + { + if ((k = lo0bits(&y))) + if (k >= 16) + { + x[0] = y | ((z << (32 - k)) & 0xffff); + x[1] = z >> (k - 16) & 0xffff; + x[2] = z >> k; + i = 2; + } + else + { + x[0] = y & 0xffff; + x[1] = (y >> 16) | ((z << (16 - k)) & 0xffff); + x[2] = z >> k & 0xffff; + x[3] = z >> (k + 16); + i = 3; + } + else + { + x[0] = y & 0xffff; + x[1] = y >> 16; + x[2] = z & 0xffff; + x[3] = z >> 16; + i = 3; + } + } + else + { +#ifdef CONFIG_DEBUG_LIB + if (!z) + { + ldbg("Zero passed to d2b\n"); + } +#endif + k = lo0bits(&z); + if (k >= 16) + { + x[0] = z; + i = 0; + } + else + { + x[0] = z & 0xffff; + x[1] = z >> 16; + i = 1; + } + k += 32; + } + while (!x[i]) + --i; + b->wds = i + 1; +#endif + if (de) + { + *e = de - Bias - (P - 1) + k; + *bits = P - k; + } + else + { + *e = de - Bias - (P - 1) + 1 + k; +#ifdef Pack_32 + *bits = 32 * i - hi0bits(x[i - 1]); +#else + *bits = (i + 2) * 16 - hi0bits(x[i]); +#endif + } + return b; +} + +static const double tens[] = { + 1e0, 1e1, 1e2, 1e3, 1e4, 1e5, 1e6, 1e7, 1e8, 1e9, + 1e10, 1e11, 1e12, 1e13, 1e14, 1e15, 1e16, 1e17, 1e18, 1e19, + 1e20, 1e21, 1e22 +}; + +#ifdef IEEE_Arith +static const double bigtens[] = { 1e16, 1e32, 1e64, 1e128, 1e256 }; +static const double tinytens[] = { 1e-16, 1e-32, 1e-64, 1e-128, 1e-256 }; + +# define n_bigtens 5 +#else +static const double bigtens[] = { 1e16, 1e32 }; +static const double tinytens[] = { 1e-16, 1e-32 }; + +# define n_bigtens 2 +#endif + +static int quorem(Bigint * b, Bigint * S) +{ + int n; + long borrow, y; + unsigned long carry, q, ys; + unsigned long *bx, *bxe, *sx, *sxe; +#ifdef Pack_32 + int32_t z; + uint32_t si, zs; +#endif + + n = S->wds; +#ifdef CONFIG_DEBUG_LIB + if (b->wds > n) + { + ldbg("oversize b in quorem\n"); + } +#endif + if (b->wds < n) + { + return 0; + } + sx = S->x; + sxe = sx + --n; + bx = b->x; + bxe = bx + n; + q = *bxe / (*sxe + 1); /* ensure q <= true quotient */ +#ifdef CONFIG_DEBUG_LIB + if (q > 9) + { + ldbg("oversized quotient in quorem\n"); + } +#endif + if (q) + { + borrow = 0; + carry = 0; + do + { +#ifdef Pack_32 + si = *sx++; + ys = (si & 0xffff) * q + carry; + zs = (si >> 16) * q + (ys >> 16); + carry = zs >> 16; + y = (*bx & 0xffff) - (ys & 0xffff) + borrow; + borrow = y >> 16; + Sign_Extend(borrow, y); + z = (*bx >> 16) - (zs & 0xffff) + borrow; + borrow = z >> 16; + Sign_Extend(borrow, z); + Storeinc(bx, z, y); +#else + ys = *sx++ * q + carry; + carry = ys >> 16; + y = *bx - (ys & 0xffff) + borrow; + borrow = y >> 16; + Sign_Extend(borrow, y); + *bx++ = y & 0xffff; +#endif + } + while (sx <= sxe); + if (!*bxe) + { + bx = b->x; + while (--bxe > bx && !*bxe) + --n; + b->wds = n; + } + } + if (cmp(b, S) >= 0) + { + q++; + borrow = 0; + carry = 0; + bx = b->x; + sx = S->x; + do + { +#ifdef Pack_32 + si = *sx++; + ys = (si & 0xffff) + carry; + zs = (si >> 16) + (ys >> 16); + carry = zs >> 16; + y = (*bx & 0xffff) - (ys & 0xffff) + borrow; + borrow = y >> 16; + Sign_Extend(borrow, y); + z = (*bx >> 16) - (zs & 0xffff) + borrow; + borrow = z >> 16; + Sign_Extend(borrow, z); + Storeinc(bx, z, y); +#else + ys = *sx++ + carry; + carry = ys >> 16; + y = *bx - (ys & 0xffff) + borrow; + borrow = y >> 16; + Sign_Extend(borrow, y); + *bx++ = y & 0xffff; +#endif + } + while (sx <= sxe); + bx = b->x; + bxe = bx + n; + if (!*bxe) + { + while (--bxe > bx && !*bxe) + --n; + b->wds = n; + } + } + return q; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/* dtoa for IEEE arithmetic (dmg): convert double to ASCII string. + * + * Inspired by "How to Print Floating-Point Numbers Accurately" by + * Guy L. Steele, Jr. and Jon L. White [Proc. ACM SIGPLAN '90, pp. 92-101]. + * + * Modifications: + * 1. Rather than iterating, we use a simple numeric overestimate + * to determine k = floor(log10(d)). We scale relevant + * quantities using O(log2(k)) rather than O(k) multiplications. + * 2. For some modes > 2 (corresponding to ecvt and fcvt), we don't + * try to generate digits strictly left to right. Instead, we + * compute with fewer bits and propagate the carry if necessary + * when rounding the final digit up. This is often faster. + * 3. Under the assumption that input will be rounded nearest, + * mode 0 renders 1e23 as 1e23 rather than 9.999999999999999e22. + * That is, we allow equality in stopping tests when the + * round-nearest rule will give the same floating-point value + * as would satisfaction of the stopping test with strict + * inequality. + * 4. We remove common factors of powers of 2 from relevant + * quantities. + * 5. When converting floating-point integers less than 1e16, + * we use floating-point arithmetic rather than resorting + * to multiple-precision integers. + * 6. When asked to produce fewer than 15 digits, we first try + * to get by with floating-point arithmetic; we resort to + * multiple-precision integer arithmetic only if we cannot + * guarantee that the floating-point calculation has given + * the correctly rounded result. For k requested digits and + * "uniformly" distributed input, the probability is + * something like 10^(k-15) that we must resort to the int32_t + * calculation. + */ + +char *__dtoa(double d, int mode, int ndigits, int *decpt, int *sign, char **rve) +{ + /* Arguments ndigits, decpt, sign are similar to those of ecvt and fcvt; + * trailing zeros are suppressed from the returned string. If not null, *rve + * is set to point to the end of the return value. If d is +-Infinity or + * NaN, then *decpt is set to 9999. + * + * mode: 0 ==> shortest string that yields d when read in and rounded to + * nearest. 1 ==> like 0, but with Steele & White stopping rule; e.g. with + * IEEE P754 arithmetic , mode 0 gives 1e23 whereas mode 1 gives + * 9.999999999999999e22. 2 ==> max(1,ndigits) significant digits. This gives + * a return value similar to that of ecvt, except that trailing zeros are + * suppressed. 3 ==> through ndigits past the decimal point. This gives a + * return value similar to that from fcvt, except that trailing zeros are + * suppressed, and ndigits can be negative. 4-9 should give the same return + * values as 2-3, i.e., 4 <= mode <= 9 ==> same return as mode 2 + (mode & + * 1). These modes are mainly for debugging; often they run slower but + * sometimes faster than modes 2-3. 4,5,8,9 ==> left-to-right digit + * generation. 6-9 ==> don't try fast floating-point estimate (if + * applicable). + * + * Values of mode other than 0-9 are treated as mode 0. + * + * Sufficient space is allocated to the return value to hold the suppressed + * trailing zeros. */ + + int bbits, b2, b5, be, dig, i, ieps, ilim = 0, ilim0, ilim1 = 0, + j, j_1, k, k0, k_check, leftright, m2, m5, s2, s5, spec_case = 0, try_quick; + long L; + int denorm; + unsigned long x; + Bigint *b, *b1, *delta, *mlo = NULL, *mhi, *S; + double d2, ds, eps; + char *s, *s0; + static Bigint *result; + static int result_k; + + if (result) + { + result->k = result_k; + result->maxwds = 1 << result_k; + Bfree(result); + result = 0; + } + + if (word0(d) & Sign_bit) + { + /* set sign for everything, including 0's and NaNs */ + *sign = 1; + word0(d) &= ~Sign_bit; /* clear sign bit */ + } + else + { + *sign = 0; + } + +#if defined(IEEE_Arith) +# ifdef IEEE_Arith + if ((word0(d) & Exp_mask) == Exp_mask) +#else + if (word0(d) == 0x8000) +#endif + { + /* Infinity or NaN */ + *decpt = 9999; + s = +#ifdef IEEE_Arith + !word1(d) && !(word0(d) & 0xfffff) ? "Infinity" : +#endif + "NaN"; + if (rve) + *rve = +#ifdef IEEE_Arith + s[3] ? s + 8 : +#endif + s + 3; + return s; + } +#endif + if (!d) + { + *decpt = 1; + s = "0"; + if (rve) + *rve = s + 1; + return s; + } + + b = d2b(d, &be, &bbits); + if ((i = (int)(word0(d) >> Exp_shift1 & (Exp_mask >> Exp_shift1)))) + { + d2 = d; + word0(d2) &= Frac_mask1; + word0(d2) |= Exp_11; + + /* log(x) ~=~ log(1.5) + (x-1.5)/1.5 log10(x) = log(x) / log(10) ~=~ + * log(1.5)/log(10) + (x-1.5)/(1.5*log(10)) log10(d) = + * (i-Bias)*log(2)/log(10) + log10(d2) This suggests computing an + * approximation k to log10(d) by k = (i - Bias)*0.301029995663981 + ( + * (d2-1.5)*0.289529654602168 + 0.176091259055681 ); We want k to be too + * large rather than too small. The error in the first-order Taylor + * series approximation is in our favor, so we just round up the constant + * enough to compensate for any error in the multiplication of (i - Bias) + * by 0.301029995663981; since |i - Bias| <= 1077, and 1077 * 0.30103 * + * 2^-52 ~=~ 7.2e-14, adding 1e-13 to the constant term more than + * suffices. Hence we adjust the constant term to 0.1760912590558. (We + * could get a more accurate k by invoking log10, but this is probably + * not worthwhile.) */ + + i -= Bias; + denorm = 0; + } + else + { + /* d is denormalized */ + + i = bbits + be + (Bias + (P - 1) - 1); + x = i > 32 ? word0(d) << (64 - i) | word1(d) >> (i - 32) + : word1(d) << (32 - i); + d2 = x; + word0(d2) -= 31 * Exp_msk1; /* adjust exponent */ + i -= (Bias + (P - 1) - 1) + 1; + denorm = 1; + } + + ds = (d2 - 1.5) * 0.289529654602168 + 0.1760912590558 + i * 0.301029995663981; + k = (int)ds; + if (ds < 0. && ds != k) + { + k--; /* want k = floor(ds) */ + } + k_check = 1; + + if (k >= 0 && k <= Ten_pmax) + { + if (d < tens[k]) + k--; + k_check = 0; + } + + j = bbits - i - 1; + if (j >= 0) + { + b2 = 0; + s2 = j; + } + else + { + b2 = -j; + s2 = 0; + } + + if (k >= 0) + { + b5 = 0; + s5 = k; + s2 += k; + } + else + { + b2 -= k; + b5 = -k; + s5 = 0; + } + + if (mode < 0 || mode > 9) + { + mode = 0; + } + + try_quick = 1; + if (mode > 5) + { + mode -= 4; + try_quick = 0; + } + + leftright = 1; + switch (mode) + { + case 0: + case 1: + ilim = ilim1 = -1; + i = 18; + ndigits = 0; + break; + + case 2: + leftright = 0; + /* no break */ + case 4: + if (ndigits <= 0) + { + ndigits = 1; + } + + ilim = ilim1 = i = ndigits; + break; + + case 3: + leftright = 0; + /* no break */ + case 5: + i = ndigits + k + 1; + ilim = i; + ilim1 = i - 1; + if (i <= 0) + { + i = 1; + } + } + + j = sizeof(unsigned long); + for (result_k = 0; + (signed)(sizeof(Bigint) - sizeof(unsigned long) + j) <= i; + j <<= 1) + { + result_k++; + } + + result = Balloc(result_k); + s = s0 = (char *)result; + + if (ilim >= 0 && ilim <= Quick_max && try_quick) + { + /* Try to get by with floating-point arithmetic. */ + + i = 0; + d2 = d; + k0 = k; + ilim0 = ilim; + ieps = 2; /* conservative */ + + if (k > 0) + { + ds = tens[k & 0xf]; + j = k >> 4; + + if (j & Bletch) + { + /* prevent overflows */ + j &= Bletch - 1; + d /= bigtens[n_bigtens - 1]; + ieps++; + } + + for (; j; j >>= 1, i++) + { + if (j & 1) + { + ieps++; + ds *= bigtens[i]; + } + } + + d /= ds; + } + else if ((j_1 = -k)) + { + d *= tens[j_1 & 0xf]; + for (j = j_1 >> 4; j; j >>= 1, i++) + { + if (j & 1) + { + ieps++; + d *= bigtens[i]; + } + } + } + + if (k_check && d < 1. && ilim > 0) + { + if (ilim1 <= 0) + { + goto fast_failed; + } + + ilim = ilim1; + k--; + d *= 10.; + ieps++; + } + + eps = ieps * d + 7.; + word0(eps) -= (P - 1) * Exp_msk1; + if (ilim == 0) + { + S = mhi = 0; + d -= 5.; + if (d > eps) + goto one_digit; + if (d < -eps) + goto no_digits; + goto fast_failed; + } + +#ifndef No_leftright + if (leftright) + { + /* Use Steele & White method of only generating digits needed. */ + + eps = 0.5 / tens[ilim - 1] - eps; + for (i = 0;;) + { + L = (int)d; + d -= L; + *s++ = '0' + (int)L; + if (d < eps) + goto ret1; + if (1. - d < eps) + goto bump_up; + if (++i >= ilim) + break; + eps *= 10.; + d *= 10.; + } + } + else + { +#endif + /* Generate ilim digits, then fix them up. */ + + eps *= tens[ilim - 1]; + for (i = 1;; i++, d *= 10.) + { + L = (int)d; + d -= L; + *s++ = '0' + (int)L; + if (i == ilim) + { + if (d > 0.5 + eps) + goto bump_up; + else if (d < 0.5 - eps) + { + while (*--s == '0'); + s++; + goto ret1; + } + break; + } + } +#ifndef No_leftright + } +#endif + fast_failed: + s = s0; + d = d2; + k = k0; + ilim = ilim0; + } + + /* Do we have a "small" integer? */ + + if (be >= 0 && k <= Int_max) + { + /* Yes. */ + + ds = tens[k]; + if (ndigits < 0 && ilim <= 0) + { + S = mhi = 0; + if (ilim < 0 || d <= 5 * ds) + goto no_digits; + goto one_digit; + } + + for (i = 1;; i++) + { + L = (int)(d / ds); + d -= L * ds; +#ifdef Check_FLT_ROUNDS + /* If FLT_ROUNDS == 2, L will usually be high by 1 */ + if (d < 0) + { + L--; + d += ds; + } +#endif + *s++ = '0' + (int)L; + if (i == ilim) + { + d += d; + if (d > ds || (d == ds && (L & 1))) + { + bump_up: + while (*--s == '9') + if (s == s0) + { + k++; + *s = '0'; + break; + } + ++*s++; + } + break; + } + if (!(d *= 10.)) + { + break; + } + } + + goto ret1; + } + + m2 = b2; + m5 = b5; + mhi = mlo = 0; + if (leftright) + { + if (mode < 2) + { + i = denorm ? be + (Bias + (P - 1) - 1 + 1) : 1 + P - bbits; + } + else + { + j = ilim - 1; + if (m5 >= j) + m5 -= j; + else + { + s5 += j -= m5; + b5 += j; + m5 = 0; + } + if ((i = ilim) < 0) + { + m2 -= i; + i = 0; + } + } + + b2 += i; + s2 += i; + mhi = i2b(1); + } + + if (m2 > 0 && s2 > 0) + { + i = m2 < s2 ? m2 : s2; + b2 -= i; + m2 -= i; + s2 -= i; + } + + if (b5 > 0) + { + if (leftright) + { + if (m5 > 0) + { + mhi = pow5mult(mhi, m5); + b1 = mult(mhi, b); + Bfree(b); + b = b1; + } + if ((j = b5 - m5)) + b = pow5mult(b, j); + } + else + { + b = pow5mult(b, b5); + } + } + + S = i2b(1); + if (s5 > 0) + { + S = pow5mult(S, s5); + } + + /* Check for special case that d is a normalized power of 2. */ + + if (mode < 2) + { + if (!word1(d) && !(word0(d) & Bndry_mask) && word0(d) & Exp_mask) + { + /* The special case */ + b2 += Log2P; + s2 += Log2P; + spec_case = 1; + } + else + { + spec_case = 0; + } + } + + /* Arrange for convenient computation of quotients: shift left if + * necessary so divisor has 4 leading 0 bits. + * + * Perhaps we should just compute leading 28 bits of S once and for all + * and pass them and a shift to quorem, so it can do shifts and ors + * to compute the numerator for q. + */ + +#ifdef Pack_32 + if ((i = ((s5 ? 32 - hi0bits(S->x[S->wds - 1]) : 1) + s2) & 0x1f)) + { + i = 32 - i; + } +#else + if ((i = ((s5 ? 32 - hi0bits(S->x[S->wds - 1]) : 1) + s2) & 0xf)) + { + i = 16 - i; + } +#endif + + if (i > 4) + { + i -= 4; + b2 += i; + m2 += i; + s2 += i; + } + else if (i < 4) + { + i += 28; + b2 += i; + m2 += i; + s2 += i; + } + + if (b2 > 0) + { + b = lshift(b, b2); + } + + if (s2 > 0) + { + S = lshift(S, s2); + } + + if (k_check) + { + if (cmp(b, S) < 0) + { + k--; + b = multadd(b, 10, 0); /* we botched the k estimate */ + if (leftright) + { + mhi = multadd(mhi, 10, 0); + } + + ilim = ilim1; + } + } + + if (ilim <= 0 && mode > 2) + { + if (ilim < 0 || cmp(b, S = multadd(S, 5, 0)) <= 0) + { + /* no digits, fcvt style */ + no_digits: + k = -1 - ndigits; + goto ret; + } + one_digit: + *s++ = '1'; + k++; + goto ret; + } + + if (leftright) + { + if (m2 > 0) + { + mhi = lshift(mhi, m2); + } + + /* Compute mlo -- check for special case that d is a normalized power of + * 2. */ + + mlo = mhi; + if (spec_case) + { + mhi = Balloc(mhi->k); + Bcopy(mhi, mlo); + mhi = lshift(mhi, Log2P); + } + + for (i = 1;; i++) + { + dig = quorem(b, S) + '0'; + /* Do we yet have the shortest decimal string that will round to d? */ + j = cmp(b, mlo); + delta = diff(S, mhi); + j_1 = delta->sign ? 1 : cmp(b, delta); + Bfree(delta); +#ifndef ROUND_BIASED + if (j_1 == 0 && !mode && !(word1(d) & 1)) + { + if (dig == '9') + { + goto round_9_up; + } + + if (j > 0) + { + dig++; + } + + *s++ = dig; + goto ret; + } +#endif + if (j < 0 || (j == 0 && !mode +#ifndef ROUND_BIASED + && (!(word1(d) & 1)) +#endif + )) + { + if ((j_1 > 0)) + { + b = lshift(b, 1); + j_1 = cmp(b, S); + if ((j_1 > 0 || (j_1 == 0 && (dig & 1))) && dig++ == '9') + { + goto round_9_up; + } + } + + *s++ = dig; + goto ret; + } + + if (j_1 > 0) + { + if (dig == '9') + { /* possible if i == 1 */ + round_9_up: + *s++ = '9'; + goto roundoff; + } + + *s++ = dig + 1; + goto ret; + } + + *s++ = dig; + if (i == ilim) + { + break; + } + + b = multadd(b, 10, 0); + if (mlo == mhi) + { + mlo = mhi = multadd(mhi, 10, 0); + } + else + { + mlo = multadd(mlo, 10, 0); + mhi = multadd(mhi, 10, 0); + } + } + } + else + { + for (i = 1;; i++) + { + *s++ = dig = quorem(b, S) + '0'; + if (i >= ilim) + { + break; + } + + b = multadd(b, 10, 0); + } + } + + /* Round off last digit */ + + b = lshift(b, 1); + j = cmp(b, S); + if (j > 0 || (j == 0 && (dig & 1))) + { + roundoff: + while (*--s == '9') + if (s == s0) + { + k++; + *s++ = '1'; + goto ret; + } + ++*s++; + } + else + { + while (*--s == '0'); + s++; + } + +ret: + Bfree(S); + if (mhi) + { + if (mlo && mlo != mhi) + { + Bfree(mlo); + } + + Bfree(mhi); + } +ret1: + Bfree(b); + if (s == s0) + { /* don't return empty string */ + *s++ = '0'; + k = 0; + } + + *s = 0; + *decpt = k + 1; + if (rve) + { + *rve = s; + } + + return s0; +} diff --git a/nuttx/lib/stdio/lib_fclose.c b/nuttx/lib/stdio/lib_fclose.c new file mode 100644 index 0000000000..8cecb8af3c --- /dev/null +++ b/nuttx/lib/stdio/lib_fclose.c @@ -0,0 +1,154 @@ +/**************************************************************************** + * lib/stdio/lib_fclose.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fclose + * + * Description + * The fclose() function will flush the stream pointed to by stream + * (writing any buffered output data using lib_fflush()) and close the + * underlying file descriptor. + * + * Returned Value: + * Upon successful completion 0 is returned. Otherwise, EOF is returned + * and the global variable errno is set to indicate the error. In either + * case any further access (including another call to fclose()) to the + * stream results in undefined behaviour. + * + ****************************************************************************/ + +int fclose(FAR FILE *stream) +{ + int err = EINVAL; + int ret = ERROR; + int status; + + /* Verify that a stream was provided. */ + + if (stream) + { + /* Check that the underlying file descriptor corresponds to an an open + * file. + */ + + ret = OK; + if (stream->fs_filedes >= 0) + { + /* If the stream was opened for writing, then flush the stream */ + + if ((stream->fs_oflags & O_WROK) != 0) + { + ret = lib_fflush(stream, true); + err = errno; + } + + /* Close the underlying file descriptor and save the return status */ + + status = close(stream->fs_filedes); + + /* If close() returns an error but flush() did not then make sure + * that we return the close() error condition. + */ + + if (ret == OK) + { + ret = status; + err = errno; + } + } + +#if CONFIG_STDIO_BUFFER_SIZE > 0 + /* Destroy the semaphore */ + + sem_destroy(&stream->fs_sem); + + /* Release the buffer */ + + if (stream->fs_bufstart) + { + lib_free(stream->fs_bufstart); + } + + /* Clear the whole structure */ + + memset(stream, 0, sizeof(FILE)); +#else +#if CONFIG_NUNGET_CHARS > 0 + /* Reset the number of ungetc characters */ + + stream->fs_nungotten = 0; +#endif + /* Reset the flags */ + + stream->fs_oflags = 0; +#endif + /* Setting the fs_filedescriptor to -1 makes the stream available for reuse */ + + stream->fs_filedes = -1; + } + + /* On an error, reset the errno to the first error encountered and return + * EOF. + */ + + if (ret != OK) + { + set_errno(err); + return EOF; + } + + /* Return success */ + + return OK; +} + diff --git a/nuttx/lib/stdio/lib_fflush.c b/nuttx/lib/stdio/lib_fflush.c new file mode 100644 index 0000000000..d0b5e0185d --- /dev/null +++ b/nuttx/lib/stdio/lib_fflush.c @@ -0,0 +1,132 @@ +/**************************************************************************** + * lib/stdio/lib_fflush.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fflush + * + * Description: + * The function fflush() forces a write of all user-space buffered data for + * the given output or update stream via the stream's underlying write + * function. The open status of the stream is unaffected. + * + * If the stream argument is NULL, fflush() flushes all open output streams. + * + * Return: + * OK on success EOF on failure (with errno set appropriately) + * + ****************************************************************************/ + +int fflush(FAR FILE *stream) +{ + int ret; + + /* Is the stream argument NULL? */ + + if (!stream) + { + /* Yes... then this is a request to flush all streams */ + + ret = lib_flushall(sched_getstreams()); + } + else + { + ret = lib_fflush(stream, true); + } + + /* Check the return value */ + + if (ret < 0) + { + /* An error occurred during the flush AND/OR we were unable to flush + * all of the buffered write data. Set the errno value. + */ + + set_errno(-ret); + + /* And return EOF on failure. */ + + return EOF; + } + + return OK; +} + diff --git a/nuttx/lib/stdio/lib_fgetc.c b/nuttx/lib/stdio/lib_fgetc.c new file mode 100644 index 0000000000..4b3d0ec44f --- /dev/null +++ b/nuttx/lib/stdio/lib_fgetc.c @@ -0,0 +1,101 @@ +/**************************************************************************** + * lib/stdio/lib_fgetc.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/************************************************************************** + * Global Constant Data + **************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/************************************************************************** + * Private Constant Data + **************************************************************************/ + +/**************************************************************************** + * Private Variables + **************************************************************************/ + +/**************************************************************************** + * Global Functions + **************************************************************************/ + +/**************************************************************************** + * fgetc + **************************************************************************/ + +int fgetc(FAR FILE *stream) +{ + unsigned char ch; + ssize_t ret; + + ret = lib_fread(&ch, 1, stream); + if (ret > 0) + { + return ch; + } + else + { + return EOF; + } +} diff --git a/nuttx/lib/stdio/lib_fgetpos.c b/nuttx/lib/stdio/lib_fgetpos.c new file mode 100644 index 0000000000..e9e9f4d102 --- /dev/null +++ b/nuttx/lib/stdio/lib_fgetpos.c @@ -0,0 +1,123 @@ +/**************************************************************************** + * lib/stdio/lib_fgetpos.c + * + * Copyright (C) 2008-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fgetpos + * + * Description: + * fgetpos() function is an alternate interfaces equivalent to ftell(). + * It gets the current value of the file offset and store it in the location + * referenced by pos. On some non-UNIX systems an fpos_t object may be a + * complex object and fsetpos may be the only way to portably reposition a + * stream. + * + * Returned Value: + * Zero on succes; -1 on failure with errno set appropriately. + * + ****************************************************************************/ + +int fgetpos(FAR FILE *stream, FAR fpos_t *pos) +{ + long position; + +#if CONFIG_DEBUG + if (!stream || !pos) + { + set_errno(EINVAL); + return ERROR; + } +#endif + + position = ftell(stream); + if (position == -1) + { + return ERROR; + } + + *pos = (fpos_t)position; + return OK; +} diff --git a/nuttx/lib/stdio/lib_fgets.c b/nuttx/lib/stdio/lib_fgets.c new file mode 100644 index 0000000000..a4f9089ed7 --- /dev/null +++ b/nuttx/lib/stdio/lib_fgets.c @@ -0,0 +1,207 @@ +/**************************************************************************** + * lib/stdio/lib_fgets.c + * + * Copyright (C) 2007-2008, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ +/* Some environments may return CR as end-of-line, others LF, and others + * both. If not specified, the logic here assumes either (but not both) as + * the default. + */ + +#if defined(CONFIG_EOL_IS_CR) +# undef CONFIG_EOL_IS_LF +# undef CONFIG_EOL_IS_BOTH_CRLF +# undef CONFIG_EOL_IS_EITHER_CRLF +#elif defined(CONFIG_EOL_IS_LF) +# undef CONFIG_EOL_IS_CR +# undef CONFIG_EOL_IS_BOTH_CRLF +# undef CONFIG_EOL_IS_EITHER_CRLF +#elif defined(CONFIG_EOL_IS_BOTH_CRLF) +# undef CONFIG_EOL_IS_CR +# undef CONFIG_EOL_IS_LF +# undef CONFIG_EOL_IS_EITHER_CRLF +#elif defined(CONFIG_EOL_IS_EITHER_CRLF) +# undef CONFIG_EOL_IS_CR +# undef CONFIG_EOL_IS_LF +# undef CONFIG_EOL_IS_BOTH_CRLF +#else +# undef CONFIG_EOL_IS_CR +# undef CONFIG_EOL_IS_LF +# undef CONFIG_EOL_IS_BOTH_CRLF +# define CONFIG_EOL_IS_EITHER_CRLF 1 +#endif + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fgets + * + * Description: + * fgets() reads in at most one less than 'buflen' characters from stream + * and stores them into the buffer pointed to by 'buf'. Reading stops after + * an EOF or a newline. If a newline is read, it is stored into the + * buffer. A null terminator is stored after the last character in the + * buffer. + * + **************************************************************************/ + +char *fgets(FAR char *buf, int buflen, FILE *stream) +{ + int nch = 0; + + /* Sanity checks */ + + if (!stream || !buf || buflen < 1 || stream->fs_filedes < 0) + { + return NULL; + } + + if (buflen < 2) + { + *buf = '\0'; + return buf; + } + + /* Read characters until we have a full line. On each the loop we must + * be assured that there are two free bytes in the line buffer: One for + * the next character and one for the null terminator. + */ + + for(;;) + { + /* Get the next character */ + + int ch = fgetc(stream); + + /* Check for end-of-line. This is tricky only in that some + * environments may return CR as end-of-line, others LF, and + * others both. + */ + +#if defined(CONFIG_EOL_IS_LF) || defined(CONFIG_EOL_IS_BOTH_CRLF) + if (ch == '\n') +#elif defined(CONFIG_EOL_IS_CR) + if (ch == '\r') +#elif CONFIG_EOL_IS_EITHER_CRLF + if (ch == '\n' || ch == '\r') +#endif + { + /* The newline is stored in the buffer along with the null + * terminator. + */ + + buf[nch++] = '\n'; + buf[nch] = '\0'; + return buf; + } + + /* Check for end-of-file */ + + else if (ch == EOF) + { + /* End of file with no data? */ + + if (!nch) + { + /* Yes.. return NULL as the end of file mark */ + + return NULL; + } + else + { + /* Terminate the line */ + + buf[nch] = '\0'; + return buf; + } + } + + /* Otherwise, check if the character is printable and, if so, put the + * character in the line buffer + */ + + else if (isprint(ch)) + { + buf[nch++] = ch; + + /* Check if there is room for another character and the line's + * null terminator. If not then we have to end the line now. + */ + + if (nch + 1 >= buflen) + { + buf[nch] = '\0'; + return buf; + } + } + } +} + diff --git a/nuttx/lib/stdio/lib_fileno.c b/nuttx/lib/stdio/lib_fileno.c new file mode 100644 index 0000000000..fca08fc0d4 --- /dev/null +++ b/nuttx/lib/stdio/lib_fileno.c @@ -0,0 +1,70 @@ +/**************************************************************************** + * lib/stdio/lib_fileno.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#if CONFIG_NFILE_STREAMS > 0 + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +int fileno(FAR FILE *stream) +{ + int ret = -1; + if (stream) + { + ret = stream->fs_filedes; + } + + if (ret < 0) + { + set_errno(EBADF); + return ERROR; + } + + return ret; +} +#endif /* CONFIG_NFILE_STREAMS */ + diff --git a/nuttx/lib/stdio/lib_fopen.c b/nuttx/lib/stdio/lib_fopen.c new file mode 100644 index 0000000000..29ff4569c2 --- /dev/null +++ b/nuttx/lib/stdio/lib_fopen.c @@ -0,0 +1,299 @@ +/**************************************************************************** + * lib/stdio/lib_fopen.c + * + * Copyright (C) 2007-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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +enum open_mode_e +{ + MODE_NONE = 0, /* No access mode determined */ + MODE_R, /* "r" or "rb" open for reading */ + MODE_W, /* "w" or "wb" open for writing, truncating or creating file */ + MODE_A, /* "a" or "ab" open for writing, appending to file */ + MODE_RPLUS, /* "r+", "rb+", or "r+b" open for update (reading and writing) */ + MODE_WPLUS, /* "w+", "wb+", or "w+b" open for update, truncating or creating file */ + MODE_APLUS /* "a+", "ab+", or "a+b" open for update, appending to file */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_mode2oflags + ****************************************************************************/ + +static int lib_mode2oflags(FAR const char *mode) +{ + enum open_mode_e state; + int oflags; + + /* Verify that a mode string was provided. No error is */ + + if (!mode) + { + goto errout; + } + + /* Parse the mode string to determine the corresponding open flags */ + + state = MODE_NONE; + oflags = 0; + + for (; *mode; mode++) + { + switch (*mode) + { + /* Open for read access ("r", "r[+]", "r[b]", "r[b+]", or "r[+b]") */ + + case 'r' : + if (state == MODE_NONE) + { + /* Open for read access */ + + oflags = O_RDOK; + state = MODE_R; + } + else + { + goto errout; + } + break; + + /* Open for write access ("w", "w[+]", "w[b]", "w[b+]", or "w[+b]") */ + + case 'w' : + if (state == MODE_NONE) + { + /* Open for write access, truncating any existing file */ + + oflags = O_WROK|O_CREAT|O_TRUNC; + state = MODE_W; + } + else + { + goto errout; + } + break; + + /* Open for write/append access ("a", "a[+]", "a[b]", "a[b+]", or "a[+b]") */ + + case 'a' : + if (state == MODE_NONE) + { + /* Write to the end of the file */ + + oflags = O_WROK|O_CREAT|O_APPEND; + state = MODE_A; + } + else + { + goto errout; + } + break; + + /* Open for update access ("[r]+", "[rb]+]", "[r]+[b]", "[w]+", + * "[wb]+]", "[w]+[b]", "[a]+", "[ab]+]", "[a]+[b]") + */ + + case '+' : + switch (state) + { + case MODE_R: + { + /* Retain any binary mode selection */ + + oflags &= O_BINARY; + + /* Open for read/write access */ + + oflags |= O_RDWR; + state = MODE_RPLUS; + } + break; + + case MODE_W: + { + /* Retain any binary mode selection */ + + oflags &= O_BINARY; + + /* Open for write read/access, truncating any existing file */ + + oflags |= O_RDWR|O_CREAT|O_TRUNC; + state = MODE_WPLUS; + } + break; + + case MODE_A: + { + /* Retain any binary mode selection */ + + oflags &= O_BINARY; + + /* Read from the beginning of the file; write to the end */ + + oflags |= O_RDWR|O_CREAT|O_APPEND; + state = MODE_APLUS; + } + break; + + default: + goto errout; + break; + } + break; + + /* Open for binary access ("[r]b", "[r]b[+]", "[r+]b", "[w]b", + * "[w]b[+]", "[w+]b", "[a]b", "[a]b[+]", "[a+]b") + */ + + case 'b' : + if (state != MODE_NONE) + { + /* The file is opened in binary mode */ + + oflags |= O_BINARY; + } + else + { + goto errout; + } + break; + + /* Unrecognized or unsupported mode */ + + default: + goto errout; + break; + } + } + + return oflags; + +/* Both fopen and fdopen should fail with errno == EINVAL if the mode + * string is invalid. + */ + +errout: + set_errno(EINVAL); + return ERROR; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fdopen + ****************************************************************************/ + +FAR FILE *fdopen(int fd, FAR const char *mode) +{ + FAR FILE *ret = NULL; + int oflags; + + /* Map the open mode string to open flags */ + + oflags = lib_mode2oflags(mode); + if (oflags >= 0) + { + ret = fs_fdopen(fd, oflags, NULL); + } + + return ret; +} + +/**************************************************************************** + * Name: fopen + ****************************************************************************/ + +FAR FILE *fopen(FAR const char *path, FAR const char *mode) +{ + FAR FILE *ret = NULL; + int oflags; + int fd; + + /* Map the open mode string to open flags */ + + oflags = lib_mode2oflags(mode); + if (oflags < 0) + { + return NULL; + } + + /* Open the file */ + + fd = open(path, oflags, 0666); + + /* If the open was successful, then fdopen() the fil using the file + * desciptor returned by open. If open failed, then just return the + * NULL stream -- open() has already set the errno. + */ + + if (fd >= 0) + { + ret = fs_fdopen(fd, oflags, NULL); + if (!ret) + { + /* Don't forget to close the file descriptor if any other + * failures are reported by fdopen(). + */ + + (void)close(fd); + } + } + return ret; +} diff --git a/nuttx/lib/stdio/lib_fprintf.c b/nuttx/lib/stdio/lib_fprintf.c new file mode 100644 index 0000000000..a803de4bd0 --- /dev/null +++ b/nuttx/lib/stdio/lib_fprintf.c @@ -0,0 +1,93 @@ +/**************************************************************************** + * lib/stdio/lib_fprintf.c + * + * Copyright (C) 2007, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fprintf + ****************************************************************************/ + +int fprintf(FAR FILE *stream, FAR const char *fmt, ...) +{ + va_list ap; + int n; + + /* vfprintf into the stream */ + + va_start(ap, fmt); + n = vfprintf(stream, fmt, ap); + va_end(ap); + return n; +} diff --git a/nuttx/lib/stdio/lib_fputc.c b/nuttx/lib/stdio/lib_fputc.c new file mode 100644 index 0000000000..121161f102 --- /dev/null +++ b/nuttx/lib/stdio/lib_fputc.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * lib/stdio/lib_fputc.c + * + * Copyright (C) 2007, 2008, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fputc + ****************************************************************************/ + +int fputc(int c, FAR FILE *stream) +{ + unsigned char buf = (unsigned char)c; + int ret; + + ret = lib_fwrite(&buf, 1, stream); + if (ret > 0) + { + /* Flush the buffer if a newline is output */ + +#ifdef CONFIG_STDIO_LINEBUFFER + if (c == '\n') + { + ret = lib_fflush(stream, true); + if (ret < 0) + { + return EOF; + } + } +#endif + return c; + } + else + { + return EOF; + } +} diff --git a/nuttx/lib/stdio/lib_fputs.c b/nuttx/lib/stdio/lib_fputs.c new file mode 100644 index 0000000000..2d6217d4aa --- /dev/null +++ b/nuttx/lib/stdio/lib_fputs.c @@ -0,0 +1,220 @@ +/**************************************************************************** + * lib/stdio/lib_fputs.c + * + * Copyright (C) 2007, 2008, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fputs + * + * Description: + * fputs() writes the string s to stream, without its trailing '\0'. + * + ****************************************************************************/ + +#if defined(CONFIG_ARCH_ROMGETC) +int fputs(FAR const char *s, FAR FILE *stream) +{ + int nput; + int ret; + char ch; + + /* Make sure that a string was provided. */ + +#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */ + if (!s) + { + set_errno(EINVAL); + return EOF; + } +#endif + + /* Write the string. Loop until the null terminator is encountered */ + + for (nput = 0, ch = up_romgetc(s); ch; nput++, s++, ch = up_romgetc(s)) + { + /* Write the next character to the stream buffer */ + + ret = lib_fwrite(&ch, 1, stream); + if (ret <= 0) + { + return EOF; + } + + /* Flush the buffer if a newline was written to the buffer */ + +#ifdef CONFIG_STDIO_LINEBUFFER + if (ch == '\n') + { + ret = lib_fflush(stream, true); + if (ret < 0) + { + return EOF; + } + } +#endif + } + + return nput; +} + +#elif defined(CONFIG_STDIO_LINEBUFFER) +int fputs(FAR const char *s, FAR FILE *stream) +{ + int nput; + int ret; + + /* Make sure that a string was provided. */ + +#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */ + if (!s) + { + set_errno(EINVAL); + return EOF; + } +#endif + + /* Write the string. Loop until the null terminator is encountered */ + + for (nput = 0; *s; nput++, s++) + { + /* Write the next character to the stream buffer */ + + ret = lib_fwrite(s, 1, stream); + if (ret <= 0) + { + return EOF; + } + + /* Flush the buffer if a newline was written to the buffer */ + + if (*s == '\n') + { + ret = lib_fflush(stream, true); + if (ret < 0) + { + return EOF; + } + } + } + + return nput; +} + +#else +int fputs(FAR const char *s, FAR FILE *stream) +{ + int ntowrite; + int nput; + + /* Make sure that a string was provided. */ + +#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */ + if (!s) + { + set_errno(EINVAL); + return EOF; + } +#endif + + /* Get the length of the string. */ + + ntowrite = strlen(s); + if (ntowrite == 0) + { + return 0; + } + + /* Write the string */ + + nput = lib_fwrite(s, ntowrite, stream); + if (nput < 0) + { + return EOF; + } + return nput; +} +#endif diff --git a/nuttx/lib/stdio/lib_fread.c b/nuttx/lib/stdio/lib_fread.c new file mode 100644 index 0000000000..4a4b29256d --- /dev/null +++ b/nuttx/lib/stdio/lib_fread.c @@ -0,0 +1,101 @@ +/**************************************************************************** + * lib/stdio/lib_fread.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fread + ****************************************************************************/ + +size_t fread(FAR void *ptr, size_t size, size_t n_items, FAR FILE *stream) +{ + size_t full_size = n_items * (size_t)size; + ssize_t bytes_read; + size_t items_read = 0; + + /* Write the data into the stream buffer */ + + bytes_read = lib_fread(ptr, full_size, stream); + if (bytes_read > 0) + { + /* Return the number of full items read */ + + items_read = bytes_read / size; + } + return items_read; +} + + diff --git a/nuttx/lib/stdio/lib_fseek.c b/nuttx/lib/stdio/lib_fseek.c new file mode 100644 index 0000000000..7380f83b3b --- /dev/null +++ b/nuttx/lib/stdio/lib_fseek.c @@ -0,0 +1,138 @@ +/**************************************************************************** + * lib/stdio/lib_fseek.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fseek + * + * Description: + * The fseek() function sets the file position indicator for the stream + * pointed to by stream. The new position, measured in bytes, is obtained + * by adding offset bytes to the position specified by whence. If whence is + * set to SEEK_SET, SEEK_CUR, or SEEK_END, the offset is relative to the + * start of the file, the current position indicator, or end-of-file, + * respectively. A successful call to the fseek() function clears the + * end-of-file indicator for the stream and undoes any effects of the ungetc(3) + * function on the same stream. + * + * Returned Value: + * Zero on succes; -1 on failure with errno set appropriately. + * + ****************************************************************************/ + +int fseek(FAR FILE *stream, long int offset, int whence) +{ + #if CONFIG_STDIO_BUFFER_SIZE > 0 + /* Flush any valid read/write data in the buffer (also verifies stream) */ + + if (lib_rdflush(stream) < 0 || lib_wrflush(stream) < 0) + { + return ERROR; + } +#else + /* Verify that we were provided with a stream */ + + if (!stream) + { + set_errno(EBADF); + return ERROR; + } +#endif + + /* On success or failure, discard any characters saved by ungetc() */ + +#if CONFIG_NUNGET_CHARS > 0 + stream->fs_nungotten = 0; +#endif + + /* Perform the fseek on the underlying file descriptor */ + + return lseek(stream->fs_filedes, offset, whence) == (off_t)-1 ? ERROR : OK; +} + + diff --git a/nuttx/lib/stdio/lib_fsetpos.c b/nuttx/lib/stdio/lib_fsetpos.c new file mode 100644 index 0000000000..13d556521b --- /dev/null +++ b/nuttx/lib/stdio/lib_fsetpos.c @@ -0,0 +1,116 @@ +/**************************************************************************** + * lib/stdio/lib_fsetpos.c + * + * Copyright (C) 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fsetpos + * + * Description: + * fsetpos() function is an alternate interfaces equivalent to fseek() + * (with whence set to SEEK_SET). It sets the current value of the file + * offset to value in the location referenced by pos. On some non-UNIX + * systems an fpos_t object may be a complex object and fsetpos may be the + * only way to portably reposition a stream. + * + * Returned Value: + * Zero on succes; -1 on failure with errno set appropriately. + * + ****************************************************************************/ + +int fsetpos(FAR FILE *stream, FAR fpos_t *pos) +{ +#if CONFIG_DEBUG + if (!stream || !pos) + { + set_errno(EINVAL); + return ERROR; + } +#endif + + return fseek(stream, (FAR off_t)*pos, SEEK_SET); +} diff --git a/nuttx/lib/stdio/lib_ftell.c b/nuttx/lib/stdio/lib_ftell.c new file mode 100644 index 0000000000..9476481529 --- /dev/null +++ b/nuttx/lib/stdio/lib_ftell.c @@ -0,0 +1,129 @@ +/**************************************************************************** + * lib/stdio/lib_ftell.c + * + * Copyright (C) 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: ftell + * + * Description: + * ftell() returns the current value of the file position indicator for the + * stream pointed to by stream. + * + * Returned Value: + * Zero on succes; -1 on failure with errno set appropriately. + * + ****************************************************************************/ + +long ftell(FAR FILE *stream) +{ + off_t position; + + /* Verify that we were provided with a stream */ + + if (!stream) + { + set_errno(EBADF); + return ERROR; + } + + /* Perform the lseek to the current position. This will not move the + * file pointer, but will return its current setting + */ + + position = lseek(stream->fs_filedes, 0, SEEK_CUR); + if (position != (off_t)-1) + { + return (long)position; + } + else + { + return ERROR; + } +} + + diff --git a/nuttx/lib/stdio/lib_fwrite.c b/nuttx/lib/stdio/lib_fwrite.c new file mode 100644 index 0000000000..60e0017463 --- /dev/null +++ b/nuttx/lib/stdio/lib_fwrite.c @@ -0,0 +1,99 @@ +/**************************************************************************** + * lib/stdio/lib_fwrite.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fwrite + ****************************************************************************/ + +size_t fwrite(FAR const void *ptr, size_t size, size_t n_items, FAR FILE *stream) +{ + size_t full_size = n_items * (size_t)size; + ssize_t bytes_written; + size_t items_written = 0; + + /* Write the data into the stream buffer */ + + bytes_written = lib_fwrite(ptr, full_size, stream); + if (bytes_written > 0) + { + /* Return the number of full items written */ + + items_written = bytes_written / size; + } + return items_written; +} diff --git a/nuttx/lib/stdio/lib_gets.c b/nuttx/lib/stdio/lib_gets.c new file mode 100644 index 0000000000..95a6b36ebf --- /dev/null +++ b/nuttx/lib/stdio/lib_gets.c @@ -0,0 +1,120 @@ +/**************************************************************************** + * lib/stdio/lib_gets.c + * + * Copyright (C) 2007-2008, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: gets + * + * Description: + * gets() reads a line from stdin into the buffer pointed to by s until + * either a terminating newline or EOF, which it replaces with '\0'. No + * check for buffer overrun is performed + * + * This API should not be used because it is inherently unsafe. Consider + * using fgets which is safer and slightly more efficient. + * + **************************************************************************/ + +FAR char *gets(FAR char *s) +{ + /* gets is ALMOST the same as fgets using stdin and no length limit + * (hence, the unsafeness of gets). So let fgets do most of the work. + */ + + FAR char *ret = fgets(s, INT_MAX, stdin); + if (ret) + { + /* Another subtle difference from fgets is that gets replaces + * end-of-line markers with null terminators. We will do that as + * a second step (with some loss in performance). + */ + + int len = strlen(ret); + if (len > 0 && ret[len-1] == '\n') + { + ret[len-1] = '\0'; + } + } + + return ret; +} + diff --git a/nuttx/lib/stdio/lib_libdtoa.c b/nuttx/lib/stdio/lib_libdtoa.c new file mode 100644 index 0000000000..667c49c535 --- /dev/null +++ b/nuttx/lib/stdio/lib_libdtoa.c @@ -0,0 +1,304 @@ +/**************************************************************************** + * lib/unistd/lib_libdtoa.c + * + * This file was ported to NuttX by Yolande Cates. + * + * Copyright (c) 1990, 1993 + * The Regents of the University of California. All rights reserved. + * + * This code is derived from software contributed to Berkeley by + * Chris Torek. + * + * 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * This product includes software developed by the University of + * California, Berkeley and its contributors. + * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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 + ****************************************************************************/ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define MAX_PREC 16 + +#ifndef MIN +# define MIN(a,b) (a < b ? a : b) +#endif + +#ifndef MAX +# define MAX(a,b) (a > b ? a : b) +#endif + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Name: zeroes + * + * Description: + * Print the specified number of zeres + * + ****************************************************************************/ + +static void zeroes(FAR struct lib_outstream_s *obj, int nzeroes) +{ + int i; + + for (i = nzeroes; i > 0; i--) + { + obj->put(obj, '0'); + } +} + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_dtoa + * + * Description: + * This is part of lib_vsprintf(). It handles the floating point formats. + * This version supports only the %f (with precision). If no precision + * was provided in the format, this will use precision == 0 which is + * probably not what you want. + * + * Input Parameters: + * obj - The output stream object + * fmt - The format character. Not used 'f' is always assumed + * prec - The number of digits to the right of the decimal point. If no + * precision is provided in the format, this will be zero. And, + * unfortunately in this case, it will be treated literally as + * a precision of zero. + * flags - Only ALTFORM and SHOWPLUS flags are supported. ALTFORM only + * applies if prec == 0 which is not supported anyway. + * value - The floating point value to convert. + * + ****************************************************************************/ + +static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec, + uint8_t flags, double value) +{ + FAR char *digits; /* String returned by __dtoa */ + FAR char *digalloc; /* Copy of digits to be freed after usage */ + FAR char *rve; /* Points to the end of the return value */ + int expt; /* Integer value of exponent */ + int numlen; /* Actual number of digits returned by cvt */ + int nchars; /* Number of characters to print */ + int dsgn; /* Unused sign indicator */ + int i; + + /* Non-zero... positive or negative */ + + if (value < 0) + { + value = -value; + SET_NEGATE(flags); + } + + /* Perform the conversion */ + + digits = __dtoa(value, 3, prec, &expt, &dsgn, &rve); + digalloc = digits; + numlen = rve - digits; + + if (IS_NEGATE(flags)) + { + obj->put(obj, '-'); + } + else if (IS_SHOWPLUS(flags)) + { + obj->put(obj, '+'); + } + + /* Special case exact zero or the case where the number is smaller than + * the print precision. + */ + + if (value == 0 || expt < -prec) + { + /* kludge for __dtoa irregularity */ + + obj->put(obj, '0'); + + /* A decimal point is printed only in the alternate form or if a + * particular precision is requested. + */ + + if (prec > 0 || IS_ALTFORM(flags)) + { + obj->put(obj, '.'); + + /* Always print at least one digit to the right of the decimal point. */ + + prec = MAX(1, prec); + } + } + + /* A non-zero value will be printed */ + + else + { + + /* Handle the case where the value is less than 1.0 (in magnitude) and + * will need a leading zero. + */ + + if (expt <= 0) + { + /* Print a single zero to the left of the decimal point */ + + obj->put(obj, '0'); + + /* Print the decimal point */ + + obj->put(obj, '.'); + + /* Print any leading zeros to the right of the decimal point */ + + if (expt < 0) + { + nchars = MIN(-expt, prec); + zeroes(obj, nchars); + prec -= nchars; + } + } + + /* Handle the general case where the value is greater than 1.0 (in + * magnitude). + */ + + else + { + /* Print the integer part to the left of the decimal point */ + + for (i = expt; i > 0; i--) + { + if (*digits != '\0') + { + obj->put(obj, *digits); + digits++; + } + else + { + obj->put(obj, '0'); + } + } + + /* Get the length of the fractional part */ + + numlen -= expt; + + /* If there is no fractional part, then a decimal point is printed + * only in the alternate form or if a particular precision is + * requested. + */ + + if (numlen > 0 || prec > 0 || IS_ALTFORM(flags)) + { + /* Print the decimal point */ + + obj->put(obj, '.'); + + /* Always print at least one digit to the right of the decimal + * point. + */ + + prec = MAX(1, prec); + } + } + + /* If a precision was specified, then limit the number digits to the + * right of the decimal point. + */ + + if (prec > 0) + { + nchars = MIN(numlen, prec); + } + else + { + nchars = numlen; + } + + /* Print the fractional part to the right of the decimal point */ + + for (i = nchars; i > 0; i--) + { + obj->put(obj, *digits); + digits++; + } + + /* Decremnt to get the number of trailing zeroes to print */ + + prec -= nchars; + } + + /* Finally, print any trailing zeroes */ + + zeroes(obj, prec); + + /* Is this memory supposed to be freed or not? */ + +#if 0 + if (digalloc) + { + free(digalloc); + } +#endif +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + diff --git a/nuttx/lib/stdio/lib_libfflush.c b/nuttx/lib/stdio/lib_libfflush.c new file mode 100644 index 0000000000..2a4fe29326 --- /dev/null +++ b/nuttx/lib/stdio/lib_libfflush.c @@ -0,0 +1,202 @@ +/**************************************************************************** + * lib/stdio/lib_libfflush.c + * + * Copyright (C) 2007-2008, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_fflush + * + * Description: + * The function lib_fflush() forces a write of all user-space buffered data for + * the given output or update stream via the stream's underlying write + * function. The open status of the stream is unaffected. + * + * Parmeters: + * stream - the stream to flush + * bforce - flush must be complete. + * + * Return: + * A negated errno value on failure, otherwise the number of bytes remaining + * in the buffer. + * + ****************************************************************************/ + +ssize_t lib_fflush(FAR FILE *stream, bool bforce) +{ +#if CONFIG_STDIO_BUFFER_SIZE > 0 + FAR const unsigned char *src; + ssize_t bytes_written; + ssize_t nbuffer; + + /* Return EBADF if the file is not opened for writing */ + + if (stream->fs_filedes < 0 || (stream->fs_oflags & O_WROK) == 0) + { + return -EBADF; + } + + /* Make sure that we have exclusive access to the stream */ + + lib_take_semaphore(stream); + + /* Make sure that the buffer holds valid data */ + + if (stream->fs_bufpos != stream->fs_bufstart) + { + /* Make sure that the buffer holds buffered write data. We do not + * support concurrent read/write buffer usage. + */ + + if (stream->fs_bufread != stream->fs_bufstart) + { + /* The buffer holds read data... just return zero meaning "no bytes + * remaining in the buffer." + */ + + lib_give_semaphore(stream); + return 0; + } + + /* How many bytes of write data are used in the buffer now */ + + nbuffer = stream->fs_bufpos - stream->fs_bufstart; + + /* Try to write that amount */ + + src = stream->fs_bufstart; + do + { + /* Perform the write */ + + bytes_written = write(stream->fs_filedes, src, nbuffer); + if (bytes_written < 0) + { + /* Write failed. The cause of the failure is in 'errno'. + * returned the negated errno value. + */ + + lib_give_semaphore(stream); + return -get_errno(); + } + + /* Handle partial writes. fflush() must either return with + * an error condition or with the data successfully flushed + * from the buffer. + */ + + src += bytes_written; + nbuffer -= bytes_written; + } + while (bforce && nbuffer > 0); + + /* Reset the buffer position to the beginning of the buffer */ + + stream->fs_bufpos = stream->fs_bufstart; + + /* For the case of an incomplete write, nbuffer will be non-zero + * It will hold the number of bytes that were not written. + * Move the data down in the buffer to handle this (rare) case + */ + + while (nbuffer) + { + *stream->fs_bufpos++ = *src++; + --nbuffer; + } + } + + /* Restore normal access to the stream and return the number of bytes + * remaining in the buffer. + */ + + lib_give_semaphore(stream); + return stream->fs_bufpos - stream->fs_bufstart; +#else + /* Return no bytes remaining in the buffer */ + + return 0; +#endif +} + diff --git a/nuttx/lib/stdio/lib_libflushall.c b/nuttx/lib/stdio/lib_libflushall.c new file mode 100644 index 0000000000..9d0a89e9c1 --- /dev/null +++ b/nuttx/lib/stdio/lib_libflushall.c @@ -0,0 +1,137 @@ +/**************************************************************************** + * lib/stdio/lib_libflushall.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_flushall + * + * Description: + * Called either (1) by the OS when a task exits, or (2) from fflush() + * when a NULL stream argument is provided. + * + ****************************************************************************/ + +int lib_flushall(FAR struct streamlist *list) +{ + int lasterrno = OK; + int ret; + + /* Make sure that there are streams associated with this thread */ + + if (list) + { + int i; + + /* Process each stream in the thread's stream list */ + + stream_semtake(list); + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + { + FILE *stream = &list->sl_streams[i]; + + /* If the stream is open (i.e., assigned a non-negative file + * descriptor) and opened for writing, then flush all of the pending + * write data in the stream. + */ + + if (stream->fs_filedes >= 0 && (stream->fs_oflags & O_WROK) != 0) + { + /* Flush the writable FILE */ + + ret = lib_fflush(stream, true); + if (ret < 0) + { + /* An error occurred during the flush AND/OR we were unable + * to flush all of the buffered write data. Remember the + * last errcode. + */ + + lasterrno = ret; + } + } + } + + stream_semgive(list); + } + + /* If any flush failed, return the errorcode of the last failed flush */ + + return lasterrno; +} diff --git a/nuttx/lib/stdio/lib_libfread.c b/nuttx/lib/stdio/lib_libfread.c new file mode 100644 index 0000000000..03b47eda66 --- /dev/null +++ b/nuttx/lib/stdio/lib_libfread.c @@ -0,0 +1,290 @@ +/**************************************************************************** + * lib/stdio/lib_libfread.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include /* for CONFIG_STDIO_BUFFER_SIZE */ + +#include +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_fread + ****************************************************************************/ + +ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) +{ + unsigned char *dest = (unsigned char*)ptr; + ssize_t bytes_read; + int ret; + + /* Make sure that reading from this stream is allowed */ + + if (!stream || (stream->fs_oflags & O_RDOK) == 0) + { + set_errno(EBADF); + bytes_read = -1; + } + else + { + /* The stream must be stable until we complete the read */ + + lib_take_semaphore(stream); + +#if CONFIG_NUNGET_CHARS > 0 + /* First, re-read any previously ungotten characters */ + + while ((stream->fs_nungotten > 0) && (count > 0)) + { + /* Decrement the count of ungotten bytes to get an index */ + + stream->fs_nungotten--; + + /* Return the last ungotten byte */ + + *dest++ = stream->fs_ungotten[stream->fs_nungotten]; + + /* That's one less byte that we have to read */ + + count--; + } +#endif + +#if CONFIG_STDIO_BUFFER_SIZE > 0 + /* If the buffer is currently being used for write access, then + * flush all of the buffered write data. We do not support concurrent + * buffered read/write access. + */ + + ret = lib_wrflush(stream); + if (ret < 0) + { + lib_give_semaphore(stream); + return ret; + } + + /* Now get any other needed chars from the buffer or the file. */ + + while (count > 0) + { + /* Is there readable data in the buffer? */ + + while ((count > 0) && (stream->fs_bufpos < stream->fs_bufread)) + { + /* Yes, copy a byte into the user buffer */ + + *dest++ = *stream->fs_bufpos++; + count--; + } + + /* The buffer is empty OR we have already supplied the number of + * bytes requested in the read. Check if we need to read + * more from the file. + */ + + if (count > 0) + { + size_t buffer_available; + + /* We need to read more data into the buffer from the file */ + + /* Mark the buffer empty */ + + stream->fs_bufpos = stream->fs_bufread = stream->fs_bufstart; + + /* How much space is available in the buffer? */ + + buffer_available = stream->fs_bufend - stream->fs_bufread; + + /* Will the number of bytes that we need to read fit into + * the buffer space that is available? If the read size is + * larger than the buffer, then read some of the data + * directly into the user's buffer. + */ + + if (count > buffer_available) + { + bytes_read = read(stream->fs_filedes, dest, count); + if (bytes_read < 0) + { + /* An error occurred on the read. The error code is + * in the 'errno' variable. + */ + + goto errout_with_errno; + } + else if (bytes_read == 0) + { + /* We are at the end of the file */ + + goto shortread; + } + else + { + /* Some bytes were read. Adjust the dest pointer */ + + dest += bytes_read; + + /* Were all of the requested bytes read? */ + + if (bytes_read < count) + { + /* No. We must be at the end of file. */ + + goto shortread; + } + else + { + /* Yes. We are done. */ + + count = 0; + } + } + } + else + { + /* The number of bytes required to satisfy the read + * is less than or equal to the size of the buffer + * space that we have left. Read as much as we can + * into the buffer. + */ + + bytes_read = read(stream->fs_filedes, stream->fs_bufread, buffer_available); + if (bytes_read < 0) + { + /* An error occurred on the read. The error code is + * in the 'errno' variable. + */ + + goto errout_with_errno; + } + else if (bytes_read == 0) + { + /* We are at the end of the file */ + + goto shortread; + } + else + { + /* Some bytes were read */ + + stream->fs_bufread += bytes_read; + } + } + } + } +#else + /* Now get any other needed chars from the file. */ + + while (count > 0) + { + bytes_read = read(stream->fs_filedes, dest, count); + if (bytes_read < 0) + { + /* An error occurred on the read. The error code is + * in the 'errno' variable. + */ + + goto errout_with_errno; + } + else if (bytes_read == 0) + { + break; + } + else + { + dest += bytes_read; + count -= bytes_read; + } + } +#endif + /* Here after a successful (but perhaps short) read */ + +#if CONFIG_STDIO_BUFFER_SIZE > 0 + shortread: +#endif + bytes_read = dest - (unsigned char*)ptr; + } + + lib_give_semaphore(stream); + return bytes_read; + +/* Error exits */ + +errout_with_errno: + lib_give_semaphore(stream); + return -get_errno(); +} + diff --git a/nuttx/lib/stdio/lib_libfwrite.c b/nuttx/lib/stdio/lib_libfwrite.c new file mode 100644 index 0000000000..e71866b498 --- /dev/null +++ b/nuttx/lib/stdio/lib_libfwrite.c @@ -0,0 +1,179 @@ +/**************************************************************************** + * lib/stdio/lib_libfwrite.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include /* for CONFIG_STDIO_BUFFER_SIZE */ + +#include +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_fwrite + ****************************************************************************/ + +ssize_t lib_fwrite(FAR const void *ptr, size_t count, FAR FILE *stream) +#if CONFIG_STDIO_BUFFER_SIZE > 0 +{ + FAR const unsigned char *start = ptr; + FAR const unsigned char *src = ptr; + ssize_t ret = ERROR; + unsigned char *dest; + + /* Make sure that writing to this stream is allowed */ + + if (!stream || (stream->fs_oflags & O_WROK) == 0) + { + set_errno(EBADF); + goto errout; + } + + /* Get exclusive access to the stream */ + + lib_take_semaphore(stream); + + /* If the buffer is currently being used for read access, then + * discard all of the read-ahead data. We do not support concurrent + * buffered read/write access. + */ + + if (lib_rdflush(stream) < 0) + { + goto errout_with_semaphore; + } + + /* Loop until all of the bytes have been buffered */ + + while (count > 0) + { + /* Determine the number of bytes left in the buffer */ + + size_t gulp_size = stream->fs_bufend - stream->fs_bufpos; + + /* Will the user data fit into the amount of buffer space + * that we have left? + */ + + if (gulp_size > count) + { + /* Yes, clip the gulp to the size of the user data */ + + gulp_size = count; + } + + /* Adjust the number of bytes remaining to be transferred + * on the next pass through the loop (might be zero). + */ + + count -= gulp_size; + + /* Transfer the data into the buffer */ + + for (dest = stream->fs_bufpos; gulp_size > 0; gulp_size--) + { + *dest++ = *src++; + } + stream->fs_bufpos = dest; + + /* Is the buffer full? */ + + if (dest >= stream->fs_bufend) + { + /* Flush the buffered data to the IO stream */ + + int bytes_buffered = lib_fflush(stream, false); + if (bytes_buffered < 0) + { + goto errout_with_semaphore; + } + } + } + + /* Return the number of bytes written */ + + ret = src - start; + +errout_with_semaphore: + lib_give_semaphore(stream); + +errout: + return ret; +} +#else +{ + return write(stream->fs_filedes, ptr, count); +} +#endif /* CONFIG_STDIO_BUFFER_SIZE */ + diff --git a/nuttx/lib/stdio/lib_libnoflush.c b/nuttx/lib/stdio/lib_libnoflush.c new file mode 100644 index 0000000000..e3b8911534 --- /dev/null +++ b/nuttx/lib/stdio/lib_libnoflush.c @@ -0,0 +1,103 @@ +/**************************************************************************** + * lib/stdio/lib_libnoflush.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +#include "lib_internal.h" + +#ifdef CONFIG_STDIO_LINEBUFFER + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_noflush + * + * Description: + * lib_noflush() provides a common, dummy flush method for output streams + * that are not flushable. Only used if CONFIG_STDIO_LINEBUFFER is selected. + * + * Return: + * Always returns OK + * + ****************************************************************************/ + +int lib_noflush(FAR struct lib_outstream_s *this) +{ + return OK; +} + +#endif /* CONFIG_STDIO_LINEBUFFER */ + diff --git a/nuttx/lib/stdio/lib_libsprintf.c b/nuttx/lib/stdio/lib_libsprintf.c new file mode 100644 index 0000000000..2474a6f01d --- /dev/null +++ b/nuttx/lib/stdio/lib_libsprintf.c @@ -0,0 +1,90 @@ +/**************************************************************************** + * lib/stdio/lib_libsprintf.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_sprintf + ****************************************************************************/ + +int lib_sprintf(FAR struct lib_outstream_s *obj, const char *fmt, ...) +{ + va_list ap; + int n; + + /* Let lib_vsprintf do the real work */ + + va_start(ap, fmt); + n = lib_vsprintf(obj, fmt, ap); + va_end(ap); + return n; +} diff --git a/nuttx/lib/stdio/lib_libvsprintf.c b/nuttx/lib/stdio/lib_libvsprintf.c new file mode 100644 index 0000000000..30c988599c --- /dev/null +++ b/nuttx/lib/stdio/lib_libvsprintf.c @@ -0,0 +1,1620 @@ +/**************************************************************************** + * lib/stdio/lib_libvsprintf.c + * + * Copyright (C) 2007-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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* If you have floating point but no fieldwidth, then use a fixed (but + * configurable) floating point precision. + */ + +#if defined(CONFIG_LIBC_FLOATINGPOINT) && \ + defined(CONFIG_NOPRINTF_FIELDWIDTH) && \ + !defined(CONFIG_LIBC_FIXEDPRECISION) +# define CONFIG_LIBC_FIXEDPRECISION 3 +#endif + +#define FLAG_SHOWPLUS 0x01 +#define FLAG_ALTFORM 0x02 +#define FLAG_HASDOT 0x04 +#define FLAG_HASASTERISKWIDTH 0x08 +#define FLAG_HASASTERISKTRUNC 0x10 +#define FLAG_LONGPRECISION 0x20 +#define FLAG_LONGLONGPRECISION 0x40 +#define FLAG_NEGATE 0x80 + +#define SET_SHOWPLUS(f) do (f) |= FLAG_SHOWPLUS; while (0) +#define SET_ALTFORM(f) do (f) |= FLAG_ALTFORM; while (0) +#define SET_HASDOT(f) do (f) |= FLAG_HASDOT; while (0) +#define SET_HASASTERISKWIDTH(f) do (f) |= FLAG_HASASTERISKWIDTH; while (0) +#define SET_HASASTERISKTRUNC(f) do (f) |= FLAG_HASASTERISKTRUNC; while (0) +#define SET_LONGPRECISION(f) do (f) |= FLAG_LONGPRECISION; while (0) +#define SET_LONGLONGPRECISION(f) do (f) |= FLAG_LONGLONGPRECISION; while (0) +#define SET_NEGATE(f) do (f) |= FLAG_NEGATE; while (0) + +#define CLR_SHOWPLUS(f) do (f) &= ~FLAG_SHOWPLUS; while (0) +#define CLR_ALTFORM(f) do (f) &= ~FLAG_ALTFORM; while (0) +#define CLR_HASDOT(f) do (f) &= ~FLAG_HASDOT; while (0) +#define CLR_HASASTERISKWIDTH(f) do (f) &= ~FLAG_HASASTERISKWIDTH; while (0) +#define CLR_HASASTERISKTRUNC(f) do (f) &= ~FLAG_HASASTERISKTRUNC; while (0) +#define CLR_LONGPRECISION(f) do (f) &= ~FLAG_LONGPRECISION; while (0) +#define CLR_LONGLONGPRECISION(f) do (f) &= ~FLAG_LONGLONGPRECISION; while (0) +#define CLR_NEGATE(f) do (f) &= ~FLAG_NEGATE; while (0) +#define CLR_SIGNED(f) do (f) &= ~(FLAG_SHOWPLUS|FLAG_NEGATE); while (0) + +#define IS_SHOWPLUS(f) (((f) & FLAG_SHOWPLUS) != 0) +#define IS_ALTFORM(f) (((f) & FLAG_ALTFORM) != 0) +#define IS_HASDOT(f) (((f) & FLAG_HASDOT) != 0) +#define IS_HASASTERISKWIDTH(f) (((f) & FLAG_HASASTERISKWIDTH) != 0) +#define IS_HASASTERISKTRUNC(f) (((f) & FLAG_HASASTERISKTRUNC) != 0) +#define IS_LONGPRECISION(f) (((f) & FLAG_LONGPRECISION) != 0) +#define IS_LONGLONGPRECISION(f) (((f) & FLAG_LONGLONGPRECISION) != 0) +#define IS_NEGATE(f) (((f) & FLAG_NEGATE) != 0) +#define IS_SIGNED(f) (((f) & (FLAG_SHOWPLUS|FLAG_NEGATE)) != 0) + +/* If CONFIG_ARCH_ROMGETC is defined, then it is assumed that the format + * string data cannot be accessed by simply de-referencing the format string + * pointer. This might be in the case in Harvard architectures where string + * data might be stored in instruction space or if string data were stored + * on some media like EEPROM or external serial FLASH. In all of these cases, + * string data has to be accessed indirectly using the architecture-supplied + * up_romgetc(). The following mechanisms attempt to make these different + * access methods indistinguishable in the following code. + * + * NOTE: It is assumed that string arguments for %s still reside in memory + * that can be directly accessed by de-referencing the string pointer. + */ + +#ifdef CONFIG_ARCH_ROMGETC +# define FMT_TOP ch = up_romgetc(src) /* Loop initialization */ +# define FMT_BOTTOM src++, ch = up_romgetc(src) /* Bottom of a loop */ +# define FMT_CHAR ch /* Access a character */ +# define FMT_NEXT src++; ch = up_romgetc(src) /* Advance to the next character */ +# define FMT_PREV src--; ch = up_romgetc(src) /* Backup to the previous character */ +#else +# define FMT_TOP /* Loop initialization */ +# define FMT_BOTTOM src++ /* Bottom of a loop */ +# define FMT_CHAR *src /* Access a character */ +# define FMT_NEXT src++ /* Advance to the next character */ +# define FMT_PREV src-- /* Backup to the previous character */ +#endif + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +enum +{ + FMT_RJUST = 0, /* Default */ + FMT_LJUST, + FMT_RJUST0, + FMT_CENTER +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Pointer to ASCII conversion */ + +#ifdef CONFIG_PTR_IS_NOT_INT +static void ptohex(FAR struct lib_outstream_s *obj, uint8_t flags, FAR void *p); +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static int getsizesize(uint8_t fmt, uint8_t flags, FAR void *p) +#endif /* CONFIG_NOPRINTF_FIELDWIDTH */ +#endif /* CONFIG_PTR_IS_NOT_INT */ + +/* Unsigned int to ASCII conversion */ + +static void utodec(FAR struct lib_outstream_s *obj, unsigned int n); +static void utohex(FAR struct lib_outstream_s *obj, unsigned int n, uint8_t a); +static void utooct(FAR struct lib_outstream_s *obj, unsigned int n); +static void utobin(FAR struct lib_outstream_s *obj, unsigned int n); +static void utoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, + uint8_t flags, unsigned int lln); + +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static void fixup(uint8_t fmt, FAR uint8_t *flags, int *n); +static int getusize(uint8_t fmt, uint8_t flags, unsigned int lln); +#endif + +/* Unsigned long int to ASCII conversion */ + +#ifdef CONFIG_LONG_IS_NOT_INT +static void lutodec(FAR struct lib_outstream_s *obj, unsigned long ln); +static void lutohex(FAR struct lib_outstream_s *obj, unsigned long ln, uint8_t a); +static void lutooct(FAR struct lib_outstream_s *obj, unsigned long ln); +static void lutobin(FAR struct lib_outstream_s *obj, unsigned long ln); +static void lutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, + uint8_t flags, unsigned long ln); +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static void lfixup(uint8_t fmt, FAR uint8_t *flags, long *ln); +static int getlusize(uint8_t fmt, FAR uint8_t flags, unsigned long ln); +#endif +#endif + +/* Unsigned long long int to ASCII conversions */ + +#ifdef CONFIG_HAVE_LONG_LONG +static void llutodec(FAR struct lib_outstream_s *obj, unsigned long long lln); +static void llutohex(FAR struct lib_outstream_s *obj, unsigned long long lln, uint8_t a); +static void llutooct(FAR struct lib_outstream_s *obj, unsigned long long lln); +static void llutobin(FAR struct lib_outstream_s *obj, unsigned long long lln); +static void llutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, + uint8_t flags, unsigned long long lln); +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static void llfixup(uint8_t fmt, FAR uint8_t *flags, FAR long long *lln); +static int getllusize(uint8_t fmt, FAR uint8_t flags, FAR unsigned long long lln); +#endif +#endif + +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static void prejustify(FAR struct lib_outstream_s *obj, uint8_t fmt, + uint8_t flags, int fieldwidth, int valwidth); +static void postjustify(FAR struct lib_outstream_s *obj, uint8_t fmt, + uint8_t flags, int fieldwidth, int valwidth); +#endif + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +static const char g_nullstring[] = "(null)"; + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/* Include floating point functions */ + +#ifdef CONFIG_LIBC_FLOATINGPOINT +# include "stdio/lib_libdtoa.c" +#endif + +/**************************************************************************** + * Name: ptohex + ****************************************************************************/ + +#ifdef CONFIG_PTR_IS_NOT_INT +static void ptohex(FAR struct lib_outstream_s *obj, uint8_t flags, FAR void *p) +{ + union + { + uint32_t dw; + FAR void *p; + } u; + uint8_t bits; + + /* Check for alternate form */ + + if (IS_ALTFORM(flags)) + { + /* Prefix the number with "0x" */ + + obj->put(obj, '0'); + obj->put(obj, 'x'); + } + + u.dw = 0; + u.p = p; + + for (bits = 8*sizeof(void *); bits > 0; bits -= 4) + { + uint8_t nibble = (uint8_t)((u.dw >> (bits - 4)) & 0xf); + if (nibble < 10) + { + obj->put(obj, nibble + '0'); + } + else + { + obj->put(obj, nibble + 'a' - 10); + } + } +} + +/**************************************************************************** + * Name: getpsize + ****************************************************************************/ + +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static int getpsize(uint8_t flags, FAR void *p) +{ + struct lib_outstream_s nulloutstream; + lib_nulloutstream(&nulloutstream); + + ptohex(&nulloutstream, flags, p); + return nulloutstream.nput; +} + +#endif /* CONFIG_NOPRINTF_FIELDWIDTH */ +#endif /* CONFIG_PTR_IS_NOT_INT */ + +/**************************************************************************** + * Name: utodec + ****************************************************************************/ + +static void utodec(FAR struct lib_outstream_s *obj, unsigned int n) +{ + unsigned int remainder = n % 10; + unsigned int dividend = n / 10; + + if (dividend) + { + utodec(obj, dividend); + } + + obj->put(obj, (remainder + (unsigned int)'0')); +} + +/**************************************************************************** + * Name: utohex + ****************************************************************************/ + +static void utohex(FAR struct lib_outstream_s *obj, unsigned int n, uint8_t a) +{ + bool nonzero = false; + uint8_t bits; + + for (bits = 8*sizeof(unsigned int); bits > 0; bits -= 4) + { + uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf); + if (nibble || nonzero) + { + nonzero = true; + + if (nibble < 10) + { + obj->put(obj, nibble + '0'); + } + else + { + obj->put(obj, nibble + a - 10); + } + } + } + + if (!nonzero) + { + obj->put(obj, '0'); + } +} + +/**************************************************************************** + * Name: utooct + ****************************************************************************/ + +static void utooct(FAR struct lib_outstream_s *obj, unsigned int n) +{ + unsigned int remainder = n & 0x7; + unsigned int dividend = n >> 3; + + if (dividend) + { + utooct(obj, dividend); + } + + obj->put(obj, (remainder + (unsigned int)'0')); +} + +/**************************************************************************** + * Name: utobin + ****************************************************************************/ + +static void utobin(FAR struct lib_outstream_s *obj, unsigned int n) +{ + unsigned int remainder = n & 1; + unsigned int dividend = n >> 1; + + if (dividend) + { + utobin(obj, dividend); + } + + obj->put(obj, (remainder + (unsigned int)'0')); +} + +/**************************************************************************** + * Name: utoascii + ****************************************************************************/ + +static void utoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned int n) +{ + /* Perform the integer conversion according to the format specifier */ + + switch (fmt) + { + case 'd': + case 'i': + /* Signed base 10 */ + { +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + if ((int)n < 0) + { + obj->put(obj, '-'); + n = (unsigned int)(-(int)n); + } + else if (IS_SHOWPLUS(flags)) + { + obj->put(obj, '+'); + } +#endif + /* Convert the unsigned value to a string. */ + + utodec(obj, n); + } + break; + + case 'u': + /* Unigned base 10 */ + { +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + if (IS_SHOWPLUS(flags)) + { + obj->put(obj, '+'); + } +#endif + /* Convert the unsigned value to a string. */ + + utodec(obj, n); + } + break; + +#ifndef CONFIG_PTR_IS_NOT_INT + case 'p': +#endif + case 'x': + case 'X': + /* Hexadecimal */ + { + /* Check for alternate form */ + + if (IS_ALTFORM(flags)) + { + /* Prefix the number with "0x" */ + + obj->put(obj, '0'); + obj->put(obj, 'x'); + } + + /* Convert the unsigned value to a string. */ + + if (fmt == 'X') + { + utohex(obj, n, 'A'); + } + else + { + utohex(obj, n, 'a'); + } + } + break; + + case 'o': + /* Octal */ + { + /* Check for alternate form */ + + if (IS_ALTFORM(flags)) + { + /* Prefix the number with '0' */ + + obj->put(obj, '0'); + } + + /* Convert the unsigned value to a string. */ + + utooct(obj, n); + } + break; + + case 'b': + /* Binary */ + { + /* Convert the unsigned value to a string. */ + + utobin(obj, n); + } + break; + +#ifdef CONFIG_PTR_IS_NOT_INT + case 'p': +#endif + default: + break; + } +} + +/**************************************************************************** + * Name: fixup + ****************************************************************************/ + +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static void fixup(uint8_t fmt, FAR uint8_t *flags, FAR int *n) +{ + /* Perform the integer conversion according to the format specifier */ + + switch (fmt) + { + case 'd': + case 'i': + /* Signed base 10 */ + + if (*n < 0) + { + SET_NEGATE(*flags); + CLR_SHOWPLUS(*flags); + *n = -*n; + } + break; + + case 'u': + /* Unsigned base 10 */ + break; + + case 'p': + case 'x': + case 'X': + /* Hexadecimal */ + case 'o': + /* Octal */ + case 'b': + /* Binary */ + CLR_SIGNED(*flags); + break; + + default: + break; + } +} + +/**************************************************************************** + * Name: getusize + ****************************************************************************/ + +static int getusize(uint8_t fmt, uint8_t flags, unsigned int n) +{ + struct lib_outstream_s nulloutstream; + lib_nulloutstream(&nulloutstream); + + utoascii(&nulloutstream, fmt, flags, n); + return nulloutstream.nput; +} + +/**************************************************************************** + * Name: getdblsize + ****************************************************************************/ + +#ifdef CONFIG_LIBC_FLOATINGPOINT +static int getdblsize(uint8_t fmt, int trunc, uint8_t flags, double n) +{ + struct lib_outstream_s nulloutstream; + lib_nulloutstream(&nulloutstream); + + lib_dtoa(&nulloutstream, fmt, trunc, flags, n); + return nulloutstream.nput; +} +#endif +#endif /* CONFIG_NOPRINTF_FIELDWIDTH */ + +#ifdef CONFIG_LONG_IS_NOT_INT +/**************************************************************************** + * Name: lutodec + ****************************************************************************/ + +static void lutodec(FAR struct lib_outstream_s *obj, unsigned long n) +{ + unsigned int remainder = n % 10; + unsigned long dividend = n / 10; + + if (dividend) + { + lutodec(obj, dividend); + } + + obj->put(obj, (remainder + (unsigned int)'0')); +} + +/**************************************************************************** + * Name: lutohex + ****************************************************************************/ + +static void lutohex(FAR struct lib_outstream_s *obj, unsigned long n, uint8_t a) +{ + bool nonzero = false; + uint8_t bits; + + for (bits = 8*sizeof(unsigned long); bits > 0; bits -= 4) + { + uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf); + if (nibble || nonzero) + { + nonzero = true; + + if (nibble < 10) + { + obj->put(obj, nibble + '0'); + } + else + { + obj->put(obj, nibble + a - 10); + } + } + } + + if (!nonzero) + { + obj->put(obj, '0'); + } +} + +/**************************************************************************** + * Name: lutooct + ****************************************************************************/ + +static void lutooct(FAR struct lib_outstream_s *obj, unsigned long n) +{ + unsigned int remainder = n & 0x7; + unsigned long dividend = n >> 3; + + if (dividend) + { + lutooct(obj, dividend); + } + + obj->put(obj, (remainder + (unsigned int)'0')); +} + +/**************************************************************************** + * Name: lutobin + ****************************************************************************/ + +static void lutobin(FAR struct lib_outstream_s *obj, unsigned long n) +{ + unsigned int remainder = n & 1; + unsigned long dividend = n >> 1; + + if (dividend) + { + lutobin(obj, dividend); + } + + obj->put(obj, (remainder + (unsigned int)'0')); +} + +/**************************************************************************** + * Name: lutoascii + ****************************************************************************/ + +static void lutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned long ln) +{ + /* Perform the integer conversion according to the format specifier */ + + switch (fmt) + { + case 'd': + case 'i': + /* Signed base 10 */ + { +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + if ((long)ln < 0) + { + obj->put(obj, '-'); + ln = (unsigned long)(-(long)ln); + } + else if (IS_SHOWPLUS(flags)) + { + obj->put(obj, '+'); + } +#endif + /* Convert the unsigned value to a string. */ + + lutodec(obj, ln); + } + break; + + case 'u': + /* Unigned base 10 */ + { +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + if (IS_SHOWPLUS(flags)) + { + obj->put(obj, '+'); + } +#endif + /* Convert the unsigned value to a string. */ + + lutodec(obj, ln); + } + break; + + case 'x': + case 'X': + /* Hexadecimal */ + { + /* Check for alternate form */ + + if (IS_ALTFORM(flags)) + { + /* Prefix the number with "0x" */ + + obj->put(obj, '0'); + obj->put(obj, 'x'); + } + + /* Convert the unsigned value to a string. */ + + if (fmt == 'X') + { + lutohex(obj, ln, 'A'); + } + else + { + lutohex(obj, ln, 'a'); + } + } + break; + + case 'o': + /* Octal */ + { + /* Check for alternate form */ + + if (IS_ALTFORM(flags)) + { + /* Prefix the number with '0' */ + + obj->put(obj, '0'); + } + + /* Convert the unsigned value to a string. */ + + lutooct(obj, ln); + } + break; + + case 'b': + /* Binary */ + { + /* Convert the unsigned value to a string. */ + + lutobin(obj, ln); + } + break; + + case 'p': + default: + break; + } +} + +/**************************************************************************** + * Name: lfixup + ****************************************************************************/ + +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static void lfixup(uint8_t fmt, FAR uint8_t *flags, FAR long *ln) +{ + /* Perform the integer conversion according to the format specifier */ + + switch (fmt) + { + case 'd': + case 'i': + /* Signed base 10 */ + + if (*ln < 0) + { + SET_NEGATE(*flags); + CLR_SHOWPLUS(*flags); + *ln = -*ln; + } + break; + + case 'u': + /* Unsigned base 10 */ + break; + + case 'p': + case 'x': + case 'X': + /* Hexadecimal */ + case 'o': + /* Octal */ + case 'b': + /* Binary */ + CLR_SIGNED(*flags); + break; + + default: + break; + } +} + +/**************************************************************************** + * Name: getlusize + ****************************************************************************/ + +static int getlusize(uint8_t fmt, uint8_t flags, unsigned long ln) +{ + struct lib_outstream_s nulloutstream; + lib_nulloutstream(&nulloutstream); + + lutoascii(&nulloutstream, fmt, flags, ln); + return nulloutstream.nput; +} + +#endif /* CONFIG_NOPRINTF_FIELDWIDTH */ +#endif /* CONFIG_LONG_IS_NOT_INT */ + +#ifdef CONFIG_HAVE_LONG_LONG +/**************************************************************************** + * Name: llutodec + ****************************************************************************/ + +static void llutodec(FAR struct lib_outstream_s *obj, unsigned long long n) +{ + unsigned int remainder = n % 10; + unsigned long long dividend = n / 10; + + if (dividend) + { + llutodec(obj, dividend); + } + + obj->put(obj, (remainder + (unsigned int)'0')); +} + +/**************************************************************************** + * Name: llutohex + ****************************************************************************/ + +static void llutohex(FAR struct lib_outstream_s *obj, unsigned long long n, uint8_t a) +{ + bool nonzero = false; + uint8_t bits; + + for (bits = 8*sizeof(unsigned long long); bits > 0; bits -= 4) + { + uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf); + if (nibble || nonzero) + { + nonzero = true; + + if (nibble < 10) + { + obj->put(obj, (nibble + '0')); + } + else + { + obj->put(obj, (nibble + a - 10)); + } + } + } + + if (!nonzero) + { + obj->put(obj, '0'); + } +} + +/**************************************************************************** + * Name: llutooct + ****************************************************************************/ + +static void llutooct(FAR struct lib_outstream_s *obj, unsigned long long n) +{ + unsigned int remainder = n & 0x7; + unsigned long long dividend = n >> 3; + + if (dividend) + { + llutooct(obj, dividend); + } + + obj->put(obj, (remainder + (unsigned int)'0')); +} + +/**************************************************************************** + * Name: llutobin + ****************************************************************************/ + +static void llutobin(FAR struct lib_outstream_s *obj, unsigned long long n) +{ + unsigned int remainder = n & 1; + unsigned long long dividend = n >> 1; + + if (dividend) + { + llutobin(obj, dividend); + } + + obj->put(obj, (remainder + (unsigned int)'0')); +} + +/**************************************************************************** + * Name: llutoascii + ****************************************************************************/ + +static void llutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned long long lln) +{ + /* Perform the integer conversion according to the format specifier */ + + switch (fmt) + { + case 'd': + case 'i': + /* Signed base 10 */ + { +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + if ((long long)lln < 0) + { + obj->put(obj, '-'); + lln = (unsigned long long)(-(long long)lln); + } + else if (IS_SHOWPLUS(flags)) + { + obj->put(obj, '+'); + } +#endif + /* Convert the unsigned value to a string. */ + + llutodec(obj, (unsigned long long)lln); + } + break; + + case 'u': + /* Unigned base 10 */ + { +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + if (IS_SHOWPLUS(flags)) + { + obj->put(obj, '+'); + } +#endif + /* Convert the unsigned value to a string. */ + + llutodec(obj, (unsigned long long)lln); + } + break; + + case 'x': + case 'X': + /* Hexadecimal */ + { + /* Check for alternate form */ + + if (IS_ALTFORM(flags)) + { + /* Prefix the number with "0x" */ + + obj->put(obj, '0'); + obj->put(obj, 'x'); + } + + /* Convert the unsigned value to a string. */ + + if (fmt == 'X') + { + llutohex(obj, (unsigned long long)lln, 'A'); + } + else + { + llutohex(obj, (unsigned long long)lln, 'a'); + } + } + break; + + case 'o': + /* Octal */ + { + /* Check for alternate form */ + + if (IS_ALTFORM(flags)) + { + /* Prefix the number with '0' */ + + obj->put(obj, '0'); + } + + /* Convert the unsigned value to a string. */ + + llutooct(obj, (unsigned long long)lln); + } + break; + + case 'b': + /* Binary */ + { + /* Convert the unsigned value to a string. */ + + llutobin(obj, (unsigned long long)lln); + } + break; + + case 'p': + default: + break; + } +} + +/**************************************************************************** + * Name: llfixup + ****************************************************************************/ + +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static void llfixup(uint8_t fmt, FAR uint8_t *flags, FAR long long *lln) +{ + /* Perform the integer conversion according to the format specifier */ + + switch (fmt) + { + case 'd': + case 'i': + /* Signed base 10 */ + + if (*lln < 0) + { + SET_NEGATE(*flags); + CLR_SHOWPLUS(*flags); + *lln = -*lln; + } + break; + + case 'u': + /* Unsigned base 10 */ + break; + + case 'p': + case 'x': + case 'X': + /* Hexadecimal */ + case 'o': + /* Octal */ + case 'b': + /* Binary */ + CLR_SIGNED(*flags); + break; + + default: + break; + } +} + +/**************************************************************************** + * Name: getllusize + ****************************************************************************/ + +static int getllusize(uint8_t fmt, uint8_t flags, unsigned long long lln) +{ + struct lib_outstream_s nulloutstream; + lib_nulloutstream(&nulloutstream); + + + llutoascii(&nulloutstream, fmt, flags, lln); + return nulloutstream.nput; +} + +#endif /* CONFIG_NOPRINTF_FIELDWIDTH */ +#endif /* CONFIG_HAVE_LONG_LONG */ + +/**************************************************************************** + * Name: prejustify + ****************************************************************************/ + +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static void prejustify(FAR struct lib_outstream_s *obj, uint8_t fmt, + uint8_t flags, int fieldwidth, int valwidth) +{ + int i; + + switch (fmt) + { + default: + case FMT_RJUST: + if (IS_SIGNED(flags)) + { + valwidth++; + } + + for (i = fieldwidth - valwidth; i > 0; i--) + { + obj->put(obj, ' '); + } + + if (IS_NEGATE(flags)) + { + obj->put(obj, '-'); + } + else if (IS_SHOWPLUS(flags)) + { + obj->put(obj, '+'); + } + break; + + case FMT_RJUST0: + if (IS_NEGATE(flags)) + { + obj->put(obj, '-'); + valwidth++; + } + else if (IS_SHOWPLUS(flags)) + { + obj->put(obj, '+'); + valwidth++; + } + + for (i = fieldwidth - valwidth; i > 0; i--) + { + obj->put(obj, '0'); + } + break; + + case FMT_LJUST: + if (IS_NEGATE(flags)) + { + obj->put(obj, '-'); + } + else if (IS_SHOWPLUS(flags)) + { + obj->put(obj, '+'); + } + break; + } +} +#endif + +/**************************************************************************** + * Name: postjustify + ****************************************************************************/ + +#ifndef CONFIG_NOPRINTF_FIELDWIDTH +static void postjustify(FAR struct lib_outstream_s *obj, uint8_t fmt, + uint8_t flags, int fieldwidth, int valwidth) +{ + int i; + + /* Apply field justification to the integer value. */ + + switch (fmt) + { + default: + case FMT_RJUST: + case FMT_RJUST0: + break; + + case FMT_LJUST: + if (IS_SIGNED(flags)) + { + valwidth++; + } + + for (i = fieldwidth - valwidth; i > 0; i--) + { + obj->put(obj, ' '); + } + break; + } +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * lib/stdio/lib_vsprintf + ****************************************************************************/ + +int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list ap) +{ + FAR char *ptmp; +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + int width; +#ifdef CONFIG_LIBC_FLOATINGPOINT + int trunc; +#endif + uint8_t fmt; +#endif + uint8_t flags; +#ifdef CONFIG_ARCH_ROMGETC + char ch; +#endif + + for (FMT_TOP; FMT_CHAR; FMT_BOTTOM) + { + /* Just copy regular characters */ + + if (FMT_CHAR != '%') + { + /* Output the character */ + + obj->put(obj, FMT_CHAR); + + /* Flush the buffer if a newline is encountered */ + +#ifdef CONFIG_STDIO_LINEBUFFER + if (FMT_CHAR == '\n') + { + /* Should return an error on a failure to flush */ + + (void)obj->flush(obj); + } +#endif + /* Process the next character in the format */ + + continue; + } + + /* We have found a format specifier. Move past it. */ + + FMT_NEXT; + + /* Assume defaults */ + + flags = 0; +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + fmt = FMT_RJUST; + width = 0; +#ifdef CONFIG_LIBC_FLOATINGPOINT + trunc = 0; +#endif +#endif + + /* Process each format qualifier. */ + + for (; FMT_CHAR; FMT_BOTTOM) + { + /* Break out of the loop when the format is known. */ + + if (strchr("diuxXpobeEfgGlLsc%", FMT_CHAR)) + { + break; + } + + /* Check for left justification. */ + + else if (FMT_CHAR == '-') + { +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + fmt = FMT_LJUST; +#endif + } + + /* Check for leading zero fill right justification. */ + + else if (FMT_CHAR == '0') + { +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + fmt = FMT_RJUST0; +#endif + } +#if 0 + /* Center justification. */ + + else if (FMT_CHAR == '~') + { +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + fmt = FMT_CENTER; +#endif + } +#endif + + else if (FMT_CHAR == '*') + { +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + int value = va_arg(ap, int); + if (IS_HASDOT(flags)) + { +#ifdef CONFIG_LIBC_FLOATINGPOINT + trunc = value; + SET_HASASTERISKTRUNC(flags); +#endif + } + else + { + width = value; + SET_HASASTERISKWIDTH(flags); + } +#endif + } + + /* Check for field width */ + + else if (FMT_CHAR >= '1' && FMT_CHAR <= '9') + { +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + do + { + FMT_NEXT; + } + while (FMT_CHAR >= '0' && FMT_CHAR <= '9'); +#else + /* Accumulate the field width integer. */ + + int n = ((int)(FMT_CHAR)) - (int)'0'; + for (;;) + { + FMT_NEXT; + if (FMT_CHAR >= '0' && FMT_CHAR <= '9') + { + n = 10*n + (((int)(FMT_CHAR)) - (int)'0'); + } + else + { + break; + } + } + + if (IS_HASDOT(flags)) + { +#ifdef CONFIG_LIBC_FLOATINGPOINT + trunc = n; +#endif + } + else + { + width = n; + } +#endif + /* Back up to the last digit. */ + + FMT_PREV; + } + + /* Check for a decimal point. */ + + else if (FMT_CHAR == '.') + { +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + SET_HASDOT(flags); +#endif + } + + /* Check for leading plus sign. */ + + else if (FMT_CHAR == '+') + { + SET_SHOWPLUS(flags); + } + + /* Check for alternate form. */ + + else if (FMT_CHAR == '#') + { + SET_ALTFORM(flags); + } + } + + /* "%%" means that a literal '%' was intended (instead of a format + * specification). + */ + + if (FMT_CHAR == '%') + { + obj->put(obj, '%'); + continue; + } + + /* Check for the string format. */ + + if (FMT_CHAR == 's') + { +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + int swidth; +#endif + /* Get the string to output */ + + ptmp = va_arg(ap, char *); + if (!ptmp) + { + ptmp = (char*)g_nullstring; + } + + /* Get the widith of the string and perform right-justification + * operations. + */ + +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + swidth = strlen(ptmp); + prejustify(obj, fmt, 0, width, swidth); +#endif + /* Concatenate the string into the output */ + + while (*ptmp) + { + obj->put(obj, *ptmp); + ptmp++; + } + + /* Perform left-justification operations. */ + +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + postjustify(obj, fmt, 0, width, swidth); +#endif + continue; + } + + /* Check for the character output */ + + else if (FMT_CHAR == 'c') + { + /* Just copy the character into the output. */ + + int n = va_arg(ap, int); + obj->put(obj, n); + continue; + } + + /* Check for the long long prefix. */ + + if (FMT_CHAR == 'L') + { + SET_LONGLONGPRECISION(flags); + FMT_NEXT; + } + else if (FMT_CHAR == 'l') + { + SET_LONGPRECISION(flags); + FMT_NEXT; + if (FMT_CHAR == 'l') + { + SET_LONGLONGPRECISION(flags); + FMT_NEXT; + } + } + + /* Handle integer conversions */ + + if (strchr("diuxXpob", FMT_CHAR)) + { +#ifdef CONFIG_HAVE_LONG_LONG + if (IS_LONGLONGPRECISION(flags) && FMT_CHAR != 'p') + { + long long lln; +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + int lluwidth; +#endif + /* Extract the long long value. */ + + lln = va_arg(ap, long long); + +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + /* Output the number */ + + llutoascii(obj, FMT_CHAR, flags, (unsigned long long)lln); +#else + /* Resolve sign-ness and format issues */ + + llfixup(FMT_CHAR, &flags, &lln); + + /* Get the width of the output */ + + lluwidth = getllusize(FMT_CHAR, flags, lln); + + /* Perform left field justification actions */ + + prejustify(obj, fmt, flags, width, lluwidth); + + /* Output the number */ + + llutoascii(obj, FMT_CHAR, flags, (unsigned long long)lln); + + /* Perform right field justification actions */ + + postjustify(obj, fmt, flags, width, lluwidth); +#endif + } + else +#endif /* CONFIG_HAVE_LONG_LONG */ +#ifdef CONFIG_LONG_IS_NOT_INT + if (IS_LONGPRECISION(flags) && FMT_CHAR != 'p') + { + long ln; +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + int luwidth; +#endif + /* Extract the long value. */ + + ln = va_arg(ap, long); + +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + /* Output the number */ + + lutoascii(obj, FMT_CHAR, flags, (unsigned long)ln); +#else + /* Resolve sign-ness and format issues */ + + lfixup(FMT_CHAR, &flags, &ln); + + /* Get the width of the output */ + + luwidth = getlusize(FMT_CHAR, flags, ln); + + /* Perform left field justification actions */ + + prejustify(obj, fmt, flags, width, luwidth); + + /* Output the number */ + + lutoascii(obj, FMT_CHAR, flags, (unsigned long)ln); + + /* Perform right field justification actions */ + + postjustify(obj, fmt, flags, width, luwidth); +#endif + } + else +#endif /* CONFIG_LONG_IS_NOT_INT */ +#ifdef CONFIG_PTR_IS_NOT_INT + if (FMT_CHAR == 'p') + { + void *p; +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + int pwidth; +#endif + /* Extract the integer value. */ + + p = va_arg(ap, void *); + +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + /* Output the pointer value */ + + ptohex(obj, flags, p); +#else + /* Resolve sign-ness and format issues */ + + lfixup(FMT_CHAR, &flags, &ln); + + /* Get the width of the output */ + + luwidth = getpsize(FMT_CHAR, flags, p); + + /* Perform left field justification actions */ + + prejustify(obj, fmt, flags, width, pwidth); + + /* Output the pointer value */ + + ptohex(obj, flags, p); + + /* Perform right field justification actions */ + + postjustify(obj, fmt, flags, width, pwidth); +#endif + } + else +#endif + { + int n; +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + int uwidth; +#endif + /* Extract the long long value. */ + + n = va_arg(ap, int); + +#ifdef CONFIG_NOPRINTF_FIELDWIDTH + /* Output the number */ + + utoascii(obj, FMT_CHAR, flags, (unsigned int)n); +#else + /* Resolve sign-ness and format issues */ + + fixup(FMT_CHAR, &flags, &n); + + /* Get the width of the output */ + + uwidth = getusize(FMT_CHAR, flags, n); + + /* Perform left field justification actions */ + + prejustify(obj, fmt, flags, width, uwidth); + + /* Output the number */ + + utoascii(obj, FMT_CHAR, flags, (unsigned int)n); + + /* Perform right field justification actions */ + + postjustify(obj, fmt, flags, width, uwidth); +#endif + } + } + + /* Handle floating point conversions */ + +#ifdef CONFIG_LIBC_FLOATINGPOINT + else if (strchr("eEfgG", FMT_CHAR)) + { +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + double dblval = va_arg(ap, double); + int dblsize; + + /* Get the width of the output */ + + dblsize = getdblsize(FMT_CHAR, trunc, flags, dblval); + + /* Perform left field justification actions */ + + prejustify(obj, fmt, 0, width, dblsize); + + /* Output the number */ + + lib_dtoa(obj, FMT_CHAR, trunc, flags, dblval); + + /* Perform right field justification actions */ + + postjustify(obj, fmt, 0, width, dblsize); +#else + /* Output the number with a fixed precision */ + + double dblval = va_arg(ap, double); + lib_dtoa(obj, FMT_CHAR, CONFIG_LIBC_FIXEDPRECISION, flags, dblval); +#endif + } +#endif /* CONFIG_LIBC_FLOATINGPOINT */ + } + + return obj->nput; +} + + diff --git a/nuttx/lib/stdio/lib_lowinstream.c b/nuttx/lib/stdio/lib_lowinstream.c new file mode 100644 index 0000000000..499a647ea2 --- /dev/null +++ b/nuttx/lib/stdio/lib_lowinstream.c @@ -0,0 +1,102 @@ +/**************************************************************************** + * lib/stdio/lib_lowinstream.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "lib_internal.h" + +#ifdef CONFIG_ARCH_LOWGETC + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lowinstream_getc + ****************************************************************************/ + +static int lowinstream_getc(FAR struct lib_instream_s *this) +{ + int ret; + + DEBUGASSERT(this); + + /* Get the next character from the incoming stream */ + + ret = up_getc(ch) + if (ret != EOF) + { + this->nget++; + } + + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_lowinstream + * + * Description: + * Initializes a stream for use with low-level, architecture-specific I/O. + * + * Input parameters: + * lowoutstream - User allocated, uninitialized instance of struct + * lib_lowoutstream_s to be initialized. + * + * Returned Value: + * None (User allocated instance initialized). + * + ****************************************************************************/ + +void lib_lowinstream(FAR struct lib_instream_s *stream) +{ + stream->get = lowinstream_getc; + stream->nget = 0; +} + +#endif /* CONFIG_ARCH_LOWGETC */ diff --git a/nuttx/lib/stdio/lib_lowoutstream.c b/nuttx/lib/stdio/lib_lowoutstream.c new file mode 100644 index 0000000000..092f39ca25 --- /dev/null +++ b/nuttx/lib/stdio/lib_lowoutstream.c @@ -0,0 +1,97 @@ +/**************************************************************************** + * lib/stdio/lib_lowoutstream.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef CONFIG_ARCH_LOWPUTC + +#include +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lowoutstream_putc + ****************************************************************************/ + +static void lowoutstream_putc(FAR struct lib_outstream_s *this, int ch) +{ + DEBUGASSERT(this); + + if (up_putc(ch) != EOF) + { + this->nput++; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_lowoutstream + * + * Description: + * Initializes a stream for use with low-level, architecture-specific I/O. + * + * Input parameters: + * lowoutstream - User allocated, uninitialized instance of struct + * lib_lowoutstream_s to be initialized. + * + * Returned Value: + * None (User allocated instance initialized). + * + ****************************************************************************/ + +void lib_lowoutstream(FAR struct lib_outstream_s *stream) +{ + stream->put = lowoutstream_putc; +#ifdef CONFIG_STDIO_LINEBUFFER + stream->flush = lib_noflush; +#endif + stream->nput = 0; +} + +#endif /* CONFIG_ARCH_LOWPUTC */ diff --git a/nuttx/lib/stdio/lib_lowprintf.c b/nuttx/lib/stdio/lib_lowprintf.c new file mode 100644 index 0000000000..392ef2c6a8 --- /dev/null +++ b/nuttx/lib/stdio/lib_lowprintf.c @@ -0,0 +1,128 @@ +/**************************************************************************** + * lib/stdio/lib_lowprintf.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include "lib_internal.h" + +/* This interface can only be used from within the kernel */ + +#if !defined(CONFIG_NUTTX_KERNEL) || defined(__KERNEL__) + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_lowvprintf + ****************************************************************************/ + +#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_SYSLOG) + +int lib_lowvprintf(const char *fmt, va_list ap) +{ + struct lib_outstream_s stream; + + /* Wrap the stdout in a stream object and let lib_vsprintf do the work. */ + +#ifdef CONFIG_SYSLOG + lib_syslogstream((FAR struct lib_outstream_s *)&stream); +#else + lib_lowoutstream((FAR struct lib_outstream_s *)&stream); +#endif + return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); +} + +/**************************************************************************** + * Name: lib_lowprintf + ****************************************************************************/ + +int lib_lowprintf(const char *fmt, ...) +{ + va_list ap; + int ret; + +#ifdef CONFIG_DEBUG_ENABLE + ret = 0; + if (g_dbgenable) +#endif + { + va_start(ap, fmt); + ret = lib_lowvprintf(fmt, ap); + va_end(ap); + } + + return ret; +} + +#endif /* CONFIG_ARCH_LOWPUTC || CONFIG_SYSLOG */ +#endif /* __KERNEL__ */ diff --git a/nuttx/lib/stdio/lib_meminstream.c b/nuttx/lib/stdio/lib_meminstream.c new file mode 100644 index 0000000000..a842096fb4 --- /dev/null +++ b/nuttx/lib/stdio/lib_meminstream.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * lib/stdio/lib_meminstream.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: meminstream_getc + ****************************************************************************/ + +static int meminstream_getc(FAR struct lib_instream_s *this) +{ + FAR struct lib_meminstream_s *mthis = (FAR struct lib_meminstream_s *)this; + int ret; + + DEBUGASSERT(this); + + /* Get the next character (if any) from the buffer */ + + if (this->nget < mthis->buflen) + { + ret = mthis->buffer[this->nget]; + this->nget++; + } + else + { + ret = EOF; + } + + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_meminstream + * + * Description: + * Initializes a stream for use with a fixed-size memory buffer. + * + * Input parameters: + * meminstream - User allocated, uninitialized instance of struct + * lib_meminstream_s to be initialized. + * bufstart - Address of the beginning of the fixed-size memory buffer + * buflen - Size of the fixed-sized memory buffer in bytes + * + * Returned Value: + * None (meminstream initialized). + * + ****************************************************************************/ + +void lib_meminstream(FAR struct lib_meminstream_s *meminstream, + FAR const char *bufstart, int buflen) +{ + meminstream->public.get = meminstream_getc; + meminstream->public.nget = 0; /* Will be buffer index */ + meminstream->buffer = bufstart; /* Start of buffer */ + meminstream->buflen = buflen; /* Length of the buffer */ +} + + diff --git a/nuttx/lib/stdio/lib_memoutstream.c b/nuttx/lib/stdio/lib_memoutstream.c new file mode 100644 index 0000000000..21197358b7 --- /dev/null +++ b/nuttx/lib/stdio/lib_memoutstream.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * lib/stdio/lib_memoutstream.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: memoutstream_putc + ****************************************************************************/ + +static void memoutstream_putc(FAR struct lib_outstream_s *this, int ch) +{ + FAR struct lib_memoutstream_s *mthis = (FAR struct lib_memoutstream_s *)this; + + DEBUGASSERT(this); + + /* If this will not overrun the buffer, then write the character to the + * buffer. Not that buflen was pre-decremented when the stream was + * created so it is okay to write past the end of the buflen by one. + */ + + if (this->nput < mthis->buflen) + { + mthis->buffer[this->nput] = ch; + this->nput++; + mthis->buffer[this->nput] = '\0'; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_memoutstream + * + * Description: + * Initializes a stream for use with a fixed-size memory buffer. + * + * Input parameters: + * memoutstream - User allocated, uninitialized instance of struct + * lib_memoutstream_s to be initialized. + * bufstart - Address of the beginning of the fixed-size memory buffer + * buflen - Size of the fixed-sized memory buffer in bytes + * + * Returned Value: + * None (memoutstream initialized). + * + ****************************************************************************/ + +void lib_memoutstream(FAR struct lib_memoutstream_s *memoutstream, + FAR char *bufstart, int buflen) +{ + memoutstream->public.put = memoutstream_putc; +#ifdef CONFIG_STDIO_LINEBUFFER + memoutstream->public.flush = lib_noflush; +#endif + memoutstream->public.nput = 0; /* Will be buffer index */ + memoutstream->buffer = bufstart; /* Start of buffer */ + memoutstream->buflen = buflen - 1; /* Save space for null terminator */ + memoutstream->buffer[0] = '\0'; /* Start with an empty string */ +} + + diff --git a/nuttx/lib/stdio/lib_nullinstream.c b/nuttx/lib/stdio/lib_nullinstream.c new file mode 100644 index 0000000000..0eadb0a8e4 --- /dev/null +++ b/nuttx/lib/stdio/lib_nullinstream.c @@ -0,0 +1,79 @@ +/**************************************************************************** + * lib/stdio/lib_nullinstream.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static int nullinstream_getc(FAR struct lib_instream_s *this) +{ + return EOF; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_nullinstream + * + * Description: + * Initializes a NULL stream. The initialized stream will will return only + * EOF. + * + * Input parameters: + * nullinstream - User allocated, uninitialized instance of struct + * lib_instream_s to be initialized. + * + * Returned Value: + * None (User allocated instance initialized). + * + ****************************************************************************/ + +void lib_nullinstream(FAR struct lib_instream_s *nullinstream) +{ + nullinstream->get = nullinstream_getc; + nullinstream->nget = 0; +} + diff --git a/nuttx/lib/stdio/lib_nulloutstream.c b/nuttx/lib/stdio/lib_nulloutstream.c new file mode 100644 index 0000000000..69878fd579 --- /dev/null +++ b/nuttx/lib/stdio/lib_nulloutstream.c @@ -0,0 +1,84 @@ +/**************************************************************************** + * lib/stdio/lib_nulloutstream.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static void nulloutstream_putc(FAR struct lib_outstream_s *this, int ch) +{ + DEBUGASSERT(this); + this->nput++; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_nulloutstream + * + * Description: + * Initializes a NULL streams. The initialized stream will write all data + * to the bit-bucket. + * + * Input parameters: + * nulloutstream - User allocated, uninitialized instance of struct + * lib_outstream_s to be initialized. + * + * Returned Value: + * None (User allocated instance initialized). + * + ****************************************************************************/ + +void lib_nulloutstream(FAR struct lib_outstream_s *nulloutstream) +{ + nulloutstream->put = nulloutstream_putc; +#ifdef CONFIG_STDIO_LINEBUFFER + nulloutstream->flush = lib_noflush; +#endif + nulloutstream->nput = 0; +} + diff --git a/nuttx/lib/stdio/lib_perror.c b/nuttx/lib/stdio/lib_perror.c new file mode 100644 index 0000000000..867e113f98 --- /dev/null +++ b/nuttx/lib/stdio/lib_perror.c @@ -0,0 +1,99 @@ +/**************************************************************************** + * lib/stdio/lib_perror.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* POSIX requires that perror provide its output on stderr. This option may + * be defined, however, to provide perror output that is serialized with + * other stdout messages. + */ + +#ifdef CONFIG_LIBC_PERROR_STDOUT +# define PERROR_STREAM stdout +#else +# define PERROR_STREAM stderr +#endif + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: perror + ****************************************************************************/ + +void perror(FAR const char *s) +{ + + /* If strerror() is not enabled, then just print the error number */ + +#ifdef CONFIG_LIBC_STRERROR + (void)fprintf(PERROR_STREAM, "%s: %s\n", s, strerror(errno)); +#else + (void)fprintf(PERROR_STREAM, "%s: Error %d\n", s, errno); +#endif +} + diff --git a/nuttx/lib/stdio/lib_printf.c b/nuttx/lib/stdio/lib_printf.c new file mode 100644 index 0000000000..50db06c475 --- /dev/null +++ b/nuttx/lib/stdio/lib_printf.c @@ -0,0 +1,109 @@ +/**************************************************************************** + * lib/stdio/lib_printf.c + * + * Copyright (C) 2007-2008, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/************************************************************************** + * Global Constant Data + **************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/************************************************************************** + * Private Constant Data + **************************************************************************/ + +/**************************************************************************** + * Private Variables + **************************************************************************/ + +/**************************************************************************** + * Global Functions + **************************************************************************/ + +/**************************************************************************** + * Name: printf + **************************************************************************/ + +int printf(const char *fmt, ...) +{ + va_list ap; + int ret; + + va_start(ap, fmt); +#if CONFIG_NFILE_STREAMS > 0 + ret = vfprintf(stdout, fmt, ap); +#elif CONFIG_NFILE_DESCRIPTORS > 0 + ret = lib_rawvprintf(fmt, ap); +#elif defined(CONFIG_ARCH_LOWPUTC) + ret = lib_lowvprintf(fmt, ap); +#else +# ifdef CONFIG_CPP_HAVE_WARNING +# warning "printf has no data sink" +# endif + ret = 0; +#endif + va_end(ap); + + return ret; +} + diff --git a/nuttx/lib/stdio/lib_puts.c b/nuttx/lib/stdio/lib_puts.c new file mode 100644 index 0000000000..e63a63917f --- /dev/null +++ b/nuttx/lib/stdio/lib_puts.c @@ -0,0 +1,130 @@ +/**************************************************************************** + * lib/stdio/lib_puts.c + * + * Copyright (C) 2007, 2008, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: puts + * + * Description: + * puts() writes the string s and a trailing newline to stdout. + * + ****************************************************************************/ + +int puts(FAR const char *s) +{ + FILE *stream = stdout; + int nwritten; + int nput = EOF; + int ret; + + /* Write the string (the next two steps must be atomic) */ + + lib_take_semaphore(stream); + + /* Write the string without its trailing '\0' */ + + nwritten = fputs(s, stream); + if (nwritten > 0) + { + /* Followed by a newline */ + + char newline = '\n'; + ret = lib_fwrite(&newline, 1, stream); + if (ret > 0) + { + nput = nwritten + 1; + + /* Flush the buffer after the newline is output. */ + +#ifdef CONFIG_STDIO_LINEBUFFER + ret = lib_fflush(stream, true); + if (ret < 0) + { + nput = EOF; + } +#endif + } + } + + lib_give_semaphore(stdout); + return nput; +} + diff --git a/nuttx/lib/stdio/lib_rawinstream.c b/nuttx/lib/stdio/lib_rawinstream.c new file mode 100644 index 0000000000..9671a27166 --- /dev/null +++ b/nuttx/lib/stdio/lib_rawinstream.c @@ -0,0 +1,107 @@ +/**************************************************************************** + * lib/stdio/lib_rawinstream.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: rawinstream_getc + ****************************************************************************/ + +static int rawinstream_getc(FAR struct lib_instream_s *this) +{ + FAR struct lib_rawinstream_s *rthis = (FAR struct lib_rawinstream_s *)this; + int nwritten; + char ch; + + DEBUGASSERT(this && rthis->fd >= 0); + + /* Attempt to read one character */ + + nwritten = read(rthis->fd, &ch, 1); + if (nwritten == 1) + { + this->nget++; + return ch; + } + + /* Return EOF on any failure to read from the incoming byte stream. The + * only expected error is EINTR meaning that the read was interrupted + * by a signal. A Zero return value would indicated an end-of-file + * confition. + */ + + return EOF; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_rawinstream + * + * Description: + * Initializes a stream for use with a file descriptor. + * + * Input parameters: + * rawinstream - User allocated, uninitialized instance of struct + * lib_rawinstream_s to be initialized. + * fd - User provided file/socket descriptor (must have been opened + * for the correct access). + * + * Returned Value: + * None (User allocated instance initialized). + * + ****************************************************************************/ + +void lib_rawinstream(FAR struct lib_rawinstream_s *rawinstream, int fd) +{ + rawinstream->public.get = rawinstream_getc; + rawinstream->public.nget = 0; + rawinstream->fd = fd; +} + diff --git a/nuttx/lib/stdio/lib_rawoutstream.c b/nuttx/lib/stdio/lib_rawoutstream.c new file mode 100644 index 0000000000..ed813f87aa --- /dev/null +++ b/nuttx/lib/stdio/lib_rawoutstream.c @@ -0,0 +1,115 @@ +/**************************************************************************** + * lib/stdio/lib_rawoutstream.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: rawoutstream_putc + ****************************************************************************/ + +static void rawoutstream_putc(FAR struct lib_outstream_s *this, int ch) +{ + FAR struct lib_rawoutstream_s *rthis = (FAR struct lib_rawoutstream_s *)this; + int nwritten; + char buffer = ch; + + DEBUGASSERT(this && rthis->fd >= 0); + + /* Loop until the character is successfully transferred or until an + * irrecoverable error occurs. + */ + + do + { + nwritten = write(rthis->fd, &buffer, 1); + if (nwritten == 1) + { + this->nput++; + return; + } + + /* The only expected error is EINTR, meaning that the write operation + * was awakened by a signal. Zero would not be a valid return value + * from write(). + */ + + DEBUGASSERT(nwritten < 0); + } + while (get_errno() == EINTR); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_rawoutstream + * + * Description: + * Initializes a stream for use with a file descriptor. + * + * Input parameters: + * rawoutstream - User allocated, uninitialized instance of struct + * lib_rawoutstream_s to be initialized. + * fd - User provided file/socket descriptor (must have been opened + * for write access). + * + * Returned Value: + * None (User allocated instance initialized). + * + ****************************************************************************/ + +void lib_rawoutstream(FAR struct lib_rawoutstream_s *rawoutstream, int fd) +{ + rawoutstream->public.put = rawoutstream_putc; +#ifdef CONFIG_STDIO_LINEBUFFER + rawoutstream->public.flush = lib_noflush; +#endif + rawoutstream->public.nput = 0; + rawoutstream->fd = fd; +} + diff --git a/nuttx/lib/stdio/lib_rawprintf.c b/nuttx/lib/stdio/lib_rawprintf.c new file mode 100644 index 0000000000..19dfa895e1 --- /dev/null +++ b/nuttx/lib/stdio/lib_rawprintf.c @@ -0,0 +1,151 @@ +/**************************************************************************** + * lib/stdio/lib_rawprintf.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Some output destinations are only available from within the kernel */ + +#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__) +# undef CONFIG_SYSLOG +# undef CONFIG_ARCH_LOWPUTC +#endif + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_rawvprintf + ****************************************************************************/ + +int lib_rawvprintf(const char *fmt, va_list ap) +{ +#if defined(CONFIG_SYSLOG) + + struct lib_outstream_s stream; + + /* Wrap the low-level output in a stream object and let lib_vsprintf + * do the work. + */ + + lib_syslogstream((FAR struct lib_outstream_s *)&stream); + return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); + +#elif CONFIG_NFILE_DESCRIPTORS > 0 + + struct lib_rawoutstream_s rawoutstream; + + /* Wrap the stdout in a stream object and let lib_vsprintf + * do the work. + */ + + lib_rawoutstream(&rawoutstream, 1); + return lib_vsprintf(&rawoutstream.public, fmt, ap); + +#elif defined(CONFIG_ARCH_LOWPUTC) + + struct lib_outstream_s stream; + + /* Wrap the low-level output in a stream object and let lib_vsprintf + * do the work. + */ + + lib_lowoutstream((FAR struct lib_outstream_s *)&stream); + return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); + +#else + return 0; +#endif +} + +/**************************************************************************** + * Name: lib_rawprintf + ****************************************************************************/ + +int lib_rawprintf(const char *fmt, ...) +{ + va_list ap; + int ret; + +#ifdef CONFIG_DEBUG_ENABLE + ret = 0; + if (g_dbgenable) +#endif + { + va_start(ap, fmt); + ret = lib_rawvprintf(fmt, ap); + va_end(ap); + } + + return ret; +} diff --git a/nuttx/lib/stdio/lib_rdflush.c b/nuttx/lib/stdio/lib_rdflush.c new file mode 100644 index 0000000000..35c5495c17 --- /dev/null +++ b/nuttx/lib/stdio/lib_rdflush.c @@ -0,0 +1,144 @@ +/**************************************************************************** + * lib/stdio/lib_rdflush.c + * + * Copyright (C) 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_rdflush + * + * Description: + * Flush read data from the I/O buffer and adjust the file pointer to + * account for the unread data + * + ****************************************************************************/ + +#if CONFIG_STDIO_BUFFER_SIZE > 0 +int lib_rdflush(FAR FILE *stream) +{ + if (!stream) + { + set_errno(EBADF); + return ERROR; + } + + /* Get exclusive access to the stream */ + + lib_take_semaphore(stream); + + /* If the buffer is currently being used for read access, then discard all + * of the read-ahead data. We do not support concurrent buffered read/write + * access. + */ + + if (stream->fs_bufread != stream->fs_bufstart) + { + /* Now adjust the stream pointer to account for the read-ahead data that + * was not actually read by the user. + */ + +#if CONFIG_NUNGET_CHARS > 0 + off_t rdoffset = stream->fs_bufread - stream->fs_bufpos + stream->fs_nungotten; +#else + off_t rdoffset = stream->fs_bufread - stream->fs_bufpos; +#endif + /* Mark the buffer as empty (do this before calling fseek() because fseek() + * also calls this function). + */ + + stream->fs_bufpos = stream->fs_bufread = stream->fs_bufstart; +#if CONFIG_NUNGET_CHARS > 0 + stream->fs_nungotten = 0; +#endif + /* Then seek to the position corresponding to the last data read by the user */ + + if (fseek(stream, -rdoffset, SEEK_CUR) < 0) + { + lib_give_semaphore(stream); + return ERROR; + } + } + + lib_give_semaphore(stream); + return OK; +} +#endif /* CONFIG_STDIO_BUFFER_SIZE */ + diff --git a/nuttx/lib/stdio/lib_snprintf.c b/nuttx/lib/stdio/lib_snprintf.c new file mode 100644 index 0000000000..e5ce7b0f02 --- /dev/null +++ b/nuttx/lib/stdio/lib_snprintf.c @@ -0,0 +1,99 @@ +/**************************************************************************** + * lib/stdio/lib_snprintf.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * sprintf + ****************************************************************************/ + +int snprintf(FAR char *buf, size_t size, const char *format, ...) +{ + struct lib_memoutstream_s memoutstream; + va_list ap; + int n; + + /* Initialize a memory stream to write to the buffer */ + + lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, size); + + /* Then let lib_vsprintf do the real work */ + + va_start(ap, format); + n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, format, ap); + va_end(ap); + return n; +} diff --git a/nuttx/lib/stdio/lib_sprintf.c b/nuttx/lib/stdio/lib_sprintf.c new file mode 100644 index 0000000000..89fd610330 --- /dev/null +++ b/nuttx/lib/stdio/lib_sprintf.c @@ -0,0 +1,95 @@ +/**************************************************************************** + * lib/stdio/lib_sprintf.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * sprintf + ****************************************************************************/ + +int sprintf (FAR char *buf, const char *fmt, ...) +{ + struct lib_memoutstream_s memoutstream; + va_list ap; + int n; + + /* Initialize a memory stream to write to the buffer */ + + lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, LIB_BUFLEN_UNKNOWN); + + /* Then let lib_vsprintf do the real work */ + + va_start(ap, fmt); + n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, fmt, ap); + va_end(ap); + return n; +} diff --git a/nuttx/lib/stdio/lib_sscanf.c b/nuttx/lib/stdio/lib_sscanf.c new file mode 100644 index 0000000000..7e1fae276d --- /dev/null +++ b/nuttx/lib/stdio/lib_sscanf.c @@ -0,0 +1,507 @@ +/**************************************************************************** + * lib/stdio/lib_sscanf.c + * + * Copyright (C) 2007, 2008, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define MAXLN 128 + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +int vsscanf(char *buf, const char *fmt, va_list ap); + +/************************************************************************** + * Global Constant Data + **************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/************************************************************************** + * Private Constant Data + **************************************************************************/ + +static const char spaces[] = " \t\n\r\f\v"; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: findwidth + * + * Description: + * Try to figure out the width of the input data. + * + ****************************************************************************/ + +static int findwidth(FAR const char *buf, FAR const char *fmt) +{ + FAR const char *next = fmt + 1; + + /* No... is there a space after the format? Or does the format string end + * here? + */ + + if (isspace(*next) || *next == 0) + { + /* Use the input up until the first white space is encountered. */ + + return strcspn(buf, spaces); + } + + /* No.. Another possibility is the the format character is followed by + * some recognizable delimiting value. + */ + + if (*next != '%') + { + /* If so we will say that the string ends there if we can find that + * delimiter in the input string. + */ + + FAR const char *ptr = strchr(buf, *next); + if (ptr) + { + return (int)(ptr - buf); + } + } + + /* No... the format has not delimiter and is back-to-back with the next + * formats (or no is following by a delimiter that does not exist in the + * input string). At this point we just bail and Use the input up until + * the first white space is encountered. + * + * NOTE: This means that values from the following format may be + * concatenated with the first. This is a bug. We have no generic way of + * determining the width of the data if there is no fieldwith, no space + * separating the input, and no usable delimiter character. + */ + + return strcspn(buf, spaces); +} + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Function: sscanf + * + * Description: + * ANSI standard sscanf implementation. + * + ****************************************************************************/ + +int sscanf(FAR const char *buf, FAR const char *fmt, ...) +{ + va_list ap; + int count; + + va_start(ap, fmt); + count = vsscanf((FAR char*)buf, fmt, ap); + va_end(ap); + return count; +} + +/**************************************************************************** + * Function: vsscanf + * + * Description: + * ANSI standard vsscanf implementation. + * + ****************************************************************************/ + +int vsscanf(FAR char *buf, FAR const char *fmt, va_list ap) +{ + FAR char *bufstart; + FAR char *tv; + FAR const char *tc; + bool lflag; + bool noassign; + int count; + int width; + int base = 10; + char tmp[MAXLN]; + + lvdbg("vsscanf: buf=\"%s\" fmt=\"%s\"\n", buf, fmt); + + /* Remember the start of the input buffer. We will need this for %n + * calculations. + */ + + bufstart = buf; + + /* Parse the format, extracting values from the input buffer as needed */ + + count = 0; + width = 0; + noassign = false; + lflag = false; + + while (*fmt && *buf) + { + /* Skip over white space */ + + while (isspace(*fmt)) + { + fmt++; + } + + /* Check for a conversion specifier */ + + if (*fmt == '%') + { + lvdbg("vsscanf: Specifier found\n"); + + /* Check for qualifiers on the conversion specifier */ + fmt++; + for (; *fmt; fmt++) + { + lvdbg("vsscanf: Processing %c\n", *fmt); + + if (strchr("dibouxcsefgn%", *fmt)) + { + break; + } + + if (*fmt == '*') + { + noassign = true; + } + else if (*fmt == 'l' || *fmt == 'L') + { + /* NOTE: Missing check for long long ('ll') */ + + lflag = true; + } + else if (*fmt >= '1' && *fmt <= '9') + { + for (tc = fmt; isdigit(*fmt); fmt++); + strncpy(tmp, tc, fmt - tc); + tmp[fmt - tc] = '\0'; + width = atoi(tmp); + fmt--; + } + } + + /* Process %s: String conversion */ + + if (*fmt == 's') + { + lvdbg("vsscanf: Performing string conversion\n"); + + while (isspace(*buf)) + { + buf++; + } + + /* Was a fieldwidth specified? */ + + if (!width) + { + /* No... Guess a field width using some heuristics */ + + width = findwidth(buf, fmt); + } + + if (!noassign) + { + tv = va_arg(ap, char*); + strncpy(tv, buf, width); + tv[width] = '\0'; + } + + buf += width; + } + + /* Process %c: Character conversion */ + + else if (*fmt == 'c') + { + lvdbg("vsscanf: Performing character conversion\n"); + + /* Was a fieldwidth specified? */ + + if (!width) + { + /* No, then width is this one single character */ + + width = 1; + } + + if (!noassign) + { + tv = va_arg(ap, char*); + strncpy(tv, buf, width); + tv[width] = '\0'; + } + + buf += width; + } + + /* Process %d, %o, %b, %x, %u: Various integer conversions */ + + else if (strchr("dobxu", *fmt)) + { + lvdbg("vsscanf: Performing integer conversion\n"); + + /* Skip over any white space before the integer string */ + + while (isspace(*buf)) + { + buf++; + } + + /* The base of the integer conversion depends on the specific + * conversion specification. + */ + + if (*fmt == 'd' || *fmt == 'u') + { + base = 10; + } + else if (*fmt == 'x') + { + base = 16; + } + else if (*fmt == 'o') + { + base = 8; + } + else if (*fmt == 'b') + { + base = 2; + } + + /* Was a fieldwidth specified? */ + + if (!width) + { + /* No... Guess a field width using some heuristics */ + + width = findwidth(buf, fmt); + } + + /* Copy the numeric string into a temporary working buffer. */ + + strncpy(tmp, buf, width); + tmp[width] = '\0'; + + lvdbg("vsscanf: tmp[]=\"%s\"\n", tmp); + + /* Perform the integer conversion */ + + buf += width; + if (!noassign) + { +#ifdef SDCC + char *endptr; + long tmplong = strtol(tmp, &endptr, base); +#else + long tmplong = strtol(tmp, NULL, base); +#endif + if (lflag) + { + long *plong = va_arg(ap, long*); + lvdbg("vsscanf: Return %ld to 0x%p\n", tmplong, plong); + *plong = tmplong; + } + else + { + int *pint = va_arg(ap, int*); + lvdbg("vsscanf: Return %ld to 0x%p\n", tmplong, pint); + *pint = (int)tmplong; + } + } + } + + /* Process %f: Floating point conversion */ + + else if (*fmt == 'f') + { +#ifndef CONFIG_LIBC_FLOATINGPOINT + /* No floating point conversions */ + + void *pv = va_arg(ap, void*); + + lvdbg("vsscanf: Return 0.0 to %p\n", pv); + *((double_t*)pv) = 0.0; +#else + lvdbg("vsscanf: Performing floating point conversion\n"); + + /* Skip over any white space before the real string */ + + while (isspace(*buf)) + { + buf++; + } + + /* Was a fieldwidth specified? */ + + if (!width) + { + /* No... Guess a field width using some heuristics */ + + width = findwidth(buf, fmt); + } + + /* Copy the real string into a temporary working buffer. */ + + strncpy(tmp, buf, width); + tmp[width] = '\0'; + buf += width; + + lvdbg("vsscanf: tmp[]=\"%s\"\n", tmp); + + /* Perform the floating point conversion */ + + if (!noassign) + { + /* strtod always returns a double */ +#ifdef SDCC + char *endptr; + double_t dvalue = strtod(tmp,&endptr); +#else + double_t dvalue = strtod(tmp, NULL); +#endif + void *pv = va_arg(ap, void*); + + lvdbg("vsscanf: Return %f to %p\n", dvalue, pv); + + /* But we have to check whether we need to return a + * float or a double. + */ + +#ifdef CONFIG_HAVE_DOUBLE + if (lflag) + { + *((double_t*)pv) = dvalue; + } + else +#endif + { + *((float*)pv) = (float)dvalue; + } + } +#endif + } + + /* Process %n: Character count */ + + else if (*fmt == 'n') + { + lvdbg("vsscanf: Performing character count\n"); + + if (!noassign) + { + size_t nchars = (size_t)(buf - bufstart); + + if (lflag) + { + long *plong = va_arg(ap, long*); + *plong = (long)nchars; + } + else + { + int *pint = va_arg(ap, int*); + *pint = (int)nchars; + } + } + } + + /* Note %n does not count as a conversion */ + + if (!noassign && *fmt != 'n') + { + count++; + } + + width = 0; + noassign = false; + lflag = false; + + fmt++; + } + + /* Its is not a conversion specifier */ + + else + { + while (isspace(*buf)) + { + buf++; + } + + if (*fmt != *buf) + { + break; + } + else + { + fmt++; + buf++; + } + } + } + + return count; +} diff --git a/nuttx/lib/stdio/lib_stdinstream.c b/nuttx/lib/stdio/lib_stdinstream.c new file mode 100644 index 0000000000..77aab9ec88 --- /dev/null +++ b/nuttx/lib/stdio/lib_stdinstream.c @@ -0,0 +1,99 @@ +/**************************************************************************** + * lib/stdio/lib_stdinstream.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stdinstream_getc + ****************************************************************************/ + +static int stdinstream_getc(FAR struct lib_instream_s *this) +{ + FAR struct lib_stdinstream_s *sthis = (FAR struct lib_stdinstream_s *)this; + int ret; + + DEBUGASSERT(this); + + /* Get the next character from the incoming stream */ + + ret = getc(sthis->stream); + if (ret != EOF) + { + this->nget++; + } + + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_stdinstream + * + * Description: + * Initializes a stream for use with a FILE instance. + * + * Input parameters: + * stdinstream - User allocated, uninitialized instance of struct + * lib_stdinstream_s to be initialized. + * stream - User provided stream instance (must have been opened for + * read access). + * + * Returned Value: + * None (User allocated instance initialized). + * + ****************************************************************************/ + +void lib_stdinstream(FAR struct lib_stdinstream_s *stdinstream, + FAR FILE *stream) +{ + stdinstream->public.get = stdinstream_getc; + stdinstream->public.nget = 0; + stdinstream->stream = stream; +} + + diff --git a/nuttx/lib/stdio/lib_stdoutstream.c b/nuttx/lib/stdio/lib_stdoutstream.c new file mode 100644 index 0000000000..20da5b7026 --- /dev/null +++ b/nuttx/lib/stdio/lib_stdoutstream.c @@ -0,0 +1,147 @@ +/**************************************************************************** + * lib/stdio/lib_stdoutstream.c + * + * Copyright (C) 2007-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stdoutstream_putc + ****************************************************************************/ + +static void stdoutstream_putc(FAR struct lib_outstream_s *this, int ch) +{ + FAR struct lib_stdoutstream_s *sthis = (FAR struct lib_stdoutstream_s *)this; + int result; + + DEBUGASSERT(this && sthis->stream); + + /* Loop until the character is successfully transferred or an irrecoverable + * error occurs. + */ + + do + { + result = fputc(ch, sthis->stream); + if (result != EOF) + { + this->nput++; + return; + } + + /* EINTR (meaning that fputc was interrupted by a signal) is the only + * recoverable error. + */ + } + while (get_errno() == EINTR); +} + +/**************************************************************************** + * Name: stdoutstream_flush + ****************************************************************************/ + +#if defined(CONFIG_STDIO_LINEBUFFER) && CONFIG_STDIO_BUFFER_SIZE > 0 +int stdoutstream_flush(FAR struct lib_outstream_s *this) +{ + FAR struct lib_stdoutstream_s *sthis = (FAR struct lib_stdoutstream_s *)this; + return lib_fflush(sthis->stream, true); +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_stdoutstream + * + * Description: + * Initializes a stream for use with a FILE instance. + * + * Input parameters: + * stdoutstream - User allocated, uninitialized instance of struct + * lib_stdoutstream_s to be initialized. + * stream - User provided stream instance (must have been opened for + * write access). + * + * Returned Value: + * None (User allocated instance initialized). + * + ****************************************************************************/ + +void lib_stdoutstream(FAR struct lib_stdoutstream_s *stdoutstream, + FAR FILE *stream) +{ + /* Select the put operation */ + + stdoutstream->public.put = stdoutstream_putc; + + /* Select the correct flush operation. This flush is only called when + * a newline is encountered in the output stream. However, we do not + * want to support this line buffering behavior if the stream was + * opened in binary mode. In binary mode, the newline has no special + * meaning. + */ + +#ifdef CONFIG_STDIO_LINEBUFFER +#if CONFIG_STDIO_BUFFER_SIZE > 0 + if ((stream->fs_oflags & O_BINARY) == 0) + { + stdoutstream->public.flush = stdoutstream_flush; + } + else +#endif + { + stdoutstream->public.flush = lib_noflush; + } +#endif + + /* Set the number of bytes put to zero and remember the stream */ + + stdoutstream->public.nput = 0; + stdoutstream->stream = stream; +} + + diff --git a/nuttx/lib/stdio/lib_syslogstream.c b/nuttx/lib/stdio/lib_syslogstream.c new file mode 100644 index 0000000000..21151b43a1 --- /dev/null +++ b/nuttx/lib/stdio/lib_syslogstream.c @@ -0,0 +1,122 @@ +/**************************************************************************** + * lib/stdio/lib_syslogstream.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "lib_internal.h" + +#ifdef CONFIG_SYSLOG + +/**************************************************************************** + * Pre-processor definition + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: syslogstream_putc + ****************************************************************************/ + +static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) +{ + int ret; + + /* Try writing until the write was successful or until an irrecoverable + * error occurs. + */ + + do + { + /* Write the character to the supported logging device */ + + ret = syslog_putc(ch); + if (ret == OK) + { + this->nput++; + return; + } + + /* On failure syslog_putc will return a negated errno value. The + * errno variable will not be set. The special value -EINTR means that + * syslog_putc() was awakened by a signal. This is not a real error and + * must be ignored in this context. + */ + } + while (ret == -EINTR); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_syslogstream + * + * Description: + * Initializes a stream for use with the configured syslog interface. + * + * Input parameters: + * lowoutstream - User allocated, uninitialized instance of struct + * lib_lowoutstream_s to be initialized. + * + * Returned Value: + * None (User allocated instance initialized). + * + ****************************************************************************/ + +void lib_syslogstream(FAR struct lib_outstream_s *stream) +{ + stream->put = syslogstream_putc; +#ifdef CONFIG_STDIO_LINEBUFFER + stream->flush = lib_noflush; +#endif + stream->nput = 0; +} + +#endif /* CONFIG_SYSLOG */ + + diff --git a/nuttx/lib/stdio/lib_ungetc.c b/nuttx/lib/stdio/lib_ungetc.c new file mode 100644 index 0000000000..c10d4fba1a --- /dev/null +++ b/nuttx/lib/stdio/lib_ungetc.c @@ -0,0 +1,121 @@ +/**************************************************************************** + * lib/stdio/lib_ungetc.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include "lib_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/************************************************************************** + * Global Constant Data + **************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/************************************************************************** + * Private Constant Data + **************************************************************************/ + +/**************************************************************************** + * Private Variables + **************************************************************************/ + +/**************************************************************************** + * Public Functions + **************************************************************************/ + +/**************************************************************************** + * Name: ungetc + **************************************************************************/ + +int ungetc(int c, FAR FILE *stream) +{ +#if CONFIG_NUNGET_CHARS > 0 + int nungotten; +#endif + + /* Stream must be open for read access */ + + if ((stream && stream->fs_filedes < 0) || + ((stream->fs_oflags & O_RDOK) == 0)) + { + set_errno(EBADF); + return EOF; + } + +#if CONFIG_NUNGET_CHARS > 0 + nungotten = stream->fs_nungotten; + if (stream->fs_nungotten < CONFIG_NUNGET_CHARS) + { + stream->fs_ungotten[nungotten] = c; + stream->fs_nungotten = nungotten + 1; + return c; + } + else +#endif + { + set_errno(ENOMEM); + return EOF; + } +} + diff --git a/nuttx/lib/stdio/lib_vfprintf.c b/nuttx/lib/stdio/lib_vfprintf.c new file mode 100644 index 0000000000..1c3a2d7fc9 --- /dev/null +++ b/nuttx/lib/stdio/lib_vfprintf.c @@ -0,0 +1,102 @@ +/**************************************************************************** + * lib/stdio/lib_vfprintf.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int vfprintf(FAR FILE *stream, FAR const char *fmt, va_list ap) +{ + struct lib_stdoutstream_s stdoutstream; + int n = ERROR; + + if (stream) + { + /* Wrap the stream in a stream object and let lib_vsprintf + * do the work. + */ + + lib_stdoutstream(&stdoutstream, stream); + + /* Hold the stream semaphore throughout the lib_vsprintf + * call so that this thread can get its entire message out + * before being pre-empted by the next thread. + */ + + lib_take_semaphore(stream); + n = lib_vsprintf(&stdoutstream.public, fmt, ap); + lib_give_semaphore(stream); + } + return n; +} diff --git a/nuttx/lib/stdio/lib_vprintf.c b/nuttx/lib/stdio/lib_vprintf.c new file mode 100644 index 0000000000..d085d58869 --- /dev/null +++ b/nuttx/lib/stdio/lib_vprintf.c @@ -0,0 +1,92 @@ +/**************************************************************************** + * lib/stdio/lib_vprintf.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/************************************************************************** + * Global Constant Data + **************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/************************************************************************** + * Private Constant Data + **************************************************************************/ + +/**************************************************************************** + * Private Variables + **************************************************************************/ + +/**************************************************************************** + * Public Functions + **************************************************************************/ + +/**************************************************************************** + * Name: vprintf + **************************************************************************/ + +int vprintf(FAR const char *fmt, va_list ap) +{ + /* vfprintf into stdout */ + + return vfprintf(stdout, fmt, ap); +} + diff --git a/nuttx/lib/stdio/lib_vsnprintf.c b/nuttx/lib/stdio/lib_vsnprintf.c new file mode 100644 index 0000000000..c6f52092d1 --- /dev/null +++ b/nuttx/lib/stdio/lib_vsnprintf.c @@ -0,0 +1,96 @@ +/**************************************************************************** + * lib/stdio/lib_vsnprintf.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: vsnprintf + ****************************************************************************/ + +int vsnprintf(FAR char *buf, size_t size, const char *format, va_list ap) +{ + struct lib_memoutstream_s memoutstream; + int n; + + /* Initialize a memory stream to write to the buffer */ + + lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, size); + + /* Then let lib_vsprintf do the real work */ + + n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, format, ap); + return n; +} diff --git a/nuttx/lib/stdio/lib_vsprintf.c b/nuttx/lib/stdio/lib_vsprintf.c new file mode 100644 index 0000000000..5db46664e3 --- /dev/null +++ b/nuttx/lib/stdio/lib_vsprintf.c @@ -0,0 +1,92 @@ +/**************************************************************************** + * lib/stdio/lib_vsprintf.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: vsprintf + ****************************************************************************/ + +int vsprintf(FAR char *dest, const char *src, va_list ap) +{ + struct lib_memoutstream_s memoutstream; + + /* Wrap the destination buffer in a stream object and let + * lib/stdio/lib_vsprintf do the work. + */ + + lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, dest, LIB_BUFLEN_UNKNOWN); + return lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, src, ap); +} diff --git a/nuttx/lib/stdio/lib_wrflush.c b/nuttx/lib/stdio/lib_wrflush.c new file mode 100644 index 0000000000..39680da6ae --- /dev/null +++ b/nuttx/lib/stdio/lib_wrflush.c @@ -0,0 +1,134 @@ +/**************************************************************************** + * lib/stdio/lib_wrflush.c + * + * Copyright (C) 2008-2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_wrflush + * + * Description: + * This is simply a version of fflush that does not report an error if + * the file is not open for writing. + * + ****************************************************************************/ + +int lib_wrflush(FAR FILE *stream) +{ +#if CONFIG_STDIO_BUFFER_SIZE > 0 + /* Verify that we were passed a valid (i.e., non-NULL) stream */ + +#ifdef CONFIG_DEBUG + if (!stream) + { + return -EINVAL; + } +#endif + + /* Verify that the stream is opened for writing... lib_fflush will + * return an error if it is called for a stream that is not opened for + * writing. Check that first so that this function will not fail in + * that case. + */ + + if ((stream->fs_oflags & O_WROK) == 0) + { + /* Report that the success was successful if we attempt to flush a + * read-only stream. + */ + + return OK; + } + + /* Flush the stream. Return success if there is no buffered write data + * -- i.e., that the stream is opened for writing and that all of the + * buffered write data was successfully flushed by lib_fflush(). + */ + + return lib_fflush(stream, true); +#else + /* Verify that we were passed a valid (i.e., non-NULL) stream */ + +#ifdef CONFIG_DEBUG + if (!stream) + { + return -EINVAL; + } +#endif + + return OK; +#endif +} diff --git a/nuttx/lib/stdio/lib_zeroinstream.c b/nuttx/lib/stdio/lib_zeroinstream.c new file mode 100644 index 0000000000..39a6c22ef3 --- /dev/null +++ b/nuttx/lib/stdio/lib_zeroinstream.c @@ -0,0 +1,79 @@ +/**************************************************************************** + * lib/stdio/lib_zeroinstream.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static int zeroinstream_getc(FAR struct lib_instream_s *this) +{ + this->nget++; + return 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_zeroinstream + * + * Description: + * Initializes a NULL stream. The initialized stream will return an + * infinitely long stream of zeroes. + * + * Input parameters: + * zeroinstream - User allocated, uninitialized instance of struct + * lib_instream_s to be initialized. + * + * Returned Value: + * None (User allocated instance initialized). + * + ****************************************************************************/ + +void lib_zeroinstream(FAR struct lib_instream_s *zeroinstream) +{ + zeroinstream->get = zeroinstream_getc; + zeroinstream->nget = 0; +} + diff --git a/nuttx/lib/stdlib/Make.defs b/nuttx/lib/stdlib/Make.defs new file mode 100644 index 0000000000..76e285808a --- /dev/null +++ b/nuttx/lib/stdlib/Make.defs @@ -0,0 +1,44 @@ +############################################################################ +# lib/stdlib/Make.defs +# +# 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. +# +############################################################################ + +# Add the stdlib C files to the build + +CSRCS += lib_abs.c lib_abort.c lib_imaxabs.c lib_labs.c lib_llabs.c \ + lib_rand.c lib_qsort.c + +# Add the stdlib directory to the build + +DEPPATH += --dep-path stdlib +VPATH += :stdlib diff --git a/nuttx/lib/stdlib/lib_abort.c b/nuttx/lib/stdlib/lib_abort.c new file mode 100644 index 0000000000..84b6009500 --- /dev/null +++ b/nuttx/lib/stdlib/lib_abort.c @@ -0,0 +1,121 @@ +/************************************************************************ + * lib/stdlib/lib_abort.c + * + * Copyright (C) 2007, 2009, 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include +#include + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +/************************************************************************ + * Private Type Declarations + ************************************************************************/ + +/************************************************************************ + * Global Variables + ************************************************************************/ + +/************************************************************************ + * Private Variables + ************************************************************************/ + +/************************************************************************ + * Private Function Prototypes + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: Abort + * + * Description: + * The abort() first unblocks the SIGABRT signal, and then raises that + * signal for the calling process. This results in the abnormal + * termination of the process unless the SIGABRT signal is caught and + * the signal handler does not return. + * + * If the abort() function causes process termination, all open + * streams are closed and flushed. + * + * If the SIGABRT signal is ignored, or caught by a handler that + * returns, the abort() function will still terminate the process. + * It does this by restoring the default disposition for SIGABRT and + * then raising the signal for a second time. + * + * Input parameters: + * None + * + * Returned Value: + * This function does not return, + * + ************************************************************************/ + +void abort(void) +{ + /* NuttX does not support standard signal functionality (like the + * behavior of the SIGABRT signal). So no attempt is made to provide + * a conformant version of abort() at this time. This version does not + * signal the calling thread all. + * + * Note that pthread_exit() is called instead of exit(). That is because + * we do no know if abort was called from a pthread or a normal thread + * (we could find out, of course). If abort() is called from a non-pthread, + * then pthread_exit() should fail and fall back to call exit() anyway. + * + * If exit() is called (either below or via pthread_exit()), then exit() + * will flush and close all open files and terminate the thread. If this + * function was called from a pthread, then pthread_exit() will complete + * any joins, but will not flush or close any streams. + */ + +#ifdef CONFIG_DISABLE_PTHREAD + exit(EXIT_FAILURE); +#else + pthread_exit(NULL); +#endif +} diff --git a/nuttx/lib/stdlib/lib_abs.c b/nuttx/lib/stdlib/lib_abs.c new file mode 100644 index 0000000000..1a0c1671cc --- /dev/null +++ b/nuttx/lib/stdlib/lib_abs.c @@ -0,0 +1,54 @@ +/************************************************************************ + * lib/stdlib/lib_abs.c + * + * Copyright (C) 2010-2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +/************************************************************************ + * Global Functions + ************************************************************************/ + +int abs(int j) +{ + if (j < 0) + { + j = -j; + } + return j; +} diff --git a/nuttx/lib/stdlib/lib_imaxabs.c b/nuttx/lib/stdlib/lib_imaxabs.c new file mode 100644 index 0000000000..c6e227c7de --- /dev/null +++ b/nuttx/lib/stdlib/lib_imaxabs.c @@ -0,0 +1,54 @@ +/************************************************************************ + * lib/stdlib//lib_abs.c + * + * Copyright (C) 2010-2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +/************************************************************************ + * Global Functions + ************************************************************************/ + +intmax_t imaxabs(intmax_t j) +{ + if (j < 0) + { + j = -j; + } + return j; +} diff --git a/nuttx/lib/stdlib/lib_labs.c b/nuttx/lib/stdlib/lib_labs.c new file mode 100644 index 0000000000..f7218ee833 --- /dev/null +++ b/nuttx/lib/stdlib/lib_labs.c @@ -0,0 +1,54 @@ +/************************************************************************ + * lib/stdlib/lib_labs.c + * + * Copyright (C) 2010-2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +/************************************************************************ + * Global Functions + ************************************************************************/ + +long int labs(long int j) +{ + if (j < 0) + { + j = -j; + } + return j; +} diff --git a/nuttx/lib/stdlib/lib_llabs.c b/nuttx/lib/stdlib/lib_llabs.c new file mode 100644 index 0000000000..db7d3dbe07 --- /dev/null +++ b/nuttx/lib/stdlib/lib_llabs.c @@ -0,0 +1,57 @@ +/************************************************************************ + * lib/stdlib/lib_llabs.c + * + * Copyright (C) 2010-2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include +#include + +/************************************************************************ + * Global Functions + ************************************************************************/ + +#ifdef CONFIG_HAVE_LONG_LONG +long long int llabs(long long int j) +{ + if (j < 0) + { + j = -j; + } + return j; +} +#endif diff --git a/nuttx/lib/stdlib/lib_qsort.c b/nuttx/lib/stdlib/lib_qsort.c new file mode 100644 index 0000000000..9dd5c00409 --- /dev/null +++ b/nuttx/lib/stdlib/lib_qsort.c @@ -0,0 +1,238 @@ +/**************************************************************************** + * lib/stdlib/lib_qsort.c + * + * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Leveraged from: + * + * Copyright (c) 1992, 1993 + * The Regents of the University of California. All rights reserved. + * + * 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * This product includes software developed by the University of + * California, Berkeley and its contributors. + * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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 + +/**************************************************************************** + * Preprocessor Definitions + ****************************************************************************/ + +#define min(a, b) (a) < (b) ? a : b + +#define swapcode(TYPE, parmi, parmj, n) \ + { \ + long i = (n) / sizeof (TYPE); \ + register TYPE *pi = (TYPE *) (parmi); \ + register TYPE *pj = (TYPE *) (parmj); \ + do { \ + register TYPE t = *pi; \ + *pi++ = *pj; \ + *pj++ = t; \ + } while (--i > 0); \ + } + +#define SWAPINIT(a, size) \ + swaptype = ((char *)a - (char *)0) % sizeof(long) || \ + size % sizeof(long) ? 2 : size == sizeof(long)? 0 : 1; + +#define swap(a, b) \ + if (swaptype == 0) \ + { \ + long t = *(long *)(a); \ + *(long *)(a) = *(long *)(b); \ + *(long *)(b) = t; \ + } \ + else \ + { \ + swapfunc(a, b, size, swaptype); \ + } + +#define vecswap(a, b, n) if ((n) > 0) swapfunc(a, b, n, swaptype) + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static inline void swapfunc(char *a, char *b, int n, int swaptype); +static inline char *med3(char *a, char *b, char *c, + int (*compar)(const void *, const void *)); + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static inline void swapfunc(char *a, char *b, int n, int swaptype) +{ + if(swaptype <= 1) + { + swapcode(long, a, b, n) + } + else + { + swapcode(char, a, b, n) + } +} + +static inline char *med3(char *a, char *b, char *c, + int (*compar)(const void *, const void *)) +{ + return compar(a, b) < 0 ? + (compar(b, c) < 0 ? b : (compar(a, c) < 0 ? c : a )) + :(compar(b, c) > 0 ? b : (compar(a, c) < 0 ? a : c )); +} + +/**************************************************************************** + * Public Function + ****************************************************************************/ + +/**************************************************************************** + * Name: qsort + * + * Description: + * Qsort routine from Bentley & McIlroy's "Engineering a Sort Function". + * + ****************************************************************************/ + +void qsort(void *base, size_t nmemb, size_t size, + int(*compar)(const void *, const void *)) +{ + char *pa, *pb, *pc, *pd, *pl, *pm, *pn; + int d, r, swaptype, swap_cnt; + +loop: + SWAPINIT(base, size); + swap_cnt = 0; + if (nmemb < 7) + { + for (pm = (char *) base + size; pm < (char *) base + nmemb * size; pm += size) + { + for (pl = pm; pl > (char *) base && compar(pl - size, pl) > 0; pl -= size) + { + swap(pl, pl - size); + } + } + return; + } + + pm = (char *) base + (nmemb / 2) * size; + if (nmemb > 7) + { + pl = base; + pn = (char *) base + (nmemb - 1) * size; + if (nmemb > 40) + { + d = (nmemb / 8) * size; + pl = med3(pl, pl + d, pl + 2 * d, compar); + pm = med3(pm - d, pm, pm + d, compar); + pn = med3(pn - 2 * d, pn - d, pn, compar); + } + pm = med3(pl, pm, pn, compar); + } + swap(base, pm); + pa = pb = (char *) base + size; + + pc = pd = (char *) base + (nmemb - 1) * size; + for (;;) + { + while (pb <= pc && (r = compar(pb, base)) <= 0) + { + if (r == 0) + { + swap_cnt = 1; + swap(pa, pb); + pa += size; + } + pb += size; + } + while (pb <= pc && (r = compar(pc, base)) >= 0) + { + if (r == 0) + { + swap_cnt = 1; + swap(pc, pd); + pd -= size; + } + pc -= size; + } + + if (pb > pc) + { + break; + } + + swap(pb, pc); + swap_cnt = 1; + pb += size; + pc -= size; + } + + if (swap_cnt == 0) + { + /* Switch to insertion sort */ + + for (pm = (char *) base + size; pm < (char *) base + nmemb * size; pm += size) + { + for (pl = pm; pl > (char *) base && compar(pl - size, pl) > 0; pl -= size) + { + swap(pl, pl - size); + } + } + return; + } + + pn = (char *) base + nmemb * size; + r = min(pa - (char *)base, pb - pa); + vecswap(base, pb - r, r); + r = min(pd - pc, pn - pd - size); + vecswap(pb, pn - r, r); + + if ((r = pb - pa) > size) + { + qsort(base, r / size, size, compar); + } + + if ((r = pd - pc) > size) + { + /* Iterate rather than recurse to save stack space */ + base = pn - r; + nmemb = r / size; + goto loop; + } +} + diff --git a/nuttx/lib/stdlib/lib_rand.c b/nuttx/lib/stdlib/lib_rand.c new file mode 100644 index 0000000000..7227c52d0d --- /dev/null +++ b/nuttx/lib/stdlib/lib_rand.c @@ -0,0 +1,220 @@ +/************************************************************ + * lib/stdlib/lib_rand.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include +#include + +/************************************************************ + * Definitions + ************************************************************/ + +#ifndef CONFIG_LIB_RAND_ORDER +#define CONFIG_LIB_RAND_ORDER 1 +#endif + +/* Values needed by the random number generator */ + +#define RND1_CONSTK 470001 +#define RND1_CONSTP 999563 +#define RND2_CONSTK1 366528 +#define RND2_CONSTK2 508531 +#define RND2_CONSTP 998917 +#define RND3_CONSTK1 360137 +#define RND3_CONSTK2 519815 +#define RND3_CONSTK3 616087 +#define RND3_CONSTP 997783 + +#if CONFIG_LIB_RAND_ORDER == 1 +# define RND_CONSTP RND1_CONSTP +#elif CONFIG_LIB_RAND_ORDER == 2 +# define RND_CONSTP RND2_CONSTP +#else +# define RND_CONSTP RND3_CONSTP +#endif + +/************************************************************ + * Private Type Declarations + ************************************************************/ + +/************************************************************ + * Private Function Prototypes + ************************************************************/ + +static unsigned int nrand(unsigned int nLimit); +static double_t frand1(void); +#if (CONFIG_LIB_RAND_ORDER > 1) +static double_t frand2(void); +#if (CONFIG_LIB_RAND_ORDER > 2) +static double_t frand3(void); +#endif +#endif + +/********************************************************** + * Global Constant Data + **********************************************************/ + +/************************************************************ + * Global Variables + ************************************************************/ + +/********************************************************** + * Private Constant Data + **********************************************************/ + +/************************************************************ + * Private Variables + ************************************************************/ + +static unsigned long g_nRandInt1; +#if (CONFIG_LIB_RAND_ORDER > 1) +static unsigned long g_nRandInt2; +#if (CONFIG_LIB_RAND_ORDER > 2) +static unsigned long g_nRandInt3; +#endif +#endif + +/************************************************************ + * Private Functions + ************************************************************/ + +static unsigned int nrand(unsigned int nLimit) +{ + unsigned long nResult; + double_t fRatio; + + /* Loop to be sure a legal random number is generated */ + do { + + /* Get a random integer in the requested range */ +#if (CONFIG_LIB_RAND_ORDER == 1) + fRatio = frand1(); +#elif (CONFIG_LIB_RAND_ORDER == 2) + fRatio = frand2(); +#else + fRatio = frand3(); +#endif + + /* Then, produce the return-able value */ + nResult = (unsigned long)(((double_t)nLimit) * fRatio); + + } while (nResult >= (unsigned long)nLimit); + + return (unsigned int)nResult; + +} /* end nrand */ + +static double_t frand1(void) +{ + unsigned long nRandInt; + + /* First order congruential generator */ + nRandInt = (RND1_CONSTK * g_nRandInt1) % RND1_CONSTP; + g_nRandInt1 = nRandInt; + + /* Construct an floating point value in the range from 0.0 up to 1.0 */ + return ((double_t)nRandInt) / ((double_t)RND_CONSTP); + +} /* end frand */ + +#if (CONFIG_LIB_RAND_ORDER > 1) +static double_t frand2(void) +{ + unsigned long nRandInt; + + /* Second order congruential generator */ + nRandInt = (RND2_CONSTK1 * g_nRandInt1 + RND2_CONSTK2 * g_nRandInt2) % + RND2_CONSTP; + g_nRandInt2 = g_nRandInt1; + g_nRandInt1 = nRandInt; + + /* Construct an floating point value in the range from 0.0 up to 1.0 */ + return ((double_t)nRandInt) / ((double_t)RND_CONSTP); + +} /* end frand */ + +#if (CONFIG_LIB_RAND_ORDER > 2) +static double_t frand3(void) +{ + unsigned long nRandInt; + + /* Third order congruential generator */ + nRandInt = (RND3_CONSTK1 * g_nRandInt1 + RND3_CONSTK2 * g_nRandInt2 + + RND3_CONSTK2 * g_nRandInt3) % RND3_CONSTP; + g_nRandInt3 = g_nRandInt2; + g_nRandInt2 = g_nRandInt1; + g_nRandInt1 = nRandInt; + + /* Construct an floating point value in the range from 0.0 up to 1.0 */ + return ((double_t)nRandInt) / ((double_t)RND_CONSTP); + +} /* end frand */ +#endif +#endif + +/************************************************************ + * Public Functions + ************************************************************/ +/************************************************************ + * Function: srand, rand + ************************************************************/ + +void srand(unsigned int seed) +{ + g_nRandInt1 = seed; +#if (CONFIG_LIB_RAND_ORDER > 1) + g_nRandInt2 = seed; + (void)frand1(); +#if (CONFIG_LIB_RAND_ORDER > 2) + g_nRandInt3 = seed; + (void)frand2(); +#endif +#endif + +} /* end srand */ + +int rand(void) +{ + return (int)nrand(32768); + +} /* end rand */ + diff --git a/nuttx/lib/string/Make.defs b/nuttx/lib/string/Make.defs new file mode 100644 index 0000000000..6b21c7f146 --- /dev/null +++ b/nuttx/lib/string/Make.defs @@ -0,0 +1,50 @@ +############################################################################ +# lib/string/Make.defs +# +# 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. +# +############################################################################ + +# Add the string C files to the build + +CSRCS += lib_checkbase.c lib_isbasedigit.c lib_memset.c lib_memchr.c \ + lib_memccpy.c lib_memcpy.c lib_memcmp.c lib_memmove.c lib_skipspace.c \ + lib_strcasecmp.c lib_strcat.c lib_strchr.c lib_strcpy.c lib_strcmp.c \ + lib_strcspn.c lib_strdup.c lib_strerror.c lib_strlen.c lib_strnlen.c \ + lib_strncasecmp.c lib_strncat.c lib_strncmp.c lib_strncpy.c \ + lib_strndup.c lib_strcasestr.c lib_strpbrk.c lib_strrchr.c\ + lib_strspn.c lib_strstr.c lib_strtok.c lib_strtokr.c lib_strtol.c \ + lib_strtoll.c lib_strtoul.c lib_strtoull.c lib_strtod.c + +# Add the string directory to the build + +DEPPATH += --dep-path string +VPATH += :string diff --git a/nuttx/lib/string/lib_checkbase.c b/nuttx/lib/string/lib_checkbase.c new file mode 100644 index 0000000000..bc79ab2cec --- /dev/null +++ b/nuttx/lib/string/lib_checkbase.c @@ -0,0 +1,115 @@ +/**************************************************************************** + * lib/string/lib_checkbase.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_checkbase + * + * Description: + * This is part of the strol() family implementation. This function checks + * the initial part of a string to see if it can determine the numeric + * base that is represented. + * + * Assumptions: + * *ptr points to the first, non-whitespace character in the string. + * + ****************************************************************************/ + +int lib_checkbase(int base, const char **pptr) +{ + const char *ptr = *pptr; + + /* Check for unspecified base */ + + if (!base) + { + /* Assume base 10 */ + + base = 10; + + /* Check for leading '0' - that would signify octal or hex (or binary) */ + + if (*ptr == '0') + { + /* Assume octal */ + + base = 8; + ptr++; + + /* Check for hexidecimal */ + + if ((*ptr == 'X' || *ptr == 'x') && + lib_isbasedigit(ptr[1], 16, NULL)) + { + base = 16; + ptr++; + } + } + } + + /* If it a hexidecimal representation, than discard any leading "0X" or "0x" */ + + else if (base == 16) + { + if (ptr[0] == '0' && (ptr[1] == 'X' || ptr[1] == 'x')) + { + ptr += 2; + } + } + + /* Return the updated pointer and base */ + + *pptr = ptr; + return base; +} + diff --git a/nuttx/lib/string/lib_isbasedigit.c b/nuttx/lib/string/lib_isbasedigit.c new file mode 100644 index 0000000000..a2421bf2a4 --- /dev/null +++ b/nuttx/lib/string/lib_isbasedigit.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * lib/string/lib_isbasedigit.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_isbasedigit + * + * Description: + * Given an ASCII character, ch, and a base (1-36) do two + * things: 1) Determine if ch is a valid charcter, and 2) + * convert ch to its binary value. + * + ****************************************************************************/ + +bool lib_isbasedigit(int ch, int base, int *value) +{ + bool ret = false; + int tmp = 0; + + if (base <= 10) + { + if (ch >= '0' && ch <= base + '0' - 1) + { + tmp = ch - '0'; + ret = true; + } + } + else if (base <= 36) + { + if (ch >= '0' && ch <= '9') + { + tmp = ch - '0'; + ret = true; + } + else if (ch >= 'a' && ch <= 'a' + base - 11) + { + tmp = ch - 'a' + 10; + ret = true; + } + else if (ch >= 'A' && ch <= 'A' + base - 11) + { + tmp = ch - 'A' + 10; + ret = true; + } + } + + if (value) + { + *value = tmp; + } + return ret; +} + + diff --git a/nuttx/lib/string/lib_memccpy.c b/nuttx/lib/string/lib_memccpy.c new file mode 100644 index 0000000000..1f3dbb52dd --- /dev/null +++ b/nuttx/lib/string/lib_memccpy.c @@ -0,0 +1,99 @@ +/**************************************************************************** + * lib/string/lib_memccpy.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + + +/**************************************************************************** + * Name: memccpy + * + * Description: + * The memccpy() function copies bytes from memory area s2 into s1, + * stopping after the first occurrence of byte c (converted to an unsigned + * char) is copied, or after n bytes are copied, whichever comes first. If + * copying takes place between objects that overlap, the behavior is + * undefined. + * + * Returned Value: + * The memccpy() function returns a pointer to the byte after the copy of c + * in s1, or a null pointer if c was not found in the first n bytes of s2. + * + ****************************************************************************/ + +FAR void *memccpy(FAR void *s1, FAR const void *s2, int c, size_t n) +{ + FAR unsigned char *pout = (FAR unsigned char*)s1; + FAR unsigned char *pin = (FAR unsigned char*)s2; + + /* Copy at most n bytes */ + + while (n-- > 0) + { + /* Copy one byte */ + + *pout = *pin++; + + /* Did we just copy the terminating byte c? */ + + if (*pout == (unsigned char)c) + { + /* Yes return a pointer to the byte after the copy of c into s1 */ + + return (FAR void *)pout; + } + + /* No increment to the next destination location */ + + pout++; + } + + /* C was not found in the first n bytes of s2 */ + + return NULL; +} diff --git a/nuttx/lib/string/lib_memchr.c b/nuttx/lib/string/lib_memchr.c new file mode 100644 index 0000000000..e0dec82700 --- /dev/null +++ b/nuttx/lib/string/lib_memchr.c @@ -0,0 +1,80 @@ +/**************************************************************************** + * lib/string/lib_memchr.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: memchr + * + * Description: + * The memchr() function locates the first occurrence of 'c' (converted to + * an unsigned char) in the initial 'n' bytes (each interpreted as + * unsigned char) of the object pointed to by s. + * + * Returned Value: + * The memchr() function returns a pointer to the located byte, or a null + * pointer if the byte does not occur in the object. + * + ****************************************************************************/ + +FAR void *memchr(FAR const void *s, int c, size_t n) +{ + FAR const unsigned char *p = (FAR const unsigned char *)s; + + if (s) + { + while (n--) + { + if (*p == (unsigned char)c) + { + return (FAR void *)p; + } + + p++; + } + } + + return NULL; +} diff --git a/nuttx/lib/string/lib_memcmp.c b/nuttx/lib/string/lib_memcmp.c new file mode 100644 index 0000000000..eb2e1fd125 --- /dev/null +++ b/nuttx/lib/string/lib_memcmp.c @@ -0,0 +1,74 @@ +/************************************************************ + * lib/string/lib_memcmp.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include +#include +#include + +/************************************************************ + * Global Functions + ************************************************************/ + +#ifndef CONFIG_ARCH_MEMCMP +int memcmp(const void *s1, const void *s2, size_t n) +{ + unsigned char *p1 = (unsigned char *)s1; + unsigned char *p2 = (unsigned char *)s2; + + while (n-- > 0) + { + if (*p1 < *p2) + { + return -1; + } + else if (*p1 > *p2) + { + return 1; + } + + p1++; + p2++; + } + return 0; +} +#endif diff --git a/nuttx/lib/string/lib_memcpy.c b/nuttx/lib/string/lib_memcpy.c new file mode 100644 index 0000000000..3b62edbabd --- /dev/null +++ b/nuttx/lib/string/lib_memcpy.c @@ -0,0 +1,64 @@ +/**************************************************************************** + * lib/string/lib_memcpy.c + * + * Copyright (C) 2007, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: memcpy + ****************************************************************************/ + +#ifndef CONFIG_ARCH_MEMCPY +FAR void *memcpy(FAR void *dest, FAR const void *src, size_t n) +{ + FAR unsigned char *pout = (FAR unsigned char*)dest; + FAR unsigned char *pin = (FAR unsigned char*)src; + while (n-- > 0) *pout++ = *pin++; + return dest; +} +#endif diff --git a/nuttx/lib/string/lib_memmove.c b/nuttx/lib/string/lib_memmove.c new file mode 100644 index 0000000000..ecaeb54cf2 --- /dev/null +++ b/nuttx/lib/string/lib_memmove.c @@ -0,0 +1,72 @@ +/************************************************************ + * lib/string/lib_memmove.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include +#include +#include + +/************************************************************ + * Global Functions + ************************************************************/ + +#ifndef CONFIG_ARCH_MEMMOVE +void *memmove(void *dest, const void *src, size_t count) +{ + char *tmp, *s; + if (dest <= src) + { + tmp = (char*) dest; + s = (char*) src; + while (count--) + *tmp++ = *s++; + } + else + { + tmp = (char*) dest + count; + s = (char*) src + count; + while (count--) + *--tmp = *--s; + } + return dest; +} +#endif diff --git a/nuttx/lib/string/lib_memset.c b/nuttx/lib/string/lib_memset.c new file mode 100644 index 0000000000..916351b974 --- /dev/null +++ b/nuttx/lib/string/lib_memset.c @@ -0,0 +1,59 @@ +/************************************************************ + * lib/string/lib_memset.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include +#include +#include + +/************************************************************ + * Global Functions + ************************************************************/ + +#ifndef CONFIG_ARCH_MEMSET +void *memset(void *s, int c, size_t n) +{ + unsigned char *p = (unsigned char*)s; + while (n-- > 0) *p++ = c; + return s; +} +#endif diff --git a/nuttx/lib/string/lib_skipspace.c b/nuttx/lib/string/lib_skipspace.c new file mode 100644 index 0000000000..b4e6588e59 --- /dev/null +++ b/nuttx/lib/string/lib_skipspace.c @@ -0,0 +1,69 @@ +/**************************************************************************** + * lib/string/lib_skipspace.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lib_skipspace + * + * Description: + * Skip over leading whitespace + * + ****************************************************************************/ + +void lib_skipspace(const char **pptr) +{ + const char *ptr = *pptr; + while (isspace(*ptr)) ptr++; + *pptr = ptr; +} + + diff --git a/nuttx/lib/string/lib_strcasecmp.c b/nuttx/lib/string/lib_strcasecmp.c new file mode 100644 index 0000000000..d4aa8cc031 --- /dev/null +++ b/nuttx/lib/string/lib_strcasecmp.c @@ -0,0 +1,65 @@ +/**************************************************************************** + * lib/string/lib_strcasecmp.c + * + * Copyright (C) 2008-2009, 2011 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. + * + *****************************************************************************/ + +/**************************************************************************** + * Included Files + *****************************************************************************/ + +#include + +#include +#include + +/**************************************************************************** + * Public Functions + *****************************************************************************/ + +#ifndef CONFIG_ARCH_STRCMP +int strcasecmp(const char *cs, const char *ct) +{ + int result; + for (;;) + { + if ((result = (int)toupper(*cs) - (int)toupper(*ct)) != 0 || !*cs) + { + break; + } + + cs++; + ct++; + } + return result; +} +#endif diff --git a/nuttx/lib/string/lib_strcasestr.c b/nuttx/lib/string/lib_strcasestr.c new file mode 100644 index 0000000000..23f0ab57e6 --- /dev/null +++ b/nuttx/lib/string/lib_strcasestr.c @@ -0,0 +1,134 @@ +/**************************************************************************** + * lib/string/lib_strstr.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use str 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 str binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer str + * 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 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static FAR char *strcasechr(FAR const char *s, int uc) +{ + register char ch; + + if (s) + { + for (; *s; s++) + { + ch = *s; + if (toupper(ch) == uc) + { + return (FAR char*)s; + } + } + } + + return NULL; +} + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +FAR char *strcasestr(FAR const char *str, FAR const char *substr) +{ + const char *candidate; /* Candidate in str with matching start character */ + char ch; /* First character of the substring */ + int len; /* The length of the substring */ + + /* Special case the empty substring */ + + len = strlen(substr); + ch = *substr; + + if (!ch) + { + /* We'll say that an empty substring matches at the beginning of + * the string + */ + + return (char*)str; + } + + /* Search for the substring */ + + candidate = str; + ch = toupper(ch); + + for (;;) + { + /* strcasechr() will return a pointer to the next occurrence of the + * character ch in the string (ignoring case) + */ + + candidate = strcasechr(candidate, ch); + if (!candidate || strlen(candidate) < len) + { + /* First character of the substring does not appear in the string + * or the remainder of the string is not long enough to contain the + * substring. + */ + + return NULL; + } + + /* Check if this is the beginning of a matching substring (ignoring case) */ + + if (strncasecmp(candidate, substr, len) == 0) + { + /* Yes.. return the pointer to the first occurrence of the matching + * substring. + */ + + return (char*)candidate; + } + + /* No, find the next candidate after this one */ + + candidate++; + } + + /* Won't get here, but some compilers might complain */ + + return NULL; +} + diff --git a/nuttx/lib/string/lib_strcat.c b/nuttx/lib/string/lib_strcat.c new file mode 100644 index 0000000000..20350fec07 --- /dev/null +++ b/nuttx/lib/string/lib_strcat.c @@ -0,0 +1,62 @@ +/**************************************************************************** + * lib/string/lib_strcat.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +#ifndef CONFIG_ARCH_STRCAT +char *strcat(char *dest, const char *src) +{ + char *ret = dest; + + dest += strlen(dest); + while (*src != '\0') + { + *dest++ = *src++; + } + *dest = '\0'; + + return ret; +} +#endif diff --git a/nuttx/lib/string/lib_strchr.c b/nuttx/lib/string/lib_strchr.c new file mode 100644 index 0000000000..ad72738620 --- /dev/null +++ b/nuttx/lib/string/lib_strchr.c @@ -0,0 +1,76 @@ +/**************************************************************************** + * lib/string/lib_strchr.c + * + * Copyright (C) 2007, 2009, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: strchr + * + * Description: + * The strchr() function locates the first occurrence of 'c' (converted to + * a char) in the string pointed to by 's'. The terminating null byte is + * considered to be part of the string. + * + * Returned Value: + * Upon completion, strchr() returns a pointer to the byte, or a null + * pointer if the byte was not found. + * + ****************************************************************************/ + +FAR char *strchr(FAR const char *s, int c) +{ + if (s) + { + for (; *s; s++) + { + if (*s == c) + { + return (FAR char *)s; + } + } + } + + return NULL; +} diff --git a/nuttx/lib/string/lib_strcmp.c b/nuttx/lib/string/lib_strcmp.c new file mode 100644 index 0000000000..0e3eee8900 --- /dev/null +++ b/nuttx/lib/string/lib_strcmp.c @@ -0,0 +1,59 @@ +/**************************************************************************** + * lib/string/lib_strcmp.c + * + * Copyright (C) 2007-2009, 2011 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. + * + *****************************************************************************/ + +/**************************************************************************** + * Included Files + *****************************************************************************/ + +#include + +#include + +/**************************************************************************** + * Public Functions + *****************************************************************************/ + +#ifndef CONFIG_ARCH_STRCMP +int strcmp(const char *cs, const char *ct) +{ + register signed char result; + for (;;) + { + if ((result = *cs - *ct++) != 0 || !*cs++) + break; + } + return result; +} +#endif diff --git a/nuttx/lib/string/lib_strcpy.c b/nuttx/lib/string/lib_strcpy.c new file mode 100644 index 0000000000..e2f70b94e3 --- /dev/null +++ b/nuttx/lib/string/lib_strcpy.c @@ -0,0 +1,55 @@ +/************************************************************************ + * lib/string/lib_strcpy.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include + +/************************************************************************ + * Global Functions + ************************************************************************/ + +#ifndef CONFIG_ARCH_STRCPY +char *strcpy(char *dest, const char *src) +{ + char *tmp = dest; + while ((*dest++ = *src++) != '\0'); + return tmp; +} +#endif diff --git a/nuttx/lib/string/lib_strcspn.c b/nuttx/lib/string/lib_strcspn.c new file mode 100644 index 0000000000..9da89241c5 --- /dev/null +++ b/nuttx/lib/string/lib_strcspn.c @@ -0,0 +1,67 @@ +/**************************************************************************** + * lib/string/lib_strcspn.c + * + * Copyright (C) 2007, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: strcspn + * + * Description: + * strspn() calculates the length of the initial segment of s which + * consists entirely of characters not in reject + * + ****************************************************************************/ + +size_t strcspn(const char *s, const char *reject) +{ + size_t i; + for (i = 0; s[i] && strchr(reject, s[i]) == NULL; i++); + return i; +} + diff --git a/nuttx/lib/string/lib_strdup.c b/nuttx/lib/string/lib_strdup.c new file mode 100644 index 0000000000..44a0cbc0d8 --- /dev/null +++ b/nuttx/lib/string/lib_strdup.c @@ -0,0 +1,62 @@ +/************************************************************************ + * lib/string//lib_strdup.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include + +#include "lib_internal.h" + +/************************************************************************ + * Global Functions + ************************************************************************/ + +FAR char *strdup(const char *s) +{ + FAR char *news = NULL; + if (s) + { + news = (FAR char*)lib_malloc(strlen(s) + 1); + if (news) + { + strcpy(news, s); + } + } + return news; +} diff --git a/nuttx/lib/string/lib_strerror.c b/nuttx/lib/string/lib_strerror.c new file mode 100644 index 0000000000..249f695c1b --- /dev/null +++ b/nuttx/lib/string/lib_strerror.c @@ -0,0 +1,375 @@ +/************************************************************************ + * lib/string/lib_strerror.c + * + * Copyright (C) 2007, 2009, 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include +#include +#include + +/************************************************************************ + * Definitions + ************************************************************************/ + +/************************************************************************ + * Private Types + ************************************************************************/ + +struct errno_strmap_s +{ + uint8_t errnum; + const char *str; +}; + +/************************************************************************ + * Private Data + ************************************************************************/ + +#ifdef CONFIG_LIBC_STRERROR + +/* This table maps all error numbers to descriptive strings. + * The only assumption that the code makes with regard to this + * this table is that it is ordered by error number. + * + * The size of this table is quite large. Its size can be + * reduced by eliminating some of the more obscure error + * strings. + */ + +#ifndef CONFIG_LIBC_STRERROR_SHORT + +static const struct errno_strmap_s g_errnomap[] = +{ + { EPERM, EPERM_STR }, + { ENOENT, ENOENT_STR }, + { ESRCH, ESRCH_STR }, + { EINTR, EINTR_STR }, + { EIO, EIO_STR }, + { ENXIO, ENXIO_STR }, + { E2BIG, E2BIG_STR }, + { ENOEXEC, ENOEXEC_STR }, + { EBADF, EBADF_STR }, + { ECHILD, ECHILD_STR }, + { EAGAIN, EAGAIN_STR }, + { ENOMEM, ENOMEM_STR }, + { EACCES, EACCES_STR }, + { EFAULT, EFAULT_STR }, + { ENOTBLK, ENOTBLK_STR }, + { EBUSY, EBUSY_STR }, + { EEXIST, EEXIST_STR }, + { EXDEV, EXDEV_STR }, + { ENODEV, ENODEV_STR }, + { ENOTDIR, ENOTDIR_STR }, + { EISDIR, EISDIR_STR }, + { EINVAL, EINVAL_STR }, + { ENFILE, ENFILE_STR }, + { EMFILE, EMFILE_STR }, + { ENOTTY, ENOTTY_STR }, + { ETXTBSY, ETXTBSY_STR }, + { EFBIG, EFBIG_STR }, + { ENOSPC, ENOSPC_STR }, + { ESPIPE, ESPIPE_STR }, + { EROFS, EROFS_STR }, + { EMLINK, EMLINK_STR }, + { EPIPE, EPIPE_STR }, + { EDOM, EDOM_STR }, + { ERANGE, ERANGE_STR }, + { EDEADLK, EDEADLK_STR }, + { ENAMETOOLONG, ENAMETOOLONG_STR }, + { ENOLCK, ENOLCK_STR }, + { ENOSYS, ENOSYS_STR }, + { ENOTEMPTY, ENOTEMPTY_STR }, + { ELOOP, ELOOP_STR }, + { ENOMSG, ENOMSG_STR }, + { EIDRM, EIDRM_STR }, + { ECHRNG, ECHRNG_STR }, + { EL2NSYNC, EL2NSYNC_STR }, + { EL3HLT, EL3HLT_STR }, + { EL3RST, EL3RST_STR }, + { ELNRNG, ELNRNG_STR }, + { EUNATCH, EUNATCH_STR }, + { ENOCSI, ENOCSI_STR }, + { EL2HLT, EL2HLT_STR }, + { EBADE, EBADE_STR }, + { EBADR, EBADR_STR }, + { EXFULL, EXFULL_STR }, + { ENOANO, ENOANO_STR }, + { EBADRQC, EBADRQC_STR }, + { EBADSLT, EBADSLT_STR }, + { EBFONT, EBFONT_STR }, + { ENOSTR, ENOSTR_STR }, + { ENODATA, ENODATA_STR }, + { ETIME, ETIME_STR }, + { ENOSR, ENOSR_STR }, + { ENONET, ENONET_STR }, + { ENOPKG, ENOPKG_STR }, + { EREMOTE, EREMOTE_STR }, + { ENOLINK, ENOLINK_STR }, + { EADV, EADV_STR }, + { ESRMNT, ESRMNT_STR }, + { ECOMM, ECOMM_STR }, + { EPROTO, EPROTO_STR }, + { EMULTIHOP, EMULTIHOP_STR }, + { EDOTDOT, EDOTDOT_STR }, + { EBADMSG, EBADMSG_STR }, + { EOVERFLOW, EOVERFLOW_STR }, + { ENOTUNIQ, ENOTUNIQ_STR }, + { EBADFD, EBADFD_STR }, + { EREMCHG, EREMCHG_STR }, + { ELIBACC, ELIBACC_STR }, + { ELIBBAD, ELIBBAD_STR }, + { ELIBSCN, ELIBSCN_STR }, + { ELIBMAX, ELIBMAX_STR }, + { ELIBEXEC, ELIBEXEC_STR }, + { EILSEQ, EILSEQ_STR }, + { ERESTART, ERESTART_STR }, + { ESTRPIPE, ESTRPIPE_STR }, + { EUSERS, EUSERS_STR }, + { ENOTSOCK, ENOTSOCK_STR }, + { EDESTADDRREQ, EDESTADDRREQ_STR }, + { EMSGSIZE, EMSGSIZE_STR }, + { EPROTOTYPE, EPROTOTYPE_STR }, + { ENOPROTOOPT, ENOPROTOOPT_STR }, + { EPROTONOSUPPORT, EPROTONOSUPPORT_STR }, + { ESOCKTNOSUPPORT, ESOCKTNOSUPPORT_STR }, + { EOPNOTSUPP, EOPNOTSUPP_STR }, + { EPFNOSUPPORT, EPFNOSUPPORT_STR }, + { EAFNOSUPPORT, EAFNOSUPPORT_STR }, + { EADDRINUSE, EADDRINUSE_STR }, + { EADDRNOTAVAIL, EADDRNOTAVAIL_STR }, + { ENETDOWN, ENETDOWN_STR }, + { ENETUNREACH, ENETUNREACH_STR }, + { ENETRESET, ENETRESET_STR }, + { ECONNABORTED, ECONNABORTED_STR }, + { ECONNRESET, ECONNRESET_STR }, + { ENOBUFS, ENOBUFS_STR }, + { EISCONN, EISCONN_STR }, + { ENOTCONN, ENOTCONN_STR }, + { ESHUTDOWN, ESHUTDOWN_STR }, + { ETOOMANYREFS, ETOOMANYREFS_STR }, + { ETIMEDOUT, ETIMEDOUT_STR }, + { ECONNREFUSED, ECONNREFUSED_STR }, + { EHOSTDOWN, EHOSTDOWN_STR }, + { EHOSTUNREACH, EHOSTUNREACH_STR }, + { EALREADY, EALREADY_STR }, + { EINPROGRESS, EINPROGRESS_STR }, + { ESTALE, ESTALE_STR }, + { EUCLEAN, EUCLEAN_STR }, + { ENOTNAM, ENOTNAM_STR }, + { ENAVAIL, ENAVAIL_STR }, + { EISNAM, EISNAM_STR }, + { EREMOTEIO, EREMOTEIO_STR }, + { EDQUOT, EDQUOT_STR }, + { ENOMEDIUM, ENOMEDIUM_STR }, + { EMEDIUMTYPE, EMEDIUMTYPE_STR } +}; + +#else /* CONFIG_LIBC_STRERROR_SHORT */ + +static const struct errno_strmap_s g_errnomap[] = +{ + { EPERM, "EPERM" }, + { ENOENT, "ENOENT" }, + { ESRCH, "ESRCH" }, + { EINTR, "EINTR" }, + { EIO, "EIO" }, + { ENXIO, "ENXIO" }, + { E2BIG, "E2BIG" }, + { ENOEXEC, "ENOEXEC" }, + { EBADF, "EBADF" }, + { ECHILD, "ECHILD" }, + { EAGAIN, "EAGAIN" }, + { ENOMEM, "ENOMEM" }, + { EACCES, "EACCES" }, + { EFAULT, "EFAULT" }, + { ENOTBLK, "ENOTBLK" }, + { EBUSY, "EBUSY" }, + { EEXIST, "EEXIST" }, + { EXDEV, "EXDEV" }, + { ENODEV, "ENODEV" }, + { ENOTDIR, "ENOTDIR" }, + { EISDIR, "EISDIR" }, + { EINVAL, "EINVAL" }, + { ENFILE, "ENFILE" }, + { EMFILE, "EMFILE" }, + { ENOTTY, "ENOTTY" }, + { ETXTBSY, "ETXTBSY" }, + { EFBIG, "EFBIG" }, + { ENOSPC, "ENOSPC" }, + { ESPIPE, "ESPIPE" }, + { EROFS, "EROFS" }, + { EMLINK, "EMLINK" }, + { EPIPE, "EPIPE" }, + { EDOM, "EDOM" }, + { ERANGE, "ERANGE" }, + { EDEADLK, "EDEADLK" }, + { ENAMETOOLONG, "ENAMETOOLONG" }, + { ENOLCK, "ENOLCK" }, + { ENOSYS, "ENOSYS" }, + { ENOTEMPTY, "ENOTEMPTY" }, + { ELOOP, "ELOOP" }, + { ENOMSG, "ENOMSG" }, + { EIDRM, "EIDRM" }, + { ECHRNG, "ECHRNG" }, + { EL2NSYNC, "EL2NSYNC" }, + { EL3HLT, "EL3HLT" }, + { EL3RST, "EL3RST" }, + { EL3RST, "EL3RST" }, + { EUNATCH, "EUNATCH" }, + { ENOCSI, "ENOCSI" }, + { EL2HLT, "EL2HLT" }, + { EBADE, "EBADE" }, + { EBADR, "EBADR" }, + { EXFULL, "EXFULL" }, + { ENOANO, "ENOANO" }, + { EBADRQC, "EBADRQC" }, + { EBADSLT, "EBADSLT" }, + { EBFONT, "EBFONT" }, + { ENOSTR, "ENOSTR" }, + { ENODATA, "ENODATA" }, + { ETIME, "ETIME" }, + { ENOSR, "ENOSR" }, + { ENONET, "ENONET" }, + { ENOPKG, "ENOPKG" }, + { EREMOTE, "EREMOTE" }, + { ENOLINK, "ENOLINK" }, + { EADV, "EADV" }, + { ESRMNT, "ESRMNT" }, + { ECOMM, "ECOMM" }, + { EPROTO, "EPROTO" }, + { EMULTIHOP, "EMULTIHOP" }, + { EDOTDOT, "EDOTDOT" }, + { EBADMSG, "EBADMSG" }, + { EOVERFLOW, "EOVERFLOW" }, + { ENOTUNIQ, "ENOTUNIQ" }, + { EBADFD, "EBADFD" }, + { EREMCHG, "EREMCHG" }, + { ELIBACC, "ELIBACC" }, + { ELIBBAD, "ELIBBAD" }, + { ELIBSCN, "ELIBSCN" }, + { ELIBMAX, "ELIBMAX" }, + { ELIBEXEC, "ELIBEXEC" }, + { EILSEQ, "EILSEQ" }, + { ERESTART, "ERESTART" }, + { ESTRPIPE, "ESTRPIPE" }, + { EUSERS, "EUSERS" }, + { ENOTSOCK, "ENOTSOCK" }, + { EDESTADDRREQ, "EDESTADDRREQ" }, + { EMSGSIZE, "EMSGSIZE" }, + { EPROTOTYPE, "EPROTOTYPE" }, + { ENOPROTOOPT, "ENOPROTOOPT" }, + { EPROTONOSUPPORT, "EPROTONOSUPPORT" }, + { ESOCKTNOSUPPORT, "ESOCKTNOSUPPORT" }, + { EOPNOTSUPP, "EOPNOTSUPP" }, + { EPFNOSUPPORT, "EPFNOSUPPORT" }, + { EAFNOSUPPORT, "EAFNOSUPPORT" }, + { EADDRINUSE, "EADDRINUSE" }, + { EADDRNOTAVAIL, "EADDRNOTAVAIL" }, + { ENETDOWN, "ENETDOWN" }, + { ENETUNREACH, "ENETUNREACH" }, + { ENETRESET, "ENETRESET" }, + { ECONNABORTED, "ECONNABORTED" }, + { ECONNRESET, "ECONNRESET" }, + { ENOBUFS, "ENOBUFS" }, + { EISCONN, "EISCONN" }, + { ENOTCONN, "ENOTCONN" }, + { ESHUTDOWN, "ESHUTDOWN" }, + { ETOOMANYREFS, "ETOOMANYREFS" }, + { ETIMEDOUT, "ETIMEDOUT" }, + { ECONNREFUSED, "ECONNREFUSED" }, + { EHOSTDOWN, "EHOSTDOWN" }, + { EHOSTUNREACH, "EHOSTUNREACH" }, + { EALREADY, "EALREADY" }, + { EINPROGRESS, "EINPROGRESS" }, + { ESTALE, "ESTALE" }, + { EUCLEAN, "EUCLEAN" }, + { ENOTNAM, "ENOTNAM" }, + { ENAVAIL, "ENAVAIL" }, + { EISNAM, "EISNAM" }, + { EREMOTEIO, "EREMOTEIO" }, + { EDQUOT, "EDQUOT" }, + { ENOMEDIUM, "ENOMEDIUM" }, + { EMEDIUMTYPE, "EMEDIUMTYPE" } +}; + +#endif /* CONFIG_LIBC_STRERROR_SHORT */ + +#define NERRNO_STRS (sizeof(g_errnomap) / sizeof(struct errno_strmap_s)) + +#endif /* CONFIG_LIBC_STRERROR */ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: strerror + ************************************************************************/ + +FAR const char *strerror(int errnum) +{ +#ifdef CONFIG_LIBC_STRERROR + int ndxlow = 0; + int ndxhi = NERRNO_STRS - 1; + int ndxmid; + + do + { + ndxmid = (ndxlow + ndxhi) >> 1; + if (errnum > g_errnomap[ndxmid].errnum) + { + ndxlow = ndxmid + 1; + } + else if (errnum < g_errnomap[ndxmid].errnum) + { + ndxhi = ndxmid - 1; + } + else + { + return g_errnomap[ndxmid].str; + } + } + while (ndxlow <= ndxhi); +#endif + return "Unknown error"; +} diff --git a/nuttx/lib/string/lib_strlen.c b/nuttx/lib/string/lib_strlen.c new file mode 100644 index 0000000000..8333058091 --- /dev/null +++ b/nuttx/lib/string/lib_strlen.c @@ -0,0 +1,55 @@ +/**************************************************************************** + * lib/string/lib_strlen.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +#ifndef CONFIG_ARCH_STRLEN +size_t strlen(const char *s) +{ + const char *sc; + for (sc = s; *sc != '\0'; ++sc); + return sc - s; +} +#endif diff --git a/nuttx/lib/string/lib_strncasecmp.c b/nuttx/lib/string/lib_strncasecmp.c new file mode 100644 index 0000000000..be369cf0d8 --- /dev/null +++ b/nuttx/lib/string/lib_strncasecmp.c @@ -0,0 +1,70 @@ +/**************************************************************************** + * lib/string/lib_strncasecmp.c + * + * Copyright (C) 2007-2009, 2011 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. + * + *****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + *****************************************************************************/ + +/**************************************************************************** + * Included Files + *****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Global Functions + *****************************************************************************/ + +#ifndef CONFIG_ARCH_STRNCASECMP +int strncasecmp(const char *cs, const char *ct, size_t nb) +{ + int result = 0; + for (; nb > 0; nb--) + { + if ((result = (int)toupper(*cs) - (int)toupper(*ct)) != 0 || !*cs) + { + break; + } + + cs++; + ct++; + } + return result; +} +#endif diff --git a/nuttx/lib/string/lib_strncat.c b/nuttx/lib/string/lib_strncat.c new file mode 100644 index 0000000000..af893e0f9b --- /dev/null +++ b/nuttx/lib/string/lib_strncat.c @@ -0,0 +1,62 @@ +/************************************************************ + * lib/string/lib_strncat.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include +#include +#include + +/************************************************************ + * Global Functions + ************************************************************/ + +#ifndef CONFIG_ARCH_STRNCAT +char *strncat(char *dest, const char *src, size_t n) +{ + char *ret = dest; + + dest += strlen(dest); + for (; n > 0 && *src != '\0' ; n--) + { + *dest++ = *src++; + } + *dest = '\0'; + + return ret; +} +#endif diff --git a/nuttx/lib/string/lib_strncmp.c b/nuttx/lib/string/lib_strncmp.c new file mode 100644 index 0000000000..ce22820249 --- /dev/null +++ b/nuttx/lib/string/lib_strncmp.c @@ -0,0 +1,65 @@ +/**************************************************************************** + * lib/lib_strncmp.c + * + * Copyright (C) 2007-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. + * + *****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + *****************************************************************************/ + +/**************************************************************************** + * Included Files + *****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Global Functions + *****************************************************************************/ + +#ifndef CONFIG_ARCH_STRNCMP +int strncmp(const char *cs, const char *ct, size_t nb) +{ + int result = 0; + for (; nb > 0; nb--) + { + if ((result = (int)*cs - (int)*ct++) != 0 || !*cs++) + { + break; + } + } + return result; +} +#endif diff --git a/nuttx/lib/string/lib_strncpy.c b/nuttx/lib/string/lib_strncpy.c new file mode 100644 index 0000000000..149369d508 --- /dev/null +++ b/nuttx/lib/string/lib_strncpy.c @@ -0,0 +1,57 @@ +/************************************************************ + * lib/string/lib_strncpy.c + * + * Copyright (C) 2007, 2011 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. + * + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include +#include +#include + +/************************************************************ + * Global Functions + ************************************************************/ + +#ifndef CONFIG_ARCH_STRNCPY +char *strncpy(char *dest, const char *src, size_t n) +{ + char *ret = dest; /* Value to be returned */ + char *end = dest + n; /* End of dest buffer + 1 byte */ + + while ((*dest++ = *src++) != '\0' && dest != end); + return ret; +} +#endif diff --git a/nuttx/lib/string/lib_strndup.c b/nuttx/lib/string/lib_strndup.c new file mode 100644 index 0000000000..ffaf892eaa --- /dev/null +++ b/nuttx/lib/string/lib_strndup.c @@ -0,0 +1,93 @@ +/************************************************************************ + * lib/string//lib_strndup.c + * + * Copyright (C) 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include + +#include "lib_internal.h" + +/************************************************************************ + * Global Functions + ************************************************************************/ +/************************************************************************ + * Name: strndup + * + * Description: + * The strndup() function is equivalent to the strdup() function, + * duplicating the provided 's' in a new block of memory allocated as + * if by using malloc(), with the exception being that strndup() copies + * at most 'size' plus one bytes into the newly allocated memory, + * terminating the new string with a NUL character. If the length of 's' + * is larger than 'size', only 'size' bytes will be duplicated. If + * 'size' is larger than the length of 's', all bytes in s will be + * copied into the new memory buffer, including the terminating NUL + * character. The newly created string will always be properly + * terminated. + * + ************************************************************************/ + +FAR char *strndup(FAR const char *s, size_t size) +{ + FAR char *news = NULL; + if (s) + { + /* Get the size of the new string = MIN(strlen(s), size) */ + + size_t allocsize = strlen(s); + if (allocsize > size) + { + allocsize = size; + } + + /* Allocate the new string, adding 1 for the NUL terminator */ + + news = (FAR char*)lib_malloc(allocsize + 1); + if (news) + { + /* Copy the string into the allocated memory and add a NUL + * terminator in any case. + */ + + memcpy(news, s, allocsize); + news[allocsize] = '\0'; + } + } + return news; +} diff --git a/nuttx/lib/string/lib_strnlen.c b/nuttx/lib/string/lib_strnlen.c new file mode 100644 index 0000000000..2b64fe9845 --- /dev/null +++ b/nuttx/lib/string/lib_strnlen.c @@ -0,0 +1,62 @@ +/**************************************************************************** + * lib/string/lib_strnlen.c + * + * This file is part of NuttX, contributed by Michael Hrabanek + * + * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Author: Michael Hrabanek + * + * Derives from the file lib/lib_strlen.c: + * + * Copyright (C) 2007, 2008, 2010 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +#ifndef CONFIG_ARCH_STRNLEN +size_t strnlen(const char *s, size_t maxlen) +{ + const char *sc; + for (sc = s; maxlen != 0 && *sc != '\0'; maxlen--, ++sc); + return sc - s; +} +#endif diff --git a/nuttx/lib/string/lib_strpbrk.c b/nuttx/lib/string/lib_strpbrk.c new file mode 100644 index 0000000000..02e2ea2c70 --- /dev/null +++ b/nuttx/lib/string/lib_strpbrk.c @@ -0,0 +1,85 @@ +/**************************************************************************** + * lib/string/lib_strpbrk.c + * + * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use str 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 str binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer str + * 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 + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +char *strpbrk(const char *str, const char *charset) +{ + /* Sanity checking */ + +#ifdef CONFIG_DEBUG + if (!str || !charset) + { + return NULL; + } +#endif + + /* Check each character in the string */ + + while (*str) + { + /* Check if the character from the string matches any character in the charset */ + + if (strchr(charset, *str) != NULL) + { + /* Yes, then this position must be the first occurrence in string */ + + return (char*)str; + } + + /* This character from the strings matches none of those in the charset. + * Try the next character from the string. + */ + + str++; + } + + /* We have looked at every character in the string, and none of them match any of + * the characters in charset. + */ + + return NULL; +} + diff --git a/nuttx/lib/string/lib_strrchr.c b/nuttx/lib/string/lib_strrchr.c new file mode 100644 index 0000000000..91243ce589 --- /dev/null +++ b/nuttx/lib/string/lib_strrchr.c @@ -0,0 +1,68 @@ +/************************************************************************ + * lib/string/lib_strrchr.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include + +/************************************************************************ + * Global Functions + ************************************************************************/ + +/* The strrchr() function returns a pointer to the last + * occurrence of the character c in the string s. + */ + +char *strrchr(const char *s, int c) +{ + if (s) + { + const char *p = &s[strlen(s) - 1]; + for (; p >= s; p--) + { + if (*p == c) + { + return (char*)p; + } + } + } + + return NULL; +} + diff --git a/nuttx/lib/string/lib_strspn.c b/nuttx/lib/string/lib_strspn.c new file mode 100644 index 0000000000..e7b5ea0a5b --- /dev/null +++ b/nuttx/lib/string/lib_strspn.c @@ -0,0 +1,66 @@ +/**************************************************************************** + * lib/string/lib_strspn.c + * + * Copyright (C) 2007, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: strspn + * + * Description: + * strspn() calculates the length of the initial segment of s which + * consists entirely of characters in accept. + * + ****************************************************************************/ + +size_t strspn(const char *s, const char *accept) +{ + size_t i; + for (i = 0; s[i] && strchr(accept, s[i]) != NULL; i++); + return i; +} diff --git a/nuttx/lib/string/lib_strstr.c b/nuttx/lib/string/lib_strstr.c new file mode 100644 index 0000000000..b8c896fa2e --- /dev/null +++ b/nuttx/lib/string/lib_strstr.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * lib/string/lib_strstr.c + * + * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use str 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 str binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer str + * 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 + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +char *strstr(const char *str, const char *substr) +{ + const char *candidate; /* Candidate in str with matching start character */ + char ch; /* First character of the substring */ + int len; /* The length of the substring */ + + /* Special case the empty substring */ + + len = strlen(substr); + ch = *substr; + + if (!ch) + { + /* We'll say that an empty substring matches at the beginning of + * the string + */ + + return (char*)str; + } + + /* Search for the substring */ + + candidate = str; + for (;;) + { + /* strchr() will return a pointer to the next occurrence of the + * character ch in the string + */ + + candidate = strchr(candidate, ch); + if (!candidate || strlen(candidate) < len) + { + /* First character of the substring does not appear in the string + * or the remainder of the string is not long enough to contain the + * substring. + */ + + return NULL; + } + + /* Check if this is the beginning of a matching substring */ + + if (strncmp(candidate, substr, len) == 0) + { + return (char*)candidate; + } + + /* No, find the next candidate after this one */ + + candidate++; + } + + /* Won't get here, but some compilers might complain */ + + return NULL; +} + diff --git a/nuttx/lib/string/lib_strtod.c b/nuttx/lib/string/lib_strtod.c new file mode 100644 index 0000000000..8fecd45713 --- /dev/null +++ b/nuttx/lib/string/lib_strtod.c @@ -0,0 +1,241 @@ +/**************************************************************************** + * lib/string/lib_strtod.c + * Convert string to double + * + * Copyright (C) 2002 Michael Ringgaard. All rights reserved. + * Copyright (C) 2006-2007 H. Peter Anvin. + * + * 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 of the project 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_HAVE_DOUBLE + +/**************************************************************************** + * Pre-processor definitions + ****************************************************************************/ + +/* These are predefined with GCC, but could be issues for other compilers. If + * not defined, an arbitrary big number is put in for now. These should be + * added to nuttx/compiler for your compiler. + */ + +#if !defined(__DBL_MIN_EXP__) || !defined(__DBL_MAX_EXP__) +# ifdef CONFIG_CPP_HAVE_WARNING +# warning "Size of exponent is unknown" +# endif +# undef __DBL_MIN_EXP__ +# define __DBL_MIN_EXP__ (-1021) +# undef __DBL_MAX_EXP__ +# define __DBL_MAX_EXP__ (1024) +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static inline int is_real(double x) +{ + const double_t infinite = 1.0/0.0; + return (x < infinite) && (x >= -infinite); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/***************************************************(************************ + * Name: strtod + * + * Description: + * Convert a string to a double value + * + ****************************************************************************/ + +double_t strtod(const char *str, char **endptr) +{ + double_t number; + int exponent; + int negative; + char *p = (char *) str; + double p10; + int n; + int num_digits; + int num_decimals; + const double_t infinite = 1.0/0.0; + + /* Skip leading whitespace */ + + while (isspace(*p)) + { + p++; + } + + /* Handle optional sign */ + + negative = 0; + switch (*p) + { + case '-': + negative = 1; /* Fall through to increment position */ + case '+': + p++; + } + + number = 0.; + exponent = 0; + num_digits = 0; + num_decimals = 0; + + /* Process string of digits */ + + while (isdigit(*p)) + { + number = number * 10. + (*p - '0'); + p++; + num_digits++; + } + + /* Process decimal part */ + + if (*p == '.') + { + p++; + + while (isdigit(*p)) + { + number = number * 10. + (*p - '0'); + p++; + num_digits++; + num_decimals++; + } + + exponent -= num_decimals; + } + + if (num_digits == 0) + { + set_errno(ERANGE); + return 0.0; + } + + /* Correct for sign */ + + if (negative) + { + number = -number; + } + + /* Process an exponent string */ + + if (*p == 'e' || *p == 'E') + { + /* Handle optional sign */ + + negative = 0; + switch(*++p) + { + case '-': + negative = 1; /* Fall through to increment pos */ + case '+': + p++; + } + + /* Process string of digits */ + + n = 0; + while (isdigit(*p)) + { + n = n * 10 + (*p - '0'); + p++; + } + + if (negative) + { + exponent -= n; + } + else + { + exponent += n; + } + } + + if (exponent < __DBL_MIN_EXP__ || + exponent > __DBL_MAX_EXP__) + { + set_errno(ERANGE); + return infinite; + } + + /* Scale the result */ + + p10 = 10.; + n = exponent; + if (n < 0) n = -n; + while (n) + { + if (n & 1) + { + if (exponent < 0) + { + number /= p10; + } + else + { + number *= p10; + } + } + n >>= 1; + p10 *= p10; + } + + if (!is_real(number)) + { + set_errno(ERANGE); + } + + if (endptr) + { + *endptr = p; + } + + return number; +} + +#endif /* CONFIG_HAVE_DOUBLE */ + diff --git a/nuttx/lib/string/lib_strtok.c b/nuttx/lib/string/lib_strtok.c new file mode 100644 index 0000000000..c409931359 --- /dev/null +++ b/nuttx/lib/string/lib_strtok.c @@ -0,0 +1,87 @@ +/**************************************************************************** + * lib/string/lib_strtok.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static char *g_saveptr = NULL; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: strtok + * + * Description: + * The strtok() function parses a string into a + * sequence of tokens. On the first call to strtok() the + * string to be parsed should be specified in 'str'. In + * each subsequent call that should parse the same string, + * 'str' should be NULL. + * + * The 'delim' argument specifies a set of characters that + * delimit the tokens in the parsed string. The caller + * may specify different strings in delim in successive + * calls that parse the same string. + * + * Each call to strtok() returns a pointer to a null- + * terminated string containing the next token. This + * string does not include the delimiting character. If + * no more tokens are found, strtok() returns NULL. + * + * A sequence of two or more contiguous delimiter + * characters in the parsed string is considered to be a + * single delimiter. Delimiter characters at the start or + * end of the string are ignored. The tokens returned by + * strtok() are always non-empty strings. + * + * Return + * strtok() returns a pointer to the next token, or NULL + * if there are no more tokens. + * + ****************************************************************************/ + +char *strtok(char *str, const char *delim) +{ + return strtok_r(str, delim, &g_saveptr); +} diff --git a/nuttx/lib/string/lib_strtokr.c b/nuttx/lib/string/lib_strtokr.c new file mode 100644 index 0000000000..1c571b6ae5 --- /dev/null +++ b/nuttx/lib/string/lib_strtokr.c @@ -0,0 +1,157 @@ +/**************************************************************************** + * lib/string/lib_strtokr.c + * + * Copyright (C) 2007, 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: strtok_r + * + * Description: + * The strtok_r() function is a reentrant version strtok(). + * Like strtok(), it parses a string into a sequence of + * tokens. On the first call to strtok() the string to be + * parsed should be specified in 'str'. In each subsequent + * call that should parse the same string, 'str' should be + * NULL. + * + * The 'saveptr' argument is a pointer to a char * + * variable that is used internally by strtok_r() in + * order to maintain context between successive calls + * that parse the same string. + * + * On the first call to strtok_r(), 'str' should point to the + * string to be parsed, and the value of 'saveptr' is + * ignored. In subsequent calls, 'str' should be NULL, and + * saveptr should be unchanged since the previous call. + * + * The 'delim' argument specifies a set of characters that + * delimit the tokens in the parsed string. The caller + * may specify different strings in delim in successive + * calls that parse the same string. + * + * Each call to strtok_r() returns a pointer to a null- + * terminated string containing the next token. This + * string does not include the delimiting character. If + * no more tokens are found, strtok_r() returns NULL. + * + * A sequence of two or more contiguous delimiter + * characters in the parsed string is considered to be a + * single delimiter. Delimiter characters at the start or + * end of the string are ignored. The tokens returned by + * strtok() are always non-empty strings. + * + * Return + * strtok_r() returns a pointer to the next token, or NULL + * if there are no more tokens. + * + ****************************************************************************/ + +FAR char *strtok_r(FAR char *str, FAR const char *delim, FAR char **saveptr) +{ + char *pbegin; + char *pend = NULL; + + /* Decide if we are starting a new string or continuing from + * the point we left off. + */ + + if (str) + { + pbegin = str; + } + else if (saveptr && *saveptr) + { + pbegin = *saveptr; + } + else + { + return NULL; + } + + /* Find the beginning of the next token */ + + for (; + *pbegin && strchr(delim, *pbegin) != NULL; + pbegin++); + + /* If we are at the end of the string with nothing + * but delimiters found, then return NULL. + */ + + if (!*pbegin) + { + return NULL; + } + + /* Find the end of the token */ + + for (pend = pbegin + 1; + *pend && strchr(delim, *pend) == NULL; + pend++); + + + /* pend either points to the end of the string or to + * the first delimiter after the string. + */ + + if (*pend) + { + /* Turn the delimiter into a null terminator */ + + *pend++ = '\0'; + } + + /* Save the pointer where we left off and return the + * beginning of the token. + */ + + if (saveptr) + { + *saveptr = pend; + } + return pbegin; +} diff --git a/nuttx/lib/string/lib_strtol.c b/nuttx/lib/string/lib_strtol.c new file mode 100644 index 0000000000..c17d87e635 --- /dev/null +++ b/nuttx/lib/string/lib_strtol.c @@ -0,0 +1,103 @@ +/**************************************************************************** + * lib/string/lib_strtol.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: strtol + * + * Description: + * The strtol() function converts the initial part of the string in + * nptr to a long integer value according to the given base, which must be + * between 2 and 36 inclusive, or be the special value 0. + * + * Warning: does not check for integer overflow! + * + ****************************************************************************/ + +long strtol(const char *nptr, char **endptr, int base) +{ + unsigned long accum = 0; + bool negate = false; + + if (nptr) + { + /* Skip leading spaces */ + + lib_skipspace(&nptr); + + /* Check for leading + or - */ + + if (*nptr == '-') + { + negate = true; + nptr++; + } + else if (*nptr == '+') + { + nptr++; + } + + /* Get the unsigned value */ + + accum = strtoul(nptr, endptr, base); + + /* Correct the sign of the result */ + + if (negate) + { + return -(long)accum; + } + } + return (long)accum; +} + diff --git a/nuttx/lib/string/lib_strtoll.c b/nuttx/lib/string/lib_strtoll.c new file mode 100644 index 0000000000..242e025c07 --- /dev/null +++ b/nuttx/lib/string/lib_strtoll.c @@ -0,0 +1,107 @@ +/**************************************************************************** + * lib/string/lib_strtoll.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "lib_internal.h" + +#ifdef CONFIG_HAVE_LONG_LONG + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: strtoll + * + * Description: + * The strtol() function converts the initial part of the string in + * nptr to a long long integer value according to the given base, which + * must be between 2 and 36 inclusive, or be the special value 0. + * + * Warning: does not check for integer overflow! + * + ****************************************************************************/ + +long long strtoll(const char *nptr, char **endptr, int base) +{ + unsigned long long accum = 0; + bool negate = false; + + if (nptr) + { + /* Skip leading spaces */ + + lib_skipspace(&nptr); + + /* Check for leading + or - */ + + if (*nptr == '-') + { + negate = true; + nptr++; + } + else if (*nptr == '+') + { + nptr++; + } + + /* Get the unsigned value */ + + accum = strtoull(nptr, endptr, base); + + /* Correct the sign of the result */ + + if (negate) + { + return -(long long)accum; + } + } + return (long long)accum; +} + +#endif + diff --git a/nuttx/lib/string/lib_strtoul.c b/nuttx/lib/string/lib_strtoul.c new file mode 100644 index 0000000000..b0d2d090e6 --- /dev/null +++ b/nuttx/lib/string/lib_strtoul.c @@ -0,0 +1,98 @@ +/**************************************************************************** + * /lib/string/lib_strtoul.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include "lib_internal.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: strtoul + * + * Description: + * The strtol() function converts the initial part of the string in + * nptr to a long unsigned integer value according to the given base, which + * must be between 2 and 36 inclusive, or be the special value 0. + * + * Warning: does not check for integer overflow! + * + ****************************************************************************/ + +unsigned long strtoul(const char *nptr, char **endptr, int base) +{ + unsigned long accum = 0; + int value; + + if (nptr) + { + /* Skip leading spaces */ + + lib_skipspace(&nptr); + + /* Check for unspecified base */ + + base = lib_checkbase(base, &nptr); + + /* Accumulate each "digit" */ + + while (lib_isbasedigit(*nptr, base, &value)) + { + accum = accum*base + value; + nptr++; + } + + /* Return the final pointer to the unused value */ + + if (endptr) + { + *endptr = (char *)nptr; + } + } + return accum; +} + diff --git a/nuttx/lib/string/lib_strtoull.c b/nuttx/lib/string/lib_strtoull.c new file mode 100644 index 0000000000..6567457c0e --- /dev/null +++ b/nuttx/lib/string/lib_strtoull.c @@ -0,0 +1,100 @@ +/**************************************************************************** + * /lib/string/lib_strtoull.c + * + * Copyright (C) 2009, 2010 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include + +#include "lib_internal.h" + +#ifdef CONFIG_HAVE_LONG_LONG + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: strtoull + * + * Description: + * The strtol() function converts the initial part of the string in + * nptr to a long unsigned integer value according to the given base, which + * must be between 2 and 36 inclusive, or be the special value 0. + * + ****************************************************************************/ + +unsigned long long strtoull(const char *nptr, char **endptr, int base) +{ + unsigned long long accum = 0; + int value; + + if (nptr) + { + /* Skip leading spaces */ + + lib_skipspace(&nptr); + + /* Check for unspecified base */ + + base = lib_checkbase(base, &nptr); + + /* Accumulate each "digit" */ + + while (lib_isbasedigit(*nptr, base, &value)) + { + accum = accum*base + value; + nptr++; + } + + /* Return the final pointer to the unused value */ + + if (endptr) + { + *endptr = (char *)nptr; + } + } + return accum; +} +#endif + diff --git a/nuttx/lib/termios/Make.defs b/nuttx/lib/termios/Make.defs new file mode 100644 index 0000000000..a6bb77f835 --- /dev/null +++ b/nuttx/lib/termios/Make.defs @@ -0,0 +1,54 @@ +############################################################################ +# lib/misc/Make.defs +# +# 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. +# +############################################################################ + +# termios.h support requires file descriptors and that CONFIG_SERIAL_TERMIOS +# is defined + +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) +ifeq ($(CONFIG_SERIAL_TERMIOS),y) + +# Add the termios C files to the build + +CSRCS += lib_cfgetspeed.c lib_cfsetspeed.c lib_tcflush.c +CSRCS += lib_tcgetattr.c lib_tcsetattr.c + +# Add the termios directory to the build + +DEPPATH += --dep-path termios +VPATH += termios + +endif +endif + diff --git a/nuttx/lib/termios/lib_cfgetspeed.c b/nuttx/lib/termios/lib_cfgetspeed.c new file mode 100644 index 0000000000..d7f0dc4736 --- /dev/null +++ b/nuttx/lib/termios/lib_cfgetspeed.c @@ -0,0 +1,93 @@ +/**************************************************************************** + * lib/termios/lib_cfgetspeed.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cfgetspeed + * + * Descripton: + * The cfgetspeed() function is a non-POSIX function will extract the baud + * from the termios structure to which the termiosp argument points. + * + * This function will return exactly the value in the termios data + * structure, without interpretation. + * + * NOTE 1: NuttX does not control input/output baud independently. Both + * must be the same. The POSIX standard interfaces, cfisetispeed() and + * cfisetospeed() are defined to be cfgetspeed() in termios.h. + * NOTE 2. In Nuttx, the speed_t is defined to be uint32_t and the baud + * encodings of termios.h are the actual baud values themselves. Therefore, + * any baud value may be returned here... not just those enumerated in + * termios.h + * + * Input Parameters: + * termiosp - The termiosp argument is a pointer to a termios structure. + * + * Returned Value: + * Encoded baud value from the termios structure. + * + ****************************************************************************/ + +speed_t cfgetspeed(FAR const struct termios *termiosp) +{ + DEBUGASSERT(termiosp); + return termiosp->c_speed; +} diff --git a/nuttx/lib/termios/lib_cfsetspeed.c b/nuttx/lib/termios/lib_cfsetspeed.c new file mode 100644 index 0000000000..bf9e660640 --- /dev/null +++ b/nuttx/lib/termios/lib_cfsetspeed.c @@ -0,0 +1,121 @@ +/**************************************************************************** + * lib/termios/lib_cfsetspeed.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cfsetspeed + * + * Descripton: + * The cfsetspeed() function is a non-POSIX function that sets the baud + * stored in the structure pointed to by termiosp to speed. + * + * There is no effect on the baud set in the hardware until a subsequent + * successful call to tcsetattr() on the same termios structure. + * + * NOTE 1: NuttX does not control input/output baud independently. Both + * must be the same. The POSIX standard interfaces, cfisetispeed() and + * cfisetospeed() are defined to be cfsetspeed() in termios.h. + * + * NOTE 3: A consequence of NOTE 1 is that you should never attempt to + * set the input and output baud to different values. + * + * Also, the following POSIX requirement cannot be supported: "If the input + * baud rate stored in the termios structure pointed to by termios_p is 0, + * the input baud rate given to the hardware will be the same as the output + * baud rate stored in the termios structure." + * + * NOTE 2. In Nuttx, the speed_t is defined to be uint32_t and the baud + * encodings of termios.h are the actual baud values themselves. Therefore, + * any baud value can be provided as the speed argument here. However, if + * you do so, your code will *NOT* be portable to other environments where + * speed_t is smaller and where the termios.h baud values are encoded! To + * avoid portability issues, use the baud definitions in termios.h! + * + * Linux, for example, would require this (also non-portable) sequence: + * + * cfsetispeed(termiosp, BOTHER); + * termiosp->c_ispeed = baud; + * + * cfsetospeed(termiosp, BOTHER); + * termiosp->c_ospeed = baud; + * + * Input Parameters: + * termiosp - The termiosp argument is a pointer to a termios structure. + * speed - The new input speed + * + * Returned Value: + * Baud is not checked... OK is always returned (this is non-standard + * behavior). + * + ****************************************************************************/ + +int cfsetspeed(FAR struct termios *termiosp, speed_t speed) +{ + FAR speed_t *speedp; + + DEBUGASSERT(termiosp); + + speedp = (FAR speed_t *)&termiosp->c_speed; + *speedp = speed; + + return OK; +} diff --git a/nuttx/lib/termios/lib_tcflush.c b/nuttx/lib/termios/lib_tcflush.c new file mode 100644 index 0000000000..338524bdda --- /dev/null +++ b/nuttx/lib/termios/lib_tcflush.c @@ -0,0 +1,88 @@ +/**************************************************************************** + * lib/termios/lib_tcflush.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: tcflush + * + * Descripton: + * Function for flushing a terminal/serial device + * + * Input Parameters: + * fd - The 'fd' argument is an open file descriptor associated with a terminal. + * cmd - The TCFLSH ioctl argument. + * + * Returned Value: + * Upon successful completion, 0 is returned. Otherwise, -1 is returned and + * errno is set to indicate the error. + * + ****************************************************************************/ + +int tcflush(int fd, int cmd) +{ + return ioctl(fd, TCFLSH, (unsigned long)cmd); +} diff --git a/nuttx/lib/termios/lib_tcgetattr.c b/nuttx/lib/termios/lib_tcgetattr.c new file mode 100644 index 0000000000..500871d9ff --- /dev/null +++ b/nuttx/lib/termios/lib_tcgetattr.c @@ -0,0 +1,93 @@ +/**************************************************************************** + * lib/termios/lib_tcgetattr.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: tcgetattr + * + * Descripton: + * The tcgetattr() function gets the parameters associated with the + * terminal referred to by 'fd' and stores them in the termios structure + * referenced by 'termiosp'. + * + * Input Parameters: + * fd - The 'fd' argument is an open file descriptor associated with a terminal. + * termiosp - The termiosp argument is a pointer to a termios structure. + * + * Returned Value: + * Upon successful completion, 0 is returned. Otherwise, -1 is returned and + * errno is set to indicate the error. The following errors may be reported: + * + * - EBADF: The 'fd' argument is not a valid file descriptor. + * - ENOTTY: The file associated with 'fd' is not a terminal. + * + ****************************************************************************/ + +int tcgetattr(int fd, FAR struct termios *termiosp) +{ + return ioctl(fd, TCGETS, (unsigned long)termiosp); +} diff --git a/nuttx/lib/termios/lib_tcsetattr.c b/nuttx/lib/termios/lib_tcsetattr.c new file mode 100644 index 0000000000..791b519c85 --- /dev/null +++ b/nuttx/lib/termios/lib_tcsetattr.c @@ -0,0 +1,122 @@ +/**************************************************************************** + * lib/termios/lib_tcsetattr.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: tcsetattr + * + * Descripton: + * The tcsetattr() function sets the parameters associated with the + * terminal referred to by the open file descriptor 'fd' from the termios + * structure referenced by 'termiop' as follows: + * + * If 'options' is TCSANOW, the change will occur immediately. + * + * If 'options' is TCSADRAIN, the change will occur after all output + * written to 'fd' is transmitted. This function should be used when changing + * parameters that affect output. + * + * If 'options' is TCSAFLUSH, the change will occur after all + * output written to 'fd' is transmitted, and all input so far received but + * not read will be discarded before the change is made. + * + * The tcsetattr() function will return successfully if it was able to + * perform any of the requested actions, even if some of the requested + * actions could not be performed. It will set all the attributes that + * implementation supports as requested and leave all the attributes not + * supported by the implementation unchanged. If no part of the request + * can be honoured, it will return -1 and set errno to EINVAL. + * + * The effect of tcsetattr() is undefined if the value of the termios + * structure pointed to by 'termiop' was not derived from the result of + * a call to tcgetattr() on 'fd'; an application should modify only fields + * and flags defined by this specification between the call to tcgetattr() + * and tcsetattr(), leaving all other fields and flags unmodified. + * + * Returned Value: + * + * Upon successful completion, 0 is returned. Otherwise, -1 is returned + * and errno is set to indicate the error. The following errors may be + * reported: + * + * - EBADF: The 'fd' argument is not a valid file descriptor. + * - EINTR: A signal interrupted tcsetattr(). + * - EINVAL: The 'options' argument is not a supported value, or + * an attempt was made to change an attribute represented in the + * termios structure to an unsupported value. + * - ENOTTY: The file associated with 'fd' is not a terminal. + * + ****************************************************************************/ + +int tcsetattr(int fd, int options, FAR const struct termios *termiosp) +{ + if (options == TCSANOW) + { + return ioctl(fd, TCSETS, (unsigned long)termiosp); + } + return -ENOSYS; +} diff --git a/nuttx/lib/time/Make.defs b/nuttx/lib/time/Make.defs new file mode 100644 index 0000000000..ab74142291 --- /dev/null +++ b/nuttx/lib/time/Make.defs @@ -0,0 +1,44 @@ +############################################################################ +# lib/time/Make.defs +# +# 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. +# +############################################################################ + +# Add the time C files to the build + +CSRCS += lib_mktime.c lib_gmtime.c lib_gmtimer.c lib_strftime.c \ + lib_calendar2utc.c lib_daysbeforemonth.c lib_isleapyear.c lib_time.c + +# Add the time directory to the build + +DEPPATH += --dep-path time +VPATH += :time diff --git a/nuttx/lib/time/lib_calendar2utc.c b/nuttx/lib/time/lib_calendar2utc.c new file mode 100644 index 0000000000..e80c292fc6 --- /dev/null +++ b/nuttx/lib/time/lib_calendar2utc.c @@ -0,0 +1,209 @@ +/**************************************************************************** + * lib/time/lib_calendar2utc.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: clock_gregorian2utc, clock_julian2utc + * + * Description: + * UTC conversion routines. These conversions are based + * on algorithms from p. 604 of Seidelman, P. K. 1992. + * Explanatory Supplement to the Astronomical Almanac. + * University Science Books, Mill Valley. + * + ****************************************************************************/ + +#ifdef CONFIG_GREGORIAN_TIME +static time_t clock_gregorian2utc(int year, int month, int day) +{ + int temp; + + /* temp = (month - 14)/12; */ + + temp = (month <= 2 ? -1:0); + + return (1461*(year + 4800 + temp))/4 + + (367*(month - 2 - 12*temp))/12 + - (3*((year + 4900 + temp)/100))/4 + day - 32075; +} + +#ifdef CONFIG_JULIAN_TIME +static time_t clock_julian2utc(int year, int month, int day) +{ + return 367*year + - (7*(year + 5001 + (month-9)/7))/4 + + (275*month)/9 + + day + 1729777; +} +#endif /* CONFIG_JULIAN_TIME */ +#endif /* CONFIG_GREGORIAN_TIME */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: clock_calendar2utc + * + * Description: + * Calendar/UTC conversion based on algorithms from p. 604 + * of Seidelman, P. K. 1992. Explanatory Supplement to + * the Astronomical Almanac. University Science Books, + * Mill Valley. + * + ****************************************************************************/ + +#ifdef CONFIG_GREGORIAN_TIME +time_t clock_calendar2utc(int year, int month, int day) +{ + int dyear; +#ifdef CONFIG_JULIAN_TIME + bool isgreg; +#endif /* CONFIG_JULIAN_TIME */ + + /* Correct year & month ranges. Shift month into range 1-12 */ + + dyear = (month-1) / 12; + month -= 12 * dyear; + year += dyear; + + if (month < 1) + { + month += 12; + year -= 1; + } + +#ifdef CONFIG_JULIAN_TIME + /* Determine which calendar to use */ + + if (year > GREG_YEAR) + { + isgreg = true; + } + else if (year < GREG_YEAR) + { + isgreg = false; + } + else if (month > GREG_MONTH) + { + isgreg = true; + } + else if (month < GREG_MONTH) + { + isgreg = false; + } + else + { + isgreg = (day >= GREG_DAY); + } + + /* Calculate and return date */ + + if (isgreg) + { + return clock_gregorian2utc(year, month, day) - JD_OF_EPOCH; + } + else + { + return clock_julian2utc (year, month, day) - JD_OF_EPOCH; + } + +#else /* CONFIG_JULIAN_TIME */ + + return clock_gregorian2utc(year, month, day) - JD_OF_EPOCH; + +#endif /* CONFIG_JULIAN_TIME */ +} +#else + +/* A highly simplified version that only handles days in the time + * since Jan 1, 1970. + */ + +time_t clock_calendar2utc(int year, int month, int day) +{ + struct tm t; + + /* mktime can (kind of) do this */ + + t.tm_year = year; + t.tm_mon = month; + t.tm_mday = day; + t.tm_hour = 0; + t.tm_min = 0; + t.tm_sec = 0; + return mktime(&t); +} +#endif /* CONFIG_GREGORIAN_TIME */ + diff --git a/nuttx/lib/time/lib_daysbeforemonth.c b/nuttx/lib/time/lib_daysbeforemonth.c new file mode 100644 index 0000000000..8000b0e7a9 --- /dev/null +++ b/nuttx/lib/time/lib_daysbeforemonth.c @@ -0,0 +1,102 @@ +/**************************************************************************** + * lib/time/lib_daysbeforemonth.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +uint16_t g_daysbeforemonth[13] = +{ + 0, 31, 59, 90, 120, 151, 181, 212, 243, 273, 304, 334, 365 +}; + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: clock_daysbeforemonth + * + * Description: + * Get the number of days that occurred before the beginning of the month. + * + ****************************************************************************/ + +int clock_daysbeforemonth(int month, bool leapyear) +{ + int retval = g_daysbeforemonth[month]; + if (month >= 2 && leapyear) + { + retval++; + } + return retval; +} + + diff --git a/nuttx/lib/time/lib_gmtime.c b/nuttx/lib/time/lib_gmtime.c new file mode 100644 index 0000000000..99afeded9e --- /dev/null +++ b/nuttx/lib/time/lib_gmtime.c @@ -0,0 +1,93 @@ +/**************************************************************************** + * lib/time/lib_gmtime.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/************************************************************************** + * Public Constant Data + **************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/************************************************************************** + * Private Variables + **************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: gmtime + * + * Description: + * Similar to gmtime_r, but not thread-safe + * + ****************************************************************************/ + +struct tm *gmtime(const time_t *timer) +{ + static struct tm tm; + return gmtime_r(timer, &tm); +} + diff --git a/nuttx/lib/time/lib_gmtimer.c b/nuttx/lib/time/lib_gmtimer.c new file mode 100644 index 0000000000..ba1c9724f1 --- /dev/null +++ b/nuttx/lib/time/lib_gmtimer.c @@ -0,0 +1,355 @@ +/**************************************************************************** + * lib/time/lib_gmtimer.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define SEC_PER_MIN ((time_t)60) +#define SEC_PER_HOUR ((time_t)60 * SEC_PER_MIN) +#define SEC_PER_DAY ((time_t)24 * SEC_PER_HOUR) + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Calendar/UTC conversion routines */ + +static void clock_utc2calendar(time_t utc, int *year, int *month, int *day); +#ifdef CONFIG_GREGORIAN_TIME +static void clock_utc2gregorian (time_t jdn, int *year, int *month, int *day); + +#ifdef CONFIG_JULIAN_TIME +static void clock_utc2julian(time_t jdn, int *year, int *month, int *day); +#endif /* CONFIG_JULIAN_TIME */ +#endif /* CONFIG_GREGORIAN_TIME */ + +/************************************************************************** + * Public Constant Data + **************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/************************************************************************** + * Private Variables + **************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: clock_calendar2utc, clock_gregorian2utc, + * and clock_julian2utc + * + * Description: + * Calendar to UTC conversion routines. These conversions + * are based on algorithms from p. 604 of Seidelman, P. K. + * 1992. Explanatory Supplement to the Astronomical + * Almanac. University Science Books, Mill Valley. + * + ****************************************************************************/ + +#ifdef CONFIG_GREGORIAN_TIME +static void clock_utc2calendar(time_t utc, int *year, int *month, int *day) +{ +#ifdef CONFIG_JULIAN_TIME + + if (utc >= GREG_DUTC) + { + clock_utc2gregorian(utc + JD_OF_EPOCH, year, month, day); + } + else + { + clock_utc2julian (utc + JD_OF_EPOCH, year, month, day); + } + +#else /* CONFIG_JULIAN_TIME */ + + clock_utc2gregorian(utc + JD_OF_EPOCH, year, month, day); + +#endif /* CONFIG_JULIAN_TIME */ +} + +static void clock_utc2gregorian(time_t jd, int *year, int *month, int *day) +{ + long l, n, i, j, d, m, y; + + l = jd + 68569; + n = (4*l) / 146097; + l = l - (146097*n + 3)/4; + i = (4000*(l+1))/1461001; + l = l - (1461*i)/4 + 31; + j = (80*l)/2447; + d = l - (2447*j)/80; + l = j/11; + m = j + 2 - 12*l; + y = 100*(n-49) + i + l; + + *year = y; + *month = m; + *day = d; +} + +#ifdef CONFIG_JULIAN_TIME + +static void clock_utc2julian(time_t jd, int *year, int *month, int *day) +{ + long j, k, l, n, d, i, m, y; + + j = jd + 1402; + k = (j-1)/1461; + l = j - 1461*k; + n = (l-1)/365 - l/1461; + i = l - 365*n + 30; + j = (80*i)/2447; + d = i - (2447*j)/80; + i = j/11; + m = j + 2 - 12*i; + y = 4*k + n + i - 4716; + + *year = y; + *month = m; + *day = d; +} + +#endif /* CONFIG_JULIAN_TIME */ +#else/* CONFIG_GREGORIAN_TIME */ + +/* Only handles dates since Jan 1, 1970 */ + +static void clock_utc2calendar(time_t days, int *year, int *month, int *day) +{ + int value; + int min; + int max; + int tmp; + bool leapyear; + + /* There is one leap year every four years, so we can get close with the + * following: + */ + + value = days / (4*365 + 1); /* Number of 4-years periods since the epoch*/ + days -= value * (4*365 + 1); /* Remaining days */ + value <<= 2; /* Years since the epoch */ + + /* Then we will brute force the next 0-3 years */ + + for (;;) + { + /* Is this year a leap year (we'll need this later too) */ + + leapyear = clock_isleapyear(value + 1970); + + /* Get the number of days in the year */ + + tmp = (leapyear ? 366 : 365); + + /* Do we have that many days? */ + + if (days >= tmp) + { + /* Yes.. bump up the year */ + + value++; + days -= tmp; + } + else + { + /* Nope... then go handle months */ + + break; + } + } + + /* At this point, value has the year and days has number days into this year */ + + *year = 1970 + value; + + /* Handle the month (zero based) */ + + min = 0; + max = 11; + + do + { + /* Get the midpoint */ + + value = (min + max) >> 1; + + /* Get the number of days that occurred before the beginning of the month + * following the midpoint. + */ + + tmp = clock_daysbeforemonth(value + 1, leapyear); + + /* Does the number of days before this month that equal or exceed the + * number of days we have remaining? + */ + + if (tmp > days) + { + /* Yes.. then the month we want is somewhere from 'min' and to the + * midpoint, 'value'. Could it be the midpoint? + */ + + tmp = clock_daysbeforemonth(value, leapyear); + if (tmp > days) + { + /* No... The one we want is somewhere between min and value-1 */ + + max = value - 1; + } + else + { + /* Yes.. 'value' contains the month that we want */ + + break; + } + } + else + { + /* No... The one we want is somwhere between value+1 and max */ + + min = value + 1; + } + + /* If we break out of the loop because min == max, then we want value + * to be equal to min == max. + */ + + value = min; + } + while (min < max); + + /* The selected month number is in value. Subtract the number of days in the + * selected month + */ + + days -= clock_daysbeforemonth(value, leapyear); + + /* At this point, value has the month into this year (zero based) and days has + * number of days into this month (zero based) + */ + + *month = value + 1; /* 1-based */ + *day = days + 1; /* 1-based */ +} + +#endif /* CONFIG_GREGORIAN_TIME */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: gmtime_r + * + * Description: + * Time conversion (based on the POSIX API) + * + ****************************************************************************/ + +FAR struct tm *gmtime_r(FAR const time_t *timer, FAR struct tm *result) +{ + time_t epoch; + time_t jdn; + int year; + int month; + int day; + int hour; + int min; + int sec; + + /* Get the seconds since the EPOCH */ + + epoch = *timer; + sdbg("timer=%d\n", (int)epoch); + + /* Convert to days, hours, minutes, and seconds since the EPOCH */ + + jdn = epoch / SEC_PER_DAY; + epoch -= SEC_PER_DAY * jdn; + + hour = epoch / SEC_PER_HOUR; + epoch -= SEC_PER_HOUR * hour; + + min = epoch / SEC_PER_MIN; + epoch -= SEC_PER_MIN * min; + + sec = epoch; + + sdbg("hour=%d min=%d sec=%d\n", + (int)hour, (int)min, (int)sec); + + /* Convert the days since the EPOCH to calendar day */ + + clock_utc2calendar(jdn, &year, &month, &day); + + sdbg("jdn=%d year=%d month=%d day=%d\n", + (int)jdn, (int)year, (int)month, (int)day); + + /* Then return the struct tm contents */ + + result->tm_year = (int)year - 1900; /* Relative to 1900 */ + result->tm_mon = (int)month - 1; /* zero-based */ + result->tm_mday = (int)day; /* one-based */ + result->tm_hour = (int)hour; + result->tm_min = (int)min; + result->tm_sec = (int)sec; + + return result; +} + diff --git a/nuttx/lib/time/lib_isleapyear.c b/nuttx/lib/time/lib_isleapyear.c new file mode 100644 index 0000000000..966c248e01 --- /dev/null +++ b/nuttx/lib/time/lib_isleapyear.c @@ -0,0 +1,88 @@ +/**************************************************************************** + * lib/time/lib_isleapyear.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: clock_isleapyear + * + * Description: + * Return true if the specified year is a leap year + * + ****************************************************************************/ + +int clock_isleapyear(int year) +{ + return year % 400 ? (year % 100 ? (year % 4 ? 0 : 1) : 0) : 1; +} + diff --git a/nuttx/lib/time/lib_mktime.c b/nuttx/lib/time/lib_mktime.c new file mode 100644 index 0000000000..8c17e7c0ab --- /dev/null +++ b/nuttx/lib/time/lib_mktime.c @@ -0,0 +1,141 @@ +/**************************************************************************** + * lib/time/lib_mktime.c + * + * Copyright (C) 2007, 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: mktime + * + * Description: + * Time conversion (based on the POSIX API) + * + ****************************************************************************/ + +#ifdef CONFIG_GREGORIAN_TIME +time_t mktime(const struct tm *tp) +{ + time_t ret; + time_t jdn; + + /* Get the EPOCH-relative julian date from the calendar year, + * month, and date + */ + + jdn = clock_calendar2utc(tp->tm_year+1900, tp->tm_mon+1, tp->tm_mday); + sdbg("jdn=%d tm_year=%d tm_mon=%d tm_mday=%d\n", + (int)jdn, tp->tm_year, tp->tm_mon, tp->tm_mday); + + /* Return the seconds into the julian day. */ + + ret = ((jdn*24 + tp->tm_hour)*60 + tp->tm_min)*60 + tp->tm_sec; + sdbg("ret=%d tm_hour=%d tm_min=%d tm_sec=%d\n", + (int)ret, tp->tm_hour, tp->tm_min, tp->tm_sec); + + return ret; +} +#else + +/* Simple version that only works for dates within a (relatively) small range + * from the epoch. It does not handle earlier days or longer days where leap + * seconds, etc. apply. + */ + +time_t mktime(const struct tm *tp) +{ + unsigned int days; + + /* Years since epoch in units of days (ignoring leap years). */ + + days = (tp->tm_year - 70) * 365; + + /* Add in the extra days for the leap years prior to the current year. */ + + days += (tp->tm_year - 69) >> 2; + + /* Add in the days up to the beginning of this month. */ + + days += (time_t)clock_daysbeforemonth(tp->tm_mon, clock_isleapyear(tp->tm_year + 1900)); + + /* Add in the days since the beginning of this month (days are 1-based). */ + + days += tp->tm_mday - 1; + + /* Then convert the seconds and add in hours, minutes, and seconds */ + + return ((days * 24 + tp->tm_hour) * 60 + tp->tm_min) * 60 + tp->tm_sec; +} +#endif /* CONFIG_GREGORIAN_TIME */ + diff --git a/nuttx/lib/time/lib_strftime.c b/nuttx/lib/time/lib_strftime.c new file mode 100644 index 0000000000..cd0804f55d --- /dev/null +++ b/nuttx/lib/time/lib_strftime.c @@ -0,0 +1,398 @@ +/**************************************************************************** + * lib/time/lib_strftime.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const char * const g_abbrevmonthname[12] = +{ + "Jan", "Feb", "Mar", "Apr", "May", "Jun", + "Jul", "Aug", "Sep", "Oct", "Nov", "Dec" +}; + +static const char * const g_monthname[12] = +{ + "January", "February", "March", "April", "May", "June", + "July", "August", "September", "October", "November", "December" +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: strftime + * + * Description: + * The strftime() function formats the broken-down time tm according to + * the format specification format and places the result in the character + * array s of size max. + * + * Ordinary characters placed in the format string are copied to s without + * conversion. Conversion specifications are introduced by a '%' charac- + * ter, and terminated by a conversion specifier character, and are + * replaced in s as follows: + * + * %b The abbreviated month name according to the current locale. + * %B The full month name according to the current locale. + * %C The century number (year/100) as a 2-digit integer. (SU) + * %d The day of the month as a decimal number (range 01 to 31). + * %e Like %d, the day of the month as a decimal number, but a leading + * zero is replaced by a space. + * %h Equivalent to %b. (SU) + * %H The hour as a decimal number using a 24-hour clock (range 00 to 23). + * %I The hour as a decimal number using a 12-hour clock (range 01 to 12). + * %j The day of the year as a decimal number (range 001 to 366). + * %k The hour (24-hour clock) as a decimal number (range 0 to 23); + * single digits are preceded by a blank. (See also %H.) (TZ) + * %l The hour (12-hour clock) as a decimal number (range 1 to 12); + * single digits are preceded by a blank. (See also %I.) (TZ) + * %m The month as a decimal number (range 01 to 12). + * %M The minute as a decimal number (range 00 to 59). + * %n A newline character. (SU) + * %p Either "AM" or "PM" according to the given time value, or the + * corresponding strings for the current locale. Noon is treated + * as "PM" and midnight as "AM". + * %P Like %p but in lowercase: "am" or "pm" or a corresponding string + * for the current locale. (GNU) + * %s The number of seconds since the Epoch, that is, since 1970-01-01 + * 00:00:00 UTC. (TZ) + * %S The second as a decimal number (range 00 to 60). (The range is + * up to 60 to allow for occasional leap seconds.) + * %t A tab character. (SU) + * %y The year as a decimal number without a century (range 00 to 99). + * %Y The year as a decimal number including the century. + * %% A literal '%' character. + * + * Returned Value: + * The strftime() function returns the number of characters placed in the + * array s, not including the terminating null byte, provided the string, + * including the terminating null byte, fits. Otherwise, it returns 0, + * and the contents of the array is undefined. + * + ****************************************************************************/ + +size_t strftime(char *s, size_t max, const char *format, const struct tm *tm) +{ + const char *str; + char *dest = s; + int chleft = max; + int value; + int len; + + while (*format && chleft > 0) + { + /* Just copy regular characters */ + + if (*format != '%') + { + *dest++ = *format++; + chleft--; + continue; + } + + /* Handle the format character */ + + format++; + len = 0; + + switch (*format++) + { + /* %a: A three-letter abbreviation for the day of the week. */ + /* %A: The full name for the day of the week. */ + + case 'a': + case 'A': + { + len = snprintf(dest, chleft, "Day"); /* Not supported */ + } + break; + + /* %h: Equivalent to %b */ + + case 'h': + + /* %b: The abbreviated month name according to the current locale. */ + + case 'b': + { + if (tm->tm_mon < 12) + { + str = g_abbrevmonthname[tm->tm_mon]; + len = snprintf(dest, chleft, "%s", str); + } + } + break; + + /* %B: The full month name according to the current locale. */ + + case 'B': + { + if (tm->tm_mon < 12) + { + str = g_monthname[tm->tm_mon]; + len = snprintf(dest, chleft, "%s", str); + } + } + break; + + /* %y: The year as a decimal number without a century (range 00 to 99). */ + + case 'y': + + /* %C: The century number (year/100) as a 2-digit integer. */ + + case 'C': + { + len = snprintf(dest, chleft, "%02d", tm->tm_year % 100); + } + break; + + /* %d: The day of the month as a decimal number (range 01 to 31). */ + + case 'd': + { + len = snprintf(dest, chleft, "%02d", tm->tm_mday); + } + break; + + /* %e: Like %d, the day of the month as a decimal number, but a leading + * zero is replaced by a space. + */ + + case 'e': + { + len = snprintf(dest, chleft, "%2d", tm->tm_mday); + } + break; + + /* %H: The hour as a decimal number using a 24-hour clock (range 00 to 23). */ + + case 'H': + { + len = snprintf(dest, chleft, "%02d", tm->tm_hour); + } + break; + + /* %I: The hour as a decimal number using a 12-hour clock (range 01 to 12). */ + + case 'I': + { + len = snprintf(dest, chleft, "%02d", tm->tm_hour % 12); + } + break; + + /* %j: The day of the year as a decimal number (range 001 to 366). */ + + case 'j': + { + if (tm->tm_mon < 12) + { + value = clock_daysbeforemonth(tm->tm_mon, clock_isleapyear(tm->tm_year)) + tm->tm_mday; + len = snprintf(dest, chleft, "%03d", value); + } + } + break; + + /* %k: The hour (24-hour clock) as a decimal number (range 0 to 23); + * single digits are preceded by a blank. + */ + + case 'k': + { + len = snprintf(dest, chleft, "%2d", tm->tm_hour); + } + break; + + /* %l: The hour (12-hour clock) as a decimal number (range 1 to 12); + * single digits are preceded by a blank. + */ + + case 'l': + { + len = snprintf(dest, chleft, "%2d", tm->tm_hour % 12); + } + break; + + /* %m: The month as a decimal number (range 01 to 12). */ + + case 'm': + { + len = snprintf(dest, chleft, "%02d", tm->tm_mon + 1); + } + break; + + /* %M: The minute as a decimal number (range 00 to 59). */ + + case 'M': + { + len = snprintf(dest, chleft, "%02d", tm->tm_min); + } + break; + + /* %n: A newline character. */ + + case 'n': + { + *dest = '\n'; + len = 1; + } + break; + + /* %p: Either "AM" or "PM" according to the given time value. */ + + case 'p': + { + if (tm->tm_hour >= 12) + { + str = "PM"; + } + else + { + str = "AM"; + } + len = snprintf(dest, chleft, "%s", str); + } + break; + + /* %P: Like %p but in lowercase: "am" or "pm" */ + + case 'P': + { + if (tm->tm_hour >= 12) + { + str = "pm"; + } + else + { + str = "am"; + } + len = snprintf(dest, chleft, "%s", str); + } + break; + + /* %s: The number of seconds since the Epoch, that is, since 1970-01-01 + * 00:00:00 UTC. + */ + + case 's': + { + len = snprintf(dest, chleft, "%d", mktime(tm)); + } + break; + + /* %S: The second as a decimal number (range 00 to 60). (The range is + * up to 60 to allow for occasional leap seconds.) + */ + + case 'S': + { + len = snprintf(dest, chleft, "%02d", tm->tm_sec); + } + break; + + /* %t: A tab character. */ + + case 't': + { + *dest = '\t'; + len = 1; + } + break; + + /* %Y: The year as a decimal number including the century. */ + + case 'Y': + { + len = snprintf(dest, chleft, "%04d", tm->tm_year + 1900); + } + break; + + /* %%: A literal '%' character. */ + + case '%': + { + *dest = '%'; + len = 1; + } + break; + } + + /* Update counts and pointers */ + + dest += len; + chleft -= len; + } + + return max - chleft; +} diff --git a/nuttx/lib/time/lib_time.c b/nuttx/lib/time/lib_time.c new file mode 100644 index 0000000000..106a04c366 --- /dev/null +++ b/nuttx/lib/time/lib_time.c @@ -0,0 +1,110 @@ +/**************************************************************************** + * lib/time/lib_time.c + * + * Copyright (C) 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#ifndef CONFIG_DISABLE_CLOCK + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: time + * + * Description: + * Get the current calendar time as a time_t object. The function returns + * this value, and if the argument is not a null pointer, the value is also + * set to the object pointed by tloc. + * + * Note that this function is just a thin wrapper around gettimeofday() + * and is provided for compatibility. gettimeofday() is the preffered way + * to obtain system time. + * + * Parameters: + * Pointer to an object of type time_t, where the time value is stored. + * Alternativelly, this parameter can be a null pointer, in which case the + * parameter is not used, but a time_t object is still returned by the + * function. + * + * Return Value: + * The current calendar time as a time_t object. If the argument is not + * a null pointer, the return value is the same as the one stored in the + * location pointed by the argument. + * + * If the function could not retrieve the calendar time, it returns a -1 + * value. + * + ****************************************************************************/ + +time_t time(time_t *tloc) +{ + struct timeval tp; + int ret; + + /* Get the current time from the system */ + + ret = gettimeofday(&tp, NULL); + if (ret == OK) + { + /* Return the seconds since the epoch */ + + if (tloc) + { + *tloc = tp.tv_sec; + } + + return tp.tv_sec; + } + + return (time_t)ERROR; +} + +#endif /* !CONFIG_DISABLE_CLOCK */ diff --git a/nuttx/lib/unistd/Make.defs b/nuttx/lib/unistd/Make.defs new file mode 100644 index 0000000000..e1441a48d3 --- /dev/null +++ b/nuttx/lib/unistd/Make.defs @@ -0,0 +1,49 @@ +############################################################################ +# lib/unistd/Make.defs +# +# 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. +# +############################################################################ + +# Add the unistd C files to the build + +CSRCS += lib_getopt.c lib_getoptargp.c lib_getoptindp.c lib_getoptoptp.c + +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) +ifneq ($(CONFIG_DISABLE_ENVIRON),y) +CSRCS += lib_chdir.c lib_getcwd.c +endif +endif + +# Add the unistd directory to the build + +DEPPATH += --dep-path unistd +VPATH += :unistd diff --git a/nuttx/lib/unistd/lib_chdir.c b/nuttx/lib/unistd/lib_chdir.c new file mode 100644 index 0000000000..3dd1333cec --- /dev/null +++ b/nuttx/lib/unistd/lib_chdir.c @@ -0,0 +1,179 @@ +/**************************************************************************** + * lib/unistd/lib_chdir.c + * + * Copyright (C) 2008-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON) + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: _trimdir + ****************************************************************************/ + +#if 0 +static inline void _trimdir(char *path) +{ + /* Skip any trailing '/' characters (unless it is also the leading '/') */ + + int len = strlen(path) - 1; + while (len > 0 && path[len] == '/') + { + path[len] = '\0'; + len--; + } +} +#else +# define _trimdir(p) +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: chdir + * + * Description: + * The chdir() function causes the directory named by the pathname pointed + * to by the 'path' argument to become the current working directory; that + * is, the starting point for path searches for pathnames not beginning + * with '/'. + * + * Input Parmeters: + * path - A pointer to a directory to use as the new current working + * directory + * + * Returned Value: + * 0(OK) on success; -1(ERROR) on failure with errno set appropriately: + * + * EACCES + * Search permission is denied for any component of the pathname. + * ELOOP + * A loop exists in symbolic links encountered during resolution of the + * 'path' argument OR more that SYMLOOP_MAX symbolic links in the + * resolution of the 'path' argument. + * ENAMETOOLONG + * The length of the path argument exceeds PATH_MAX or a pathname component + * is longer than NAME_MAX. + * ENOENT + * A component of 'path' does not name an existing directory or path is + * an empty string. + * ENOTDIR + * A component of the pathname is not a directory. + * + ****************************************************************************/ + +int chdir(FAR const char *path) +{ + struct stat buf; + char *oldpwd; + char *alloc; + int err; + int ret; + + /* Verify the input parameters */ + + if (!path) + { + err = ENOENT; + goto errout; + } + + /* Verify that 'path' refers to a directory */ + + ret = stat(path, &buf); + if (ret != 0) + { + err = ENOENT; + goto errout; + } + + /* Something exists here... is it a directory? */ + + if (!S_ISDIR(buf.st_mode)) + { + err = ENOTDIR; + goto errout; + } + + /* Yes, it is a directory. Remove any trailing '/' characters from the path */ + + _trimdir(path); + + /* Replace any preceding OLDPWD with the current PWD (this is to + * support 'cd -' in NSH) + */ + + sched_lock(); + oldpwd = getenv("PWD"); + if (!oldpwd) + { + oldpwd = CONFIG_LIB_HOMEDIR; + } + + alloc = strdup(oldpwd); /* kludge needed because environment is realloc'ed */ + setenv("OLDPWD", alloc, TRUE); + lib_free(alloc); + + /* Set the cwd to the input 'path' */ + + setenv("PWD", path, TRUE); + sched_unlock(); + return OK; + +errout: + set_errno(err); + return ERROR; +} +#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/lib/unistd/lib_getcwd.c b/nuttx/lib/unistd/lib_getcwd.c new file mode 100644 index 0000000000..b94823300b --- /dev/null +++ b/nuttx/lib/unistd/lib_getcwd.c @@ -0,0 +1,132 @@ +/**************************************************************************** + * lib/unistd/lib_getcwd.c + * + * Copyright (C) 2008, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include "lib_internal.h" + +#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON) + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: getwcd + * + * Description: + * getcwd() function places the absolute pathname of the current working + * directory in the array pointed to by 'buf', and returns 'buf.' The + * pathname copied to the array shall contain no components that are + * symbolic links. The 'size' argument is the size in bytes of the + * character array pointed to by the 'buf' argument. + * + * Input Parmeters: + * buf - a pointer to the location in which the current working directory + * pathaname is returned. + * size - The size in bytes avaiable at 'buf' + * + * Returned Value: + * Upon successful completion, getcwd() returns the 'buf' argument. + * Otherwise, getcwd() returns a null pointer and sets errno to indicate + * the error: + * + * EINVAL + * The 'size' argument is 0 or the 'buf' argument is NULL. + * ERANGE + * The size argument is greater than 0, but is smaller than the length + * of the currrent working directory pathname +1. + * EACCES + * Read or search permission was denied for a component of the pathname. + * ENOMEM + * Insufficient storage space is available. + * + ****************************************************************************/ + +FAR char *getcwd(FAR char *buf, size_t size) +{ + char *pwd; + + /* Verify input parameters */ + +#ifdef CONFIG_DEBUG + if (!buf || !size) + { + set_errno(EINVAL); + return NULL; + } +#endif + + /* If no working directory is defined, then default to the home directory */ + + pwd = getenv("PWD"); + if (!pwd) + { + pwd = CONFIG_LIB_HOMEDIR; + } + + /* Verify that the cwd will fit into the user-provided buffer */ + + if (strlen(pwd) + 1 > size) + { + set_errno(ERANGE); + return NULL; + } + + /* Copy the cwd to the user buffer */ + + strcpy(buf, pwd); + sched_unlock(); + return buf; +} +#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/lib/unistd/lib_getopt.c b/nuttx/lib/unistd/lib_getopt.c new file mode 100644 index 0000000000..832d287213 --- /dev/null +++ b/nuttx/lib/unistd/lib_getopt.c @@ -0,0 +1,269 @@ +/**************************************************************************** + * lib/unistd/lib_getopt.c + * + * Copyright (C) 2007-2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +FAR char *optarg; /* Optional argument following option */ +int optind = 1; /* Index into argv */ +int optopt = '?'; /* unrecognized option character */ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +static FAR char *g_optptr = NULL; +static bool g_binitialized = false; + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: getopt + * + * Description: getopt() parses command-line arguments. Its arguments argc + * and argv are the argument count and array as passed to the main() + * function on program invocation. An element of argv that starts with + * '-' is an option element. The characters of this element (aside from + * the initial '-') are option characters. If getopt() is called repeatedly, + * it returns successively each of the option characters from each of the + * option elements. + * + * If getopt() finds another option character, it returns that character, + * updating the external variable optind and a static variable nextchar so + * that the next call to getopt() can resume the scan with the following + * option character or argv-element. + * + * If there are no more option characters, getopt() returns -1. Then optind + * is the index in argv of the first argv-element that is not an option. + * + * The 'optstring' argument is a string containing the legitimate option + * characters. If such a character is followed by a colon, this indicates + * that the option requires an argument. If an argument is required for an + * option so getopt() places a pointer to the following text in the same + * argv-element, or the text of the following argv-element, in optarg. + * + * NOTES: + * 1. opterr is not supported and this implementation of getopt() never + * printfs error messages. + * 2. getopt is NOT threadsafe! + * 3. This version of getopt() does not reset global variables until + * -1 is returned. As a result, your command line parsing loops + * must call getopt() repeatedly and continue to parse if other + * errors are returned ('?' or ':') until getopt() finally returns -1. + * (You can also set optind to -1 to force a reset). + * + * Return: If an option was successfully found, then getopt() returns the + * option character. If all command-line options have been parsed, then + * getopt() returns -1. If getopt() encounters an option character that + * was not in optstring, then '?' is returned. If getopt() encounters an + * option with a missing argument, then the return value depends on the + * first character in optstring: if it is ':', then ':' is returned; + * otherwise '?' is returned. + * + ****************************************************************************/ + +int getopt(int argc, FAR char *const argv[], FAR const char *optstring) +{ + if (argv && optstring && argc > 1) + { + int noarg_ret = '?'; + char *optchar; + + /* The inital value of optind is 1. If getopt() is called again in the + * program, optind must be reset to some value <= 1. + */ + + if (optind < 1 || !g_binitialized) + { + optind = 1; /* Skip over the program name */ + g_optptr = NULL; /* Start at the beginning of the first argument */ + g_binitialized = true; /* Now we are initialized */ + } + + /* If the first character of opstring s ':', then ':' is in the event of + * a missing argument. Otherwise '?' is returned. + */ + + if (*optstring == ':') + { + noarg_ret = ':'; + optstring++; + } + + /* Are we resuming in the middle, or at the end of a string of arguments? + * g_optptr == NULL means that we are started at the beginning of argv[optind]; + * *g_optptr == \0 means that we are starting at the beginning of optind+1 + */ + + while (!g_optptr || !*g_optptr) + { + /* We need to start at the beginning of the next argv. Check if we need + * to increment optind + */ + + if (g_optptr) + { + /* Yes.. Increment it and check for the case where where we have + * processed everything in the argv[] array. + */ + + optind++; + } + + /* Check for the end of the argument list */ + + g_optptr = argv[optind]; + if (!g_optptr) + { + /* There are no more arguments, we are finished */ + + g_binitialized = false; + return ERROR; + } + + /* We are starting at the beginning of argv[optind]. In this case, the + * first character must be '-' + */ + + if (*g_optptr != '-') + { + /* The argument does not start with '-', we are finished */ + + g_binitialized = false; + return ERROR; + } + + /* Skip over the '-' */ + + g_optptr++; + } + + /* Special case handling of "-" and "-:" */ + + if (!*g_optptr) + { + optopt = '\0'; /* We'll fix up g_optptr the next time we are called */ + return '?'; + } + + /* Handle the case of "-:" */ + + if (*g_optptr == ':') + { + optopt = ':'; + g_optptr++; + return '?'; + } + + /* g_optptr now points at the next option and it is not something crazy. + * check if the option is in the list of valid options. + */ + + optchar = strchr(optstring, *g_optptr); + if (!optchar) + { + /* No this character is not in the list of valid options */ + + optopt = *g_optptr; + g_optptr++; + return '?'; + } + + /* Yes, the character is in the list of valid options. Does it have an + * required argument? + */ + + if (optchar[1] != ':') + { + /* No, no arguments. Just return the character that we found */ + + g_optptr++; + return *optchar; + } + + /* Yes, it has a required argument. Is the required argument + * immediately after the command in this same argument? + */ + + if (g_optptr[1] != '\0') + { + /* Yes, return a pointer into the current argument */ + + optarg = &g_optptr[1]; + optind++; + g_optptr = NULL; + return *optchar; + } + + /* No.. is the optional argument the next argument in argv[] ? */ + + if (argv[optind+1] && *argv[optind+1] != '-') + { + /* Yes.. return that */ + + optarg = argv[optind+1]; + optind += 2; + g_optptr = NULL; + return *optchar; + } + + /* No argument was supplied */ + + optarg = NULL; + optopt = *optchar; + optind++; + return noarg_ret; + } + + g_binitialized = false; + return ERROR; +} diff --git a/nuttx/lib/unistd/lib_getoptargp.c b/nuttx/lib/unistd/lib_getoptargp.c new file mode 100644 index 0000000000..98a4850169 --- /dev/null +++ b/nuttx/lib/unistd/lib_getoptargp.c @@ -0,0 +1,73 @@ +/**************************************************************************** + * lib/unistd/lib_getoptargp.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: getoptargp + * + * Description: + * Returns a pointer to optarg. This function is only used for external + * modules that need to access the base, global variable, optarg. + * + ****************************************************************************/ + +FAR char **getoptargp(void) +{ + return &optarg; +} + diff --git a/nuttx/lib/unistd/lib_getoptindp.c b/nuttx/lib/unistd/lib_getoptindp.c new file mode 100644 index 0000000000..7714f8e708 --- /dev/null +++ b/nuttx/lib/unistd/lib_getoptindp.c @@ -0,0 +1,73 @@ +/**************************************************************************** + * lib/unistd/lib_getoptindp.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: getoptindp + * + * Description: + * Returns a pointer to optind. This function is only used for external + * modules that need to access the base, global variable, optind. + * + ****************************************************************************/ + +int *getoptindp(void) +{ + return &optind; +} + diff --git a/nuttx/lib/unistd/lib_getoptoptp.c b/nuttx/lib/unistd/lib_getoptoptp.c new file mode 100644 index 0000000000..4805b7ac3b --- /dev/null +++ b/nuttx/lib/unistd/lib_getoptoptp.c @@ -0,0 +1,73 @@ +/**************************************************************************** + * lib/unistd/lib_getoptoptp.c + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: getoptoptp + * + * Description: + * Returns a pointer to optopt. This function is only used for external + * modules that need to access the base, global variable, optopt. + * + ****************************************************************************/ + +int *getoptoptp(void) +{ + return &optopt; +} + diff --git a/nuttx/libxx/Kconfig b/nuttx/libxx/Kconfig index 8b5fc42e8b..4133a0ceb9 100644 --- a/nuttx/libxx/Kconfig +++ b/nuttx/libxx/Kconfig @@ -3,8 +3,6 @@ # see misc/tools/kconfig-language.txt. # -comment "Basic CXX Support" - config HAVE_CXX bool "Have C++ compiler" default n @@ -12,8 +10,6 @@ config HAVE_CXX Toolchain supports C++ and CXX, CXXFLAGS, and COMPILEXX have been defined in the configurations Make.defs file. -if HAVE_CXX - config HAVE_CXXINITIALIZE bool "Have C++ initialization" default n @@ -29,33 +25,3 @@ config CXX_NEWLONG size_t may be type long or type int. This matters for some C++ library routines because the NuttX size_t might not have the same underlying type as your toolchain's size_t. - -comment "uClibc++ Standard C++ Library" - -config UCLIBCXX - bool "Build uClibc++ (must be installed)" - default n - ---help--- - If you have installed uClibc++ into the NuttX source try, then it can - be built by selecting this option. See misc/uClibc++/README.txt for - information on installing uClibc++. - -if UCLIBCXX - -config UCLIBCXX_EXCEPTION - bool "Enable Exception Suppport" - default y - -config UCLIBCXX_IOSTREAM_BUFSIZE - int "IO Stream Buffer Size" - default 32 - -config UCLIBCXX_HAVE_LIBSUPCXX - bool "Have libsupc++ (required)" - default y - ---help--- - Select if your toolchain provides libsupc++. This option is required - at present because the built-in libsupc++ support is incomplete. - -endif -endif diff --git a/nuttx/libxx/Makefile b/nuttx/libxx/Makefile index 2ab146e9cc..4122931ac9 100644 --- a/nuttx/libxx/Makefile +++ b/nuttx/libxx/Makefile @@ -1,7 +1,7 @@ ############################################################################ # libxx/Makefile # -# Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2009 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -35,56 +35,20 @@ -include $(TOPDIR)/Make.defs -# Sources +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) +CSRCS = +COBJS = $(CSRCS:.c=$(OBJEXT)) +CXXSRCS = libxx_cxapurevirtual.cxx libxx_delete.cxx libxx_deletea.cxx \ + libxx_eabi_atexit.cxx libxx_new.cxx libxx_newa.cxx +CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) -ASRCS = -CSRCS = +SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) +OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -CXXSRCS = libxx_cxapurevirtual.cxx libxx_eabi_atexit.cxx libxx_cxa_atexit.cxx +BIN = liblibxx$(LIBEXT) -# Some of the libxx/ files are not need if uClibc++ is installed because -# uClibx++ replaces them - -ifneq ($(CONFIG_UCLIBCXX),y) -CXXSRCS += libxx_delete.cxx libxx_deletea.cxx libxx_new.cxx libxx_newa.cxx -CXXSRCS += libxx_stdthrow.cxx -else -ifneq ($(UCLIBCXX_EXCEPTION),y) -CXXSRCS += libxx_stdthrow.cxx -endif -endif - -# Paths - -DEPPATH = --dep-path . -VPATH = . - -# Include the uClibc++ Make.defs file if selected. If it is included, -# the uClibc++/Make.defs file will add its files to the source file list, -# add its DEPPATH info, and will add the appropriate paths to the VPATH -# variable -# -# Note that an error will occur if you select CONFIG_LIBXX_UCLIBCXX -# without installing the uClibc++ package. This is intentional to let -# you know about the configuration problem. Refer to misc/uClibc++/README.txt -# for more information - -ifeq ($(CONFIG_UCLIBCXX),y) -include uClibc++/Make.defs -endif - -# Object Files - -AOBJS = $(ASRCS:.S=$(OBJEXT)) -COBJS = $(CSRCS:.c=$(OBJEXT)) -CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) - -SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) -OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) - -BIN = libcxx$(LIBEXT) - -all: $(BIN) +all: $(BIN) $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -96,20 +60,21 @@ $(CXXOBJS): %$(OBJEXT): %.cxx $(call COMPILEXX, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) .depend: Makefile $(SRCS) - $(Q) $(MKDEP) $(DEPPATH) "$(CXX)" -- $(CXXFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(CXX) -- $(CXXFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, $(BIN)) + @rm -f $(BIN) *~ .*.swp $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/nuttx/libxx/README.txt b/nuttx/libxx/README.txt index 7a1c51fa70..6cf066f080 100644 --- a/nuttx/libxx/README.txt +++ b/nuttx/libxx/README.txt @@ -12,10 +12,6 @@ are recommended: - uClibc++ http://cxx.uclibc.org/ - uSTL http://ustl.sourceforge.net/ -There is a version of uClibc++ that is customized for NuttX that can -be found here: misc/uClibc++. See misc/uClibc++ for installation -instructions. - At present, only the following are supported here: - void *operator new(std::size_t nbytes); @@ -23,7 +19,6 @@ At present, only the following are supported here: - void operator delete[](void *ptr); - void __cxa_pure_virtual(void); - int __aeabi_atexit(void* object, void (*destroyer)(void*), void *dso_handle); - - int __cxa_atexit(__cxa_exitfunc_t func, FAR void *arg, FAR void *dso_handle); operator new ------------ diff --git a/nuttx/libxx/libxx_eabi_atexit.cxx b/nuttx/libxx/libxx_eabi_atexit.cxx index 25f8306a84..aa0ff6956c 100644 --- a/nuttx/libxx/libxx_eabi_atexit.cxx +++ b/nuttx/libxx/libxx_eabi_atexit.cxx @@ -40,22 +40,26 @@ #include #include -#include "libxx_internal.hxx" - //*************************************************************************** -// Pre-processor Definitions +// Definitions //*************************************************************************** //*************************************************************************** // Private Data //*************************************************************************** -//*************************************************************************** -// Public Functions -//*************************************************************************** - extern "C" { + //************************************************************************* + // Public Data + //************************************************************************* + + void *__dso_handle = NULL; + + //************************************************************************* + // Public Functions + //************************************************************************* + //************************************************************************* // Name: __aeabi_atexit // @@ -71,8 +75,9 @@ extern "C" // //************************************************************************* - int __aeabi_atexit(FAR void *object, __cxa_exitfunc_t func, FAR void *dso_handle) + int __aeabi_atexit(void* object, void (*destroyer)(void*), void *dso_handle) { - return __cxa_atexit(func, object, dso_handle); // 0 ? OK; non-0 ? failed + //return __cxa_atexit(destroyer, object, dso_handle); // 0 ? OK; non-0 ? failed } + return 0; } } diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile index da41f9f57b..0ccf5a09a9 100644 --- a/nuttx/mm/Makefile +++ b/nuttx/mm/Makefile @@ -37,8 +37,8 @@ ASRCS = CSRCS = mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c mm_shrinkchunk.c \ - mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c \ - mm_memalign.c mm_free.c mm_mallinfo.c + mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c \ + mm_memalign.c mm_free.c mm_mallinfo.c ifeq ($(CONFIG_GRAN),y) CSRCS += mm_graninit.c mm_granalloc.c mm_granfree.c mm_grancritical.c @@ -61,20 +61,21 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) .depend: Makefile $(SRCS) - $(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, $(BIN)) + @rm -f $(BIN) *~ .*.swp $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/nuttx/mm/Makefile.test b/nuttx/mm/Makefile.test index 2ae9dcb883..63cab910e9 100644 --- a/nuttx/mm/Makefile.test +++ b/nuttx/mm/Makefile.test @@ -33,14 +33,12 @@ # ############################################################################ --include $(TOPDIR)/Make.defs - -SRCS = mm_test.c mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c mm_shrinkchunk.c \ +SRCS = mm_test.c mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c mm_shrinkchunk.c \ mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c \ mm_memalign.c mm_free.c mm_mallinfo.c -OBJS = $(SRCS:.c=.o1) +OBJS = $(SRCS:.c=.o1) -LIBS = -lpthread -lc +LIBS = -lpthread -lc CC = gcc LD = gcc @@ -50,19 +48,17 @@ WARNIGNS = -Wall -Wstrict-prototypes -Wshadow CFLAGS = -g $(DEFINES) LDFLAGS = -BIN = ..$(DELIM)mm_test +BIN = ../mm_test all: $(BIN) $(OBJS): %.o1: %.c @echo "Compiling $<" - $(Q) $(CC) -c $(CFLAGS) $< -o $@ + $(CC) -c $(CFLAGS) $< -o $@ $(BIN): $(OBJS) @echo "Linking {$(OBJS)} to produce $@" - $(Q) $(LD) $(LDFLAGS) $(OBJS) $(LIBS) -o $@ + $(LD) $(LDFLAGS) $(OBJS) $(LIBS) -o $@ clean: - $(call DELFILE, $(BIN)) - $(call DELFILE, *.o1) - $(call CLEAN) + @rm -f $(BIN) *.o1 *~ diff --git a/nuttx/mm/mm_initialize.c b/nuttx/mm/mm_initialize.c index a7f64cfafd..3a21d1759b 100644 --- a/nuttx/mm/mm_initialize.c +++ b/nuttx/mm/mm_initialize.c @@ -95,9 +95,9 @@ void mm_initialize(FAR void *heapstart, size_t heapsize) mlldbg("Heap: start=%p size=%u\n", heapstart, heapsize); - /* The following two lines have cause problems for some older ZiLog - * compilers in the past (but not the more recent). Life is easier if we - * just the suppress them altogther for those tools. + /* The following two lines have cause problems for some ZiLog compilers + * in the past. Life is easier if we just the suppress them for those + * tools. */ #ifndef __ZILOG__ diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile index 74540b67d4..506ef82138 100644 --- a/nuttx/net/Makefile +++ b/nuttx/net/Makefile @@ -100,22 +100,24 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) .depend: Makefile $(SRCS) ifeq ($(CONFIG_NET),y) - $(Q) $(MKDEP) --dep-path . --dep-path uip "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) --dep-path . --dep-path uip $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep endif - $(Q) touch $@ + @touch $@ depend: .depend clean: - $(call DELFILE, $(BIN)) + @rm -f $(BIN) *~ .*.swp + @rm -f uip/*~ uip/.*.swp $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/nuttx/net/netdev_ioctl.c b/nuttx/net/netdev_ioctl.c index ea5c0e4362..4b5876efa0 100644 --- a/nuttx/net/netdev_ioctl.c +++ b/nuttx/net/netdev_ioctl.c @@ -138,47 +138,19 @@ static void ioctl_setipaddr(FAR uip_ipaddr_t *outaddr, FAR const void *inaddr) * ****************************************************************************/ -static void ioctl_ifup(FAR struct uip_driver_s *dev) +static inline void ioctl_ifup(FAR struct uip_driver_s *dev) { - /* Make sure that the device supports the d_ifup() method */ - if (dev->d_ifup) { - /* Is the interface already up? */ - - if ((dev->d_flags & IFF_RUNNING) == 0) - { - /* No, bring the interface up now */ - - if (dev->d_ifup(dev) == OK) - { - /* Mark the interface as up */ - - dev->d_flags |= IFF_RUNNING; - } - } + dev->d_ifup(dev); } } -static void ioctl_ifdown(FAR struct uip_driver_s *dev) +static inline void ioctl_ifdown(FAR struct uip_driver_s *dev) { - /* Make sure that the device supports the d_ifdown() method */ - if (dev->d_ifdown) { - /* Is the interface already down? */ - - if ((dev->d_flags & IFF_RUNNING) != 0) - { - /* No, take the interface down now */ - - if (dev->d_ifdown(dev) == OK) - { - /* Mark the interface as down */ - - dev->d_flags &= ~IFF_RUNNING; - } - } + dev->d_ifdown(dev); } } @@ -222,130 +194,63 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, struct ifreq *req) switch (cmd) { - case SIOCGIFADDR: /* Get IP address */ - { - ioctl_getipaddr(&req->ifr_addr, &dev->d_ipaddr); - } + case SIOCGIFADDR: /* Get IP address */ + ioctl_getipaddr(&req->ifr_addr, &dev->d_ipaddr); break; - case SIOCSIFADDR: /* Set IP address */ - { - ioctl_ifdown(dev); - ioctl_setipaddr(&dev->d_ipaddr, &req->ifr_addr); - ioctl_ifup(dev); - } + case SIOCSIFADDR: /* Set IP address */ + ioctl_ifdown(dev); + ioctl_setipaddr(&dev->d_ipaddr, &req->ifr_addr); + ioctl_ifup(dev); break; case SIOCGIFDSTADDR: /* Get P-to-P address */ - { - ioctl_getipaddr(&req->ifr_dstaddr, &dev->d_draddr); - } + ioctl_getipaddr(&req->ifr_dstaddr, &dev->d_draddr); break; case SIOCSIFDSTADDR: /* Set P-to-P address */ - { - ioctl_setipaddr(&dev->d_draddr, &req->ifr_dstaddr); - } + ioctl_setipaddr(&dev->d_draddr, &req->ifr_dstaddr); break; case SIOCGIFNETMASK: /* Get network mask */ - { - ioctl_getipaddr(&req->ifr_addr, &dev->d_netmask); - } + ioctl_getipaddr(&req->ifr_addr, &dev->d_netmask); break; case SIOCSIFNETMASK: /* Set network mask */ - { - ioctl_setipaddr(&dev->d_netmask, &req->ifr_addr); - } + ioctl_setipaddr(&dev->d_netmask, &req->ifr_addr); break; case SIOCGIFMTU: /* Get MTU size */ - { - req->ifr_mtu = CONFIG_NET_BUFSIZE; - } - break; - - case SIOCSIFFLAGS: /* Sets the interface flags */ - { - /* Is this a request to bring the interface up? */ - - if (req->ifr_flags & IF_FLAG_IFUP) - { - /* Yes.. bring the interface up */ - - ioctl_ifup(dev); - } - - /* Is this a request to take the interface down? */ - - else if (req->ifr_flags & IF_FLAG_IFDOWN) - { - /* Yes.. take the interface down */ - - ioctl_ifdown(dev); - } - } - break; - - case SIOCGIFFLAGS: /* Gets the interface flags */ - { - req->ifr_flags = 0; - - /* Is the interface running? */ - - if (dev->d_flags & IFF_RUNNING) - { - /* Yes.. report interface up */ - - req->ifr_flags |= IF_FLAG_IFUP; - } - else - { - /* No.. report interface down */ - - req->ifr_flags |= IF_FLAG_IFDOWN; - } - } + req->ifr_mtu = CONFIG_NET_BUFSIZE; break; /* MAC address operations only make sense if Ethernet is supported */ #ifdef CONFIG_NET_ETHERNET case SIOCGIFHWADDR: /* Get hardware address */ - { - req->ifr_hwaddr.sa_family = AF_INETX; - memcpy(req->ifr_hwaddr.sa_data, dev->d_mac.ether_addr_octet, IFHWADDRLEN); - } + req->ifr_hwaddr.sa_family = AF_INETX; + memcpy(req->ifr_hwaddr.sa_data, dev->d_mac.ether_addr_octet, IFHWADDRLEN); break; case SIOCSIFHWADDR: /* Set hardware address -- will not take effect until ifup */ - { - req->ifr_hwaddr.sa_family = AF_INETX; - memcpy(dev->d_mac.ether_addr_octet, req->ifr_hwaddr.sa_data, IFHWADDRLEN); - } + req->ifr_hwaddr.sa_family = AF_INETX; + memcpy(dev->d_mac.ether_addr_octet, req->ifr_hwaddr.sa_data, IFHWADDRLEN); break; #endif case SIOCDIFADDR: /* Delete IP address */ - { - ioctl_ifdown(dev); - memset(&dev->d_ipaddr, 0, sizeof(uip_ipaddr_t)); - } + ioctl_ifdown(dev); + memset(&dev->d_ipaddr, 0, sizeof(uip_ipaddr_t)); break; case SIOCGIFCOUNT: /* Get number of devices */ - { - req->ifr_count = netdev_count(); - ret = -ENOSYS; - } + req->ifr_count = netdev_count(); + ret = -ENOSYS; break; - case SIOCGIFBRDADDR: /* Get broadcast IP address */ - case SIOCSIFBRDADDR: /* Set broadcast IP address */ - { - ret = -ENOSYS; - } + case SIOCGIFBRDADDR: /* Get broadcast IP address */ + case SIOCSIFBRDADDR: /* Set broadcast IP address */ + ret = -ENOSYS; break; #ifdef CONFIG_NET_ARPIOCTLS @@ -356,9 +261,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, struct ifreq *req) #endif default: - { - ret = -EINVAL; - } + ret = -EINVAL; break;; } diff --git a/nuttx/net/uip/uip_icmpping.c b/nuttx/net/uip/uip_icmpping.c index 36f6e892ad..e3ebf72520 100644 --- a/nuttx/net/uip/uip_icmpping.c +++ b/nuttx/net/uip/uip_icmpping.c @@ -123,7 +123,6 @@ static inline int ping_timeout(struct icmp_ping_s *pstate) { return TRUE; } - return FALSE; } @@ -366,7 +365,6 @@ int uip_ping(uip_ipaddr_t addr, uint16_t id, uint16_t seqno, uip_icmpcallbackfree(state.png_cb); } - uip_unlock(save); /* Return the negated error number in the event of a failure, or the diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig index 4a3e877454..4f7149595e 100644 --- a/nuttx/sched/Kconfig +++ b/nuttx/sched/Kconfig @@ -214,17 +214,12 @@ config SCHED_ATEXIT config SCHED_ATEXIT_MAX int "Max number of atexit() functions" default 1 - depends on SCHED_ATEXIT && !SCHED_ONEXIT + depends on SCHED_ATEXIT ---help--- By default if SCHED_ATEXIT is selected, only a single atexit() function is supported. That number can be increased by defined this setting to the number that you require. - If both SCHED_ONEXIT and SCHED_ATEXIT are selected, then atexit() is built - on top of the on_exit() implementation. In that case, SCHED_ONEXIT_MAX - determines the size of the combined number of atexit(0) and on_exit calls - and SCHED_ATEXIT_MAX is not used. - config SCHED_ONEXIT bool "Enable on_exit() API" default n @@ -240,10 +235,6 @@ config SCHED_ONEXIT_MAX is supported. That number can be increased by defined this setting to the number that you require. - If both SCHED_ONEXIT and SCHED_ATEXIT are selected, then atexit() is built - on top of the on_exit() implementation. In that case, SCHED_ONEXIT_MAX - determines the size of the combined number of atexit(0) and on_exit calls. - config USER_ENTRYPOINT string "Application entry point" default "user_start" diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 82f74fc3c8..1e0a55aeaf 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -94,7 +94,7 @@ SIGNAL_SRCS = sig_initialize.c \ sig_findaction.c sig_allocatependingsigaction.c \ sig_releasependingsigaction.c sig_unmaskpendingsignal.c \ sig_removependingsignal.c sig_releasependingsignal.c sig_lowest.c \ - sig_mqnotempty.c sig_cleanup.c sig_received.c sig_deliver.c pause.c + sig_mqnotempty.c sig_cleanup.c sig_received.c sig_deliver.c MQUEUE_SRCS = mq_open.c mq_close.c mq_unlink.c mq_send.c mq_timedsend.c\ mq_sndinternal.c mq_receive.c mq_timedreceive.c mq_rcvinternal.c \ @@ -188,7 +188,6 @@ OBJS = $(AOBJS) $(COBJS) BIN = libsched$(LIBEXT) all: $(BIN) -.PHONY: context depend clean distclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -197,20 +196,21 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) .depend: Makefile $(SRCS) - $(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, $(BIN)) + @rm -f $(BIN) *~ .*.swp $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/nuttx/sched/atexit.c b/nuttx/sched/atexit.c index b0559b01be..f7d81bec20 100644 --- a/nuttx/sched/atexit.c +++ b/nuttx/sched/atexit.c @@ -96,13 +96,8 @@ * CONFIG_SCHED_ATEXIT_MAX defines a larger number. * 2. atexit functions are not inherited when a new task is * created. - * 3. If both SCHED_ONEXIT and SCHED_ATEXIT are selected, then atexit() - * is built on top of the on_exit() implementation. In that case, - * CONFIG_SCHED_ONEXIT_MAX determines the size of the combined - * number of atexit(0) and on_exit calls and SCHED_ATEXIT_MAX is - * not used. * - * Input Parameters: + * Parameters: * func - A pointer to the function to be called when the task exits. * * Return Value: @@ -112,14 +107,7 @@ int atexit(void (*func)(void)) { -#if defined(CONFIG_SCHED_ONEXIT) - /* atexit is equivalent to on_exit() with no argument (Assuming that the ABI - * can handle a callback function that recieves more parameters than it expects). - */ - - return on_exit(onexitfunc_t func, NULL); - -#elif defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1 +#if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1 _TCB *tcb = (_TCB*)g_readytorun.head; int index; int ret = ERROR; diff --git a/nuttx/sched/mq_open.c b/nuttx/sched/mq_open.c index 89d80f072a..5e1b9b1377 100644 --- a/nuttx/sched/mq_open.c +++ b/nuttx/sched/mq_open.c @@ -113,6 +113,7 @@ mqd_t mq_open(const char *mq_name, int oflags, ...) FAR msgq_t *msgq; mqd_t mqdes = NULL; va_list arg; /* Points to each un-named argument */ + mode_t mode; /* MQ creation mode parameter (ignored) */ struct mq_attr *attr; /* MQ creation attributes */ int namelen; /* Length of MQ name */ @@ -169,7 +170,7 @@ mqd_t mq_open(const char *mq_name, int oflags, ...) */ va_start(arg, oflags); - (void)va_arg(arg, mode_t); /* MQ creation mode parameter (ignored) */ + mode = va_arg(arg, mode_t); attr = va_arg(arg, struct mq_attr*); /* Initialize the new named message queue */ diff --git a/nuttx/sched/on_exit.c b/nuttx/sched/on_exit.c index 19a4f91960..5b8be5cd10 100644 --- a/nuttx/sched/on_exit.c +++ b/nuttx/sched/on_exit.c @@ -117,7 +117,7 @@ int on_exit(CODE void (*func)(int, FAR void *), FAR void *arg) #if defined(CONFIG_SCHED_ONEXIT_MAX) && CONFIG_SCHED_ONEXIT_MAX > 1 _TCB *tcb = (_TCB*)g_readytorun.head; int index; - int ret = ENOSPC; + int ret = ERROR; /* The following must be atomic */ @@ -131,6 +131,7 @@ int on_exit(CODE void (*func)(int, FAR void *), FAR void *arg) * indices. */ + available = -1; for (index = 0; index < CONFIG_SCHED_ONEXIT_MAX; index++) { if (!tcb->onexitfunc[index]) @@ -148,7 +149,7 @@ int on_exit(CODE void (*func)(int, FAR void *), FAR void *arg) return ret; #else _TCB *tcb = (_TCB*)g_readytorun.head; - int ret = ENOSPC; + int ret = ERROR; /* The following must be atomic */ diff --git a/nuttx/sched/sched_getscheduler.c b/nuttx/sched/sched_getscheduler.c index 0d996ca271..5771e86ff4 100644 --- a/nuttx/sched/sched_getscheduler.c +++ b/nuttx/sched/sched_getscheduler.c @@ -129,4 +129,3 @@ int sched_getscheduler(pid_t pid) return SCHED_FIFO; } } - diff --git a/nuttx/sched/sem_open.c b/nuttx/sched/sem_open.c index b2b76fe380..817c36b49b 100644 --- a/nuttx/sched/sem_open.c +++ b/nuttx/sched/sem_open.c @@ -120,6 +120,7 @@ FAR sem_t *sem_open (FAR const char *name, int oflag, ...) FAR nsem_t *psem; FAR sem_t *sem = (FAR sem_t*)ERROR; va_list arg; /* Points to each un-named argument */ + mode_t mode; /* Creation mode parameter (ignored) */ unsigned int value; /* Semaphore value parameter */ /* Make sure that a non-NULL name is supplied */ @@ -164,7 +165,7 @@ FAR sem_t *sem_open (FAR const char *name, int oflag, ...) */ va_start(arg, oflag); - (void)va_arg(arg, mode_t); /* Creation mode parameter (ignored) */ + mode = va_arg(arg, mode_t); value = va_arg(arg, unsigned int); /* Verify that a legal initial value was selected. */ diff --git a/nuttx/sched/sleep.c b/nuttx/sched/sleep.c index 9b3b6d57fc..03884a5b64 100644 --- a/nuttx/sched/sleep.c +++ b/nuttx/sched/sleep.c @@ -141,7 +141,7 @@ unsigned int sleep(unsigned int seconds) if (seconds) { /* Set up for the sleep. Using the empty set means that we are not - * waiting for any particular signal. However, any unmasked signal + * waiting for any particualar signal. However, any unmasked signal * can still awaken sigtimedwait(). */ diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 6f52ef739e..e94476f2a7 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -81,8 +81,8 @@ * Call any registerd atexit function(s) * ****************************************************************************/ - -#if defined(CONFIG_SCHED_ATEXIT) && !defined(CONFIG_SCHED_ONEXIT) + +#ifdef CONFIG_SCHED_ATEXIT static inline void task_atexit(FAR _TCB *tcb) { #if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1 diff --git a/nuttx/sched/usleep.c b/nuttx/sched/usleep.c index 893a420f4e..21996d788b 100644 --- a/nuttx/sched/usleep.c +++ b/nuttx/sched/usleep.c @@ -137,7 +137,7 @@ int usleep(useconds_t usec) if (usec) { /* Set up for the sleep. Using the empty set means that we are not - * waiting for any particular signal. However, any unmasked signal + * waiting for any particualar signal. However, any unmasked signal * can still awaken sigtimedwait(). */ diff --git a/nuttx/syscall/Makefile b/nuttx/syscall/Makefile index ec2627b464..88365759d1 100644 --- a/nuttx/syscall/Makefile +++ b/nuttx/syscall/Makefile @@ -1,7 +1,7 @@ ############################################################################ # syscall/Makefile # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -34,11 +34,11 @@ ########################################################################### -include $(TOPDIR)/Make.defs -include proxies$(DELIM)Make.defs -include stubs$(DELIM)Make.defs +include proxies/Make.defs +include stubs/Make.defs -MKSYSCALL = "$(TOPDIR)$(DELIM)tools$(DELIM)mksyscall$(EXEEXT)" -CSVFILE = "$(TOPDIR)$(DELIM)syscall$(DELIM)syscall.csv" +MKSYSCALL = "$(TOPDIR)/tools/mksyscall$(EXEEXT)" +CSVFILE = "$(TOPDIR)/syscall/syscall.csv" STUB_SRCS += stub_lookup.c @@ -72,43 +72,42 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) $(BIN1): $(PROXY_OBJS) - $(call ARCHIVE, $@, $(PROXY_OBJS)) + @( for obj in $(PROXY_OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) $(BIN2): $(STUB_OBJS) - $(call ARCHIVE, $@, "$(STUB_OBJS)") + @( for obj in $(STUB_OBJS) ; do \ + $(call ARCHIVE, $@, $${obj}); \ + done ; ) .depend: Makefile $(SRCS) - $(Q) $(MKDEP) $(ROOTDEPPATH) $(PROXYDEPPATH) $(STUBDEPPATH) \ - "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(ROOTDEPPATH) $(PROXYDEPPATH) $(STUBDEPPATH) \ + $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend $(MKSYSCALL): - $(Q) $(MAKE) -C $(TOPDIR)$(DELIM)tools -f Makefile.host mksyscall + @$(MAKE) -C $(TOPDIR)/tools -f Makefile.host mksyscall .context: syscall.csv - $(Q) (cd proxies; $(MKSYSCALL) -p $(CSVFILE);) - $(Q) (cd stubs; $(MKSYSCALL) -s $(CSVFILE);) - $(Q) touch $@ + @(cd proxies; $(MKSYSCALL) -p $(CSVFILE);) + @(cd stubs; $(MKSYSCALL) -s $(CSVFILE);) + @touch $@ context: $(MKSYSCALL) .context clean: - $(call DELFILE, $(BIN1)) - $(call DELFILE, $(BIN2)) + @rm -f $(BIN1) $(BIN2) *~ .*.swp ifneq ($(OBJEXT),) - $(call DELFILE, proxies$(DELIM)*$(OBJEXT)) - $(call DELFILE, stubs$(DELIM)*$(OBJEXT)) + @rm -f proxies/*$(OBJEXT) stubs/*$(OBJEXT) endif $(call CLEAN) distclean: clean - $(call DELFILE, .context) - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) - $(call DELFILE, proxies$(DELIM)*.c) - $(call DELFILE, stubs$(DELIM)*.c) + @rm -f Make.dep .depend .context + @rm -f proxies/*.c stubs/*.c -include Make.dep diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk index 300df7a6ac..3a82a19377 100644 --- a/nuttx/tools/Config.mk +++ b/nuttx/tools/Config.mk @@ -2,12 +2,7 @@ # Config.mk # Global build rules and macros. # -# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Richard Cochran -# Gregory Nutt -# -# This file (along with $(TOPDIR)/.config) must be included by every -# configuration-specific Make.defs file. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -45,172 +40,33 @@ CONFIG_ARCH := $(patsubst "%",%,$(strip $(CONFIG_ARCH))) CONFIG_ARCH_CHIP := $(patsubst "%",%,$(strip $(CONFIG_ARCH_CHIP))) CONFIG_ARCH_BOARD := $(patsubst "%",%,$(strip $(CONFIG_ARCH_BOARD))) -# Some defaults just to prohibit some bad behavior if for some reason they -# are not defined - -OBJEXT ?= .o -LIBEXT ?= .a - -# DELIM - Path segment delimiter character -# -# Depends on this settings defined in board-specific defconfig file installed -# at $(TOPDIR)/.config: -# -# CONFIG_WINDOWS_NATIVE - Defined for a Windows native build - -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - DELIM = $(strip \) -else - DELIM = $(strip /) -endif - -# INCDIR - Convert a list of directory paths to a list of compiler include -# directirves -# Example: CFFLAGS += ${shell $(INCDIR) [options] "compiler" "dir1" "dir2" "dir2" ...} -# -# Note that the compiler string and each directory path string must quoted if -# they contain spaces or any other characters that might get mangled by the -# shell -# -# Depends on this setting passed as a make commaond line definition from the -# toplevel Makefile: -# -# TOPDIR - The path to the the top level NuttX directory in the form -# appropriate for the current build environment -# -# Depends on this settings defined in board-specific defconfig file installed -# at $(TOPDIR)/.config: -# -# CONFIG_WINDOWS_NATIVE - Defined for a Windows native build - -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - INCDIR = "$(TOPDIR)\tools\incdir.bat" -else - INCDIR = "$(TOPDIR)/tools/incdir.sh" -endif - -# PREPROCESS - Default macro to run the C pre-processor -# Example: $(call PREPROCESS, in-file, out-file) -# -# Depends on these settings defined in board-specific Make.defs file -# installed at $(TOPDIR)/Make.defs: -# -# CPP - The command to invoke the C pre-processor -# CPPFLAGS - Options to pass to the C pre-processor +# Default build rules. define PREPROCESS @echo "CPP: $1->$2" $(Q) $(CPP) $(CPPFLAGS) $1 -o $2 endef -# COMPILE - Default macro to compile one C file -# Example: $(call COMPILE, in-file, out-file) -# -# Depends on these settings defined in board-specific Make.defs file -# installed at $(TOPDIR)/Make.defs: -# -# CC - The command to invoke the C compiler -# CFLAGS - Options to pass to the C compiler - define COMPILE @echo "CC: $1" $(Q) $(CC) -c $(CFLAGS) $1 -o $2 endef -# COMPILEXX - Default macro to compile one C++ file -# Example: $(call COMPILEXX, in-file, out-file) -# -# Depends on these settings defined in board-specific Make.defs file -# installed at $(TOPDIR)/Make.defs: -# -# CXX - The command to invoke the C++ compiler -# CXXFLAGS - Options to pass to the C++ compiler - define COMPILEXX @echo "CXX: $1" $(Q) $(CXX) -c $(CXXFLAGS) $1 -o $2 endef -# ASSEMBLE - Default macro to assemble one assembly language file -# Example: $(call ASSEMBLE, in-file, out-file) -# -# Depends on these settings defined in board-specific Make.defs file -# installed at $(TOPDIR)/Make.defs: -# -# CC - By default, the C compiler is used to compile assembly lagnuage -# files -# AFLAGS - Options to pass to the C+compiler - define ASSEMBLE @echo "AS: $1" $(Q) $(CC) -c $(AFLAGS) $1 -o $2 endef -# ARCHIVE - Add a list of files to an archive -# Example: $(call ARCHIVE, archive-file, "file1 file2 file3 ...") -# -# Note: The fileN strings may not contain spaces or characters that may be -# interpreted strangely by the shell -# -# Depends on these settings defined in board-specific Make.defs file -# installed at $(TOPDIR)/Make.defs: -# -# AR - The command to invoke the archiver (includes any options) -# -# Depends on this settings defined in board-specific defconfig file installed -# at $(TOPDIR)/.config: -# -# CONFIG_WINDOWS_NATIVE - Defined for a Windows native build - -ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ARCHIVE - @echo "AR: $2" - $(AR) $1 - $(Q) $(AR) $1 $(2) + echo "AR: $2"; \ + $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; } endef -else -define ARCHIVE - @echo "AR: $2" - $(Q) $(AR) $1 $(2) || { echo "$(AR) $1 FAILED!" ; exit 1 ; } -endef -endif -# DELFILE - Delete one file - -ifeq ($(CONFIG_WINDOWS_NATIVE),y) -define DELFILE - $(Q) if exist $1 (del /f /q $1) -endef -else -define DELFILE - $(Q) rm -f $1 -endef -endif - -# DELDIR - Delect one directory - -ifeq ($(CONFIG_WINDOWS_NATIVE),y) -define DELDIR - $(Q) if exist $1 (rmdir /q /s $1) -endef -else -define DELDIR - $(Q) rm -rf $1 -endef -endif - -# CLEAN - Default clean target - -ifeq ($(CONFIG_WINDOWS_NATIVE),y) define CLEAN - $(Q) if exist *$(OBJEXT) (del /f /q *$(OBJEXT)) - $(Q) if exist *$(LIBEXT) (del /f /q *$(LIBEXT)) - $(Q) if exist *~ (del /f /q *~) - $(Q) if exist (del /f /q .*.swp) + $(Q) rm -f *.o *.a endef -else -define CLEAN - $(Q) rm -f *$(OBJEXT) *$(LIBEXT) *~ .*.swp -endef -endif - \ No newline at end of file diff --git a/nuttx/tools/Makefile.export b/nuttx/tools/Makefile.export index 95a33b7796..ce4842187a 100644 --- a/nuttx/tools/Makefile.export +++ b/nuttx/tools/Makefile.export @@ -61,7 +61,7 @@ endif @echo "ARCHCFLAGS=\"$(ARCHCFLAGS) $(ARCHCPUFLAGS)\"" >> $(EXPORTDIR)/makeinfo.sh @echo "ARCHCXXFLAGS=\"$(ARCHCXXFLAGS) $(ARCHCPUFLAGS)\"" >> $(EXPORTDIR)/makeinfo.sh @echo "CROSSDEV=\"$(CROSSDEV)\"" >> $(EXPORTDIR)/makeinfo.sh - $(Q) chmod 755 $(EXPORTDIR)/makeinfo.sh + @chmod 755 $(EXPORTDIR)/makeinfo.sh clean: - $(Q) rm -f $(EXPORTDIR)/makeinfo.sh + @rm -f $(EXPORTDIR)/makeinfo.sh diff --git a/nuttx/tools/Makefile.host b/nuttx/tools/Makefile.host index a661424dc8..33b7aaab2b 100644 --- a/nuttx/tools/Makefile.host +++ b/nuttx/tools/Makefile.host @@ -33,107 +33,45 @@ # ############################################################################ -TOPDIR ?= ${shell pwd}/.. --include $(TOPDIR)/Make.defs -include ${TOPDIR}/tools/Config.mk - -# strtok_r is used in some tools, but does not seem to be available in -# the MinGW environment. - -ifneq ($(CONFIG_WINDOWS_NATIVE),y) - HOSTCFLAGS += -D HAVE_STRTOK_C -endif - -all: mkconfig$(HOSTEXEEXT) mkversion$(HOSTEXEEXT) mksyscall$(HOSTEXEEXT) bdf-converter$(HOSTEXEEXT) mksymtab$(HOSTEXEEXT) mkdeps$(HOSTEXEEXT) -default: mkconfig$(HOSTEXEEXT) mksyscall$(HOSTEXEEXT) mkdeps$(HOSTEXEEXT) - -ifdef HOSTEXEEXT -.PHONY: clean mkconfig mkversion mksyscall bdf-converter mksymtab mkdeps -else +all: mkconfig mkversion mksyscall bdf-converter +default: mkconfig mksyscall .PHONY: clean -endif -# Add HOSTCFLAGS=-g on the make command line build debug versions +# Add CFLAGS=-g on the make command line build debug versions -HOSTCFLAGS ?= -O2 -Wall -I. -HOSTCC ?= gcc +CFLAGS = -O2 -Wall -I. # mkconfig - Convert a .config file into a C config.h file -mkconfig$(HOSTEXEEXT): mkconfig.c cfgparser.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkconfig$(HOSTEXEEXT) mkconfig.c cfgparser.c - -ifdef HOSTEXEEXT -mkconfig: mkconfig$(HOSTEXEEXT) -endif +mkconfig: mkconfig.c cfgparser.c + @gcc $(CFLAGS) -o mkconfig mkconfig.c cfgparser.c # cmpconfig - Compare the contents of two configuration files cmpconfig: cmpconfig.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o cmpconfig cmpconfig.c - -ifdef HOSTEXEEXT -cmpconfig: cmpconfig$(HOSTEXEEXT) -endif + @gcc $(CFLAGS) -o cmpconfig cmpconfig.c # mkversion - Convert a .version file into a C version.h file -mkversion$(HOSTEXEEXT): mkconfig.c cfgparser.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkversion$(HOSTEXEEXT) mkversion.c cfgparser.c - -ifdef HOSTEXEEXT -mkversion: mkversion$(HOSTEXEEXT) -endif +mkversion: mkconfig.c cfgparser.c + @gcc $(CFLAGS) -o mkversion mkversion.c cfgparser.c # mksyscall - Convert a CSV file into syscall stubs and proxies -mksyscall$(HOSTEXEEXT): mksyscall.c csvparser.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mksyscall$(HOSTEXEEXT) mksyscall.c csvparser.c - -ifdef HOSTEXEEXT -mksyscall: mksyscall$(HOSTEXEEXT) -endif +mksyscall: mksyscall.c csvparser.c + @gcc $(CFLAGS) -o mksyscall mksyscall.c csvparser.c # mksymtab - Convert a CSV file into a symbol table -mksymtab$(HOSTEXEEXT): mksymtab.c csvparser.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mksymtab$(HOSTEXEEXT) mksymtab.c csvparser.c - -ifdef HOSTEXEEXT -mksymtab: mksymtab$(HOSTEXEEXT) -endif +mksymtab: mksymtab.c csvparser.c + @gcc $(CFLAGS) -o mksymtab mksymtab.c csvparser.c # bdf-converter - Converts a BDF font to the NuttX font format -bdf-converter$(HOSTEXEEXT): bdf-converter.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o bdf-converter$(HOSTEXEEXT) bdf-converter.c - -ifdef HOSTEXEEXT -bdf-converter: bdf-converter$(HOSTEXEEXT) -endif - -# Create dependencies for a list of files - -mkdeps$(HOSTEXEEXT): mkdeps.c csvparser.c - $(Q) $(HOSTCC) $(HOSTCFLAGS) -o mkdeps$(HOSTEXEEXT) mkdeps.c - -ifdef HOSTEXEEXT -mkdeps: mkdeps$(HOSTEXEEXT) -endif +bdf-converter: bdf-converter.c + @gcc $(CFLAGS) -o bdf-converter bdf-converter.c clean: - $(call DELFILE, mkdeps) - $(call DELFILE, mkdeps.exe) - $(call DELFILE, mkconfig) - $(call DELFILE, mkconfig.exe) - $(call DELFILE, Make.dep) - $(call DELFILE, mksyscall) - $(call DELFILE, mksyscall.exe) - $(call DELFILE, mkversion) - $(call DELFILE, mkversion.exe) - $(call DELFILE, bdf-converter) - $(call DELFILE, bdf-converter.exe) -ifneq ($(CONFIG_WINDOWS_NATIVE),y) - $(Q) rm -rf *.dSYM -endif - $(call CLEAN) + @rm -f *.o *.a *~ .*.swp + @rm -f mkconfig mksyscall mkversion bdf-converter + @rm -f mkconfig.exe mksyscall.exe mkversion.exe bdf-converter.exe diff --git a/nuttx/tools/README.txt b/nuttx/tools/README.txt index 68b85dc4f3..5d52eaefff 100644 --- a/nuttx/tools/README.txt +++ b/nuttx/tools/README.txt @@ -1,5 +1,5 @@ tools/README.txt -================ +^^^^^^^^^^^^^^^^ This README file addresses the contents of the NuttX tools/ directory. @@ -8,38 +8,22 @@ that are necessary parts of the the NuttX build system. These files include: README.txt ----------- - This file! - -Config.mk ---------- - - This file contains common definitions used by many configureation files. - This file (along with /.config) must be included at the top of - each configuration-specific Make.defs file like: - - -include $(TOPDIR)/.config - include $(TOPDIR)/tools/Config.mk - - Subsequent logic within the configuration-specific Make.defs file may then - override these default definitions as necessary. + This file configure.sh ------------- This is a bash script that is used to configure NuttX for a given target board. See configs/README.txt or Documentation/NuttxPortingGuide.html for a description of how to configure NuttX with this script. discover.py ------------ Example script for discovering devices in the local network. It is the counter part to apps/netutils/discover + mkconfig.c, cfgparser.c, and cfgparser.h ----------------------------------------- These are Cs file that are used to build mkconfig program. The mkconfig program is used during the initial NuttX build. @@ -54,13 +38,11 @@ mkconfig.c, cfgparser.c, and cfgparser.h NuttX configuration that can be included by C files. cmdconfig.c ------------ This C file can be used to build a utility for comparing two NuttX configuration files. mkexport.sh and Makefile.export -------------------------------- These implement part of the top-level Makefile's 'export' target. That target will bundle up all of the NuttX libraries, header files, and the @@ -69,7 +51,6 @@ mkexport.sh and Makefile.export options from the top-level Make.defs file. mkfsdata.pl ------------ This perl script is used to build the "fake" file system and CGI support as needed for the apps/netutils/webserver. It is currently used only @@ -80,7 +61,6 @@ mkfsdata.pl by Adam Dunkels. uIP has a license that is compatible with NuttX. mkversion.c, cfgparser.c, and cfgparser.h ------------------------------------------ This is C file that is used to build mkversion program. The mkversion program is used during the initial NuttX build. @@ -94,7 +74,6 @@ mkversion.c, cfgparser.c, and cfgparser.h version.h provides version information that can be included by C files. mksyscall.c, cvsparser.c, and cvsparser.h ------------------------------------------ This is a C file that is used to build mksyscall program. The mksyscall program is used during the initial NuttX build by the logic in the top- @@ -117,7 +96,6 @@ mksyscall.c, cvsparser.c, and cvsparser.h stub files as output. See syscall/README.txt for additonal information. mksymtab.c, cvsparser.c, and cvsparser.h ----------------------------------------- This is a C file that is used to build symbol tables from common-separated value (CSV) files. This tool is not used during the NuttX build, but @@ -138,12 +116,10 @@ mksymtab.c, cvsparser.c, and cvsparser.h ./mksymtab.exe tmp.csv tmp.c pic32mx -------- This directory contains build tools used only for PIC32MX platforms bdf-convert.c -------------- This C file is used to build the bdf-converter program. The bdf-converter program be used to convert fonts in Bitmap Distribution Format (BDF) @@ -279,7 +255,6 @@ bdf-convert.c }; Makefile.host -------------- This is the makefile that is used to make the mkconfig program from the mkconfig.c C file, the cmpconfig program from cmpconfig.c C file @@ -290,25 +265,20 @@ Makefile.host make -f Makefile.host mkromfsimg.sh -------------- This script may be used to automate the generate of a ROMFS file system image. It accepts an rcS script "template" and generates and image that may be mounted under /etc in the NuttX pseudo file system. mkdeps.sh -mkdeps.bat -mkdeps.c mknulldeps.sh -------------- NuttX uses the GCC compilers capabilities to create Makefile dependencies. The bash script mkdeps.sh is used to run GCC in order to create the dependencies. If a NuttX configuration uses the GCC toolchain, its Make.defs file (see configs/README.txt) will include a line like: - MKDEP = $(TOPDIR)/tools/mkdeps.sh, or - MKDEP = $(TOPDIR)/tools/mkdeps[.exe] (See NOTE below) + MKDEP = $(TOPDIR)/tools/mkdeps.sh If the NuttX configuration does not use a GCC compatible toolchain, then it cannot use the dependencies and instead it uses mknulldeps.sh: @@ -317,61 +287,23 @@ mknulldeps.sh The mknulldeps.sh is a stub script that does essentially nothing. - NOTE: The mk*deps.* files are undergoing change. mkdeps.sh is a bash - script that produces dependencies well for POSIX style hosts (e..g., - Linux and Cygwin). It does not work well for mixed environments with - a Windows toolchain running in a POSIX style environemnt (hence, the - mknulldeps.sh script). And, of course, cannot be used in a Windows - nativ environment. - - [mkdeps.sh does have an option, --winpath, that purports to convert - the dependencies generated by a Windows toolchain to POSIX format. - However, that is not being used and mostly likely does not cover - all of the conversion cases.] - - mkdeps.bat is a simple port of the bash script to run in a Windows - command shell. However, it does not work well either because some - of the common CFLAGS use characters like '=' which are transformed - by the CMD.exe shell. - - mkdeps.c generates mkdeps (on Linux) or mkdeps.exe (on Windows). - However, this verison is still under-development. It works well in - the all POSIX environment or in the all Windows environment but also - does not work well in mixed POSIX environment with a Windows toolchain. - In that case, there are still issues with the conversion of things like - 'c:\Program Files' to 'c:program files' by bash. Those issues may, - eventually be solvable but for now continue to use mknulldeps.sh in - that mixed environment. - define.sh -define.bat ---------- Different compilers have different conventions for specifying pre- processor definitions on the compiler command line. This bash script allows the build system to create create command line definitions without concern for the particular compiler in use. - The define.bat script is a counterpart for use in the native Windows - build. - incdir.sh -incdir.bat ---------- Different compilers have different conventions for specifying lists - of include file paths on the the compiler command line. This incdir.sh - bash script allows the build system to create include file paths without + of include file paths on the the compiler command line. This bash + script allows the build system to create include file paths without concern for the particular compiler in use. - The incdir.bat script is a counterpart for use in the native Windows - build. However, there is currently only one compiler supported in - that context: MinGW-GCC. - link.sh winlink.sh unlink.sh ----------- Different file system have different capabilities for symbolic links. Some windows file systems have no native support for symbolic links. @@ -404,19 +336,16 @@ unlink.sh tried that mkimage.sh ----------- The creates a downloadable image as needed with the rrload bootloader. indent.sh ---------- This script can be used to indent .c and .h files in a manner similar to my coding NuttX coding style. It doesn't do a really good job, however (see the comments at the top of the indent.sh file). zipme.sh --------- I use this script to create the nuttx-xx.yy.tar.gz tarballs for release on SourceForge. It is handy because it also does the diff --git a/nuttx/tools/configure.sh b/nuttx/tools/configure.sh index ffa997178e..3b68fe3f62 100755 --- a/nuttx/tools/configure.sh +++ b/nuttx/tools/configure.sh @@ -100,54 +100,32 @@ if [ ! -d "${configpath}" ]; then exit 3 fi -src_makedefs="${configpath}/Make.defs" -dest_makedefs="${TOPDIR}/Make.defs" - -if [ ! -r "${src_makedefs}" ]; then - echo "File \"${src_makedefs}\" does not exist" +if [ ! -r "${configpath}/Make.defs" ]; then + echo "File \"${configpath}/Make.defs\" does not exist" exit 4 fi -src_setenv="${configpath}/setenv.sh" -unset have_setenv - -if [ -r "${src_setenv}" ]; then - dest_setenv=${TOPDIR}/setenv.sh - have_setenv=y -else - src_setenv="${configpath}/setenv.bat" - if [ -r "${src_setenv}" ]; then - dest_setenv=${TOPDIR}/setenv.bat - have_setenv=y - else - unset src_setenv - fi +if [ ! -r "${configpath}/setenv.sh" ]; then + echo "File \"${configpath}/setenv.sh\" does not exist" + exit 5 fi -src_config="${configpath}/defconfig" -tmp_config="${TOPDIR}/.configX" -dest_config="${TOPDIR}/.config" - -if [ ! -r "${src_config}" ]; then - echo "File \"${src_config}\" does not exist" +if [ ! -r "${configpath}/defconfig" ]; then + echo "File \"${configpath}/defconfig\" does not exist" exit 6 fi # Extract values needed from the defconfig file. We need: # (1) The CONFIG_NUTTX_NEWCONFIG setting to know if this is a "new" style -# configuration, -# (2) The CONFIG_WINDOWS_NATIVE setting to know it this is target for a -# native Windows (meaning that we want setenv.bat vs setenv.sh and we need -# to use backslashes in the CONFIG_APPS_DIR setting). -# (3) The CONFIG_APPS_DIR setting to see if there is a configured location for the -# application directory. This can be overridden from the command line. +# configuration, and +# (2) The CONFIG_APPS_DIR to see if there is a configured location for the +# application directory. -newconfig=`grep CONFIG_NUTTX_NEWCONFIG= "${src_config}" | cut -d'=' -f2` -winnative=`grep CONFIG_WINDOWS_NATIVE= "${src_config}" | cut -d'=' -f2` +newconfig=`grep CONFIG_NUTTX_NEWCONFIG= "${configpath}/defconfig" | cut -d'=' -f2` defappdir=y if [ -z "${appdir}" ]; then - quoted=`grep "^CONFIG_APPS_DIR=" "${src_config}" | cut -d'=' -f2` + quoted=`grep "^CONFIG_APPS_DIR=" "${configpath}/defconfig" | cut -d'=' -f2` if [ ! -z "${appdir}" ]; then appdir=`echo ${quoted} | sed -e "s/\"//g"` defappdir=n @@ -179,45 +157,34 @@ if [ -z "${appdir}" ]; then fi fi -# For checking the apps dir path, we need a POSIX version of the relative path. - -posappdir=`echo "${appdir}" | sed -e 's/\\\\/\\//g'` -winappdir=`echo "${appdir}" | sed -e 's/\\//\\\\/g'` - # If appsdir was provided (or discovered) then make sure that the apps/ # directory exists -if [ ! -z "${appdir}" -a ! -d "${TOPDIR}/${posappdir}" ]; then - echo "Directory \"${TOPDIR}/${posappdir}\" does not exist" +if [ ! -z "${appdir}" -a ! -d "${TOPDIR}/${appdir}" ]; then + echo "Directory \"${TOPDIR}/${appdir}\" does not exist" exit 7 fi # Okay... Everything looks good. Setup the configuration -install "${src_makedefs}" "${dest_makedefs}" || \ - { echo "Failed to copy \"${src_makedefs}\"" ; exit 7 ; } -if [ "X${have_setenv}" = "Xy" ]; then - install "${src_setenv}" "${dest_setenv}" || \ - { echo "Failed to copy ${src_setenv}" ; exit 8 ; } - chmod 755 "${dest_setenv}" -fi -install "${src_config}" "${tmp_config}" || \ - { echo "Failed to copy \"${src_config}\"" ; exit 9 ; } +install -C "${configpath}/Make.defs" "${TOPDIR}/." || \ + { echo "Failed to copy ${configpath}/Make.defs" ; exit 7 ; } +install -C "${configpath}/setenv.sh" "${TOPDIR}/." || \ + { echo "Failed to copy ${configpath}/setenv.sh" ; exit 8 ; } +chmod 755 "${TOPDIR}/setenv.sh" +install -C "${configpath}/defconfig" "${TOPDIR}/.configX" || \ + { echo "Failed to copy ${configpath}/defconfig" ; exit 9 ; } # If we did not use the CONFIG_APPS_DIR that was in the defconfig config file, # then append the correct application information to the tail of the .config # file if [ "X${defappdir}" = "Xy" ]; then - sed -i -e "/^CONFIG_APPS_DIR/d" "${tmp_config}" - echo "" >> "${tmp_config}" - echo "# Application configuration" >> "${tmp_config}" - echo "" >> "${tmp_config}" - if [ "X${winnative}" = "Xy" ]; then - echo "CONFIG_APPS_DIR=\"$winappdir\"" >> "${tmp_config}" - else - echo "CONFIG_APPS_DIR=\"$posappdir\"" >> "${tmp_config}" - fi + sed -i -e "/^CONFIG_APPS_DIR/d" "${TOPDIR}/.configX" + echo "" >> "${TOPDIR}/.configX" + echo "# Application configuration" >> "${TOPDIR}/.configX" + echo "" >> "${TOPDIR}/.configX" + echo "CONFIG_APPS_DIR=\"$appdir\"" >> "${TOPDIR}/.configX" fi # Copy appconfig file. The appconfig file will be copied to ${appdir}/.config @@ -228,7 +195,7 @@ if [ ! -z "${appdir}" -a "X${newconfig}" != "Xy" ]; then if [ ! -r "${configpath}/appconfig" ]; then echo "NOTE: No readable appconfig file found in ${configpath}" else - install "${configpath}/appconfig" "${TOPDIR}/${posappdir}/.config" || \ + install -C "${configpath}/appconfig" "${TOPDIR}/${appdir}/.config" || \ { echo "Failed to copy ${configpath}/appconfig" ; exit 10 ; } fi fi @@ -236,5 +203,6 @@ fi # install the final .configX only if it differs from any existing # .config file. -install "${tmp_config}" "${dest_config}" -rm -f "${tmp_config}" +install -C "${TOPDIR}/.configX" "${TOPDIR}/.config" +rm -f "${TOPDIR}/.configX" + diff --git a/nuttx/tools/define.sh b/nuttx/tools/define.sh index dc982cc648..c53cb92a83 100755 --- a/nuttx/tools/define.sh +++ b/nuttx/tools/define.sh @@ -1,7 +1,7 @@ #!/bin/bash # tools/define.sh # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -38,7 +38,7 @@ progname=$0 wintool=n -usage="USAGE: $progname [-w] [-d] [-h] [=val1] [[=val2] [[=val3] ...]]" +usage="USAGE: $progname [-w] [-d] [-l] [-h] [=val1] [[=val2] [[=val3] ...]]" advice="Try '$progname -h' for more information" while [ ! -z "$1" ]; do @@ -60,7 +60,7 @@ while [ ! -z "$1" ]; do echo " " echo " The full path to your compiler" echo " [ ..." - echo " A list of pre-preprocesser variable names to be defined." + echo " A list of pre-preprocesser variable names to be defind." echo " [=val1] [=val2] [=val3]" echo " optional values to be assigned to each pre-processor variable." echo " If not supplied, the variable will be defined with no explicit value." @@ -164,7 +164,7 @@ else fmt=std fi -# Now process each definition in the definition list +# Now process each directory in the directory list unset response for vardef in $varlist; do diff --git a/nuttx/tools/incdir.sh b/nuttx/tools/incdir.sh index 1e862aae12..be6a1d07a7 100755 --- a/nuttx/tools/incdir.sh +++ b/nuttx/tools/incdir.sh @@ -63,9 +63,6 @@ while [ ! -z "$1" ]; do echo " style pathnames like C:\\Program Files" echo " -d" echo " Enable script debug" - echo " -h" - echo " Shows this help text and exits." - exit 0 ;; * ) break; diff --git a/nuttx/tools/mkconfig.c b/nuttx/tools/mkconfig.c index 3e55f50974..2d2fff5c56 100644 --- a/nuttx/tools/mkconfig.c +++ b/nuttx/tools/mkconfig.c @@ -116,7 +116,7 @@ int main(int argc, char **argv, char **envp) printf(" * configured (at present, NXFLAT is the only supported binary.\n"); printf(" * format).\n"); printf(" */\n\n"); - printf("#if !defined(CONFIG_NXFLAT) && !defined(CONFIG_ELF)\n"); + printf("#if !defined(CONFIG_NXFLAT)\n"); printf("# undef CONFIG_BINFMT_DISABLE\n"); printf("# define CONFIG_BINFMT_DISABLE 1\n"); printf("#endif\n\n"); diff --git a/nuttx/tools/mkdeps.sh b/nuttx/tools/mkdeps.sh index 028fd1d9f5..acb6001509 100755 --- a/nuttx/tools/mkdeps.sh +++ b/nuttx/tools/mkdeps.sh @@ -2,7 +2,7 @@ ############################################################################ # tools/mkdeps.sh # -# Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without diff --git a/nuttx/tools/mkromfsimg.sh b/nuttx/tools/mkromfsimg.sh index 8811f19536..b774119800 100755 --- a/nuttx/tools/mkromfsimg.sh +++ b/nuttx/tools/mkromfsimg.sh @@ -233,7 +233,7 @@ mkdir -p $workingdir || { echo "Failed to created the new $workingdir"; exit 1; # Create the rcS file from the rcS.template if [ ! -r $rcstemplate ]; then - echo "$rcstemplate does not exist" + echo "$rcstemplete does not exist" rmdir $workingdir exit 1 fi diff --git a/nuttx/tools/mksymtab.c b/nuttx/tools/mksymtab.c index e401812c00..c5a46a92be 100644 --- a/nuttx/tools/mksymtab.c +++ b/nuttx/tools/mksymtab.c @@ -222,7 +222,7 @@ int main(int argc, char **argv, char **envp) fprintf(outstream, "/* %s: Auto-generated symbol table. Do not edit */\n\n", symtab); fprintf(outstream, "#include \n"); - fprintf(outstream, "#include \n\n"); + fprintf(outstream, "#include \n\n"); /* Output all of the require header files */ From cc582b2b4411eccae3b077b1095a2a34b6f59c06 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 28 Dec 2012 13:10:58 +0100 Subject: [PATCH 195/206] Only send actuator HIL commands if armed --- apps/mavlink/orb_listener.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index 971ba6a8ea..40e52a5005 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -455,7 +455,7 @@ l_actuator_outputs(struct listener *l) act_outputs.output[7]); /* only send in HIL mode */ - if (mavlink_hil_enabled) { + if (mavlink_hil_enabled && armed.armed) { /* translate the current syste state to mavlink state and mode */ uint8_t mavlink_state = 0; From 38a1076a33bd30eae05882460fcd69ae1a6aff4b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 28 Dec 2012 13:12:27 +0100 Subject: [PATCH 196/206] Cleaned up attitude control in HIL, implemented very simple guided / stabilized mode with just attitude stabilization --- apps/drivers/hil/hil.cpp | 3 -- .../fixedwing_att_control_main.c | 48 ++++++++++++++++++- 2 files changed, 46 insertions(+), 5 deletions(-) diff --git a/apps/drivers/hil/hil.cpp b/apps/drivers/hil/hil.cpp index 276a642fd0..3c6355d6ea 100644 --- a/apps/drivers/hil/hil.cpp +++ b/apps/drivers/hil/hil.cpp @@ -429,9 +429,6 @@ HIL::task_main() /* get new value */ orb_copy(ORB_ID(actuator_armed), _t_armed, &aa); - - /* update PWM servo armed status */ - // up_pwm_servo_arm(aa.armed); } } diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index 9c450e68ec..5ededa2e35 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -198,6 +198,48 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) /* set flaps to zero */ actuators.control[4] = 0.0f; + } else if (vstatus.state_machine == SYSTEM_STATE_STABILIZED) { + + /* if the RC signal is lost, try to stay level and go slowly back down to ground */ + if(vstatus.rc_signal_lost) { + + // XXX define failsafe throttle param + //param_get(failsafe_throttle_handle, &failsafe_throttle); + att_sp.roll_body = 0.3f; + att_sp.pitch_body = 0.0f; + att_sp.yaw_body = 0; + att_sp.thrust = 0.4f; + + // XXX disable yaw control, loiter + + } else { + + att_sp.roll_body = manual_sp.roll; + att_sp.pitch_body = manual_sp.pitch; + att_sp.yaw_body = 0; + att_sp.thrust = manual_sp.throttle; + } + + att_sp.timestamp = hrt_absolute_time(); + + // XXX: Stop copying setpoint / reference from bus, instead keep position + // and mix RC inputs in. + // XXX: For now just stabilize attitude, not anything else + // proper implementation should do stabilization in position controller + // and just check for stabilized or auto state + + /* attitude control */ + fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp); + + /* angular rate control */ + fixedwing_att_control_rates(&rates_sp, gyro, &actuators); + + /* pass through throttle */ + actuators.control[3] = att_sp.thrust; + + /* set flaps to zero */ + actuators.control[4] = 0.0f; + } else { if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { @@ -208,7 +250,8 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) //param_get(failsafe_throttle_handle, &failsafe_throttle); att_sp.roll_body = 0.3f; att_sp.pitch_body = 0.0f; - att_sp.thrust = 0.5f; + att_sp.thrust = 0.4f; + att_sp.yaw_body = 0; // XXX disable yaw control, loiter @@ -218,9 +261,10 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) att_sp.pitch_body = manual_sp.pitch; att_sp.yaw_body = 0; att_sp.thrust = manual_sp.throttle; - att_sp.timestamp = hrt_absolute_time(); } + att_sp.timestamp = hrt_absolute_time(); + /* attitude control */ fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp); From e01c0e1de654c89ac2b885a69d3c47f91e2a73d6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 28 Dec 2012 13:13:30 +0100 Subject: [PATCH 197/206] Reverting more nuttx merge --- .gitignore | 4 ---- 1 file changed, 4 deletions(-) diff --git a/.gitignore b/.gitignore index b91311ce85..ea416fae48 100644 --- a/.gitignore +++ b/.gitignore @@ -40,7 +40,3 @@ nsh_romfsimg.h cscope.out .configX-e nuttx-export.zip -nuttx/tools/mkconfig.dSYM -nuttx/tools/mkversion.dSYM -nuttx/tools/mkdeps.dSYM -nuttx/tools/mkdeps From d96add5b61a35fbbf08ade0ddd14673c437b6b65 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 28 Dec 2012 13:16:34 +0100 Subject: [PATCH 198/206] Even more cleanup, diff now clean --- apps/COPYING | 137 --------------------------------------------- apps/ChangeLog.txt | 56 +----------------- 2 files changed, 1 insertion(+), 192 deletions(-) delete mode 100644 apps/COPYING diff --git a/apps/COPYING b/apps/COPYING deleted file mode 100644 index 7e8fd8407a..0000000000 --- a/apps/COPYING +++ /dev/null @@ -1,137 +0,0 @@ -COPYING -- Describes the terms under which Nuttx is distributed. A -copy of the BSD-style licensing is included in this file. In my -words -- I believe that you should free to use NuttX in any -environment, private, private, commercial, open, closed, etc. -provided only that you repect the modest copyright notices as -described in license (below). Please feel free to contact me if you -have any licensing concerns. - -NuttX -^^^^^^ - -License for NuttX in general (authorship of individual files may vary): - - Copyright (C) 2007-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. - -uIP -^^^ - -Some lower-level networking middle-ware components of NuttX -derive from uIP which has a similar BSD style license: - - Copyright (c) 2001-2003, Adam Dunkels. - All rights reserved. - -FreeModbus -^^^^^^^^^ - -FreeModbus Libary: A portable Modbus implementation for Modbus ASCII/RTU. -Copyright (c) 2006 Christian Walter -All rights reserved. - -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. The name of the author may not be used to endorse or promote products - derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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. - -THTTPD -^^^^^^ - -Derived from the original THTTPD package: - - Copyright © 1995,1998,1999,2000,2001 by Jef Poskanzer . - All rights reserved. - -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. - -THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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. - -cJSON -^^^^^ - -Derives from the cJSON Project which has an MIT license: - - Copyright (c) 2009 Dave Gamble - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in -all copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN -THE SOFTWARE. - diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index c1c5189c43..7375adccfc 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -349,7 +349,7 @@ * apps/NxWidgets/Kconfig: Add option to turn on the memory monitor feature of the NxWidgets/NxWM unit tests. -6.23 2012-11-05 Gregory Nutt +6.23 2012-xx-xx Gregory Nutt * vsn: Moved all NSH commands from vsn/ to system/. Deleted the vsn/ directory. @@ -368,57 +368,3 @@ 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) - * apps/nshlib/nsh_telnetd.c: Add support for login to Telnet session via - username and password (Darcy Gong). - * apps/netutils/resolv/resolv.c (and files using the DNS resolver): Various - DNS address resolution improvements from Darcy Gong. - * apps/nshlib/nsh_netcmds.c: The ping command now passes a maximum round - trip time to uip_icmpping(). This allows pinging of hosts on complex - networks where the ICMP ECHO round trip time may exceed the ping interval. - * apps/examples/nxtext/nxtext_main.c: Fix bad conditional compilation - when CONFIG_NX_KBD is not defined. Submitted by Petteri Aimonen. - * apps/examples/nximage/nximage_main.c: Add a 5 second delay after the - NX logo is presented so that there is time for the image to be verified. - Suggested by Petteri Aimonen. - * apps/Makefile: Small change that reduces the number of shell invocations - by one (Mike Smith). - * apps/examples/elf: Test example for the ELF loader. - * apps/examples/elf: The ELF module test example appears fully functional. - * apps/netutils/json: Add a snapshot of the cJSON project. Contributed by - Darcy Gong. - * apps/examples/json: Test example for cJSON from Darcy Gong - * apps/nshlib/nsh_netinit.c: Fix static IP DNS problem (Darcy Gong) - * apps/netutils/resolv/resolv.c: DNS fixes from Darcy Gong. - * COPYING: Licensing information added. - * apps/netutils/codec and include/netutils/urldecode.h, base64.h, and md5.h: - A port of the BASE46, MD5 and URL CODEC library from Darcy Gong. - * nsnlib/nsh_codeccmd.c: NSH commands to use the CODEC library. - Contributed by Darcy Gong. - * apps/examples/wgetjson: Test example contributed by Darcy Gong - * apps/examples/cxxtest: A test for the uClibc++ library provided by - Qiang Yu and the RGMP team. - * apps/netutils/webclient, apps/netutils.codes, and apps/examples/wgetjson: - Add support for wget POST interface. Contributed by Darcy Gong. - * apps/examples/relays: A relay example contributed by Darcy Gong. - * apps/nshlib/nsh_netcmds: Add ifup and ifdown commands (from Darcy - Gong). - * apps/nshlib/nsh_netcmds: Extend the ifconfig command so that it - supports setting IP addresses, network masks, name server addresses, - and hardware address (from Darcy Gong). - -6.24 2012-xx-xx Gregory Nutt - - * apps/examples/ostest/roundrobin.c: Replace large tables with - algorithmic prime number generation. This allows the roundrobin - test to run on platforms with minimal SRAM (Freddie Chopin). - * apps/nshlib/nsh_dbgcmds.c: Add hexdump command to dump the contents - of a file (or character device) to the console Contributed by Petteri - Aimonen. - * apps/examples/modbus: Fixes from Freddie Chopin - * apps/examples/modbus/Kconfig: Kconfig logic for FreeModBus contributed - by Freddie Chopin. - * Makefile, */Makefile: Various fixes for Windows native build. Now uses - make foreach loops instead of shell loops. - * apps/examples/elf/test/*/Makefile: OSX doesn't support install -D, use - mkdir -p then install without the -D. From Mike Smith. - From a1e1e7bf426140ab13f9085dbb02bc58e4b3a1ab Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 28 Dec 2012 13:18:52 +0100 Subject: [PATCH 199/206] Cleaning up calibration requests --- apps/commander/commander.c | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index e0ee500dc2..50544320bf 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -881,10 +881,10 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT); if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { - mavlink_log_info(mavlink_fd, "[cmd] CMD starting gyro calibration"); + mavlink_log_info(mavlink_fd, "[cmd] starting gyro calibration"); tune_confirm(); do_gyro_calibration(status_pub, ¤t_status); - mavlink_log_info(mavlink_fd, "[cmd] CMD finished gyro calibration"); + mavlink_log_info(mavlink_fd, "[cmd] finished gyro calibration"); tune_confirm(); do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_STANDBY); result = MAV_RESULT_ACCEPTED; @@ -901,15 +901,15 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT); if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { - mavlink_log_info(mavlink_fd, "[cmd] CMD starting mag calibration"); + mavlink_log_info(mavlink_fd, "[cmd] starting mag calibration"); tune_confirm(); do_mag_calibration(status_pub, ¤t_status); - mavlink_log_info(mavlink_fd, "[cmd] CMD finished mag calibration"); + mavlink_log_info(mavlink_fd, "[cmd] finished mag calibration"); tune_confirm(); do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_STANDBY); result = MAV_RESULT_ACCEPTED; } else { - mavlink_log_critical(mavlink_fd, "[cmd] CMD REJECTING mag calibration"); + mavlink_log_critical(mavlink_fd, "[cmd] REJECTING mag calibration"); result = MAV_RESULT_DENIED; } handled = true; @@ -921,10 +921,10 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT); if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { - mavlink_log_info(mavlink_fd, "[cmd] zero altitude not implemented"); + mavlink_log_info(mavlink_fd, "[cmd] zero altitude cal. not implemented"); tune_confirm(); } else { - mavlink_log_critical(mavlink_fd, "[cmd] CMD REJECTING mag calibration"); + mavlink_log_critical(mavlink_fd, "[cmd] REJECTING altitude calibration"); result = MAV_RESULT_DENIED; } handled = true; @@ -936,15 +936,15 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT); if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { - mavlink_log_info(mavlink_fd, "[cmd] CMD starting mag calibration"); + mavlink_log_info(mavlink_fd, "[cmd] starting trim calibration"); tune_confirm(); do_rc_calibration(status_pub, ¤t_status); - mavlink_log_info(mavlink_fd, "[cmd] CMD finished mag calibration"); + mavlink_log_info(mavlink_fd, "[cmd] finished trim calibration"); tune_confirm(); do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_STANDBY); result = MAV_RESULT_ACCEPTED; } else { - mavlink_log_critical(mavlink_fd, "[cmd] CMD REJECTING mag calibration"); + mavlink_log_critical(mavlink_fd, "[cmd] REJECTING trim calibration"); result = MAV_RESULT_DENIED; } handled = true; From 913f5a78120e9404bacca63ace966c028b51bffc Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 28 Dec 2012 15:06:19 +0100 Subject: [PATCH 200/206] Cleared last diff items between origin/master and fixedwing_outdoor --- apps/examples/Kconfig | 157 +++++++++++++++++- apps/examples/Make.defs | 24 --- apps/examples/Makefile | 49 +++--- apps/examples/README.txt | 161 ++---------------- apps/examples/adc/Makefile | 21 ++- apps/examples/adc/adc_main.c | 7 +- apps/examples/buttons/Makefile | 21 ++- apps/examples/can/Makefile | 21 ++- apps/examples/cdcacm/Makefile | 19 +-- apps/examples/hello/Makefile | 19 +-- apps/examples/helloxx/Makefile | 23 ++- apps/examples/mm/Makefile | 21 ++- apps/examples/mount/Makefile | 21 ++- apps/examples/nsh/Makefile | 21 ++- apps/examples/null/Makefile | 21 ++- apps/examples/ostest/Kconfig | 27 ---- apps/examples/ostest/Makefile | 19 +-- apps/examples/ostest/roundrobin.c | 156 ++++++++++-------- apps/examples/pipe/Makefile | 21 ++- apps/examples/poll/Makefile | 22 ++- apps/examples/pwm/Makefile | 21 ++- apps/examples/pwm/pwm_main.c | 1 - apps/examples/qencoder/Makefile | 19 +-- apps/examples/romfs/Makefile | 24 ++- apps/examples/serloop/Makefile | 21 ++- apps/examples/watchdog/Makefile | 19 +-- apps/interpreters/Makefile | 32 ++-- apps/interpreters/ficl/Makefile | 29 ++-- apps/namedapp/Makefile | 32 ++-- apps/nshlib/Kconfig | 100 +----------- apps/nshlib/Makefile | 61 ++++--- apps/nshlib/README.txt | 74 ++------- apps/nshlib/nsh.h | 77 +-------- apps/nshlib/nsh_dbgcmds.c | 61 +------ apps/nshlib/nsh_netcmds.c | 260 +++--------------------------- apps/nshlib/nsh_netinit.c | 12 +- apps/nshlib/nsh_parse.c | 63 ++------ apps/system/Makefile | 33 ++-- apps/system/free/Makefile | 28 ++-- apps/system/i2c/Makefile | 27 ++-- apps/system/install/Makefile | 27 ++-- apps/system/readline/Makefile | 24 ++- 42 files changed, 629 insertions(+), 1267 deletions(-) diff --git a/apps/examples/Kconfig b/apps/examples/Kconfig index c0d126ad47..865268addb 100644 --- a/apps/examples/Kconfig +++ b/apps/examples/Kconfig @@ -3,59 +3,206 @@ # see misc/tools/kconfig-language.txt. # +menu "ADC Example" source "$APPSDIR/examples/adc/Kconfig" +endmenu + +menu "Buttons Example" source "$APPSDIR/examples/buttons/Kconfig" +endmenu + +menu "CAN Example" source "$APPSDIR/examples/can/Kconfig" +endmenu + +menu "USB CDC/ACM Class Driver Example" source "$APPSDIR/examples/cdcacm/Kconfig" +endmenu + +menu "USB composite Class Driver Example" source "$APPSDIR/examples/composite/Kconfig" -source "$APPSDIR/examples/cxxtest/Kconfig" +endmenu + +menu "DHCP Server Example" source "$APPSDIR/examples/dhcpd/Kconfig" -source "$APPSDIR/examples/elf/Kconfig" +endmenu + +menu "FTP Client Example" source "$APPSDIR/examples/ftpc/Kconfig" +endmenu + +menu "FTP Server Example" source "$APPSDIR/examples/ftpd/Kconfig" +endmenu + +menu "\"Hello, World!\" Example" source "$APPSDIR/examples/hello/Kconfig" +endmenu + +menu "\"Hello, World!\" C++ Example" source "$APPSDIR/examples/helloxx/Kconfig" -source "$APPSDIR/examples/json/Kconfig" +endmenu + +menu "USB HID Keyboard Example" source "$APPSDIR/examples/hidkbd/Kconfig" +endmenu + +menu "IGMP Example" source "$APPSDIR/examples/igmp/Kconfig" +endmenu + +menu "LCD Read/Write Example" source "$APPSDIR/examples/lcdrw/Kconfig" +endmenu + +menu "Memory Management Example" source "$APPSDIR/examples/mm/Kconfig" +endmenu + +menu "File System Mount Example" source "$APPSDIR/examples/mount/Kconfig" +endmenu + +menu "FreeModBus Example" source "$APPSDIR/examples/modbus/Kconfig" +endmenu + +menu "Network Test Example" source "$APPSDIR/examples/nettest/Kconfig" +endmenu + +menu "NuttShell (NSH) Example" source "$APPSDIR/examples/nsh/Kconfig" +endmenu + +menu "NULL Example" source "$APPSDIR/examples/null/Kconfig" +endmenu + +menu "NX Graphics Example" source "$APPSDIR/examples/nx/Kconfig" +endmenu + +menu "NxConsole Example" source "$APPSDIR/examples/nxconsole/Kconfig" +endmenu + +menu "NXFFS File System Example" source "$APPSDIR/examples/nxffs/Kconfig" +endmenu + +menu "NXFLAT Example" source "$APPSDIR/examples/nxflat/Kconfig" +endmenu + +menu "NX Graphics \"Hello, World!\" Example" source "$APPSDIR/examples/nxhello/Kconfig" +endmenu + +menu "NX Graphics image Example" source "$APPSDIR/examples/nximage/Kconfig" +endmenu + +menu "NX Graphics lines Example" source "$APPSDIR/examples/nxlines/Kconfig" +endmenu + +menu "NX Graphics Text Example" source "$APPSDIR/examples/nxtext/Kconfig" +endmenu + +menu "OS Test Example" source "$APPSDIR/examples/ostest/Kconfig" +endmenu + +menu "Pascal \"Hello, World!\"example" source "$APPSDIR/examples/pashello/Kconfig" +endmenu + +menu "Pipe Example" source "$APPSDIR/examples/pipe/Kconfig" +endmenu + +menu "Poll Example" source "$APPSDIR/examples/poll/Kconfig" +endmenu + +menu "Pulse Width Modulation (PWM) Example" source "$APPSDIR/examples/pwm/Kconfig" +endmenu + +menu "Quadrature Encoder Example" source "$APPSDIR/examples/qencoder/Kconfig" -source "$APPSDIR/examples/relays/Kconfig" +endmenu + +menu "RGMP Example" source "$APPSDIR/examples/rgmp/Kconfig" +endmenu + +menu "ROMFS Example" source "$APPSDIR/examples/romfs/Kconfig" +endmenu + +menu "sendmail Example" source "$APPSDIR/examples/sendmail/Kconfig" +endmenu + +menu "Serial Loopback Example" source "$APPSDIR/examples/serloop/Kconfig" +endmenu + +menu "Telnet Daemon Example" source "$APPSDIR/examples/telnetd/Kconfig" +endmenu + +menu "THTTPD Web Server Example" source "$APPSDIR/examples/thttpd/Kconfig" +endmenu + +menu "TIFF Generation Example" source "$APPSDIR/examples/tiff/Kconfig" +endmenu + +menu "Touchscreen Example" source "$APPSDIR/examples/touchscreen/Kconfig" +endmenu + +menu "UDP Example" source "$APPSDIR/examples/udp/Kconfig" +endmenu + +menu "UDP Discovery Daemon Example" source "$APPSDIR/examples/discover/Kconfig" +endmenu + +menu "uIP Web Server Example" source "$APPSDIR/examples/uip/Kconfig" +endmenu + +menu "USB Serial Test Example" source "$APPSDIR/examples/usbserial/Kconfig" +endmenu + +menu "USB Mass Storage Class Example" source "$APPSDIR/examples/usbstorage/Kconfig" +endmenu + +menu "USB Serial Terminal Example" source "$APPSDIR/examples/usbterm/Kconfig" +endmenu + +menu "Watchdog timer Example" source "$APPSDIR/examples/watchdog/Kconfig" +endmenu + +menu "wget Example" source "$APPSDIR/examples/wget/Kconfig" -source "$APPSDIR/examples/wgetjson/Kconfig" +endmenu + +menu "WLAN Example" source "$APPSDIR/examples/wlan/Kconfig" +endmenu + +menu "XML RPC Example" source "$APPSDIR/examples/xmlrpc/Kconfig" +endmenu diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index 3d95ccb16d..d03b976d25 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -54,10 +54,6 @@ ifeq ($(CONFIG_EXAMPLES_COMPOSITE),y) CONFIGURED_APPS += examples/composite endif -ifeq ($(CONFIG_EXAMPLES_CXXTEST),y) -CONFIGURED_APPS += examples/cxxtest -endif - ifeq ($(CONFIG_EXAMPLES_DHCPD),y) CONFIGURED_APPS += examples/dhcpd endif @@ -66,10 +62,6 @@ ifeq ($(CONFIG_EXAMPLES_DISCOVER),y) CONFIGURED_APPS += examples/discover endif -ifeq ($(CONFIG_EXAMPLES_ELF),y) -CONFIGURED_APPS += examples/elf -endif - ifeq ($(CONFIG_EXAMPLES_FTPC),y) CONFIGURED_APPS += examples/ftpc endif @@ -94,10 +86,6 @@ ifeq ($(CONFIG_EXAMPLES_IGMP),y) CONFIGURED_APPS += examples/igmp endif -ifeq ($(CONFIG_EXAMPLES_JSON),y) -CONFIGURED_APPS += examples/json -endif - ifeq ($(CONFIG_EXAMPLES_LCDRW),y) CONFIGURED_APPS += examples/lcdrw endif @@ -106,10 +94,6 @@ ifeq ($(CONFIG_EXAMPLES_MM),y) CONFIGURED_APPS += examples/mm endif -ifeq ($(CONFIG_EXAMPLES_MODBUS),y) -CONFIGURED_APPS += examples/modbus -endif - ifeq ($(CONFIG_EXAMPLES_MOUNT),y) CONFIGURED_APPS += examples/mount endif @@ -182,10 +166,6 @@ ifeq ($(CONFIG_EXAMPLES_QENCODER),y) CONFIGURED_APPS += examples/qencoder endif -ifeq ($(CONFIG_EXAMPLES_RELAYS),y) -CONFIGURED_APPS += examples/relays -endif - ifeq ($(CONFIG_EXAMPLES_RGMP),y) CONFIGURED_APPS += examples/rgmp endif @@ -246,10 +226,6 @@ ifeq ($(CONFIG_EXAMPLES_WGET),y) CONFIGURED_APPS += examples/wget endif -ifeq ($(CONFIG_EXAMPLES_WGETJSON),y) -CONFIGURED_APPS += examples/wgetjson -endif - ifeq ($(CONFIG_EXAMPLES_WLAN),y) CONFIGURED_APPS += examples/wlan endif diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 9d20e9312d..453f99ce71 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -37,12 +37,12 @@ # Sub-directories -SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf ftpc -SUBDIRS += ftpd hello helloxx hidkbd igmp json lcdrw mm modbus mount -SUBDIRS += nettest nsh null nx nxconsole nxffs nxflat nxhello nximage -SUBDIRS += nxlines nxtext ostest pashello pipe poll pwm qencoder relays -SUBDIRS += rgmp romfs serloop telnetd thttpd tiff touchscreen udp uip -SUBDIRS += usbserial sendmail usbstorage usbterm watchdog wget wgetjson wlan +SUBDIRS = adc buttons can cdcacm composite dhcpd discover ftpc ftpd hello +SUBDIRS += helloxx hidkbd igmp lcdrw mm modbus mount nettest nsh null nx +SUBDIRS += nxconsole nxffs nxflat nxhello nximage nxlines nxtext ostest +SUBDIRS += pashello pipe poll pwm qencoder rgmp romfs serloop telnetd +SUBDIRS += thttpd tiff touchscreen udp uip usbserial sendmail usbstorage +SUBDIRS += usbterm watchdog wget wlan # Sub-directories that might need context setup. Directories may need # context setup for a variety of reasons, but the most common is because @@ -57,8 +57,8 @@ SUBDIRS += usbserial sendmail usbstorage usbterm watchdog wget wgetjson wlan CNTXTDIRS = pwm ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) -CNTXTDIRS += adc can cdcacm composite cxxtestdhcpd discover ftpd json -CNTXTDIRS += modbus nettest nxlines relays qencoder telnetd watchdog wgetjson +CNTXTDIRS += adc can cdcacm composite discover ftpd dhcpd modbus nettest +CNTXTDIRS += qencoder telnetd watchdog endif ifeq ($(CONFIG_EXAMPLES_HELLO_BUILTIN),y) @@ -79,6 +79,9 @@ endif ifeq ($(CONFIG_EXAMPLES_NXIMAGE_BUILTIN),y) CNTXTDIRS += nximage endif +ifeq ($(CONFIG_EXAMPLES_LINES_BUILTIN),y) +CNTXTDIRS += nxlines +endif ifeq ($(CONFIG_EXAMPLES_NXTEXT_BUILTIN),y) CNTXTDIRS += nxtext endif @@ -102,25 +105,27 @@ all: nothing .PHONY: nothing context depend clean distclean -define SDIR_template -$(1)_$(2): - $(Q) $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" -endef - -$(foreach SDIR, $(CNTXTDIRS), $(eval $(call SDIR_template,$(SDIR),context))) -$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),depend))) -$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),clean))) -$(foreach SDIR, $(SUBDIRS), $(eval $(call SDIR_template,$(SDIR),distclean))) - nothing: -context: $(foreach SDIR, $(CNTXTDIRS), $(SDIR)_context) +context: + @for dir in $(CNTXTDIRS) ; do \ + $(MAKE) -C $$dir context TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ + done -depend: $(foreach SDIR, $(SUBDIRS), $(SDIR)_depend) +depend: + @for dir in $(SUBDIRS) ; do \ + $(MAKE) -C $$dir depend TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ + done -clean: $(foreach SDIR, $(SUBDIRS), $(SDIR)_clean) +clean: + @for dir in $(SUBDIRS) ; do \ + $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ + done -distclean: clean $(foreach SDIR, $(SUBDIRS), $(SDIR)_distclean) +distclean: clean + @for dir in $(SUBDIRS) ; do \ + $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ + done -include Make.dep diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 1463b0253f..763427e326 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -239,29 +239,6 @@ examples/composite CONFIG_EXAMPLES_COMPOSITE_TRACEINTERRUPTS Show interrupt-related events. -examples/cxxtest -^^^^^^^^^^^^^^^^ - - This is a test of the C++ standard library. At present a port of the uClibc++ - C++ library is available. Due to licensinging issues, the uClibc++ C++ library - is not included in the NuttX source tree by default, but must be installed - (see misc/uClibc++/README.txt for installation). - - The NuttX setting that are required include: - - CONFIG_HAVE_CXX=y - CONFIG_HAVE_CXXINITIALIZE=y - CONFIG_UCLIBCXX=y - - Additional uClibc++ settings may be required in your build environment. - - The uClibc++ test includes simple test of: - - - iostreams, - - STL, - - RTTI, and - - Exceptions - examples/dhcpd ^^^^^^^^^^^^^^ @@ -320,68 +297,6 @@ examples/discover CONFIG_EXAMPLES_DISCOVER_DRIPADDR - Router IP address CONFIG_EXAMPLES_DISCOVER_NETMASK - Network Mask -examples/elf -^^^^^^^^^^^^ - - This example builds a small ELF loader test case. This includes several - test programs under examples/elf tests. These tests are build using - the relocatable ELF format and installed in a ROMFS file system. At run time, - each program in the ROMFS file system is executed. Requires CONFIG_ELF. - Other configuration options: - - CONFIG_EXAMPLES_ELF_DEVMINOR - The minor device number of the ROMFS block. - For example, the N in /dev/ramN. Used for registering the RAM block driver - that will hold the ROMFS file system containing the ELF executables to be - tested. Default: 0 - - CONFIG_EXAMPLES_ELF_DEVPATH - The path to the ROMFS block driver device. This - must match EXAMPLES_ELF_DEVMINOR. Used for registering the RAM block driver - that will hold the ROMFS file system containing the ELF executables to be - tested. Default: "/dev/ram0" - - NOTES: - - 1. CFLAGS should be provided in CELFFLAGS. RAM and FLASH memory regions - may require long allcs. For ARM, this might be: - - CELFFLAGS = $(CFLAGS) -mlong-calls - - Similarly for C++ flags which must be provided in CXXELFFLAGS. - - 2. Your top-level nuttx/Make.defs file must alos include an approproate definition, - LDELFFLAGS, to generate a relocatable ELF object. With GNU LD, this should - include '-r' and '-e main' (or _main on some platforms). - - LDELFFLAGS = -r -e main - - If you use GCC to link, you make also need to include '-nostdlib' or - '-nostartfiles' and '-nodefaultlibs'. - - 3. This example also requires genromfs. genromfs can be build as part of the - nuttx toolchain. Or can built from the genromfs sources that can be found - at misc/tools/genromfs-0.5.2.tar.gz. In any event, the PATH variable must - include the path to the genromfs executable. - - 4. ELF size: The ELF files in this example are, be default, quite large - because they include a lot of "build garbage". You can greatly reduce the - size of the ELF binaries are using the 'objcopy --strip-unneeded' command to - remove un-necessary information from the ELF files. - - 5. Simulator. You cannot use this example with the the NuttX simulator on - Cygwin. That is because the Cygwin GCC does not generate ELF file but - rather some Windows-native binary format. - - If you really want to do this, you can create a NuttX x86 buildroot toolchain - and use that be build the ELF executables for the ROMFS file system. - - 6. Linker scripts. You might also want to use a linker scripts to combine - sections better. An example linker script is at nuttx/binfmt/libelf/gnu-elf.ld. - That example might have to be tuned for your particular linker output to - position additional sections correctly. The GNU LD LDELFFLAGS then might - be: - - LDELFFLAGS = -r -e main -T$(TOPDIR)/binfmt/libelf/gnu-elf.ld - examples/ftpc ^^^^^^^^^^^^^ @@ -567,19 +482,6 @@ examples/igmp CONFIGURED_APPS += uiplib -examples/json -^^^^^^^^^^^^^ - - This example exercises the cJSON implementation at apps/netutils/json. - This example contains logic taken from the cJSON project: - - http://sourceforge.net/projects/cjson/ - - The example corresponds to SVN revision r42 (with lots of changes for - NuttX coding standards). As of r42, the SVN repository was last updated - on 2011-10-10 so I presume that the code is stable and there is no risk - of maintaining duplicate logic in the NuttX repository. - examples/lcdrw ^^^^^^^^^^^^^^ @@ -594,11 +496,6 @@ examples/lcdrw * CONFIG_EXAMPLES_LDCRW_YRES LCD Y resolution. Default: 320 - NOTE: This test exercises internal lcd driver interfaces. As such, it - relies on internal OS interfaces that are not normally available to a - user-space program. As a result, this example cannot be used if a - NuttX is built as a protected, supervisor kernel (CONFIG_NUTTX_KERNEL). - examples/mm ^^^^^^^^^^^ @@ -941,6 +838,8 @@ examplex/nxlines The following configuration options can be selected: + CONFIG_EXAMPLES_NXLINES_BUILTIN -- Build the NXLINES example as a "built-in" + that can be executed from the NSH command line CONFIG_EXAMPLES_NXLINES_VPLANE -- The plane to select from the frame- buffer driver for use in the test. Default: 0 CONFIG_EXAMPLES_NXLINES_DEVNO - The LCD device to select from the LCD @@ -978,9 +877,6 @@ examplex/nxlines FAR struct fb_vtable_s *up_nxdrvinit(unsigned int devno); #endif - CONFIG_NSH_BUILTIN_APPS - Build the NX lines examples as an NSH built-in - function. - examples/nxtext ^^^^^^^^^^^^^^^ @@ -1088,17 +984,6 @@ examples/ostest Specifies the number of threads to create in the barrier test. The default is 8 but a smaller number may be needed on systems without sufficient memory to start so many threads. - * CONFIG_EXAMPLES_OSTEST_RR_RANGE - During round-robin scheduling test two threads are created. Each of the threads - searches for prime numbers in the configurable range, doing that configurable - number of times. - This value specifies the end of search range and together with number of runs - allows to configure the length of this test - it should last at least a few - tens of seconds. Allowed values [1; 32767], default 10000 - * CONFIG_EXAMPLES_OSTEST_RR_RUNS - During round-robin scheduling test two threads are created. Each of the threads - searches for prime numbers in the configurable range, doing that configurable - number of times. examples/pashello ^^^^^^^^^^^^^^^^^ @@ -1225,28 +1110,17 @@ examples/qencoder Specific configuration options for this example include: - CONFIG_EXAMPLES_QENCODER_DEVPATH - The path to the QE device. Default: - /dev/qe0 - CONFIG_EXAMPLES_QENCODER_NSAMPLES - If CONFIG_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: Samples are collected - indefinitely. - CONFIG_EXAMPLES_QENCODER_DELAY - This value provides the delay (in - milliseonds) between each sample. If CONFIG_NSH_BUILTIN_APPS - is defined, then this value is the default delay if no other delay is - provided on the command line. Default: 100 milliseconds - -examples/relays -^^^^^^^^^^^^^^^ - - Requires CONFIG_ARCH_RELAYS. - Contributed by Darcy Gong. - - NOTE: This test exercises internal relay driver interfaces. As such, it - relies on internal OS interfaces that are not normally available to a - user-space program. As a result, this example cannot be used if a - NuttX is built as a protected, supervisor kernel (CONFIG_NUTTX_KERNEL). + CONFIG_EXAMPLES_QENCODER_DEVPATH - The path to the QE device. Default: + /dev/qe0 + CONFIG_EXAMPLES_QENCODER_NSAMPLES - If CONFIG_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: Samples are collected + indefinitely. + CONFIG_EXAMPLES_QENCODER_DELAY - This value provides the delay (in + milliseonds) between each sample. If CONFIG_NSH_BUILTIN_APPS + is defined, then this value is the default delay if no other delay is + provided on the command line. Default: 100 milliseconds examples/rgmp ^^^^^^^^^^^^^ @@ -1798,16 +1672,7 @@ examples/wget CONFIGURED_APPS += resolv CONFIGURED_APPS += webclient -examples/wget -^^^^^^^^^^^^^ - - Uses wget to get a JSON encoded file, then decodes the file. - - CONFIG_EXAMPLES_WDGETJSON_MAXSIZE - Max. JSON Buffer Size - CONFIG_EXAMPLES_EXAMPLES_WGETJSON_URL - wget URL - examples/xmlrpc -^^^^^^^^^^^^^^^ This example exercises the "Embeddable Lightweight XML-RPC Server" which is discussed at: diff --git a/apps/examples/adc/Makefile b/apps/examples/adc/Makefile index 69862b383d..6357dfc3db 100644 --- a/apps/examples/adc/Makefile +++ b/apps/examples/adc/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/adc/Makefile # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -80,7 +76,9 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built .context: @@ -92,17 +90,16 @@ endif context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/adc/adc_main.c b/apps/examples/adc/adc_main.c index 553658fee0..404fba8c1f 100644 --- a/apps/examples/adc/adc_main.c +++ b/apps/examples/adc/adc_main.c @@ -289,7 +289,7 @@ int adc_main(int argc, char *argv[]) { message("adc_main: open %s failed: %d\n", g_adcstate.devpath, errno); errval = 2; - goto errout; + goto errout_with_dev; } /* Now loop the appropriate number of times, displaying the collected @@ -357,11 +357,6 @@ int adc_main(int argc, char *argv[]) } } - close(fd); - return OK; - - /* Error exits */ - errout_with_dev: close(fd); diff --git a/apps/examples/buttons/Makefile b/apps/examples/buttons/Makefile index 77c1cd67df..25d1ef2c2d 100644 --- a/apps/examples/buttons/Makefile +++ b/apps/examples/buttons/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/buttons/Makefile # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -80,7 +76,9 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built .context: @@ -92,17 +90,16 @@ endif context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/can/Makefile b/apps/examples/can/Makefile index 8924797e37..c6dc5af84c 100644 --- a/apps/examples/can/Makefile +++ b/apps/examples/can/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/can/Makefile # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -80,7 +76,9 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built .context: @@ -92,17 +90,16 @@ endif context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/cdcacm/Makefile b/apps/examples/cdcacm/Makefile index e8d03807d8..3fa886d561 100644 --- a/apps/examples/cdcacm/Makefile +++ b/apps/examples/cdcacm/Makefile @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -84,7 +80,9 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built .context: @@ -95,18 +93,17 @@ $(COBJS): %$(OBJEXT): %.c context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/hello/Makefile b/apps/examples/hello/Makefile index 560b0da358..1d78d723ed 100644 --- a/apps/examples/hello/Makefile +++ b/apps/examples/hello/Makefile @@ -54,14 +54,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -80,7 +76,9 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built .context: @@ -92,17 +90,16 @@ endif context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/helloxx/Makefile b/apps/examples/helloxx/Makefile index 062da7d588..8e85eab23e 100644 --- a/apps/examples/helloxx/Makefile +++ b/apps/examples/helloxx/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/helloxx/Makefile # -# Copyright (C) 2009-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -50,14 +50,10 @@ CXXOBJS = $(CXXSRCS:.cxx=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS) OBJS = $(AOBJS) $(COBJS) $(CXXOBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -73,7 +69,7 @@ STACKSIZE = 2048 VPATH = all: .built -.PHONY: clean depend distclean chkcxx +.PHONY: clean depend disclean chkcxx chkcxx: ifneq ($(CONFIG_HAVE_CXX),y) @@ -97,7 +93,9 @@ $(CXXOBJS): %$(OBJEXT): %.cxx $(call COMPILEXX, $<, $@) .built: chkcxx $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built .context: @@ -109,17 +107,16 @@ endif context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/mm/Makefile b/apps/examples/mm/Makefile index 5ba7f4eec9..24ed4926f7 100644 --- a/apps/examples/mm/Makefile +++ b/apps/examples/mm/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/mm/Makefile # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -74,23 +70,24 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/mount/Makefile b/apps/examples/mount/Makefile index 133bdfa1f5..69cf970cf0 100644 --- a/apps/examples/mount/Makefile +++ b/apps/examples/mount/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/Makefile # -# Copyright (C) 2007-2008, 2010-2010, 2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2008, 2010-2010 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -74,23 +70,24 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/nsh/Makefile b/apps/examples/nsh/Makefile index c7d212fc2c..bad40fb2e2 100644 --- a/apps/examples/nsh/Makefile +++ b/apps/examples/nsh/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/nsh/Makefile # -# Copyright (C) 2007-2008, 2010-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2008, 2010-2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -74,23 +70,24 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/null/Makefile b/apps/examples/null/Makefile index 47ec4cdafd..6341206007 100644 --- a/apps/examples/null/Makefile +++ b/apps/examples/null/Makefile @@ -1,7 +1,7 @@ ############################################################################ # examples/null/Makefile # -# Copyright (C) 2007-2008, 2010-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2008, 2010-2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -74,23 +70,24 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/ostest/Kconfig b/apps/examples/ostest/Kconfig index c3fe8f21df..0da7e4ce34 100644 --- a/apps/examples/ostest/Kconfig +++ b/apps/examples/ostest/Kconfig @@ -39,31 +39,4 @@ config EXAMPLES_OSTEST_NBARRIER_THREADS is 8 but a smaller number may be needed on systems without sufficient memory to start so many threads. -config EXAMPLES_OSTEST_RR_RANGE - int "Round-robin test - end of search range" - default 10000 - range 1 32767 - ---help--- - During round-robin scheduling test two threads are created. Each of the threads - searches for prime numbers in the configurable range, doing that configurable - number of times. - - This value specifies the end of search range and together with number of runs - allows to configure the length of this test - it should last at least a few - tens of seconds. Allowed values [1; 32767], default 10000 - -config EXAMPLES_OSTEST_RR_RUNS - int "Round-robin test - number of runs" - default 10 - range 1 32767 - ---help--- - During round-robin scheduling test two threads are created. Each of the threads - searches for prime numbers in the configurable range, doing that configurable - number of times. - - This value specifies the number of times the thread searches the range for - prime numbers and together with end of search range allows to configure the - length of this test - it should last at least a few tens of seconds. Allowed - values [1; 32767], default 10 - endif diff --git a/apps/examples/ostest/Makefile b/apps/examples/ostest/Makefile index 3e78c64e83..374964b396 100644 --- a/apps/examples/ostest/Makefile +++ b/apps/examples/ostest/Makefile @@ -98,14 +98,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -124,7 +120,9 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built .context: @@ -136,17 +134,16 @@ endif context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/ostest/roundrobin.c b/apps/examples/ostest/roundrobin.c index bfd344df34..5167a857ed 100644 --- a/apps/examples/ostest/roundrobin.c +++ b/apps/examples/ostest/roundrobin.c @@ -1,7 +1,7 @@ /******************************************************************************** * examples/ostest/roundrobin.c * - * Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -39,7 +39,6 @@ #include #include -#include #include "ostest.h" #if CONFIG_RR_INTERVAL > 0 @@ -48,87 +47,115 @@ * Definitions ********************************************************************************/ -/* This numbers should be tuned for different processor speeds via .config file. - * With default values the test takes about 30s on Cortex-M3 @ 24MHz. With 32767 - * range and 10 runs it takes ~320s. */ +/* This number may need to be tuned for different processor speeds. Since these + * arrays must be large to very correct SCHED_RR behavior, this test may require + * too much memory on many targets. + */ -#ifndef CONFIG_EXAMPLES_OSTEST_RR_RANGE -# define CONFIG_EXAMPLES_OSTEST_RR_RANGE 10000 -# warning "CONFIG_EXAMPLES_OSTEST_RR_RANGE undefined, using default value = 10000" -#elif (CONFIG_EXAMPLES_OSTEST_RR_RANGE < 1) || (CONFIG_EXAMPLES_OSTEST_RR_RANGE > 32767) -# define CONFIG_EXAMPLES_OSTEST_RR_RANGE 10000 -# warning "Invalid value of CONFIG_EXAMPLES_OSTEST_RR_RANGE, using default value = 10000" -#endif +/* #define CONFIG_NINTEGERS 32768 Takes forever on 60Mhz ARM7 */ -#ifndef CONFIG_EXAMPLES_OSTEST_RR_RUNS -# define CONFIG_EXAMPLES_OSTEST_RR_RUNS 10 -# warning "CONFIG_EXAMPLES_OSTEST_RR_RUNS undefined, using default value = 10" -#elif (CONFIG_EXAMPLES_OSTEST_RR_RUNS < 1) || (CONFIG_EXAMPLES_OSTEST_RR_RUNS > 32767) -# define CONFIG_EXAMPLES_OSTEST_RR_RUNS 10 -# warning "Invalid value of CONFIG_EXAMPLES_OSTEST_RR_RUNS, using default value = 10" -#endif +#define CONFIG_NINTEGERS 2048 + +/******************************************************************************** + * Private Data + ********************************************************************************/ + +static int prime1[CONFIG_NINTEGERS]; +static int prime2[CONFIG_NINTEGERS]; /******************************************************************************** * Private Functions ********************************************************************************/ /******************************************************************************** - * Name: get_primes + * Name: dosieve * * Description - * This function searches for prime numbers in the most primitive way possible. + * This implements a "sieve of aristophanes" algorithm for finding prime number. + * Credit for this belongs to someone, but I am not sure who anymore. Anyway, + * the only purpose here is that we need some algorithm that takes a long period + * of time to execute. + * ********************************************************************************/ -static void get_primes(int *count, int *last) +static void dosieve(int *prime) { - int number; - int local_count = 0; - *last = 0; // to make compiler happy + int a,d; + int i; + int j; - for (number = 1; number < CONFIG_EXAMPLES_OSTEST_RR_RANGE; number++) - { - int div; - bool is_prime = true; + a = 2; + d = a; - for (div = 2; div <= number / 2; div++) - if (number % div == 0) - { - is_prime = false; - break; - } - - if (is_prime) + for (i = 0; i < CONFIG_NINTEGERS; i++) { - local_count++; - *last = number; -#if 0 /* We don't really care what the numbers are */ - printf(" Prime %d: %d\n", local_count, number); -#endif + prime[i] = i+2; } - } - *count = local_count; + for (i = 1; i < 10; i++) + { + for (j = 0; j < CONFIG_NINTEGERS; j++) + { + d = a + d; + if (d < CONFIG_NINTEGERS) + { + prime[d]=0; + } + } + a++; + d = a; + i++; + } + +#if 0 /* We don't really care what the numbers are */ + for (i = 0, j= 0; i < CONFIG_NINTEGERS; i++) + { + if (prime[i] != 0) + { + printf(" Prime %d: %d\n", j, prime[i]); + j++; + } + } +#endif } /******************************************************************************** - * Name: get_primes_thread + * Name: sieve1 ********************************************************************************/ -static void *get_primes_thread(void *parameter) +static void *sieve1(void *parameter) { - int id = (int)parameter; - int i, count, last; + int i; - printf("get_primes_thread id=%d started, looking for primes < %d, doing %d run(s)\n", - id, CONFIG_EXAMPLES_OSTEST_RR_RANGE, CONFIG_EXAMPLES_OSTEST_RR_RUNS); + printf("sieve1 started\n"); - for (i = 0; i < CONFIG_EXAMPLES_OSTEST_RR_RUNS; i++) + for (i = 0; i < 1000; i++) { - get_primes(&count, &last); + dosieve(prime1); } - printf("get_primes_thread id=%d finished, found %d primes, last one was %d\n", - id, count, last); + printf("sieve1 finished\n"); + + pthread_exit(NULL); + return NULL; /* To keep some compilers happy */ +} + +/******************************************************************************** + * Name: sieve2 + ********************************************************************************/ + +static void *sieve2(void *parameter) +{ + int i; + + printf("sieve2 started\n"); + + for (i = 0; i < 1000; i++) + { + dosieve(prime2); + } + + printf("sieve2 finished\n"); pthread_exit(NULL); return NULL; /* To keep some compilers happy */ @@ -144,13 +171,14 @@ static void *get_primes_thread(void *parameter) void rr_test(void) { - pthread_t get_primes1_thread; - pthread_t get_primes2_thread; + pthread_t sieve1_thread; + pthread_t sieve2_thread; struct sched_param sparam; pthread_attr_t attr; pthread_addr_t result; int status; + printf("rr_test: Starting sieve1 thread \n"); status = pthread_attr_init(&attr); if (status != OK) { @@ -175,31 +203,29 @@ void rr_test(void) } else { - printf("rr_test: Set thread policy to SCHED_RR\n"); + printf("rr_test: Set thread policty to SCHED_RR\n"); } - printf("rr_test: Starting first get_primes_thread\n"); - - status = pthread_create(&get_primes1_thread, &attr, get_primes_thread, (void*)1); + status = pthread_create(&sieve1_thread, &attr, sieve1, NULL); if (status != 0) { printf("rr_test: Error in thread 1 creation, status=%d\n", status); } - printf("rr_test: Starting second get_primes_thread\n"); + printf("rr_test: Starting sieve1 thread \n"); - status = pthread_create(&get_primes2_thread, &attr, get_primes_thread, (void*)2); + status = pthread_create(&sieve2_thread, &attr, sieve2, NULL); if (status != 0) { printf("rr_test: Error in thread 2 creation, status=%d\n", status); } - printf("rr_test: Waiting for threads to complete -- this should take awhile\n"); + printf("rr_test: Waiting for sieves to complete -- this should take awhile\n"); printf("rr_test: If RR scheduling is working, they should start and complete at\n"); printf("rr_test: about the same time\n"); - pthread_join(get_primes2_thread, &result); - pthread_join(get_primes1_thread, &result); + pthread_join(sieve2_thread, &result); + pthread_join(sieve1_thread, &result); printf("rr_test: Done\n"); } diff --git a/apps/examples/pipe/Makefile b/apps/examples/pipe/Makefile index bed3190858..956c911b34 100644 --- a/apps/examples/pipe/Makefile +++ b/apps/examples/pipe/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/pipe/Makefile # -# Copyright (C) 2008, 2010-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -74,23 +70,24 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/poll/Makefile b/apps/examples/poll/Makefile index 13173f1253..aef61d199c 100644 --- a/apps/examples/poll/Makefile +++ b/apps/examples/poll/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/poll/Makefile # -# Copyright (C) 2008, 2010-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -74,25 +70,25 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ # Register application depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) - $(call DELFILE, host$(HOSTEXEEXT)) + @rm -f Make.dep .depend host -include Make.dep diff --git a/apps/examples/pwm/Makefile b/apps/examples/pwm/Makefile index 3a6f2520a0..efbdb048e0 100644 --- a/apps/examples/pwm/Makefile +++ b/apps/examples/pwm/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/pwm/Makefile # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -80,7 +76,9 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built .context: @@ -90,17 +88,16 @@ $(COBJS): %$(OBJEXT): %.c context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/pwm/pwm_main.c b/apps/examples/pwm/pwm_main.c index a46c10f55c..775bdba6b1 100644 --- a/apps/examples/pwm/pwm_main.c +++ b/apps/examples/pwm/pwm_main.c @@ -48,7 +48,6 @@ #include #include #include -#include #include diff --git a/apps/examples/qencoder/Makefile b/apps/examples/qencoder/Makefile index 7d2427c6bf..3f3fc9def8 100644 --- a/apps/examples/qencoder/Makefile +++ b/apps/examples/qencoder/Makefile @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -80,7 +76,9 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built .context: @@ -92,17 +90,16 @@ endif context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/romfs/Makefile b/apps/examples/romfs/Makefile index 2b02952eda..ba930b77d0 100644 --- a/apps/examples/romfs/Makefile +++ b/apps/examples/romfs/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/romfs/Makefile # -# Copyright (C) 2008, 2010-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -65,7 +61,7 @@ ROOTDEPPATH = --dep-path . VPATH = all: .built -.PHONY: checkgenromfs clean depend distclean +.PHONY: checkgenromfs clean depend disclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -90,26 +86,26 @@ romfs_testdir.h : testdir.img @xxd -i $< >$@ || { echo "xxd of $< failed" ; exit 1 ; } .built: romfs_testdir.h $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ # Register application depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) - $(call DELFILE, testdir.img) + @rm -f Make.dep .depend testdir.img -include Make.dep diff --git a/apps/examples/serloop/Makefile b/apps/examples/serloop/Makefile index 4a262884bb..e1c415cdd8 100644 --- a/apps/examples/serloop/Makefile +++ b/apps/examples/serloop/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/examples/serloop/Makefile # -# Copyright (C) 2008, 2010-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -74,25 +70,26 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ # Register application depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/examples/watchdog/Makefile b/apps/examples/watchdog/Makefile index 9890959fb5..d2739dbb0a 100644 --- a/apps/examples/watchdog/Makefile +++ b/apps/examples/watchdog/Makefile @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -80,7 +76,9 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built .context: @@ -90,17 +88,16 @@ $(COBJS): %$(OBJEXT): %.c context: .context .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/interpreters/Makefile b/apps/interpreters/Makefile index 867d45f996..5901fc8309 100644 --- a/apps/interpreters/Makefile +++ b/apps/interpreters/Makefile @@ -33,7 +33,7 @@ # ############################################################################ --include $(TOPDIR)/.config +-include $(TOPDIR)/.config # Current configuration # Sub-directories containing interpreter runtime @@ -41,36 +41,30 @@ SUBDIRS = pcode ficl # Create the list of installed runtime modules (INSTALLED_DIRS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) -define ADD_DIRECTORY -INSTALLED_DIRS += ${shell if exist $1\Makefile (echo $1)} -endef -else define ADD_DIRECTORY INSTALLED_DIRS += ${shell if [ -r $1/Makefile ]; then echo "$1"; fi} endef -endif $(foreach DIR, $(SUBDIRS), $(eval $(call ADD_DIRECTORY,$(DIR)))) all: nothing .PHONY: nothing context depend clean distclean -define SDIR_template -$(1)_$(2): - $(Q) $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" -endef - -$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),depend))) -$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),clean))) -$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),distclean))) - nothing: context: -depend: $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_depend) +depend: + @for dir in $(INSTALLED_DIRS) ; do \ + $(MAKE) -C $$dir depend TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ + done -clean: $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_clean) +clean: + @for dir in $(INSTALLED_DIRS) ; do \ + $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ + done -distclean: clean $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_distclean) +distclean: clean + @for dir in $(INSTALLED_DIRS) ; do \ + $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ + done diff --git a/apps/interpreters/ficl/Makefile b/apps/interpreters/ficl/Makefile index 990630fb89..fb953964e1 100644 --- a/apps/interpreters/ficl/Makefile +++ b/apps/interpreters/ficl/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/interpreters/ficl/Makefile # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -35,11 +35,14 @@ BUILDDIR := ${shell pwd | sed -e 's/ /\\ /g'} +-include $(TOPDIR)/.config -include $(TOPDIR)/Make.defs include $(APPDIR)/Make.defs # Tools +INCDIR = $(TOPDIR)/tools/incdir.sh + ifeq ($(WINTOOL),y) INCDIROPT = -w endif @@ -66,14 +69,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOT_DEPPATH = --dep-path . @@ -96,24 +95,24 @@ debug: @#echo "CFLAGS: $(CFLAGS)" .built: debug $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) - $(Q) touch .built + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) + @touch .built context: .depend: debug Makefile $(SRCS) - $(Q) $(MKDEP) $(ROOT_DEPPATH) $(SRC_DEPPATH) $(FICL_DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(ROOT_DEPPATH) $(SRC_DEPPATH) $(FICL_DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, .context) - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/namedapp/Makefile b/apps/namedapp/Makefile index a88c735674..6b0fd6a053 100644 --- a/apps/namedapp/Makefile +++ b/apps/namedapp/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/nshlib/Makefile # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -54,14 +54,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -79,32 +75,32 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) - $(Q) touch .built + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) + @touch .built .context: @echo "/* List of application requirements, generated during make context. */" > namedapp_list.h @echo "/* List of application entry points, generated during make context. */" > namedapp_proto.h - $(Q) touch $@ + @touch $@ context: .context .depend: Makefile $(SRCS) - $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, .context) - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) - $(call DELFILE, namedapp_list.h) - $(call DELFILE, namedapp_proto.h) + @rm -f .context Make.dep .depend + @rm -f namedapp_list.h + @rm -f namedapp_proto.h -include Make.dep diff --git a/apps/nshlib/Kconfig b/apps/nshlib/Kconfig index 17b107b8f5..d12a329738 100644 --- a/apps/nshlib/Kconfig +++ b/apps/nshlib/Kconfig @@ -23,194 +23,122 @@ config NSH_BUILTIN_APPS (NAMEDAPP). menu "Disable Individual commands" - -config NSH_DISABLE_BASE64DEC - bool "Disable base64dec" - default n - depends on NETUTILS_CODECS && CODECS_BASE64 - -config NSH_DISABLE_BASE64ENC - bool "Disable base64enc" - default n - depends on NETUTILS_CODECS && CODECS_BASE64 - config NSH_DISABLE_CAT bool "Disable cat" default n - config NSH_DISABLE_CD bool "Disable cd" default n - config NSH_DISABLE_CP bool "Disable cp" default n - config NSH_DISABLE_DD bool "Disable dd" default n - config NSH_DISABLE_ECHO bool "Disable echo" default n - config NSH_DISABLE_EXEC bool "Disable exec" default n - config NSH_DISABLE_EXIT bool "Disable exit" default n - config NSH_DISABLE_FREE bool "Disable free" default n - config NSH_DISABLE_GET bool "Disable get" default n - config NSH_DISABLE_HELP bool "Disable help" default n - -config NSH_DISABLE_HEXDUMP - bool "Disable hexdump" - default n - config NSH_DISABLE_IFCONFIG bool "Disable ifconfig" default n - config NSH_DISABLE_KILL bool "Disable kill" default n - config NSH_DISABLE_LOSETUP bool "Disable losetup" default n - config NSH_DISABLE_LS bool "Disable ls" default n - config NSH_DISABLE_MB bool "Disable mb" default n - -config NSH_DISABLE_MD5 - bool "Disable md5" - default n - depends on NETUTILS_CODECS && CODECS_HASH_MD5 - config NSH_DISABLE_MKDIR bool "Disable mkdir" default n - config NSH_DISABLE_MKFATFS bool "Disable mkfatfs" default n - config NSH_DISABLE_MKFIFO bool "Disable mkfifo" default n - config NSH_DISABLE_MKRD bool "Disable mkrd" default n - config NSH_DISABLE_MH bool "Disable mh" default n - config NSH_DISABLE_MOUNT bool "Disable mount" default n - config NSH_DISABLE_MW bool "Disable mw" default n - config NSH_DISABLE_NSFMOUNT bool "Disable nfsmount" default n - config NSH_DISABLE_PS bool "Disable ps" default n - config NSH_DISABLE_PING bool "Disable ping" default n - config NSH_DISABLE_PUT bool "Disable put" default n - config NSH_DISABLE_PWD bool "Disable pwd" default n - config NSH_DISABLE_RM bool "Disable rm" default n - config NSH_DISABLE_RMDIR bool "Disable rmdir" default n - config NSH_DISABLE_SET bool "Disable set" default n - config NSH_DISABLE_SH bool "Disable sh" default n - config NSH_DISABLE_SLEEP bool "Disable sleep" default n - config NSH_DISABLE_TEST bool "Disable test" default n - config NSH_DISABLE_UMOUNT bool "Disable umount" default n - config NSH_DISABLE_UNSET bool "Disable unset" default n - -config NSH_DISABLE_URLDECODE - bool "Disable urldecode" - default n - depends on NETUTILS_CODECS && CODECS_URLCODE - -config NSH_DISABLE_URLENCODE - bool "Disable urlencode" - default n - depends on NETUTILS_CODECS && CODECS_URLCODE - config NSH_DISABLE_USLEEP bool "Disable usleep" default n - config NSH_DISABLE_WGET bool "Disable wget" default n - config NSH_DISABLE_XD bool "Disable xd" default n - endmenu -config NSH_CODECS_BUFSIZE - int "File buffer size used by CODEC commands" - default 128 - config NSH_FILEIOSIZE int "NSH I/O buffer size" default 1024 @@ -562,7 +490,7 @@ config NSH_DHCPC config NSH_IPADDR hex "Target IP address" - default 0xa0000002 + default 0x10000002 depends on NSH_LIBRARY && NET && !NSH_DHCPC ---help--- If NSH_DHCPC is NOT set, then the static IP address must be provided. @@ -571,7 +499,7 @@ config NSH_IPADDR config NSH_DRIPADDR hex "Router IP address" - default 0xa0000001 + default 0x10000001 depends on NSH_LIBRARY && NET && !NSH_DHCPC ---help--- Default router IP address (aka, Gateway). This is a 32-bit integer @@ -585,21 +513,6 @@ config NSH_NETMASK Network mask. This is a 32-bit integer value in host order. So, as an example, 0xffffff00 would be 255.255.255.0. -config NSH_DNS - bool "Use DNS" - default n - depends on NSH_LIBRARY && NET && NET_UDP && NET_BROADCAST - ---help--- - Configure to use a DNS. - -config NSH_DNSIPADDR - hex "DNS IP address" - default 0xa0000001 - depends on NSH_DNS - ---help--- - Configure the DNS address. This is a 32-bit integer value in host - order. So, as an example, 0xa0000001 would be 10.0.0.1. - config NSH_NOMAC bool "Hardware has no MAC address" default n @@ -607,12 +520,3 @@ config NSH_NOMAC ---help--- Set if your ethernet hardware has no built-in MAC address. If set, a bogus MAC will be assigned. - -config NSH_MAX_ROUNDTRIP - int "Max Ping Round-Trip (DSEC)" - default 20 - depends on NSH_LIBRARY && NET && !NSH_DISABLE_PING - ---help--- - This is the maximum round trip for a response to a ICMP ECHO request. - It is in units of deciseconds. The default is 20 (2 seconds). - diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile index 73325e899d..f616374bfd 100644 --- a/apps/nshlib/Makefile +++ b/apps/nshlib/Makefile @@ -39,72 +39,64 @@ include $(APPDIR)/Make.defs # NSH Library -ASRCS = -CSRCS = nsh_init.c nsh_parse.c nsh_console.c nsh_fscmds.c nsh_ddcmd.c \ +ASRCS = +CSRCS = nsh_init.c nsh_parse.c nsh_console.c nsh_fscmds.c nsh_ddcmd.c \ nsh_proccmds.c nsh_mmcmds.c nsh_envcmds.c nsh_dbgcmds.c ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) -CSRCS += nsh_apps.c +CSRCS += nsh_apps.c endif ifeq ($(CONFIG_NSH_ROMFSETC),y) -CSRCS += nsh_romfsetc.c +CSRCS += nsh_romfsetc.c endif ifeq ($(CONFIG_NET),y) -CSRCS += nsh_netinit.c nsh_netcmds.c +CSRCS += nsh_netinit.c nsh_netcmds.c endif ifeq ($(CONFIG_RTC),y) -CSRCS += nsh_timcmds.c +CSRCS += nsh_timcmds.c endif ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y) -CSRCS += nsh_mntcmds.c +CSRCS += nsh_mntcmds.c endif ifeq ($(CONFIG_NSH_CONSOLE),y) -CSRCS += nsh_consolemain.c +CSRCS += nsh_consolemain.c endif ifeq ($(CONFIG_NSH_TELNET),y) -CSRCS += nsh_telnetd.c +CSRCS += nsh_telnetd.c endif ifneq ($(CONFIG_NSH_DISABLESCRIPT),y) -CSRCS += nsh_test.c +CSRCS += nsh_test.c endif ifeq ($(CONFIG_USBDEV),y) -CSRCS += nsh_usbdev.c +CSRCS += nsh_usbdev.c endif -ifeq ($(CONFIG_NETUTILS_CODECS),y) -CSRCS += nsh_codeccmd.c -endif +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) -AOBJS = $(ASRCS:.S=$(OBJEXT)) -COBJS = $(CSRCS:.c=$(OBJEXT)) +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) - -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif -ROOTDEPPATH = --dep-path . -VPATH = +ROOTDEPPATH = --dep-path . +VPATH = # Build targets -all: .built +all: .built .PHONY: context .depend depend clean distclean $(AOBJS): %$(OBJEXT): %.S @@ -114,25 +106,26 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) @touch .built context: .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) $(ROOTDEPPATH) \ + $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, .context) - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/nshlib/README.txt b/apps/nshlib/README.txt index 59f0538f08..0f6aee759b 100644 --- a/apps/nshlib/README.txt +++ b/apps/nshlib/README.txt @@ -235,10 +235,6 @@ o test integer -gt integer | integer -le integer | integer -lt integer | integer -ne integer -o base64dec [-w] [-f] - -o base64dec [-w] [-f] - o cat [ [ ...]] This command copies and concatentates all of the files at @@ -385,11 +381,7 @@ o help [-v] [] Show full command usage only for this command -o hexdump - - Dump data in hexadecimal format from a file or character device. - -o ifconfig [nic_name [ip]] [dr|gw|gateway ] [netmask ] [dns ] [hw ] +o ifconfig Show the current configuration of the network, for example: @@ -400,22 +392,6 @@ o ifconfig [nic_name [ip]] [dr|gw|gateway ] [netmask ] [dn if uIP statistics are enabled (CONFIG_NET_STATISTICS), then this command will also show the detailed state of uIP. -o ifdown - - Take down the interface identified by the name . - - Example: - - ifdown eth0 - -o ifup - - Bring up down the interface identified by the name . - - Example: - - ifup eth0 - o kill - Send the to the task identified by . @@ -473,8 +449,6 @@ o ls [-lRs] -l Show size and mode information along with the filenames in the listing. -o md5 [-f] - o mb [=][ ] o mh [=][ ] o mw [=][ ] @@ -807,10 +781,6 @@ o unset nsh> - o urldecode [-f] - - o urlencode [-f] - o usleep Pause execution (sleep) of microseconds. @@ -856,8 +826,6 @@ Command Dependencies on Configuration Settings Command Depends on Configuration ---------- -------------------------- [ !CONFIG_NSH_DISABLESCRIPT - base64dec CONFIG_NETUTILS_CODECS && CONFIG_CODECS_BASE64 - base64enc CONFIG_NETUTILS_CODECS && CONFIG_CODECS_BASE64 cat CONFIG_NFILE_DESCRIPTORS > 0 cd !CONFIG_DISABLE_ENVIRON && CONFIG_NFILE_DESCRIPTORS > 0 cp CONFIG_NFILE_DESCRIPTORS > 0 @@ -869,14 +837,10 @@ Command Dependencies on Configuration Settings free -- get CONFIG_NET && CONFIG_NET_UDP && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NET_BUFSIZE >= 558 (see note 1) help -- - hexdump CONFIG_NFILE_DESCRIPTORS > 0 ifconfig CONFIG_NET - ifdown CONFIG_NET - ifup CONFIG_NET kill !CONFIG_DISABLE_SIGNALS losetup !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 ls CONFIG_NFILE_DESCRIPTORS > 0 - md5 CONFIG_NETUTILS_CODECS && CONFIG_CODECS_HASH_MD5 mb,mh,mw --- mkdir !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_FS_WRITABLE (see note 4) mkfatfs !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_FS_FAT @@ -897,8 +861,6 @@ Command Dependencies on Configuration Settings test !CONFIG_NSH_DISABLESCRIPT umount !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_FS_READABLE unset !CONFIG_DISABLE_ENVIRON - urldecode CONFIG_NETUTILS_CODECS && CONFIG_CODECS_URLCODE - urlencode CONFIG_NETUTILS_CODECS && CONFIG_CODECS_URLCODE usleep !CONFIG_DISABLE_SIGNALS get CONFIG_NET && CONFIG_NET_TCP && CONFIG_NFILE_DESCRIPTORS > 0 xd --- @@ -918,22 +880,20 @@ In addition, each NSH command can be individually disabled via one of the follow settings. All of these settings make the configuration of NSH potentially complex but also allow it to squeeze into very small memory footprints. - CONFIG_NSH_DISABLE_BASE64DEC, CONFIG_NSH_DISABLE_BASE64ENC, CONFIG_NSH_DISABLE_CAT, - CONFIG_NSH_DISABLE_CD, CONFIG_NSH_DISABLE_CP, CONFIG_NSH_DISABLE_DD, - CONFIG_NSH_DISABLE_DF, CONFIG_NSH_DISABLE_ECHO, CONFIG_NSH_DISABLE_EXEC, - CONFIG_NSH_DISABLE_EXIT, CONFIG_NSH_DISABLE_FREE, CONFIG_NSH_DISABLE_GET, - CONFIG_NSH_DISABLE_HELP, CONFIG_NSH_DISABLE_HEXDUMP, CONFIG_NSH_DISABLE_IFCONFIG, - CONFIG_NSH_DISABLE_IFUPDOWN, CONFIG_NSH_DISABLE_KILL, CONFIG_NSH_DISABLE_LOSETUP, - CONFIG_NSH_DISABLE_LS, CONFIG_NSH_DISABLE_MD5 CONFIG_NSH_DISABLE_MB, - CONFIG_NSH_DISABLE_MKDIR, CONFIG_NSH_DISABLE_MKFATFS, CONFIG_NSH_DISABLE_MKFIFO, - CONFIG_NSH_DISABLE_MKRD, CONFIG_NSH_DISABLE_MH, CONFIG_NSH_DISABLE_MOUNT, - CONFIG_NSH_DISABLE_MW, CONFIG_NSH_DISABLE_MV, CONFIG_NSH_DISABLE_NFSMOUNT, - CONFIG_NSH_DISABLE_PS, CONFIG_NSH_DISABLE_PING, CONFIG_NSH_DISABLE_PUT, - CONFIG_NSH_DISABLE_PWD, CONFIG_NSH_DISABLE_RM, CONFIG_NSH_DISABLE_RMDIR, - CONFIG_NSH_DISABLE_SET, CONFIG_NSH_DISABLE_SH, CONFIG_NSH_DISABLE_SLEEP, - CONFIG_NSH_DISABLE_TEST, CONFIG_NSH_DISABLE_UMOUNT, CONFIG_NSH_DISABLE_UNSET, - CONFIG_NSH_DISABLE_URLDECODE, CONFIG_NSH_DISABLE_URLENCODE, CONFIG_NSH_DISABLE_USLEEP, - CONFIG_NSH_DISABLE_WGET, CONFIG_NSH_DISABLE_XD + CONFIG_NSH_DISABLE_CAT, CONFIG_NSH_DISABLE_CD, CONFIG_NSH_DISABLE_CP, + CONFIG_NSH_DISABLE_DD, CONFIG_NSH_DISABLE_DF, CONFIG_NSH_DISABLE_ECHO, + CONFIG_NSH_DISABLE_EXEC, CONFIG_NSH_DISABLE_EXIT, CONFIG_NSH_DISABLE_FREE, + CONFIG_NSH_DISABLE_GET, CONFIG_NSH_DISABLE_HELP, CONFIG_NSH_DISABLE_IFCONFIG, + CONFIG_NSH_DISABLE_KILL, CONFIG_NSH_DISABLE_LOSETUP, CONFIG_NSH_DISABLE_LS, + CONFIG_NSH_DISABLE_MB, CONFIG_NSH_DISABLE_MKDIR, CONFIG_NSH_DISABLE_MKFATFS, + CONFIG_NSH_DISABLE_MKFIFO, CONFIG_NSH_DISABLE_MKRD, CONFIG_NSH_DISABLE_MH, + CONFIG_NSH_DISABLE_MOUNT, CONFIG_NSH_DISABLE_MW, CONFIG_NSH_DISABLE_MV, + CONFIG_NSH_DISABLE_NFSMOUNT, CONFIG_NSH_DISABLE_PS, CONFIG_NSH_DISABLE_PING, + CONFIG_NSH_DISABLE_PUT, CONFIG_NSH_DISABLE_PWD, CONFIG_NSH_DISABLE_RM, + CONFIG_NSH_DISABLE_RMDIR, CONFIG_NSH_DISABLE_SET, CONFIG_NSH_DISABLE_SH, + CONFIG_NSH_DISABLE_SLEEP, CONFIG_NSH_DISABLE_TEST, CONFIG_NSH_DISABLE_UMOUNT, + CONFIG_NSH_DISABLE_UNSET, CONFIG_NSH_DISABLE_USLEEP, CONFIG_NSH_DISABLE_WGET, + CONFIG_NSH_DISABLE_XD Verbose help output can be suppressed by defining CONFIG_NSH_HELP_TERSE. In that case, the help command is still available but will be slightly smaller. @@ -1124,10 +1084,6 @@ NSH-Specific Configuration Settings Set if your ethernet hardware has no built-in MAC address. If set, a bogus MAC will be assigned. - * CONFIG_NSH_MAX_ROUNDTRIP - This is the maximum round trip for a response to a ICMP ECHO request. - It is in units of deciseconds. The default is 20 (2 seconds). - If you use DHCPC, then some special configuration network options are required. These include: diff --git a/apps/nshlib/nsh.h b/apps/nshlib/nsh.h index a046a384fc..7188477ced 100644 --- a/apps/nshlib/nsh.h +++ b/apps/nshlib/nsh.h @@ -47,7 +47,6 @@ #include #include #include -#include #include #include @@ -216,15 +215,6 @@ #endif /* CONFIG_NSH_TELNET_LOGIN */ -/* CONFIG_NSH_MAX_ROUNDTRIP - This is the maximum round trip for a response to - * a ICMP ECHO request. It is in units of deciseconds. The default is 20 - * (2 seconds). - */ - -#ifndef CONFIG_NSH_MAX_ROUNDTRIP -# define CONFIG_NSH_MAX_ROUNDTRIP 20 -#endif - /* Verify support for ROMFS /etc directory support options */ #ifdef CONFIG_NSH_ROMFSETC @@ -268,36 +258,12 @@ # undef CONFIG_NSH_ROMFSSECTSIZE #endif -/* This is the maximum number of arguments that will be accepted for a - * command. Here we attempt to select the smallest number possible depending - * upon the of commands that are available. Most commands use six or fewer - * arguments, but there are a few that require more. - * - * This value is also configurable with CONFIG_NSH_MAXARGUMENTS. This - * configurability is necessary since there may also be external, "built-in" - * commands that require more commands than NSH is aware of. - */ - -#ifndef CONFIG_NSH_MAXARGUMENTS -# define CONFIG_NSH_MAXARGUMENTS 6 +/* This is the maximum number of arguments that will be accepted for a command */ +#ifdef CONFIG_NSH_MAX_ARGUMENTS +# define NSH_MAX_ARGUMENTS CONFIG_NSH_MAX_ARGUMENTS +#else +# define NSH_MAX_ARGUMENTS 10 #endif - -#if CONFIG_NSH_MAXARGUMENTS < 11 -# if defined(CONFIG_NET) && !defined(CONFIG_NSH_DISABLE_IFCONFIG) -# undef CONFIG_NSH_MAXARGUMENTS -# define CONFIG_NSH_MAXARGUMENTS 11 -# endif -#endif - -#if CONFIG_NSH_MAXARGUMENTS < 7 -# if defined(CONFIG_NET_UDP) && CONFIG_NFILE_DESCRIPTORS > 0 -# if !defined(CONFIG_NSH_DISABLE_GET) || !defined(CONFIG_NSH_DISABLE_PUT) -# undef CONFIG_NSH_MAXARGUMENTS -# define CONFIG_NSH_MAXARGUMENTS 7 -# endif -# endif -#endif - /* strerror() produces much nicer output but is, however, quite large and * will only be used if CONFIG_NSH_STRERROR is defined. Note that the strerror * interface must also have been enabled with CONFIG_LIBC_STRERROR. @@ -541,7 +507,7 @@ void nsh_usbtrace(void); #ifndef CONFIG_NSH_DISABLE_XD int cmd_xd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); #endif - + #if !defined(CONFIG_NSH_DISABLESCRIPT) && !defined(CONFIG_NSH_DISABLE_TEST) int cmd_test(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); int cmd_lbracket(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); @@ -563,9 +529,6 @@ void nsh_usbtrace(void); # ifndef CONFIG_NSH_DISABLE_DD int cmd_dd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); # endif -# ifndef CONFIG_NSH_DISABLE_HEXDUMP - int cmd_hexdump(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); -# endif # ifndef CONFIG_NSH_DISABLE_LS int cmd_ls(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); # endif @@ -632,10 +595,6 @@ void nsh_usbtrace(void); # ifndef CONFIG_NSH_DISABLE_IFCONFIG int cmd_ifconfig(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); # endif -# ifndef CONFIG_NSH_DISABLE_IFUPDOWN - int cmd_ifup(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); - int cmd_ifdown(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); -# endif #if defined(CONFIG_NET_UDP) && CONFIG_NFILE_DESCRIPTORS > 0 # ifndef CONFIG_NSH_DISABLE_GET int cmd_get(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); @@ -684,28 +643,4 @@ void nsh_usbtrace(void); # endif #endif /* CONFIG_DISABLE_SIGNALS */ -#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_BASE64) -# ifndef CONFIG_NSH_DISABLE_BASE64DEC - int cmd_base64decode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); -# endif -# ifndef CONFIG_NSH_DISABLE_BASE64ENC - int cmd_base64encode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); -# endif -#endif - -#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_HASH_MD5) -# ifndef CONFIG_NSH_DISABLE_MD5 - int cmd_md5(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); -# endif -#endif - -#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_URLCODE) -# ifndef CONFIG_NSH_DISABLE_URLDECODE - int cmd_urlencode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); -# endif -# ifndef CONFIG_NSH_DISABLE_URLENCODE - int cmd_urldecode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv); -# endif -#endif - #endif /* __APPS_NSHLIB_NSH_H */ diff --git a/apps/nshlib/nsh_dbgcmds.c b/apps/nshlib/nsh_dbgcmds.c index 5463e0f5a2..384b377f3a 100644 --- a/apps/nshlib/nsh_dbgcmds.c +++ b/apps/nshlib/nsh_dbgcmds.c @@ -46,10 +46,6 @@ #include #include -#if CONFIG_NFILE_DESCRIPTORS > 0 -# include -#endif - #include "nsh.h" #include "nsh_console.h" @@ -331,7 +327,7 @@ void nsh_dumpbuffer(FAR struct nsh_vtbl_s *vtbl, const char *msg, } /**************************************************************************** - * Name: cmd_xd, hex dump of memory + * Name: cmd_xd ****************************************************************************/ #ifndef CONFIG_NSH_DISABLE_XD @@ -357,58 +353,3 @@ int cmd_xd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) return OK; } #endif - -/**************************************************************************** - * Name: cmd_hexdump, hex dump of files - ****************************************************************************/ - -#if CONFIG_NFILE_DESCRIPTORS > 0 -#ifndef CONFIG_NSH_DISABLE_HEXDUMP -int cmd_hexdump(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - uint8_t buffer[IOBUFFERSIZE]; - char msg[32]; - int position; - int fd; - int ret = OK; - - /* Open the file for reading */ - - fd = open(argv[1], O_RDONLY); - if (fd < 0) - { - nsh_output(vtbl, g_fmtcmdfailed, "hexdump", "open", NSH_ERRNO); - return ERROR; - } - - position = 0; - for (;;) - { - int nbytesread = read(fd, buffer, IOBUFFERSIZE); - - /* Check for read errors */ - - if (nbytesread < 0) - { - int errval = errno; - nsh_output(vtbl, g_fmtcmdfailed, "hexdump", "read", NSH_ERRNO_OF(errval)); - ret = ERROR; - break; - } - else if (nbytesread > 0) - { - snprintf(msg, sizeof(msg), "%s at %08x", argv[1], position); - nsh_dumpbuffer(vtbl, msg, buffer, nbytesread); - position += nbytesread; - } - else - { - break; // EOF - } - } - - (void)close(fd); - return ret; -} -#endif -#endif diff --git a/apps/nshlib/nsh_netcmds.c b/apps/nshlib/nsh_netcmds.c index d28fe873d0..cfea5a08a0 100644 --- a/apps/nshlib/nsh_netcmds.c +++ b/apps/nshlib/nsh_netcmds.c @@ -51,7 +51,6 @@ #include /* Needed for open */ #include /* Needed for basename */ #include -#include #include #include @@ -81,12 +80,6 @@ # endif #endif -#ifdef CONFIG_HAVE_GETHOSTBYNAME -# include -#else -# include -#endif - #include "nsh.h" #include "nsh_console.h" @@ -94,16 +87,8 @@ * Definitions ****************************************************************************/ -/* Size of the ECHO data */ - #define DEFAULT_PING_DATALEN 56 -/* Get the larger value */ - -#ifndef MAX -# define MAX(a,b) (a > b ? a : b) -#endif - /**************************************************************************** * Private Types ****************************************************************************/ @@ -277,34 +262,14 @@ int ifconfig_callback(FAR struct uip_driver_s *dev, void *arg) { struct nsh_vtbl_s *vtbl = (struct nsh_vtbl_s*)arg; struct in_addr addr; - bool is_running = false; - int ret; - - ret = uip_getifstatus(dev->d_ifname,&is_running); - if (ret != OK) - { - nsh_output(vtbl, "\tGet %s interface flags error: %d\n", - dev->d_ifname, ret); - } - - nsh_output(vtbl, "%s\tHWaddr %s at %s\n", - dev->d_ifname, ether_ntoa(&dev->d_mac), (is_running)?"UP":"DOWN"); + nsh_output(vtbl, "%s\tHWaddr %s\n", dev->d_ifname, ether_ntoa(&dev->d_mac)); addr.s_addr = dev->d_ipaddr; nsh_output(vtbl, "\tIPaddr:%s ", inet_ntoa(addr)); - addr.s_addr = dev->d_draddr; nsh_output(vtbl, "DRaddr:%s ", inet_ntoa(addr)); - addr.s_addr = dev->d_netmask; - nsh_output(vtbl, "Mask:%s\n", inet_ntoa(addr)); - -#if defined(CONFIG_NSH_DHCPC) || defined(CONFIG_NSH_DNS) - resolv_getserver(&addr); - nsh_output(vtbl, "\tDNSaddr:%s\n", inet_ntoa(addr)); -#endif - - nsh_output(vtbl, "\n"); + nsh_output(vtbl, "Mask:%s\n\n", inet_ntoa(addr)); return OK; } @@ -503,54 +468,6 @@ int cmd_get(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) #endif #endif -/**************************************************************************** - * Name: cmd_ifup - ****************************************************************************/ - -#ifndef CONFIG_NSH_DISABLE_IFUPDOWN -int cmd_ifup(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - FAR char *intf = NULL; - int ret; - - if (argc != 2) - { - nsh_output(vtbl, "Please select nic_name:\n"); - netdev_foreach(ifconfig_callback, vtbl); - return OK; - } - - intf = argv[1]; - ret = uip_ifup(intf); - nsh_output(vtbl, "ifup %s...%s\n", intf, (ret == OK) ? "OK" : "Failed"); - return ret; -} -#endif - -/**************************************************************************** - * Name: cmd_ifdown - ****************************************************************************/ - -#ifndef CONFIG_NSH_DISABLE_IFUPDOWN -int cmd_ifdown(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - FAR char *intf = NULL; - int ret; - - if (argc != 2) - { - nsh_output(vtbl, "Please select nic_name:\n"); - netdev_foreach(ifconfig_callback, vtbl); - return OK; - } - - intf = argv[1]; - ret = uip_ifdown(intf); - nsh_output(vtbl, "ifdown %s...%s\n", intf, (ret == OK) ? "OK" : "Failed"); - return ret; -} -#endif - /**************************************************************************** * Name: cmd_ifconfig ****************************************************************************/ @@ -559,17 +476,7 @@ int cmd_ifdown(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) int cmd_ifconfig(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) { struct in_addr addr; - in_addr_t gip; - int i; - FAR char *intf = NULL; - FAR char *hostip = NULL; - FAR char *gwip = NULL; - FAR char *mask = NULL; - FAR char *tmp = NULL; - FAR char *hw = NULL; - FAR char *dns = NULL; - bool badarg=false; - uint8_t mac[6]; + in_addr_t ip; /* With one or no arguments, ifconfig simply shows the status of ethernet * device: @@ -591,142 +498,24 @@ int cmd_ifconfig(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) * ifconfig nic_name ip_address */ - if (argc > 2) - { - for(i = 0; i < argc; i++) - { - if (i == 1) - { - intf = argv[i]; - } - else if (i == 2) - { - hostip = argv[i]; - } - else - { - tmp = argv[i]; - if (!strcmp(tmp, "dr") || !strcmp(tmp, "gw") || !strcmp(tmp, "gateway")) - { - if (argc-1 >= i+1) - { - gwip = argv[i+1]; - i++; - } - else - { - badarg = true; - } - } - else if(!strcmp(tmp, "netmask")) - { - if (argc-1 >= i+1) - { - mask = argv[i+1]; - i++; - } - else - { - badarg = true; - } - } - else if(!strcmp(tmp, "hw")) - { - if (argc-1>=i+1) - { - hw = argv[i+1]; - i++; - badarg = !uiplib_hwmacconv(hw, mac); - } - else - { - badarg = true; - } - } - else if(!strcmp(tmp, "dns")) - { - if (argc-1 >= i+1) - { - dns = argv[i+1]; - i++; - } - else - { - badarg = true; - } - } - } - } - } - - if (badarg) - { - nsh_output(vtbl, g_fmtargrequired, argv[0]); - return ERROR; - } - - /* Set Hardware ethernet MAC addr */ - - if (hw) - { - ndbg("HW MAC: %s\n", hw); - uip_setmacaddr(intf, mac); - } - /* Set host ip address */ - ndbg("Host IP: %s\n", hostip); - gip = addr.s_addr = inet_addr(hostip); - uip_sethostaddr(intf, &addr); + ip = addr.s_addr = inet_addr(argv[2]); + uip_sethostaddr(argv[1], &addr); /* Set gateway */ - if (gwip) - { - ndbg("Gateway: %s\n", gwip); - gip = addr.s_addr = inet_addr(gwip); - } - else - { - ndbg("Gateway: default\n"); - gip = NTOHL(gip); - gip &= ~0x000000ff; - gip |= 0x00000001; - gip = HTONL(gip); - addr.s_addr = gip; - } + ip = NTOHL(ip); + ip &= ~0x000000ff; + ip |= 0x00000001; - uip_setdraddr(intf, &addr); + addr.s_addr = HTONL(ip); + uip_setdraddr(argv[1], &addr); - /* Set network mask */ + /* Set netmask */ - if (mask) - { - ndbg("Netmask: %s\n",mask); - addr.s_addr = inet_addr(mask); - } - else - { - ndbg("Netmask: Default\n"); - addr.s_addr = inet_addr("255.255.255.0"); - } - - uip_setnetmask(intf, &addr); - -#if defined(CONFIG_NSH_DHCPC) || defined(CONFIG_NSH_DNS) - if (dns) - { - ndbg("DNS: %s\n", dns); - addr.s_addr = inet_addr(dns); - } - else - { - ndbg("DNS: Default\n"); - addr.s_addr = gip; - } - - resolv_conf(&addr); -#endif + addr.s_addr = inet_addr("255.255.255.0"); + uip_setnetmask(argv[1], &addr); return OK; } @@ -747,7 +536,6 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) uint32_t start; uint32_t next; uint32_t dsec = 10; - uint32_t maxwait; uint16_t id; bool badarg = false; int count = 10; @@ -811,7 +599,7 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) if (optind == argc-1) { staddr = argv[optind]; - if (dns_gethostip(staddr, &ipaddr) < 0) + if (!uiplib_ipaddrconv(staddr, (FAR unsigned char*)&ipaddr)) { goto errout; } @@ -831,26 +619,16 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) id = ping_newid(); - /* The maximum wait for a response will be the larger of the inter-ping time and - * the configured maximum round-trip time. - */ - - maxwait = MAX(dsec, CONFIG_NSH_MAX_ROUNDTRIP); - /* Loop for the specified count */ - nsh_output(vtbl, "PING %d.%d.%d.%d %d bytes of data\n", - (ipaddr ) & 0xff, (ipaddr >> 8 ) & 0xff, - (ipaddr >> 16 ) & 0xff, (ipaddr >> 24 ) & 0xff, - DEFAULT_PING_DATALEN); - + nsh_output(vtbl, "PING %s %d bytes of data\n", staddr, DEFAULT_PING_DATALEN); start = g_system_timer; for (i = 1; i <= count; i++) { /* Send the ECHO request and wait for the response */ next = g_system_timer; - seqno = uip_ping(ipaddr, id, i, DEFAULT_PING_DATALEN, maxwait); + seqno = uip_ping(ipaddr, id, i, DEFAULT_PING_DATALEN, dsec); /* Was any response returned? We can tell if a non-negative sequence * number was returned. @@ -858,7 +636,7 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) if (seqno >= 0 && seqno <= i) { - /* Get the elapsed time from the time that the request was + /* Get the elpased time from the time that the request was * sent until the response was received. If we got a response * to an earlier request, then fudge the elpased time. */ @@ -866,7 +644,7 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) elapsed = TICK2MSEC(g_system_timer - next); if (seqno < i) { - elapsed += 100 * dsec * (i - seqno); + elapsed += 100*dsec*(i - seqno); } /* Report the receipt of the reply */ @@ -884,7 +662,7 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) elapsed = TICK2DSEC(g_system_timer - next); if (elapsed < dsec) { - usleep(100000 * (dsec - elapsed)); + usleep(100000*dsec); } } diff --git a/apps/nshlib/nsh_netinit.c b/apps/nshlib/nsh_netinit.c index bb1c73dffe..bc845c4ed3 100644 --- a/apps/nshlib/nsh_netinit.c +++ b/apps/nshlib/nsh_netinit.c @@ -47,7 +47,7 @@ #include #include -#if defined(CONFIG_NSH_DHCPC) || defined(CONFIG_NSH_DNS) +#if defined(CONFIG_NSH_DHCPC) # include # include #endif @@ -60,10 +60,6 @@ * Definitions ****************************************************************************/ -#if defined(CONFIG_NSH_DRIPADDR) && !defined(CONFIG_NSH_DNSIPADDR) -# define CONFIG_NSH_DNSIPADDR CONFIG_NSH_DRIPADDR -#endif - /**************************************************************************** * Private Types ****************************************************************************/ @@ -129,14 +125,10 @@ int nsh_netinit(void) addr.s_addr = HTONL(CONFIG_NSH_NETMASK); uip_setnetmask("eth0", &addr); -#if defined(CONFIG_NSH_DHCPC) || defined(CONFIG_NSH_DNS) +#if defined(CONFIG_NSH_DHCPC) /* Set up the resolver */ resolv_init(); -#if defined(CONFIG_NSH_DNS) - addr.s_addr = HTONL(CONFIG_NSH_DNSIPADDR); - resolv_conf(&addr); -#endif #endif #if defined(CONFIG_NSH_DHCPC) diff --git a/apps/nshlib/nsh_parse.c b/apps/nshlib/nsh_parse.c index abdf5c321e..df2f7c3e39 100644 --- a/apps/nshlib/nsh_parse.c +++ b/apps/nshlib/nsh_parse.c @@ -73,19 +73,19 @@ /* Argument list size * * argv[0]: The command name. - * argv[1]: The beginning of argument (up to CONFIG_NSH_MAXARGUMENTS) + * argv[1]: The beginning of argument (up to NSH_MAX_ARGUMENTS) * argv[argc-3]: Possibly '>' or '>>' * argv[argc-2]: Possibly * argv[argc-1]: Possibly '&' (if pthreads are enabled) * argv[argc]: NULL terminating pointer * - * Maximum size is CONFIG_NSH_MAXARGUMENTS+5 + * Maximum size is NSH_MAX_ARGUMENTS+5 */ #ifndef CONFIG_NSH_DISABLEBG -# define MAX_ARGV_ENTRIES (CONFIG_NSH_MAXARGUMENTS+5) +# define MAX_ARGV_ENTRIES (NSH_MAX_ARGUMENTS+5) #else -# define MAX_ARGV_ENTRIES (CONFIG_NSH_MAXARGUMENTS+4) +# define MAX_ARGV_ENTRIES (NSH_MAX_ARGUMENTS+4) #endif /* Help command summary layout */ @@ -146,25 +146,16 @@ static const char g_failure[] = "1"; static const struct cmdmap_s g_cmdmap[] = { #if !defined(CONFIG_NSH_DISABLESCRIPT) && !defined(CONFIG_NSH_DISABLE_TEST) - { "[", cmd_lbracket, 4, CONFIG_NSH_MAXARGUMENTS, " ]" }, + { "[", cmd_lbracket, 4, NSH_MAX_ARGUMENTS, " ]" }, #endif #ifndef CONFIG_NSH_DISABLE_HELP { "?", cmd_help, 1, 1, NULL }, #endif -#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_BASE64) -# ifndef CONFIG_NSH_DISABLE_BASE64DEC - { "base64dec", cmd_base64decode, 2, 4, "[-w] [-f] " }, -# endif -# ifndef CONFIG_NSH_DISABLE_BASE64ENC - { "base64enc", cmd_base64encode, 2, 4, "[-w] [-f] " }, -# endif -#endif - #if CONFIG_NFILE_DESCRIPTORS > 0 # ifndef CONFIG_NSH_DISABLE_CAT - { "cat", cmd_cat, 2, CONFIG_NSH_MAXARGUMENTS, " [ [ ...]]" }, + { "cat", cmd_cat, 2, NSH_MAX_ARGUMENTS, " [ [ ...]]" }, # endif #ifndef CONFIG_DISABLE_ENVIRON # ifndef CONFIG_NSH_DISABLE_CD @@ -196,9 +187,9 @@ static const struct cmdmap_s g_cmdmap[] = #ifndef CONFIG_NSH_DISABLE_ECHO # ifndef CONFIG_DISABLE_ENVIRON - { "echo", cmd_echo, 0, CONFIG_NSH_MAXARGUMENTS, "[ [...]]" }, + { "echo", cmd_echo, 0, NSH_MAX_ARGUMENTS, "[ [...]]" }, # else - { "echo", cmd_echo, 0, CONFIG_NSH_MAXARGUMENTS, "[ [...]]" }, + { "echo", cmd_echo, 0, NSH_MAX_ARGUMENTS, "[ [...]]" }, # endif #endif @@ -226,20 +217,10 @@ static const struct cmdmap_s g_cmdmap[] = { "help", cmd_help, 1, 3, "[-v] []" }, # endif #endif - -#if CONFIG_NFILE_DESCRIPTORS > 0 -#ifndef CONFIG_NSH_DISABLE_HEXDUMP - { "hexdump", cmd_hexdump, 2, 2, "" }, -#endif -#endif #ifdef CONFIG_NET # ifndef CONFIG_NSH_DISABLE_IFCONFIG - { "ifconfig", cmd_ifconfig, 1, 11, "[nic_name [ip]] [dr|gw|gateway ] [netmask ] [dns ] [hw ]" }, -# endif -# ifndef CONFIG_NSH_DISABLE_IFUPDOWN - { "ifdown", cmd_ifdown, 2, 2, "" }, - { "ifup", cmd_ifup, 2, 2, "" }, + { "ifconfig", cmd_ifconfig, 1, 3, "[nic_name [ip]]" }, # endif #endif @@ -265,12 +246,6 @@ static const struct cmdmap_s g_cmdmap[] = { "mb", cmd_mb, 2, 3, "[=][ ]" }, #endif -#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_HASH_MD5) -# ifndef CONFIG_NSH_DISABLE_MD5 - { "md5", cmd_md5, 2, 3, "[-f] " }, -# endif -#endif - #if !defined(CONFIG_DISABLE_MOUNTPOINT) && CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_FS_WRITABLE) # ifndef CONFIG_NSH_DISABLE_MKDIR { "mkdir", cmd_mkdir, 2, 2, "" }, @@ -373,7 +348,7 @@ static const struct cmdmap_s g_cmdmap[] = #endif #if !defined(CONFIG_NSH_DISABLESCRIPT) && !defined(CONFIG_NSH_DISABLE_TEST) - { "test", cmd_test, 3, CONFIG_NSH_MAXARGUMENTS, "" }, + { "test", cmd_test, 3, NSH_MAX_ARGUMENTS, "" }, #endif #if !defined(CONFIG_DISABLE_MOUNTPOINT) && CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_FS_READABLE) @@ -388,15 +363,6 @@ static const struct cmdmap_s g_cmdmap[] = # endif #endif -#if defined(CONFIG_NETUTILS_CODECS) && defined(CONFIG_CODECS_URLCODE) -# ifndef CONFIG_NSH_DISABLE_URLDECODE - { "urldecode", cmd_urldecode, 2, 3, "[-f] " }, -# endif -# ifndef CONFIG_NSH_DISABLE_URLENCODE - { "urlencode", cmd_urlencode, 2, 3, "[-f] " }, -# endif -#endif - #ifndef CONFIG_DISABLE_SIGNALS # ifndef CONFIG_NSH_DISABLE_USLEEP { "usleep", cmd_usleep, 2, 2, "" }, @@ -412,7 +378,6 @@ static const struct cmdmap_s g_cmdmap[] = #ifndef CONFIG_NSH_DISABLE_XD { "xd", cmd_xd, 3, 3, " " }, #endif - { NULL, NULL, 1, 1, NULL } }; @@ -746,7 +711,7 @@ static int nsh_execute(FAR struct nsh_vtbl_s *vtbl, int argc, char *argv[]) * * argv[0]: The command name. This is argv[0] when the arguments * are, finally, received by the command vtblr - * argv[1]: The beginning of argument (up to CONFIG_NSH_MAXARGUMENTS) + * argv[1]: The beginning of argument (up to NSH_MAX_ARGUMENTS) * argv[argc]: NULL terminating pointer */ @@ -1353,13 +1318,13 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline) * of argv is: * * argv[0]: The command name. - * argv[1]: The beginning of argument (up to CONFIG_NSH_MAXARGUMENTS) + * argv[1]: The beginning of argument (up to NSH_MAX_ARGUMENTS) * argv[argc-3]: Possibly '>' or '>>' * argv[argc-2]: Possibly * argv[argc-1]: Possibly '&' * argv[argc]: NULL terminating pointer * - * Maximum size is CONFIG_NSH_MAXARGUMENTS+5 + * Maximum size is NSH_MAX_ARGUMENTS+5 */ argv[0] = cmd; @@ -1433,7 +1398,7 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline) /* Check if the maximum number of arguments was exceeded */ - if (argc > CONFIG_NSH_MAXARGUMENTS) + if (argc > NSH_MAX_ARGUMENTS) { nsh_output(vtbl, g_fmttoomanyargs, cmd); } diff --git a/apps/system/Makefile b/apps/system/Makefile index 9955a6b2ce..d64bb54c6e 100644 --- a/apps/system/Makefile +++ b/apps/system/Makefile @@ -41,36 +41,31 @@ SUBDIRS = free i2c install readline poweroff ramtron sdcard sysinfo # Create the list of installed runtime modules (INSTALLED_DIRS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) define ADD_DIRECTORY - INSTALLED_DIRS += $(if $(wildcard .\$1\Makefile),$1,) +INSTALLED_DIRS += ${shell if [ -r $1/Makefile ]; then echo "$1"; fi} endef -else -define ADD_DIRECTORY - INSTALLED_DIRS += $(if $(wildcard ./$1/Makefile),$1,) -endef -endif $(foreach DIR, $(SUBDIRS), $(eval $(call ADD_DIRECTORY,$(DIR)))) all: nothing .PHONY: nothing context depend clean distclean -define SDIR_template -$(1)_$(2): - $(Q) $(MAKE) -C $(1) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" -endef - -$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),depend))) -$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),clean))) -$(foreach SDIR, $(INSTALLED_DIRS), $(eval $(call SDIR_template,$(SDIR),distclean))) - nothing: context: -depend: $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_depend) +depend: + @for dir in $(INSTALLED_DIRS) ; do \ + $(MAKE) -C $$dir depend TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ + done -clean: $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_clean) +clean: + @for dir in $(INSTALLED_DIRS) ; do \ + $(MAKE) -C $$dir clean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ + done + +distclean: clean + @for dir in $(INSTALLED_DIRS) ; do \ + $(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \ + done -distclean: clean $(foreach SDIR, $(INSTALLED_DIRS), $(SDIR)_distclean) diff --git a/apps/system/free/Makefile b/apps/system/free/Makefile index dada00d992..7f911d81cc 100644 --- a/apps/system/free/Makefile +++ b/apps/system/free/Makefile @@ -1,7 +1,7 @@ ############################################################################ # apps/system/free/Makefile # -# Copyright (C) 2011-2012 Uros Platise. All rights reserved. +# Copyright (C) 2011 Uros Platise. All rights reserved. # Author: Uros Platise # Gregory Nutt # @@ -61,14 +61,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -87,32 +83,32 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) - $(Q) touch .built + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) + @touch .built # Register application .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - $(Q) touch $@ + @touch $@ context: .context # Create dependencies .depend: Makefile $(SRCS) - $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, .context) - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f .context Make.dep .depend -include Make.dep diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile index 029d2b6fe4..00db91bb70 100644 --- a/apps/system/i2c/Makefile +++ b/apps/system/i2c/Makefile @@ -48,14 +48,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -77,29 +73,30 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) - $(Q) touch .built + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) + @touch .built .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - $(Q) touch $@ + @touch $@ context: .context .depend: Makefile $(SRCS) - $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(ROOTDEPPATH) \ + $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, .context) - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f Make.dep .depend -include Make.dep diff --git a/apps/system/install/Makefile b/apps/system/install/Makefile index 6a02d859ff..71d82f34ce 100644 --- a/apps/system/install/Makefile +++ b/apps/system/install/Makefile @@ -2,7 +2,6 @@ # apps/system/install/Makefile # # Copyright (C) 2011 Uros Platise. All rights reserved. -# Copyright (C) 2012 Gregory Nutt. All rights reserved. # Author: Uros Platise # Gregory Nutt # @@ -62,14 +61,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -88,32 +83,32 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) - $(Q) touch .built + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) + @touch .built # Register application .context: $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) - $(Q) touch $@ + @touch $@ context: .context # Create dependencies .depend: Makefile $(SRCS) - $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, .context) - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f .context Make.dep .depend -include Make.dep diff --git a/apps/system/readline/Makefile b/apps/system/readline/Makefile index 3a48d324e7..34fab7e810 100644 --- a/apps/system/readline/Makefile +++ b/apps/system/readline/Makefile @@ -52,14 +52,10 @@ COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - BIN = ..\..\libapps$(LIBEXT) -else ifeq ($(WINTOOL),y) - BIN = ..\\..\\libapps$(LIBEXT) + BIN = "${shell cygpath -w $(APPDIR)/libapps$(LIBEXT)}" else - BIN = ../../libapps$(LIBEXT) -endif + BIN = "$(APPDIR)/libapps$(LIBEXT)" endif ROOTDEPPATH = --dep-path . @@ -78,8 +74,10 @@ $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) .built: $(OBJS) - $(call ARCHIVE, $(BIN), $(OBJS)) - $(Q) touch .built + @( for obj in $(OBJS) ; do \ + $(call ARCHIVE, $(BIN), $${obj}); \ + done ; ) + @touch .built # Context build phase target @@ -88,20 +86,18 @@ context: # Dependency build phase target .depend: Makefile $(SRCS) - $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ + @$(MKDEP) $(ROOTDEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ depend: .depend # Housekeeping targets clean: - $(call DELFILE, .built) + @rm -f *.o *~ .*.swp .built $(call CLEAN) distclean: clean - $(call DELFILE, .context) - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) + @rm -f .context Make.dep .depend -include Make.dep From 9e2076b4e4a48e20e7e5e7d85491e842cc827e22 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 28 Dec 2012 15:10:25 +0100 Subject: [PATCH 201/206] Cleared last differences, ready for testing --- apps/nshlib/nsh_codeccmd.c | 538 ------ nuttx/Makefile.unix | 749 -------- nuttx/Makefile.win | 740 -------- nuttx/arch/arm/include/elf.h | 243 --- nuttx/arch/arm/src/arm/up_elf.c | 257 --- nuttx/arch/arm/src/armv7-m/Kconfig | 51 - nuttx/arch/arm/src/armv7-m/Toolchain.defs | 266 --- nuttx/arch/arm/src/armv7-m/up_elf.c | 450 ----- nuttx/arch/arm/src/armv7-m/up_memcpy.S | 416 ----- nuttx/arch/arm/src/common/arm-elf.h | 53 - nuttx/binfmt/elf.c | 302 --- nuttx/binfmt/libelf/Kconfig | 40 - nuttx/binfmt/libelf/Make.defs | 58 - nuttx/binfmt/libelf/gnu-elf.ld | 129 -- nuttx/binfmt/libelf/libelf.h | 258 --- nuttx/binfmt/libelf/libelf_bind.c | 306 --- nuttx/binfmt/libelf/libelf_ctors.c | 215 --- nuttx/binfmt/libelf/libelf_dtors.c | 215 --- nuttx/binfmt/libelf/libelf_init.c | 202 -- nuttx/binfmt/libelf/libelf_iobuffer.c | 136 -- nuttx/binfmt/libelf/libelf_load.c | 263 --- nuttx/binfmt/libelf/libelf_read.c | 161 -- nuttx/binfmt/libelf/libelf_sections.c | 284 --- nuttx/binfmt/libelf/libelf_symbols.c | 329 ---- nuttx/binfmt/libelf/libelf_uninit.c | 126 -- nuttx/binfmt/libelf/libelf_unload.c | 119 -- nuttx/binfmt/libelf/libelf_verify.c | 120 -- nuttx/drivers/input/max11802.c | 1313 ------------- nuttx/drivers/input/max11802.h | 167 -- nuttx/drivers/lcd/ug-2864ambag01.c | 1161 ------------ nuttx/include/elf32.h | 352 ---- nuttx/include/nuttx/binfmt/binfmt.h | 226 --- nuttx/include/nuttx/binfmt/elf.h | 302 --- nuttx/include/nuttx/binfmt/nxflat.h | 264 --- nuttx/include/nuttx/binfmt/symtab.h | 163 -- nuttx/include/nuttx/float.h | 225 --- nuttx/include/nuttx/input/max11802.h | 175 -- nuttx/include/nuttx/lcd/ug-2864ambag01.h | 245 --- nuttx/libc/Kconfig | 275 --- nuttx/libc/Makefile | 145 -- nuttx/libc/README.txt | 85 - nuttx/libc/dirent/Make.defs | 48 - nuttx/libc/dirent/lib_readdirr.c | 122 -- nuttx/libc/dirent/lib_telldir.c | 91 - nuttx/libc/fixedmath/Make.defs | 43 - nuttx/libc/fixedmath/lib_b16atan2.c | 108 -- nuttx/libc/fixedmath/lib_b16cos.c | 64 - nuttx/libc/fixedmath/lib_b16sin.c | 110 -- nuttx/libc/fixedmath/lib_fixedmath.c | 272 --- nuttx/libc/fixedmath/lib_rint.c | 135 -- nuttx/libc/lib.csv | 171 -- nuttx/libc/lib_internal.h | 211 --- nuttx/libc/libgen/Make.defs | 43 - nuttx/libc/libgen/lib_basename.c | 131 -- nuttx/libc/libgen/lib_dirname.c | 144 -- nuttx/libc/math/Kconfig | 26 - nuttx/libc/math/Make.defs | 62 - nuttx/libc/math/lib_acos.c | 46 - nuttx/libc/math/lib_acosf.c | 41 - nuttx/libc/math/lib_acosl.c | 46 - nuttx/libc/math/lib_asin.c | 69 - nuttx/libc/math/lib_asinf.c | 65 - nuttx/libc/math/lib_asinl.c | 69 - nuttx/libc/math/lib_atan.c | 48 - nuttx/libc/math/lib_atan2.c | 86 - nuttx/libc/math/lib_atan2f.c | 81 - nuttx/libc/math/lib_atan2l.c | 87 - nuttx/libc/math/lib_atanf.c | 43 - nuttx/libc/math/lib_atanl.c | 48 - nuttx/libc/math/lib_ceil.c | 52 - nuttx/libc/math/lib_ceilf.c | 47 - nuttx/libc/math/lib_ceill.c | 52 - nuttx/libc/math/lib_cos.c | 46 - nuttx/libc/math/lib_cosf.c | 41 - nuttx/libc/math/lib_cosh.c | 47 - nuttx/libc/math/lib_coshf.c | 42 - nuttx/libc/math/lib_coshl.c | 47 - nuttx/libc/math/lib_cosl.c | 46 - nuttx/libc/math/lib_exp.c | 126 -- nuttx/libc/math/lib_expf.c | 112 -- nuttx/libc/math/lib_expl.c | 126 -- nuttx/libc/math/lib_fabs.c | 46 - nuttx/libc/math/lib_fabsf.c | 41 - nuttx/libc/math/lib_fabsl.c | 46 - nuttx/libc/math/lib_floor.c | 52 - nuttx/libc/math/lib_floorf.c | 47 - nuttx/libc/math/lib_floorl.c | 52 - nuttx/libc/math/lib_fmod.c | 52 - nuttx/libc/math/lib_fmodf.c | 47 - nuttx/libc/math/lib_fmodl.c | 52 - nuttx/libc/math/lib_frexp.c | 47 - nuttx/libc/math/lib_frexpf.c | 42 - nuttx/libc/math/lib_frexpl.c | 47 - nuttx/libc/math/lib_ldexp.c | 46 - nuttx/libc/math/lib_ldexpf.c | 41 - nuttx/libc/math/lib_ldexpl.c | 46 - nuttx/libc/math/lib_libexpi.c | 103 -- nuttx/libc/math/lib_libsqrtapprox.c | 50 - nuttx/libc/math/lib_log.c | 82 - nuttx/libc/math/lib_log10.c | 46 - nuttx/libc/math/lib_log10f.c | 41 - nuttx/libc/math/lib_log10l.c | 46 - nuttx/libc/math/lib_log2.c | 46 - nuttx/libc/math/lib_log2f.c | 41 - nuttx/libc/math/lib_log2l.c | 46 - nuttx/libc/math/lib_logf.c | 77 - nuttx/libc/math/lib_logl.c | 80 - nuttx/libc/math/lib_modf.c | 58 - nuttx/libc/math/lib_modff.c | 55 - nuttx/libc/math/lib_modfl.c | 61 - nuttx/libc/math/lib_pow.c | 46 - nuttx/libc/math/lib_powf.c | 41 - nuttx/libc/math/lib_powl.c | 46 - nuttx/libc/math/lib_sin.c | 114 -- nuttx/libc/math/lib_sinf.c | 104 -- nuttx/libc/math/lib_sinh.c | 47 - nuttx/libc/math/lib_sinhf.c | 42 - nuttx/libc/math/lib_sinhl.c | 47 - nuttx/libc/math/lib_sinl.c | 114 -- nuttx/libc/math/lib_sqrt.c | 99 - nuttx/libc/math/lib_sqrtf.c | 84 - nuttx/libc/math/lib_sqrtl.c | 101 - nuttx/libc/math/lib_tan.c | 46 - nuttx/libc/math/lib_tanf.c | 41 - nuttx/libc/math/lib_tanh.c | 49 - nuttx/libc/math/lib_tanhf.c | 44 - nuttx/libc/math/lib_tanhl.c | 49 - nuttx/libc/math/lib_tanl.c | 46 - nuttx/libc/misc/Make.defs | 69 - nuttx/libc/misc/lib_crc32.c | 123 -- nuttx/libc/misc/lib_dbg.c | 165 -- nuttx/libc/misc/lib_dumpbuffer.c | 129 -- nuttx/libc/misc/lib_filesem.c | 145 -- nuttx/libc/misc/lib_init.c | 207 --- nuttx/libc/misc/lib_match.c | 148 -- nuttx/libc/misc/lib_sendfile.c | 297 --- nuttx/libc/misc/lib_streamsem.c | 90 - nuttx/libc/mqueue/Make.defs | 48 - nuttx/libc/mqueue/mq_getattr.c | 104 -- nuttx/libc/mqueue/mq_setattr.c | 118 -- nuttx/libc/net/Make.defs | 44 - nuttx/libc/net/lib_etherntoa.c | 69 - nuttx/libc/net/lib_htonl.c | 68 - nuttx/libc/net/lib_htons.c | 65 - nuttx/libc/net/lib_inetaddr.c | 74 - nuttx/libc/net/lib_inetntoa.c | 79 - nuttx/libc/net/lib_inetntop.c | 202 -- nuttx/libc/net/lib_inetpton.c | 338 ---- nuttx/libc/pthread/Make.defs | 56 - nuttx/libc/pthread/pthread_attrdestroy.c | 108 -- .../pthread/pthread_attrgetinheritsched.c | 111 -- .../libc/pthread/pthread_attrgetschedparam.c | 110 -- .../libc/pthread/pthread_attrgetschedpolicy.c | 105 -- nuttx/libc/pthread/pthread_attrgetstacksize.c | 106 -- nuttx/libc/pthread/pthread_attrinit.c | 123 -- .../pthread/pthread_attrsetinheritsched.c | 113 -- .../libc/pthread/pthread_attrsetschedparam.c | 108 -- .../libc/pthread/pthread_attrsetschedpolicy.c | 111 -- nuttx/libc/pthread/pthread_attrsetstacksize.c | 106 -- .../libc/pthread/pthread_barrierattrdestroy.c | 102 - .../pthread/pthread_barrierattrgetpshared.c | 101 - nuttx/libc/pthread/pthread_barrierattrinit.c | 101 - .../pthread/pthread_barrierattrsetpshared.c | 111 -- nuttx/libc/pthread/pthread_condattrdestroy.c | 82 - nuttx/libc/pthread/pthread_condattrinit.c | 85 - nuttx/libc/pthread/pthread_mutexattrdestroy.c | 104 -- .../pthread/pthread_mutexattrgetpshared.c | 104 -- nuttx/libc/pthread/pthread_mutexattrgettype.c | 98 - nuttx/libc/pthread/pthread_mutexattrinit.c | 106 -- .../pthread/pthread_mutexattrsetpshared.c | 104 -- nuttx/libc/pthread/pthread_mutexattrsettype.c | 98 - nuttx/libc/queue/Make.defs | 47 - nuttx/libc/queue/dq_addafter.c | 74 - nuttx/libc/queue/dq_addbefore.c | 69 - nuttx/libc/queue/dq_addfirst.c | 74 - nuttx/libc/queue/dq_addlast.c | 74 - nuttx/libc/queue/dq_rem.c | 84 - nuttx/libc/queue/dq_remfirst.c | 82 - nuttx/libc/queue/dq_remlast.c | 78 - nuttx/libc/queue/sq_addafter.c | 71 - nuttx/libc/queue/sq_addfirst.c | 67 - nuttx/libc/queue/sq_addlast.c | 72 - nuttx/libc/queue/sq_rem.c | 83 - nuttx/libc/queue/sq_remafter.c | 79 - nuttx/libc/queue/sq_remfirst.c | 76 - nuttx/libc/queue/sq_remlast.c | 87 - nuttx/libc/sched/Make.defs | 43 - nuttx/libc/sched/sched_getprioritymax.c | 100 - nuttx/libc/sched/sched_getprioritymin.c | 100 - nuttx/libc/semaphore/Make.defs | 43 - nuttx/libc/semaphore/sem_getvalue.c | 108 -- nuttx/libc/semaphore/sem_init.c | 125 -- nuttx/libc/signal/Make.defs | 47 - nuttx/libc/signal/sig_addset.c | 100 - nuttx/libc/signal/sig_delset.c | 100 - nuttx/libc/signal/sig_emptyset.c | 88 - nuttx/libc/signal/sig_fillset.c | 88 - nuttx/libc/signal/sig_ismember.c | 101 - nuttx/libc/stdio/Make.defs | 85 - nuttx/libc/stdio/lib_asprintf.c | 105 -- nuttx/libc/stdio/lib_avsprintf.c | 146 -- nuttx/libc/stdio/lib_clearerr.c | 69 - nuttx/libc/stdio/lib_dtoa.c | 1641 ----------------- nuttx/libc/stdio/lib_fclose.c | 154 -- nuttx/libc/stdio/lib_feof.c | 77 - nuttx/libc/stdio/lib_ferror.c | 90 - nuttx/libc/stdio/lib_fflush.c | 132 -- nuttx/libc/stdio/lib_fgetc.c | 101 - nuttx/libc/stdio/lib_fgetpos.c | 123 -- nuttx/libc/stdio/lib_fgets.c | 207 --- nuttx/libc/stdio/lib_fileno.c | 70 - nuttx/libc/stdio/lib_fopen.c | 299 --- nuttx/libc/stdio/lib_fprintf.c | 93 - nuttx/libc/stdio/lib_fputc.c | 113 -- nuttx/libc/stdio/lib_fputs.c | 220 --- nuttx/libc/stdio/lib_fread.c | 101 - nuttx/libc/stdio/lib_fseek.c | 138 -- nuttx/libc/stdio/lib_fsetpos.c | 116 -- nuttx/libc/stdio/lib_ftell.c | 129 -- nuttx/libc/stdio/lib_fwrite.c | 99 - nuttx/libc/stdio/lib_gets.c | 120 -- nuttx/libc/stdio/lib_libdtoa.c | 304 --- nuttx/libc/stdio/lib_libfflush.c | 202 -- nuttx/libc/stdio/lib_libflushall.c | 137 -- nuttx/libc/stdio/lib_libfread.c | 315 ---- nuttx/libc/stdio/lib_libfwrite.c | 179 -- nuttx/libc/stdio/lib_libnoflush.c | 103 -- nuttx/libc/stdio/lib_libsprintf.c | 90 - nuttx/libc/stdio/lib_libvsprintf.c | 1620 ---------------- nuttx/libc/stdio/lib_lowinstream.c | 102 - nuttx/libc/stdio/lib_lowoutstream.c | 97 - nuttx/libc/stdio/lib_lowprintf.c | 128 -- nuttx/libc/stdio/lib_meminstream.c | 104 -- nuttx/libc/stdio/lib_memoutstream.c | 105 -- nuttx/libc/stdio/lib_nullinstream.c | 79 - nuttx/libc/stdio/lib_nulloutstream.c | 84 - nuttx/libc/stdio/lib_perror.c | 99 - nuttx/libc/stdio/lib_printf.c | 109 -- nuttx/libc/stdio/lib_puts.c | 130 -- nuttx/libc/stdio/lib_rawinstream.c | 107 -- nuttx/libc/stdio/lib_rawoutstream.c | 115 -- nuttx/libc/stdio/lib_rawprintf.c | 151 -- nuttx/libc/stdio/lib_rdflush.c | 144 -- nuttx/libc/stdio/lib_snprintf.c | 99 - nuttx/libc/stdio/lib_sprintf.c | 95 - nuttx/libc/stdio/lib_sscanf.c | 507 ----- nuttx/libc/stdio/lib_stdinstream.c | 99 - nuttx/libc/stdio/lib_stdoutstream.c | 147 -- nuttx/libc/stdio/lib_syslogstream.c | 122 -- nuttx/libc/stdio/lib_ungetc.c | 121 -- nuttx/libc/stdio/lib_vfprintf.c | 102 - nuttx/libc/stdio/lib_vprintf.c | 92 - nuttx/libc/stdio/lib_vsnprintf.c | 96 - nuttx/libc/stdio/lib_vsprintf.c | 92 - nuttx/libc/stdio/lib_wrflush.c | 134 -- nuttx/libc/stdio/lib_zeroinstream.c | 79 - nuttx/libc/stdlib/Make.defs | 44 - nuttx/libc/stdlib/lib_abort.c | 121 -- nuttx/libc/stdlib/lib_abs.c | 54 - nuttx/libc/stdlib/lib_imaxabs.c | 54 - nuttx/libc/stdlib/lib_labs.c | 54 - nuttx/libc/stdlib/lib_llabs.c | 57 - nuttx/libc/stdlib/lib_qsort.c | 238 --- nuttx/libc/stdlib/lib_rand.c | 220 --- nuttx/libc/string/Make.defs | 58 - nuttx/libc/string/lib_checkbase.c | 115 -- nuttx/libc/string/lib_isbasedigit.c | 105 -- nuttx/libc/string/lib_memccpy.c | 99 - nuttx/libc/string/lib_memchr.c | 80 - nuttx/libc/string/lib_memcmp.c | 74 - nuttx/libc/string/lib_memcpy.c | 64 - nuttx/libc/string/lib_memmove.c | 77 - nuttx/libc/string/lib_memset.c | 188 -- nuttx/libc/string/lib_skipspace.c | 69 - nuttx/libc/string/lib_strcasecmp.c | 65 - nuttx/libc/string/lib_strcasestr.c | 134 -- nuttx/libc/string/lib_strcat.c | 62 - nuttx/libc/string/lib_strchr.c | 78 - nuttx/libc/string/lib_strcmp.c | 59 - nuttx/libc/string/lib_strcpy.c | 55 - nuttx/libc/string/lib_strcspn.c | 67 - nuttx/libc/string/lib_strdup.c | 62 - nuttx/libc/string/lib_strerror.c | 375 ---- nuttx/libc/string/lib_strlen.c | 55 - nuttx/libc/string/lib_strncasecmp.c | 70 - nuttx/libc/string/lib_strncat.c | 62 - nuttx/libc/string/lib_strncmp.c | 65 - nuttx/libc/string/lib_strncpy.c | 57 - nuttx/libc/string/lib_strndup.c | 93 - nuttx/libc/string/lib_strnlen.c | 62 - nuttx/libc/string/lib_strpbrk.c | 85 - nuttx/libc/string/lib_strrchr.c | 68 - nuttx/libc/string/lib_strspn.c | 66 - nuttx/libc/string/lib_strstr.c | 104 -- nuttx/libc/string/lib_strtod.c | 241 --- nuttx/libc/string/lib_strtok.c | 87 - nuttx/libc/string/lib_strtokr.c | 157 -- nuttx/libc/string/lib_strtol.c | 103 -- nuttx/libc/string/lib_strtoll.c | 107 -- nuttx/libc/string/lib_strtoul.c | 98 - nuttx/libc/string/lib_strtoull.c | 100 - nuttx/libc/string/lib_vikmemcpy.c | 348 ---- nuttx/libc/termios/Make.defs | 54 - nuttx/libc/termios/lib_cfgetspeed.c | 93 - nuttx/libc/termios/lib_cfsetspeed.c | 116 -- nuttx/libc/termios/lib_tcflush.c | 88 - nuttx/libc/termios/lib_tcgetattr.c | 93 - nuttx/libc/termios/lib_tcsetattr.c | 122 -- nuttx/libc/time/Make.defs | 44 - nuttx/libc/time/lib_calendar2utc.c | 209 --- nuttx/libc/time/lib_daysbeforemonth.c | 102 - nuttx/libc/time/lib_gmtime.c | 93 - nuttx/libc/time/lib_gmtimer.c | 355 ---- nuttx/libc/time/lib_isleapyear.c | 88 - nuttx/libc/time/lib_mktime.c | 141 -- nuttx/libc/time/lib_strftime.c | 398 ---- nuttx/libc/time/lib_time.c | 110 -- nuttx/libc/unistd/Make.defs | 49 - nuttx/libc/unistd/lib_chdir.c | 179 -- nuttx/libc/unistd/lib_getcwd.c | 132 -- nuttx/libc/unistd/lib_getopt.c | 269 --- nuttx/libc/unistd/lib_getoptargp.c | 73 - nuttx/libc/unistd/lib_getoptindp.c | 73 - nuttx/libc/unistd/lib_getoptoptp.c | 73 - nuttx/libxx/libxx_cxa_atexit.cxx | 146 -- nuttx/libxx/libxx_internal.hxx | 67 - nuttx/libxx/libxx_stdthrow.cxx | 74 - nuttx/sched/pause.c | 110 -- nuttx/tools/define.bat | 178 -- nuttx/tools/incdir.bat | 133 -- nuttx/tools/mkdeps.bat | 173 -- nuttx/tools/mkdeps.c | 721 -------- 332 files changed, 45238 deletions(-) delete mode 100644 apps/nshlib/nsh_codeccmd.c delete mode 100644 nuttx/Makefile.unix delete mode 100644 nuttx/Makefile.win delete mode 100644 nuttx/arch/arm/include/elf.h delete mode 100644 nuttx/arch/arm/src/arm/up_elf.c delete mode 100644 nuttx/arch/arm/src/armv7-m/Kconfig delete mode 100644 nuttx/arch/arm/src/armv7-m/Toolchain.defs delete mode 100644 nuttx/arch/arm/src/armv7-m/up_elf.c delete mode 100644 nuttx/arch/arm/src/armv7-m/up_memcpy.S delete mode 100644 nuttx/arch/arm/src/common/arm-elf.h delete mode 100644 nuttx/binfmt/elf.c delete mode 100644 nuttx/binfmt/libelf/Kconfig delete mode 100644 nuttx/binfmt/libelf/Make.defs delete mode 100644 nuttx/binfmt/libelf/gnu-elf.ld delete mode 100644 nuttx/binfmt/libelf/libelf.h delete mode 100644 nuttx/binfmt/libelf/libelf_bind.c delete mode 100644 nuttx/binfmt/libelf/libelf_ctors.c delete mode 100644 nuttx/binfmt/libelf/libelf_dtors.c delete mode 100644 nuttx/binfmt/libelf/libelf_init.c delete mode 100644 nuttx/binfmt/libelf/libelf_iobuffer.c delete mode 100644 nuttx/binfmt/libelf/libelf_load.c delete mode 100644 nuttx/binfmt/libelf/libelf_read.c delete mode 100644 nuttx/binfmt/libelf/libelf_sections.c delete mode 100644 nuttx/binfmt/libelf/libelf_symbols.c delete mode 100644 nuttx/binfmt/libelf/libelf_uninit.c delete mode 100644 nuttx/binfmt/libelf/libelf_unload.c delete mode 100644 nuttx/binfmt/libelf/libelf_verify.c delete mode 100644 nuttx/drivers/input/max11802.c delete mode 100644 nuttx/drivers/input/max11802.h delete mode 100644 nuttx/drivers/lcd/ug-2864ambag01.c delete mode 100644 nuttx/include/elf32.h delete mode 100644 nuttx/include/nuttx/binfmt/binfmt.h delete mode 100644 nuttx/include/nuttx/binfmt/elf.h delete mode 100644 nuttx/include/nuttx/binfmt/nxflat.h delete mode 100644 nuttx/include/nuttx/binfmt/symtab.h delete mode 100644 nuttx/include/nuttx/float.h delete mode 100644 nuttx/include/nuttx/input/max11802.h delete mode 100644 nuttx/include/nuttx/lcd/ug-2864ambag01.h delete mode 100644 nuttx/libc/Kconfig delete mode 100644 nuttx/libc/Makefile delete mode 100644 nuttx/libc/README.txt delete mode 100644 nuttx/libc/dirent/Make.defs delete mode 100644 nuttx/libc/dirent/lib_readdirr.c delete mode 100644 nuttx/libc/dirent/lib_telldir.c delete mode 100644 nuttx/libc/fixedmath/Make.defs delete mode 100644 nuttx/libc/fixedmath/lib_b16atan2.c delete mode 100644 nuttx/libc/fixedmath/lib_b16cos.c delete mode 100644 nuttx/libc/fixedmath/lib_b16sin.c delete mode 100644 nuttx/libc/fixedmath/lib_fixedmath.c delete mode 100644 nuttx/libc/fixedmath/lib_rint.c delete mode 100644 nuttx/libc/lib.csv delete mode 100644 nuttx/libc/lib_internal.h delete mode 100644 nuttx/libc/libgen/Make.defs delete mode 100644 nuttx/libc/libgen/lib_basename.c delete mode 100644 nuttx/libc/libgen/lib_dirname.c delete mode 100644 nuttx/libc/math/Kconfig delete mode 100644 nuttx/libc/math/Make.defs delete mode 100644 nuttx/libc/math/lib_acos.c delete mode 100644 nuttx/libc/math/lib_acosf.c delete mode 100644 nuttx/libc/math/lib_acosl.c delete mode 100644 nuttx/libc/math/lib_asin.c delete mode 100644 nuttx/libc/math/lib_asinf.c delete mode 100644 nuttx/libc/math/lib_asinl.c delete mode 100644 nuttx/libc/math/lib_atan.c delete mode 100644 nuttx/libc/math/lib_atan2.c delete mode 100644 nuttx/libc/math/lib_atan2f.c delete mode 100644 nuttx/libc/math/lib_atan2l.c delete mode 100644 nuttx/libc/math/lib_atanf.c delete mode 100644 nuttx/libc/math/lib_atanl.c delete mode 100644 nuttx/libc/math/lib_ceil.c delete mode 100644 nuttx/libc/math/lib_ceilf.c delete mode 100644 nuttx/libc/math/lib_ceill.c delete mode 100644 nuttx/libc/math/lib_cos.c delete mode 100644 nuttx/libc/math/lib_cosf.c delete mode 100644 nuttx/libc/math/lib_cosh.c delete mode 100644 nuttx/libc/math/lib_coshf.c delete mode 100644 nuttx/libc/math/lib_coshl.c delete mode 100644 nuttx/libc/math/lib_cosl.c delete mode 100644 nuttx/libc/math/lib_exp.c delete mode 100644 nuttx/libc/math/lib_expf.c delete mode 100644 nuttx/libc/math/lib_expl.c delete mode 100644 nuttx/libc/math/lib_fabs.c delete mode 100644 nuttx/libc/math/lib_fabsf.c delete mode 100644 nuttx/libc/math/lib_fabsl.c delete mode 100644 nuttx/libc/math/lib_floor.c delete mode 100644 nuttx/libc/math/lib_floorf.c delete mode 100644 nuttx/libc/math/lib_floorl.c delete mode 100644 nuttx/libc/math/lib_fmod.c delete mode 100644 nuttx/libc/math/lib_fmodf.c delete mode 100644 nuttx/libc/math/lib_fmodl.c delete mode 100644 nuttx/libc/math/lib_frexp.c delete mode 100644 nuttx/libc/math/lib_frexpf.c delete mode 100644 nuttx/libc/math/lib_frexpl.c delete mode 100644 nuttx/libc/math/lib_ldexp.c delete mode 100644 nuttx/libc/math/lib_ldexpf.c delete mode 100644 nuttx/libc/math/lib_ldexpl.c delete mode 100644 nuttx/libc/math/lib_libexpi.c delete mode 100644 nuttx/libc/math/lib_libsqrtapprox.c delete mode 100644 nuttx/libc/math/lib_log.c delete mode 100644 nuttx/libc/math/lib_log10.c delete mode 100644 nuttx/libc/math/lib_log10f.c delete mode 100644 nuttx/libc/math/lib_log10l.c delete mode 100644 nuttx/libc/math/lib_log2.c delete mode 100644 nuttx/libc/math/lib_log2f.c delete mode 100644 nuttx/libc/math/lib_log2l.c delete mode 100644 nuttx/libc/math/lib_logf.c delete mode 100644 nuttx/libc/math/lib_logl.c delete mode 100644 nuttx/libc/math/lib_modf.c delete mode 100644 nuttx/libc/math/lib_modff.c delete mode 100644 nuttx/libc/math/lib_modfl.c delete mode 100644 nuttx/libc/math/lib_pow.c delete mode 100644 nuttx/libc/math/lib_powf.c delete mode 100644 nuttx/libc/math/lib_powl.c delete mode 100644 nuttx/libc/math/lib_sin.c delete mode 100644 nuttx/libc/math/lib_sinf.c delete mode 100644 nuttx/libc/math/lib_sinh.c delete mode 100644 nuttx/libc/math/lib_sinhf.c delete mode 100644 nuttx/libc/math/lib_sinhl.c delete mode 100644 nuttx/libc/math/lib_sinl.c delete mode 100644 nuttx/libc/math/lib_sqrt.c delete mode 100644 nuttx/libc/math/lib_sqrtf.c delete mode 100644 nuttx/libc/math/lib_sqrtl.c delete mode 100644 nuttx/libc/math/lib_tan.c delete mode 100644 nuttx/libc/math/lib_tanf.c delete mode 100644 nuttx/libc/math/lib_tanh.c delete mode 100644 nuttx/libc/math/lib_tanhf.c delete mode 100644 nuttx/libc/math/lib_tanhl.c delete mode 100644 nuttx/libc/math/lib_tanl.c delete mode 100644 nuttx/libc/misc/Make.defs delete mode 100644 nuttx/libc/misc/lib_crc32.c delete mode 100644 nuttx/libc/misc/lib_dbg.c delete mode 100644 nuttx/libc/misc/lib_dumpbuffer.c delete mode 100644 nuttx/libc/misc/lib_filesem.c delete mode 100644 nuttx/libc/misc/lib_init.c delete mode 100644 nuttx/libc/misc/lib_match.c delete mode 100644 nuttx/libc/misc/lib_sendfile.c delete mode 100644 nuttx/libc/misc/lib_streamsem.c delete mode 100644 nuttx/libc/mqueue/Make.defs delete mode 100644 nuttx/libc/mqueue/mq_getattr.c delete mode 100644 nuttx/libc/mqueue/mq_setattr.c delete mode 100644 nuttx/libc/net/Make.defs delete mode 100644 nuttx/libc/net/lib_etherntoa.c delete mode 100644 nuttx/libc/net/lib_htonl.c delete mode 100644 nuttx/libc/net/lib_htons.c delete mode 100644 nuttx/libc/net/lib_inetaddr.c delete mode 100644 nuttx/libc/net/lib_inetntoa.c delete mode 100644 nuttx/libc/net/lib_inetntop.c delete mode 100644 nuttx/libc/net/lib_inetpton.c delete mode 100644 nuttx/libc/pthread/Make.defs delete mode 100644 nuttx/libc/pthread/pthread_attrdestroy.c delete mode 100644 nuttx/libc/pthread/pthread_attrgetinheritsched.c delete mode 100644 nuttx/libc/pthread/pthread_attrgetschedparam.c delete mode 100644 nuttx/libc/pthread/pthread_attrgetschedpolicy.c delete mode 100644 nuttx/libc/pthread/pthread_attrgetstacksize.c delete mode 100644 nuttx/libc/pthread/pthread_attrinit.c delete mode 100644 nuttx/libc/pthread/pthread_attrsetinheritsched.c delete mode 100644 nuttx/libc/pthread/pthread_attrsetschedparam.c delete mode 100644 nuttx/libc/pthread/pthread_attrsetschedpolicy.c delete mode 100644 nuttx/libc/pthread/pthread_attrsetstacksize.c delete mode 100644 nuttx/libc/pthread/pthread_barrierattrdestroy.c delete mode 100644 nuttx/libc/pthread/pthread_barrierattrgetpshared.c delete mode 100644 nuttx/libc/pthread/pthread_barrierattrinit.c delete mode 100644 nuttx/libc/pthread/pthread_barrierattrsetpshared.c delete mode 100644 nuttx/libc/pthread/pthread_condattrdestroy.c delete mode 100644 nuttx/libc/pthread/pthread_condattrinit.c delete mode 100644 nuttx/libc/pthread/pthread_mutexattrdestroy.c delete mode 100644 nuttx/libc/pthread/pthread_mutexattrgetpshared.c delete mode 100644 nuttx/libc/pthread/pthread_mutexattrgettype.c delete mode 100644 nuttx/libc/pthread/pthread_mutexattrinit.c delete mode 100644 nuttx/libc/pthread/pthread_mutexattrsetpshared.c delete mode 100644 nuttx/libc/pthread/pthread_mutexattrsettype.c delete mode 100644 nuttx/libc/queue/Make.defs delete mode 100644 nuttx/libc/queue/dq_addafter.c delete mode 100644 nuttx/libc/queue/dq_addbefore.c delete mode 100644 nuttx/libc/queue/dq_addfirst.c delete mode 100644 nuttx/libc/queue/dq_addlast.c delete mode 100644 nuttx/libc/queue/dq_rem.c delete mode 100644 nuttx/libc/queue/dq_remfirst.c delete mode 100644 nuttx/libc/queue/dq_remlast.c delete mode 100644 nuttx/libc/queue/sq_addafter.c delete mode 100644 nuttx/libc/queue/sq_addfirst.c delete mode 100644 nuttx/libc/queue/sq_addlast.c delete mode 100644 nuttx/libc/queue/sq_rem.c delete mode 100644 nuttx/libc/queue/sq_remafter.c delete mode 100644 nuttx/libc/queue/sq_remfirst.c delete mode 100644 nuttx/libc/queue/sq_remlast.c delete mode 100644 nuttx/libc/sched/Make.defs delete mode 100644 nuttx/libc/sched/sched_getprioritymax.c delete mode 100644 nuttx/libc/sched/sched_getprioritymin.c delete mode 100644 nuttx/libc/semaphore/Make.defs delete mode 100644 nuttx/libc/semaphore/sem_getvalue.c delete mode 100644 nuttx/libc/semaphore/sem_init.c delete mode 100644 nuttx/libc/signal/Make.defs delete mode 100644 nuttx/libc/signal/sig_addset.c delete mode 100644 nuttx/libc/signal/sig_delset.c delete mode 100644 nuttx/libc/signal/sig_emptyset.c delete mode 100644 nuttx/libc/signal/sig_fillset.c delete mode 100644 nuttx/libc/signal/sig_ismember.c delete mode 100644 nuttx/libc/stdio/Make.defs delete mode 100644 nuttx/libc/stdio/lib_asprintf.c delete mode 100644 nuttx/libc/stdio/lib_avsprintf.c delete mode 100644 nuttx/libc/stdio/lib_clearerr.c delete mode 100644 nuttx/libc/stdio/lib_dtoa.c delete mode 100644 nuttx/libc/stdio/lib_fclose.c delete mode 100644 nuttx/libc/stdio/lib_feof.c delete mode 100644 nuttx/libc/stdio/lib_ferror.c delete mode 100644 nuttx/libc/stdio/lib_fflush.c delete mode 100644 nuttx/libc/stdio/lib_fgetc.c delete mode 100644 nuttx/libc/stdio/lib_fgetpos.c delete mode 100644 nuttx/libc/stdio/lib_fgets.c delete mode 100644 nuttx/libc/stdio/lib_fileno.c delete mode 100644 nuttx/libc/stdio/lib_fopen.c delete mode 100644 nuttx/libc/stdio/lib_fprintf.c delete mode 100644 nuttx/libc/stdio/lib_fputc.c delete mode 100644 nuttx/libc/stdio/lib_fputs.c delete mode 100644 nuttx/libc/stdio/lib_fread.c delete mode 100644 nuttx/libc/stdio/lib_fseek.c delete mode 100644 nuttx/libc/stdio/lib_fsetpos.c delete mode 100644 nuttx/libc/stdio/lib_ftell.c delete mode 100644 nuttx/libc/stdio/lib_fwrite.c delete mode 100644 nuttx/libc/stdio/lib_gets.c delete mode 100644 nuttx/libc/stdio/lib_libdtoa.c delete mode 100644 nuttx/libc/stdio/lib_libfflush.c delete mode 100644 nuttx/libc/stdio/lib_libflushall.c delete mode 100644 nuttx/libc/stdio/lib_libfread.c delete mode 100644 nuttx/libc/stdio/lib_libfwrite.c delete mode 100644 nuttx/libc/stdio/lib_libnoflush.c delete mode 100644 nuttx/libc/stdio/lib_libsprintf.c delete mode 100644 nuttx/libc/stdio/lib_libvsprintf.c delete mode 100644 nuttx/libc/stdio/lib_lowinstream.c delete mode 100644 nuttx/libc/stdio/lib_lowoutstream.c delete mode 100644 nuttx/libc/stdio/lib_lowprintf.c delete mode 100644 nuttx/libc/stdio/lib_meminstream.c delete mode 100644 nuttx/libc/stdio/lib_memoutstream.c delete mode 100644 nuttx/libc/stdio/lib_nullinstream.c delete mode 100644 nuttx/libc/stdio/lib_nulloutstream.c delete mode 100644 nuttx/libc/stdio/lib_perror.c delete mode 100644 nuttx/libc/stdio/lib_printf.c delete mode 100644 nuttx/libc/stdio/lib_puts.c delete mode 100644 nuttx/libc/stdio/lib_rawinstream.c delete mode 100644 nuttx/libc/stdio/lib_rawoutstream.c delete mode 100644 nuttx/libc/stdio/lib_rawprintf.c delete mode 100644 nuttx/libc/stdio/lib_rdflush.c delete mode 100644 nuttx/libc/stdio/lib_snprintf.c delete mode 100644 nuttx/libc/stdio/lib_sprintf.c delete mode 100644 nuttx/libc/stdio/lib_sscanf.c delete mode 100644 nuttx/libc/stdio/lib_stdinstream.c delete mode 100644 nuttx/libc/stdio/lib_stdoutstream.c delete mode 100644 nuttx/libc/stdio/lib_syslogstream.c delete mode 100644 nuttx/libc/stdio/lib_ungetc.c delete mode 100644 nuttx/libc/stdio/lib_vfprintf.c delete mode 100644 nuttx/libc/stdio/lib_vprintf.c delete mode 100644 nuttx/libc/stdio/lib_vsnprintf.c delete mode 100644 nuttx/libc/stdio/lib_vsprintf.c delete mode 100644 nuttx/libc/stdio/lib_wrflush.c delete mode 100644 nuttx/libc/stdio/lib_zeroinstream.c delete mode 100644 nuttx/libc/stdlib/Make.defs delete mode 100644 nuttx/libc/stdlib/lib_abort.c delete mode 100644 nuttx/libc/stdlib/lib_abs.c delete mode 100644 nuttx/libc/stdlib/lib_imaxabs.c delete mode 100644 nuttx/libc/stdlib/lib_labs.c delete mode 100644 nuttx/libc/stdlib/lib_llabs.c delete mode 100644 nuttx/libc/stdlib/lib_qsort.c delete mode 100644 nuttx/libc/stdlib/lib_rand.c delete mode 100644 nuttx/libc/string/Make.defs delete mode 100644 nuttx/libc/string/lib_checkbase.c delete mode 100644 nuttx/libc/string/lib_isbasedigit.c delete mode 100644 nuttx/libc/string/lib_memccpy.c delete mode 100644 nuttx/libc/string/lib_memchr.c delete mode 100644 nuttx/libc/string/lib_memcmp.c delete mode 100644 nuttx/libc/string/lib_memcpy.c delete mode 100644 nuttx/libc/string/lib_memmove.c delete mode 100644 nuttx/libc/string/lib_memset.c delete mode 100644 nuttx/libc/string/lib_skipspace.c delete mode 100644 nuttx/libc/string/lib_strcasecmp.c delete mode 100644 nuttx/libc/string/lib_strcasestr.c delete mode 100644 nuttx/libc/string/lib_strcat.c delete mode 100644 nuttx/libc/string/lib_strchr.c delete mode 100644 nuttx/libc/string/lib_strcmp.c delete mode 100644 nuttx/libc/string/lib_strcpy.c delete mode 100644 nuttx/libc/string/lib_strcspn.c delete mode 100644 nuttx/libc/string/lib_strdup.c delete mode 100644 nuttx/libc/string/lib_strerror.c delete mode 100644 nuttx/libc/string/lib_strlen.c delete mode 100644 nuttx/libc/string/lib_strncasecmp.c delete mode 100644 nuttx/libc/string/lib_strncat.c delete mode 100644 nuttx/libc/string/lib_strncmp.c delete mode 100644 nuttx/libc/string/lib_strncpy.c delete mode 100644 nuttx/libc/string/lib_strndup.c delete mode 100644 nuttx/libc/string/lib_strnlen.c delete mode 100644 nuttx/libc/string/lib_strpbrk.c delete mode 100644 nuttx/libc/string/lib_strrchr.c delete mode 100644 nuttx/libc/string/lib_strspn.c delete mode 100644 nuttx/libc/string/lib_strstr.c delete mode 100644 nuttx/libc/string/lib_strtod.c delete mode 100644 nuttx/libc/string/lib_strtok.c delete mode 100644 nuttx/libc/string/lib_strtokr.c delete mode 100644 nuttx/libc/string/lib_strtol.c delete mode 100644 nuttx/libc/string/lib_strtoll.c delete mode 100644 nuttx/libc/string/lib_strtoul.c delete mode 100644 nuttx/libc/string/lib_strtoull.c delete mode 100644 nuttx/libc/string/lib_vikmemcpy.c delete mode 100644 nuttx/libc/termios/Make.defs delete mode 100644 nuttx/libc/termios/lib_cfgetspeed.c delete mode 100644 nuttx/libc/termios/lib_cfsetspeed.c delete mode 100644 nuttx/libc/termios/lib_tcflush.c delete mode 100644 nuttx/libc/termios/lib_tcgetattr.c delete mode 100644 nuttx/libc/termios/lib_tcsetattr.c delete mode 100644 nuttx/libc/time/Make.defs delete mode 100644 nuttx/libc/time/lib_calendar2utc.c delete mode 100644 nuttx/libc/time/lib_daysbeforemonth.c delete mode 100644 nuttx/libc/time/lib_gmtime.c delete mode 100644 nuttx/libc/time/lib_gmtimer.c delete mode 100644 nuttx/libc/time/lib_isleapyear.c delete mode 100644 nuttx/libc/time/lib_mktime.c delete mode 100644 nuttx/libc/time/lib_strftime.c delete mode 100644 nuttx/libc/time/lib_time.c delete mode 100644 nuttx/libc/unistd/Make.defs delete mode 100644 nuttx/libc/unistd/lib_chdir.c delete mode 100644 nuttx/libc/unistd/lib_getcwd.c delete mode 100644 nuttx/libc/unistd/lib_getopt.c delete mode 100644 nuttx/libc/unistd/lib_getoptargp.c delete mode 100644 nuttx/libc/unistd/lib_getoptindp.c delete mode 100644 nuttx/libc/unistd/lib_getoptoptp.c delete mode 100644 nuttx/libxx/libxx_cxa_atexit.cxx delete mode 100644 nuttx/libxx/libxx_internal.hxx delete mode 100644 nuttx/libxx/libxx_stdthrow.cxx delete mode 100644 nuttx/sched/pause.c delete mode 100644 nuttx/tools/define.bat delete mode 100755 nuttx/tools/incdir.bat delete mode 100644 nuttx/tools/mkdeps.bat delete mode 100644 nuttx/tools/mkdeps.c diff --git a/apps/nshlib/nsh_codeccmd.c b/apps/nshlib/nsh_codeccmd.c deleted file mode 100644 index 8c1f5adbdf..0000000000 --- a/apps/nshlib/nsh_codeccmd.c +++ /dev/null @@ -1,538 +0,0 @@ -/**************************************************************************** - * apps/nshlib/nsh_apps.c - * - * This file is part of NuttX, contributed by Darcy Gong - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Darcy Gong 2012-10-30 - * - * 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 -#ifdef CONFIG_NETUTILS_CODECS - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#if defined(CONFIG_NSH_DISABLE_URLENCODE) && defined(CONFIG_NSH_DISABLE_URLDECODE) -# undef CONFIG_CODECS_URLCODE -#endif - -#ifdef CONFIG_CODECS_URLCODE -#include -#endif - -#if defined(CONFIG_NSH_DISABLE_BASE64ENC) && defined(CONFIG_NSH_DISABLE_BASE64ENC) -# undef CONFIG_CODECS_BASE64 -#endif - -#ifdef CONFIG_CODECS_BASE64 -#include -#endif - -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) -#include -#endif - -#include "nsh.h" -#include "nsh_console.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#ifndef CONFIG_NSH_CODECS_BUFSIZE -# define CONFIG_NSH_CODECS_BUFSIZE 128 -#endif - -#define CODEC_MODE_URLENCODE 1 -#define CODEC_MODE_URLDECODE 2 -#define CODEC_MODE_BASE64ENC 3 -#define CODEC_MODE_BASE64DEC 4 -#define CODEC_MODE_HASH_MD5 5 - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -typedef void (*codec_callback_t)(FAR char *src_buff, int src_buff_len, - FAR char *dst_buff, FAR int *dst_buff_len, - int mode); - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: urlencode_cb - ****************************************************************************/ - -#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLENCODE) -static void urlencode_cb(FAR char *src_buff, int src_buff_len, - FAR char *dst_buff, FAR int *dst_buff_len, int mode) -{ - urlencode(src_buff,src_buff_len,dst_buff,dst_buff_len); -} -#endif - -/**************************************************************************** - * Name: urldecode_cb - ****************************************************************************/ - -#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) -static void urldecode_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, - FAR int *dst_buff_len, int mode) -{ - urldecode(src_buff,src_buff_len,dst_buff,dst_buff_len); -} -#endif - -/**************************************************************************** - * Name: b64enc_cb - ****************************************************************************/ - -#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) -static void b64enc_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, - FAR int *dst_buff_len, int mode) -{ - if (mode == 0) - { - //dst_buff = - base64_encode((unsigned char *)src_buff, src_buff_len, - (unsigned char *)dst_buff, (size_t *)dst_buff_len); - } - else - { - //dst_buff = - base64w_encode((unsigned char *)src_buff, src_buff_len, - (unsigned char *)dst_buff, (size_t *)dst_buff_len); - } -} -#endif - -/**************************************************************************** - * Name: b64dec_cb - ****************************************************************************/ - -#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64DEC) -static void b64dec_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, - FAR int *dst_buff_len, int mode) -{ - if (mode == 0) - { - //dst_buff = - base64_decode((unsigned char *)src_buff, src_buff_len, - (unsigned char *)dst_buff, (size_t *)dst_buff_len); - } - else - { - //dst_buff = - base64w_decode((unsigned char *)src_buff, src_buff_len, - (unsigned char *)dst_buff,(size_t *)dst_buff_len); - } -} -#endif - -/**************************************************************************** - * Name: md5_cb - ****************************************************************************/ - -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) -static void md5_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, - FAR int *dst_buff_len, int mode) -{ - MD5Update((MD5_CTX *)dst_buff, (unsigned char *)src_buff, src_buff_len); -} -#endif - -/**************************************************************************** - * Name: calc_codec_buffsize - ****************************************************************************/ - -static int calc_codec_buffsize(int src_buffsize, uint8_t mode) -{ - switch (mode) - { - case CODEC_MODE_URLENCODE: - return src_buffsize*3+1; - case CODEC_MODE_URLDECODE: - return src_buffsize+1; - case CODEC_MODE_BASE64ENC: - return ((src_buffsize + 2)/ 3 * 4)+1; - case CODEC_MODE_BASE64DEC: - return (src_buffsize / 4 * 3 + 2)+1; - case CODEC_MODE_HASH_MD5: - return 32+1; - default: - return src_buffsize+1; - } -} - -/**************************************************************************** - * Name: cmd_codecs_proc - ****************************************************************************/ - -static int cmd_codecs_proc(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv, - uint8_t mode, codec_callback_t func) -{ -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) - static const unsigned char hex_chars[] = "0123456789abcdef"; - MD5_CTX ctx; - unsigned char mac[16]; - char *pSrc; - char *pDest; -#endif - - char *localfile = NULL; - char *src_buffer = NULL; - char *buffer = NULL; - char *fullpath = NULL; - const char *fmt; - char *s_data; - bool badarg = false; - bool is_file = false; - bool is_websafe=false; - int option; - int fd = -1; - int buff_len = 0; - int src_buff_len = 0; - int i = 0; - int ret = OK; - - /* Get the command options */ - - while ((option = getopt(argc, argv, ":fw")) != ERROR) - { - switch (option) - { - case 'f': - is_file = true; - break; - -#ifdef CONFIG_CODECS_BASE64 - case 'w': - is_websafe = true; - - if (!(mode == CODEC_MODE_BASE64ENC || mode == CODEC_MODE_BASE64DEC)) - { - badarg = true; - } - break; -#endif - case ':': - nsh_output(vtbl, g_fmtargrequired, argv[0]); - badarg = true; - break; - - case '?': - default: - nsh_output(vtbl, g_fmtarginvalid, argv[0]); - badarg = true; - break; - } - } - - /* If a bad argument was encountered, then return without processing the command */ - - if (badarg) - { - return ERROR; - } - - /* There should be exactly on parameter left on the command-line */ - - if (optind == argc-1) - { - s_data = argv[optind]; - } - else if (optind >= argc) - { - fmt = g_fmttoomanyargs; - goto errout; - } - else - { - fmt = g_fmtargrequired; - goto errout; - } - -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) - if (mode == CODEC_MODE_HASH_MD5) - { - MD5Init(&ctx); - } -#endif - - if (is_file) - { - /* Get the local file name */ - - localfile = s_data; - - /* Get the full path to the local file */ - - fullpath = nsh_getfullpath(vtbl, localfile); - - /* Open the local file for writing */ - - fd = open(fullpath, O_RDONLY|O_TRUNC, 0644); - if (fd < 0) - { - nsh_output(vtbl, g_fmtcmdfailed, argv[0], "open", NSH_ERRNO); - ret = ERROR; - goto exit; - } - - src_buffer = malloc(CONFIG_NSH_CODECS_BUFSIZE+2); -#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) - if (mode == CODEC_MODE_BASE64ENC) - { - src_buff_len = CONFIG_NSH_CODECS_BUFSIZE / 3 * 3; - } - else -#endif - { - src_buff_len = CONFIG_NSH_CODECS_BUFSIZE; - } - - buff_len = calc_codec_buffsize(src_buff_len+2, mode); - buffer = malloc(buff_len); - while(true) - { - memset(src_buffer, 0, src_buff_len+2); - ret=read(fd, src_buffer, src_buff_len); - if (ret < 0) - { - nsh_output(vtbl, g_fmtcmdfailed, argv[0], "read", NSH_ERRNO); - ret = ERROR; - goto exit; - } - else if(ret==0) - { - break; - } - -#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) - if (mode == CODEC_MODE_URLDECODE) - { - if (src_buffer[src_buff_len-1]=='%') - { - ret += read(fd,&src_buffer[src_buff_len],2); - } - else if (src_buffer[src_buff_len-2]=='%') - { - ret += read(fd,&src_buffer[src_buff_len],1); - } - } -#endif - memset(buffer, 0, buff_len); - if (func) - { -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) - if (mode == CODEC_MODE_HASH_MD5) - { - func(src_buffer, ret, (char *)&ctx, &buff_len,0); - } - else -#endif - { - func(src_buffer, ret, buffer, &buff_len,(is_websafe)?1:0); - nsh_output(vtbl, "%s", buffer); - } - } - - buff_len = calc_codec_buffsize(src_buff_len+2, mode); - } - -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) - if (mode == CODEC_MODE_HASH_MD5) - { - MD5Final(mac, &ctx); - pSrc = (char *)&mac; - pDest = buffer; - for(i=0;i<16;i++,pSrc++) - { - *pDest++ = hex_chars[(*pSrc) >> 4]; - *pDest++ = hex_chars[(*pSrc) & 0x0f]; - } - - *pDest='\0'; - nsh_output(vtbl, "%s\n", buffer); - } -#endif - ret = OK; - goto exit; - } - else - { - src_buffer = s_data; - src_buff_len = strlen(s_data); - buff_len = calc_codec_buffsize(src_buff_len, mode); - buffer = malloc(buff_len); - buffer[0]=0; - if (!buffer) - { - fmt = g_fmtcmdoutofmemory; - goto errout; - } - - memset(buffer, 0, buff_len); - if (func) - { -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) - if (mode == CODEC_MODE_HASH_MD5) - { - func(src_buffer, src_buff_len, (char *)&ctx, &buff_len, 0); - MD5Final(mac, &ctx); - pSrc = (char *)&mac; - pDest = buffer; - for(i=0;i<16;i++,pSrc++) - { - *pDest++ = hex_chars[(*pSrc) >> 4]; - *pDest++ = hex_chars[(*pSrc) & 0x0f]; - } - - *pDest='\0'; - } - else -#endif - { - func(src_buffer, src_buff_len, buffer, &buff_len,(is_websafe)?1:0); - } - } - - nsh_output(vtbl, "%s\n",buffer); - src_buffer = NULL; - goto exit; - } - -exit: - if (fd >= 0) - { - close(fd); - } - - if (fullpath) - { - free(fullpath); - } - - if (src_buffer) - { - free(src_buffer); - } - - if (buffer) - { - free(buffer); - } - - return ret; - -errout: - nsh_output(vtbl, fmt, argv[0]); - ret = ERROR; - goto exit; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: cmd_urlencode - ****************************************************************************/ - -#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLENCODE) -int cmd_urlencode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_URLENCODE, urlencode_cb); -} -#endif - -/**************************************************************************** - * Name: cmd_urldecode - ****************************************************************************/ - -#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) -int cmd_urldecode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_URLDECODE, urldecode_cb); -} -#endif - -/**************************************************************************** - * Name: cmd_base64encode - ****************************************************************************/ - -#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) -int cmd_base64encode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_BASE64ENC, b64enc_cb); -} -#endif - -/**************************************************************************** - * Name: cmd_base64decode - ****************************************************************************/ - -#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64DEC) -int cmd_base64decode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_BASE64DEC, b64dec_cb); -} -#endif - -/**************************************************************************** - * Name: cmd_md5 - ****************************************************************************/ - -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) -int cmd_md5(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - return cmd_codecs_proc(vtbl,argc,argv,CODEC_MODE_HASH_MD5,md5_cb); -} -#endif - -#endif /* CONFIG_NETUTILS_CODECS */ diff --git a/nuttx/Makefile.unix b/nuttx/Makefile.unix deleted file mode 100644 index 78c34c2de5..0000000000 --- a/nuttx/Makefile.unix +++ /dev/null @@ -1,749 +0,0 @@ -############################################################################ -# Makefile.unix -# -# Copyright (C) 2007-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. -# -############################################################################ - -TOPDIR := ${shell pwd | sed -e 's/ /\\ /g'} --include ${TOPDIR}/.config -include ${TOPDIR}/tools/Config.mk --include ${TOPDIR}/Make.defs - -# Control build verbosity - -ifeq ($(V),1) -export Q := -else -export Q := @ -endif - -# Default tools - -ifeq ($(DIRLINK),) -DIRLINK = $(TOPDIR)/tools/link.sh -DIRUNLINK = $(TOPDIR)/tools/unlink.sh -endif - -# This define is passed as EXTRADEFINES for kernel-mode builds. It is also passed -# during PASS1 (but not PASS2) context and depend targets. - -KDEFINE = ${shell $(TOPDIR)/tools/define.sh "$(CC)" __KERNEL__} - -# Process architecture and board-specific directories - -ARCH_DIR = arch/$(CONFIG_ARCH) -ARCH_SRC = $(ARCH_DIR)/src -ARCH_INC = $(ARCH_DIR)/include -BOARD_DIR = configs/$(CONFIG_ARCH_BOARD) - -# Add-on directories. These may or may not be in place in the -# NuttX source tree (they must be specifically installed) -# -# CONFIG_APPS_DIR can be over-ridden from the command line or in the .config file. -# The default value of CONFIG_APPS_DIR is ../apps. Ultimately, the application -# will be built if APPDIR is defined. APPDIR will be defined if a directory containing -# a Makefile is found at the path provided by CONFIG_APPS_DIR - -ifeq ($(CONFIG_APPS_DIR),) -CONFIG_APPS_DIR = ../apps -endif -APPDIR := ${shell if [ -r $(CONFIG_APPS_DIR)/Makefile ]; then echo "$(CONFIG_APPS_DIR)"; fi} - -# All add-on directories. -# -# NUTTX_ADDONS is the list of directories built into the NuttX kernel. -# USER_ADDONS is the list of directories that will be built into the user application - -NUTTX_ADDONS := -USER_ADDONS := - -ifeq ($(CONFIG_NUTTX_KERNEL),y) -USER_ADDONS += $(APPDIR) -else -NUTTX_ADDONS += $(APPDIR) -endif - -# Lists of build directories. -# -# FSDIRS depend on file descriptor support; NONFSDIRS do not (except for parts -# of FSDIRS). We will exclude FSDIRS from the build if file descriptor -# support is disabled -# CONTEXTDIRS include directories that have special, one-time pre-build -# requirements. Normally this includes things like auto-generation of -# configuration specific files or creation of configurable symbolic links -# USERDIRS - When NuttX is build is a monolithic kernel, this provides the -# list of directories that must be built -# OTHERDIRS - These are directories that are not built but probably should -# be cleaned to prevent garbarge from collecting in them when changing -# configurations. - -NONFSDIRS = sched $(ARCH_SRC) $(NUTTX_ADDONS) -FSDIRS = fs drivers binfmt -CONTEXTDIRS = $(APPDIR) -USERDIRS = -OTHERDIRS = lib - -ifeq ($(CONFIG_NUTTX_KERNEL),y) - -NONFSDIRS += syscall -CONTEXTDIRS += syscall -USERDIRS += syscall libc mm $(USER_ADDONS) -ifeq ($(CONFIG_HAVE_CXX),y) -USERDIRS += libxx -endif - -else - -NONFSDIRS += libc mm -OTHERDIRS += syscall $(USER_ADDONS) -ifeq ($(CONFIG_HAVE_CXX),y) -NONFSDIRS += libxx -else -OTHERDIRS += libxx -endif - -endif - -ifeq ($(CONFIG_NX),y) -NONFSDIRS += graphics -CONTEXTDIRS += graphics -else -OTHERDIRS += graphics -endif - -# CLEANDIRS are the directories that will clean in. These are -# all directories that we know about. -# KERNDEPDIRS are the directories in which we will build target dependencies. -# If NuttX and applications are built separately (CONFIG_NUTTX_KERNEL), -# then this holds only the directories containing kernel files. -# USERDEPDIRS. If NuttX and applications are built separately (CONFIG_NUTTX_KERNEL), -# then this holds only the directories containing user files. - -CLEANDIRS = $(NONFSDIRS) $(FSDIRS) $(USERDIRS) $(OTHERDIRS) -KERNDEPDIRS = $(NONFSDIRS) -USERDEPDIRS = $(USERDIRS) - -# Add file system directories to KERNDEPDIRS (they are already in CLEANDIRS) - -ifeq ($(CONFIG_NFILE_DESCRIPTORS),0) -ifeq ($(CONFIG_NET),y) -ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0) -KERNDEPDIRS += fs -endif -KERNDEPDIRS += drivers -endif -else -KERNDEPDIRS += $(FSDIRS) -endif - -# Add networking directories to KERNDEPDIRS and CLEANDIRS - -ifeq ($(CONFIG_NET),y) -KERNDEPDIRS += net -endif -CLEANDIRS += net - -# -# Extra objects used in the final link. -# -# Pass 1 1ncremental (relative) link objects should be put into the -# processor-specific source directory (where other link objects will -# be created). If the pass1 obect is an archive, it could go anywhere. - -ifeq ($(CONFIG_BUILD_2PASS),y) -EXTRA_OBJS += $(CONFIG_PASS1_OBJECT) -endif - -# NUTTXLIBS is the list of NuttX libraries that is passed to the -# processor-specific Makefile to build the final NuttX target. -# Libraries in FSDIRS are excluded if file descriptor support -# is disabled. -# USERLIBS is the list of libraries used to build the final user-space -# application - -NUTTXLIBS = lib/libsched$(LIBEXT) lib/libarch$(LIBEXT) -USERLIBS = - -# Add libraries for syscall support. The C library will be needed by -# both the kernel- and user-space builds. For now, the memory manager (mm) -# is placed in user space (only). - -ifeq ($(CONFIG_NUTTX_KERNEL),y) -NUTTXLIBS += lib/libstubs$(LIBEXT) lib/libkc$(LIBEXT) -USERLIBS += lib/libproxies$(LIBEXT) lib/libuc$(LIBEXT) lib/libmm$(LIBEXT) -else -NUTTXLIBS += lib/libmm$(LIBEXT) lib/libc$(LIBEXT) -endif - -# Add libraries for C++ support. CXX, CXXFLAGS, and COMPILEXX must -# be defined in Make.defs for this to work! - -ifeq ($(CONFIG_HAVE_CXX),y) -ifeq ($(CONFIG_NUTTX_KERNEL),y) -USERLIBS += lib/libcxx$(LIBEXT) -else -NUTTXLIBS += lib/libcxx$(LIBEXT) -endif -endif - -# Add library for application support. - -ifneq ($(APPDIR),) -ifeq ($(CONFIG_NUTTX_KERNEL),y) -USERLIBS += lib/libapps$(LIBEXT) -else -NUTTXLIBS += lib/libapps$(LIBEXT) -endif -endif - -# Add libraries for network support - -ifeq ($(CONFIG_NET),y) -NUTTXLIBS += lib/libnet$(LIBEXT) -endif - -# Add libraries for file system support - -ifeq ($(CONFIG_NFILE_DESCRIPTORS),0) -ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0) -NUTTXLIBS += lib/libfs$(LIBEXT) -endif -ifeq ($(CONFIG_NET),y) -NUTTXLIBS += lib/libdrivers$(LIBEXT) -endif -else -NUTTXLIBS += lib/libfs$(LIBEXT) lib/libdrivers$(LIBEXT) lib/libbinfmt$(LIBEXT) -endif - -# Add libraries for the NX graphics sub-system - -ifeq ($(CONFIG_NX),y) -NUTTXLIBS += lib/libgraphics$(LIBEXT) -endif - -# LINKLIBS derives from NUTTXLIBS and is simply the same list with the subdirectory removed - -LINKLIBS = $(patsubst lib/%,%,$(NUTTXLIBS)) - -# This is the name of the final target (relative to the top level directorty) - -BIN = nuttx$(EXEEXT) - -all: $(BIN) -.PHONY: context clean_context check_context export subdir_clean clean subdir_distclean distclean apps_clean apps_distclean - -# Target used to copy include/nuttx/math.h. If CONFIG_ARCH_MATH_H is -# defined, then there is an architecture specific math.h header file -# that will be included indirectly from include/math.h. But first, we -# have to copy math.h from include/nuttx/. to include/. Logic within -# include/nuttx/math.h will hand the redirection to the architecture- -# specific math.h header file. -# -# If the CONFIG_LIBM is defined, the Rhombus libm will be built at libc/math. -# Definitions and prototypes for the Rhombus libm are also contained in -# include/nuttx/math.h and so the file must also be copied in that case. -# -# If neither CONFIG_ARCH_MATH_H nor CONFIG_LIBM is defined, then no math.h -# header file will be provided. You would want that behavior if (1) you -# don't use libm, or (2) you want to use the math.h and libm provided -# within your toolchain. - -ifeq ($(CONFIG_ARCH_MATH_H),y) -NEED_MATH_H = y -else -ifeq ($(CONFIG_LIBM),y) -NEED_MATH_H = y -endif -endif - -ifeq ($(NEED_MATH_H),y) -include/math.h: include/nuttx/math.h - $(Q) cp -f include/nuttx/math.h include/math.h -else -include/math.h: -endif - -# The float.h header file defines the properties of your floating point -# implementation. It would always be best to use your toolchain's float.h -# header file but if none is avaiable, a default float.h header file will -# provided if this option is selected. However there is no assurance that -# the settings in this float.h are actually correct for your platform! - -ifeq ($(CONFIG_ARCH_FLOAT_H),y) -include/float.h: include/nuttx/float.h - $(Q) cp -f include/nuttx/float.h include/float.h -else -include/float.h: -endif - -# Target used to copy include/nuttx/stdarg.h. If CONFIG_ARCH_STDARG_H is -# defined, then there is an architecture specific stdarg.h header file -# that will be included indirectly from include/stdarg.h. But first, we -# have to copy stdarg.h from include/nuttx/. to include/. - -ifeq ($(CONFIG_ARCH_STDARG_H),y) -include/stdarg.h: include/nuttx/stdarg.h - $(Q) cp -f include/nuttx/stdarg.h include/stdarg.h -else -include/stdarg.h: -endif - -# Targets used to build include/nuttx/version.h. Creation of version.h is -# part of the overall NuttX configuration sequence. Notice that the -# tools/mkversion tool is built and used to create include/nuttx/version.h - -tools/mkversion$(HOSTEXEEXT): - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkversion$(HOSTEXEEXT) - -$(TOPDIR)/.version: - $(Q) if [ ! -f .version ]; then \ - echo "No .version file found, creating one"; \ - tools/version.sh -v 0.0 -b 0 .version; \ - chmod 755 .version; \ - fi - -include/nuttx/version.h: $(TOPDIR)/.version tools/mkversion$(HOSTEXEEXT) - $(Q) tools/mkversion $(TOPDIR) > include/nuttx/version.h - -# Targets used to build include/nuttx/config.h. Creation of config.h is -# part of the overall NuttX configuration sequence. Notice that the -# tools/mkconfig tool is built and used to create include/nuttx/config.h - -tools/mkconfig$(HOSTEXEEXT): - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkconfig$(HOSTEXEEXT) - -include/nuttx/config.h: $(TOPDIR)/.config tools/mkconfig$(HOSTEXEEXT) - $(Q) tools/mkconfig $(TOPDIR) > include/nuttx/config.h - -# Targets used to create dependencies - -tools/mkdeps$(HOSTEXEEXT): - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkdeps$(HOSTEXEEXT) - -# dirlinks, and helpers -# -# Directories links. Most of establishing the NuttX configuration involves -# setting up symbolic links with 'generic' directory names to specific, -# configured directories. -# -# Link the apps/include directory to include/apps - -include/apps: Make.defs -ifneq ($(APPDIR),) - @echo "LN: include/apps -> $(APPDIR)/include" - $(Q) if [ -d $(TOPDIR)/$(APPDIR)/include ]; then \ - $(DIRLINK) $(TOPDIR)/$(APPDIR)/include include/apps; \ - fi -endif - -# Link the arch//include directory to include/arch - -include/arch: Make.defs - @echo "LN: include/arch -> $(ARCH_DIR)/include" - $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_DIR)/include include/arch - -# Link the configs//include directory to include/arch/board - -include/arch/board: include/arch Make.defs include/arch - @echo "LN: include/arch/board -> $(BOARD_DIR)/include" - $(Q) $(DIRLINK) $(TOPDIR)/$(BOARD_DIR)/include include/arch/board - -# Link the configs//src dir to arch//src/board - -$(ARCH_SRC)/board: Make.defs - @echo "LN: $(ARCH_SRC)/board -> $(BOARD_DIR)/src" - $(Q) $(DIRLINK) $(TOPDIR)/$(BOARD_DIR)/src $(ARCH_SRC)/board - -# Link arch//include/ to arch//include/chip - -$(ARCH_SRC)/chip: Make.defs -ifneq ($(CONFIG_ARCH_CHIP),) - @echo "LN: $(ARCH_SRC)/chip -> $(ARCH_SRC)/$(CONFIG_ARCH_CHIP)" - $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_SRC)/$(CONFIG_ARCH_CHIP) $(ARCH_SRC)/chip -endif - -# Link arch//src/ to arch//src/chip - -include/arch/chip: include/arch Make.defs -ifneq ($(CONFIG_ARCH_CHIP),) - @echo "LN: include/arch/chip -> $(ARCH_INC)/$(CONFIG_ARCH_CHIP)" - $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_INC)/$(CONFIG_ARCH_CHIP) include/arch/chip -endif - -dirlinks: include/arch include/arch/board include/arch/chip $(ARCH_SRC)/board $(ARCH_SRC)/chip include/apps - -# context -# -# The context target is invoked on each target build to assure that NuttX is -# properly configured. The basic configuration steps include creation of the -# the config.h and version.h header files in the include/nuttx directory and -# the establishment of symbolic links to configured directories. - -context: check_context include/nuttx/config.h include/nuttx/version.h include/math.h include/float.h include/stdarg.h dirlinks - $(Q) for dir in $(CONTEXTDIRS) ; do \ - $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" context; \ - done - -# clean_context -# -# This is part of the distclean target. It removes all of the header files -# and symbolic links created by the context target. - -clean_context: - $(call DELFILE, include/nuttx/config.h) - $(call DELFILE, include/nuttx/version.h) - $(call DELFILE, include/math.h) - $(call DELFILE, include/stdarg.h) - $(Q) $(DIRUNLINK) include/arch/board - $(Q) $(DIRUNLINK) include/arch/chip - $(Q) $(DIRUNLINK) include/arch - $(Q) $(DIRUNLINK) $(ARCH_SRC)/board - $(Q) $(DIRUNLINK) $(ARCH_SRC)/chip - $(Q) $(DIRUNLINK) include/apps - -# check_context -# -# This target checks if NuttX has been configured. NuttX is configured using -# the script tools/configure.sh. That script will install certain files in -# the top-level NuttX build directory. This target verifies that those -# configuration files have been installed and that NuttX is ready to be built. - -check_context: - $(Q) if [ ! -e ${TOPDIR}/.config -o ! -e ${TOPDIR}/Make.defs ]; then \ - echo "" ; echo "Nuttx has not been configured:" ; \ - echo " cd tools; ./configure.sh " ; echo "" ; \ - exit 1 ; \ - fi - -# Archive targets. The target build sequency will first create a series of -# libraries, one per configured source file directory. The final NuttX -# execution will then be built from those libraries. The following targets -# build those libraries. -# -# Possible kernel-mode builds - -libc/libkc$(LIBEXT): context - $(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libkc$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib/libkc$(LIBEXT): libc/libkc$(LIBEXT) - $(Q) install libc/libkc$(LIBEXT) lib/libkc$(LIBEXT) - -sched/libsched$(LIBEXT): context - $(Q) $(MAKE) -C sched TOPDIR="$(TOPDIR)" libsched$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib/libsched$(LIBEXT): sched/libsched$(LIBEXT) - $(Q) install sched/libsched$(LIBEXT) lib/libsched$(LIBEXT) - -$(ARCH_SRC)/libarch$(LIBEXT): context - $(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" libarch$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib/libarch$(LIBEXT): $(ARCH_SRC)/libarch$(LIBEXT) - $(Q) install $(ARCH_SRC)/libarch$(LIBEXT) lib/libarch$(LIBEXT) - -net/libnet$(LIBEXT): context - $(Q) $(MAKE) -C net TOPDIR="$(TOPDIR)" libnet$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib/libnet$(LIBEXT): net/libnet$(LIBEXT) - $(Q) install net/libnet$(LIBEXT) lib/libnet$(LIBEXT) - -fs/libfs$(LIBEXT): context - $(Q) $(MAKE) -C fs TOPDIR="$(TOPDIR)" libfs$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib/libfs$(LIBEXT): fs/libfs$(LIBEXT) - $(Q) install fs/libfs$(LIBEXT) lib/libfs$(LIBEXT) - -drivers/libdrivers$(LIBEXT): context - $(Q) $(MAKE) -C drivers TOPDIR="$(TOPDIR)" libdrivers$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib/libdrivers$(LIBEXT): drivers/libdrivers$(LIBEXT) - $(Q) install drivers/libdrivers$(LIBEXT) lib/libdrivers$(LIBEXT) - -binfmt/libbinfmt$(LIBEXT): context - $(Q) $(MAKE) -C binfmt TOPDIR="$(TOPDIR)" libbinfmt$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib/libbinfmt$(LIBEXT): binfmt/libbinfmt$(LIBEXT) - $(Q) install binfmt/libbinfmt$(LIBEXT) lib/libbinfmt$(LIBEXT) - -graphics/libgraphics$(LIBEXT): context - $(Q) $(MAKE) -C graphics TOPDIR="$(TOPDIR)" libgraphics$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib/libgraphics$(LIBEXT): graphics/libgraphics$(LIBEXT) - $(Q) install graphics/libgraphics$(LIBEXT) lib/libgraphics$(LIBEXT) - -syscall/libstubs$(LIBEXT): context - $(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libstubs$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib/libstubs$(LIBEXT): syscall/libstubs$(LIBEXT) - $(Q) install syscall/libstubs$(LIBEXT) lib/libstubs$(LIBEXT) - -# Possible user-mode builds - -libc/libuc$(LIBEXT): context - $(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libuc$(LIBEXT) - -lib/libuc$(LIBEXT): libc/libuc$(LIBEXT) - $(Q) install libc/libuc$(LIBEXT) lib/libuc$(LIBEXT) - -libxx/libcxx$(LIBEXT): context - $(Q) $(MAKE) -C libxx TOPDIR="$(TOPDIR)" libcxx$(LIBEXT) - -lib/libcxx$(LIBEXT): libxx/libcxx$(LIBEXT) - $(Q) install libxx/libcxx$(LIBEXT) lib/libcxx$(LIBEXT) - -mm/libmm$(LIBEXT): context - $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib/libmm$(LIBEXT): mm/libmm$(LIBEXT) - $(Q) install mm/libmm$(LIBEXT) lib/libmm$(LIBEXT) - -$(APPDIR)/libapps$(LIBEXT): context - $(Q) $(MAKE) -C $(APPDIR) TOPDIR="$(TOPDIR)" libapps$(LIBEXT) - -lib/libapps$(LIBEXT): $(APPDIR)/libapps$(LIBEXT) - $(Q) install $(APPDIR)/libapps$(LIBEXT) lib/libapps$(LIBEXT) - -syscall/libproxies$(LIBEXT): context - $(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libproxies$(LIBEXT) - -lib/libproxies$(LIBEXT): syscall/libproxies$(LIBEXT) - $(Q) install syscall/libproxies$(LIBEXT) lib/libproxies$(LIBEXT) - -# Possible non-kernel builds - -libc/libc$(LIBEXT): context - $(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libc$(LIBEXT) - -lib/libc$(LIBEXT): libc/libc$(LIBEXT) - $(Q) install libc/libc$(LIBEXT) lib/libc$(LIBEXT) - -# pass1 and pass2 -# -# If the 2 pass build option is selected, then this pass1 target is -# configured to built before the pass2 target. This pass1 target may, as an -# example, build an extra link object (CONFIG_PASS1_OBJECT) which may be an -# incremental (relative) link object, but could be a static library (archive); -# some modification to this Makefile would be required if CONFIG_PASS1_OBJECT -# is an archive. Exactly what is performed during pass1 or what it generates -# is unknown to this makefule unless CONFIG_PASS1_OBJECT is defined. - -pass1deps: pass1dep $(USERLIBS) - -pass1: pass1deps -ifeq ($(CONFIG_BUILD_2PASS),y) - $(Q) if [ -z "$(CONFIG_PASS1_BUILDIR)" ]; then \ - echo "ERROR: CONFIG_PASS1_BUILDIR not defined"; \ - exit 1; \ - fi - $(Q) if [ ! -d "$(CONFIG_PASS1_BUILDIR)" ]; then \ - echo "ERROR: CONFIG_PASS1_BUILDIR does not exist"; \ - exit 1; \ - fi - $(Q) if [ ! -f "$(CONFIG_PASS1_BUILDIR)/Makefile" ]; then \ - echo "ERROR: No Makefile in CONFIG_PASS1_BUILDIR"; \ - exit 1; \ - fi - $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" LINKLIBS="$(LINKLIBS)" USERLIBS="$(USERLIBS)" "$(CONFIG_PASS1_TARGET)" -endif - -pass2deps: pass2dep $(NUTTXLIBS) - -pass2: pass2deps - $(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(LINKLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN) - $(Q) if [ -w /tftpboot ] ; then \ - cp -f $(BIN) /tftpboot/$(BIN).${CONFIG_ARCH}; \ - fi -ifeq ($(CONFIG_RRLOAD_BINARY),y) - @echo "MK: $(BIN).rr" - $(Q) $(TOPDIR)/tools/mkimage.sh --Prefix $(CROSSDEV) $(BIN) $(BIN).rr - $(Q) if [ -w /tftpboot ] ; then \ - cp -f $(BIN).rr /tftpboot/$\(BIN).rr.$(CONFIG_ARCH); \ - fi -endif -ifeq ($(CONFIG_INTELHEX_BINARY),y) - @echo "CP: $(BIN).hex" - $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O ihex $(BIN) $(BIN).hex -endif -ifeq ($(CONFIG_MOTOROLA_SREC),y) - @echo "CP: $(BIN).srec" - $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O srec $(BIN) $(BIN).srec -endif -ifeq ($(CONFIG_RAW_BINARY),y) - @echo "CP: $(BIN).bin" - $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O binary $(BIN) $(BIN).bin -endif - -# $(BIN) -# -# Create the final NuttX executable in a two pass build process. In the -# normal case, all pass1 and pass2 dependencies are created then pass1 -# and pass2 targets are built. However, in some cases, you may need to build -# pass1 depenencies and pass1 first, then build pass2 dependencies and pass2. -# in that case, execute 'make pass1 pass2' from the command line. - -$(BIN): pass1deps pass2deps pass1 pass2 - -# download -# -# This is a helper target that will rebuild NuttX and download it to the target -# system in one step. The operation of this target depends completely upon -# implementation of the DOWNLOAD command in the user Make.defs file. It will -# generate an error an error if the DOWNLOAD command is not defined. - -download: $(BIN) - $(call DOWNLOAD, $<) - -# pass1dep: Create pass1 build dependencies -# pass2dep: Create pass2 build dependencies - -pass1dep: context tools/mkdeps$(HOSTEXEEXT) - $(Q) for dir in $(USERDEPDIRS) ; do \ - $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" depend ; \ - done - -pass2dep: context tools/mkdeps$(HOSTEXEEXT) - $(Q) for dir in $(KERNDEPDIRS) ; do \ - $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" EXTRADEFINES=$(KDEFINE) depend; \ - done - -# Configuration targets -# -# These targets depend on the kconfig-frontends packages. To use these, you -# must first download and install the kconfig-frontends package from this -# location: http://ymorin.is-a-geek.org/projects/kconfig-frontends. See -# misc/tools/README.txt for additional information. - -config: - $(Q) APPSDIR=${CONFIG_APPS_DIR} conf Kconfig - -oldconfig: - $(Q) APPSDIR=${CONFIG_APPS_DIR} conf --oldconfig Kconfig - -menuconfig: - $(Q) APPSDIR=${CONFIG_APPS_DIR} mconf Kconfig - -# export -# -# The export target will package the NuttX libraries and header files into -# an exportable package. Caveats: (1) These needs some extension for the KERNEL -# build; it needs to receive USERLIBS and create a libuser.a). (2) The logic -# in tools/mkexport.sh only supports GCC and, for example, explicitly assumes -# that the archiver is 'ar' - -export: pass2deps - $(Q) tools/mkexport.sh -w$(WINTOOL) -t "$(TOPDIR)" -l "$(NUTTXLIBS)" - -# General housekeeping targets: dependencies, cleaning, etc. -# -# depend: Create both PASS1 and PASS2 dependencies -# clean: Removes derived object files, archives, executables, and -# temporary files, but retains the configuration and context -# files and directories. -# distclean: Does 'clean' then also removes all configuration and context -# files. This essentially restores the directory structure -# to its original, unconfigured stated. - -depend: pass1dep pass2dep - -subdir_clean: - $(Q) for dir in $(CLEANDIRS) ; do \ - if [ -e $$dir/Makefile ]; then \ - $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" clean ; \ - fi \ - done - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" clean - $(Q) $(MAKE) -C mm -f Makefile.test TOPDIR="$(TOPDIR)" clean -ifeq ($(CONFIG_BUILD_2PASS),y) - $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" clean -endif - -clean: subdir_clean - $(call DELFILE, $(BIN)) - $(call DELFILE, nuttx.*) - $(call DELFILE, mm_test) - $(call DELFILE, *.map) - $(call DELFILE, _SAVED_APPS_config) - $(call DELFILE, nuttx-export*) - $(call CLEAN) - -subdir_distclean: - $(Q) for dir in $(CLEANDIRS) ; do \ - if [ -e $$dir/Makefile ]; then \ - $(MAKE) -C $$dir TOPDIR="$(TOPDIR)" distclean ; \ - fi \ - done - -distclean: clean subdir_distclean clean_context -ifeq ($(CONFIG_BUILD_2PASS),y) - $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean -endif - $(call DELFILE, Make.defs) - $(call DELFILE, setenv.sh) - $(call DELFILE, setenv.bat) - $(call DELFILE, .config) - $(call DELFILE, .config.old) - -# Application housekeeping targets. The APPDIR variable refers to the user -# application directory. A sample apps/ directory is included with NuttX, -# however, this is not treated as part of NuttX and may be replaced with a -# different application directory. For the most part, the application -# directory is treated like any other build directory in this script. However, -# as a convenience, the following targets are included to support housekeeping -# functions in the user application directory from the NuttX build directory. -# -# apps_clean: Perform the clean operation only in the user application -# directory -# apps_distclean: Perform the distclean operation only in the user application -# directory. Note that the apps/.config file (inf any) is -# preserved so that this is not a "full" distclean but more of a -# configuration "reset." (There willnot be an apps/.config -# file if the configuration was generated via make menuconfig). - -apps_clean: -ifneq ($(APPDIR),) - $(Q) $(MAKE) -C "$(TOPDIR)/$(APPDIR)" TOPDIR="$(TOPDIR)" clean -endif - -apps_distclean: -ifneq ($(APPDIR),) - $(Q) if [ -r "$(TOPDIR)/$(APPDIR)/.config" ]; then \ - cp "$(TOPDIR)/$(APPDIR)/.config" _SAVED_APPS_config || \ - { echo "Copy of $(APPDIR)/.config failed" ; exit 1 ; } \ - else \ - rm -f _SAVED_APPS_config; \ - fi - $(Q) $(MAKE) -C "$(TOPDIR)/$(APPDIR)" TOPDIR="$(TOPDIR)" distclean - $(Q) if [ -r _SAVED_APPS_config ]; then \ - mv _SAVED_APPS_config "$(TOPDIR)/$(APPDIR)/.config" || \ - { echo "Copy of _SAVED_APPS_config failed" ; exit 1 ; } \ - fi -endif - diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win deleted file mode 100644 index 6257dbdc85..0000000000 --- a/nuttx/Makefile.win +++ /dev/null @@ -1,740 +0,0 @@ -############################################################################ -# Makefile.win -# -# 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. -# -############################################################################ - -TOPDIR := ${shell echo %CD%} --include $(TOPDIR)\.config --include $(TOPDIR)\tools\Config.mk --include $(TOPDIR)\Make.defs - -# Control build verbosity - -ifeq ($(V),1) -export Q := -else -export Q := @ -endif - -# This define is passed as EXTRADEFINES for kernel-mode builds. It is also passed -# during PASS1 (but not PASS2) context and depend targets. - -KDEFINE = ${shell $(TOPDIR)\tools\define.bat "$(CC)" __KERNEL__} - -# Process architecture and board-specific directories - -ARCH_DIR = arch\$(CONFIG_ARCH) -ARCH_SRC = $(ARCH_DIR)\src -ARCH_INC = $(ARCH_DIR)\include -BOARD_DIR = configs\$(CONFIG_ARCH_BOARD) - -# Add-on directories. These may or may not be in place in the -# NuttX source tree (they must be specifically installed) -# -# CONFIG_APPS_DIR can be over-ridden from the command line or in the .config file. -# The default value of CONFIG_APPS_DIR is ..\apps. Ultimately, the application -# will be built if APPDIR is defined. APPDIR will be defined if a directory containing -# a Makefile is found at the path provided by CONFIG_APPS_DIR - -ifeq ($(CONFIG_APPS_DIR),) -CONFIG_APPS_DIR = ..\apps -endif -APPDIR := ${shell if exist "$(CONFIG_APPS_DIR)\Makefile" echo $(CONFIG_APPS_DIR)} - -# All add-on directories. -# -# NUTTX_ADDONS is the list of directories built into the NuttX kernel. -# USER_ADDONS is the list of directories that will be built into the user application - -NUTTX_ADDONS := -USER_ADDONS := - -ifeq ($(CONFIG_NUTTX_KERNEL),y) -USER_ADDONS += $(APPDIR) -else -NUTTX_ADDONS += $(APPDIR) -endif - -# Lists of build directories. -# -# FSDIRS depend on file descriptor support; NONFSDIRS do not (except for parts -# of FSDIRS). We will exclude FSDIRS from the build if file descriptor -# support is disabled -# CONTEXTDIRS include directories that have special, one-time pre-build -# requirements. Normally this includes things like auto-generation of -# configuration specific files or creation of configurable symbolic links -# USERDIRS - When NuttX is build is a monolithic kernel, this provides the -# list of directories that must be built -# OTHERDIRS - These are directories that are not built but probably should -# be cleaned to prevent garbarge from collecting in them when changing -# configurations. - -NONFSDIRS = sched $(ARCH_SRC) $(NUTTX_ADDONS) -FSDIRS = fs drivers binfmt -CONTEXTDIRS = $(APPDIR) -USERDIRS = -OTHERDIRS = lib - -ifeq ($(CONFIG_NUTTX_KERNEL),y) - -NONFSDIRS += syscall -CONTEXTDIRS += syscall -USERDIRS += syscall libc mm $(USER_ADDONS) -ifeq ($(CONFIG_HAVE_CXX),y) -USERDIRS += libxx -endif - -else - -NONFSDIRS += libc mm -OTHERDIRS += syscall $(USER_ADDONS) -ifeq ($(CONFIG_HAVE_CXX),y) -NONFSDIRS += libxx -else -OTHERDIRS += libxx -endif - -endif - -ifeq ($(CONFIG_NX),y) -NONFSDIRS += graphics -CONTEXTDIRS += graphics -else -OTHERDIRS += graphics -endif - -# CLEANDIRS are the directories that will clean in. These are -# all directories that we know about. -# KERNDEPDIRS are the directories in which we will build target dependencies. -# If NuttX and applications are built separately (CONFIG_NUTTX_KERNEL), -# then this holds only the directories containing kernel files. -# USERDEPDIRS. If NuttX and applications are built separately (CONFIG_NUTTX_KERNEL), -# then this holds only the directories containing user files. - -CLEANDIRS = $(NONFSDIRS) $(FSDIRS) $(USERDIRS) $(OTHERDIRS) -KERNDEPDIRS = $(NONFSDIRS) -USERDEPDIRS = $(USERDIRS) - -# Add file system directories to KERNDEPDIRS (they are already in CLEANDIRS) - -ifeq ($(CONFIG_NFILE_DESCRIPTORS),0) -ifeq ($(CONFIG_NET),y) -ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0) -KERNDEPDIRS += fs -endif -KERNDEPDIRS += drivers -endif -else -KERNDEPDIRS += $(FSDIRS) -endif - -# Add networking directories to KERNDEPDIRS and CLEANDIRS - -ifeq ($(CONFIG_NET),y) -KERNDEPDIRS += net -endif -CLEANDIRS += net - -# -# Extra objects used in the final link. -# -# Pass 1 1ncremental (relative) link objects should be put into the -# processor-specific source directory (where other link objects will -# be created). If the pass1 obect is an archive, it could go anywhere. - -ifeq ($(CONFIG_BUILD_2PASS),y) -EXTRA_OBJS += $(CONFIG_PASS1_OBJECT) -endif - -# NUTTXLIBS is the list of NuttX libraries that is passed to the -# processor-specific Makefile to build the final NuttX target. -# Libraries in FSDIRS are excluded if file descriptor support -# is disabled. -# USERLIBS is the list of libraries used to build the final user-space -# application - -NUTTXLIBS = lib\libsched$(LIBEXT) lib\libarch$(LIBEXT) -USERLIBS = - -# Add libraries for syscall support. The C library will be needed by -# both the kernel- and user-space builds. For now, the memory manager (mm) -# is placed in user space (only). - -ifeq ($(CONFIG_NUTTX_KERNEL),y) -NUTTXLIBS += lib\libstubs$(LIBEXT) lib\libkc$(LIBEXT) -USERLIBS += lib\libproxies$(LIBEXT) lib\libuc$(LIBEXT) lib\libmm$(LIBEXT) -else -NUTTXLIBS += lib\libmm$(LIBEXT) lib\libc$(LIBEXT) -endif - -# Add libraries for C++ support. CXX, CXXFLAGS, and COMPILEXX must -# be defined in Make.defs for this to work! - -ifeq ($(CONFIG_HAVE_CXX),y) -ifeq ($(CONFIG_NUTTX_KERNEL),y) -USERLIBS += lib\libcxx$(LIBEXT) -else -NUTTXLIBS += lib\libcxx$(LIBEXT) -endif -endif - -# Add library for application support. - -ifneq ($(APPDIR),) -ifeq ($(CONFIG_NUTTX_KERNEL),y) -USERLIBS += lib\libapps$(LIBEXT) -else -NUTTXLIBS += lib\libapps$(LIBEXT) -endif -endif - -# Add libraries for network support - -ifeq ($(CONFIG_NET),y) -NUTTXLIBS += lib\libnet$(LIBEXT) -endif - -# Add libraries for file system support - -ifeq ($(CONFIG_NFILE_DESCRIPTORS),0) -ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0) -NUTTXLIBS += lib\libfs$(LIBEXT) -endif -ifeq ($(CONFIG_NET),y) -NUTTXLIBS += lib\libdrivers$(LIBEXT) -endif -else -NUTTXLIBS += lib\libfs$(LIBEXT) lib\libdrivers$(LIBEXT) lib\libbinfmt$(LIBEXT) -endif - -# Add libraries for the NX graphics sub-system - -ifeq ($(CONFIG_NX),y) -NUTTXLIBS += lib\libgraphics$(LIBEXT) -endif - -# LINKLIBS derives from NUTTXLIBS and is simply the same list with the subdirectory removed - -LINKLIBS = $(patsubst lib\\%,%,$(NUTTXLIBS)) - -# This is the name of the final target (relative to the top level directorty) - -BIN = nuttx$(EXEEXT) - -all: $(BIN) -.PHONY: context clean_context check_context export subdir_clean clean subdir_distclean distclean apps_clean apps_distclean - -# Target used to copy include\nuttx\math.h. If CONFIG_ARCH_MATH_H is -# defined, then there is an architecture specific math.h header file -# that will be included indirectly from include\math.h. But first, we -# have to copy math.h from include\nuttx\. to include\. Logic within -# include\nuttx\math.h will hand the redirection to the architecture- -# specific math.h header file. -# -# If the CONFIG_LIBM is defined, the Rhombus libm will be built at libc\math. -# Definitions and prototypes for the Rhombus libm are also contained in -# include\nuttx\math.h and so the file must also be copied in that case. -# -# If neither CONFIG_ARCH_MATH_H nor CONFIG_LIBM is defined, then no math.h -# header file will be provided. You would want that behavior if (1) you -# don't use libm, or (2) you want to use the math.h and libm provided -# within your toolchain. - -ifeq ($(CONFIG_ARCH_MATH_H),y) -NEED_MATH_H = y -else -ifeq ($(CONFIG_LIBM),y) -NEED_MATH_H = y -endif -endif - -ifeq ($(NEED_MATH_H),y) -include\math.h: include\nuttx\math.h - $(Q) cp -f include\nuttx\math.h include\math.h -else -include\math.h: -endif - -# The float.h header file defines the properties of your floating point -# implementation. It would always be best to use your toolchain's float.h -# header file but if none is avaiable, a default float.h header file will -# provided if this option is selected. However there is no assurance that -# the settings in this float.h are actually correct for your platform! - -ifeq ($(CONFIG_ARCH_FLOAT_H),y) -include\float.h: include\nuttx\float.h - $(Q) cp -f include\nuttx\float.h include\float.h -else -include\float.h: -endif - -# Target used to copy include\nuttx\stdarg.h. If CONFIG_ARCH_STDARG_H is -# defined, then there is an architecture specific stdarg.h header file -# that will be included indirectly from include\stdarg.h. But first, we -# have to copy stdarg.h from include\nuttx\. to include\. - -ifeq ($(CONFIG_ARCH_STDARG_H),y) -include\stdarg.h: include\nuttx\stdarg.h - $(Q) cp -f include\nuttx\stdarg.h include\stdarg.h -else -include\stdarg.h: -endif - -# Targets used to build include\nuttx\version.h. Creation of version.h is -# part of the overall NuttX configuration sequence. Notice that the -# tools\mkversion tool is built and used to create include\nuttx\version.h - -tools\mkversion$(HOSTEXEEXT): - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkversion$(HOSTEXEEXT) - -$(TOPDIR)\.version: - $(Q) if [ ! -f .version ]; then \ - echo "No .version file found, creating one"; \ - tools\version.sh -v 0.0 -b 0 .version; \ - chmod 755 .version; \ - fi - -include\nuttx\version.h: $(TOPDIR)\.version tools\mkversion$(HOSTEXEEXT) - $(Q) tools\mkversion$(HOSTEXEEXT) $(TOPDIR) > include\nuttx\version.h - -# Targets used to build include\nuttx\config.h. Creation of config.h is -# part of the overall NuttX configuration sequence. Notice that the -# tools\mkconfig tool is built and used to create include\nuttx\config.h - -tools\mkconfig$(HOSTEXEEXT): - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkconfig$(HOSTEXEEXT) - -include\nuttx\config.h: $(TOPDIR)\.config tools\mkconfig$(HOSTEXEEXT) - $(Q) tools\mkconfig$(HOSTEXEEXT) $(TOPDIR) > include\nuttx\config.h - -# Targets used to create dependencies - -tools\mkdeps$(HOSTEXEEXT): - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkdeps$(HOSTEXEEXT) - -# dirlinks, and helpers -# -# Directories links. Most of establishing the NuttX configuration involves -# setting up symbolic links with 'generic' directory names to specific, -# configured directories. -# -# Link the apps\include directory to include\apps - -include\apps: Make.defs -ifneq ($(APPDIR),) - @echo "LN: include\apps $(APPDIR)\include" -ifeq ($(CONFIG_WINDOWS_MKLINK),y) - $(Q) /user:administrator mklink /d include\apps $(APPDIR)\include -else - $(Q) xcopy $(APPDIR)\include include\apps /c /q /s /e /y /i - $(Q) echo FAKELNK > include\apps\.fakelnk -endif -endif - -# Link the arch\\include directory to include\arch - -include\arch: Make.defs - @echo "LN: include\arch -> $(ARCH_DIR)\include" -ifeq ($(CONFIG_WINDOWS_MKLINK),y) - $(Q) /user:administrator mklink /d include\arch $(TOPDIR)\$(ARCH_DIR)\include -else - $(Q) xcopy $(TOPDIR)\$(ARCH_DIR)\include include\arch /c /q /s /e /y /i - $(Q) echo FAKELNK > include\arch\.fakelnk -endif - -# Link the configs\\include directory to include\arch\board - -include\arch\board: include\arch Make.defs include\arch - @echo "LN: include\arch\board -> $(BOARD_DIR)\include" -ifeq ($(CONFIG_WINDOWS_MKLINK),y) - $(Q) /user:administrator mklink /d include\arch\board $(TOPDIR)\$(BOARD_DIR)\include -else - $(Q) xcopy $(TOPDIR)\$(BOARD_DIR)\include include\arch\board /c /q /s /e /y /i - $(Q) echo FAKELNK > include\arch\board\.fakelnk -endif - -# Link the configs\\src dir to arch\\src\board - -$(ARCH_SRC)\board: Make.defs - @echo "LN: $(ARCH_SRC)\board -> $(BOARD_DIR)\src" -ifeq ($(CONFIG_WINDOWS_MKLINK),y) - $(Q) /user:administrator mklink /d $(ARCH_SRC)\board $(TOPDIR)\$(BOARD_DIR)\src -else - $(Q) xcopy $(TOPDIR)\$(BOARD_DIR)\src $(ARCH_SRC)\board /c /q /s /e /y /i - $(Q) echo FAKELNK > $(ARCH_SRC)\board\.fakelnk -endif - -# Link arch\\include\ to arch\\include\chip - -$(ARCH_SRC)\chip: Make.defs -ifneq ($(CONFIG_ARCH_CHIP),) - @echo "LN: $(ARCH_SRC)\chip -> $(ARCH_SRC)\$(CONFIG_ARCH_CHIP)" -ifeq ($(CONFIG_WINDOWS_MKLINK),y) - $(Q) /user:administrator mklink /d $(ARCH_SRC)\chip $(TOPDIR)\$(ARCH_SRC)\$(CONFIG_ARCH_CHIP) -else - $(Q) xcopy $(TOPDIR)\$(ARCH_SRC)\$(CONFIG_ARCH_CHIP) $(ARCH_SRC)\chip /c /q /s /e /y /i - $(Q) echo FAKELNK > $(ARCH_SRC)\chip\.fakelnk -endif -endif - -# Link arch\\src\ to arch\\src\chip - -include\arch\chip: include\arch Make.defs -ifneq ($(CONFIG_ARCH_CHIP),) - @echo "LN: include\arch\chip -> $(ARCH_INC)\$(CONFIG_ARCH_CHIP)" -ifeq ($(CONFIG_WINDOWS_MKLINK),y) - $(Q) /user:administrator mklink /d include\arch\chip $(TOPDIR)\$(ARCH_INC)\$(CONFIG_ARCH_CHIP) -else - $(Q) xcopy $(TOPDIR)\$(ARCH_INC)\$(CONFIG_ARCH_CHIP) include\arch\chip /c /q /s /e /y /i - $(Q) echo FAKELNK > include\arch\chip\.fakelnk -endif -endif - -dirlinks: include\arch include\arch\board include\arch\chip $(ARCH_SRC)\board $(ARCH_SRC)\chip include\apps - -# context -# -# The context target is invoked on each target build to assure that NuttX is -# properly configured. The basic configuration steps include creation of the -# the config.h and version.h header files in the include\nuttx directory and -# the establishment of symbolic links to configured directories. - -context: check_context include\nuttx\config.h include\nuttx\version.h include\math.h include\float.h include\stdarg.h dirlinks - $(Q) for %%G in ($(CONTEXTDIRS)) do ( $(MAKE) -C %%G TOPDIR="$(TOPDIR)" context ) - -# clean_context -# -# This is part of the distclean target. It removes all of the header files -# and symbolic links created by the context target. - -clean_context: - $(call DELFILE, include\nuttx\config.h) - $(call DELFILE, include\nuttx\version.h) - $(call DELFILE, include\math.h) - $(call DELFILE, include\stdarg.h) - $(call DELDIR, include\arch\board) - $(call DELDIR, include\arch\chip) - $(call DELDIR, include\arch) - $(call DELDIR, $(ARCH_SRC)\board) - $(call DELDIR, $(ARCH_SRC)\chip) - $(call DELDIR, include\apps) - -# check_context -# -# This target checks if NuttX has been configured. NuttX is configured using -# the script tools\configure.sh. That script will install certain files in -# the top-level NuttX build directory. This target verifies that those -# configuration files have been installed and that NuttX is ready to be built. - -check_context: - $(Q) if not exist $(TOPDIR)\.config echo "$(TOPDIR)\.config does not exist" - $(Q) if not exist $(TOPDIR)\Make.defs echo "$(TOPDIR)\Make.defs does not exist" - -# Archive targets. The target build sequency will first create a series of -# libraries, one per configured source file directory. The final NuttX -# execution will then be built from those libraries. The following targets -# build those libraries. -# -# Possible kernel-mode builds - -libc\libkc$(LIBEXT): context - $(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libkc$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib\libkc$(LIBEXT): libc\libkc$(LIBEXT) - $(Q) install libc\libkc$(LIBEXT) lib\libkc$(LIBEXT) - -sched\libsched$(LIBEXT): context - $(Q) $(MAKE) -C sched TOPDIR="$(TOPDIR)" libsched$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib\libsched$(LIBEXT): sched\libsched$(LIBEXT) - $(Q) install sched\libsched$(LIBEXT) lib\libsched$(LIBEXT) - -$(ARCH_SRC)\libarch$(LIBEXT): context - $(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" libarch$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib\libarch$(LIBEXT): $(ARCH_SRC)\libarch$(LIBEXT) - $(Q) install $(ARCH_SRC)\libarch$(LIBEXT) lib\libarch$(LIBEXT) - -net\libnet$(LIBEXT): context - $(Q) $(MAKE) -C net TOPDIR="$(TOPDIR)" libnet$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib\libnet$(LIBEXT): net\libnet$(LIBEXT) - $(Q) install net\libnet$(LIBEXT) lib\libnet$(LIBEXT) - -fs\libfs$(LIBEXT): context - $(Q) $(MAKE) -C fs TOPDIR="$(TOPDIR)" libfs$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib\libfs$(LIBEXT): fs\libfs$(LIBEXT) - $(Q) install fs\libfs$(LIBEXT) lib\libfs$(LIBEXT) - -drivers\libdrivers$(LIBEXT): context - $(Q) $(MAKE) -C drivers TOPDIR="$(TOPDIR)" libdrivers$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib\libdrivers$(LIBEXT): drivers\libdrivers$(LIBEXT) - $(Q) install drivers\libdrivers$(LIBEXT) lib\libdrivers$(LIBEXT) - -binfmt\libbinfmt$(LIBEXT): context - $(Q) $(MAKE) -C binfmt TOPDIR="$(TOPDIR)" libbinfmt$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib\libbinfmt$(LIBEXT): binfmt\libbinfmt$(LIBEXT) - $(Q) install binfmt\libbinfmt$(LIBEXT) lib\libbinfmt$(LIBEXT) - -graphics\libgraphics$(LIBEXT): context - $(Q) $(MAKE) -C graphics TOPDIR="$(TOPDIR)" libgraphics$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib\libgraphics$(LIBEXT): graphics\libgraphics$(LIBEXT) - $(Q) install graphics\libgraphics$(LIBEXT) lib\libgraphics$(LIBEXT) - -syscall\libstubs$(LIBEXT): context - $(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libstubs$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib\libstubs$(LIBEXT): syscall\libstubs$(LIBEXT) - $(Q) install syscall\libstubs$(LIBEXT) lib\libstubs$(LIBEXT) - -# Possible user-mode builds - -libc\libuc$(LIBEXT): context - $(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libuc$(LIBEXT) - -lib\libuc$(LIBEXT): libc\libuc$(LIBEXT) - $(Q) install libc\libuc$(LIBEXT) lib\libuc$(LIBEXT) - -libxx\libcxx$(LIBEXT): context - $(Q) $(MAKE) -C libxx TOPDIR="$(TOPDIR)" libcxx$(LIBEXT) - -lib\libcxx$(LIBEXT): libxx\libcxx$(LIBEXT) - $(Q) install libxx\libcxx$(LIBEXT) lib\libcxx$(LIBEXT) - -mm\libmm$(LIBEXT): context - $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) EXTRADEFINES=$(KDEFINE) - -lib\libmm$(LIBEXT): mm\libmm$(LIBEXT) - $(Q) install mm\libmm$(LIBEXT) lib\libmm$(LIBEXT) - -$(APPDIR)\libapps$(LIBEXT): context - $(Q) $(MAKE) -C $(APPDIR) TOPDIR="$(TOPDIR)" libapps$(LIBEXT) - -lib\libapps$(LIBEXT): $(APPDIR)\libapps$(LIBEXT) - $(Q) install $(APPDIR)\libapps$(LIBEXT) lib\libapps$(LIBEXT) - -syscall\libproxies$(LIBEXT): context - $(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libproxies$(LIBEXT) - -lib\libproxies$(LIBEXT): syscall\libproxies$(LIBEXT) - $(Q) install syscall\libproxies$(LIBEXT) lib\libproxies$(LIBEXT) - -# Possible non-kernel builds - -libc\libc$(LIBEXT): context - $(Q) $(MAKE) -C libc TOPDIR="$(TOPDIR)" libc$(LIBEXT) - -lib\libc$(LIBEXT): libc\libc$(LIBEXT) - $(Q) install libc\libc$(LIBEXT) lib\libc$(LIBEXT) - -# pass1 and pass2 -# -# If the 2 pass build option is selected, then this pass1 target is -# configured to built before the pass2 target. This pass1 target may, as an -# example, build an extra link object (CONFIG_PASS1_OBJECT) which may be an -# incremental (relative) link object, but could be a static library (archive); -# some modification to this Makefile would be required if CONFIG_PASS1_OBJECT -# is an archive. Exactly what is performed during pass1 or what it generates -# is unknown to this makefule unless CONFIG_PASS1_OBJECT is defined. - -pass1deps: pass1dep $(USERLIBS) - -pass1: pass1deps -ifeq ($(CONFIG_BUILD_2PASS),y) - $(Q) if [ -z "$(CONFIG_PASS1_BUILDIR)" ]; then \ - echo "ERROR: CONFIG_PASS1_BUILDIR not defined"; \ - exit 1; \ - fi - $(Q) if [ ! -d "$(CONFIG_PASS1_BUILDIR)" ]; then \ - echo "ERROR: CONFIG_PASS1_BUILDIR does not exist"; \ - exit 1; \ - fi - $(Q) if [ ! -f "$(CONFIG_PASS1_BUILDIR)\Makefile" ]; then \ - echo "ERROR: No Makefile in CONFIG_PASS1_BUILDIR"; \ - exit 1; \ - fi - $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" LINKLIBS="$(LINKLIBS)" USERLIBS="$(USERLIBS)" "$(CONFIG_PASS1_TARGET)" -endif - -pass2deps: pass2dep $(NUTTXLIBS) - -pass2: pass2deps - $(Q) $(MAKE) -C $(ARCH_SRC) TOPDIR="$(TOPDIR)" EXTRA_OBJS="$(EXTRA_OBJS)" LINKLIBS="$(LINKLIBS)" EXTRADEFINES=$(KDEFINE) $(BIN) -ifeq ($(CONFIG_RRLOAD_BINARY),y) - @echo "MK: $(BIN).rr" - $(Q) $(TOPDIR)\tools\mkimage.sh --Prefix $(CROSSDEV) $(BIN) $(BIN).rr -endif -ifeq ($(CONFIG_INTELHEX_BINARY),y) - @echo "CP: $(BIN).hex" - $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O ihex $(BIN) $(BIN).hex -endif -ifeq ($(CONFIG_MOTOROLA_SREC),y) - @echo "CP: $(BIN).srec" - $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O srec $(BIN) $(BIN).srec -endif -ifeq ($(CONFIG_RAW_BINARY),y) - @echo "CP: $(BIN).bin" - $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O binary $(BIN) $(BIN).bin -endif - -# $(BIN) -# -# Create the final NuttX executable in a two pass build process. In the -# normal case, all pass1 and pass2 dependencies are created then pass1 -# and pass2 targets are built. However, in some cases, you may need to build -# pass1 depenencies and pass1 first, then build pass2 dependencies and pass2. -# in that case, execute 'make pass1 pass2' from the command line. - -$(BIN): pass1deps pass2deps pass1 pass2 - -# download -# -# This is a helper target that will rebuild NuttX and download it to the target -# system in one step. The operation of this target depends completely upon -# implementation of the DOWNLOAD command in the user Make.defs file. It will -# generate an error an error if the DOWNLOAD command is not defined. - -download: $(BIN) - $(call DOWNLOAD, $<) - -# pass1dep: Create pass1 build dependencies -# pass2dep: Create pass2 build dependencies - -pass1dep: context tools\mkdeps$(HOSTEXEEXT) - $(Q) for %%G in ($(USERDEPDIRS)) do ( $(MAKE) -C %%G TOPDIR="$(TOPDIR)" depend ) - -pass2dep: context tools\mkdeps$(HOSTEXEEXT) - $(Q) for %%G in ($(KERNDEPDIRS)) do ( $(MAKE) -C %%G TOPDIR="$(TOPDIR)" EXTRADEFINES=$(KDEFINE) depend ) - -# Configuration targets -# -# These targets depend on the kconfig-frontends packages. To use these, you -# must first download and install the kconfig-frontends package from this -# location: http://ymorin.is-a-geek.org/projects/kconfig-frontends. See -# misc\tools\README.txt for additional information. - -config: - $(Q) APPSDIR=${CONFIG_APPS_DIR} conf Kconfig - -oldconfig: - $(Q) APPSDIR=${CONFIG_APPS_DIR} conf --oldconfig Kconfig - -menuconfig: - $(Q) APPSDIR=${CONFIG_APPS_DIR} mconf Kconfig - -# export -# -# The export target will package the NuttX libraries and header files into -# an exportable package. Caveats: (1) These needs some extension for the KERNEL -# build; it needs to receive USERLIBS and create a libuser.a). (2) The logic -# in tools\mkexport.sh only supports GCC and, for example, explicitly assumes -# that the archiver is 'ar' - -export: pass2deps - $(Q) tools\mkexport.sh -w$(WINTOOL) -t "$(TOPDIR)" -l "$(NUTTXLIBS)" - -# General housekeeping targets: dependencies, cleaning, etc. -# -# depend: Create both PASS1 and PASS2 dependencies -# clean: Removes derived object files, archives, executables, and -# temporary files, but retains the configuration and context -# files and directories. -# distclean: Does 'clean' then also removes all configuration and context -# files. This essentially restores the directory structure -# to its original, unconfigured stated. - -depend: pass1dep pass2dep - -subdir_clean: - $(Q) for %%G in ($(CLEANDIRS)) do ( if exist %%G\Makefile $(MAKE) -C %%G TOPDIR="$(TOPDIR)" clean ) - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" clean - $(Q) $(MAKE) -C mm -f Makefile.test TOPDIR="$(TOPDIR)" clean -ifeq ($(CONFIG_BUILD_2PASS),y) - $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" clean -endif - -clean: subdir_clean - $(call DELFILE, $(BIN)) - $(call DELFILE, nuttx.*) - $(call DELFILE, mm_test) - $(call DELFILE, *.map) - $(call DELFILE, _SAVED_APPS_config) - $(call DELFILE, nuttx-export*) - $(call CLEAN) - -subdir_distclean: - $(Q) for %%G in ($(CLEANDIRS)) do ( if exist %%G\Makefile $(MAKE) -C %%G TOPDIR="$(TOPDIR)" distclean ) - -distclean: clean subdir_distclean clean_context -ifeq ($(CONFIG_BUILD_2PASS),y) - $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean -endif - $(call DELFILE, Make.defs) - $(call DELFILE, setenv.sh) - $(call DELFILE, setenv.bat) - $(call DELFILE, .config) - $(call DELFILE, .config.old) - -# Application housekeeping targets. The APPDIR variable refers to the user -# application directory. A sample apps\ directory is included with NuttX, -# however, this is not treated as part of NuttX and may be replaced with a -# different application directory. For the most part, the application -# directory is treated like any other build directory in this script. However, -# as a convenience, the following targets are included to support housekeeping -# functions in the user application directory from the NuttX build directory. -# -# apps_clean: Perform the clean operation only in the user application -# directory -# apps_distclean: Perform the distclean operation only in the user application -# directory. Note that the apps\.config file (inf any) is -# preserved so that this is not a "full" distclean but more of a -# configuration "reset." (There willnot be an apps\.config -# file if the configuration was generated via make menuconfig). - -apps_clean: -ifneq ($(APPDIR),) - $(Q) $(MAKE) -C "$(TOPDIR)\$(APPDIR)" TOPDIR="$(TOPDIR)" clean -endif - -apps_distclean: -ifneq ($(APPDIR),) - $(call DELFILE, _SAVED_APPS_config - $(Q) if exist "$(TOPDIR)\$(APPDIR)\.config" ( cp "$(TOPDIR)\$(APPDIR)\.config" _SAVED_APPS_config ) - $(Q) $(MAKE) -C "$(TOPDIR)\$(APPDIR)" TOPDIR="$(TOPDIR)" distclean - $(Q) if exist _SAVED_APPS_config ( mv _SAVED_APPS_config "$(TOPDIR)\$(APPDIR)\.config" ) -endif - diff --git a/nuttx/arch/arm/include/elf.h b/nuttx/arch/arm/include/elf.h deleted file mode 100644 index 21b2c1c2c1..0000000000 --- a/nuttx/arch/arm/include/elf.h +++ /dev/null @@ -1,243 +0,0 @@ -/**************************************************************************** - * arch/arm/include/syscall.h - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Reference: "ELF for the ARM® Architecture," ARM IHI 0044D, current through - * ABI release 2.08, October 28, 2009, ARM Limited. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#ifndef __ARCH_ARM_INCLUDE_ELF_H -#define __ARCH_ARM_INCLUDE_ELF_H - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* 4.3.1 ELF Identification. Should have: - * - * e_machine = EM_ARM - * e_ident[EI_CLASS] = ELFCLASS32 - * e_ident[EI_DATA] = ELFDATA2LSB (little endian) or ELFDATA2MSB (big endian) - */ - -#if 0 /* Defined in include/elf32.h */ -#define EM_ARM 40 -#endif - -/* Table 4-2, ARM-specific e_flags */ - -#define EF_ARM_EABI_MASK 0xff000000 -#define EF_ARM_EABI_UNKNOWN 0x00000000 -#define EF_ARM_EABI_VER1 0x01000000 -#define EF_ARM_EABI_VER2 0x02000000 -#define EF_ARM_EABI_VER3 0x03000000 -#define EF_ARM_EABI_VER4 0x04000000 -#define EF_ARM_EABI_VER5 0x05000000 - -#define EF_ARM_BE8 0x00800000 - -/* Table 4-4, Processor specific section types */ - -#define SHT_ARM_EXIDX 0x70000001 /* Exception Index table */ -#define SHT_ARM_PREEMPTMAP 0x70000002 /* BPABI DLL dynamic linking pre-emption map */ -#define SHT_ARM_ATTRIBUTES 0x70000003 /* Object file compatibility attributes */ -#define SHT_ARM_DEBUGOVERLAY 0x70000004 -#define SHT_ARM_OVERLAYSECTION 0x70000005 - -/* 4.7.1 Relocation codes - * - * S (when used on its own) is the address of the symbol. - * A is the addend for the relocation. - * P is the address of the place being relocated (derived from r_offset). - * Pa is the adjusted address of the place being relocated, defined as (P & 0xFFFFFFFC). - * T is 1 if the target symbol S has type STT_FUNC and the symbol addresses a Thumb instruction; - * it is 0 otherwise. - * B(S) is the addressing origin of the output segment defining the symbol S. - * GOT_ORG is the addressing origin of the Global Offset Table - * GOT(S) is the address of the GOT entry for the symbol S. - */ - -#define R_ARM_NONE 0 /* No relocation */ -#define R_ARM_PC24 1 /* ARM ((S + A) | T) - P */ -#define R_ARM_ABS32 2 /* Data (S + A) | T */ -#define R_ARM_REL32 3 /* Data ((S + A) | T) - P */ -#define R_ARM_LDR_PC_G0 4 /* ARM S + A - P */ -#define R_ARM_ABS16 5 /* Data S + A */ -#define R_ARM_ABS12 6 /* ARM S + A */ -#define R_ARM_THM_ABS5 7 /* Thumb16 S + A */ -#define R_ARM_ABS8 8 /* Data S + A */ -#define R_ARM_SBREL32 9 /* Data ((S + A) | T) - B(S) */ -#define R_ARM_THM_CALL 10 /* Thumb32 ((S + A) | T) - P */ -#define R_ARM_THM_PC8 11 /* Thumb16 S + A - Pa */ -#define R_ARM_BREL_ADJ 12 /* Data ?B(S) + A */ -#define R_ARM_TLS_DESC 13 /* Data */ -#define R_ARM_THM_SWI8 14 /* Obsolete */ -#define R_ARM_XPC25 15 /* Obsolete */ -#define R_ARM_THM_XPC22 16 /* Obsolete */ -#define R_ARM_TLS_DTPMOD32 17 /* Data Module[S] */ -#define R_ARM_TLS_DTPOFF32 18 /* Data S + A - TLS */ -#define R_ARM_TLS_TPOFF32 19 /* Data S + A - tp */ -#define R_ARM_COPY 20 /* Miscellaneous */ -#define R_ARM_GLOB_DAT 21 /* Data (S + A) | T */ -#define R_ARM_JUMP_SLOT 22 /* Data (S + A) | T */ -#define R_ARM_RELATIVE 23 /* Data B(S) + A */ -#define R_ARM_GOTOFF32 24 /* Data ((S + A) | T) - GOT_ORG */ -#define R_ARM_BASE_PREL 25 /* Data B(S) + A - P */ -#define R_ARM_GOT_BREL 26 /* Data GOT(S) + A - GOT_ORG */ -#define R_ARM_PLT32 27 /* ARM ((S + A) | T) - P */ -#define R_ARM_CALL 28 /* ARM ((S + A) | T) - P */ -#define R_ARM_JUMP24 29 /* ARM ((S + A) | T) - P */ -#define R_ARM_THM_JUMP24 30 /* Thumb32 ((S + A) | T) - P */ -#define R_ARM_BASE_ABS 31 /* Data B(S) + A */ -#define R_ARM_ALU_PCREL_7_0 32 /* Obsolete */ -#define R_ARM_ALU_PCREL_15_8 33 /* Obsolete */ -#define R_ARM_ALU_PCREL_23_15 34 /* Obsolete */ -#define R_ARM_LDR_SBREL_11_0_NC 35 /* ARM S + A - B(S) */ -#define R_ARM_ALU_SBREL_19_12_NC 36 /* ARM S + A - B(S) */ -#define R_ARM_ALU_SBREL_27_20_CK 37 /* ARM S + A - B(S) */ -#define R_ARM_TARGET1 38 /* Miscellaneous (S + A) | T or ((S + A) | T) - P */ -#define R_ARM_SBREL31 39 /* Data ((S + A) | T) - B(S) */ -#define R_ARM_V4BX 40 /* Miscellaneous */ -#define R_ARM_TARGET2 41 /* Miscellaneous */ -#define R_ARM_PREL31 42 /* Data ((S + A) | T) - P */ -#define R_ARM_MOVW_ABS_NC 43 /* ARM (S + A) | T */ -#define R_ARM_MOVT_ABS 44 /* ARM S + A */ -#define R_ARM_MOVW_PREL_NC 45 /* ARM ((S + A) | T) - P */ -#define R_ARM_MOVT_PREL 46 /* ARM S + A - P */ -#define R_ARM_THM_MOVW_ABS_NC 47 /* Thumb32 (S + A) | T */ -#define R_ARM_THM_MOVT_ABS 48 /* Thumb32 S + A */ -#define R_ARM_THM_MOVW_PREL_NC 49 /* Thumb32 ((S + A) | T) - P */ -#define R_ARM_THM_MOVT_PREL 50 /* Thumb32 S + A - P */ -#define R_ARM_THM_JUMP19 51 /* Thumb32 ((S + A) | T) - P */ -#define R_ARM_THM_JUMP6 52 /* Thumb16 S + A - P */ -#define R_ARM_THM_ALU_PREL_11_0 53 /* Thumb32 ((S + A) | T) - Pa */ -#define R_ARM_THM_PC12 54 /* Thumb32 S + A - Pa */ -#define R_ARM_ABS32_NOI 55 /* Data S + A */ -#define R_ARM_REL32_NOI 56 /* Data S + A - P */ -#define R_ARM_ALU_PC_G0_NC 57 /* ARM ((S + A) | T) - P */ -#define R_ARM_ALU_PC_G0 58 /* ARM ((S + A) | T) - P */ -#define R_ARM_ALU_PC_G1_NC 59 /* ARM ((S + A) | T) - P */ -#define R_ARM_ALU_PC_G1 60 /* ARM ((S + A) | T) - P */ -#define R_ARM_ALU_PC_G2 61 /* ARM ((S + A) | T) - P */ -#define R_ARM_LDR_PC_G1 62 /* ARM S + A - P */ -#define R_ARM_LDR_PC_G2 63 /* ARM S + A - P */ -#define R_ARM_LDRS_PC_G0 64 /* ARM S + A - P */ -#define R_ARM_LDRS_PC_G1 65 /* ARM S + A - P */ -#define R_ARM_LDRS_PC_G2 66 /* ARM S + A - P */ -#define R_ARM_LDC_PC_G0 67 /* ARM S + A - P */ -#define R_ARM_LDC_PC_G1 68 /* ARM S + A - P */ -#define R_ARM_LDC_PC_G2 69 /* ARM S + A - P */ -#define R_ARM_ALU_SB_G0_NC 70 /* ARM ((S + A) | T) - B(S) */ -#define R_ARM_ALU_SB_G0 71 /* ARM ((S + A) | T) - B(S) */ -#define R_ARM_ALU_SB_G1_NC 72 /* ARM ((S + A) | T) - B(S) */ -#define R_ARM_ALU_SB_G1 73 /* ARM ((S + A) | T) - B(S) */ -#define R_ARM_ALU_SB_G2 74 /* ARM ((S + A) | T) - B(S) */ -#define R_ARM_LDR_SB_G0 75 /* ARM S + A - B(S) */ -#define R_ARM_LDR_SB_G1 76 /* ARM S + A - B(S) */ -#define R_ARM_LDR_SB_G2 77 /* ARM S + A - B(S) */ -#define R_ARM_LDRS_SB_G0 78 /* ARM S + A - B(S) */ -#define R_ARM_LDRS_SB_G1 79 /* ARM S + A - B(S) */ -#define R_ARM_LDRS_SB_G2 80 /* ARM S + A - B(S) */ -#define R_ARM_LDC_SB_G0 81 /* ARM S + A - B(S) */ -#define R_ARM_LDC_SB_G1 82 /* ARM S + A - B(S) */ -#define R_ARM_LDC_SB_G2 83 /* ARM S + A - B(S) */ -#define R_ARM_MOVW_BREL_NC 84 /* ARM ((S + A) | T) - B(S) */ -#define R_ARM_MOVT_BREL 85 /* ARM S + A - B(S) */ -#define R_ARM_MOVW_BREL 86 /* ARM ((S + A) | T) - B(S) */ -#define R_ARM_THM_MOVW_BREL_NC 87 /* Thumb32 ((S + A) | T) - B(S) */ -#define R_ARM_THM_MOVT_BREL 88 /* Thumb32 S + A - B(S) */ -#define R_ARM_THM_MOVW_BREL 89 /* Thumb32 ((S + A) | T) - B(S) */ -#define R_ARM_TLS_GOTDESC 90 /* Data */ -#define R_ARM_TLS_CALL 91 /* ARM */ -#define R_ARM_TLS_DESCSEQ 92 /* ARM TLS relaxation */ -#define R_ARM_THM_TLS_CALL 93 /* Thumb32 */ -#define R_ARM_PLT32_ABS 94 /* Data PLT(S) + A */ -#define R_ARM_GOT_ABS 95 /* Data GOT(S) + A */ -#define R_ARM_GOT_PREL 96 /* Data GOT(S) + A - P */ -#define R_ARM_GOT_BREL12 97 /* ARM GOT(S) + A - GOT_ORG */ -#define R_ARM_GOTOFF12 98 /* ARM S + A - GOT_ORG */ -#define R_ARM_GOTRELAX 99 /* Miscellaneous */ -#define R_ARM_GNU_VTENTRY 100 /* Data */ -#define R_ARM_GNU_VTINHERIT 101 /* Data */ -#define R_ARM_THM_JUMP11 102 /* Thumb16 S + A - P */ -#define R_ARM_THM_JUMP8 103 /* Thumb16 S + A - P */ -#define R_ARM_TLS_GD32 104 /* Data GOT(S) + A - P */ -#define R_ARM_TLS_LDM32 105 /* Data GOT(S) + A - P */ -#define R_ARM_TLS_LDO32 106 /* Data S + A - TLS */ -#define R_ARM_TLS_IE32 107 /* Data GOT(S) + A - P */ -#define R_ARM_TLS_LE32 108 /* Data S + A - tp */ -#define R_ARM_TLS_LDO12 109 /* ARM S + A - TLS */ -#define R_ARM_TLS_LE12 110 /* ARM S + A - tp */ -#define R_ARM_TLS_IE12GP 111 /* ARM GOT(S) + A - GOT_ORG */ -#define R_ARM_ME_TOO 128 /* Obsolete */ -#define R_ARM_THM_TLS_DESCSEQ16 129 /* Thumb16 */ -#define R_ARM_THM_TLS_DESCSEQ32 130 /* Thumb32 */ - -/* 5.2.1 Platform architecture compatibility data */ - -#define PT_ARM_ARCHEXT_FMTMSK 0xff000000 -#define PT_ARM_ARCHEXT_PROFMSK 0x00ff0000 -#define PT_ARM_ARCHEXT_ARCHMSK 0x000000ff - -#define PT_ARM_ARCHEXT_FMT_OS 0x00000000 -#define PT_ARM_ARCHEXT_FMT_ABI 0x01000000 - -#define PT_ARM_ARCHEXT_PROF_NONE 0x00000000 -#define PT_ARM_ARCHEXT_PROF_ARM 0x00410000 -#define PT_ARM_ARCHEXT_PROF_RT 0x00520000 -#define PT_ARM_ARCHEXT_PROF_MC 0x004d0000 -#define PT_ARM_ARCHEXT_PROF_CLASSIC 0x00530000 - -#define PT_ARM_ARCHEXT_ARCH_UNKNOWN 0x00 -#define PT_ARM_ARCHEXT_ARCHv4 0x01 -#define PT_ARM_ARCHEXT_ARCHv4T 0x02 -#define PT_ARM_ARCHEXT_ARCHv5T 0x03 -#define PT_ARM_ARCHEXT_ARCHv5TE 0x04 -#define PT_ARM_ARCHEXT_ARCHv5TEJ 0x05 -#define PT_ARM_ARCHEXT_ARCHv6 0x06 -#define PT_ARM_ARCHEXT_ARCHv6KZ 0x07 -#define PT_ARM_ARCHEXT_ARCHv6T2 0x08 -#define PT_ARM_ARCHEXT_ARCHv6K 0x09 -#define PT_ARM_ARCHEXT_ARCHv7 0x0a -#define PT_ARM_ARCHEXT_ARCHv6M 0x0b -#define PT_ARM_ARCHEXT_ARCHv6SM 0x0c -#define PT_ARM_ARCHEXT_ARCHv7EM 0x0d - -/* Table 5-6, ARM-specific dynamic array tags */ - -#define DT_ARM_RESERVED1 0x70000000 -#define DT_ARM_SYMTABSZ 0x70000001 -#define DT_ARM_PREEMPTMAP 0x70000002 -#define DT_ARM_RESERVED2 0x70000003 - -#endif /* __ARCH_ARM_INCLUDE_ELF_H */ diff --git a/nuttx/arch/arm/src/arm/up_elf.c b/nuttx/arch/arm/src/arm/up_elf.c deleted file mode 100644 index 2dd8366aa0..0000000000 --- a/nuttx/arch/arm/src/arm/up_elf.c +++ /dev/null @@ -1,257 +0,0 @@ -/**************************************************************************** - * arch/arm/src/arm/up_elf.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: arch_checkarch - * - * Description: - * Given the ELF header in 'hdr', verify that the ELF file is appropriate - * for the current, configured architecture. Every architecture that uses - * the ELF loader must provide this function. - * - * Input Parameters: - * hdr - The ELF header read from the ELF file. - * - * Returned Value: - * True if the architecture supports this ELF file. - * - ****************************************************************************/ - -bool arch_checkarch(FAR const Elf32_Ehdr *ehdr) -{ - /* Make sure it's an ARM executable */ - - if (ehdr->e_machine != EM_ARM) - { - bdbg("Not for ARM: e_machine=%04x\n", ehdr->e_machine); - return -ENOEXEC; - } - - /* Make sure that 32-bit objects are supported */ - - if (ehdr->e_ident[EI_CLASS] != ELFCLASS32) - { - bdbg("Need 32-bit objects: e_ident[EI_CLASS]=%02x\n", ehdr->e_ident[EI_CLASS]); - return -ENOEXEC; - } - - /* Verify endian-ness */ - -#ifdef CONFIG_ENDIAN_BIG - if (ehdr->e_ident[EI_DATA] != ELFDATA2MSB) -#else - if (ehdr->e_ident[EI_DATA] != ELFDATA2LSB) -#endif - { - bdbg("Wrong endian-ness: e_ident[EI_DATA]=%02x\n", ehdr->e_ident[EI_DATA]); - return -ENOEXEC; - } - - /* Make sure the entry point address is properly aligned */ - - if ((ehdr->e_entry & 3) != 0) - { - bdbg("Entry point is not properly aligned: %08x\n", ehdr->e_entry); - return -ENOEXEC - } - - /* TODO: Check ABI here. */ - return OK; -} - -/**************************************************************************** - * Name: arch_relocate and arch_relocateadd - * - * Description: - * Perform on architecture-specific ELF relocation. Every architecture - * that uses the ELF loader must provide this function. - * - * Input Parameters: - * rel - The relocation type - * sym - The ELF symbol structure containing the fully resolved value. - * addr - The address that requires the relocation. - * - * Returned Value: - * Zero (OK) if the relocation was successful. Otherwise, a negated errno - * value indicating the cause of the relocation failure. - * - ****************************************************************************/ - -int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, - uintptr_t addr) -{ - int32_t offset; - - switch (ELF32_R_TYPE(rel->r_info)) - { - case R_ARM_NONE: - { - /* No relocation */ - } - break; - - case R_ARM_PC24: - case R_ARM_CALL: - case R_ARM_JUMP24: - { - bvdbg("Performing PC24 [%d] link at addr %08lx [%08lx] to sym '%s' st_value=%08lx\n", - ELF32_R_TYPE(rel->r_info), (long)addr, (long)(*(uint32_t*)addr), - sym, (long)sym->st_value); - - offset = (*(uint32_t*)addr & 0x00ffffff) << 2; - if (offset & 0x02000000) - { - offset -= 0x04000000; - } - - offset += sym->st_value - addr; - if (offset & 3 || offset <= (int32_t) 0xfe000000 || offset >= (int32_t) 0x02000000) - { - bdbg(" ERROR: PC24 [%d] relocation out of range, offset=%08lx\n", - ELF32_R_TYPE(rel->r_info), offset); - - return -EINVAL; - } - - offset >>= 2; - - *(uint32_t*)addr &= 0xff000000; - *(uint32_t*)addr |= offset & 0x00ffffff; - } - break; - - case R_ARM_ABS32: - case R_ARM_TARGET1: /* New ABI: TARGET1 always treated as ABS32 */ - { - bvdbg("Performing ABS32 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", - (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value); - - *(uint32_t*)addr += sym->st_value; - } - break; - - case R_ARM_V4BX: - { - bvdbg("Performing V4BX link at addr=%08lx [%08lx]\n", - (long)addr, (long)(*(uint32_t*)addr)); - - /* Preserve only Rm and the condition code */ - - *(uint32_t*)addr &= 0xf000000f; - - /* Change instruction to 'mov pc, Rm' */ - - *(uint32_t*)addr |= 0x01a0f000; - } - break; - - case R_ARM_PREL31: - { - bvdbg("Performing PREL31 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", - (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value); - - offset = *(uint32_t*)addr + sym->st_value - addr; - *(uint32_t*)addr = offset & 0x7fffffff; - } - break; - - case R_ARM_MOVW_ABS_NC: - case R_ARM_MOVT_ABS: - { - bvdbg("Performing MOVx_ABS [%d] link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", - ELF32_R_TYPE(rel->r_info), (long)addr, (long)(*(uint32_t*)addr), - sym, (long)sym->st_value); - - offset = *(uint32_t*)addr; - offset = ((offset & 0xf0000) >> 4) | (offset & 0xfff); - offset = (offset ^ 0x8000) - 0x8000; - - offset += sym->st_value; - if (ELF32_R_TYPE(rel->r_info) == R_ARM_MOVT_ABS) - { - offset >>= 16; - } - - *(uint32_t*)addr &= 0xfff0f000; - *(uint32_t*)addr |= ((offset & 0xf000) << 4) | (offset & 0x0fff); - } - break; - - default: - bdbg("Unsupported relocation: %d\n", ELF32_R_TYPE(rel->r_info)); - return -EINVAL; - } - - return OK; -} - -int arch_relocateadd(FAR const Elf32_Rela *rel, FAR const Elf32_Sym *sym, - uintptr_t addr) -{ - bdbg("RELA relocation not supported\n"); - return -ENOSYS; -} - diff --git a/nuttx/arch/arm/src/armv7-m/Kconfig b/nuttx/arch/arm/src/armv7-m/Kconfig deleted file mode 100644 index dc5aa39153..0000000000 --- a/nuttx/arch/arm/src/armv7-m/Kconfig +++ /dev/null @@ -1,51 +0,0 @@ -# -# For a description of the syntax of this configuration file, -# see misc/tools/kconfig-language.txt. -# - -comment "ARMV7M Configuration Options" - -choice - prompt "Toolchain Selection" - default ARMV7M_TOOLCHAIN_CODESOURCERYW if HOST_WINDOWS - default ARMV7M_TOOLCHAIN_GNU_EABI if !HOST_WINDOWS - -config ARMV7M_TOOLCHAIN_ATOLLIC - bool "Atollic Lite/Pro for Windows" - depends on HOST_WINDOWS - -config ARMV7M_TOOLCHAIN_BUILDROOT - bool "Buildroot (Cygwin or Linux)" - depends on !WINDOWS_NATIVE - -config ARMV7M_TOOLCHAIN_CODEREDL - bool "CodeRed for Linux" - depends on HOST_LINUX - -config ARMV7M_TOOLCHAIN_CODEREDW - bool "CodeRed for Windows" - depends on HOST_WINDOWS - -config ARMV7M_TOOLCHAIN_CODESOURCERYL - bool "CodeSourcery GNU toolchain under Linux" - depends on HOST_LINUX - -config ARMV7M_TOOLCHAIN_CODESOURCERYW - bool "CodeSourcery GNU toolchain under Windows" - depends on HOST_WINDOWS - -config ARMV7M_TOOLCHAIN_DEVKITARM - bool "devkitARM GNU toolchain" - depends on HOST_WINDOWS - -config ARMV7M_TOOLCHAIN_GNU_EABI - bool "Generic GNU EABI toolchain" - ---help--- - This option should work for any modern GNU toolchain (GCC 4.5 or newer) - configured for arm-none-eabi. - -config ARMV7M_TOOLCHAIN_RAISONANCE - bool "STMicro Raisonance for Windows" - depends on HOST_WINDOWS - -endchoice diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs deleted file mode 100644 index e39d7f4141..0000000000 --- a/nuttx/arch/arm/src/armv7-m/Toolchain.defs +++ /dev/null @@ -1,266 +0,0 @@ -############################################################################ -# arch/arm/src/armv7-m/Toolchain.defs -# -# 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. -# -############################################################################ - -# Setup for the selected toolchain - -# -# Handle old-style chip-specific toolchain names in the absence of -# a new-style toolchain specification, force the selection of a single -# toolchain and allow the selected toolchain to be overridden by a -# command-line selection. -# - -ifeq ($(filter y, \ - $(CONFIG_LPC43_ATOLLIC_LITE) \ - $(CONFIG_STM32_ATOLLIC_LITE) \ - $(CONFIG_LPC43_ATOLLIC_PRO) \ - $(CONFIG_STM32_ATOLLIC_PRO) \ - $(CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC) \ - ),y) - CONFIG_ARMV7M_TOOLCHAIN ?= ATOLLIC -endif -ifeq ($(filter y, \ - $(CONFIG_KINETIS_BUILDROOT) \ - $(CONFIG_LM3S_BUILDROOT) \ - $(CONFIG_LPC17_BUILDROOT) \ - $(CONFIG_LPC43_BUILDROOT) \ - $(CONFIG_SAM3U_BUILDROOT) \ - $(CONFIG_STM32_BUILDROOT) \ - $(CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT) \ - ),y) - CONFIG_ARMV7M_TOOLCHAIN ?= BUILDROOT -endif -ifeq ($(filter y, \ - $(CONFIG_LPC17_CODEREDL) \ - $(CONFIG_ARMV7M_TOOLCHAIN_CODEREDL) \ - ),y) - CONFIG_ARMV7M_TOOLCHAIN ?= CODEREDL -endif -ifeq ($(filter y, \ - $(CONFIG_LPC17_CODEREDW) \ - $(CONFIG_LPC43_CODEREDW) \ - $(CONFIG_ARMV7M_TOOLCHAIN_CODEREDW) \ - ),y) - CONFIG_ARMV7M_TOOLCHAIN ?= CODEREDW -endif -ifeq ($(filter y, \ - $(CONFIG_KINETIS_CODESOURCERYL) \ - $(CONFIG_LM3S_CODESOURCERYL) \ - $(CONFIG_LPC17_CODESOURCERYL) \ - $(CONFIG_LPC43_CODESOURCERYL) \ - $(CONFIG_SAM3U_CODESOURCERYL) \ - $(CONFIG_STM32_CODESOURCERYL) \ - $(CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL) \ - ),y) - CONFIG_ARMV7M_TOOLCHAIN ?= CODESOURCERYL -endif -ifeq ($(filter y, \ - $(CONFIG_KINETIS_CODESOURCERYW) \ - $(CONFIG_LM3S_CODESOURCERYW) \ - $(CONFIG_LPC17_CODESOURCERYW) \ - $(CONFIG_LPC43_CODESOURCERYW) \ - $(CONFIG_SAM3U_CODESOURCERYW) \ - $(CONFIG_STM32_CODESOURCERYW) \ - $(CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW) \ - ),y) - CONFIG_ARMV7M_TOOLCHAIN ?= CODESOURCERYW -endif -ifeq ($(filter y, \ - $(CONFIG_KINETIS_DEVKITARM) \ - $(CONFIG_LM3S_DEVKITARM) \ - $(CONFIG_LPC17_DEVKITARM) \ - $(CONFIG_LPC43_DEVKITARM) \ - $(CONFIG_SAM3U_DEVKITARM) \ - $(CONFIG_STM32_DEVKITARM) \ - $(CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM) \ - ),y) - CONFIG_ARMV7M_TOOLCHAIN ?= DEVKITARM -endif -ifeq ($(filter y, \ - $(CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI) \ - ),y) - CONFIG_ARMV7M_TOOLCHAIN ?= GNU_EABI -endif -ifeq ($(filter y, \ - $(CONFIG_STM32_RAISONANCE) \ - $(CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE) \ - ),y) - CONFIG_ARMV7M_TOOLCHAIN ?= RAISONANCE -endif - -# -# Supported toolchains -# -# TODO - It's likely that all of these toolchains now support the -# CortexM4. Since they are all GCC-based, we could almost -# certainly simplify this further. -# -# Each toolchain definition should set: -# -# CROSSDEV The GNU toolchain triple (command prefix) -# ARCROSSDEV If required, an alternative prefix used when -# invoking ar and nm. -# ARCHCPUFLAGS CPU-specific flags selecting the instruction set -# FPU options, etc. -# MAXOPTIMIZATION The maximum optimization level that results in -# reliable code generation. -# - -# Atollic toolchain under Windows - -ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),ATOLLIC) - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- -ifneq ($(CONFIG_WINDOWS_NATIVE),y) - WINTOOL = y -endif - ifeq ($(CONFIG_ARCH_CORTEXM4),y) - ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard - else - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft - endif - else ifeq ($(CONFIG_ARCH_CORTEXM3),y) - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - endif -endif - -# NuttX buildroot under Linux or Cygwin - -ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),BUILDROOT) - # 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 - -# Code Red RedSuite under Linux - -ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDL) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ifeq ($(CONFIG_ARCH_CORTEXM4),y) - ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard - else - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft - endif - else ifeq ($(CONFIG_ARCH_CORTEXM3),y) - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - endif -endif - -# Code Red RedSuite under Windows - -ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDW) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- -ifneq ($(CONFIG_WINDOWS_NATIVE),y) - WINTOOL = y -endif - ifeq ($(CONFIG_ARCH_CORTEXM4),y) - ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard - else - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft - endif - else ifeq ($(CONFIG_ARCH_CORTEXM3),y) - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - endif -endif - -# CodeSourcery under Linux - -ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYL) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - MAXOPTIMIZATION = -O2 -endif - -# CodeSourcery under Windows - -ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYW) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- -ifneq ($(CONFIG_WINDOWS_NATIVE),y) - WINTOOL = y -endif - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif - -# devkitARM under Windows - -ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),DEVKITARM) - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- -ifneq ($(CONFIG_WINDOWS_NATIVE),y) - WINTOOL = y -endif - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif - -# Generic GNU EABI toolchain on OS X, Linux or any typical Posix system - -ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),GNU_EABI) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- - MAXOPTIMIZATION = -O3 - ifeq ($(CONFIG_ARCH_CORTEXM4),y) - ifeq ($(CONFIG_ARCH_FPU),y) - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard - else - ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft - endif - else ifeq ($(CONFIG_ARCH_CORTEXM3),y) - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft - endif -endif - -# Raisonance RIDE7 under Windows - -ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),RAISONANCE) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- -ifneq ($(CONFIG_WINDOWS_NATIVE),y) - WINTOOL = y -endif - ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft -endif diff --git a/nuttx/arch/arm/src/armv7-m/up_elf.c b/nuttx/arch/arm/src/armv7-m/up_elf.c deleted file mode 100644 index b838a69057..0000000000 --- a/nuttx/arch/arm/src/armv7-m/up_elf.c +++ /dev/null @@ -1,450 +0,0 @@ -/**************************************************************************** - * arch/arm/src/armv7-m/up_elf.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: arch_checkarch - * - * Description: - * Given the ELF header in 'hdr', verify that the ELF file is appropriate - * for the current, configured architecture. Every architecture that uses - * the ELF loader must provide this function. - * - * Input Parameters: - * hdr - The ELF header read from the ELF file. - * - * Returned Value: - * True if the architecture supports this ELF file. - * - ****************************************************************************/ - -bool arch_checkarch(FAR const Elf32_Ehdr *ehdr) -{ - /* Make sure it's an ARM executable */ - - if (ehdr->e_machine != EM_ARM) - { - bdbg("Not for ARM: e_machine=%04x\n", ehdr->e_machine); - return -ENOEXEC; - } - - /* Make sure that 32-bit objects are supported */ - - if (ehdr->e_ident[EI_CLASS] != ELFCLASS32) - { - bdbg("Need 32-bit objects: e_ident[EI_CLASS]=%02x\n", ehdr->e_ident[EI_CLASS]); - return -ENOEXEC; - } - - /* Verify endian-ness */ - -#ifdef CONFIG_ENDIAN_BIG - if (ehdr->e_ident[EI_DATA] != ELFDATA2MSB) -#else - if (ehdr->e_ident[EI_DATA] != ELFDATA2LSB) -#endif - { - bdbg("Wrong endian-ness: e_ident[EI_DATA]=%02x\n", ehdr->e_ident[EI_DATA]); - return -ENOEXEC; - } - - /* TODO: Check ABI here. */ - return OK; -} - -/**************************************************************************** - * Name: arch_relocate and arch_relocateadd - * - * Description: - * Perform on architecture-specific ELF relocation. Every architecture - * that uses the ELF loader must provide this function. - * - * Input Parameters: - * rel - The relocation type - * sym - The ELF symbol structure containing the fully resolved value. - * addr - The address that requires the relocation. - * - * Returned Value: - * Zero (OK) if the relocation was successful. Otherwise, a negated errno - * value indicating the cause of the relocation failure. - * - ****************************************************************************/ - -int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, - uintptr_t addr) -{ - int32_t offset; - uint32_t upper_insn; - uint32_t lower_insn; - - switch (ELF32_R_TYPE(rel->r_info)) - { - case R_ARM_NONE: - { - /* No relocation */ - } - break; - - case R_ARM_PC24: - case R_ARM_CALL: - case R_ARM_JUMP24: - { - bvdbg("Performing PC24 [%d] link at addr %08lx [%08lx] to sym '%s' st_value=%08lx\n", - ELF32_R_TYPE(rel->r_info), (long)addr, (long)(*(uint32_t*)addr), - sym, (long)sym->st_value); - - offset = (*(uint32_t*)addr & 0x00ffffff) << 2; - if (offset & 0x02000000) - { - offset -= 0x04000000; - } - - offset += sym->st_value - addr; - if (offset & 3 || offset <= (int32_t) 0xfe000000 || offset >= (int32_t) 0x02000000) - { - bdbg(" ERROR: PC24 [%d] relocation out of range, offset=%08lx\n", - ELF32_R_TYPE(rel->r_info), offset); - - return -EINVAL; - } - - offset >>= 2; - - *(uint32_t*)addr &= 0xff000000; - *(uint32_t*)addr |= offset & 0x00ffffff; - } - break; - - case R_ARM_ABS32: - case R_ARM_TARGET1: /* New ABI: TARGET1 always treated as ABS32 */ - { - bvdbg("Performing ABS32 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", - (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value); - - *(uint32_t*)addr += sym->st_value; - } - break; - - case R_ARM_THM_CALL: - case R_ARM_THM_JUMP24: - { - uint32_t S; - uint32_t J1; - uint32_t J2; - - /* Thumb BL and B.W instructions. Encoding: - * - * upper_insn: - * - * 1 1 1 1 1 1 - * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 - * +----------+---+-------------------------------+--------------+ - * |1 1 1 |OP1| OP2 | | 32-Bit Instructions - * +----------+---+--+-----+----------------------+--------------+ - * |1 1 1 | 1 0| S | imm10 | BL Instruction - * +----------+------+-----+-------------------------------------+ - * - * lower_insn: - * - * 1 1 1 1 1 1 - * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 - * +---+---------------------------------------------------------+ - * |OP | | 32-Bit Instructions - * +---+--+---+---+---+------------------------------------------+ - * |1 1 |J1 | 1 |J2 | imm11 | BL Instruction - * +------+---+---+---+------------------------------------------+ - * - * The branch target is encoded in these bits: - * - * S = upper_insn[10] - * imm10 = upper_insn[0:9] - * imm11 = lower_insn[0:10] - * J1 = lower_insn[13] - * J2 = lower_insn[11] - */ - - upper_insn = (uint32_t)(*(uint16_t*)addr); - lower_insn = (uint32_t)(*(uint16_t*)(addr + 2)); - - bvdbg("Performing THM_JUMP24 [%d] link at addr=%08lx [%04x %04x] to sym=%p st_value=%08lx\n", - ELF32_R_TYPE(rel->r_info), (long)addr, (int)upper_insn, (int)lower_insn, - sym, (long)sym->st_value); - - /* Extract the 25-bit offset from the 32-bit instruction: - * - * offset[24] = S - * offset[23] = ~(J1 ^ S) - * offset[22] = ~(J2 ^ S)] - * offset[12:21] = imm10 - * offset[1:11] = imm11 - * offset[0] = 0 - */ - - S = (upper_insn >> 10) & 1; - J1 = (lower_insn >> 13) & 1; - J2 = (lower_insn >> 11) & 1; - - offset = (S << 24) | /* S - > offset[24] */ - ((~(J1 ^ S) & 1) << 23) | /* J1 -> offset[23] */ - ((~(J2 ^ S) & 1) << 22) | /* J2 -> offset[22] */ - ((upper_insn & 0x03ff) << 12) | /* imm10 -> offset[12:21] */ - ((lower_insn & 0x07ff) << 1); /* imm11 -> offset[1:11] */ - /* 0 -> offset[0] */ - - /* Sign extend */ - - if (offset & 0x01000000) - { - offset -= 0x02000000; - } - - /* And perform the relocation */ - - bvdbg(" S=%d J1=%d J2=%d offset=%08lx branch target=%08lx\n", - S, J1, J2, (long)offset, offset + sym->st_value - addr); - - offset += sym->st_value - addr; - - /* Is this a function symbol? If so, then the branch target must be - * an odd Thumb address - */ - - if (ELF32_ST_TYPE(sym->st_info) == STT_FUNC && (offset & 1) == 0) - { - bdbg(" ERROR: JUMP24 [%d] requires odd offset, offset=%08lx\n", - ELF32_R_TYPE(rel->r_info), offset); - - return -EINVAL; - } - - /* Check the range of the offset */ - - if (offset <= (int32_t)0xff000000 || offset >= (int32_t)0x01000000) - { - bdbg(" ERROR: JUMP24 [%d] relocation out of range, branch taget=%08lx\n", - ELF32_R_TYPE(rel->r_info), offset); - - return -EINVAL; - } - - /* Now, reconstruct the 32-bit instruction using the new, relocated - * branch target. - */ - - S = (offset >> 24) & 1; - J1 = S ^ (~(offset >> 23) & 1); - J2 = S ^ (~(offset >> 22) & 1); - - upper_insn = ((upper_insn & 0xf800) | (S << 10) | ((offset >> 12) & 0x03ff)); - *(uint16_t*)addr = (uint16_t)upper_insn; - - lower_insn = ((lower_insn & 0xd000) | (J1 << 13) | (J2 << 11) | ((offset >> 1) & 0x07ff)); - *(uint16_t*)(addr + 2) = (uint16_t)lower_insn; - - bvdbg(" S=%d J1=%d J2=%d insn [%04x %04x]\n", - S, J1, J2, (int)upper_insn, (int)lower_insn); - } - break; - - case R_ARM_V4BX: - { - bvdbg("Performing V4BX link at addr=%08lx [%08lx]\n", - (long)addr, (long)(*(uint32_t*)addr)); - - /* Preserve only Rm and the condition code */ - - *(uint32_t*)addr &= 0xf000000f; - - /* Change instruction to 'mov pc, Rm' */ - - *(uint32_t*)addr |= 0x01a0f000; - } - break; - - case R_ARM_PREL31: - { - bvdbg("Performing PREL31 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", - (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value); - - offset = *(uint32_t*)addr + sym->st_value - addr; - *(uint32_t*)addr = offset & 0x7fffffff; - } - break; - - case R_ARM_MOVW_ABS_NC: - case R_ARM_MOVT_ABS: - { - bvdbg("Performing MOVx_ABS [%d] link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n", - ELF32_R_TYPE(rel->r_info), (long)addr, (long)(*(uint32_t*)addr), - sym, (long)sym->st_value); - - offset = *(uint32_t*)addr; - offset = ((offset & 0xf0000) >> 4) | (offset & 0xfff); - offset = (offset ^ 0x8000) - 0x8000; - - offset += sym->st_value; - if (ELF32_R_TYPE(rel->r_info) == R_ARM_MOVT_ABS) - { - offset >>= 16; - } - - *(uint32_t*)addr &= 0xfff0f000; - *(uint32_t*)addr |= ((offset & 0xf000) << 4) | (offset & 0x0fff); - } - break; - - case R_ARM_THM_MOVW_ABS_NC: - case R_ARM_THM_MOVT_ABS: - { - /* Thumb BL and B.W instructions. Encoding: - * - * upper_insn: - * - * 1 1 1 1 1 1 - * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 - * +----------+---+-------------------------------+--------------+ - * |1 1 1 |OP1| OP2 | | 32-Bit Instructions - * +----------+---+--+-----+----------------------+--------------+ - * |1 1 1 | 1 0| i | 1 0 1 1 0 0 | imm4 | MOVT Instruction - * +----------+------+-----+----------------------+--------------+ - * - * lower_insn: - * - * 1 1 1 1 1 1 - * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 - * +---+---------------------------------------------------------+ - * |OP | | 32-Bit Instructions - * +---+----------+--------------+-------------------------------+ - * |0 | imm3 | Rd | imm8 | MOVT Instruction - * +---+----------+--------------+-------------------------------+ - * - * The 16-bit immediate value is encoded in these bits: - * - * i = imm16[11] = upper_insn[10] - * imm4 = imm16[12:15] = upper_insn[3:0] - * imm3 = imm16[8:10] = lower_insn[14:12] - * imm8 = imm16[0:7] = lower_insn[7:0] - */ - - upper_insn = (uint32_t)(*(uint16_t*)addr); - lower_insn = (uint32_t)(*(uint16_t*)(addr + 2)); - - bvdbg("Performing THM_MOVx [%d] link at addr=%08lx [%04x %04x] to sym=%p st_value=%08lx\n", - ELF32_R_TYPE(rel->r_info), (long)addr, (int)upper_insn, (int)lower_insn, - sym, (long)sym->st_value); - - /* Extract the 16-bit offset from the 32-bit instruction */ - - offset = ((upper_insn & 0x000f) << 12) | /* imm4 -> imm16[8:10] */ - ((upper_insn & 0x0400) << 1) | /* i -> imm16[11] */ - ((lower_insn & 0x7000) >> 4) | /* imm3 -> imm16[8:10] */ - (lower_insn & 0x00ff); /* imm8 -> imm16[0:7] */ - - /* Sign extend */ - - offset = (offset ^ 0x8000) - 0x8000; - - /* And perform the relocation */ - - bvdbg(" offset=%08lx branch target=%08lx\n", - (long)offset, offset + sym->st_value); - - offset += sym->st_value; - - /* Update the immediate value in the instruction. For MOVW we want the bottom - * 16-bits; for MOVT we want the top 16-bits. - */ - - if (ELF32_R_TYPE(rel->r_info) == R_ARM_THM_MOVT_ABS) - { - offset >>= 16; - } - - upper_insn = ((upper_insn & 0xfbf0) | ((offset & 0xf000) >> 12) | ((offset & 0x0800) >> 1)); - *(uint16_t*)addr = (uint16_t)upper_insn; - - lower_insn = ((lower_insn & 0x8f00) | ((offset & 0x0700) << 4) | (offset & 0x00ff)); - *(uint16_t*)(addr + 2) = (uint16_t)lower_insn; - - bvdbg(" insn [%04x %04x]\n", - (int)upper_insn, (int)lower_insn); - } - break; - - default: - bdbg("Unsupported relocation: %d\n", ELF32_R_TYPE(rel->r_info)); - return -EINVAL; - } - - return OK; -} - -int arch_relocateadd(FAR const Elf32_Rela *rel, FAR const Elf32_Sym *sym, - uintptr_t addr) -{ - bdbg("RELA relocation not supported\n"); - return -ENOSYS; -} - diff --git a/nuttx/arch/arm/src/armv7-m/up_memcpy.S b/nuttx/arch/arm/src/armv7-m/up_memcpy.S deleted file mode 100644 index a154cab614..0000000000 --- a/nuttx/arch/arm/src/armv7-m/up_memcpy.S +++ /dev/null @@ -1,416 +0,0 @@ -/************************************************************************************ - * nuttx/arch/arm/src/armv7-m/up_memcpy.S - * - * armv7m-optimised memcpy, contributed by Mike Smith. Apparently in the public - * domain and is re-released here under the modified BSD license: - * - * Obtained via a posting on the Stellaris forum: - * http://e2e.ti.com/support/microcontrollers/\ - * stellaris_arm_cortex-m3_microcontroller/f/473/t/44360.aspx - * - * Posted by rocksoft on Jul 24, 2008 10:19 AM - * - * Hi, - * - * I recently finished a "memcpy" replacement and thought it might be useful for - * others... - * - * I've put some instructions and the code here: - * - * http://www.rock-software.net/downloads/memcpy/ - * - * Hope it works for you as well as it did for me. - * - * Liam. - * - * 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. - * - ************************************************************************************/ - -/************************************************************************************ - * Global Symbols - ************************************************************************************/ - - .global memcpy - - .syntax unified - .thumb - .cpu cortex-m3 - .file "up_memcpy.S" - -/************************************************************************************ - * .text - ************************************************************************************/ - - .text - -/************************************************************************************ - * Private Constant Data - ************************************************************************************/ - -/* We have 16 possible alignment combinations of src and dst, this jump table - * directs the copy operation - * - * Bits: Src=00, Dst=00 - Long to Long copy - * Bits: Src=00, Dst=01 - Long to Byte before half word - * Bits: Src=00, Dst=10 - Long to Half word - * Bits: Src=00, Dst=11 - Long to Byte before long word - * Bits: Src=01, Dst=00 - Byte before half word to long - * Bits: Src=01, Dst=01 - Byte before half word to byte before half word - - * Same alignment - * Bits: Src=01, Dst=10 - Byte before half word to half word - * Bits: Src=01, Dst=11 - Byte before half word to byte before long word - * Bits: Src=10, Dst=00 - Half word to long word - * Bits: Src=10, Dst=01 - Half word to byte before half word - * Bits: Src=10, Dst=10 - Half word to half word - Same Alignment - * Bits: Src=10, Dst=11 - Half word to byte before long word - * Bits: Src=11, Dst=00 - Byte before long word to long word - * Bits: Src=11, Dst=01 - Byte before long word to byte before half word - * Bits: Src=11, Dst=11 - Byte before long word to half word - * Bits: Src=11, Dst=11 - Byte before long word to Byte before long word - - * Same alignment - */ - -MEM_DataCopyTable: - .byte (MEM_DataCopy0 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy1 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy2 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy3 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy4 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy5 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy6 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy7 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy8 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy9 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy10 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy11 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy12 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy13 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy14 - MEM_DataCopyJump) >> 1 - .byte (MEM_DataCopy15 - MEM_DataCopyJump) >> 1 - - .align 2 - -MEM_LongCopyTable: - .byte (MEM_LongCopyEnd - MEM_LongCopyJump) >> 1 /* 0 bytes left */ - .byte 0 /* 4 bytes left */ - .byte (1 * 10) >> 1 /* 8 bytes left */ - .byte (2 * 10) >> 1 /* 12 bytes left */ - .byte (3 * 10) >> 1 /* 16 bytes left */ - .byte (4 * 10) >> 1 /* 20 bytes left */ - .byte (5 * 10) >> 1 /* 24 bytes left */ - .byte (6 * 10) >> 1 /* 28 bytes left */ - .byte (7 * 10) >> 1 /* 32 bytes left */ - .byte (8 * 10) >> 1 /* 36 bytes left */ - - .align 2 - -/************************************************************************************ - * Public Functions - ************************************************************************************/ -/************************************************************************************ - * Name: memcpy - * - * Description: - * Optimised "general" copy routine - * - * Input Parameters: - * r0 = destination, r1 = source, r2 = length - * - ************************************************************************************/ - - .thumb_func -memcpy: - push {r14} - - /* This allows the inner workings to "assume" a minimum amount of bytes */ - /* Quickly check for very short copies */ - - cmp r2, #4 - blt MEM_DataCopyBytes - - and r14, r0, #3 /* Get destination alignment bits */ - bfi r14, r1, #2, #2 /* Get source alignment bits */ - ldr r3, =MEM_DataCopyTable /* Jump table base */ - tbb [r3, r14] /* Perform jump on src/dst alignment bits */ -MEM_DataCopyJump: - - .align 4 - -/* Bits: Src=01, Dst=01 - Byte before half word to byte before half word - Same alignment - * 3 bytes to read for long word aligning - */ - -MEM_DataCopy5: - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - sub r2, r2, #0x01 - -/* Bits: Src=10, Dst=10 - Half word to half word - Same Alignment - * 2 bytes to read for long word aligning - */ - -MEM_DataCopy10: - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - sub r2, r2, #0x01 - -/* Bits: Src=11, Dst=11 - Byte before long word to Byte before long word - Same alignment - * 1 bytes to read for long word aligning - */ - -MEM_DataCopy15: - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - sub r2, r2, #0x01 - -/* Bits: Src=00, Dst=00 - Long to Long copy */ - -MEM_DataCopy0: - /* Save regs that may be used by memcpy */ - - push {r4-r12} - - /* Check for short word-aligned copy */ - - cmp r2, #0x28 - blt MEM_DataCopy0_2 - - /* Bulk copy loop */ - -MEM_DataCopy0_1: - ldmia r1!, {r3-r12} - stmia r0!, {r3-r12} - sub r2, r2, #0x28 - cmp r2, #0x28 - bge MEM_DataCopy0_1 - - /* Copy remaining long words */ - -MEM_DataCopy0_2: - /* Copy remaining long words */ - - ldr r14, =MEM_LongCopyTable - lsr r11, r2, #0x02 - tbb [r14, r11] - - /* longword copy branch table anchor */ - -MEM_LongCopyJump: - ldr.w r3, [r1], #0x04 /* 4 bytes remain */ - str.w r3, [r0], #0x04 - b MEM_LongCopyEnd - ldmia.w r1!, {r3-r4} /* 8 bytes remain */ - stmia.w r0!, {r3-r4} - b MEM_LongCopyEnd - ldmia.w r1!, {r3-r5} /* 12 bytes remain */ - stmia.w r0!, {r3-r5} - b MEM_LongCopyEnd - ldmia.w r1!, {r3-r6} /* 16 bytes remain */ - stmia.w r0!, {r3-r6} - b MEM_LongCopyEnd - ldmia.w r1!, {r3-r7} /* 20 bytes remain */ - stmia.w r0!, {r3-r7} - b MEM_LongCopyEnd - ldmia.w r1!, {r3-r8} /* 24 bytes remain */ - stmia.w r0!, {r3-r8} - b MEM_LongCopyEnd - ldmia.w r1!, {r3-r9} /* 28 bytes remain */ - stmia.w r0!, {r3-r9} - b MEM_LongCopyEnd - ldmia.w r1!, {r3-r10} /* 32 bytes remain */ - stmia.w r0!, {r3-r10} - b MEM_LongCopyEnd - ldmia.w r1!, {r3-r11} /* 36 bytes remain */ - stmia.w r0!, {r3-r11} - -MEM_LongCopyEnd: - pop {r4-r12} - and r2, r2, #0x03 /* All the longs have been copied */ - - /* Deal with up to 3 remaining bytes */ - -MEM_DataCopyBytes: - /* Deal with up to 3 remaining bytes */ - - cmp r2, #0x00 - it eq - popeq {pc} - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - subs r2, r2, #0x01 - it eq - popeq {pc} - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - subs r2, r2, #0x01 - it eq - popeq {pc} - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - pop {pc} - - .align 4 - -/* Bits: Src=01, Dst=11 - Byte before half word to byte before long word - * 3 bytes to read for long word aligning the source - */ - -MEM_DataCopy7: - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - sub r2, r2, #0x01 - -/* Bits: Src=10, Dst=00 - Half word to long word - * 2 bytes to read for long word aligning the source - */ - -MEM_DataCopy8: - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - sub r2, r2, #0x01 - -/* Bits: Src=11, Dst=01 - Byte before long word to byte before half word - * 1 byte to read for long word aligning the source - */ - -MEM_DataCopy13: - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - sub r2, r2, #0x01 - -/* Bits: Src=00, Dst=10 - Long to Half word */ - -MEM_DataCopy2: - cmp r2, #0x28 - blt MEM_DataCopy2_1 - - /* Save regs */ - - push {r4-r12} - - /* Bulk copy loop */ - -MEM_DataCopy2_2: - ldmia r1!, {r3-r12} - - strh r3, [r0], #0x02 - - lsr r3, r3, #0x10 - bfi r3, r4, #0x10, #0x10 - lsr r4, r4, #0x10 - bfi r4, r5, #0x10, #0x10 - lsr r5, r5, #0x10 - bfi r5, r6, #0x10, #0x10 - lsr r6, r6, #0x10 - bfi r6, r7, #0x10, #0x10 - lsr r7, r7, #0x10 - bfi r7, r8, #0x10, #0x10 - lsr r8, r8, #0x10 - bfi r8, r9, #0x10, #0x10 - lsr r9, r9, #0x10 - bfi r9, r10, #0x10, #0x10 - lsr r10, r10, #0x10 - bfi r10, r11, #0x10, #0x10 - lsr r11, r11, #0x10 - bfi r11, r12, #0x10, #0x10 - stmia r0!, {r3-r11} - lsr r12, r12, #0x10 - strh r12, [r0], #0x02 - - sub r2, r2, #0x28 - cmp r2, #0x28 - bge MEM_DataCopy2_2 - pop {r4-r12} - -MEM_DataCopy2_1: /* Read longs and write 2 x half words */ - cmp r2, #4 - blt MEM_DataCopyBytes - ldr r3, [r1], #0x04 - strh r3, [r0], #0x02 - lsr r3, r3, #0x10 - strh r3, [r0], #0x02 - sub r2, r2, #0x04 - b MEM_DataCopy2 - -/* Bits: Src=01, Dst=00 - Byte before half word to long - * Bits: Src=01, Dst=10 - Byte before half word to half word - * 3 bytes to read for long word aligning the source - */ - -MEM_DataCopy4: -MEM_DataCopy6: - /* Read B and write B */ - - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - sub r2, r2, #0x01 - -/* Bits: Src=10, Dst=01 - Half word to byte before half word - * Bits: Src=10, Dst=11 - Half word to byte before long word - * 2 bytes to read for long word aligning the source - */ - -MEM_DataCopy9: -MEM_DataCopy11: - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - sub r2, r2, #0x01 - -/* Bits: Src=11, Dst=00 -chm Byte before long word to long word - * Bits: Src=11, Dst=11 - Byte before long word to half word - * 1 byte to read for long word aligning the source - */ - -MEM_DataCopy12: -MEM_DataCopy14: - /* Read B and write B */ - - ldrb r3, [r1], #0x01 - strb r3, [r0], #0x01 - sub r2, r2, #0x01 - -/* Bits: Src=00, Dst=01 - Long to Byte before half word - * Bits: Src=00, Dst=11 - Long to Byte before long word - */ - -MEM_DataCopy1: /* Read longs, write B->H->B */ -MEM_DataCopy3: - cmp r2, #4 - blt MEM_DataCopyBytes - ldr r3, [r1], #0x04 - strb r3, [r0], #0x01 - lsr r3, r3, #0x08 - strh r3, [r0], #0x02 - lsr r3, r3, #0x10 - strb r3, [r0], #0x01 - sub r2, r2, #0x04 - b MEM_DataCopy3 - - .size memcpy, .-memcpy - .end diff --git a/nuttx/arch/arm/src/common/arm-elf.h b/nuttx/arch/arm/src/common/arm-elf.h deleted file mode 100644 index fac387b110..0000000000 --- a/nuttx/arch/arm/src/common/arm-elf.h +++ /dev/null @@ -1,53 +0,0 @@ -/**************************************************************************** - * arch/arm/src/common/arm-elf.h - * - * 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. - * - ****************************************************************************/ - -#ifndef __ARCH_ARM_SRC_ARM_ELF_H -#define __ARCH_ARM_SRC_ARM_ELF_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -#endif /* __ARCH_ARM_SRC_ARM_ELF_H */ diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c deleted file mode 100644 index ea1e7b0ca8..0000000000 --- a/nuttx/binfmt/elf.c +++ /dev/null @@ -1,302 +0,0 @@ -/**************************************************************************** - * binfmt/elf.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#ifdef CONFIG_ELF - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be - * defined or CONFIG_ELF_DUMPBUFFER does nothing. - */ - -#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT) -# undef CONFIG_ELF_DUMPBUFFER -#endif - -#ifndef CONFIG_ELF_STACKSIZE -# define CONFIG_ELF_STACKSIZE 2048 -#endif - -#ifdef CONFIG_ELF_DUMPBUFFER -# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n) -#else -# define elf_dumpbuffer(m,b,n) -#endif - -#ifndef MIN -# define MIN(a,b) (a < b ? a : b) -#endif - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -static int elf_loadbinary(FAR struct binary_s *binp); -#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT) -static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo); -#endif - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static struct binfmt_s g_elfbinfmt = -{ - NULL, /* next */ - elf_loadbinary, /* load */ -}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_dumploadinfo - ****************************************************************************/ - -#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT) -static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo) -{ - int i; - - bdbg("LOAD_INFO:\n"); - bdbg(" elfalloc: %08lx\n", (long)loadinfo->elfalloc); - bdbg(" elfsize: %ld\n", (long)loadinfo->elfsize); - bdbg(" filelen: %ld\n", (long)loadinfo->filelen); -#ifdef CONFIG_BINFMT_CONSTRUCTORS - bdbg(" ctoralloc: %08lx\n", (long)loadinfo->ctoralloc); - bdbg(" ctors: %08lx\n", (long)loadinfo->ctors); - bdbg(" nctors: %d\n", loadinfo->nctors); - bdbg(" dtoralloc: %08lx\n", (long)loadinfo->dtoralloc); - bdbg(" dtors: %08lx\n", (long)loadinfo->dtors); - bdbg(" ndtors: %d\n", loadinfo->ndtors); -#endif - bdbg(" filfd: %d\n", loadinfo->filfd); - bdbg(" symtabidx: %d\n", loadinfo->symtabidx); - bdbg(" strtabidx: %d\n", loadinfo->strtabidx); - - bdbg("ELF Header:\n"); - bdbg(" e_ident: %02x %02x %02x %02x\n", - loadinfo->ehdr.e_ident[0], loadinfo->ehdr.e_ident[1], - loadinfo->ehdr.e_ident[2], loadinfo->ehdr.e_ident[3]); - bdbg(" e_type: %04x\n", loadinfo->ehdr.e_type); - bdbg(" e_machine: %04x\n", loadinfo->ehdr.e_machine); - bdbg(" e_version: %08x\n", loadinfo->ehdr.e_version); - bdbg(" e_entry: %08lx\n", (long)loadinfo->ehdr.e_entry); - bdbg(" e_phoff: %d\n", loadinfo->ehdr.e_phoff); - bdbg(" e_shoff: %d\n", loadinfo->ehdr.e_shoff); - bdbg(" e_flags: %08x\n" , loadinfo->ehdr.e_flags); - bdbg(" e_ehsize: %d\n", loadinfo->ehdr.e_ehsize); - bdbg(" e_phentsize: %d\n", loadinfo->ehdr.e_phentsize); - bdbg(" e_phnum: %d\n", loadinfo->ehdr.e_phnum); - bdbg(" e_shentsize: %d\n", loadinfo->ehdr.e_shentsize); - bdbg(" e_shnum: %d\n", loadinfo->ehdr.e_shnum); - bdbg(" e_shstrndx: %d\n", loadinfo->ehdr.e_shstrndx); - - if (loadinfo->shdr && loadinfo->ehdr.e_shnum > 0) - { - for (i = 0; i < loadinfo->ehdr.e_shnum; i++) - { - FAR Elf32_Shdr *shdr = &loadinfo->shdr[i]; - bdbg("Sections %d:\n", i); - bdbg(" sh_name: %08x\n", shdr->sh_name); - bdbg(" sh_type: %08x\n", shdr->sh_type); - bdbg(" sh_flags: %08x\n", shdr->sh_flags); - bdbg(" sh_addr: %08x\n", shdr->sh_addr); - bdbg(" sh_offset: %d\n", shdr->sh_offset); - bdbg(" sh_size: %d\n", shdr->sh_size); - bdbg(" sh_link: %d\n", shdr->sh_link); - bdbg(" sh_info: %d\n", shdr->sh_info); - bdbg(" sh_addralign: %d\n", shdr->sh_addralign); - bdbg(" sh_entsize: %d\n", shdr->sh_entsize); - } - } -} -#else -# define elf_dumploadinfo(i) -#endif - -/**************************************************************************** - * Name: elf_loadbinary - * - * Description: - * Verify that the file is an ELF binary and, if so, load the ELF - * binary into memory - * - ****************************************************************************/ - -static int elf_loadbinary(struct binary_s *binp) -{ - struct elf_loadinfo_s loadinfo; /* Contains globals for libelf */ - int ret; - - bvdbg("Loading file: %s\n", binp->filename); - - /* Initialize the xflat library to load the program binary. */ - - ret = elf_init(binp->filename, &loadinfo); - elf_dumploadinfo(&loadinfo); - if (ret != 0) - { - bdbg("Failed to initialize for load of ELF program: %d\n", ret); - goto errout; - } - - /* Load the program binary */ - - ret = elf_load(&loadinfo); - elf_dumploadinfo(&loadinfo); - if (ret != 0) - { - bdbg("Failed to load ELF program binary: %d\n", ret); - goto errout_with_init; - } - - /* Bind the program to the exported symbol table */ - - ret = elf_bind(&loadinfo, binp->exports, binp->nexports); - if (ret != 0) - { - bdbg("Failed to bind symbols program binary: %d\n", ret); - goto errout_with_load; - } - - /* Return the load information */ - - binp->entrypt = (main_t)(loadinfo.elfalloc + loadinfo.ehdr.e_entry); - binp->alloc[0] = (FAR void *)loadinfo.elfalloc; - binp->stacksize = CONFIG_ELF_STACKSIZE; - -#ifdef CONFIG_BINFMT_CONSTRUCTORS - /* Save information about constructors. NOTE: desctructors are not - * yet supported. - */ - - binp->alloc[1] = loadinfo.ctoralloc; - binp->ctors = loadinfo.ctors; - binp->nctors = loadinfo.nctors; - - binp->alloc[2] = loadinfo.dtoralloc; - binp->dtors = loadinfo.dtors; - binp->ndtors = loadinfo.ndtors; -#endif - - elf_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt, - MIN(loadinfo.allocsize - loadinfo.ehdr.e_entry, 512)); - - elf_uninit(&loadinfo); - return OK; - -errout_with_load: - elf_unload(&loadinfo); -errout_with_init: - elf_uninit(&loadinfo); -errout: - return ret; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_initialize - * - * Description: - * ELF support is built unconditionally. However, it order to - * use this binary format, this function must be called during system - * format in order to register the ELF binary format. - * - * Returned Value: - * This is a NuttX internal function so it follows the convention that - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_initialize(void) -{ - int ret; - - /* Register ourselves as a binfmt loader */ - - bvdbg("Registering ELF\n"); - - ret = register_binfmt(&g_elfbinfmt); - if (ret != 0) - { - bdbg("Failed to register binfmt: %d\n", ret); - } - - return ret; -} - -/**************************************************************************** - * Name: elf_uninitialize - * - * Description: - * Unregister the ELF binary loader - * - * Returned Value: - * None - * - ****************************************************************************/ - -void elf_uninitialize(void) -{ - unregister_binfmt(&g_elfbinfmt); -} - -#endif /* CONFIG_ELF */ - diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig deleted file mode 100644 index f6f579276c..0000000000 --- a/nuttx/binfmt/libelf/Kconfig +++ /dev/null @@ -1,40 +0,0 @@ -# -# For a description of the syntax of this configuration file, -# see misc/tools/kconfig-language.txt. -# - -config ELF_ALIGN_LOG2 - int "Log2 Section Alignment" - default 2 - ---help--- - Align all sections to this Log2 value: 0->1, 1->2, 2->4, etc. - -config ELF_STACKSIZE - int "ELF Stack Size" - default 2048 - ---help--- - This is the default stack size that will will be used when starting ELF binaries. - -config ELF_BUFFERSIZE - int "ELF I/O Buffer Size" - default 128 - ---help--- - This is an I/O buffer that is used to access the ELF file. Variable length items - will need to be read (such as symbol names). This is really just this initial - size of the buffer; it will be reallocated as necessary to hold large symbol - names). Default: 128 - -config ELF_BUFFERINCR - int "ELF I/O Buffer Realloc Increment" - default 32 - ---help--- - This is an I/O buffer that is used to access the ELF file. Variable length items - will need to be read (such as symbol names). This value specifies the size - increment to use each time the buffer is reallocated. Default: 32 - -config ELF_DUMPBUFFER - bool "Dump ELF buffers" - default n - depends on DEBUG && DEBUG_VERBOSE - ---help--- - Dump various ELF buffers for debug purposes diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs deleted file mode 100644 index c8857c3f74..0000000000 --- a/nuttx/binfmt/libelf/Make.defs +++ /dev/null @@ -1,58 +0,0 @@ -############################################################################ -# binfmt/libelf/Make.defs -# -# 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_ELF),y) - -# ELF application interfaces - -BINFMT_CSRCS += elf.c - -# ELF library - -BINFMT_CSRCS += libelf_bind.c libelf_init.c libelf_iobuffer.c libelf_load.c \ - libelf_read.c libelf_sections.c libelf_symbols.c libelf_uninit.c \ - libelf_unload.c libelf_verify.c - -ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) -BINFMT_CSRCS += libelf_ctors.c libelf_dtors.c -endif - -# Hook the libelf subdirectory into the build - -VPATH += libelf -SUBDIRS += libelf -DEPPATH += --dep-path libelf - -endif diff --git a/nuttx/binfmt/libelf/gnu-elf.ld b/nuttx/binfmt/libelf/gnu-elf.ld deleted file mode 100644 index b2a3dc1131..0000000000 --- a/nuttx/binfmt/libelf/gnu-elf.ld +++ /dev/null @@ -1,129 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/gnu-elf.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. - * - ****************************************************************************/ - -SECTIONS -{ - .text 0x00000000 : - { - _stext = . ; - *(.text) - *(.text.*) - *(.gnu.warning) - *(.stub) - *(.glue_7) - *(.glue_7t) - *(.jcr) - - /* C++ support: The .init and .fini sections contain specific logic - * to manage static constructors and destructors. - */ - - *(.gnu.linkonce.t.*) - *(.init) /* Old ABI */ - *(.fini) /* Old ABI */ - _etext = . ; - } - - .rodata : - { - _srodata = . ; - *(.rodata) - *(.rodata1) - *(.rodata.*) - *(.gnu.linkonce.r*) - _erodata = . ; - } - - .data : - { - _sdata = . ; - *(.data) - *(.data1) - *(.data.*) - *(.gnu.linkonce.d*) - _edata = . ; - } - - /* 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. - */ - - .ctors : - { - _sctors = . ; - *(.ctors) /* Old ABI: Unallocated */ - *(.init_array) /* New ABI: Allocated */ - _edtors = . ; - } - - .dtors : - { - _sdtors = . ; - *(.dtors) /* Old ABI: Unallocated */ - *(.fini_array) /* New ABI: Allocated */ - _edtors = . ; - } - - .bss : - { - _sbss = . ; - *(.bss) - *(.bss.*) - *(.sbss) - *(.sbss.*) - *(.gnu.linkonce.b*) - *(COMMON) - _ebss = . ; - } - - /* 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/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h deleted file mode 100644 index 5b0be9ab02..0000000000 --- a/nuttx/binfmt/libelf/libelf.h +++ /dev/null @@ -1,258 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf.h - * - * 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. - * - ****************************************************************************/ - -#ifndef __BINFMT_LIBELF_LIBELF_H -#define __BINFMT_LIBELF_LIBELF_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_verifyheader - * - * Description: - * Given the header from a possible ELF executable, verify that it is - * an ELF executable. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_verifyheader(FAR const Elf32_Ehdr *header); - -/**************************************************************************** - * Name: elf_read - * - * Description: - * Read 'readsize' bytes from the object file at 'offset' - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer, - size_t readsize, off_t offset); - -/**************************************************************************** - * Name: elf_loadshdrs - * - * Description: - * Loads section headers into memory. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo); - -/**************************************************************************** - * Name: elf_findsection - * - * Description: - * A section by its name. - * - * Input Parameters: - * loadinfo - Load state information - * sectname - Name of the section to find - * - * Returned Value: - * On success, the index to the section is returned; A negated errno value - * is returned on failure. - * - ****************************************************************************/ - -int elf_findsection(FAR struct elf_loadinfo_s *loadinfo, - FAR const char *sectname); - -/**************************************************************************** - * Name: elf_findsymtab - * - * Description: - * Find the symbol table section. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_findsymtab(FAR struct elf_loadinfo_s *loadinfo); - -/**************************************************************************** - * Name: elf_readsym - * - * Description: - * Read the ELFT symbol structure at the specfied index into memory. - * - * Input Parameters: - * loadinfo - Load state information - * index - Symbol table index - * sym - Location to return the table entry - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index, - FAR Elf32_Sym *sym); - -/**************************************************************************** - * Name: elf_symvalue - * - * Description: - * Get the value of a symbol. The updated value of the symbol is returned - * in the st_value field of the symbol table entry. - * - * Input Parameters: - * loadinfo - Load state information - * sym - Symbol table entry (value might be undefined) - * exports - The symbol table to use for resolving undefined symbols. - * nexports - Number of symbols in the symbol table. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_symvalue(FAR struct elf_loadinfo_s *loadinfo, FAR Elf32_Sym *sym, - FAR const struct symtab_s *exports, int nexports); - -/**************************************************************************** - * Name: elf_freebuffers - * - * Description: - * Release all working buffers. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_freebuffers(FAR struct elf_loadinfo_s *loadinfo); - -/**************************************************************************** - * Name: elf_allocbuffer - * - * Description: - * Perform the initial allocation of the I/O buffer, if it has not already - * been allocated. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_allocbuffer(FAR struct elf_loadinfo_s *loadinfo); - -/**************************************************************************** - * Name: elf_reallocbuffer - * - * Description: - * Increase the size of I/O buffer by the specified buffer increment. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_reallocbuffer(FAR struct elf_loadinfo_s *loadinfo, size_t increment); - -/**************************************************************************** - * Name: elf_findctors - * - * Description: - * Find C++ static constructors. - * - * Input Parameters: - * loadinfo - Load state information - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -#ifdef CONFIG_BINFMT_CONSTRUCTORS -int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo); -#endif - -/**************************************************************************** - * Name: elf_loaddtors - * - * Description: - * Load pointers to static destructors into an in-memory array. - * - * Input Parameters: - * loadinfo - Load state information - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -#ifdef CONFIG_BINFMT_CONSTRUCTORS -int elf_loaddtors(FAR struct elf_loadinfo_s *loadinfo); -#endif - -#endif /* __BINFMT_LIBELF_LIBELF_H */ diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c deleted file mode 100644 index e35087b1de..0000000000 --- a/nuttx/binfmt/libelf/libelf_bind.c +++ /dev/null @@ -1,306 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf_bind.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include - -#include -#include - -#include "libelf.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be - * defined or CONFIG_ELF_DUMPBUFFER does nothing. - */ - -#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT) -# undef CONFIG_ELF_DUMPBUFFER -#endif - -#ifndef CONFIG_ELF_BUFFERSIZE -# define CONFIG_ELF_BUFFERSIZE 128 -#endif - -#ifdef CONFIG_ELF_DUMPBUFFER -# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n) -#else -# define elf_dumpbuffer(m,b,n) -#endif - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_readsym - * - * Description: - * Read the ELFT symbol structure at the specfied index into memory. - * - ****************************************************************************/ - -static inline int elf_readrel(FAR struct elf_loadinfo_s *loadinfo, - FAR const Elf32_Shdr *relsec, - int index, FAR Elf32_Rel *rel) -{ - off_t offset; - - /* Verify that the symbol table index lies within symbol table */ - - if (index < 0 || index > (relsec->sh_size / sizeof(Elf32_Rel))) - { - bdbg("Bad relocation symbol index: %d\n", index); - return -EINVAL; - } - - /* Get the file offset to the symbol table entry */ - - offset = relsec->sh_offset + sizeof(Elf32_Rel) * index; - - /* And, finally, read the symbol table entry into memory */ - - return elf_read(loadinfo, (FAR uint8_t*)rel, sizeof(Elf32_Rel), offset); -} - -/**************************************************************************** - * Name: elf_relocate and elf_relocateadd - * - * Description: - * Perform all relocations associated with a section. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx, - FAR const struct symtab_s *exports, int nexports) - -{ - FAR Elf32_Shdr *relsec = &loadinfo->shdr[relidx]; - FAR Elf32_Shdr *dstsec = &loadinfo->shdr[relsec->sh_info]; - Elf32_Rel rel; - Elf32_Sym sym; - uintptr_t addr; - int symidx; - int ret; - int i; - - /* Examine each relocation in the section. 'relsec' is the section - * containing the relations. 'dstsec' is the section containing the data - * to be relocated. - */ - - for (i = 0; i < relsec->sh_size / sizeof(Elf32_Rel); i++) - { - /* Read the relocation entry into memory */ - - ret = elf_readrel(loadinfo, relsec, i, &rel); - if (ret < 0) - { - bdbg("Section %d reloc %d: Failed to read relocation entry: %d\n", - relidx, i, ret); - return ret; - } - - /* Get the symbol table index for the relocation. This is contained - * in a bit-field within the r_info element. - */ - - symidx = ELF32_R_SYM(rel.r_info); - - /* Read the symbol table entry into memory */ - - ret = elf_readsym(loadinfo, symidx, &sym); - if (ret < 0) - { - bdbg("Section %d reloc %d: Failed to read symbol[%d]: %d\n", - relidx, i, symidx, ret); - return ret; - } - - /* Get the value of the symbol (in sym.st_value) */ - - ret = elf_symvalue(loadinfo, &sym, exports, nexports); - if (ret < 0) - { - bdbg("Section %d reloc %d: Failed to get value of symbol[%d]: %d\n", - relidx, i, symidx, ret); - return ret; - } - - /* Calculate the relocation address */ - - if (rel.r_offset < 0 || rel.r_offset > dstsec->sh_size - sizeof(uint32_t)) - { - bdbg("Section %d reloc %d: Relocation address out of range, offset %d size %d\n", - relidx, i, rel.r_offset, dstsec->sh_size); - return -EINVAL; - } - - addr = dstsec->sh_addr + rel.r_offset; - - /* Now perform the architecture-specific relocation */ - - ret = arch_relocate(&rel, &sym, addr); - if (ret < 0) - { - bdbg("Section %d reloc %d: Relocation failed: %d\n", ret); - return ret; - } - } - - return OK; -} - -static int elf_relocateadd(FAR struct elf_loadinfo_s *loadinfo, int relidx, - FAR const struct symtab_s *exports, int nexports) -{ - bdbg("Not implemented\n"); - return -ENOSYS; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_bind - * - * Description: - * Bind the imported symbol names in the loaded module described by - * 'loadinfo' using the exported symbol values provided by 'symtab'. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_bind(FAR struct elf_loadinfo_s *loadinfo, - FAR const struct symtab_s *exports, int nexports) -{ - int ret; - int i; - - /* Find the symbol and string tables */ - - ret = elf_findsymtab(loadinfo); - if (ret < 0) - { - return ret; - } - - /* Allocate an I/O buffer. This buffer is used by elf_symname() to - * accumulate the variable length symbol name. - */ - - ret = elf_allocbuffer(loadinfo); - if (ret < 0) - { - bdbg("elf_allocbuffer failed: %d\n", ret); - return -ENOMEM; - } - - /* Process relocations in every allocated section */ - - for (i = 1; i < loadinfo->ehdr.e_shnum; i++) - { - /* Get the index to the relocation section */ - - int infosec = loadinfo->shdr[i].sh_info; - if (infosec >= loadinfo->ehdr.e_shnum) - { - continue; - } - - /* Make sure that the section is allocated. We can't relocated - * sections that were not loaded into memory. - */ - - if ((loadinfo->shdr[infosec].sh_flags & SHF_ALLOC) == 0) - { - continue; - } - - /* Process the relocations by type */ - - if (loadinfo->shdr[i].sh_type == SHT_REL) - { - ret = elf_relocate(loadinfo, i, exports, nexports); - } - else if (loadinfo->shdr[i].sh_type == SHT_RELA) - { - ret = elf_relocateadd(loadinfo, i, exports, nexports); - } - - if (ret < 0) - { - break; - } - } - - /* Flush the instruction cache before starting the newly loaded module */ - -#ifdef CONFIG_ELF_ICACHE - arch_flushicache((FAR void*)loadinfo->elfalloc, loadinfo->elfsize); -#endif - - return ret; -} - diff --git a/nuttx/binfmt/libelf/libelf_ctors.c b/nuttx/binfmt/libelf/libelf_ctors.c deleted file mode 100644 index 20f1256e2e..0000000000 --- a/nuttx/binfmt/libelf/libelf_ctors.c +++ /dev/null @@ -1,215 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf_ctors.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include -#include - -#include "libelf.h" - -#ifdef CONFIG_BINFMT_CONSTRUCTORS - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_loadctors - * - * Description: - * Load pointers to static constructors into an in-memory array. - * - * Input Parameters: - * loadinfo - Load state information - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo) -{ - FAR Elf32_Shdr *shdr; - size_t ctorsize; - int ctoridx; - int ret; - int i; - - DEBUGASSERT(loadinfo->ctors == NULL); - - /* Allocate an I/O buffer if necessary. This buffer is used by - * elf_sectname() to accumulate the variable length symbol name. - */ - - ret = elf_allocbuffer(loadinfo); - if (ret < 0) - { - bdbg("elf_allocbuffer failed: %d\n", ret); - return -ENOMEM; - } - - /* Find the index to the section named ".ctors." NOTE: On old ABI system, - * .ctors is the name of the section containing the list of constructors; - * On newer systems, the similar section is called .init_array. It is - * expected that the linker script will force the section name to be ".ctors" - * in either case. - */ - - ctoridx = elf_findsection(loadinfo, ".ctors"); - if (ctoridx < 0) - { - /* This may not be a failure. -ENOENT indicates that the file has no - * static constructor section. - */ - - bvdbg("elf_findsection .ctors section failed: %d\n", ctoridx); - return ret == -ENOENT ? OK : ret; - } - - /* Now we can get a pointer to the .ctor section in the section header - * table. - */ - - shdr = &loadinfo->shdr[ctoridx]; - - /* Get the size of the .ctor section and the number of constructors that - * will need to be called. - */ - - ctorsize = shdr->sh_size; - loadinfo->nctors = ctorsize / sizeof(binfmt_ctor_t); - - bvdbg("ctoridx=%d ctorsize=%d sizeof(binfmt_ctor_t)=%d nctors=%d\n", - ctoridx, ctorsize, sizeof(binfmt_ctor_t), loadinfo->nctors); - - /* Check if there are any constructors. It is not an error if there - * are none. - */ - - if (loadinfo->nctors > 0) - { - /* Check an assumption that we made above */ - - DEBUGASSERT(shdr->sh_size == loadinfo->nctors * sizeof(binfmt_ctor_t)); - - /* In the old ABI, the .ctors section is not allocated. In that case, - * we need to allocate memory to hold the .ctors and then copy the - * from the file into the allocated memory. - * - * SHF_ALLOC indicates that the section requires memory during - * execution. - */ - - if ((shdr->sh_flags & SHF_ALLOC) == 0) - { - /* Allocate memory to hold a copy of the .ctor section */ - - loadinfo->ctoralloc = (binfmt_ctor_t*)kmalloc(ctorsize); - if (!loadinfo->ctoralloc) - { - bdbg("Failed to allocate memory for .ctors\n"); - return -ENOMEM; - } - - loadinfo->ctors = (binfmt_ctor_t *)loadinfo->ctoralloc; - - /* Read the section header table into memory */ - - ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->ctors, ctorsize, - shdr->sh_offset); - if (ret < 0) - { - bdbg("Failed to allocate .ctors: %d\n", ret); - return ret; - } - - /* Fix up all of the .ctor addresses. Since the addresses - * do not lie in allocated memory, there will be no relocation - * section for them. - */ - - for (i = 0; i < loadinfo->nctors; i++) - { - FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->ctors)[i]); - - bvdbg("ctor %d: %08lx + %08lx = %08lx\n", - i, *ptr, loadinfo->elfalloc, *ptr + loadinfo->elfalloc); - - *ptr += loadinfo->elfalloc; - } - } - else - { - - /* Save the address of the .ctors (actually, .init_array) where it was - * loaded into memory. Since the .ctors lie in allocated memory, they - * will be relocated via the normal mechanism. - */ - - loadinfo->ctors = (binfmt_ctor_t*)shdr->sh_addr; - } - } - - return OK; -} - -#endif /* CONFIG_BINFMT_CONSTRUCTORS */ diff --git a/nuttx/binfmt/libelf/libelf_dtors.c b/nuttx/binfmt/libelf/libelf_dtors.c deleted file mode 100644 index c0c73a3373..0000000000 --- a/nuttx/binfmt/libelf/libelf_dtors.c +++ /dev/null @@ -1,215 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf_dtors.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include -#include - -#include "libelf.h" - -#ifdef CONFIG_BINFMT_CONSTRUCTORS - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_loaddtors - * - * Description: - * Load pointers to static destructors into an in-memory array. - * - * Input Parameters: - * loadinfo - Load state information - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_loaddtors(FAR struct elf_loadinfo_s *loadinfo) -{ - FAR Elf32_Shdr *shdr; - size_t dtorsize; - int dtoridx; - int ret; - int i; - - DEBUGASSERT(loadinfo->dtors == NULL); - - /* Allocate an I/O buffer if necessary. This buffer is used by - * elf_sectname() to accumulate the variable length symbol name. - */ - - ret = elf_allocbuffer(loadinfo); - if (ret < 0) - { - bdbg("elf_allocbuffer failed: %d\n", ret); - return -ENOMEM; - } - - /* Find the index to the section named ".dtors." NOTE: On old ABI system, - * .dtors is the name of the section containing the list of destructors; - * On newer systems, the similar section is called .fini_array. It is - * expected that the linker script will force the section name to be ".dtors" - * in either case. - */ - - dtoridx = elf_findsection(loadinfo, ".dtors"); - if (dtoridx < 0) - { - /* This may not be a failure. -ENOENT indicates that the file has no - * static destructor section. - */ - - bvdbg("elf_findsection .dtors section failed: %d\n", dtoridx); - return ret == -ENOENT ? OK : ret; - } - - /* Now we can get a pointer to the .dtor section in the section header - * table. - */ - - shdr = &loadinfo->shdr[dtoridx]; - - /* Get the size of the .dtor section and the number of destructors that - * will need to be called. - */ - - dtorsize = shdr->sh_size; - loadinfo->ndtors = dtorsize / sizeof(binfmt_dtor_t); - - bvdbg("dtoridx=%d dtorsize=%d sizeof(binfmt_dtor_t)=%d ndtors=%d\n", - dtoridx, dtorsize, sizeof(binfmt_dtor_t), loadinfo->ndtors); - - /* Check if there are any destructors. It is not an error if there - * are none. - */ - - if (loadinfo->ndtors > 0) - { - /* Check an assumption that we made above */ - - DEBUGASSERT(shdr->sh_size == loadinfo->ndtors * sizeof(binfmt_dtor_t)); - - /* In the old ABI, the .dtors section is not allocated. In that case, - * we need to allocate memory to hold the .dtors and then copy the - * from the file into the allocated memory. - * - * SHF_ALLOC indicates that the section requires memory during - * execution. - */ - - if ((shdr->sh_flags & SHF_ALLOC) == 0) - { - /* Allocate memory to hold a copy of the .dtor section */ - - loadinfo->ctoralloc = (binfmt_dtor_t*)kmalloc(dtorsize); - if (!loadinfo->ctoralloc) - { - bdbg("Failed to allocate memory for .dtors\n"); - return -ENOMEM; - } - - loadinfo->dtors = (binfmt_dtor_t *)loadinfo->ctoralloc; - - /* Read the section header table into memory */ - - ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->dtors, dtorsize, - shdr->sh_offset); - if (ret < 0) - { - bdbg("Failed to allocate .dtors: %d\n", ret); - return ret; - } - - /* Fix up all of the .dtor addresses. Since the addresses - * do not lie in allocated memory, there will be no relocation - * section for them. - */ - - for (i = 0; i < loadinfo->ndtors; i++) - { - FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->dtors)[i]); - - bvdbg("dtor %d: %08lx + %08lx = %08lx\n", - i, *ptr, loadinfo->elfalloc, *ptr + loadinfo->elfalloc); - - *ptr += loadinfo->elfalloc; - } - } - else - { - - /* Save the address of the .dtors (actually, .init_array) where it was - * loaded into memory. Since the .dtors lie in allocated memory, they - * will be relocated via the normal mechanism. - */ - - loadinfo->dtors = (binfmt_dtor_t*)shdr->sh_addr; - } - } - - return OK; -} - -#endif /* CONFIG_BINFMT_CONSTRUCTORS */ diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c deleted file mode 100644 index fa4b7983cb..0000000000 --- a/nuttx/binfmt/libelf/libelf_init.c +++ /dev/null @@ -1,202 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf_init.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include -#include -#include -#include -#include -#include - -#include - -#include "libelf.h" - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be - * defined or CONFIG_ELF_DUMPBUFFER does nothing. - */ - -#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT) -# undef CONFIG_ELF_DUMPBUFFER -#endif - -#ifdef CONFIG_ELF_DUMPBUFFER -# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n) -#else -# define elf_dumpbuffer(m,b,n) -#endif - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_filelen - * - * Description: - * Get the size of the ELF file - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -static inline int elf_filelen(FAR struct elf_loadinfo_s *loadinfo, - FAR const char *filename) -{ - struct stat buf; - int ret; - - /* Get the file stats */ - - ret = stat(filename, &buf); - if (ret < 0) - { - int errval = errno; - bdbg("Failed to fstat file: %d\n", errval); - return -errval; - } - - /* Verify that it is a regular file */ - - if (!S_ISREG(buf.st_mode)) - { - bdbg("Not a regular file. mode: %d\n", buf.st_mode); - return -ENOENT; - } - - /* TODO: Verify that the file is readable. Not really important because - * we will detect this when we try to open the file read-only. - */ - - /* Return the size of the file in the loadinfo structure */ - - loadinfo->filelen = buf.st_size; - return OK; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_init - * - * Description: - * This function is called to configure the library to process an ELF - * program binary. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo) -{ - int ret; - - bvdbg("filename: %s loadinfo: %p\n", filename, loadinfo); - - /* Clear the load info structure */ - - memset(loadinfo, 0, sizeof(struct elf_loadinfo_s)); - - /* Get the length of the file. */ - - ret = elf_filelen(loadinfo, filename); - if (ret < 0) - { - bdbg("elf_filelen failed: %d\n", ret); - return ret; - } - - /* Open the binary file for reading (only) */ - - loadinfo->filfd = open(filename, O_RDONLY); - if (loadinfo->filfd < 0) - { - int errval = errno; - bdbg("Failed to open ELF binary %s: %d\n", filename, errval); - return -errval; - } - - /* Read the ELF ehdr from offset 0 */ - - ret = elf_read(loadinfo, (FAR uint8_t*)&loadinfo->ehdr, sizeof(Elf32_Ehdr), 0); - if (ret < 0) - { - bdbg("Failed to read ELF header: %d\n", ret); - return ret; - } - - elf_dumpbuffer("ELF header", (FAR const uint8_t*)&loadinfo->ehdr, sizeof(Elf32_Ehdr)); - - /* Verify the ELF header */ - - ret = elf_verifyheader(&loadinfo->ehdr); - if (ret <0) - { - /* This may not be an error because we will be called to attempt loading - * EVERY binary. If elf_verifyheader() does not recognize the ELF header, - * it will -ENOEXEC whcih simply informs the system that the file is not an - * ELF file. elf_verifyheader() will return other errors if the ELF header - * is not correctly formed. - */ - - bdbg("Bad ELF header: %d\n", ret); - return ret; - } - - return OK; -} - diff --git a/nuttx/binfmt/libelf/libelf_iobuffer.c b/nuttx/binfmt/libelf/libelf_iobuffer.c deleted file mode 100644 index ead99ca099..0000000000 --- a/nuttx/binfmt/libelf/libelf_iobuffer.c +++ /dev/null @@ -1,136 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/elf_iobuffer.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include -#include - -#include "libelf.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_allocbuffer - * - * Description: - * Perform the initial allocation of the I/O buffer, if it has not already - * been allocated. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_allocbuffer(FAR struct elf_loadinfo_s *loadinfo) -{ - /* Has a buffer been allocated> */ - - if (!loadinfo->iobuffer) - { - /* No.. allocate one now */ - - loadinfo->iobuffer = (FAR uint8_t *)kmalloc(CONFIG_ELF_BUFFERSIZE); - if (!loadinfo->iobuffer) - { - bdbg("Failed to allocate an I/O buffer\n"); - return -ENOMEM; - } - - loadinfo->buflen = CONFIG_ELF_BUFFERSIZE; - } - - return OK; -} - -/**************************************************************************** - * Name: elf_reallocbuffer - * - * Description: - * Increase the size of I/O buffer by the specified buffer increment. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_reallocbuffer(FAR struct elf_loadinfo_s *loadinfo, size_t increment) -{ - FAR void *buffer; - size_t newsize; - - /* Get the new size of the allocation */ - - newsize = loadinfo->buflen + increment; - - /* And perform the reallocation */ - - buffer = krealloc((FAR void *)loadinfo->iobuffer, newsize); - if (!buffer) - { - bdbg("Failed to reallocate the I/O buffer\n"); - return -ENOMEM; - } - - /* Save the new buffer info */ - - loadinfo->iobuffer = buffer; - loadinfo->buflen = newsize; - return OK; -} - diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c deleted file mode 100644 index b1ac44e21f..0000000000 --- a/nuttx/binfmt/libelf/libelf_load.c +++ /dev/null @@ -1,263 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf_load.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include "libelf.h" - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -#define ELF_ALIGN_MASK ((1 << CONFIG_ELF_ALIGN_LOG2) - 1) -#define ELF_ALIGNUP(a) (((unsigned long)(a) + ELF_ALIGN_MASK) & ~ELF_ALIGN_MASK) -#define ELF_ALIGNDOWN(a) ((unsigned long)(a) & ~ELF_ALIGN_MASK) - - -#ifndef MAX -#define MAX(x,y) ((x) > (y) ? (x) : (y)) -#endif - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_elfsize - * - * Description: - * Calculate total memory allocation for the ELF file. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -static void elf_elfsize(struct elf_loadinfo_s *loadinfo) -{ - size_t elfsize; - int i; - - /* Accumulate the size each section into memory that is marked SHF_ALLOC */ - - elfsize = 0; - for (i = 0; i < loadinfo->ehdr.e_shnum; i++) - { - FAR Elf32_Shdr *shdr = &loadinfo->shdr[i]; - - /* SHF_ALLOC indicates that the section requires memory during - * execution. - */ - - if ((shdr->sh_flags & SHF_ALLOC) != 0) - { - elfsize += ELF_ALIGNUP(shdr->sh_size); - } - } - - /* Save the allocation size */ - - loadinfo->elfsize = elfsize; -} - -/**************************************************************************** - * Name: elf_loadfile - * - * Description: - * Allocate memory for the file and read the section data into the - * allocated memory. Section addresses in the shdr[] are updated to point - * to the corresponding position in the allocated memory. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo) -{ - FAR uint8_t *dest; - int ret; - int i; - - /* Allocate (and zero) memory for the ELF file. */ - - loadinfo->elfalloc = (uintptr_t)kzalloc(loadinfo->elfsize); - if (!loadinfo->elfalloc) - { - return -ENOMEM; - } - - /* Read each section into memory that is marked SHF_ALLOC + SHT_NOBITS */ - - bvdbg("Loaded sections:\n"); - dest = (FAR uint8_t*)loadinfo->elfalloc; - - for (i = 0; i < loadinfo->ehdr.e_shnum; i++) - { - FAR Elf32_Shdr *shdr = &loadinfo->shdr[i]; - - /* SHF_ALLOC indicates that the section requires memory during - * execution */ - - if ((shdr->sh_flags & SHF_ALLOC) == 0) - { - continue; - } - - /* SHT_NOBITS indicates that there is no data in the file for the - * section. - */ - - if (shdr->sh_type != SHT_NOBITS) - { - /* Read the section data from sh_offset to dest */ - - ret = elf_read(loadinfo, dest, shdr->sh_size, shdr->sh_offset); - if (ret < 0) - { - bdbg("Failed to read section %d: %d\n", i, ret); - return ret; - } - } - - /* Update sh_addr to point to copy in memory */ - - bvdbg("%d. %08x->%08x\n", i, (long)shdr->sh_addr, (long)dest); - shdr->sh_addr = (uintptr_t)dest; - - /* Setup the memory pointer for the next time through the loop */ - - dest += ELF_ALIGNUP(shdr->sh_size); - } - - return OK; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_load - * - * Description: - * Loads the binary into memory, allocating memory, performing relocations - * and inializing the data and bss segments. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_load(FAR struct elf_loadinfo_s *loadinfo) -{ - int ret; - - bvdbg("loadinfo: %p\n", loadinfo); - DEBUGASSERT(loadinfo && loadinfo->filfd >= 0); - - /* Load section headers into memory */ - - ret = elf_loadshdrs(loadinfo); - if (ret < 0) - { - bdbg("elf_loadshdrs failed: %d\n", ret); - goto errout_with_buffers; - } - - /* Determine total size to allocate */ - - elf_elfsize(loadinfo); - - /* Allocate memory and load sections into memory */ - - ret = elf_loadfile(loadinfo); - if (ret < 0) - { - bdbg("elf_loadfile failed: %d\n", ret); - goto errout_with_buffers; - } - - /* Load static constructors and destructors. */ - -#ifdef CONFIG_BINFMT_CONSTRUCTORS - ret = elf_loadctors(loadinfo); - if (ret < 0) - { - bdbg("elf_loadctors failed: %d\n", ret); - goto errout_with_buffers; - } - - ret = elf_loaddtors(loadinfo); - if (ret < 0) - { - bdbg("elf_loaddtors failed: %d\n", ret); - goto errout_with_buffers; - } -#endif - - return OK; - - /* Error exits */ - -errout_with_buffers: - elf_unload(loadinfo); - return ret; -} - diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c deleted file mode 100644 index da41212f23..0000000000 --- a/nuttx/binfmt/libelf/libelf_read.c +++ /dev/null @@ -1,161 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf_read.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include - -#include - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -#undef ELF_DUMP_READDATA /* Define to dump all file data read */ -#define DUMPER lib_rawprintf /* If ELF_DUMP_READDATA is defined, this - * is the API used to dump data */ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_dumpreaddata - ****************************************************************************/ - -#if defined(ELF_DUMP_READDATA) -static inline void elf_dumpreaddata(char *buffer, int buflen) -{ - uint32_t *buf32 = (uint32_t*)buffer; - int i; - int j; - - for (i = 0; i < buflen; i += 32) - { - DUMPER("%04x:", i); - for (j = 0; j < 32; j += sizeof(uint32_t)) - { - DUMPER(" %08x", *buf32++); - } - DUMPER("\n"); - } -} -#else -# define elf_dumpreaddata(b,n) -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_read - * - * Description: - * Read 'readsize' bytes from the object file at 'offset' - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer, - size_t readsize, off_t offset) -{ - ssize_t nbytes; /* Number of bytes read */ - off_t rpos; /* Position returned by lseek */ - - bvdbg("Read %ld bytes from offset %ld\n", (long)readsize, (long)offset); - - /* Loop until all of the requested data has been read. */ - - while (readsize > 0) - { - /* Seek to the next read position */ - - rpos = lseek(loadinfo->filfd, offset, SEEK_SET); - if (rpos != offset) - { - int errval = errno; - bdbg("Failed to seek to position %ld: %d\n", (long)offset, errval); - return -errval; - } - - /* Read the file data at offset into the user buffer */ - - nbytes = read(loadinfo->filfd, buffer, readsize); - if (nbytes < 0) - { - int errval = errno; - - /* EINTR just means that we received a signal */ - - if (errval != EINTR) - { - bdbg("Read of .data failed: %d\n", errval); - return -errval; - } - } - else if (nbytes == 0) - { - bdbg("Unexpected end of file\n"); - return -ENODATA; - } - else - { - readsize -= nbytes; - buffer += nbytes; - offset += nbytes; - } - } - - elf_dumpreaddata(buffer, readsize); - return OK; -} diff --git a/nuttx/binfmt/libelf/libelf_sections.c b/nuttx/binfmt/libelf/libelf_sections.c deleted file mode 100644 index c417935446..0000000000 --- a/nuttx/binfmt/libelf/libelf_sections.c +++ /dev/null @@ -1,284 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf_sections.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include -#include - -#include "libelf.h" - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_sectname - * - * Description: - * Get the symbol name in loadinfo->iobuffer[]. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -static inline int elf_sectname(FAR struct elf_loadinfo_s *loadinfo, - FAR const Elf32_Shdr *shdr) -{ - FAR Elf32_Shdr *shstr; - FAR uint8_t *buffer; - off_t offset; - size_t readlen; - size_t bytesread; - int shstrndx; - int ret; - - /* Get the section header table index of the entry associated with the - * section name string table. If the file has no section name string table, - * this member holds the value SH_UNDEF. - */ - - shstrndx = loadinfo->ehdr.e_shstrndx; - if (shstrndx == SHN_UNDEF) - { - bdbg("No section header string table\n"); - return -EINVAL; - } - - /* Get the section name string table section header */ - - shstr = &loadinfo->shdr[shstrndx]; - - /* Get the file offset to the string that is the name of the section. This - * is the sum of: - * - * shstr->sh_offset: The file offset to the first byte of the section - * header string table data. - * shdr->sh_name: The offset to the name of the section in the section - * name table - */ - - offset = shstr->sh_offset + shdr->sh_name; - - /* Loop until we get the entire section name into memory */ - - buffer = loadinfo->iobuffer; - bytesread = 0; - - for (;;) - { - /* Get the number of bytes to read */ - - readlen = loadinfo->buflen - bytesread; - if (offset + readlen > loadinfo->filelen) - { - readlen = loadinfo->filelen - offset; - if (readlen <= 0) - { - bdbg("At end of file\n"); - return -EINVAL; - } - } - - /* Read that number of bytes into the array */ - - buffer = &loadinfo->iobuffer[bytesread]; - ret = elf_read(loadinfo, buffer, readlen, offset); - if (ret < 0) - { - bdbg("Failed to read section name\n"); - return ret; - } - - bytesread += readlen; - - /* Did we read the NUL terminator? */ - - if (memchr(buffer, '\0', readlen) != NULL) - { - /* Yes, the buffer contains a NUL terminator. */ - - return OK; - } - - /* No.. then we have to read more */ - - ret = elf_reallocbuffer(loadinfo, CONFIG_ELF_BUFFERINCR); - if (ret < 0) - { - bdbg("elf_reallocbuffer failed: %d\n", ret); - return ret; - } - } - - /* We will not get here */ - - return OK; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_loadshdrs - * - * Description: - * Loads section headers into memory. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo) -{ - size_t shdrsize; - int ret; - - DEBUGASSERT(loadinfo->shdr == NULL); - - /* Verify that there are sections */ - - if (loadinfo->ehdr.e_shnum < 1) - { - bdbg("No sections(?)\n"); - return -EINVAL; - } - - /* Get the total size of the section header table */ - - shdrsize = (size_t)loadinfo->ehdr.e_shentsize * (size_t)loadinfo->ehdr.e_shnum; - if(loadinfo->ehdr.e_shoff + shdrsize > loadinfo->filelen) - { - bdbg("Insufficent space in file for section header table\n"); - return -ESPIPE; - } - - /* Allocate memory to hold a working copy of the sector header table */ - - loadinfo->shdr = (FAR Elf32_Shdr*)kmalloc(shdrsize); - if (!loadinfo->shdr) - { - bdbg("Failed to allocate the section header table. Size: %ld\n", (long)shdrsize); - return -ENOMEM; - } - - /* Read the section header table into memory */ - - ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->shdr, shdrsize, loadinfo->ehdr.e_shoff); - if (ret < 0) - { - bdbg("Failed to read section header table: %d\n", ret); - } - - return ret; -} - -/**************************************************************************** - * Name: elf_findsection - * - * Description: - * A section by its name. - * - * Input Parameters: - * loadinfo - Load state information - * sectname - Name of the section to find - * - * Returned Value: - * On success, the index to the section is returned; A negated errno value - * is returned on failure. - * - ****************************************************************************/ - -int elf_findsection(FAR struct elf_loadinfo_s *loadinfo, - FAR const char *sectname) -{ - FAR const Elf32_Shdr *shdr; - int ret; - int i; - - /* Search through the shdr[] array in loadinfo for a section named 'sectname' */ - - for (i = 0; i < loadinfo->ehdr.e_shnum; i++) - { - /* Get the name of this section */ - - shdr = &loadinfo->shdr[i]; - ret = elf_sectname(loadinfo, shdr); - if (ret < 0) - { - bdbg("elf_sectname failed: %d\n", ret); - return ret; - } - - /* Check if the name of this section is 'sectname' */ - - bvdbg("%d. Comparing \"%s\" and .\"%s\"\n", - i, loadinfo->iobuffer, sectname); - - if (strcmp((FAR const char *)loadinfo->iobuffer, sectname) == 0) - { - /* We found it... return the index */ - - return i; - } - } - - /* We failed to find a section with this name. */ - - return -ENOENT; -} diff --git a/nuttx/binfmt/libelf/libelf_symbols.c b/nuttx/binfmt/libelf/libelf_symbols.c deleted file mode 100644 index 2d94b11af0..0000000000 --- a/nuttx/binfmt/libelf/libelf_symbols.c +++ /dev/null @@ -1,329 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf_symbols.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include -#include - -#include "libelf.h" - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -#ifndef CONFIG_ELF_BUFFERINCR -# define CONFIG_ELF_BUFFERINCR 32 -#endif - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_symname - * - * Description: - * Get the symbol name in loadinfo->iobuffer[]. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -static int elf_symname(FAR struct elf_loadinfo_s *loadinfo, - FAR const Elf32_Sym *sym) -{ - FAR uint8_t *buffer; - off_t offset; - size_t readlen; - size_t bytesread; - int ret; - - /* Get the file offset to the string that is the name of the symbol. The - * st_name member holds an offset into the file's symbol string table. - */ - - if (sym->st_name == 0) - { - bdbg("Symbol has no name\n"); - return -ENOENT; - } - - offset = loadinfo->shdr[loadinfo->strtabidx].sh_offset + sym->st_name; - - /* Loop until we get the entire symbol name into memory */ - - bytesread = 0; - - for (;;) - { - /* Get the number of bytes to read */ - - readlen = loadinfo->buflen - bytesread; - if (offset + readlen > loadinfo->filelen) - { - readlen = loadinfo->filelen - offset; - if (readlen <= 0) - { - bdbg("At end of file\n"); - return -EINVAL; - } - } - - /* Read that number of bytes into the array */ - - buffer = &loadinfo->iobuffer[bytesread]; - ret = elf_read(loadinfo, buffer, readlen, offset); - if (ret < 0) - { - bdbg("elf_read failed: %d\n", ret); - return ret; - } - - bytesread += readlen; - - /* Did we read the NUL terminator? */ - - if (memchr(buffer, '\0', readlen) != NULL) - { - /* Yes, the buffer contains a NUL terminator. */ - - return OK; - } - - /* No.. then we have to read more */ - - ret = elf_reallocbuffer(loadinfo, CONFIG_ELF_BUFFERINCR); - if (ret < 0) - { - bdbg("elf_reallocbuffer failed: %d\n", ret); - return ret; - } - } - - /* We will not get here */ - - return OK; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_findsymtab - * - * Description: - * Find the symbol table section. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_findsymtab(FAR struct elf_loadinfo_s *loadinfo) -{ - int i; - - /* Find the symbol table section header and its associated string table */ - - for (i = 1; i < loadinfo->ehdr.e_shnum; i++) - { - if (loadinfo->shdr[i].sh_type == SHT_SYMTAB) - { - loadinfo->symtabidx = i; - loadinfo->strtabidx = loadinfo->shdr[i].sh_link; - break; - } - } - - /* Verify that there is a symbol and string table */ - - if (loadinfo->symtabidx == 0) - { - bdbg("No symbols in ELF file\n"); - return -EINVAL; - } - - return OK; -} - -/**************************************************************************** - * Name: elf_readsym - * - * Description: - * Read the ELFT symbol structure at the specfied index into memory. - * - * Input Parameters: - * loadinfo - Load state information - * index - Symbol table index - * sym - Location to return the table entry - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index, - FAR Elf32_Sym *sym) -{ - FAR Elf32_Shdr *symtab = &loadinfo->shdr[loadinfo->symtabidx]; - off_t offset; - - /* Verify that the symbol table index lies within symbol table */ - - if (index < 0 || index > (symtab->sh_size / sizeof(Elf32_Sym))) - { - bdbg("Bad relocation symbol index: %d\n", index); - return -EINVAL; - } - - /* Get the file offset to the symbol table entry */ - - offset = symtab->sh_offset + sizeof(Elf32_Sym) * index; - - /* And, finally, read the symbol table entry into memory */ - - return elf_read(loadinfo, (FAR uint8_t*)sym, sizeof(Elf32_Sym), offset); -} - -/**************************************************************************** - * Name: elf_symvalue - * - * Description: - * Get the value of a symbol. The updated value of the symbol is returned - * in the st_value field of the symbol table entry. - * - * Input Parameters: - * loadinfo - Load state information - * sym - Symbol table entry (value might be undefined) - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_symvalue(FAR struct elf_loadinfo_s *loadinfo, FAR Elf32_Sym *sym, - FAR const struct symtab_s *exports, int nexports) -{ - FAR const struct symtab_s *symbol; - uintptr_t secbase; - int ret; - - switch (sym->st_shndx) - { - case SHN_COMMON: - { - /* NuttX ELF modules should be compiled with -fno-common. */ - - bdbg("SHN_COMMON: Re-compile with -fno-common\n"); - return -EINVAL; - } - - case SHN_ABS: - { - /* st_value already holds the correct value */ - - bvdbg("SHN_ABS: st_value=%08lx\n", (long)sym->st_value); - return OK; - } - - case SHN_UNDEF: - { - /* Get the name of the undefined symbol */ - - ret = elf_symname(loadinfo, sym); - if (ret < 0) - { - bdbg("SHN_UNDEF: Failed to get symbol name: %d\n", ret); - return ret; - } - - /* Check if the base code exports a symbol of this name */ - -#ifdef CONFIG_SYMTAB_ORDEREDBYNAME - symbol = symtab_findorderedbyname(exports, (FAR char *)loadinfo->iobuffer, nexports); -#else - symbol = symtab_findbyname(exports, (FAR char *)loadinfo->iobuffer, nexports); -#endif - if (!symbol) - { - bdbg("SHN_UNDEF: Exported symbol \"%s\" not found\n", loadinfo->iobuffer); - return -ENOENT; - } - - /* Yes... add the exported symbol value to the ELF symbol table entry */ - - bvdbg("SHN_ABS: name=%s %08x+%08x=%08x\n", - loadinfo->iobuffer, sym->st_value, symbol->sym_value, - sym->st_value + symbol->sym_value); - - sym->st_value += (Elf32_Word)((uintptr_t)symbol->sym_value); - } - break; - - default: - { - secbase = loadinfo->shdr[sym->st_shndx].sh_addr; - - bvdbg("Other: %08x+%08x=%08x\n", - sym->st_value, secbase, sym->st_value + secbase); - - sym->st_value += secbase; - } - break; - } - - return OK; -} diff --git a/nuttx/binfmt/libelf/libelf_uninit.c b/nuttx/binfmt/libelf/libelf_uninit.c deleted file mode 100644 index 3ec6f6c61c..0000000000 --- a/nuttx/binfmt/libelf/libelf_uninit.c +++ /dev/null @@ -1,126 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf_uninit.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include -#include - -#include "libelf.h" - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_uninit - * - * Description: - * Releases any resources committed by elf_init(). This essentially - * undoes the actions of elf_init. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_uninit(struct elf_loadinfo_s *loadinfo) -{ - /* Free all working buffers */ - - elf_freebuffers(loadinfo); - - /* Close the ELF file */ - - if (loadinfo->filfd >= 0) - { - close(loadinfo->filfd); - } - - return OK; -} - -/**************************************************************************** - * Name: elf_freebuffers - * - * Description: - * Release all working buffers. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_freebuffers(struct elf_loadinfo_s *loadinfo) -{ - /* Release all working allocations */ - - if (loadinfo->shdr) - { - kfree((FAR void *)loadinfo->shdr); - loadinfo->shdr = NULL; - } - - if (loadinfo->iobuffer) - { - kfree((FAR void *)loadinfo->iobuffer); - loadinfo->iobuffer = NULL; - loadinfo->buflen = 0; - } - - return OK; -} diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c deleted file mode 100644 index 532fc606fb..0000000000 --- a/nuttx/binfmt/libelf/libelf_unload.c +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/libelf_unload.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include -#include - -#include "libelf.h" - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_unload - * - * Description: - * This function unloads the object from memory. This essentially - * undoes the actions of elf_load. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -int elf_unload(struct elf_loadinfo_s *loadinfo) -{ - /* Free all working buffers */ - - elf_freebuffers(loadinfo); - - /* Release memory holding the relocated ELF image */ - - if (loadinfo->elfalloc != 0) - { - kfree((FAR void *)loadinfo->elfalloc); - loadinfo->elfalloc = 0; - } - - loadinfo->elfsize = 0; - - /* Release memory used to hold static constructors and destructors */ - -#ifdef CONFIG_BINFMT_CONSTRUCTORS - if (loadinfo->ctoralloc != 0) - { - kfree(loadinfo->ctoralloc); - loadinfo->ctoralloc = NULL; - } - - loadinfo->ctors = NULL; - loadinfo->nctors = 0; - - if (loadinfo->dtoralloc != 0) - { - kfree(loadinfo->dtoralloc); - loadinfo->dtoralloc = NULL; - } - - loadinfo->dtors = NULL; - loadinfo->ndtors = 0; -#endif - - return OK; -} - diff --git a/nuttx/binfmt/libelf/libelf_verify.c b/nuttx/binfmt/libelf/libelf_verify.c deleted file mode 100644 index c5f185ec3f..0000000000 --- a/nuttx/binfmt/libelf/libelf_verify.c +++ /dev/null @@ -1,120 +0,0 @@ -/**************************************************************************** - * binfmt/libelf/elf_verify.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -static const char g_elfmagic[EI_MAGIC_SIZE] = { 0x7f, 'E', 'L', 'F' }; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_verifyheader - * - * Description: - * Given the header from a possible ELF executable, verify that it - * is an ELF executable. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - * -ENOEXEC : Not an ELF file - * -EINVAL : Not a relocatable ELF file or not supported by the current, - * configured architecture. - * - ****************************************************************************/ - -int elf_verifyheader(FAR const Elf32_Ehdr *ehdr) -{ - if (!ehdr) - { - bdbg("NULL ELF header!"); - return -ENOEXEC; - } - - /* Verify that the magic number indicates an ELF file */ - - if (memcmp(ehdr->e_ident, g_elfmagic, EI_MAGIC_SIZE) != 0) - { - bvdbg("Not ELF magic {%02x, %02x, %02x, %02x}\n", - ehdr->e_ident[0], ehdr->e_ident[1], ehdr->e_ident[2], ehdr->e_ident[3]); - return -ENOEXEC; - } - - /* Verify that this is a relocatable file */ - - if (ehdr->e_type != ET_REL) - { - bdbg("Not a relocatable file: e_type=%d\n", ehdr->e_type); - return -EINVAL; - } - - /* Verify that this file works with the currently configured architecture */ - - if (arch_checkarch(ehdr)) - { - bdbg("Not a supported architecture\n"); - return -ENOEXEC; - } - - /* Looks good so far... we still might find some problems later. */ - - return OK; -} - diff --git a/nuttx/drivers/input/max11802.c b/nuttx/drivers/input/max11802.c deleted file mode 100644 index ea3883cd0c..0000000000 --- a/nuttx/drivers/input/max11802.c +++ /dev/null @@ -1,1313 +0,0 @@ -/**************************************************************************** - * drivers/input/max11802.c - * - * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. - * Authors: Gregory Nutt - * Petteri Aimonen - * - * References: - * "Low-Power, Ultra-Small Resistive Touch-Screen Controllers - * with I2C/SPI Interface" Maxim IC, Rev 3, 10/2010 - * - * 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 -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include -#include - -#include "max11802.h" - -/**************************************************************************** - * 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 - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ -/* Low-level SPI helpers */ - -#ifdef CONFIG_SPI_OWNBUS -static inline void max11802_configspi(FAR struct spi_dev_s *spi); -# define max11802_lock(spi) -# define max11802_unlock(spi) -#else -# define max11802_configspi(spi); -static void max11802_lock(FAR struct spi_dev_s *spi); -static void max11802_unlock(FAR struct spi_dev_s *spi); -#endif - -static uint16_t max11802_sendcmd(FAR struct max11802_dev_s *priv, uint8_t cmd, int *tags); - -/* Interrupts and data sampling */ - -static void max11802_notify(FAR struct max11802_dev_s *priv); -static int max11802_sample(FAR struct max11802_dev_s *priv, - FAR struct max11802_sample_s *sample); -static int max11802_waitsample(FAR struct max11802_dev_s *priv, - FAR struct max11802_sample_s *sample); -static void max11802_worker(FAR void *arg); -static int max11802_interrupt(int irq, FAR void *context); - -/* Character driver methods */ - -static int max11802_open(FAR struct file *filep); -static int max11802_close(FAR struct file *filep); -static ssize_t max11802_read(FAR struct file *filep, FAR char *buffer, size_t len); -static int max11802_ioctl(FAR struct file *filep, int cmd, unsigned long arg); -#ifndef CONFIG_DISABLE_POLL -static int max11802_poll(FAR struct file *filep, struct pollfd *fds, bool setup); -#endif - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/* This the the vtable that supports the character driver interface */ - -static const struct file_operations max11802_fops = -{ - max11802_open, /* open */ - max11802_close, /* close */ - max11802_read, /* read */ - 0, /* write */ - 0, /* seek */ - max11802_ioctl /* ioctl */ -#ifndef CONFIG_DISABLE_POLL - , max11802_poll /* poll */ -#endif -}; - -/* If only a single MAX11802 device is supported, then the driver state - * structure may as well be pre-allocated. - */ - -#ifndef CONFIG_MAX11802_MULTIPLE -static struct max11802_dev_s g_max11802; - -/* Otherwise, we will need to maintain allocated driver instances in a list */ - -#else -static struct max11802_dev_s *g_max11802list; -#endif - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: max11802_lock - * - * Description: - * 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 - * - * Returned Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -#ifndef CONFIG_SPI_OWNBUS -static void max11802_lock(FAR struct spi_dev_s *spi) -{ - /* Lock the SPI bus because there are multiple devices competing for the - * SPI bus - */ - - (void)SPI_LOCK(spi, true); - - /* We have the lock. Now make sure that the SPI bus is configured for the - * MAX11802 (it might have gotten configured for a different device while - * unlocked) - */ - - SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); - SPI_SETMODE(spi, CONFIG_MAX11802_SPIMODE); - SPI_SETBITS(spi, 8); - SPI_SETFREQUENCY(spi, CONFIG_MAX11802_FREQUENCY); - SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); -} -#endif - -/**************************************************************************** - * Function: max11802_unlock - * - * Description: - * 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 - * - * Returned Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -#ifndef CONFIG_SPI_OWNBUS -static void max11802_unlock(FAR struct spi_dev_s *spi) -{ - /* Relinquish the SPI bus. */ - - (void)SPI_LOCK(spi, false); -} -#endif - -/**************************************************************************** - * Function: max11802_configspi - * - * Description: - * Configure the SPI for use with the MAX11802. This function should be - * called once during touchscreen initialization to configure the SPI - * bus. Note that if CONFIG_SPI_OWNBUS is not defined, then this function - * does nothing. - * - * Parameters: - * spi - Reference to the SPI driver structure - * - * Returned Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -#ifdef CONFIG_SPI_OWNBUS -static inline void max11802_configspi(FAR struct spi_dev_s *spi) -{ - /* Configure SPI for the MAX11802. But only if we own the SPI bus. Otherwise, don't - * bother because it might change. - */ - - SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); - SPI_SETMODE(spi, CONFIG_MAX11802_SPIMODE); - SPI_SETBITS(spi, 8); - SPI_SETFREQUENCY(spi, CONFIG_MAX11802_FREQUENCY); - SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); -} -#endif - -/**************************************************************************** - * Name: max11802_sendcmd - ****************************************************************************/ - -static uint16_t max11802_sendcmd(FAR struct max11802_dev_s *priv, uint8_t cmd, int *tags) -{ - uint8_t buffer[2]; - uint16_t result; - - /* Select the MAX11802 */ - - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); - - /* Send the command */ - - (void)SPI_SEND(priv->spi, cmd); - - /* Read the data */ - - SPI_RECVBLOCK(priv->spi, buffer, 2); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); - - result = ((uint16_t)buffer[0] << 8) | (uint16_t)buffer[1]; - *tags = result & 0xF; - result >>= 4; // Get rid of tags - - ivdbg("cmd:%02x response:%04x\n", cmd, result); - return result; -} - -/**************************************************************************** - * Name: max11802_notify - ****************************************************************************/ - -static void max11802_notify(FAR struct max11802_dev_s *priv) -{ -#ifndef CONFIG_DISABLE_POLL - int i; -#endif - - /* If there are threads waiting for read data, then signal one of them - * that the read data is available. - */ - - if (priv->nwaiters > 0) - { - /* After posting this semaphore, we need to exit because the sample - * is no longer available. - */ - - sem_post(&priv->waitsem); - } - - /* If there are threads waiting on poll() for MAX11802 data to become available, - * then wake them up now. NOTE: we wake up all waiting threads because we - * do not know that they are going to do. If they all try to read the data, - * then some make end up blocking after all. - */ - -#ifndef CONFIG_DISABLE_POLL - for (i = 0; i < CONFIG_MAX11802_NPOLLWAITERS; i++) - { - struct pollfd *fds = priv->fds[i]; - if (fds) - { - fds->revents |= POLLIN; - ivdbg("Report events: %02x\n", fds->revents); - sem_post(fds->sem); - } - } -#endif -} - -/**************************************************************************** - * Name: max11802_sample - ****************************************************************************/ - -static int max11802_sample(FAR struct max11802_dev_s *priv, - FAR struct max11802_sample_s *sample) -{ - irqstate_t flags; - int ret = -EAGAIN; - - /* Interrupts must be disabled when this is called to (1) prevent posting - * of semaphores from interrupt handlers, and (2) to prevent sampled data - * from changing until it has been reported. - */ - - flags = irqsave(); - - /* Is there new MAX11802 sample data available? */ - - if (priv->penchange) - { - /* Yes.. the state has changed in some way. Return a copy of the - * sampled data. - */ - - memcpy(sample, &priv->sample, sizeof(struct max11802_sample_s )); - - /* Now manage state transitions */ - - if (sample->contact == CONTACT_UP) - { - /* Next.. no contact. Increment the ID so that next contact ID - * will be unique. X/Y positions are no longer valid. - */ - - priv->sample.contact = CONTACT_NONE; - priv->sample.valid = false; - priv->id++; - } - else if (sample->contact == CONTACT_DOWN) - { - /* First report -- next report will be a movement */ - - priv->sample.contact = CONTACT_MOVE; - } - - priv->penchange = false; - ret = OK; - } - - irqrestore(flags); - return ret; -} - -/**************************************************************************** - * Name: max11802_waitsample - ****************************************************************************/ - -static int max11802_waitsample(FAR struct max11802_dev_s *priv, - FAR struct max11802_sample_s *sample) -{ - irqstate_t flags; - int ret; - - /* Interrupts must be disabled when this is called to (1) prevent posting - * of semaphores from interrupt handlers, and (2) to prevent sampled data - * from changing until it has been reported. - * - * In addition, we will also disable pre-emption to prevent other threads - * from getting control while we muck with the semaphores. - */ - - sched_lock(); - flags = irqsave(); - - /* Now release the semaphore that manages mutually exclusive access to - * the device structure. This may cause other tasks to become ready to - * run, but they cannot run yet because pre-emption is disabled. - */ - - sem_post(&priv->devsem); - - /* Try to get the a sample... if we cannot, then wait on the semaphore - * that is posted when new sample data is available. - */ - - while (max11802_sample(priv, sample) < 0) - { - /* Wait for a change in the MAX11802 state */ - - ivdbg("Waiting..\n"); - priv->nwaiters++; - ret = sem_wait(&priv->waitsem); - priv->nwaiters--; - - if (ret < 0) - { - /* If we are awakened by a signal, then we need to return - * the failure now. - */ - - idbg("sem_wait: %d\n", errno); - DEBUGASSERT(errno == EINTR); - ret = -EINTR; - goto errout; - } - } - - ivdbg("Sampled\n"); - - /* Re-acquire the the semaphore that manages mutually exclusive access to - * the device structure. We may have to wait here. But we have our sample. - * Interrupts and pre-emption will be re-enabled while we wait. - */ - - ret = sem_wait(&priv->devsem); - -errout: - /* Then re-enable interrupts. We might get interrupt here and there - * could be a new sample. But no new threads will run because we still - * have pre-emption disabled. - */ - - irqrestore(flags); - - /* Restore pre-emption. We might get suspended here but that is okay - * because we already have our sample. Note: this means that if there - * were two threads reading from the MAX11802 for some reason, the data - * might be read out of order. - */ - - sched_unlock(); - return ret; -} - -/**************************************************************************** - * Name: max11802_schedule - ****************************************************************************/ - -static int max11802_schedule(FAR struct max11802_dev_s *priv) -{ - FAR struct max11802_config_s *config; - int ret; - - /* Get a pointer the callbacks for convenience (and so the code is not so - * ugly). - */ - - config = priv->config; - DEBUGASSERT(config != NULL); - - /* Disable further interrupts. MAX11802 interrupts will be re-enabled - * after the worker thread executes. - */ - - config->enable(config, false); - - /* Disable the watchdog timer. It will be re-enabled in the worker thread - * while the pen remains down. - */ - - wd_cancel(priv->wdog); - - /* Transfer processing to the worker thread. Since MAX11802 interrupts are - * disabled while the work is pending, no special action should be required - * to protected the work queue. - */ - - DEBUGASSERT(priv->work.worker == NULL); - ret = work_queue(HPWORK, &priv->work, max11802_worker, priv, 0); - if (ret != 0) - { - illdbg("Failed to queue work: %d\n", ret); - } - - return OK; -} - -/**************************************************************************** - * Name: max11802_wdog - ****************************************************************************/ - -static void max11802_wdog(int argc, uint32_t arg1, ...) -{ - FAR struct max11802_dev_s *priv = (FAR struct max11802_dev_s *)((uintptr_t)arg1); - (void)max11802_schedule(priv); -} - -/**************************************************************************** - * Name: max11802_worker - ****************************************************************************/ - -static void max11802_worker(FAR void *arg) -{ - FAR struct max11802_dev_s *priv = (FAR struct max11802_dev_s *)arg; - FAR struct max11802_config_s *config; - uint16_t x; - uint16_t y; - uint16_t xdiff; - uint16_t ydiff; - bool pendown; - int ret; - int tags, tags2; - - ASSERT(priv != NULL); - - /* Get a pointer the callbacks for convenience (and so the code is not so - * ugly). - */ - - config = priv->config; - DEBUGASSERT(config != NULL); - - /* 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); - - /* Lock the SPI bus so that we have exclusive access */ - - max11802_lock(priv->spi); - - /* Start coordinate measurement */ - (void)max11802_sendcmd(priv, MAX11802_CMD_MEASUREXY, &tags); - - /* 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); - - /* Handle the change from pen down to pen up */ - - if (pendown) - ivdbg("\nPD\n"); - else - ivdbg("\nPU\n"); - - if (!pendown) - { - /* 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) - */ - - ivdbg("\nPC%d\n", priv->sample.contact); - - if (priv->sample.contact == CONTACT_NONE || - priv->sample.contact == CONTACT_UP) - - { - goto ignored; - } - - /* The pen is up. NOTE: We know from a previous test, that this is a - * loss of contact condition. This will be changed to CONTACT_NONE - * after the loss of contact is sampled. - */ - - priv->sample.contact = CONTACT_UP; - } - - /* It is a pen down event. If the last loss-of-contact event has not been - * processed yet, then we have to ignore the pen down event (or else it will - * look like a drag event) - */ - - else if (priv->sample.contact == CONTACT_UP) - { - /* 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. - */ - - ivdbg("Previous pen up event still in buffer\n"); - max11802_notify(priv); - wd_start(priv->wdog, MAX11802_WDOG_DELAY, max11802_wdog, 1, (uint32_t)priv); - goto ignored; - } - else - { - /* Wait for data ready */ - do { - /* Handle pen down events. First, sample positional values. */ - -#ifdef CONFIG_MAX11802_SWAPXY - x = max11802_sendcmd(priv, MAX11802_CMD_YPOSITION, &tags); - y = max11802_sendcmd(priv, MAX11802_CMD_XPOSITION, &tags2); -#else - x = max11802_sendcmd(priv, MAX11802_CMD_XPOSITION, &tags); - y = max11802_sendcmd(priv, MAX11802_CMD_YPOSITION, &tags2); -#endif - } while (tags == 0xF || tags2 == 0xF); - - /* Continue to sample the position while the pen is down */ - wd_start(priv->wdog, MAX11802_WDOG_DELAY, max11802_wdog, 1, (uint32_t)priv); - - /* Check if data is valid */ - if ((tags & 0x03) != 0) - { - ivdbg("Touch ended before measurement\n"); - goto ignored; - } - - /* 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); - - /* Check the thresholds. Bail if there is no significant difference */ - - if (xdiff < CONFIG_MAX11802_THRESHX && ydiff < CONFIG_MAX11802_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 */ - - priv->sample.valid = true; - - /* If this is the first (acknowledged) pen down report, then report - * this as the first contact. If contact == CONTACT_DOWN, it will be - * set to set to CONTACT_MOVE after the contact is first sampled. - */ - - if (priv->sample.contact != CONTACT_MOVE) - { - /* First contact */ - - priv->sample.contact = CONTACT_DOWN; - } - } - - /* Indicate the availability of new sample data for this ID */ - - priv->sample.id = priv->id; - priv->penchange = true; - - /* Notify any waiters that new MAX11802 data is available */ - - max11802_notify(priv); - -ignored: - config->enable(config, true); - - /* Release our lock on the state structure and unlock the SPI bus */ - - sem_post(&priv->devsem); - max11802_unlock(priv->spi); -} - -/**************************************************************************** - * Name: max11802_interrupt - ****************************************************************************/ - -static int max11802_interrupt(int irq, FAR void *context) -{ - FAR struct max11802_dev_s *priv; - FAR struct max11802_config_s *config; - int ret; - - /* Which MAX11802 device caused the interrupt? */ - -#ifndef CONFIG_MAX11802_MULTIPLE - priv = &g_max11802; -#else - for (priv = g_max11802list; - priv && priv->configs->irq != irq; - priv = priv->flink); - - ASSERT(priv != NULL); -#endif - - /* Get a pointer the callbacks for convenience (and so the code is not so - * ugly). - */ - - config = priv->config; - DEBUGASSERT(config != NULL); - - /* Schedule sampling to occur on the worker thread */ - - ret = max11802_schedule(priv); - - /* Clear any pending interrupts and return success */ - - config->clear(config); - return ret; -} - -/**************************************************************************** - * Name: max11802_open - ****************************************************************************/ - -static int max11802_open(FAR struct file *filep) -{ -#ifdef CONFIG_MAX11802_REFCNT - FAR struct inode *inode; - FAR struct max11802_dev_s *priv; - uint8_t tmp; - int ret; - - ivdbg("Opening\n"); - - DEBUGASSERT(filep); - inode = filep->f_inode; - - DEBUGASSERT(inode && inode->i_private); - priv = (FAR struct max11802_dev_s *)inode->i_private; - - /* Get exclusive access to the driver data structure */ - - ret = sem_wait(&priv->devsem); - if (ret < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - /* Increment the reference count */ - - tmp = priv->crefs + 1; - if (tmp == 0) - { - /* More than 255 opens; uint8_t overflows to zero */ - - ret = -EMFILE; - goto errout_with_sem; - } - - /* When the reference increments to 1, this is the first open event - * on the driver.. and an opportunity to do any one-time initialization. - */ - - /* Save the new open count on success */ - - priv->crefs = tmp; - -errout_with_sem: - sem_post(&priv->devsem); - return ret; -#else - ivdbg("Opening\n"); - return OK; -#endif -} - -/**************************************************************************** - * Name: max11802_close - ****************************************************************************/ - -static int max11802_close(FAR struct file *filep) -{ -#ifdef CONFIG_MAX11802_REFCNT - FAR struct inode *inode; - FAR struct max11802_dev_s *priv; - int ret; - - ivdbg("Closing\n"); - DEBUGASSERT(filep); - inode = filep->f_inode; - - DEBUGASSERT(inode && inode->i_private); - priv = (FAR struct max11802_dev_s *)inode->i_private; - - /* Get exclusive access to the driver data structure */ - - ret = sem_wait(&priv->devsem); - if (ret < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - /* Decrement the reference count unless it would decrement a negative - * value. When the count decrements to zero, there are no further - * open references to the driver. - */ - - if (priv->crefs >= 1) - { - priv->crefs--; - } - - sem_post(&priv->devsem); -#endif - ivdbg("Closing\n"); - return OK; -} - -/**************************************************************************** - * Name: max11802_read - ****************************************************************************/ - -static ssize_t max11802_read(FAR struct file *filep, FAR char *buffer, size_t len) -{ - FAR struct inode *inode; - FAR struct max11802_dev_s *priv; - FAR struct touch_sample_s *report; - struct max11802_sample_s sample; - int ret; - - ivdbg("buffer:%p len:%d\n", buffer, len); - DEBUGASSERT(filep); - inode = filep->f_inode; - - DEBUGASSERT(inode && inode->i_private); - priv = (FAR struct max11802_dev_s *)inode->i_private; - - /* Verify that the caller has provided a buffer large enough to receive - * the touch data. - */ - - if (len < SIZEOF_TOUCH_SAMPLE_S(1)) - { - /* We could provide logic to break up a touch report into segments and - * handle smaller reads... but why? - */ - - idbg("Unsupported read size: %d\n", len); - return -ENOSYS; - } - - /* Get exclusive access to the driver data structure */ - - ret = sem_wait(&priv->devsem); - if (ret < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - idbg("sem_wait: %d\n", errno); - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - /* Try to read sample data. */ - - ret = max11802_sample(priv, &sample); - if (ret < 0) - { - /* Sample data is not available now. We would ave to wait to get - * receive sample data. If the user has specified the O_NONBLOCK - * option, then just return an error. - */ - - ivdbg("Sample data is not available\n"); - if (filep->f_oflags & O_NONBLOCK) - { - ret = -EAGAIN; - goto errout; - } - - /* Wait for sample data */ - - ret = max11802_waitsample(priv, &sample); - if (ret < 0) - { - /* We might have been awakened by a signal */ - - idbg("max11802_waitsample: %d\n", ret); - goto errout; - } - } - - /* In any event, we now have sampled MAX11802 data that we can report - * to the caller. - */ - - report = (FAR struct touch_sample_s *)buffer; - memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1)); - report->npoints = 1; - report->point[0].id = sample.id; - report->point[0].x = sample.x; - report->point[0].y = sample.y; - - /* Report the appropriate flags */ - - if (sample.contact == CONTACT_UP) - { - /* Pen is now up. Is the positional data valid? This is important to - * know because the release will be sent to the window based on its - * last positional data. - */ - - if (sample.valid) - { - report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | TOUCH_POS_VALID; - } - else - { - report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID; - } - } - else if (sample.contact == CONTACT_DOWN) - { - /* First contact */ - - report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID; - } - else /* if (sample->contact == CONTACT_MOVE) */ - { - /* Movement of the same contact */ - - report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID; - } - - ivdbg(" id: %d\n", report->point[0].id); - ivdbg(" flags: %02x\n", report->point[0].flags); - ivdbg(" x: %d\n", report->point[0].x); - ivdbg(" y: %d\n", report->point[0].y); - - ret = SIZEOF_TOUCH_SAMPLE_S(1); - -errout: - sem_post(&priv->devsem); - ivdbg("Returning: %d\n", ret); - return ret; -} - -/**************************************************************************** - * Name:max11802_ioctl - ****************************************************************************/ - -static int max11802_ioctl(FAR struct file *filep, int cmd, unsigned long arg) -{ - FAR struct inode *inode; - FAR struct max11802_dev_s *priv; - int ret; - - ivdbg("cmd: %d arg: %ld\n", cmd, arg); - DEBUGASSERT(filep); - inode = filep->f_inode; - - DEBUGASSERT(inode && inode->i_private); - priv = (FAR struct max11802_dev_s *)inode->i_private; - - /* Get exclusive access to the driver data structure */ - - ret = sem_wait(&priv->devsem); - if (ret < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - /* Process the IOCTL by command */ - - switch (cmd) - { - case TSIOC_SETFREQUENCY: /* arg: Pointer to uint32_t frequency value */ - { - FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); - DEBUGASSERT(priv->config != NULL && ptr != NULL); - priv->config->frequency = SPI_SETFREQUENCY(priv->spi, *ptr); - } - break; - - case TSIOC_GETFREQUENCY: /* arg: Pointer to uint32_t frequency value */ - { - FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); - DEBUGASSERT(priv->config != NULL && ptr != NULL); - *ptr = priv->config->frequency; - } - break; - - default: - ret = -ENOTTY; - break; - } - - sem_post(&priv->devsem); - return ret; -} - -/**************************************************************************** - * Name: max11802_poll - ****************************************************************************/ - -#ifndef CONFIG_DISABLE_POLL -static int max11802_poll(FAR struct file *filep, FAR struct pollfd *fds, - bool setup) -{ - FAR struct inode *inode; - FAR struct max11802_dev_s *priv; - pollevent_t eventset; - int ndx; - int ret = OK; - int i; - - ivdbg("setup: %d\n", (int)setup); - DEBUGASSERT(filep && fds); - inode = filep->f_inode; - - DEBUGASSERT(inode && inode->i_private); - priv = (FAR struct max11802_dev_s *)inode->i_private; - - /* Are we setting up the poll? Or tearing it down? */ - - ret = sem_wait(&priv->devsem); - if (ret < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - if (setup) - { - /* Ignore waits that do not include POLLIN */ - - if ((fds->events & POLLIN) == 0) - { - ret = -EDEADLK; - goto errout; - } - - /* This is a request to set up the poll. Find an available - * slot for the poll structure reference - */ - - for (i = 0; i < CONFIG_MAX11802_NPOLLWAITERS; i++) - { - /* Find an available slot */ - - if (!priv->fds[i]) - { - /* Bind the poll structure and this slot */ - - priv->fds[i] = fds; - fds->priv = &priv->fds[i]; - break; - } - } - - if (i >= CONFIG_MAX11802_NPOLLWAITERS) - { - fds->priv = NULL; - ret = -EBUSY; - goto errout; - } - - /* Should we immediately notify on any of the requested events? */ - - if (priv->penchange) - { - max11802_notify(priv); - } - } - else if (fds->priv) - { - /* This is a request to tear down the poll. */ - - struct pollfd **slot = (struct pollfd **)fds->priv; - DEBUGASSERT(slot != NULL); - - /* Remove all memory of the poll setup */ - - *slot = NULL; - fds->priv = NULL; - } - -errout: - sem_post(&priv->devsem); - return ret; -} -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: max11802_register - * - * Description: - * Configure the MAX11802 to use the provided SPI device instance. This - * will register the driver as /dev/inputN where N is the minor device - * number - * - * Input Parameters: - * dev - An SPI driver instance - * config - Persistent board configuration data - * minor - The input device minor number - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -int max11802_register(FAR struct spi_dev_s *spi, - FAR struct max11802_config_s *config, int minor) -{ - FAR struct max11802_dev_s *priv; - char devname[DEV_NAMELEN]; -#ifdef CONFIG_MAX11802_MULTIPLE - irqstate_t flags; -#endif - int ret; - - ivdbg("spi: %p minor: %d\n", spi, minor); - - /* Debug-only sanity checks */ - - DEBUGASSERT(spi != NULL && config != NULL && minor >= 0 && minor < 100); - - /* Create and initialize a MAX11802 device driver instance */ - -#ifndef CONFIG_MAX11802_MULTIPLE - priv = &g_max11802; -#else - priv = (FAR struct max11802_dev_s *)kmalloc(sizeof(struct max11802_dev_s)); - if (!priv) - { - idbg("kmalloc(%d) failed\n", sizeof(struct max11802_dev_s)); - return -ENOMEM; - } -#endif - - /* Initialize the MAX11802 device driver instance */ - - memset(priv, 0, sizeof(struct max11802_dev_s)); - 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 */ - - config->clear(config); - config->enable(config, false); - - /* Attach the interrupt handler */ - - ret = config->attach(config, max11802_interrupt); - if (ret < 0) - { - idbg("Failed to attach interrupt\n"); - goto errout_with_priv; - } - - idbg("Mode: %d Bits: 8 Frequency: %d\n", - CONFIG_MAX11802_SPIMODE, CONFIG_MAX11802_FREQUENCY); - - /* Lock the SPI bus so that we have exclusive access */ - - max11802_lock(spi); - - /* Configure the SPI interface */ - - max11802_configspi(spi); - - /* Configure MAX11802 registers */ - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); - (void)SPI_SEND(priv->spi, MAX11802_CMD_MODE_WR); - (void)SPI_SEND(priv->spi, MAX11802_MODE); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); - - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); - (void)SPI_SEND(priv->spi, MAX11802_CMD_AVG_WR); - (void)SPI_SEND(priv->spi, MAX11802_AVG); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); - - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); - (void)SPI_SEND(priv->spi, MAX11802_CMD_TIMING_WR); - (void)SPI_SEND(priv->spi, MAX11802_TIMING); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); - - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); - (void)SPI_SEND(priv->spi, MAX11802_CMD_DELAY_WR); - (void)SPI_SEND(priv->spi, MAX11802_DELAY); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); - - /* Test that the device access was successful. */ - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); - (void)SPI_SEND(priv->spi, MAX11802_CMD_MODE_RD); - ret = SPI_SEND(priv->spi, 0); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); - - /* Unlock the bus */ - max11802_unlock(spi); - - if (ret != MAX11802_MODE) - { - idbg("max11802 mode readback failed: %02x\n", ret); - goto errout_with_priv; - } - - /* Register the device as an input device */ - - (void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor); - ivdbg("Registering %s\n", devname); - - ret = register_driver(devname, &max11802_fops, 0666, priv); - if (ret < 0) - { - idbg("register_driver() failed: %d\n", ret); - goto errout_with_priv; - } - - /* If multiple MAX11802 devices are supported, then we will need to add - * this new instance to a list of device instances so that it can be - * found by the interrupt handler based on the recieved IRQ number. - */ - -#ifdef CONFIG_MAX11802_MULTIPLE - priv->flink = g_max11802list; - g_max11802list = priv; - irqrestore(flags); -#endif - - /* Schedule work to perform the initial sampling and to set the data - * availability conditions. - */ - - ret = work_queue(HPWORK, &priv->work, max11802_worker, priv, 0); - if (ret != 0) - { - idbg("Failed to queue work: %d\n", ret); - goto errout_with_priv; - } - - /* And return success (?) */ - - return OK; - -errout_with_priv: - sem_destroy(&priv->devsem); -#ifdef CONFIG_MAX11802_MULTIPLE - kfree(priv); -#endif - return ret; -} diff --git a/nuttx/drivers/input/max11802.h b/nuttx/drivers/input/max11802.h deleted file mode 100644 index b6beec0451..0000000000 --- a/nuttx/drivers/input/max11802.h +++ /dev/null @@ -1,167 +0,0 @@ -/******************************************************************************************** - * drivers/input/max11802.h - * - * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. - * Authors: Gregory Nutt - * Petteri Aimonen - * - * References: - * "Low-Power, Ultra-Small Resistive Touch-Screen Controllers - * with I2C/SPI Interface" Maxim IC, Rev 3, 10/2010 - * - * 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 __DRIVERS_INPUT_MAX11802_H -#define __DRIVERS_INPUT_MAX11802_H - -/******************************************************************************************** - * Included Files - ********************************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include -#include -#include - -/******************************************************************************************** - * Pre-Processor Definitions - ********************************************************************************************/ -/* Configuration ****************************************************************************/ - -/* MAX11802 Interfaces *********************************************************************/ - -/* LSB of register addresses specifies read (1) or write (0). */ -#define MAX11802_CMD_XPOSITION ((0x52 << 1) | 1) -#define MAX11802_CMD_YPOSITION ((0x54 << 1) | 1) -#define MAX11802_CMD_MEASUREXY (0x70 << 1) -#define MAX11802_CMD_MODE_WR (0x0B << 1) -#define MAX11802_CMD_MODE_RD ((0x0B << 1) | 1) -#define MAX11802_CMD_AVG_WR (0x03 << 1) -#define MAX11802_CMD_TIMING_WR (0x05 << 1) -#define MAX11802_CMD_DELAY_WR (0x06 << 1) - -/* Register values to set */ -#define MAX11802_MODE 0x0E -#define MAX11802_AVG 0x55 -#define MAX11802_TIMING 0x77 -#define MAX11802_DELAY 0x55 - -/* Driver support **************************************************************************/ -/* This format is used to construct the /dev/input[n] device driver path. It - * defined here so that it will be used consistently in all places. - */ - -#define DEV_FORMAT "/dev/input%d" -#define DEV_NAMELEN 16 - -/* Poll the pen position while the pen is down at this rate (50MS): */ - -#define MAX11802_WDOG_DELAY ((50 + (MSEC_PER_TICK-1))/ MSEC_PER_TICK) - -/******************************************************************************************** - * Public Types - ********************************************************************************************/ - -/* This describes the state of one contact */ - -enum max11802_contact_3 -{ - CONTACT_NONE = 0, /* No contact */ - CONTACT_DOWN, /* First contact */ - CONTACT_MOVE, /* Same contact, possibly different position */ - CONTACT_UP, /* Contact lost */ -}; - -/* This structure describes the results of one MAX11802 sample */ - -struct max11802_sample_s -{ - uint8_t id; /* Sampled touch point ID */ - uint8_t contact; /* Contact state (see enum ads7843e_contact_e) */ - bool valid; /* True: x,y contain valid, sampled data */ - uint16_t x; /* Measured X position */ - uint16_t y; /* Measured Y position */ -}; - -/* This structure describes the state of one MAX11802 driver instance */ - -struct max11802_dev_s -{ -#ifdef CONFIG_ADS7843E_MULTIPLE - FAR struct ads7843e_dev_s *flink; /* Supports a singly linked list of drivers */ -#endif - uint8_t nwaiters; /* Number of threads waiting for MAX11802 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 */ - - FAR struct max11802_config_s *config; /* Board configuration data */ - FAR struct spi_dev_s *spi; /* Saved SPI driver instance */ - struct work_s work; /* Supports the interrupt handling "bottom half" */ - struct max11802_sample_s sample; /* Last sampled touch point data */ - WDOG_ID wdog; /* Poll the position while the pen is down */ - - /* The following is a list if poll structures of threads waiting for - * driver events. The 'struct pollfd' reference for each open is also - * retained in the f_priv field of the 'struct file'. - */ - -#ifndef CONFIG_DISABLE_POLL - struct pollfd *fds[CONFIG_ADS7843E_NPOLLWAITERS]; -#endif -}; - -/******************************************************************************************** - * Public Function Prototypes - ********************************************************************************************/ - -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -#undef EXTERN -#ifdef __cplusplus -} -#endif - -#endif /* __DRIVERS_INPUT_ADS7843E_H */ diff --git a/nuttx/drivers/lcd/ug-2864ambag01.c b/nuttx/drivers/lcd/ug-2864ambag01.c deleted file mode 100644 index e133f39010..0000000000 --- a/nuttx/drivers/lcd/ug-2864ambag01.c +++ /dev/null @@ -1,1161 +0,0 @@ -/************************************************************************************** - * drivers/lcd/ug-2864ambag01.c - * Driver for Univision UG-2864AMBAG01 OLED display (wih SH1101A controller) in SPI - * mode - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * 1. Product Specification (Preliminary), Part Name: OEL Display Module, Part ID: - * UG-2864AMBAG01, Doc No: SASI-9015-A, Univision Technology Inc. - * 2. SH1101A, 132 X 64 Dot Matrix OLED/PLED, Preliminary Segment/Common Driver with - * Controller, Sino Wealth - * - * 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. - * - **************************************************************************************/ -/************************************************************************************** - * Device memory organization: - * - * +----------------------------+ - * | Column | - * --------+----+---+---+---+-...-+-----+ - * Page | 0 | 1 | 2 | 3 | ... | 131 | - * --------+----+---+---+---+-...-+-----+ - * Page 0 | D0 | X | | | | | - * | D1 | X | | | | | - * | D2 | X | | | | | - * | D3 | X | | | | | - * | D4 | X | | | | | - * | D5 | X | | | | | - * | D6 | X | | | | | - * | D7 | X | | | | | - * --------+----+---+---+---+-...-+-----+ - * Page 1 | | | | | | | - * --------+----+---+---+---+-...-+-----+ - * Page 2 | | | | | | | - * --------+----+---+---+---+-...-+-----+ - * Page 3 | | | | | | | - * --------+----+---+---+---+-...-+-----+ - * Page 4 | | | | | | | - * --------+----+---+---+---+-...-+-----+ - * Page 5 | | | | | | | - * --------+----+---+---+---+-...-+-----+ - * Page 6 | | | | | | | - * --------+----+---+---+---+-...-+-----+ - * Page 7 | | | | | | | - * --------+----+---+---+---+-...-+-----+ - * - * -----------------------------------+--------------------------------------- - * Landscape Display: | Reverse Landscape Display: - * --------+-----------------------+ | --------+---------------------------+ - * | Column | | | Column | - * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ - * Page 0 | 0 | 1 | 2 | | 131 | | Page 7 | 131 | 130 | 129 | | 0 | - * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ - * Page 1 | V | | Page 6 | ^ | - * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ - * Page 2 | V | | Page 5 | ^ | - * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ - * Page 3 | V | | Page 4 | ^ | - * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ - * Page 4 | V | | Page 3 | ^ | - * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ - * Page 5 | V | | Page 2 | ^ | - * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ - * Page 6 | V | | Page 1 | ^ | - * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ - * Page 7 | V | | Page 0 | ^ | - * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+ - * -----------------------------------+--------------------------------------- - * - * -----------------------------------+--------------------------------------- - * Portrait Display: | Reverse Portrait Display: - * -----------+---------------------+ | -----------+---------------------+ - * | Page | | | Page | - * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ - * Column 0 | 0 | 1 | 2 | | 7 | | Column 131 | 7 | 6 | 5 | | 0 | - * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ - * Column 1 | > > > > > | | Column 130 | | - * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ - * Column 2 | | | Column 129 | | - * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ - * ... | | | ... | | - * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ - * Column 131 | | | Column 0 | < < < < < | - * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+ - * -----------------------------------+---------------------------------------- - **************************************************************************************/ - -/************************************************************************************** - * Included Files - **************************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include - -#ifdef CONFIG_LCD_UG2864AMBAG01 - -/************************************************************************************** - * Pre-processor Definitions - **************************************************************************************/ -/* Configuration **********************************************************************/ -/* Limitations of the current configuration that I hope to fix someday */ - -#if CONFIG_UG2864AMBAG01_NINTERFACES != 1 -# warning "This implementation supports only a single OLED device" -# undef CONFIG_UG2864AMBAG01_NINTERFACES -# define CONFIG_UG2864AMBAG01_NINTERFACES 1 -#endif - -#if defined(CONFIG_LCD_PORTRAIT) || defined(CONFIG_LCD_RPORTRAIT) -# warning "No support yet for portrait modes" -# define CONFIG_LCD_LANDSCAPE 1 -# undef CONFIG_LCD_PORTRAIT -# undef CONFIG_LCD_RLANDSCAPE -# undef CONFIG_LCD_RPORTRAIT -#elif defined(CONFIG_LCD_RLANDSCAPE) -# warning "Reverse landscape mode is untested and, hence, probably buggy" -#endif - -/* SH1101A Commands *******************************************************************/ - -#define SH1101A_SETCOLL(ad) (0x00 | ((ad) & 0x0f)) /* Set Lower Column Address: (00h - 0fh) */ -#define SH1101A_SETCOLH(ad) (0x10 | ((ad) & 0x0f)) /* Set Higher Column Address: (10h - 1fh) */ -#define SH1101A_STARTLINE(ln) (0x40 | ((ln) & 0x3f)) /* Set Display Start Line: (40h - 7fh) */ -#define SH1101A_CONTRAST_MODE (0x81) /* Set Contrast Control Register: (Double Bytes Command) */ -# define SH1101A_CONTRAST(c) (c) -#define SH1101A_SEGREMAP(m) (0xa0 | ((m) & 0x01)) /* Set Segment Re-map: (a0h - a1h) */ -# define SH1101A_REMAPRIGHT SH1101A_SEGREMAP(0) /* Right rotation */ -# define SH1101A_REMAPPLEFT SH1101A_SEGREMAP(1) /* Left rotation */ -#define SH1101A_EDISPOFFON(s) (0xa4 | ((s) & 0x01)) /* Set Entire Display OFF/ON: (a4h - a5h) */ -# define SH1101A_EDISPOFF SH1101A_EDISPOFFON(0) /* Display off */ -# define SH1101A_EDISPON SH1101A_EDISPOFFON(1) /* Display on */ -#define SH1101A_NORMREV(s) (0xa6 | ((s) & 0x01)) /* Set Normal/Reverse Display: (a6h -a7h) */ -# define SH1101A_NORMAL SH1101A_NORMREV(0) /* Normal display */ -# define SH1101A_REVERSE SH1101A_NORMREV(1) /* Reverse display */ -#define SH1101A_MRATIO_MODE (0xa8) /* Set Multiplex Ration: (Double Bytes Command) */ -# define SH1101A_MRATIO(d) ((d) & 0x3f) -#define SH1101A_DCDC_MODE (0xad) /* Set DC-DC OFF/ON: (Double Bytes Command) */ -# define SH1101A_DCDC_OFF (0x8a) - # define SH1101A_DCDC_ON (0x8b) -#define SH1101A_DISPOFFON(s) (0xae | ((s) & 0x01)) /* Display OFF/ON: (aeh - afh) */ -# define SH1101A_DISPOFF SH1101A_DISPOFFON(0) /* Display off */ -# define SH1101A_DISPON SH1101A_DISPOFFON(1) /* Display on */ -#define SH1101A_PAGEADDR(a) (0xb0 | ((a) & 0x0f)) /* Set Page Address: (b0h - b7h) */ -#define SH1101A_SCANDIR(d) (0xc0 | ((d) & 0x08)) /* Set Common Output Scan Direction: (c0h - c8h) */ -# define SH1101A_SCANFROMCOM0 SH1101A_SCANDIR(0x00) /* Scan from COM[0] to COM[n-1]*/ -# define SH1101A_SCANTOCOM0 SH1101A_SCANDIR(0x08) /* Scan from COM[n-1] to COM[0] */ -#define SH1101A_DISPOFFS_MODE (0xd3) /* Set Display Offset: (Double Bytes Command) */ -# define SH1101A_DISPOFFS(o) ((o) & 0x3f) -#define SH1101A_CLKDIV_SET (0xd5) /* Set Display Clock Divide Ratio/Oscillator Frequency: (Double Bytes Command) */ -# define SH1101A_CLKDIV(f,d) ((((f) & 0x0f) << 4) | ((d) & 0x0f)) -#define SH1101A_CHRGPER_SET (0xd9) /* Set Dis-charge/Pre-charge Period: (Double Bytes Command) */ -# define SH1101A_CHRGPER(d,p) ((((d) & 0x0f) << 4) | ((p) & 0x0f)) -#define SH1101A_CMNPAD_CONFIG (0xda) /* Set Common pads hardware configuration: (Double Bytes Command) */ - #define SH1101A_CMNPAD(c) ((0x02) | ((c) & 0x10)) -#define SH1101A_VCOM_SET (0xdb) /* Set VCOM Deselect Level: (Double Bytes Command) */ -# define SH1101A_VCOM(v) (v) -#define SH1101A_RMWSTART (0xe0) /* Read-Modify-Write: (e0h) */ -#define SH1101A_NOP (0xe3) /* NOP: (e3h) */ -#define SH1101A_END (0xee) /* End: (eeh) */ - -#define SH1101A_WRDATA(d) (d) /* Write Display Data */ -#define SH1101A_STATUS_BUSY (0x80) /* Read Status */ -#define SH1101A_STATUS_ONOFF (0x40) -#define SH1101A_RDDATA(d) (d) /* Read Display Data */ - -/* Color Properties *******************************************************************/ -/* Display Resolution - * - * The SH1101A display controller can handle a resolution of 132x64. The UG-2864AMBAG01 - * on the base board is 128x64. - */ - -#define UG2864AMBAG01_DEV_XRES 128 /* Only 128 of 131 columns used */ -#define UG2864AMBAG01_DEV_YRES 64 /* 8 pages each 8 rows */ -#define UG2864AMBAG01_DEV_XOFFSET 2 /* Offset to logical column 0 */ -#define UG2864AMBAG01_DEV_PAGES 8 /* 8 pages */ - -#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) -# define UG2864AMBAG01_XRES UG2864AMBAG01_DEV_XRES -# define UG2864AMBAG01_YRES UG2864AMBAG01_DEV_YRES -#else -# define UG2864AMBAG01_XRES UG2864AMBAG01_DEV_YRES -# define UG2864AMBAG01_YRES UG2864AMBAG01_DEV_XRES -#endif - -/* Color depth and format */ - -#define UG2864AMBAG01_BPP 1 -#define UG2864AMBAG01_COLORFMT FB_FMT_Y1 - -/* Bytes per logical row and actual device row */ - -#define UG2864AMBAG01_XSTRIDE (UG2864AMBAG01_XRES >> 3) -#define UG2864AMBAG01_YSTRIDE (UG2864AMBAG01_YRES >> 3) - -/* Default contrast */ - -#define UG2864AMBAG01_CONTRAST (128) - -/* The size of the shadow frame buffer or one row buffer. - * - * Frame buffer size: 128 columns x 64 rows / 8 bits-per-pixel - * Row size: 128 columns x 8 rows-per-page / 8 bits-per-pixel - */ - -#define UG2864AMBAG01_FBSIZE (UG2864AMBAG01_XSTRIDE * UG2864AMBAG01_YRES) -#define UG2864AMBAG01_ROWSIZE (UG2864AMBAG01_XSTRIDE) - -/* Bit helpers */ - -#define LS_BIT (1 << 0) -#define MS_BIT (1 << 7) - -/* Debug ******************************************************************************/ - -#ifdef CONFIG_DEBUG_LCD -# define lcddbg(format, arg...) dbg(format, ##arg) -# define lcdvdbg(format, arg...) vdbg(format, ##arg) -#else -# define lcddbg(x...) -# define lcdvdbg(x...) -#endif - -/************************************************************************************** - * Private Type Definition - **************************************************************************************/ - -/* This structure describes the state of this driver */ - -struct ug2864ambag01_dev_s -{ - struct lcd_dev_s dev; /* Publically visible device structure */ - - /* Private LCD-specific information follows */ - - FAR struct spi_dev_s *spi; /* Cached SPI device reference */ - uint8_t contrast; /* Current contrast setting */ - bool on; /* true: display is on */ - - - /* The SH1101A does not support reading from the display memory in SPI mode. - * Since there is 1 BPP and access is byte-by-byte, it is necessary to keep - * a shadow copy of the framebuffer memory. At 128x64, this amounts to 1KB. - */ - - uint8_t fb[UG2864AMBAG01_FBSIZE]; -}; - -/************************************************************************************** - * Private Function Protototypes - **************************************************************************************/ - -/* Low-level SPI helpers */ - -#ifdef CONFIG_SPI_OWNBUS -static inline void ug2864ambag01_configspi(FAR struct spi_dev_s *spi); -# define ug2864ambag01_lock(spi) -# define ug2864ambag01_unlock(spi) -#else -# define ug2864ambag01_configspi(spi) -static void ug2864ambag01_lock(FAR struct spi_dev_s *spi); -static void ug2864ambag01_unlock(FAR struct spi_dev_s *spi); -#endif - -/* LCD Data Transfer Methods */ - -static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, - FAR const uint8_t *buffer, size_t npixels); -static int ug2864ambag01_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, - size_t npixels); - -/* LCD Configuration */ - -static int ug2864ambag01_getvideoinfo(FAR struct lcd_dev_s *dev, - FAR struct fb_videoinfo_s *vinfo); -static int ug2864ambag01_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno, - FAR struct lcd_planeinfo_s *pinfo); - -/* LCD RGB Mapping */ - -#ifdef CONFIG_FB_CMAP -# error "RGB color mapping not supported by this driver" -#endif - -/* Cursor Controls */ - -#ifdef CONFIG_FB_HWCURSOR -# error "Cursor control not supported by this driver" -#endif - -/* LCD Specific Controls */ - -static int ug2864ambag01_getpower(struct lcd_dev_s *dev); -static int ug2864ambag01_setpower(struct lcd_dev_s *dev, int power); -static int ug2864ambag01_getcontrast(struct lcd_dev_s *dev); -static int ug2864ambag01_setcontrast(struct lcd_dev_s *dev, unsigned int contrast); - -/************************************************************************************** - * Private Data - **************************************************************************************/ - -/* 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 - * (bpp * xres / 8). Actual alignment of the buffer must conform to the - * bitwidth of the underlying pixel type. - * - * If there are multiple planes, they may share the same working buffer - * because different planes will not be operate on concurrently. However, - * if there are multiple LCD devices, they must each have unique run buffers. - */ - -static uint8_t g_runbuffer[UG2864AMBAG01_ROWSIZE]; - -/* This structure describes the overall LCD video controller */ - -static const struct fb_videoinfo_s g_videoinfo = -{ - .fmt = UG2864AMBAG01_COLORFMT, /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */ - .xres = UG2864AMBAG01_XRES, /* Horizontal resolution in pixel columns */ - .yres = UG2864AMBAG01_YRES, /* Vertical resolution in pixel rows */ - .nplanes = 1, /* Number of color planes supported */ -}; - -/* This is the standard, NuttX Plane information object */ - -static const struct lcd_planeinfo_s g_planeinfo = -{ - .putrun = ug2864ambag01_putrun, /* Put a run into LCD memory */ - .getrun = ug2864ambag01_getrun, /* Get a run from LCD memory */ - .buffer = (uint8_t*)g_runbuffer, /* Run scratch buffer */ - .bpp = UG2864AMBAG01_BPP, /* Bits-per-pixel */ -}; - -/* This is the OLED driver instance (only a single device is supported for now) */ - -static struct ug2864ambag01_dev_s g_oleddev = -{ - .dev = - { - /* LCD Configuration */ - - .getvideoinfo = ug2864ambag01_getvideoinfo, - .getplaneinfo = ug2864ambag01_getplaneinfo, - - /* LCD RGB Mapping -- Not supported */ - /* Cursor Controls -- Not supported */ - - /* LCD Specific Controls */ - - .getpower = ug2864ambag01_getpower, - .setpower = ug2864ambag01_setpower, - .getcontrast = ug2864ambag01_getcontrast, - .setcontrast = ug2864ambag01_setcontrast, - }, -}; - -/************************************************************************************** - * Private Functions - **************************************************************************************/ - -/************************************************************************************** - * Name: ug2864ambag01_configspi - * - * Description: - * Configure the SPI for use with the UG-2864AMBAG01 - * - * Input Parameters: - * spi - Reference to the SPI driver structure - * - * Returned Value: - * None - * - * Assumptions: - * - **************************************************************************************/ - -#ifdef CONFIG_SPI_OWNBUS -static inline void ug2864ambag01_configspi(FAR struct spi_dev_s *spi) -{ - lcdvdbg("Mode: %d Bits: 8 Frequency: %d\n", - CONFIG_UG2864AMBAG01_SPIMODE, CONFIG_UG2864AMBAG01_FREQUENCY); - - /* Configure SPI for the UG-2864AMBAG01. But only if we own the SPI bus. Otherwise, - * don't bother because it might change. - */ - - SPI_SETMODE(spi, CONFIG_UG2864AMBAG01_SPIMODE); - SPI_SETBITS(spi, 8); - SPI_SETFREQUENCY(spi, CONFIG_UG2864AMBAG01_FREQUENCY) -} -#endif - -/************************************************************************************** - * Name: ug2864ambag01_lock - * - * Description: - * Select the SPI, locking and re-configuring if necessary - * - * Input Parameters: - * spi - Reference to the SPI driver structure - * - * Returned Value: - * None - * - * Assumptions: - * - **************************************************************************************/ - -#ifndef CONFIG_SPI_OWNBUS -static inline void ug2864ambag01_lock(FAR struct spi_dev_s *spi) -{ - /* Lock the SPI bus if there are multiple devices competing for the SPI bus. */ - - SPI_LOCK(spi, true); - - /* Now make sure that the SPI bus is configured for the UG-2864AMBAG01 (it - * might have gotten configured for a different device while unlocked) - */ - - SPI_SETMODE(spi, CONFIG_UG2864AMBAG01_SPIMODE); - SPI_SETBITS(spi, 8); - SPI_SETFREQUENCY(spi, CONFIG_UG2864AMBAG01_FREQUENCY); -} -#endif - -/************************************************************************************** - * Name: ug2864ambag01_unlock - * - * Description: - * De-select the SPI - * - * Input Parameters: - * spi - Reference to the SPI driver structure - * - * Returned Value: - * None - * - * Assumptions: - * - **************************************************************************************/ - -#ifndef CONFIG_SPI_OWNBUS -static inline void ug2864ambag01_unlock(FAR struct spi_dev_s *spi) -{ - /* De-select UG-2864AMBAG01 chip and relinquish the SPI bus. */ - - SPI_LOCK(spi, false); -} -#endif - -/************************************************************************************** - * Name: ug2864ambag01_putrun - * - * Description: - * This method can be used to write a partial raster line to the LCD. - * - * Input Parameters: - * row - Starting row to write to (range: 0 <= row < yres) - * col - Starting column to write to (range: 0 <= col <= xres-npixels) - * buffer - The buffer containing the run to be written to the LCD - * npixels - The number of pixels to write to the LCD - * (range: 0 < npixels <= xres-col) - * - **************************************************************************************/ - -#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) -static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, - size_t npixels) -{ - /* Because of this line of code, we will only be able to support a single UG device */ - - FAR struct ug2864ambag01_dev_s *priv = (FAR struct ug2864ambag01_dev_s *)&g_oleddev; - FAR uint8_t *fbptr; - FAR uint8_t *ptr; - uint8_t devcol; - uint8_t fbmask; - uint8_t page; - uint8_t usrmask; - int pixlen; - uint8_t i; - - lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); - DEBUGASSERT(buffer); - - /* Clip the run to the display */ - - pixlen = npixels; - if ((unsigned int)col + (unsigned int)pixlen > (unsigned int)UG2864AMBAG01_XRES) - { - pixlen = (int)UG2864AMBAG01_XRES - (int)col; - } - - /* Verify that some portion of the run remains on the display */ - - if (pixlen <= 0 || row > UG2864AMBAG01_YRES) - { - return OK; - } - - /* Perform coordinate conversion for reverse landscape mode */ - -#ifdef CONFIG_LCD_RLANDSCAPE - row = (UG2864AMBAG01_YRES-1) - row; - col = (UG2864AMBAG01_XRES-1) - col; -#endif - - /* Get the page number. The range of 64 lines is divided up into eight - * pages of 8 lines each. - */ - - page = row >> 3; - - /* Update the shadow frame buffer memory. First determine the pixel - * position in the frame buffer memory. Pixels are organized like - * this: - * - * --------+---+---+---+---+-...-+-----+ - * Segment | 0 | 1 | 2 | 3 | ... | 131 | - * --------+---+---+---+---+-...-+-----+ - * D0 | | X | | | | | - * D1 | | X | | | | | - * D2 | | X | | | | | - * D3 | | X | | | | | - * D4 | | X | | | | | - * D5 | | X | | | | | - * D6 | | X | | | | | - * D7 | | X | | | | | - * --------+---+---+---+---+-...-+-----+ - * - * So, in order to draw a white, horizontal line, at row 45. we - * would have to modify all of the bytes in page 45/8 = 5. We - * would have to set bit 45%8 = 5 in every byte in the page. - */ - - fbmask = 1 << (row & 7); - fbptr = &priv->fb[page * UG2864AMBAG01_XRES + col]; -#ifdef CONFIG_LCD_RLANDSCAPE - ptr = fbptr + pixlen - 1; -#else - ptr = fbptr; -#endif -#ifdef CONFIG_NX_PACKEDMSFIRST - usrmask = MS_BIT; -#else - usrmask = LS_BIT; -#endif - - for (i = 0; i < pixlen; i++) - { - /* Set or clear the corresponding bit */ - -#ifdef CONFIG_LCD_RLANDSCAPE - if ((*buffer & usrmask) != 0) - { - *ptr-- |= fbmask; - } - else - { - *ptr-- &= ~fbmask; - } -#else - if ((*buffer & usrmask) != 0) - { - *ptr++ |= fbmask; - } - else - { - *ptr++ &= ~fbmask; - } -#endif - - /* Inc/Decrement to the next source pixel */ - -#ifdef CONFIG_NX_PACKEDMSFIRST - if (usrmask == LS_BIT) - { - buffer++; - usrmask = MS_BIT; - } - else - { - usrmask >>= 1; - } -#else - if (usrmask == MS_BIT) - { - buffer++; - usrmask = LS_BIT; - } - else - { - usrmask <<= 1; - } -#endif - } - - /* Offset the column position to account for smaller horizontal - * display range. - */ - - devcol = col + UG2864AMBAG01_DEV_XOFFSET; - - /* Lock and select device */ - - ug2864ambag01_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); - - /* Select command transfer */ - - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); - - /* Set the starting position for the run */ - /* Set the column address to the XOFFSET value */ - - SPI_SEND(priv->spi, SH1101A_SETCOLL(devcol & 0x0f)); - SPI_SEND(priv->spi, SH1101A_SETCOLH(devcol >> 4)); - - /* Set the page address */ - - SPI_SEND(priv->spi, SH1101A_PAGEADDR(page)); - - /* Select data transfer */ - - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, false); - - /* Then transfer all of the data */ - - (void)SPI_SNDBLOCK(priv->spi, fbptr, pixlen); - - /* De-select and unlock the device */ - - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); - ug2864ambag01_unlock(priv->spi); - return OK; -} -#else -# error "Configuration not implemented" -#endif - -/************************************************************************************** - * Name: ug2864ambag01_getrun - * - * Description: - * This method can be used to read a partial raster line from the LCD: - * - * Description: - * This method can be used to write a partial raster line to the LCD. - * - * row - Starting row to read from (range: 0 <= row < yres) - * col - Starting column to read read (range: 0 <= col <= xres-npixels) - * buffer - The buffer in which to return the run read from the LCD - * npixels - The number of pixels to read from the LCD - * (range: 0 < npixels <= xres-col) - * - **************************************************************************************/ - -#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) -static int ug2864ambag01_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, - size_t npixels) -{ - /* Because of this line of code, we will only be able to support a single UG device */ - - FAR struct ug2864ambag01_dev_s *priv = &g_oleddev; - FAR uint8_t *fbptr; - uint8_t page; - uint8_t fbmask; - uint8_t usrmask; - int pixlen; - uint8_t i; - - lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); - DEBUGASSERT(buffer); - - /* Clip the run to the display */ - - pixlen = npixels; - if ((unsigned int)col + (unsigned int)pixlen > (unsigned int)UG2864AMBAG01_XRES) - { - pixlen = (int)UG2864AMBAG01_XRES - (int)col; - } - - /* Verify that some portion of the run is actually the display */ - - if (pixlen <= 0 || row > UG2864AMBAG01_YRES) - { - return -EINVAL; - } - - /* Perform coordinate conversion for reverse landscape mode */ - -#ifdef CONFIG_LCD_RLANDSCAPE - row = (UG2864AMBAG01_YRES-1) - row; - col = (UG2864AMBAG01_XRES-1) - col; -#endif - - /* Then transfer the display data from the shadow frame buffer memory */ - /* Get the page number. The range of 64 lines is divided up into eight - * pages of 8 lines each. - */ - - page = row >> 3; - - /* Update the shadow frame buffer memory. First determine the pixel - * position in the frame buffer memory. Pixels are organized like - * this: - * - * --------+---+---+---+---+-...-+-----+ - * Segment | 0 | 1 | 2 | 3 | ... | 131 | - * --------+---+---+---+---+-...-+-----+ - * D0 | | X | | | | | - * D1 | | X | | | | | - * D2 | | X | | | | | - * D3 | | X | | | | | - * D4 | | X | | | | | - * D5 | | X | | | | | - * D6 | | X | | | | | - * D7 | | X | | | | | - * --------+---+---+---+---+-...-+-----+ - * - * So, in order to draw a white, horizontal line, at row 45. we - * would have to modify all of the bytes in page 45/8 = 5. We - * would have to set bit 45%8 = 5 in every byte in the page. - */ - - fbmask = 1 << (row & 7); -#ifdef CONFIG_LCD_RLANDSCAPE - fbptr = &priv->fb[page * (UG2864AMBAG01_XRES-1) + col + pixlen]; -#else - fbptr = &priv->fb[page * UG2864AMBAG01_XRES + col]; -#endif -#ifdef CONFIG_NX_PACKEDMSFIRST - usrmask = MS_BIT; -#else - usrmask = LS_BIT; -#endif - - *buffer = 0; - for (i = 0; i < pixlen; i++) - { - /* Set or clear the corresponding bit */ - -#ifdef CONFIG_LCD_RLANDSCAPE - uint8_t byte = *fbptr--; -#else - uint8_t byte = *fbptr++; -#endif - if ((byte & fbmask) != 0) - { - *buffer |= usrmask; - } - - /* Inc/Decrement to the next destination pixel. Hmmmm. It looks like - * this logic could write past the end of the user buffer. Revisit - * this! - */ - -#ifdef CONFIG_NX_PACKEDMSFIRST - if (usrmask == LS_BIT) - { - buffer++; - *buffer = 0; - usrmask = MS_BIT; - } - else - { - usrmask >>= 1; - } -#else - if (usrmask == MS_BIT) - { - buffer++; - *buffer = 0; - usrmask = LS_BIT; - } - else - { - usrmask <<= 1; - } -#endif - } - - return OK; -} -#else -# error "Configuration not implemented" -#endif - -/************************************************************************************** - * Name: ug2864ambag01_getvideoinfo - * - * Description: - * Get information about the LCD video controller configuration. - * - **************************************************************************************/ - -static int ug2864ambag01_getvideoinfo(FAR struct lcd_dev_s *dev, - FAR struct fb_videoinfo_s *vinfo) -{ - DEBUGASSERT(dev && vinfo); - lcdvdbg("fmt: %d xres: %d yres: %d nplanes: %d\n", - g_videoinfo.fmt, g_videoinfo.xres, g_videoinfo.yres, g_videoinfo.nplanes); - memcpy(vinfo, &g_videoinfo, sizeof(struct fb_videoinfo_s)); - return OK; -} - -/************************************************************************************** - * Name: ug2864ambag01_getplaneinfo - * - * Description: - * Get information about the configuration of each LCD color plane. - * - **************************************************************************************/ - -static int ug2864ambag01_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno, - FAR struct lcd_planeinfo_s *pinfo) -{ - DEBUGASSERT(pinfo && planeno == 0); - lcdvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp); - memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s)); - return OK; -} - -/************************************************************************************** - * Name: ug2864ambag01_getpower - * - * Description: - * Get the LCD panel power status (0: full off - CONFIG_LCD_MAXPOWER: full on. On - * backlit LCDs, this setting may correspond to the backlight setting. - * - **************************************************************************************/ - -static int ug2864ambag01_getpower(FAR struct lcd_dev_s *dev) -{ - FAR struct ug2864ambag01_dev_s *priv = (FAR struct ug2864ambag01_dev_s *)dev; - DEBUGASSERT(priv); - - lcdvdbg("power: %s\n", priv->on ? "ON" : "OFF"); - return priv->on ? CONFIG_LCD_MAXPOWER : 0; -} - -/************************************************************************************** - * Name: ug2864ambag01_setpower - * - * Description: - * Enable/disable LCD panel power (0: full off - CONFIG_LCD_MAXPOWER: full on). On - * backlit LCDs, this setting may correspond to the backlight setting. - * - **************************************************************************************/ - -static int ug2864ambag01_setpower(struct lcd_dev_s *dev, int power) -{ - struct ug2864ambag01_dev_s *priv = (struct ug2864ambag01_dev_s *)dev; - DEBUGASSERT(priv && (unsigned)power <= CONFIG_LCD_MAXPOWER && priv->spi); - - lcdvdbg("power: %d [%d]\n", power, priv->on ? CONFIG_LCD_MAXPOWER : 0); - - /* Lock and select device */ - - ug2864ambag01_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); - - if (power <= 0) - { - /* Turn the display off */ - - (void)SPI_SEND(priv->spi, SH1101A_DISPOFF); - priv->on = false; - } - else - { - /* Turn the display on */ - - (void)SPI_SEND(priv->spi, SH1101A_DISPON); /* Display on, dim mode */ - priv->on = true; - } - - /* De-select and unlock the device */ - - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); - ug2864ambag01_unlock(priv->spi); - return OK; -} - -/************************************************************************************** - * Name: ug2864ambag01_getcontrast - * - * Description: - * Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST). - * - **************************************************************************************/ - -static int ug2864ambag01_getcontrast(struct lcd_dev_s *dev) -{ - struct ug2864ambag01_dev_s *priv = (struct ug2864ambag01_dev_s *)dev; - DEBUGASSERT(priv); - - lcdvdbg("contrast: %d\n", priv->contrast); - return priv->contrast; -} - -/************************************************************************************** - * Name: ug2864ambag01_setcontrast - * - * Description: - * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST). - * - **************************************************************************************/ - -static int ug2864ambag01_setcontrast(struct lcd_dev_s *dev, unsigned int contrast) -{ - struct ug2864ambag01_dev_s *priv = (struct ug2864ambag01_dev_s *)dev; - unsigned int scaled; - - lcdvdbg("contrast: %d\n", contrast); - DEBUGASSERT(priv); - - /* Verify the contrast value */ - -#ifdef CONFIG_DEBUG - if (contrast > CONFIG_LCD_MAXCONTRAST) - { - return -EINVAL; - } -#endif - - /* Scale contrast: newcontrast = 255 * contrast / CONFIG_LCD_MAXCONTRAST - * Where contrast is in the range {1,255} - */ - -#if CONFIG_LCD_MAXCONTRAST != 255 - newcontrast = ((contrast << 8) - 1) / CONFIG_LCD_MAXCONTRAST; -#else - scaled = contrast; -#endif - - /* Lock and select device */ - - ug2864ambag01_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); - - /* Select command transfer */ - - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); - - /* Set the contrast */ - - (void)SPI_SEND(priv->spi, SH1101A_CONTRAST_MODE); /* Set contrast control register */ - (void)SPI_SEND(priv->spi, SH1101A_CONTRAST(scaled)); /* Data 1: Set 1 of 256 contrast steps */ - priv->contrast = contrast; - - /* De-select and unlock the device */ - - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); - ug2864ambag01_unlock(priv->spi); - return OK; -} - -/************************************************************************************** - * Public Functions - **************************************************************************************/ - -/************************************************************************************** - * Name: ug2864ambag01_initialize - * - * Description: - * Initialize the UG-2864AMBAG01 video hardware. The initial state of the - * OLED is fully initialized, display memory cleared, and the OLED ready - * to use, but with the power setting at 0 (full off == sleep mode). - * - * Input Parameters: - * - * spi - A reference to the SPI driver instance. - * devno - A value in the range of 0 through CONFIG_UG2864AMBAG01_NINTERFACES-1. - * This allows support for multiple OLED devices. - * - * Returned Value: - * - * On success, this function returns a reference to the LCD object for - * the specified OLED. NULL is returned on any failure. - * - **************************************************************************************/ - -FAR struct lcd_dev_s *ug2864ambag01_initialize(FAR struct spi_dev_s *spi, unsigned int devno) -{ - FAR struct ug2864ambag01_dev_s *priv = &g_oleddev; - - lcdvdbg("Initializing\n"); - DEBUGASSERT(spi && devno == 0); - - /* Save the reference to the SPI device */ - - priv->spi = spi; - - /* Configure the SPI */ - - ug2864ambag01_configspi(spi) - - /* Lock and select device */ - - ug2864ambag01_lock(priv->spi); - SPI_SELECT(spi, SPIDEV_DISPLAY, true); - - /* Select command transfer */ - - SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); - - /* Configure the device */ - - SPI_SEND(spi, SH1101A_DISPOFF); /* Display off */ - SPI_SEND(spi, SH1101A_SETCOLL(0)); /* Set lower column address */ - SPI_SEND(spi, SH1101A_SETCOLH(0)); /* Set higher column address */ - SPI_SEND(spi, SH1101A_STARTLINE(0)); /* Set display start line */ - SPI_SEND(spi, SH1101A_PAGEADDR(0)); /* Set page address */ - SPI_SEND(spi, SH1101A_CONTRAST_MODE); /* Contrast control */ - SPI_SEND(spi ,UG2864AMBAG01_CONTRAST); /* Default contrast */ - SPI_SEND(spi, SH1101A_REMAPPLEFT); /* Set segment remap left */ - SPI_SEND(spi, SH1101A_EDISPOFF); /* Normal display */ - SPI_SEND(spi, SH1101A_NORMAL); /* Normal (un-reversed) display mode */ - SPI_SEND(spi, SH1101A_MRATIO_MODE); /* Multiplex ratio */ - SPI_SEND(spi, SH1101A_MRATIO(0x3f)); /* Duty = 1/64 */ - SPI_SEND(spi, SH1101A_SCANTOCOM0); /* Com scan direction: Scan from COM[n-1] to COM[0] */ - SPI_SEND(spi, SH1101A_DISPOFFS_MODE); /* Set display offset */ - SPI_SEND(spi, SH1101A_DISPOFFS(0)); - SPI_SEND(spi, SH1101A_CLKDIV_SET); /* Set clock divider */ - SPI_SEND(spi, SH1101A_CLKDIV(0,0)); - SPI_SEND(spi, SH1101A_CMNPAD_CONFIG); /* Set common pads */ - SPI_SEND(spi, SH1101A_CMNPAD(0x10)); - SPI_SEND(spi, SH1101A_VCOM_SET); - SPI_SEND(spi, SH1101A_VCOM(0x40)); - SPI_SEND(spi, SH1101A_DCDC_MODE); /* DC/DC control mode: on */ - SPI_SEND(spi, SH1101A_DCDC_ON); - SPI_SEND(spi, SH1101A_DISPON); /* display ON */ - - /* De-select and unlock the device */ - - SPI_SELECT(spi, SPIDEV_DISPLAY, false); - ug2864ambag01_unlock(priv->spi); - - /* Clear the display */ - - up_mdelay(100); - ug2864ambag01_fill(&priv->dev, UG_Y1_BLACK); - return &priv->dev; -} - -/************************************************************************************** - * Name: ug2864ambag01_fill - * - * Description: - * This non-standard method can be used to clear the entire display by writing one - * color to the display. This is much faster than writing a series of runs. - * - * Input Parameters: - * priv - Reference to private driver structure - * - * Assumptions: - * Caller has selected the OLED section. - * - **************************************************************************************/ - -void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color) -{ - FAR struct ug2864ambag01_dev_s *priv = &g_oleddev; - unsigned int page; - - /* Make an 8-bit version of the selected color */ - - if (color & 1) - { - color = 0xff; - } - else - { - color = 0; - } - - /* Initialize the framebuffer */ - - memset(priv->fb, color, UG2864AMBAG01_FBSIZE); - - /* Lock and select device */ - - ug2864ambag01_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); - - /* Visit each page */ - - for (page = 0; page < UG2864AMBAG01_DEV_PAGES; page++) - { - /* Select command transfer */ - - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); - - /* Set the column address to the XOFFSET value */ - - SPI_SEND(priv->spi, SH1101A_SETCOLL(UG2864AMBAG01_DEV_XOFFSET)); - SPI_SEND(priv->spi, SH1101A_SETCOLH(0)); - - /* Set the page address */ - - SPI_SEND(priv->spi, SH1101A_PAGEADDR(page)); - - /* Select data transfer */ - - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, false); - - /* Transfer one page of the selected color */ - - (void)SPI_SNDBLOCK(priv->spi, &priv->fb[page * UG2864AMBAG01_XRES], - UG2864AMBAG01_XRES); - } - - /* De-select and unlock the device */ - - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); - ug2864ambag01_unlock(priv->spi); -} - -#endif /* CONFIG_LCD_UG2864AMBAG01 */ diff --git a/nuttx/include/elf32.h b/nuttx/include/elf32.h deleted file mode 100644 index e16ae0091a..0000000000 --- a/nuttx/include/elf32.h +++ /dev/null @@ -1,352 +0,0 @@ -/**************************************************************************** - * include/elf32.h - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Reference: System V Application Binary Interface, Edition 4.1, March 18, - * 1997, The Santa Cruz Operation, Inc. - * - * 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 __INCLUDE_ELF32_H -#define __INCLUDE_ELF32_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Values for Elf32_Ehdr::e_type */ - -#define ET_NONE 0 /* No file type */ -#define ET_REL 1 /* Relocatable file */ -#define ET_EXEC 2 /* Executable file */ -#define ET_DYN 3 /* Shared object file */ -#define ET_CORE 4 /* Core file */ -#define ET_LOPROC 0xff00 /* Processor-specific */ -#define ET_HIPROC 0xffff /* Processor-specific */ - -/* Values for Elf32_Ehdr::e_machine (most of this were not included in the - * original SCO document but have been gleaned from elsewhere). - */ - -#define EM_NONE 0 /* No machine */ -#define EM_M32 1 /* AT&T WE 32100 */ -#define EM_SPARC 2 /* SPARC */ -#define EM_386 3 /* Intel 80386 */ -#define EM_68K 4 /* Motorola 68000 */ -#define EM_88K 5 /* Motorola 88000 */ -#define EM_486 6 /* Intel 486+ */ -#define EM_860 7 /* Intel 80860 */ -#define EM_MIPS 8 /* MIPS R3000 Big-Endian */ -#define EM_MIPS_RS4_BE 10 /* MIPS R4000 Big-Endian */ -#define EM_PARISC 15 /* HPPA */ -#define EM_SPARC32PLUS 18 /* Sun's "v8plus" */ -#define EM_PPC 20 /* PowerPC */ -#define EM_PPC64 21 /* PowerPC64 */ -#define EM_ARM 40 /* ARM */ -#define EM_SH 42 /* SuperH */ -#define EM_SPARCV9 43 /* SPARC v9 64-bit */ -#define EM_IA_64 50 /* HP/Intel IA-64 */ -#define EM_X86_64 62 /* AMD x86-64 */ -#define EM_S390 22 /* IBM S/390 */ -#define EM_CRIS 76 /* Axis Communications 32-bit embedded processor */ -#define EM_V850 87 /* NEC v850 */ -#define EM_M32R 88 /* Renesas M32R */ -#define EM_H8_300 46 -#define EM_ALPHA 0x9026 -#define EM_CYGNUS_V850 0x9080 -#define EM_CYGNUS_M32R 0x9041 -#define EM_S390_OLD 0xa390 -#define EM_FRV 0x5441 - -/* Values for Elf32_Ehdr::e_version */ - -#define EV_NONE 0 /* Invalid version */ -#define EV_CURRENT 1 /* The current version */ - -/* Ehe ELF identifier */ - -#define EI_MAG0 0 /* File identification */ -#define EI_MAG1 1 /* " " " " */ -#define EI_MAG2 2 /* " " " " */ -#define EI_MAG3 3 /* " " " " */ -#define EI_CLASS 4 /* File class */ -#define EI_DATA 5 /* Data encoding */ -#define EI_VERSION 6 /* File version */ -#define EI_PAD 7 /* Start of padding bytes */ -#define EI_NIDENT 16 /* Size of eident[] */ - -#define EI_MAGIC_SIZE 4 -#define EI_MAGIC {0x7f, 'E', 'L', 'F'} - -/* Values for EI_CLASS */ - -#define ELFCLASSNONE 0 /* Invalid class */ -#define ELFCLASS32 1 /* 32-bit objects */ -#define ELFCLASS64 2 /* 64-bit objects */ - -/* Values for EI_DATA */ - -#define ELFDATANONE 0 /* Invalid data encoding */ -#define ELFDATA2LSB 1 /* Least significant byte occupying the lowest address */ -#define ELFDATA2MSB 2 /* Most significant byte occupying the lowest address */ - -/* Figure 4-7: Special Section Indexes */ - -#define SHN_UNDEF 0 -#define SHN_LORESERVE 0xff00 -#define SHN_LOPROC 0xff00 -#define SHN_HIPROC 0xff1f -#define SHN_ABS 0xfff1 -#define SHN_COMMON 0xfff2 -#define SHN_HIRESERVE 0xffff - -/* Figure 4-9: Section Types, sh_type */ - -#define SHT_NULL 0 -#define SHT_PROGBITS 1 -#define SHT_SYMTAB 2 -#define SHT_STRTAB 3 -#define SHT_RELA 4 -#define SHT_HASH 5 -#define SHT_DYNAMIC 6 -#define SHT_NOTE 7 -#define SHT_NOBITS 8 -#define SHT_REL 9 -#define SHT_SHLIB 10 -#define SHT_DYNSYM 11 -#define SHT_LOPROC 0x70000000 -#define SHT_HIPROC 0x7fffffff -#define SHT_LOUSER 0x80000000 -#define SHT_HIUSER 0xffffffff - -/* Figure 4-11: Section Attribute Flags, sh_flags */ - -#define SHF_WRITE 1 -#define SHF_ALLOC 2 -#define SHF_EXECINSTR 4 -#define SHF_MASKPROC 0xf0000000 - -/* Definitions for Elf32_Sym::st_info */ - -#define ELF32_ST_BIND(i) ((i) >> 4) -#define ELF32_ST_TYPE(i) ((i) & 0xf) -#define ELF32_ST_INFO(b,t) (((b) << 4) | ((t) & 0xf)) - -/* Figure 4-16: Symbol Binding, ELF32_ST_BIND */ - -#define STB_LOCAL 0 -#define STB_GLOBAL 1 -#define STB_WEAK 2 -#define STB_LOPROC 13 -#define STB_HIPROC 15 - -/* Figure 4-17: Symbol Types, ELF32_ST_TYPE */ - -#define STT_NOTYPE 0 -#define STT_OBJECT 1 -#define STT_FUNC 2 -#define STT_SECTION 3 -#define STT_FILE 4 -#define STT_LOPROC 13 -#define STT_HIPROC 15 - -/* Definitions for Elf32_Rel*::r_info */ - -#define ELF32_R_SYM(i) ((i) >> 8) -#define ELF32_R_TYPE(i) ((i) & 0xff) -#define ELF32_R_INFO(s,t) (((s)<< 8) | ((t) & 0xff)) - -/* Figure 5-2: Segment Types, p_type */ - -#define PT_NULL 0 -#define PT_LOAD 1 -#define PT_DYNAMIC 2 -#define PT_INTERP 3 -#define PT_NOTE 4 -#define PT_SHLIB 5 -#define PT_PHDR 6 -#define PT_LOPROC 0x70000000 -#define PT_HIPROC 0x7fffffff - -/* Figure 5-3: Segment Flag Bits, p_flags */ - -#define PF_X 1 /* Execute */ -#define PF_W 2 /* Write */ -#define PF_R 4 /* Read */ -#define PF_MASKPROC 0xf0000000 /* Unspecified */ - -/* Figure 5-10: Dynamic Array Tags, d_tag */ - -#define DT_NULL 0 /* d_un=ignored */ -#define DT_NEEDED 1 /* d_un=d_val */ -#define DT_PLTRELSZ 2 /* d_un=d_val */ -#define DT_PLTGOT 3 /* d_un=d_ptr */ -#define DT_HASH 4 /* d_un=d_ptr */ -#define DT_STRTAB 5 /* d_un=d_ptr */ -#define DT_SYMTAB 6 /* d_un=d_ptr */ -#define DT_RELA 7 /* d_un=d_ptr */ -#define DT_RELASZ 8 /* d_un=d_val */ -#define DT_RELAENT 9 /* d_un=d_val */ -#define DT_STRSZ 10 /* d_un=d_val */ -#define DT_SYMENT 11 /* d_un=d_val */ -#define DT_INIT 12 /* d_un=d_ptr */ -#define DT_FINI 13 /* d_un=d_ptr */ -#define DT_SONAME 14 /* d_un=d_val */ -#define DT_RPATH 15 /* d_un=d_val */ -#define DT_SYMBOLIC 16 /* d_un=ignored */ -#define DT_REL 17 /* d_un=d_ptr */ -#define DT_RELSZ 18 /* d_un=d_val */ -#define DT_RELENT 19 /* d_un=d_val */ -#define DT_PLTREL 20 /* d_un=d_val */ -#define DT_DEBUG 21 /* d_un=d_ptr */ -#define DT_TEXTREL 22 /* d_un=ignored */ -#define DT_JMPREL 23 /* d_un=d_ptr */ -#define DT_BINDNOW 24 /* d_un=ignored */ -#define DT_LOPROC 0x70000000 /* d_un=unspecified */ -#define DT_HIPROC 0x7fffffff /* d_un= unspecified */ - -/**************************************************************************** - * Public Type Definitions - ****************************************************************************/ - -/* Figure 4.2: 32-Bit Data Types */ - -typedef uint32_t Elf32_Addr; /* Unsigned program address */ -typedef uint16_t Elf32_Half; /* Unsigned medium integer */ -typedef uint32_t Elf32_Off; /* Unsigned file offset */ -typedef int32_t Elf32_Sword; /* Signed large integer */ -typedef uint32_t Elf32_Word; /* Unsigned large integer */ - -/* Figure 4-3: ELF Header */ - -typedef struct -{ - unsigned char e_ident[EI_NIDENT]; - Elf32_Half e_type; - Elf32_Half e_machine; - Elf32_Word e_version; - Elf32_Addr e_entry; - Elf32_Off e_phoff; - Elf32_Off e_shoff; - Elf32_Word e_flags; - Elf32_Half e_ehsize; - Elf32_Half e_phentsize; - Elf32_Half e_phnum; - Elf32_Half e_shentsize; - Elf32_Half e_shnum; - Elf32_Half e_shstrndx; -} Elf32_Ehdr; - -/* Figure 4-8: Section Header */ - -typedef struct -{ - Elf32_Word sh_name; - Elf32_Word sh_type; - Elf32_Word sh_flags; - Elf32_Addr sh_addr; - Elf32_Off sh_offset; - Elf32_Word sh_size; - Elf32_Word sh_link; - Elf32_Word sh_info; - Elf32_Word sh_addralign; - Elf32_Word sh_entsize; -} Elf32_Shdr; - -/* Figure 4-15: Symbol Table Entry */ - -typedef struct -{ - Elf32_Word st_name; - Elf32_Addr st_value; - Elf32_Word st_size; - unsigned char st_info; - unsigned char st_other; - Elf32_Half st_shndx; -} Elf32_Sym; - -/* Figure 4-19: Relocation Entries */ - -typedef struct -{ - Elf32_Addr r_offset; - Elf32_Word r_info; -} Elf32_Rel; - -typedef struct -{ - Elf32_Addr r_offset; - Elf32_Word r_info; - Elf32_Sword r_addend; -} Elf32_Rela; - -/* Figure 5-1: Program Header */ - -typedef struct -{ - Elf32_Word p_type; - Elf32_Off p_offset; - Elf32_Addr p_vaddr; - Elf32_Addr p_paddr; - Elf32_Word p_filesz; - Elf32_Word p_memsz; - Elf32_Word p_flags; - Elf32_Word p_align; -} Elf32_Phdr; - -/* Figure 5-9: Dynamic Structure */ - -typedef struct -{ - Elf32_Sword d_tag; - union - { - Elf32_Word d_val; - Elf32_Addr d_ptr; - } d_un; -} Elf32_Dyn; - -//extern Elf32_Dyn _DYNAMIC[] ; - -#endif /* __INCLUDE_ELF32_H */ diff --git a/nuttx/include/nuttx/binfmt/binfmt.h b/nuttx/include/nuttx/binfmt/binfmt.h deleted file mode 100644 index 49ab37264f..0000000000 --- a/nuttx/include/nuttx/binfmt/binfmt.h +++ /dev/null @@ -1,226 +0,0 @@ -/**************************************************************************** - * include/nuttx/binfmt/binfmt.h - * - * 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. - * - ****************************************************************************/ - -#ifndef __INCLUDE_NUTTX_BINFMT_BINFMT_H -#define __INCLUDE_NUTTX_BINFMT_BINFMT_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define BINFMT_NALLOC 3 - -/**************************************************************************** - * Public Types - ****************************************************************************/ -/* The type of one C++ constructor or destructor */ - -typedef FAR void (*binfmt_ctor_t)(void); -typedef FAR void (*binfmt_dtor_t)(void); - -/* This describes the file to be loaded */ - -struct symtab_s; -struct binary_s -{ - /* Information provided to the loader to load and bind a module */ - - FAR const char *filename; /* Full path to the binary to be loaded */ - FAR const char **argv; /* Argument list */ - FAR const struct symtab_s *exports; /* Table of exported symbols */ - int nexports; /* The number of symbols in exports[] */ - - /* Information provided from the loader (if successful) describing the - * resources used by the loaded module. - */ - - main_t entrypt; /* Entry point into a program module */ - FAR void *mapped; /* Memory-mapped, address space */ - FAR void *alloc[BINFMT_NALLOC]; /* Allocated address spaces */ -#ifdef CONFIG_BINFMT_CONSTRUCTORS - FAR binfmt_ctor_t *ctors; /* Pointer to a list of constructors */ - FAR binfmt_dtor_t *dtors; /* Pointer to a list of destructors */ - uint16_t nctors; /* Number of constructors in the list */ - uint16_t ndtors; /* Number of destructors in the list */ -#endif - size_t mapsize; /* Size of the mapped address region (needed for munmap) */ - size_t stacksize; /* Size of the stack in bytes (unallocated) */ -}; - -/* This describes one binary format handler */ - -struct binfmt_s -{ - FAR struct binfmt_s *next; /* Supports a singly-linked list */ - int (*load)(FAR struct binary_s *bin); /* Verify and load binary into memory */ -}; - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Name: register_binfmt - * - * Description: - * Register a loader for a binary format - * - * Returned Value: - * This is a NuttX internal function so it follows the convention that - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int register_binfmt(FAR struct binfmt_s *binfmt); - -/**************************************************************************** - * Name: unregister_binfmt - * - * Description: - * Register a loader for a binary format - * - * Returned Value: - * This is a NuttX internal function so it follows the convention that - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int unregister_binfmt(FAR struct binfmt_s *binfmt); - -/**************************************************************************** - * Name: load_module - * - * Description: - * Load a module into memory, bind it to an exported symbol take, and - * prep the module for execution. - * - * Returned Value: - * This is an end-user function, so it follows the normal convention: - * Returns 0 (OK) on success. On failure, it returns -1 (ERROR) with - * errno set appropriately. - * - ****************************************************************************/ - -EXTERN int load_module(FAR struct binary_s *bin); - -/**************************************************************************** - * Name: unload_module - * - * Description: - * Unload a (non-executing) module from memory. If the module has - * been started (via exec_module) and has not exited, calling this will - * be fatal. - * - * However, this function must be called after the module exist. How - * this is done is up to your logic. Perhaps you register it to be - * called by on_exit()? - * - * Returned Value: - * This is a NuttX internal function so it follows the convention that - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int unload_module(FAR const struct binary_s *bin); - -/**************************************************************************** - * Name: exec_module - * - * Description: - * Execute a module that has been loaded into memory by load_module(). - * - * Returned Value: - * This is an end-user function, so it follows the normal convention: - * Returns the PID of the exec'ed module. On failure, it.returns - * -1 (ERROR) and sets errno appropriately. - * - ****************************************************************************/ - -EXTERN int exec_module(FAR const struct binary_s *bin, int priority); - -/**************************************************************************** - * Name: exec - * - * Description: - * This is a convenience function that wraps load_ and exec_module into - * one call. - * - * Input Parameter: - * filename - Fulll path to the binary to be loaded - * argv - Argument list - * exports - Table of exported symbols - * nexports - The number of symbols in exports - * - * Returned Value: - * This is an end-user function, so it follows the normal convention: - * Returns the PID of the exec'ed module. On failure, it.returns - * -1 (ERROR) and sets errno appropriately. - * - ****************************************************************************/ - -EXTERN int exec(FAR const char *filename, FAR const char **argv, - FAR const struct symtab_s *exports, int nexports); - -#undef EXTERN -#if defined(__cplusplus) -} -#endif - -#endif /* __INCLUDE_NUTTX_BINFMT_BINFMT_H */ - diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h deleted file mode 100644 index 432e57f0f8..0000000000 --- a/nuttx/include/nuttx/binfmt/elf.h +++ /dev/null @@ -1,302 +0,0 @@ -/**************************************************************************** - * include/nuttx/binfmt/elf.h - * - * 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. - * - ****************************************************************************/ - -#ifndef __INCLUDE_NUTTX_BINFMT_ELF_H -#define __INCLUDE_NUTTX_BINFMT_ELF_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include -#include -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ -/* Configuration ************************************************************/ - -#ifndef CONFIG_ELF_ALIGN_LOG2 -# define CONFIG_ELF_ALIGN_LOG2 2 -#endif - -/* Allocation array size and indices */ - -#define LIBELF_ELF_ALLOC 0 -#ifdef CONFIG_BINFMT_CONSTRUCTORS -# define LIBELF_CTORS_ALLOC 1 -# define LIBELF_CTPRS_ALLOC 2 -# define LIBELF_NALLOC 3 -#else -# define LIBELF_NALLOC 1 -#endif - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/* This struct provides a desciption of the currently loaded instantiation - * of an ELF binary. - */ - -struct elf_loadinfo_s -{ - /* The alloc[] array holds memory that persists after the ELF module has - * been loaded. - */ - - uintptr_t elfalloc; /* Memory allocated when ELF file was loaded */ - size_t elfsize; /* Size of the ELF memory allocation */ - off_t filelen; /* Length of the entire ELF file */ - Elf32_Ehdr ehdr; /* Buffered ELF file header */ - FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */ - uint8_t *iobuffer; /* File I/O buffer */ -#ifdef CONFIG_BINFMT_CONSTRUCTORS - FAR void *ctoralloc; /* Memory allocated for ctors */ - FAR void *dtoralloc; /* Memory allocated dtors */ - FAR binfmt_ctor_t *ctors; /* Pointer to a list of constructors */ - FAR binfmt_dtor_t *dtors; /* Pointer to a list of destructors */ - uint16_t nctors; /* Number of constructors */ - uint16_t ndtors; /* Number of destructors */ -#endif - uint16_t symtabidx; /* Symbol table section index */ - uint16_t strtabidx; /* String table section index */ - uint16_t buflen; /* size of iobuffer[] */ - int filfd; /* Descriptor for the file being loaded */ -}; - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -/**************************************************************************** - * These are APIs exported by libelf (but are used only by the binfmt logic): - ****************************************************************************/ - -/**************************************************************************** - * Name: elf_init - * - * Description: - * This function is called to configure the library to process an ELF - * program binary. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int elf_init(FAR const char *filename, - FAR struct elf_loadinfo_s *loadinfo); - -/**************************************************************************** - * Name: elf_uninit - * - * Description: - * Releases any resources committed by elf_init(). This essentially - * undoes the actions of elf_init. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int elf_uninit(FAR struct elf_loadinfo_s *loadinfo); - -/**************************************************************************** - * Name: elf_load - * - * Description: - * Loads the binary into memory, allocating memory, performing relocations - * and inializing the data and bss segments. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int elf_load(FAR struct elf_loadinfo_s *loadinfo); - -/**************************************************************************** - * Name: elf_bind - * - * Description: - * Bind the imported symbol names in the loaded module described by - * 'loadinfo' using the exported symbol values provided by 'symtab'. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -struct symtab_s; -EXTERN int elf_bind(FAR struct elf_loadinfo_s *loadinfo, - FAR const struct symtab_s *exports, int nexports); - -/**************************************************************************** - * Name: elf_unload - * - * Description: - * This function unloads the object from memory. This essentially - * undoes the actions of elf_load. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int elf_unload(struct elf_loadinfo_s *loadinfo); - -/**************************************************************************** - * These are APIs used outside of binfmt by NuttX: - ****************************************************************************/ -/**************************************************************************** - * Name: elf_initialize - * - * Description: - * ELF support is built unconditionally. However, it order to - * use this binary format, this function must be called during system - * format in order to register the ELF binary format. - * - * Returned Value: - * This is a NuttX internal function so it follows the convention that - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int elf_initialize(void); - -/**************************************************************************** - * Name: elf_uninitialize - * - * Description: - * Unregister the ELF binary loader - * - * Returned Value: - * None - * - ****************************************************************************/ - -EXTERN void elf_uninitialize(void); - -/**************************************************************************** - * These are APIs must be provided by architecture-specific logic: - ****************************************************************************/ -/**************************************************************************** - * Name: arch_checkarch - * - * Description: - * Given the ELF header in 'hdr', verify that the ELF file is appropriate - * for the current, configured architecture. Every architecture that uses - * the ELF loader must provide this function. - * - * Input Parameters: - * hdr - The ELF header read from the ELF file. - * - * Returned Value: - * True if the architecture supports this ELF file. - * - ****************************************************************************/ - -EXTERN bool arch_checkarch(FAR const Elf32_Ehdr *hdr); - -/**************************************************************************** - * Name: arch_relocate and arch_relocateadd - * - * Description: - * Perform on architecture-specific ELF relocation. Every architecture - * that uses the ELF loader must provide this function. - * - * Input Parameters: - * rel - The relocation type - * sym - The ELF symbol structure containing the fully resolved value. - * addr - The address that requires the relocation. - * - * Returned Value: - * Zero (OK) if the relocation was successful. Otherwise, a negated errno - * value indicating the cause of the relocation failure. - * - ****************************************************************************/ - -EXTERN int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym, - uintptr_t addr); -EXTERN int arch_relocateadd(FAR const Elf32_Rela *rel, - FAR const Elf32_Sym *sym, uintptr_t addr); - -/**************************************************************************** - * Name: arch_flushicache - * - * Description: - * Flush the instruction cache. - * - * Input Parameters: - * addr - Start address to flush - * len - Number of bytes to flush - * - * Returned Value: - * True if the architecture supports this ELF file. - * - ****************************************************************************/ - -#ifdef CONFIG_ELF_ICACHE -EXTERN bool arch_flushicache(FAR void *addr, size_t len); -#endif - -#undef EXTERN -#if defined(__cplusplus) -} -#endif - -#endif /* __INCLUDE_NUTTX_BINFMT_ELF_H */ diff --git a/nuttx/include/nuttx/binfmt/nxflat.h b/nuttx/include/nuttx/binfmt/nxflat.h deleted file mode 100644 index 89e28fbcc1..0000000000 --- a/nuttx/include/nuttx/binfmt/nxflat.h +++ /dev/null @@ -1,264 +0,0 @@ -/**************************************************************************** - * include/nuttx/binfmt/nxflat.h - * - * 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. - * - ****************************************************************************/ - -#ifndef __INCLUDE_NUTTX_BINFMT_NXFLAT_H -#define __INCLUDE_NUTTX_BINFMT_NXFLAT_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/* This struct provides a desciption of the currently loaded instantiation - * of an nxflat binary. - */ - -struct nxflat_loadinfo_s -{ - /* Instruction Space (ISpace): This region contains the nxflat file header - * plus everything from the text section. Ideally, will have only one mmap'ed - * text section instance in the system for each module. - */ - - uint32_t ispace; /* Address where hdr/text is loaded */ - uint32_t entryoffs; /* Offset from ispace to entry point */ - uint32_t isize; /* Size of ispace. */ - - /* Data Space (DSpace): This region contains all information that in referenced - * as data (other than the stack which is separately allocated). There will be - * a unique instance of DSpace (and stack) for each instance of a process. - */ - - struct dspace_s *dspace; /* Allocated D-Space (data/bss/etc) */ - uint32_t datasize; /* Size of data segment in dspace */ - uint32_t bsssize; /* Size of bss segment in dspace */ - uint32_t stacksize; /* Size of stack (not allocated) */ - uint32_t dsize; /* Size of dspace (may be large than parts) */ - - /* This is temporary memory where relocation records will be loaded. */ - - uint32_t relocstart; /* Start of array of struct flat_reloc */ - uint16_t reloccount; /* Number of elements in reloc array */ - - /* File descriptors */ - - int filfd; /* Descriptor for the file being loaded */ - - /* This is a copy of the NXFLAT header (still in network order) */ - - struct nxflat_hdr_s header; -}; - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -/**************************************************************************** - * These are APIs exported by libnxflat (and may be used outside of NuttX): - ****************************************************************************/ - -/**************************************************************************** - * Name: nxflat_verifyheader - * - * Description: - * Given the header from a possible NXFLAT executable, verify that it is - * an NXFLAT executable. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header); - -/**************************************************************************** - * Name: nxflat_init - * - * Description: - * This function is called to configure the library to process an NXFLAT - * program binary. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int nxflat_init(const char *filename, - struct nxflat_loadinfo_s *loadinfo); - -/**************************************************************************** - * Name: nxflat_uninit - * - * Description: - * Releases any resources committed by nxflat_init(). This essentially - * undoes the actions of nxflat_init. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo); - -/**************************************************************************** - * Name: nxflat_load - * - * Description: - * Loads the binary specified by nxflat_init into memory, mapping - * the I-space executable regions, allocating the D-Space region, - * and inializing the data segment (relocation information is - * temporarily loaded into the BSS region. BSS will be cleared - * by nxflat_bind() after the relocation data has been processed). - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int nxflat_load(struct nxflat_loadinfo_s *loadinfo); - -/**************************************************************************** - * Name: nxflat_read - * - * Description: - * Read 'readsize' bytes from the object file at 'offset' - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, - int readsize, int offset); - -/**************************************************************************** - * Name: nxflat_bind - * - * Description: - * Bind the imported symbol names in the loaded module described by - * 'loadinfo' using the exported symbol values provided by 'symtab' - * After binding the module, clear the BSS region (which held the relocation - * data) in preparation for execution. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -struct symtab_s; -EXTERN int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo, - FAR const struct symtab_s *exports, int nexports); - -/**************************************************************************** - * Name: nxflat_unload - * - * Description: - * This function unloads the object from memory. This essentially - * undoes the actions of nxflat_load. - * - * Returned Value: - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int nxflat_unload(struct nxflat_loadinfo_s *loadinfo); - -/**************************************************************************** - * These are APIs used internally only by NuttX: - ****************************************************************************/ -/**************************************************************************** - * Name: nxflat_initialize - * - * Description: - * NXFLAT support is built unconditionally. However, it order to - * use this binary format, this function must be called during system - * format in order to register the NXFLAT binary format. - * - * Returned Value: - * This is a NuttX internal function so it follows the convention that - * 0 (OK) is returned on success and a negated errno is returned on - * failure. - * - ****************************************************************************/ - -EXTERN int nxflat_initialize(void); - -/**************************************************************************** - * Name: nxflat_uninitialize - * - * Description: - * Unregister the NXFLAT binary loader - * - * Returned Value: - * None - * - ****************************************************************************/ - -EXTERN void nxflat_uninitialize(void); - -#undef EXTERN -#if defined(__cplusplus) -} -#endif - -#endif /* __INCLUDE_NUTTX_BINFMT_NXFLAT_H */ diff --git a/nuttx/include/nuttx/binfmt/symtab.h b/nuttx/include/nuttx/binfmt/symtab.h deleted file mode 100644 index 346c6099fd..0000000000 --- a/nuttx/include/nuttx/binfmt/symtab.h +++ /dev/null @@ -1,163 +0,0 @@ -/**************************************************************************** - * include/nuttx/binfmt/symtab.h - * - * 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. - * - ****************************************************************************/ - -#ifndef __INCLUDE_NUTTX_BINFMT_SYMTAB_H -#define __INCLUDE_NUTTX_BINFMT_SYMTAB_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/* struct symbtab_s describes one entry in the symbol table. A symbol table - * is a fixed size array of struct symtab_s. The information is intentionally - * minimal and supports only: - * - * 1. Function pointers as sym_values. Of other kinds of values need to be - * supported, then typing information would also need to be included in - * the structure. - * - * 2. Fixed size arrays. There is no explicit provisional for dyanamically - * adding or removing entries from the symbol table (realloc might be - * used for that purpose if needed). The intention is to support only - * fixed size arrays completely defined at compilation or link time. - */ - -struct symtab_s -{ - FAR const char *sym_name; /* A pointer to the symbol name string */ - FAR const void *sym_value; /* The value associated witht the string */ -}; - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -/**************************************************************************** - * Name: symtab_findbyname - * - * Description: - * Find the symbol in the symbol table with the matching name. - * This version assumes that table is not ordered with respect to symbol - * name and, hence, access time will be linear with respect to nsyms. - * - * Returned Value: - * A reference to the symbol table entry if an entry with the matching - * name is found; NULL is returned if the entry is not found. - * - ****************************************************************************/ - -EXTERN FAR const struct symtab_s * -symtab_findbyname(FAR const struct symtab_s *symtab, - FAR const char *name, int nsyms); - -/**************************************************************************** - * Name: symtab_findorderedbyname - * - * Description: - * Find the symbol in the symbol table with the matching name. - * This version assumes that table ordered with respect to symbol name. - * - * Returned Value: - * A reference to the symbol table entry if an entry with the matching - * name is found; NULL is returned if the entry is not found. - * - ****************************************************************************/ - -EXTERN FAR const struct symtab_s * -symtab_findorderedbyname(FAR const struct symtab_s *symtab, - FAR const char *name, int nsyms); - -/**************************************************************************** - * Name: symtab_findbyvalue - * - * Description: - * Find the symbol in the symbol table whose value closest (but not greater - * than), the provided value. This version assumes that table is not ordered - * with respect to symbol name and, hence, access time will be linear with - * respect to nsyms. - * - * Returned Value: - * A reference to the symbol table entry if an entry with the matching - * name is found; NULL is returned if the entry is not found. - * - ****************************************************************************/ - -EXTERN FAR const struct symtab_s * -symtab_findbyvalue(FAR const struct symtab_s *symtab, - FAR void *value, int nsyms); - -/**************************************************************************** - * Name: symtab_findorderedbyvalue - * - * Description: - * Find the symbol in the symbol table whose value closest (but not greater - * than), the provided value. This version assumes that table is ordered - * with respect to symbol name. - * - * Returned Value: - * A reference to the symbol table entry if an entry with the matching - * name is found; NULL is returned if the entry is not found. - * - ****************************************************************************/ - -EXTERN FAR const struct symtab_s * -symtab_findorderedbyvalue(FAR const struct symtab_s *symtab, - FAR void *value, int nsyms); - -#undef EXTERN -#if defined(__cplusplus) -} -#endif - -#endif /* __INCLUDE_NUTTX_BINFMT_SYMTAB_H */ - diff --git a/nuttx/include/nuttx/float.h b/nuttx/include/nuttx/float.h deleted file mode 100644 index a8e4aa28b5..0000000000 --- a/nuttx/include/nuttx/float.h +++ /dev/null @@ -1,225 +0,0 @@ -/**************************************************************************** - * include/nuttx/float.h - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Reference: http://pubs.opengroup.org/onlinepubs/009695399/basedefs/float.h.html - * - * 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 __INCLUDE_NUTTX_FLOAT_H -#define __INCLUDE_NUTTX_FLOAT_H - -/* TODO: These values could vary with architectures toolchains. This - * logic should be move at least to the include/arch directory. - */ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Radix of exponent representation, b. */ - -#define FLT_RADIX 2 - -/* Number of base-FLT_RADIX digits in the floating-point significand, p. */ - -#define FLT_MANT_DIG 24 - -#if CONFIG_HAVE_DOUBLE -# define DBL_MANT_DIG 53 -#else -# define DBL_MANT_DIG FLT_MANT_DIG -#endif - -#ifdef CONFIG_HAVE_LONG_DOUBLE -# define LDBL_MANT_DIG DBL_MANT_DIG /* FIX ME */ -#else -# define LDBL_MANT_DIG DBL_MANT_DIG -#endif - -/* Number of decimal digits, n, such that any floating-point number in the - * widest supported floating type with pmax radix b digits can be rounded - * to a floating-point number with n decimal digits and back again without - * change to the value. - */ - -#define DECIMAL_DIG 10 - -/* Number of decimal digits, q, such that any floating-point number with q - * decimal digits can be rounded into a floating-point number with p radix - * b digits and back again without change to the q decimal digits. - */ - -#define FLT_DIG 6 - -#if CONFIG_HAVE_DOUBLE -# define DBL_DIG 15 /* 10 */ -#else -# define DBL_DIG FLT_DIG -#endif - -#ifdef CONFIG_HAVE_LONG_DOUBLE -# define LDBL_DIG DBL_DIG /* FIX ME */ -#else -# define LDBL_DIG DBL_DIG -#endif - -/* Minimum negative integer such that FLT_RADIX raised to that power minus - * 1 is a normalized floating-point number, emin. - */ - -#define FLT_MIN_EXP (-125) - -#if CONFIG_HAVE_DOUBLE -# define DBL_MIN_EXP (-1021) -#else -# define DBL_MIN_EXP FLT_MIN_EXP -#endif - -#ifdef CONFIG_HAVE_LONG_DOUBLE -# define LDBL_MIN_EXP DBL_MIN_EXP /* FIX ME */ -#else -# define LDBL_MIN_EXP DBL_MIN_EXP -#endif - -/* inimum negative integer such that 10 raised to that power is in the range - * of normalized floating-point numbers. - */ - -#define FLT_MIN_10_EXP (-37) - -#if CONFIG_HAVE_DOUBLE -# define DBL_MIN_10_EXP (-307) /* -37 */ -#else -# define DBL_MIN_10_EXP FLT_MIN_10_EXP -#endif - -#ifdef CONFIG_HAVE_LONG_DOUBLE -# define LDBL_MIN_10_EXP DBL_MIN_10_EXP /* FIX ME */ -#else -# define LDBL_MIN_10_EXP DBL_MIN_10_EXP -#endif - -/* Maximum integer such that FLT_RADIX raised to that power minus 1 is a - * representable finite floating-point number, emax. - */ - -#define FLT_MAX_EXP 128 - -#if CONFIG_HAVE_DOUBLE -# define DBL_MAX_EXP 1024 -#else -# define DBL_MAX_EXP FLT_MAX_EXP -#endif - -#ifdef CONFIG_HAVE_LONG_DOUBLE -# define LDBL_MAX_EXP DBL_MAX_EXP /* FIX ME */ -#else -# define LDBL_MAX_EXP DBL_MAX_EXP -#endif - -/* Maximum integer such that 10 raised to that power is in the range of - * representable finite floating-point numbers. - */ - -#define FLT_MAX_10_EXP 38 /* 37 */ - -#if CONFIG_HAVE_DOUBLE -# define DBL_MAX_10_EXP 308 /* 37 */ -#else -# define DBL_MAX_10_EXP FLT_MAX_10_EXP -#endif - -#ifdef CONFIG_HAVE_LONG_DOUBLE -# define LDBL_MAX_10_EXP DBL_MAX_10_EXP /* FIX ME */ -#else -# define LDBL_MAX_10_EXP DBL_MAX_10_EXP -#endif - -/* Maximum representable finite floating-point number. */ - -#define FLT_MAX 3.40282347e+38F /* 1E+37 */ - -#if CONFIG_HAVE_DOUBLE -# define DBL_MAX 1.7976931348623157e+308 /* 1E+37 */ -#else -# define DBL_MAX FLT_MAX -#endif - -#ifdef CONFIG_HAVE_LONG_DOUBLE -# define LDBL_MAX DBL_MAX /* FIX ME */ -#else -# define LDBL_MAX DBL_MAX -#endif - -/* The difference between 1 and the least value greater than 1 that is - * representable in the given floating-point type, b1-p. - */ - -#define FLT_EPSILON 1.1920929e-07F /* 1E-5 */ - -#if CONFIG_HAVE_DOUBLE -# define DBL_EPSILON 2.2204460492503131e-16 /* 1E-9 */ -#else -# define DBL_EPSILON FLT_EPSILON -#endif - -#ifdef CONFIG_HAVE_LONG_DOUBLE -# define LDBL_EPSILON DBL_EPSILON /* FIX ME */ -#else -# define LDBL_EPSILON DBL_EPSILON -#endif - -/* Minimum normalized positive floating-point number, bemin -1. */ - -#define FLT_MIN 1.17549435e-38F /* 1E-37 */ - -#if CONFIG_HAVE_DOUBLE -#define DBL_MIN 2.2250738585072014e-308 /* 1E-37 */ -#else -# define DBL_MIN FLT_MIN -#endif - -#ifdef CONFIG_HAVE_LONG_DOUBLE -# define LDBL_MIN DBL_MIN /* FIX ME */ -#else -# define LDBL_MIN DBL_MIN -#endif - -#endif /* __INCLUDE_NUTTX_FLOAT_H */ diff --git a/nuttx/include/nuttx/input/max11802.h b/nuttx/include/nuttx/input/max11802.h deleted file mode 100644 index 3d03bdd115..0000000000 --- a/nuttx/include/nuttx/input/max11802.h +++ /dev/null @@ -1,175 +0,0 @@ -/**************************************************************************** - * include/nuttx/input/max11802.h - * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. - * Authors: Gregory Nutt - * Petteri Aimonen - * - * References: - * "Low-Power, Ultra-Small Resistive Touch-Screen Controllers - * with I2C/SPI Interface" Maxim IC, Rev 3, 10/2010 - * - * 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 __INCLUDE_NUTTX_INPUT_MAX11802_H -#define __INCLUDE_NUTTX_INPUT_MAX11802_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include -#include - -#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_MAX11802) - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ -/* Configuration ************************************************************/ -/* SPI Frequency. Default: 100KHz */ - -#ifndef CONFIG_MAX11802_FREQUENCY -# define CONFIG_MAX11802_FREQUENCY 100000 -#endif - -/* Maximum number of threads than can be waiting for POLL events */ - -#ifndef CONFIG_MAX11802_NPOLLWAITERS -# define CONFIG_MAX11802_NPOLLWAITERS 2 -#endif - -#ifndef CONFIG_MAX11802_SPIMODE -# define CONFIG_MAX11802_SPIMODE SPIDEV_MODE0 -#endif - -/* Thresholds */ - -#ifndef CONFIG_MAX11802_THRESHX -# define CONFIG_MAX11802_THRESHX 12 -#endif - -#ifndef CONFIG_MAX11802_THRESHY -# define CONFIG_MAX11802_THRESHY 12 -#endif - -/* Check for some required settings. This can save the user a lot of time - * in getting the right configuration. - */ - -#ifdef CONFIG_DISABLE_SIGNALS -# error "Signals are required. CONFIG_DISABLE_SIGNALS must not be selected." -#endif - -#ifndef CONFIG_SCHED_WORKQUEUE -# error "Work queue support required. CONFIG_SCHED_WORKQUEUE must be selected." -#endif - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/* A reference to a structure of this type must be passed to the MAX11802 - * driver. This structure provides information about the configuration - * of the MAX11802 and provides some board-specific hooks. - * - * Memory for this structure is provided by the caller. It is not copied - * by the driver and is presumed to persist while the driver is active. The - * memory must be writable because, under certain circumstances, the driver - * may modify frequency or X plate resistance values. - */ - -struct max11802_config_s -{ - /* Device characterization */ - - uint32_t frequency; /* SPI frequency */ - - /* IRQ/GPIO access callbacks. These operations all hidden behind - * callbacks to isolate the MAX11802 driver from differences in GPIO - * interrupt handling by varying boards and MCUs. If possible, - * interrupts should be configured on both rising and falling edges - * so that contact and loss-of-contact events can be detected. - * - * attach - Attach the MAX11802 interrupt handler to the GPIO interrupt - * enable - Enable or disable the GPIO interrupt - * clear - Acknowledge/clear any pending GPIO interrupt - * pendown - Return the state of the pen down GPIO input - */ - - int (*attach)(FAR struct max11802_config_s *state, xcpt_t isr); - void (*enable)(FAR struct max11802_config_s *state, bool enable); - void (*clear)(FAR struct max11802_config_s *state); - bool (*pendown)(FAR struct max11802_config_s *state); -}; - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -/**************************************************************************** - * Name: max11802_register - * - * Description: - * Configure the MAX11802 to use the provided SPI device instance. This - * will register the driver as /dev/inputN where N is the minor device - * number - * - * Input Parameters: - * spi - An SPI driver instance - * config - Persistent board configuration data - * minor - The input device minor number - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -EXTERN int max11802_register(FAR struct spi_dev_s *spi, - FAR struct max11802_config_s *config, - int minor); - -#undef EXTERN -#ifdef __cplusplus -} -#endif - -#endif /* CONFIG_INPUT && CONFIG_INPUT_MAX11802 */ -#endif /* __INCLUDE_NUTTX_INPUT_MAX11802_H */ diff --git a/nuttx/include/nuttx/lcd/ug-2864ambag01.h b/nuttx/include/nuttx/lcd/ug-2864ambag01.h deleted file mode 100644 index deb5689812..0000000000 --- a/nuttx/include/nuttx/lcd/ug-2864ambag01.h +++ /dev/null @@ -1,245 +0,0 @@ -/************************************************************************************** - * include/nuttx/lcd/ug-2864ambag01.h - * Driver for Univision UG-2864AMBAG01 OLED display (wih SH1101A controller) in SPI - * mode - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * 1. Product Specification (Preliminary), Part Name: OEL Display Module, Part ID: - * UG-2864AMBAG01, Doc No: SASI-9015-A, Univision Technology Inc. - * 2. SH1101A, 132 X 64 Dot Matrix OLED/PLED, Preliminary Segment/Common Driver with - * Controller, Sino Wealth - * - * 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 __INCLUDE_NUTTX_UG_8264AMBAG01_H -#define __INCLUDE_NUTTX_UG_8264AMBAG01_H - -/************************************************************************************** - * Included Files - **************************************************************************************/ - -#include - -#include - -#include - -#ifdef CONFIG_LCD_UG2864AMBAG01 - -/************************************************************************************** - * Pre-processor Definitions - **************************************************************************************/ -/* Configuration **********************************************************************/ -/* UG-2864AMBAG01 Configuration Settings: - * - * CONFIG_UG2864AMBAG01_SPIMODE - Controls the SPI mode - * CONFIG_UG2864AMBAG01_FREQUENCY - Define to use a different bus frequency - * CONFIG_UG2864AMBAG01_NINTERFACES - Specifies the number of physical UG-2864AMBAG01 - * devices that will be supported. - * - * Required LCD driver settings: - * - * CONFIG_LCD_UG28AMBAG01 - Enable UG-2864AMBAG01 support - * CONFIG_LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. - * CONFIG_LCD_MAXPOWER must be 1 - * - * Option LCD driver settings: - * CONFIG_LCD_LANDSCAPE, CONFIG_LCD_PORTRAIT, CONFIG_LCD_RLANDSCAPE, and - * CONFIG_LCD_RPORTRAIT - Display orientation. - * - * Required SPI driver settings: - * CONFIG_SPI_CMDDATA - Include support for cmd/data selection. - */ - -/* SPI Interface - * - * "The serial interface consists of serial clock SCL, serial data SI, A0 and - * CS . SI is shifted into an 8-bit shift register on every rising edge of - * SCL in the order of D7, D6, … and D0. A0 is sampled on every eighth clock - * and the data byte in the shift register is written to the display data RAM - * or command register in the same clock." - * - * MODE 3: - * Clock polarity: High (CPOL=1) - * Clock phase: Sample on trailing (rising edge) (CPHA 1) - */ - -#ifndef CONFIG_UG2864AMBAG01_SPIMODE -# define CONFIG_UG2864AMBAG01_SPIMODE SPIDEV_MODE3 -#endif - -/* "This module determines whether the input data is interpreted as data or - * command. When A0 = “H”, the inputs at D7 - D0 are interpreted as data and be - * written to display RAM. When A0 = “L”, the inputs at D7 - D0 are interpreted - * as command, they will be decoded and be written to the corresponding command - * registers. - */ - -#ifndef CONFIG_SPI_CMDDATA -# error "CONFIG_SPI_CMDDATA must be defined in your NuttX configuration" -#endif - -/* CONFIG_UG2864AMBAG01_NINTERFACES determines the number of physical interfaces - * that will be supported. - */ - -#ifndef CONFIG_UG2864AMBAG01_NINTERFACES -# define CONFIG_UG2864AMBAG01_NINTERFACES 1 -#endif - -/* Check contrast selection */ - -#if !defined(CONFIG_LCD_MAXCONTRAST) -# define CONFIG_LCD_MAXCONTRAST 255 -#endif - -#if CONFIG_LCD_MAXCONTRAST <= 0|| CONFIG_LCD_MAXCONTRAST > 255 -# error "CONFIG_LCD_MAXCONTRAST exceeds supported maximum" -#endif - -#if CONFIG_LCD_MAXCONTRAST < 255 -# warning "Optimal setting of CONFIG_LCD_MAXCONTRAST is 255" -#endif - -/* Check power setting */ - -#if !defined(CONFIG_LCD_MAXPOWER) -# define CONFIG_LCD_MAXPOWER 1 -#endif - -#if CONFIG_LCD_MAXPOWER != 1 -# warning "CONFIG_LCD_MAXPOWER exceeds supported maximum" -# undef CONFIG_LCD_MAXPOWER -# define CONFIG_LCD_MAXPOWER 1 -#endif - -/* Color is 1bpp monochrome with leftmost column contained in bits 0 */ - -#ifdef CONFIG_NX_DISABLE_1BPP -# warning "1 bit-per-pixel support needed" -#endif - -/* Orientation */ - -#if defined(CONFIG_LCD_LANDSCAPE) -# undef CONFIG_LCD_PORTRAIT -# undef CONFIG_LCD_RLANDSCAPE -# undef CONFIG_LCD_RPORTRAIT -#elif defined(CONFIG_LCD_PORTRAIT) -# undef CONFIG_LCD_LANDSCAPE -# undef CONFIG_LCD_RLANDSCAPE -# undef CONFIG_LCD_RPORTRAIT -#elif defined(CONFIG_LCD_RLANDSCAPE) -# undef CONFIG_LCD_LANDSCAPE -# undef CONFIG_LCD_PORTRAIT -# undef CONFIG_LCD_RPORTRAIT -#elif defined(CONFIG_LCD_RPORTRAIT) -# undef CONFIG_LCD_LANDSCAPE -# undef CONFIG_LCD_PORTRAIT -# undef CONFIG_LCD_RLANDSCAPE -#else -# define CONFIG_LCD_LANDSCAPE 1 -# warning "Assuming landscape orientation" -#endif - -/* Some important "colors" */ - -#define UG_Y1_BLACK 0 -#define UG_Y1_WHITE 1 - -/************************************************************************************** - * Public Types - **************************************************************************************/ - -/************************************************************************************** - * Public Data - **************************************************************************************/ - -#ifdef __cplusplus -extern "C" -{ -#endif - -/************************************************************************************** - * Public Function Prototypes - **************************************************************************************/ - -/************************************************************************************** - * Name: ug2864ambag01_initialize - * - * Description: - * Initialize the UG-2864AMBAG01 video hardware. The initial state of the - * OLED is fully initialized, display memory cleared, and the OLED ready - * to use, but with the power setting at 0 (full off == sleep mode). - * - * Input Parameters: - * - * spi - A reference to the SPI driver instance. - * devno - A value in the range of 0 through CONFIG_UG2864AMBAG01_NINTERFACES-1. - * This allows support for multiple OLED devices. - * - * Returned Value: - * - * On success, this function returns a reference to the LCD object for - * the specified OLED. NULL is returned on any failure. - * - **************************************************************************************/ - -struct lcd_dev_s; /* See include/nuttx/lcd/lcd.h */ -struct spi_dev_s; /* See include/nuttx/spi.h */ -FAR struct lcd_dev_s *ug2864ambag01_initialize(FAR struct spi_dev_s *spi, - unsigned int devno); - -/************************************************************************************************ - * Name: ug2864ambag01_fill - * - * Description: - * This non-standard method can be used to clear the entire display by writing one - * color to the display. This is much faster than writing a series of runs. - * - * Input Parameters: - * priv - Reference to private driver structure - * - * Assumptions: - * Caller has selected the OLED section. - * - **************************************************************************************/ - -void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color); - -#ifdef __cplusplus -} -#endif - -#endif /* CONFIG_LCD_UG2864AMBAG01 */ -#endif /* __INCLUDE_NUTTX_UG_8264AMBAG01_H */ diff --git a/nuttx/libc/Kconfig b/nuttx/libc/Kconfig deleted file mode 100644 index bd470be7f5..0000000000 --- a/nuttx/libc/Kconfig +++ /dev/null @@ -1,275 +0,0 @@ -# -# For a description of the syntax of this configuration file, -# see misc/tools/kconfig-language.txt. -# - -config STDIO_BUFFER_SIZE - int "C STDIO buffer size" - default 64 - ---help--- - Size of buffers using within the C buffered I/O interfaces. - (printf, putchar, fwrite, etc.). - -config STDIO_LINEBUFFER - bool "STDIO line buffering" - default y - ---help--- - Flush buffer I/O whenever a newline character is found in - the output data stream. - -config NUNGET_CHARS - int "Number unget() characters" - default 2 - ---help--- - Number of characters that can be buffered by ungetc() (Only if NFILE_STREAMS > 0) - -config LIB_HOMEDIR - string "Home directory" - default "/" - depends on !DISABLE_ENVIRON - ---help--- - The home directory to use with operations like such as 'cd ~' - -source libc/math/Kconfig - -config NOPRINTF_FIELDWIDTH - bool "Disable sprintf support fieldwidth" - default n - ---help--- - sprintf-related logic is a - little smaller if we do not support fieldwidthes - -config LIBC_FLOATINGPOINT - bool "Enable floating point in printf" - default n - ---help--- - By default, floating point - support in printf, sscanf, etc. is disabled. - -choice - prompt "Newline Options" - default EOL_IS_EITHER_CRLF - ---help--- - This selection determines the line terminating character that is used. - Some environments may return CR as end-of-line, others LF, and others - both. If not specified, the default is either CR or LF (but not both) - as the line terminating charactor. - -config EOL_IS_CR - bool "EOL is CR" - -config EOL_IS_LF - bool "EOL is LF" - -config EOL_IS_BOTH_CRLF - bool "EOL is CR and LF" - -config EOL_IS_EITHER_CRLF - bool "EOL is CR or LF" - -endchoice - -config LIBC_STRERROR - bool "Enable strerror" - default n - ---help--- - strerror() is useful because it decodes 'errno' values into a human readable - strings. But it can also require a lot of memory. If this option is selected, - strerror() will still exist in the build but it will not decode error values. - This option should be used by other logic to decide if it should use strerror() - or not. For example, the NSH application will not use strerror() if this - option is not selected; perror() will not use strerror() is this option is not - selected (see also NSH_STRERROR). - -config LIBC_STRERROR_SHORT - bool "Use short error descriptions in strerror()" - default n - depends on LIBC_STRERROR - ---help--- - If this option is selected, then strerror() will use a shortened string when - it decodes the error. Specifically, strerror() is simply use the string that - is the common name for the error. For example, the 'errno' value of 2 will - produce the string "No such file or directory" is LIBC_STRERROR_SHORT - is not defined but the string "ENOENT" is LIBC_STRERROR_SHORT is defined. - -config LIBC_PERROR_STDOUT - bool "perror() to stdout" - default n - ---help--- - POSIX requires that perror() provide its output on stderr. This option may - be defined, however, to provide perror() output that is serialized with - other stdout messages. - -config ARCH_LOWPUTC - bool "Low-level console output" - default "y" - ---help--- - architecture supports low-level, boot time console output - -config LIB_SENDFILE_BUFSIZE - int "sendfile() buffer size" - default 512 - ---help--- - Size of the I/O buffer to allocate in sendfile(). Default: 512b - -config ARCH_ROMGETC - bool "Support for ROM string access" - default n - ---help--- - In Harvard architectures, data accesses and instruction accesses - occur on different busses, perhaps concurrently. All data accesses - are performed on the data bus unless special machine instructions - are used to read data from the instruction address space. Also, in - the typical MCU, the available SRAM data memory is much smaller that - the non-volatile FLASH instruction memory. So if the application - requires many constant strings, the only practical solution may be - to store those constant strings in FLASH memory where they can only - be accessed using architecture-specific machine instructions. - - If ARCH_ROMGETC is defined, then the architecture logic must export - the function up_romgetc(). up_romgetc() will simply read one byte - of data from the instruction space. - - If ARCH_ROMGETC, certain C stdio functions are effected: (1) All - format strings in printf, fprintf, sprintf, etc. are assumed to lie - in FLASH (string arguments for %s are still assumed to reside in SRAM). - And (2), the string argument to puts and fputs is assumed to reside - in FLASH. Clearly, these assumptions may have to modified for the - particular needs of your environment. There is no "one-size-fits-all" - solution for this problem. - -config ARCH_OPTIMIZED_FUNCTIONS - bool "Enable arch optimized functions" - default n - ---help--- - Allow for architecture optimized implementations of certain library - functions. Architecture-specific implementations can improve overall - system performance. - -if ARCH_OPTIMIZED_FUNCTIONS -config ARCH_MEMCPY - bool "memcpy()" - default n - ---help--- - Select this option if the architecture provides an optimized version - of memcpy(). - -config MEMCPY_VIK - bool "Vik memcpy()" - default n - depends on !ARCH_MEMCPY - ---help--- - Select this option to use the optimized memcpy() function by Daniel Vik. - Select this option for improved performance at the expense of increased - size. See licensing information in the top-level COPYING file. - -if MEMCPY_VIK -config MEMCPY_PRE_INC_PTRS - bool "Pre-increment pointers" - default n - ---help--- - Use pre-increment of pointers. Default is post increment of pointers. - -config MEMCPY_INDEXED_COPY - bool "Array indexing" - default y - ---help--- - Copying data using array indexing. Using this option, disables the - MEMCPY_PRE_INC_PTRS option. - -config MEMCPY_64BIT - bool "64-bit memcpy()" - default n - ---help--- - Compiles memcpy() for architectures that suppport 64-bit operations - efficiently. - -endif - -config ARCH_MEMCMP - bool "memcmp()" - default n - ---help--- - Select this option if the architecture provides an optimized version - of memcmp(). - -config ARCH_MEMMOVE - bool "memmove()" - default n - ---help--- - Select this option if the architecture provides an optimized version - of memmove(). - -config ARCH_MEMSET - bool "memset()" - default n - ---help--- - Select this option if the architecture provides an optimized version - of memset(). - -config MEMSET_OPTSPEED - bool "Optimize memset() for speed" - default n - depends on !ARCH_MEMSET - ---help--- - Select this option to use a version of memcpy() optimized for speed. - Default: memcpy() is optimized for size. - -config MEMSET_64BIT - bool "64-bit memset()" - default n - depends on MEMSET_OPTSPEED - ---help--- - Compiles memset() for architectures that suppport 64-bit operations - efficiently. - -config ARCH_STRCHR - bool "strchr()" - default n - ---help--- - Select this option if the architecture provides an optimized version - of strchr(). - -config ARCH_STRCMP - bool "strcmp()" - default n - ---help--- - Select this option if the architecture provides an optimized version - of strcmp(). - -config ARCH_STRCPY - bool "strcpy()" - default n - ---help--- - Select this option if the architecture provides an optimized version - of strcpy(). - -config ARCH_STRNCPY - bool "strncpy()" - default n - ---help--- - Select this option if the architecture provides an optimized version - of strncpy(). - -config ARCH_STRLEN - bool "strlen" - default n - ---help--- - Select this option if the architecture provides an optimized version - of strlen(). - -config ARCH_STRNLEN - bool "strlen()" - default n - ---help--- - Select this option if the architecture provides an optimized version - of strnlen(). - -config ARCH_BZERO - bool "bzero()" - default n - ---help--- - Select this option if the architecture provides an optimized version - of bzero(). - -endif diff --git a/nuttx/libc/Makefile b/nuttx/libc/Makefile deleted file mode 100644 index 22dbba1d91..0000000000 --- a/nuttx/libc/Makefile +++ /dev/null @@ -1,145 +0,0 @@ -############################################################################ -# libc/Makefile -# -# Copyright (C) 2007-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)/Make.defs - -ASRCS = -CSRCS = - -DEPPATH := --dep-path . -VPATH := . - -include stdio/Make.defs -include stdlib/Make.defs -include unistd/Make.defs -include sched/Make.defs -include string/Make.defs -include pthread/Make.defs -include semaphore/Make.defs -include signal/Make.defs -include mqueue/Make.defs -include math/Make.defs -include fixedmath/Make.defs -include net/Make.defs -include time/Make.defs -include libgen/Make.defs -include dirent/Make.defs -include termios/Make.defs -include queue/Make.defs -include misc/Make.defs - -AOBJS = $(ASRCS:.S=$(OBJEXT)) -COBJS = $(CSRCS:.c=$(OBJEXT)) - -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) - -UBIN = libuc$(LIBEXT) -KBIN = libkc$(LIBEXT) -BIN = libc$(LIBEXT) - -all: $(BIN) - -$(AOBJS): %$(OBJEXT): %.S - $(call ASSEMBLE, $<, $@) - -$(COBJS): %$(OBJEXT): %.c - $(call COMPILE, $<, $@) - -$(BIN): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) - -ifneq ($(BIN),$(UBIN)) -.userlib: - $(Q) $(MAKE) $(UBIN) BIN=$(UBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) - $(Q) touch .userlib - -$(UBIN): kclean .userlib -endif - -ifneq ($(BIN),$(KBIN)) -.kernlib: - $(Q) $(MAKE) $(KBIN) BIN=$(KBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) - $(Q) touch .kernlib - -$(KBIN): uclean .kernlib -endif - -.depend: Makefile $(SRCS) - $(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ - -depend: .depend - -# Clean Targets: -# Clean user-mode temporary files (retaining the UBIN binary) - -uclean: -ifneq ($(OBJEXT),) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - $(Q) if exist .userlib ]; then del *$(OBJEXT) -else - $(Q) ( if [ -f .userlib ]; then rm -f *$(OBJEXT); fi ) -endif -endif - $(call DELFILE, .userlib) - -# Clean kernel-mode temporary files (retaining the KBIN binary) - -kclean: -ifneq ($(OBJEXT),) -ifeq ($(CONFIG_WINDOWS_NATIVE),y) - $(Q) if exist .kernlib ]; then del *$(OBJEXT) -else - $(Q) ( if [ -f .kernlib ]; then rm -f *$(OBJEXT); fi ) -endif -endif - $(call DELFILE, .kernlib) - -# Really clean everything - -clean: uclean kclean - $(call DELFILE, $(BIN)) - $(call DELFILE, $(UBIN)) - $(call DELFILE, $(KBIN)) - $(call CLEAN) - -# Deep clean -- removes all traces of the configuration - -distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) - --include Make.dep diff --git a/nuttx/libc/README.txt b/nuttx/libc/README.txt deleted file mode 100644 index ed672d0388..0000000000 --- a/nuttx/libc/README.txt +++ /dev/null @@ -1,85 +0,0 @@ -lib -=== - -This directory contains numerous, small functions typically associated with -what you would expect to find in a standard C library. The sub-directories -in this directory contain standard interface that can be executed by user- -mode programs. - -Normally, NuttX is built with no protection and all threads running in kerne- -mode. In that model, there is no real architectural distinction between -what is a kernel-mode program and what is a user-mode program; the system is -more like on multi-threaded program that all runs in kernel-mode. - -But if the CONFIG_NUTTX_KERNEL option is selected, NuttX will be built into -distinct user-mode and kernel-mode sections. In that case, most of the -code in the nuttx/ directory will run in kernel-mode with with exceptions -of (1) the user-mode "proxies" found in syscall/proxies, and (2) the -standard C library functions found in this directory. In this build model, -it is critical to separate the user-mode OS interfaces in this way. - -Sub-Directories -=============== - -The files in the libc/ directory are organized (mostly) according which file -in the include/ directory provides the prototype for library functions. So -we have: - - libgen - libgen.h - fixedmath - fixedmath.h - math - math.h - mqueue - pthread.h - net - Various network-related header files: netinet/ether.h, arpa/inet.h - pthread - pthread.h - queue - queue.h - sched - sched.h - semaphore - semaphore.h - stdio - stdio.h - stdlib - stdlib.h - string - string.h - time - time.h - unistd - unistd.h - -There is also a misc/ subdirectory that contains various internal functions -and interfaces from header files that are too few to warrant their own sub- -directory: - - misc - Nonstandard "glue" logic, debug.h, crc32.h, dirent.h - -Library Database -================ - -Information about functions available in the NuttX C library information is -maintained in a database. That "database" is implemented as a simple comma- -separated-value file, lib.csv. Most spreadsheets programs will accept this -format and can be used to maintain the library database. - -This library database will (eventually) be used to generate symbol library -symbol table information that can be exported to external applications. - -The format of the CSV file for each line is: - - Field 1: Function name - Field 2: The header file that contains the function prototype - Field 3: Condition for compilation - Field 4: The type of function return value. - Field 5 - N+5: The type of each of the N formal parameters of the function - -Each type field has a format as follows: - - type name: - For all simpler types - formal type | actual type: - For array types where the form of the formal (eg. int parm[2]) - differs from the type of actual passed parameter (eg. int*). This - is necessary because you cannot do simple casts to array types. - formal type | union member actual type | union member fieldname: - A similar situation exists for unions. For example, the formal - parameter type union sigval -- You cannot cast a uintptr_t to - a union sigval, but you can cast to the type of one of the union - member types when passing the actual paramter. Similarly, we - cannot cast a union sigval to a uinptr_t either. Rather, we need - to cast a specific union member fieldname to uintptr_t. - -NOTE: The tool mksymtab can be used to generate a symbol table from this CSV -file. See nuttx/tools/README.txt for further details about the use of mksymtab. diff --git a/nuttx/libc/dirent/Make.defs b/nuttx/libc/dirent/Make.defs deleted file mode 100644 index f2927bed82..0000000000 --- a/nuttx/libc/dirent/Make.defs +++ /dev/null @@ -1,48 +0,0 @@ -############################################################################ -# libc/dirent/Make.defs -# -# 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. -# -############################################################################ - -ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) - -# Add the dirent C files to the build - -CSRCS += lib_readdirr.c lib_telldir.c - -# Add the dirent directory to the build - -DEPPATH += --dep-path dirent -VPATH += :dirent - -endif - diff --git a/nuttx/libc/dirent/lib_readdirr.c b/nuttx/libc/dirent/lib_readdirr.c deleted file mode 100644 index 93c99ac283..0000000000 --- a/nuttx/libc/dirent/lib_readdirr.c +++ /dev/null @@ -1,122 +0,0 @@ -/**************************************************************************** - * libc/dirent/lib_readdirr.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: readdir_r - * - * Description: - * The readdir() function returns a pointer to a dirent - * structure representing the next directory entry in the - * directory stream pointed to by dir. It returns NULL on - * reaching the end-of-file or if an error occurred. - * - * Inputs: - * dirp -- An instance of type DIR created by a previous - * call to opendir(); - * entry -- The storage pointed to by entry must be large - * enough for a dirent with an array of char d_name - * members containing at least {NAME_MAX}+1 elements. - * result -- Upon successful return, the pointer returned - * at *result shall have the same value as the - * argument entry. Upon reaching the end of the directory - * stream, this pointer shall have the value NULL. - * - * Return: - * If successful, the readdir_r() function return s zero; - * otherwise, an error number is returned to indicate the - * error. - * - * EBADF - Invalid directory stream descriptor dir - * - ****************************************************************************/ - -int readdir_r(FAR DIR *dirp, FAR struct dirent *entry, - FAR struct dirent **result) -{ - struct dirent *tmp; - - /* NOTE: The following use or errno is *not* thread-safe */ - - set_errno(0); - tmp = readdir(dirp); - if (!tmp) - { - int error = get_errno(); - if (!error) - { - if (result) - { - *result = NULL; - } - return 0; - } - else - { - return error; - } - } - - if (entry) - { - memcpy(entry, tmp, sizeof(struct dirent)); - } - - if (result) - { - *result = entry; - } - return 0; -} - diff --git a/nuttx/libc/dirent/lib_telldir.c b/nuttx/libc/dirent/lib_telldir.c deleted file mode 100644 index f77a4a1c21..0000000000 --- a/nuttx/libc/dirent/lib_telldir.c +++ /dev/null @@ -1,91 +0,0 @@ -/**************************************************************************** - * libc/dirent/fs_telldir.c - * - * Copyright (C) 2007-2008, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include -#include - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: telldir - * - * Description: - * The telldir() function returns the current location - * associated with the directory stream dirp. - * - * Inputs: - * dirp -- An instance of type DIR created by a previous - * call to opendir(); - * - * Return: - * On success, the telldir() function returns the current - * location in the directory stream. On error, -1 is - * returned, and errno is set appropriately. - * - * EBADF - Invalid directory stream descriptor dir - * - ****************************************************************************/ - -off_t telldir(FAR DIR *dirp) -{ - struct fs_dirent_s *idir = (struct fs_dirent_s *)dirp; - - if (!idir || !idir->fd_root) - { - set_errno(EBADF); - return (off_t)-1; - } - - /* Just return the current position */ - - return idir->fd_position; -} - diff --git a/nuttx/libc/fixedmath/Make.defs b/nuttx/libc/fixedmath/Make.defs deleted file mode 100644 index b53df2b2c0..0000000000 --- a/nuttx/libc/fixedmath/Make.defs +++ /dev/null @@ -1,43 +0,0 @@ -############################################################################ -# libc/fixedmath/Make.defs -# -# 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. -# -############################################################################ - -# Add the fixed precision math C files to the build - -CSRCS += lib_rint.c lib_fixedmath.c lib_b16sin.c lib_b16cos.c lib_b16atan2.c - -# Add the fixed precision math directory to the build - -DEPPATH += --dep-path fixedmath -VPATH += :fixedmath diff --git a/nuttx/libc/fixedmath/lib_b16atan2.c b/nuttx/libc/fixedmath/lib_b16atan2.c deleted file mode 100644 index 443ab7be34..0000000000 --- a/nuttx/libc/fixedmath/lib_b16atan2.c +++ /dev/null @@ -1,108 +0,0 @@ -/**************************************************************************** - * libc/fixedmath/lib_b16atan2.c - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define B16_C1 0x00000373 /* 0.013480470 */ -#define B16_C2 0x00000eb7 /* 0.057477314 */ -#define B16_C3 0x00001f0a /* 0.121239071 */ -#define B16_C4 0x00003215 /* 0.195635925 */ -#define B16_C5 0x0000553f /* 0.332994597 */ -#define B16_C6 0x00010000 /* 0.999995630 */ -#define B16_HALFPI 0x00019220 /* 1.570796327 */ -#define B16_PI 0x00032440 /* 3.141592654 */ - -#ifndef MAX -# define MAX(a,b) (a > b ? a : b) -#endif - -#ifndef MIN -# define MIN(a,b) (a < b ? a : b) -#endif - -#ifndef ABS -# define ABS(a) (a < 0 ? -a : a) -#endif - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: b16atan2 - * - * Description: - * atan2 calculates the arctangent of y/x. (Based on a algorithm I saw - * posted on the internet... now I have lost the link -- sorry). - * - ****************************************************************************/ - -b16_t b16atan2(b16_t y, b16_t x) -{ - b16_t t0; - b16_t t1; - b16_t t2; - b16_t t3; - - t2 = ABS(x); - t1 = ABS(y); - t0 = MAX(t2, t1); - t1 = MIN(t2, t1); - t2 = ub16inv(t0); - t2 = b16mulb16(t1, t2); - - t3 = b16mulb16(t2, t2); - t0 = - B16_C1; - t0 = b16mulb16(t0, t3) + B16_C2; - t0 = b16mulb16(t0, t3) - B16_C3; - t0 = b16mulb16(t0, t3) + B16_C4; - t0 = b16mulb16(t0, t3) - B16_C5; - t0 = b16mulb16(t0, t3) + B16_C6; - t2 = b16mulb16(t0, t2); - - t2 = (ABS(y) > ABS(x)) ? B16_HALFPI - t2 : t2; - t2 = (x < 0) ? B16_PI - t2 : t2; - t2 = (y < 0) ? -t2 : t2; - - return t2; -} diff --git a/nuttx/libc/fixedmath/lib_b16cos.c b/nuttx/libc/fixedmath/lib_b16cos.c deleted file mode 100644 index 0ebe482624..0000000000 --- a/nuttx/libc/fixedmath/lib_b16cos.c +++ /dev/null @@ -1,64 +0,0 @@ -/**************************************************************************** - * libc/fixedmath/lib_b16cos.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: b16cos - ****************************************************************************/ - -b16_t b16cos(b16_t rad) -{ - /* Compute cosine: sin(rad + PI/2) = cos(rad) */ - - rad += b16HALFPI; - if (rad > b16PI) - { - rad -= b16TWOPI; - } - return b16sin(rad); -} diff --git a/nuttx/libc/fixedmath/lib_b16sin.c b/nuttx/libc/fixedmath/lib_b16sin.c deleted file mode 100644 index 9cd2f0da3e..0000000000 --- a/nuttx/libc/fixedmath/lib_b16sin.c +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * libc/fixedmath/lib_b16sin.c - * - * Copyright (C) 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define b16_P225 0x0000399a -#define b16_P405284735 0x000067c1 -#define b16_1P27323954 0x000145f3 - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: b16sin - * Ref: http://lab.polygonal.de/2007/07/18/fast-and-accurate-sinecosine-approximation/ - ****************************************************************************/ - -b16_t b16sin(b16_t rad) -{ - b16_t tmp1; - b16_t tmp2; - b16_t tmp3; - - /* Force angle into the good range */ - - if (rad < -b16PI) - { - rad += b16TWOPI; - } - else if (rad > b16PI) - { - rad -= b16TWOPI; - } - - /* tmp1 = 1.27323954 * rad - * tmp2 = .405284735 * rad * rad - */ - - - tmp1 = b16mulb16(b16_1P27323954, rad); - tmp2 = b16mulb16(b16_P405284735, b16sqr(rad)); - - if (rad < 0) - { - /* tmp3 = 1.27323954 * rad + .405284735 * rad * rad */ - - tmp3 = tmp1 + tmp2; - } - else - { - /* tmp3 = 1.27323954 * rad - 0.405284735 * rad * rad */ - - tmp3 = tmp1 - tmp2; - } - - /* tmp1 = tmp3*tmp3 */ - - tmp1 = b16sqr(tmp3); - if (tmp3 < 0) - { - /* tmp1 = tmp3 * -tmp3 */ - - tmp1 = -tmp1; - } - - /* Return sin = .225 * (tmp3 * (+/-tmp3) - tmp3) + tmp3 */ - - return b16mulb16(b16_P225, (tmp1 - tmp3)) + tmp3; -} diff --git a/nuttx/libc/fixedmath/lib_fixedmath.c b/nuttx/libc/fixedmath/lib_fixedmath.c deleted file mode 100644 index 9e9213b4fc..0000000000 --- a/nuttx/libc/fixedmath/lib_fixedmath.c +++ /dev/null @@ -1,272 +0,0 @@ -/**************************************************************************** - * libc/math/lib_fixedmath.c - * - * Copyright (C) 2008-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#ifndef CONFIG_HAVE_LONG_LONG - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Name: fixsign - ****************************************************************************/ - -static void fixsign(b16_t *parg1, b16_t *parg2, bool *pnegate) -{ - bool negate = false; - b16_t arg; - - arg = *parg1; - if (arg < 0) - { - *parg1 = -arg; - negate = true; - } - - arg = *parg2; - if (arg < 0) - { - *parg2 = -arg; - negate ^= true; - } - - *pnegate = negate; -} - -/**************************************************************************** - * Name: adjustsign - ****************************************************************************/ - -static b16_t adjustsign(b16_t result, bool negate) -{ - /* If the product is negative, then we overflowed */ - - if (result < 0) - { - if (result) - { - return b16MIN; - } - else - { - return b16MAX; - } - } - - /* correct the sign of the result */ - - if (negate) - { - return -result; - } - return result; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: b16mulb16 - ****************************************************************************/ - -b16_t b16mulb16(b16_t m1, b16_t m2) -{ - bool negate; - b16_t product; - - fixsign(&m1, &m2, &negate); - product = (b16_t)ub16mulub16((ub16_t)m1, (ub16_t)m2); - return adjustsign(product, negate); -} - -/**************************************************************************** - * Name: ub16mulub16 - **************************************************************************/ - -ub16_t ub16mulub16(ub16_t m1, ub16_t m2) -{ - /* Let: - * - * m1 = m1i*2**16 + m1f (b16) - * m2 = m2i*2**16 + m2f (b16) - * - * Then: - * - * m1*m2 = (m1i*m2i)*2**32 + (m1i*m2f + m2i*m1f)*2**16 + m1f*m2f (b32) - * = (m1i*m2i)*2**16 + (m1i*m2f + m2i*m1f) + m1f*m2f*2**-16 (b16) - * = a*2**16 + b + c*2**-16 - */ - - uint32_t m1i = ((uint32_t)m1 >> 16); - uint32_t m2i = ((uint32_t)m1 >> 16); - uint32_t m1f = ((uint32_t)m1 & 0x0000ffff); - uint32_t m2f = ((uint32_t)m2 & 0x0000ffff); - - return (m1i*m2i << 16) + m1i*m2f + m2i*m1f + (((m1f*m2f) + b16HALF) >> 16); -} - -/**************************************************************************** - * Name: b16sqr - **************************************************************************/ - -b16_t b16sqr(b16_t a) -{ - b16_t sq; - - /* The result is always positive. Just take the absolute value */ - - if (a < 0) - { - a = -a; - } - - /* Overflow occurred if the result is negative */ - - sq = (b16_t)ub16sqr(a); - if (sq < 0) - { - sq = b16MAX; - } - return sq; -} - -/**************************************************************************** - * Name: b16divb16 - **************************************************************************/ - -ub16_t ub16sqr(ub16_t a) -{ - /* Let: - * - * m = mi*2**16 + mf (b16) - * - * Then: - * - * m*m = (mi*mi)*2**32 + 2*(m1*m2)*2**16 + mf*mf (b32) - * = (mi*mi)*2**16 + 2*(mi*mf) + mf*mf*2**-16 (b16) - */ - - uint32_t mi = ((uint32_t)a >> 16); - uint32_t mf = ((uint32_t)a & 0x0000ffff); - - return (mi*mi << 16) + (mi*mf << 1) + ((mf*mf + b16HALF) >> 16); -} - -/**************************************************************************** - * Name: b16divb16 - **************************************************************************/ - -b16_t b16divb16(b16_t num, b16_t denom) -{ - bool negate; - b16_t quotient; - - fixsign(&num, &denom, &negate); - quotient = (b16_t)ub16divub16((ub16_t)num, (ub16_t)denom); - return adjustsign(quotient, negate); -} - -/**************************************************************************** - * Name: ub16divub16 - **************************************************************************/ - -ub16_t ub16divub16(ub16_t num, ub16_t denom) -{ - uint32_t term1; - uint32_t numf; - uint32_t product; - - /* Let: - * - * num = numi*2**16 + numf (b16) - * den = deni*2**16 + denf (b16) - * - * Then: - * - * num/den = numi*2**16 / den + numf / den (b0) - * = numi*2**32 / den + numf*2**16 /den (b16) - */ - - /* Check for overflow in the first part of the quotient */ - - term1 = ((uint32_t)num & 0xffff0000) / denom; - if (term1 >= 0x00010000) - { - return ub16MAX; /* Will overflow */ - } - - /* Finish the division */ - - numf = num - term1 * denom; - term1 <<= 16; - product = term1 + (numf + (denom >> 1)) / denom; - - /* Check for overflow */ - - if (product < term1) - { - return ub16MAX; /* Overflowed */ - } - return product; -} - -#endif diff --git a/nuttx/libc/fixedmath/lib_rint.c b/nuttx/libc/fixedmath/lib_rint.c deleted file mode 100644 index a1212c970b..0000000000 --- a/nuttx/libc/fixedmath/lib_rint.c +++ /dev/null @@ -1,135 +0,0 @@ -/************************************************************ - * libc/fixedmath/lib_rint.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include -#include -#include - -/************************************************************ - * Definitions - ************************************************************/ - -/************************************************************ - * Private Type Declarations - ************************************************************/ - -/************************************************************ - * Private Function Prototypes - ************************************************************/ - -/********************************************************** - * Global Constant Data - **********************************************************/ - -/************************************************************ - * Global Variables - ************************************************************/ - -/********************************************************** - * Private Constant Data - **********************************************************/ - -/************************************************************ - * Private Variables - ************************************************************/ - -double_t rint(double_t x) -{ - double_t ret; - - /* If the current rounding mode rounds toward negative - * infinity, rint() is identical to floor(). If the current - * rounding mode rounds toward positive infinity, rint() is - * identical to ceil(). - */ - -#if defined(CONFIG_FP_ROUND_POSITIVE) && CONFIG_FP_ROUNDING_POSITIVE != 0 - - ret = ceil(x); - -#elif defined(CONFIG_FP_ROUND_NEGATIVE) && CONFIG_FP_ROUNDING_NEGATIVE != 0 - - ret = floor(x); - -#else - - /* In the default rounding mode (round to nearest), rint(x) is the - * integer nearest x with the additional stipulation that if - * |rint(x)-x|=1/2, then rint(x) is even. - */ - - long dwinteger = (long)x; - double_t fremainder = x - (double_t)dwinteger; - - if (x < 0.0) - { - /* fremainder should be in range 0 .. -1 */ - - if (fremainder == -0.5) - { - dwinteger = ((dwinteger+1)&~1); - } - else if (fremainder < -0.5) - { - dwinteger--; - } - } - else - { - /* fremainder should be in range 0 .. 1 */ - - if (fremainder == 0.5) - { - dwinteger = ((dwinteger+1)&~1); - } - else if (fremainder > 0.5) - { - dwinteger++; - } - } - - ret = (double_t)dwinteger; -#endif - - return ret; -} diff --git a/nuttx/libc/lib.csv b/nuttx/libc/lib.csv deleted file mode 100644 index 171f64e9b7..0000000000 --- a/nuttx/libc/lib.csv +++ /dev/null @@ -1,171 +0,0 @@ -"_inet_ntoa","arpa/inet.h","!defined(CONFIG_NET_IPv6) && !defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","in_addr_t" -"abort","stdlib.h","","void" -"abs","stdlib.h","","int","int" -"asprintf","stdio.h","","int","FAR char **","const char *","..." -"avsprintf","stdio.h","","int","FAR char **","const char *","va_list" -"b16atan2","fixedmath.h","","b16_t","b16_t","b16_t" -"b16cos","fixedmath.h","","b16_t","b16_t" -"b16divb16","fixedmath.h","","b16_t","b16_t","b16_t" -"b16mulb16","fixedmath.h","","b16_t","b16_t","b16_t" -"b16sin","fixedmath.h","","b16_t","b16_t" -"b16sqr","fixedmath.h","","b16_t","b16_t" -"basename","libgen.h","","FAR char","FAR char *" -"cfgetspeed","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","speed_t","FAR const struct termios *" -"cfsetspeed","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","FAR struct termios *","speed_t" -"chdir","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)","int","FAR const char *" -"crc32","crc32.h","","uint32_t","FAR const uint8_t *","size_t" -"crc32part","crc32.h","","uint32_t","FAR const uint8_t *","size_t","uint32_t" -"dbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG)","int","const char *","..." -"dbg_enable","debug.h","defined(CONFIG_DEBUG_ENABLE)","void","bool" -"dirname","libgen.h","","FAR char","FAR char *" -"dq_addafter","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *" -"dq_addbefore","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *" -"dq_addfirst","queue.h","","void","FAR dq_entry_t *","dq_queue_t *" -"dq_addlast","queue.h","","void","FAR dq_entry_t *","dq_queue_t *" -"dq_rem","queue.h","","void","FAR dq_entry_t *","dq_queue_t *" -"dq_remfirst","queue.h","","FAR dq_entry_t","dq_queue_t *" -"dq_remlast","queue.h","","FAR dq_entry_t","dq_queue_t *" -"ether_ntoa","netinet/ether.h","","FAR char","FAR const struct ether_addr *" -"fclose","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *" -"fdopen","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR FILE","int","FAR const char *" -"fflush","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *" -"fgetc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *" -"fgetpos","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR fpos_t *" -"fgets","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR char","FAR char *","int","FAR FILE *" -"fileno","stdio.h","","int","FAR FILE *" -"fopen","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR FILE","FAR const char *","FAR const char *" -"fprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR const char *","..." -"fputc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","int c","FAR FILE *" -"fputs","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *","FAR FILE *" -"fread","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","size_t","FAR void *","size_t","size_t","FAR FILE *" -"fseek","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","long int","int" -"fsetpos","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR fpos_t *" -"ftell","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","long","FAR FILE *" -"fwrite","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","size_t","FAR const void *","size_t","size_t","FAR FILE *" -"getcwd","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)","FAR char","FAR char *","size_t" -"getopt","unistd.h","","int","int","FAR char *const[]","FAR const char *" -"getoptargp","unistd.h","","FAR char *" -"getoptindp","unistd.h","","int" -"getoptoptp","unistd.h","","int" -"gets","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR char","FAR char *" -"gmtime","time.h","","struct tm","const time_t *" -"gmtime_r","time.h","","FAR struct tm","FAR const time_t *","FAR struct tm *" -"htonl","arpa/inet.h","","uint32_t","uint32_t" -"htons","arpa/inet.h","","uint16_t","uint16_t" -"imaxabs","stdlib.h","","intmax_t","intmax_t" -"inet_addr","arpa/inet.h","","in_addr_t","FAR const char " -"inet_ntoa","arpa/inet.h","!defined(CONFIG_NET_IPv6) && defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","struct in_addr" -"inet_ntop","arpa/inet.h","","FAR const char","int","FAR const void *","FAR char *","socklen_t" -"inet_pton","arpa/inet.h","","int","int","FAR const char *","FAR void *" -"labs","stdlib.h","","long int","long int" -"lib_dumpbuffer","debug.h","","void","FAR const char *","FAR const uint8_t *","unsigned int" -"lib_lowprintf","debug.h","","int","FAR const char *","..." -"lib_rawprintf","debug.h","","int","FAR const char *","..." -"llabs","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long int","long long int" -"lldbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..." -"llvdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..." -"match","","","int","const char *","const char *" -"memccpy","string.h","","FAR void","FAR void *","FAR const void *","int c","size_t" -"memchr","string.h","","FAR void","FAR const void *","int c","size_t" -"memcmp","string.h","","int","FAR const void *","FAR const void *","size_t" -"memcpy","string.h","","FAR void","FAR void *","FAR const void *","size_t" -"memmove","string.h","","FAR void","FAR void *","FAR const void *","size_t" -"memset","string.h","","FAR void","FAR void *","int c","size_t" -"mktime","time.h","","time_t","const struct tm *" -"mq_getattr","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","struct mq_attr *" -"mq_setattr","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","const struct mq_attr *","struct mq_attr *" -"ntohl","arpa/inet.h","","uint32_t","uint32_t" -"ntohs","arpa/inet.h","","uint16_t","uint16_t" -"perror","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","void","FAR const char *" -"printf","stdio.h","","int","const char *","..." -"pthread_attr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *" -"pthread_attr_getinheritsched","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_attr_t *","FAR int *" -"pthread_attr_getschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR struct sched_param *" -"pthread_attr_getschedpolicy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int *" -"pthread_attr_getstacksize","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR long *" -"pthread_attr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *" -"pthread_attr_setinheritsched","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int" -"pthread_attr_setschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR const struct sched_param *" -"pthread_attr_setschedpolicy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int" -"pthread_attr_setstacksize","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","long" -"pthread_barrierattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *" -"pthread_barrierattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_barrierattr_t *","FAR int *" -"pthread_barrierattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *" -"pthread_barrierattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *","int" -"pthread_condattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *" -"pthread_condattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *" -"pthread_mutexattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *" -"pthread_mutexattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","FAR int *" -"pthread_mutexattr_gettype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","const pthread_mutexattr_t *","int *" -"pthread_mutexattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *" -"pthread_mutexattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","int " -"pthread_mutexattr_settype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","pthread_mutexattr_t *","int" -"puts","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *" -"qsort","stdlib.h","","void","void *","size_t","size_t","int(*)(const void *","const void *)" -"rand","stdlib.h","","int" -"readdir_r","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","int","FAR DIR *","FAR struct dirent *","FAR struct dirent **" -"rint","","","double_t","double_t" -"sched_get_priority_max","sched.h","","int","int" -"sched_get_priority_min","sched.h","","int","int" -"sem_getvalue","semaphore.h","","int","FAR sem_t *","FAR int *" -"sem_init","semaphore.h","","int","FAR sem_t *","int","unsigned int" -"sendfile","sys/sendfile.h","CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0","ssize_t","int","int","off_t","size_t" -"sigaddset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *","int" -"sigdelset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *","int" -"sigemptyset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *" -"sigfillset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *" -"sigismember","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR const sigset_t *","int" -"snprintf","stdio.h","","int","FAR char *","size_t","const char *","..." -"sprintf","stdio.h","","int","FAR char *","const char *","..." -"sq_addafter","queue.h","","void","FAR sq_entry_t *","FAR sq_entry_t *","FAR sq_queue_t *" -"sq_addfirst","queue.h","","void","FAR sq_entry_t *","sq_queue_t *" -"sq_addlast","queue.h","","void","FAR sq_entry_t *","sq_queue_t *" -"sq_rem","queue.h","","void","FAR sq_entry_t *","sq_queue_t *" -"sq_remafter","queue.h","","FAR sq_entry_t","FAR sq_entry_t *","sq_queue_t *" -"sq_remfirst","queue.h","","FAR sq_entry_t","sq_queue_t *" -"sq_remlast","queue.h","","FAR sq_entry_t","sq_queue_t *" -"srand","stdlib.h","","void","unsigned int" -"sscanf","stdio.h","","int","const char *","const char *","..." -"strcasecmp","string.h","","int","FAR const char *","FAR const char *" -"strcasestr","string.h","","FAR char","FAR const char *","FAR const char *" -"strcat","string.h","","FAR char","FAR char *","FAR const char *" -"strchr","string.h","","FAR char","FAR const char *","int" -"strcmp","string.h","","int","FAR const char *","FAR const char *" -"strcpy","string.h","","FAR char","char *","FAR const char *" -"strcspn","string.h","","size_t","FAR const char *","FAR const char *" -"strdup","string.h","","FAR char","FAR const char *" -"strerror","string.h","","FAR const char","int" -"strftime","time.h","","size_t","char *","size_t","const char *","const struct tm *" -"strlen","string.h","","size_t","FAR const char *" -"strncasecmp","string.h","","int","FAR const char *","FAR const char *","size_t" -"strncat","string.h","","FAR char","FAR char *","FAR const char *","size_t" -"strncmp","string.h","","int","FAR const char *","FAR const char *","size_t" -"strncpy","string.h","","FAR char","char *","FAR const char *","size_t" -"strndup","string.h","","FAR char","FAR const char *","size_t" -"strnlen","string.h","","size_t","FAR const char *","size_t" -"strpbrk","string.h","","FAR char","FAR const char *","FAR const char *" -"strrchr","string.h","","FAR char","FAR const char *","int" -"strspn","string.h","","size_t","FAR const char *","FAR const char *" -"strstr","string.h","","FAR char","FAR const char *","FAR const char *" -"strtod","stdlib.h","","double_t","const char *str","char **endptr" -"strtok","string.h","","FAR char","FAR char *","FAR const char *" -"strtok_r","string.h","","FAR char","FAR char *","FAR const char *","FAR char **" -"strtol","string.h","","long","const char *","char **","int" -"strtoll","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long","const char *nptr","char **endptr","int base" -"strtoul","stdlib.h","","unsigned long","const char *","char **","int" -"strtoull","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","unsigned long long","const char *","char **","int" -"tcflush","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int" -"tcgetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","FAR struct termios *" -"tcsetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int","FAR const struct termios *" -"telldir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","off_t","FAR DIR *" -"time","time.h","","time_t","time_t *" -"ub16divub16","fixedmath.h","","ub16_t","ub16_t","ub16_t" -"ub16mulub16","fixedmath.h","","ub16_t","ub16_t","ub16_t" -"ub16sqr","fixedmath.h","","ub16_t","ub16_t" -"ungetc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","int","FAR FILE *" -"vdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE)","int","const char *","..." -"vfprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","const char *","va_list" -"vprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *","va_list" -"vsnprintf","stdio.h","","int","FAR char *","size_t","const char *","va_list" -"vsprintf","stdio.h","","int","FAR char *","const char *","va_list" -"vsscanf","stdio.h","","int","char *","const char *","va_list" diff --git a/nuttx/libc/lib_internal.h b/nuttx/libc/lib_internal.h deleted file mode 100644 index c09c751d4a..0000000000 --- a/nuttx/libc/lib_internal.h +++ /dev/null @@ -1,211 +0,0 @@ -/**************************************************************************** - * libc/lib_internal.h - * - * Copyright (C) 2007-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. - * - ****************************************************************************/ - -#ifndef __LIB_LIB_INTERNAL_H -#define __LIB_LIB_INTERNAL_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ -/* This configuration directory is used in environment variable processing - * when we need to reference the user's home directory. There are no user - * directories in NuttX so, by default, this always refers to the root - * directory. - */ - -#ifndef CONFIG_LIB_HOMEDIR -# define CONFIG_LIB_HOMEDIR "/" -#endif - -/* If C std I/O buffering is not supported, then we don't need its semaphore - * protection. - */ - -#if CONFIG_STDIO_BUFFER_SIZE <= 0 -# define lib_sem_initialize(s) -# define lib_take_semaphore(s) -# define lib_give_semaphore(s) -#endif - -/* The NuttX C library an be build in two modes: (1) as a standard, C-libary - * that can be used by normal, user-space applications, or (2) as a special, - * kernel-mode C-library only used within the OS. If NuttX is not being - * built as separated kernel- and user-space modules, then only the first - * mode is supported. - */ - -#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__) -# include -# define lib_malloc(s) kmalloc(s) -# define lib_zalloc(s) kzalloc(s) -# define lib_realloc(p,s) krealloc(p,s) -# define lib_free(p) kfree(p) -#else -# include -# define lib_malloc(s) malloc(s) -# define lib_zalloc(s) zalloc(s) -# define lib_realloc(p,s) realloc(p,s) -# define lib_free(p) free(p) -#endif - -#define LIB_BUFLEN_UNKNOWN INT_MAX - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/* Debug output is initially disabled */ - -#ifdef CONFIG_DEBUG_ENABLE -extern bool g_dbgenable; -#endif - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -/* Defined in lib_streamsem.c */ - -#if CONFIG_NFILE_STREAMS > 0 -void stream_semtake(FAR struct streamlist *list); -void stream_semgive(FAR struct streamlist *list); -#endif - -/* Defined in lib_libnoflush.c */ - -#ifdef CONFIG_STDIO_LINEBUFFER -int lib_noflush(FAR struct lib_outstream_s *this); -#endif - -/* Defined in lib_libsprintf.c */ - -int lib_sprintf(FAR struct lib_outstream_s *obj, - const char *fmt, ...); - -/* Defined lib_libvsprintf.c */ - -int lib_vsprintf(FAR struct lib_outstream_s *obj, - FAR const char *src, va_list ap); - -/* Defined lib_rawprintf.c */ - -int lib_rawvprintf(const char *src, va_list ap); - -/* Defined lib_lowprintf.c */ - -int lib_lowvprintf(const char *src, va_list ap); - -/* Defined in lib_dtoa.c */ - -#ifdef CONFIG_LIBC_FLOATINGPOINT -char *__dtoa(double d, int mode, int ndigits, int *decpt, int *sign, - char **rve); -#endif - -/* Defined in lib_libwrite.c */ - -ssize_t lib_fwrite(FAR const void *ptr, size_t count, FAR FILE *stream); - -/* Defined in lib_libfread.c */ - -ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream); - -/* Defined in lib_libfflush.c */ - -ssize_t lib_fflush(FAR FILE *stream, bool bforce); - -/* Defined in lib_rdflush.c */ - -int lib_rdflush(FAR FILE *stream); - -/* Defined in lib_wrflush.c */ - -int lib_wrflush(FAR FILE *stream); - -/* Defined in lib_sem.c */ - -#if CONFIG_STDIO_BUFFER_SIZE > 0 -void lib_sem_initialize(FAR struct file_struct *stream); -void lib_take_semaphore(FAR struct file_struct *stream); -void lib_give_semaphore(FAR struct file_struct *stream); -#endif - -/* Defined in lib_libgetbase.c */ - -int lib_getbase(const char *nptr, const char **endptr); - -/* Defined in lib_skipspace.c */ - -void lib_skipspace(const char **pptr); - -/* Defined in lib_isbasedigit.c */ - -bool lib_isbasedigit(int ch, int base, int *value); - -/* Defined in lib_checkbase.c */ - -int lib_checkbase(int base, const char **pptr); - -/* Defined in lib_expi.c */ - -#ifdef CONFIG_LIBM -double lib_expi(size_t n); -#endif - -/* Defined in lib_libsqrtapprox.c */ - -#ifdef CONFIG_LIBM -float lib_sqrtapprox(float x); -#endif - -#endif /* __LIB_LIB_INTERNAL_H */ diff --git a/nuttx/libc/libgen/Make.defs b/nuttx/libc/libgen/Make.defs deleted file mode 100644 index 6e786655d9..0000000000 --- a/nuttx/libc/libgen/Make.defs +++ /dev/null @@ -1,43 +0,0 @@ -############################################################################ -# libc/libgen/Make.defs -# -# 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. -# -############################################################################ - -# Add the libgen C files to the build - -CSRCS += lib_basename.c lib_dirname.c - -# Add the libgen directory to the build - -DEPPATH += --dep-path libgen -VPATH += :libgen diff --git a/nuttx/libc/libgen/lib_basename.c b/nuttx/libc/libgen/lib_basename.c deleted file mode 100644 index 68188edbf5..0000000000 --- a/nuttx/libc/libgen/lib_basename.c +++ /dev/null @@ -1,131 +0,0 @@ -/**************************************************************************** - * libc/libgen/lib_basename.c - * - * Copyright (C) 2007, 2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static char g_retchar[2]; - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: basename - * - * Description: - * basename() extracts the filename component from a null-terminated - * pathname string. In the usual case, basename() returns the component - * following the final '/'. Trailing '/' characters are not counted as - * part of the pathname. - * - * If path does not contain a slash, basename() returns a copy of path. - * If path is the string "/", then basename() returns the string "/". If - * path is a NULL pointer or points to an empty string, then basename() - * return the string ".". - * - * basename() may modify the contents of path, so copies should be passed. - * basename() may return pointers to statically allocated memory which may - * be overwritten by subsequent calls. - * - * Parameter: - * path The null-terminated string referring to the path to be decomposed - * - * Return: - * On success the filename component of the path is returned. - * - ****************************************************************************/ - -FAR char *basename(FAR char *path) -{ - char *p; - int len; - int ch; - - /* Handle some corner cases */ - - if (!path || *path == '\0') - { - ch = '.'; - goto out_retchar; - } - - /* Check for trailing slash characters */ - - len = strlen(path); - while (path[len-1] == '/') - { - /* Remove trailing '/' UNLESS this would make a zero length string */ - if (len > 1) - { - path[len-1] = '\0'; - len--; - } - else - { - ch = '/'; - goto out_retchar; - } - } - - /* Get the address of the last '/' which is not at the end of the path and, - * therefor, must be just before the beginning of the filename component. - */ - - p = strrchr(path, '/'); - if (p) - { - return p + 1; - } - - /* There is no '/' in the path */ - - return path; - -out_retchar: - g_retchar[0] = ch; - g_retchar[1] = '\0'; - return g_retchar; -} diff --git a/nuttx/libc/libgen/lib_dirname.c b/nuttx/libc/libgen/lib_dirname.c deleted file mode 100644 index 6d076fd610..0000000000 --- a/nuttx/libc/libgen/lib_dirname.c +++ /dev/null @@ -1,144 +0,0 @@ -/**************************************************************************** - * libc/libgen/lib_dirname.c - * - * Copyright (C) 2007, 2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static char g_retchar[2]; - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: dirname - * - * Description: - * dirname() extracts the directory component from a null-terminated - * pathname string. In the usual case, dirname() returns the string up - * to, but not including, the final '/'. Trailing '/' characters are not - * counted as part of the pathname. - * - * If path does not contain a slash, dirname() returns the string ".". If - * path is the string "/", then dirname() returns the string "/". If path - * is a NULL pointer or points to an empty string, then dirname() returns - * the string ".". - * - * dirname() may modify the contents of path, so copies should be passed. - * dirname() may return pointers to statically allocated memory which may - * be overwritten by subsequent calls. - * - * Parameter: - * path The null-terminated string referring to the path to be decomposed - * - * Return: - * On success the directory component of the path is returned. - * - ****************************************************************************/ - -FAR char *dirname(FAR char *path) -{ - char *p; - int len; - int ch; - - /* Handle some corner cases */ - - if (!path || *path == '\0') - { - ch = '.'; - goto out_retchar; - } - - /* Check for trailing slash characters */ - - len = strlen(path); - while (path[len-1] == '/') - { - /* Remove trailing '/' UNLESS this would make a zero length string */ - if (len > 1) - { - path[len-1] = '\0'; - len--; - } - else - { - ch = '/'; - goto out_retchar; - } - } - - /* Get the address of the last '/' which is not at the end of the path and, - * therefor, must be the end of the directory component. - */ - - p = strrchr(path, '/'); - if (p) - { - /* Handle the case where the only '/' in the string is the at the beginning - * of the path. - */ - - if (p == path) - { - ch = '/'; - goto out_retchar; - } - - /* No, the directory component is the substring before the '/'. */ - - *p = '\0'; - return path; - } - - /* There is no '/' in the path */ - - ch = '.'; - -out_retchar: - g_retchar[0] = ch; - g_retchar[1] = '\0'; - return g_retchar; -} diff --git a/nuttx/libc/math/Kconfig b/nuttx/libc/math/Kconfig deleted file mode 100644 index c24bfd53f3..0000000000 --- a/nuttx/libc/math/Kconfig +++ /dev/null @@ -1,26 +0,0 @@ -# -# For a description of the syntax of this configuration file, -# see misc/tools/kconfig-language.txt. -# - -config LIBM - bool "Math library" - default n - depends on !ARCH_MATH_H - ---help--- - By default, no math library will be provided by NuttX. In this this case, it - is assumed that (1) no math library is required, or (2) you will be using the - math.h header file and the libm library provided by your toolchain. - - This is may be a very good choice is possible because your toolchain may have - have a highly optimized version of libm. - - Another possibility is that you have a custom, architecture-specific math - libary and that the corresponding math.h file resides at arch//include/math.h. - The option is selected via ARCH_MATH_H. If ARCH_MATH_H is selected,then the include/nuttx/math.h - header file will be copied to include/math.h where it can be used by your applications. - - If ARCH_MATH_H is not defined, then this option can be selected to build a generic, - math library built into NuttX. This math library comes from the Rhombus OS and - was written by Nick Johnson. The Rhombus OS math library port was contributed by - Darcy Gong. diff --git a/nuttx/libc/math/Make.defs b/nuttx/libc/math/Make.defs deleted file mode 100644 index bc6a265f0e..0000000000 --- a/nuttx/libc/math/Make.defs +++ /dev/null @@ -1,62 +0,0 @@ -############################################################################ -# libc/math/Make.defs -# -# 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_LIBM),y) - -# Add the floating point math C files to the build - -CSRCS += lib_acosf.c lib_asinf.c lib_atan2f.c lib_atanf.c lib_ceilf.c lib_cosf.c -CSRCS += lib_coshf.c lib_expf.c lib_fabsf.c lib_floorf.c lib_fmodf.c lib_frexpf.c -CSRCS += lib_ldexpf.c lib_logf.c lib_log10f.c lib_log2f.c lib_modff.c lib_powf.c -CSRCS += lib_sinf.c lib_sinhf.c lib_sqrtf.c lib_tanf.c lib_tanhf.c - -CSRCS += lib_acos.c lib_asin.c lib_atan.c lib_atan2.c lib_ceil.c lib_cos.c -CSRCS += lib_cosh.c lib_exp.c lib_fabs.c lib_floor.c lib_fmod.c lib_frexp.c -CSRCS += lib_ldexp.c lib_log.c lib_log10.c lib_log2.c lib_modf.c lib_pow.c -CSRCS += lib_sin.c lib_sinh.c lib_sqrt.c lib_tan.c lib_tanh.c - -CSRCS += lib_acosl.c lib_asinl.c lib_atan2l.c lib_atanl.c lib_ceill.c lib_cosl.c -CSRCS += lib_coshl.c lib_expl.c lib_fabsl.c lib_floorl.c lib_fmodl.c lib_frexpl.c -CSRCS += lib_ldexpl.c lib_logl.c lib_log10l.c lib_log2l.c lib_modfl.c lib_powl.c -CSRCS += lib_sinl.c lib_sinhl.c lib_sqrtl.c lib_tanl.c lib_tanhl.c - -CSRCS += lib_libexpi.c lib_libsqrtapprox.c - -# Add the floating point math directory to the build - -DEPPATH += --dep-path math -VPATH += :math - -endif diff --git a/nuttx/libc/math/lib_acos.c b/nuttx/libc/math/lib_acos.c deleted file mode 100644 index 147003237f..0000000000 --- a/nuttx/libc/math/lib_acos.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_acos.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double acos(double x) -{ - return (M_PI_2 - asin(x)); -} -#endif diff --git a/nuttx/libc/math/lib_acosf.c b/nuttx/libc/math/lib_acosf.c deleted file mode 100644 index 447b2767f1..0000000000 --- a/nuttx/libc/math/lib_acosf.c +++ /dev/null @@ -1,41 +0,0 @@ -/************************************************************************ - * libc/math/lib_acosf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float acosf(float x) -{ - return (M_PI_2 - asinf(x)); -} diff --git a/nuttx/libc/math/lib_acosl.c b/nuttx/libc/math/lib_acosl.c deleted file mode 100644 index a0f2262380..0000000000 --- a/nuttx/libc/math/lib_acosl.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_acos.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double acosl(long double x) -{ - return (M_PI_2 - asinl(x)); -} -#endif diff --git a/nuttx/libc/math/lib_asin.c b/nuttx/libc/math/lib_asin.c deleted file mode 100644 index d9941a7e5b..0000000000 --- a/nuttx/libc/math/lib_asin.c +++ /dev/null @@ -1,69 +0,0 @@ -/************************************************************************ - * libc/math/lib_sin.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double asin(double x) -{ - long double y, y_sin, y_cos; - - y = 0; - - while (1) - { - y_sin = sin(y); - y_cos = cos(y); - - if (y > M_PI_2 || y < -M_PI_2) - { - y = fmod(y, M_PI); - } - - if (y_sin + DBL_EPSILON >= x && y_sin - DBL_EPSILON <= x) - { - break; - } - - y = y - (y_sin - x) / y_cos; - } - - return y; -} -#endif diff --git a/nuttx/libc/math/lib_asinf.c b/nuttx/libc/math/lib_asinf.c deleted file mode 100644 index 57e518acb4..0000000000 --- a/nuttx/libc/math/lib_asinf.c +++ /dev/null @@ -1,65 +0,0 @@ -/************************************************************************ - * libc/math/lib_sinf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float asinf(float x) -{ - long double y, y_sin, y_cos; - - y = 0; - - while (1) - { - y_sin = sinf(y); - y_cos = cosf(y); - - if (y > M_PI_2 || y < -M_PI_2) - { - y = fmodf(y, M_PI); - } - - if (y_sin + FLT_EPSILON >= x && y_sin - FLT_EPSILON <= x) - { - break; - } - - y = y - (y_sin - x) / y_cos; - } - - return y; -} - diff --git a/nuttx/libc/math/lib_asinl.c b/nuttx/libc/math/lib_asinl.c deleted file mode 100644 index 19f284e535..0000000000 --- a/nuttx/libc/math/lib_asinl.c +++ /dev/null @@ -1,69 +0,0 @@ -/************************************************************************ - * libc/math/lib_sinl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double asinl(long double x) -{ - long double y, y_sin, y_cos; - - y = 0; - - while (1) - { - y_sin = sinl(y); - y_cos = cosl(y); - - if (y > M_PI_2 || y < -M_PI_2) - { - y = fmodl(y, M_PI); - } - - if (y_sin + LDBL_EPSILON >= x && y_sin - LDBL_EPSILON <= x) - { - break; - } - - y = y - (y_sin - x) / y_cos; - } - - return y; -} -#endif diff --git a/nuttx/libc/math/lib_atan.c b/nuttx/libc/math/lib_atan.c deleted file mode 100644 index 44d68ece2f..0000000000 --- a/nuttx/libc/math/lib_atan.c +++ /dev/null @@ -1,48 +0,0 @@ -/************************************************************************ - * libc/math/lib_atan.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double atan(double x) -{ - return asin(x / sqrt(x * x + 1)); -} -#endif diff --git a/nuttx/libc/math/lib_atan2.c b/nuttx/libc/math/lib_atan2.c deleted file mode 100644 index 6d7d2ad482..0000000000 --- a/nuttx/libc/math/lib_atan2.c +++ /dev/null @@ -1,86 +0,0 @@ -/************************************************************************ - * libc/math/lib_atan2.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double atan2(double y, double x) -{ - if (y == 0.0) - { - if (x >= 0.0) - { - return 0.0; - } - else - { - return M_PI; - } - } - else if (y > 0.0) - { - if (x == 0.0) - { - return M_PI_2; - } - else if (x > 0.0) - { - return atan(y / x); - } - else - { - return M_PI - atan(y / x); - } - } - else - { - if (x == 0.0) - { - return M_PI + M_PI_2; - } - else if (x > 0.0) - { - return 2 * M_PI - atan(y / x); - } - else - { - return M_PI + atan(y / x); - } - } -} -#endif diff --git a/nuttx/libc/math/lib_atan2f.c b/nuttx/libc/math/lib_atan2f.c deleted file mode 100644 index 7ff9af1305..0000000000 --- a/nuttx/libc/math/lib_atan2f.c +++ /dev/null @@ -1,81 +0,0 @@ -/************************************************************************ - * libc/math/lib_atan2f.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float atan2f(float y, float x) -{ - if (y == 0.0) - { - if (x >= 0.0) - { - return 0.0; - } - else - { - return M_PI; - } - } - else if (y > 0.0) - { - if (x == 0.0) - { - return M_PI_2; - } - else if (x > 0.0) - { - return atanf(y / x); - } - else - { - return M_PI - atanf(y / x); - } - } - else - { - if (x == 0.0) - { - return M_PI + M_PI_2; - } - else if (x > 0.0) - { - return 2 * M_PI - atanf(y / x); - } - else - { - return M_PI + atanf(y / x); - } - } -} diff --git a/nuttx/libc/math/lib_atan2l.c b/nuttx/libc/math/lib_atan2l.c deleted file mode 100644 index 48bfd06f39..0000000000 --- a/nuttx/libc/math/lib_atan2l.c +++ /dev/null @@ -1,87 +0,0 @@ -/************************************************************************ - * libc/math/lib_atan2l.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double atan2l(long double y, long double x) -{ - - if (y == 0.0) - { - if (x >= 0.0) - { - return 0.0; - } - else - { - return M_PI; - } - } - else if (y > 0.0) - { - if (x == 0.0) - { - return M_PI_2; - } - else if (x > 0.0) - { - return atanl(y / x); - } - else - { - return M_PI - atanl(y / x); - } - } - else - { - if (x == 0.0) - { - return M_PI + M_PI_2; - } - else if (x > 0.0) - { - return 2 * M_PI - atanl(y / x); - } - else - { - return M_PI + atanl(y / x); - } - } -} -#endif diff --git a/nuttx/libc/math/lib_atanf.c b/nuttx/libc/math/lib_atanf.c deleted file mode 100644 index a84605787a..0000000000 --- a/nuttx/libc/math/lib_atanf.c +++ /dev/null @@ -1,43 +0,0 @@ -/************************************************************************ - * libc/math/lib_atanf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float atanf(float x) -{ - return asinf(x / sqrtf(x * x + 1)); -} diff --git a/nuttx/libc/math/lib_atanl.c b/nuttx/libc/math/lib_atanl.c deleted file mode 100644 index 752d493070..0000000000 --- a/nuttx/libc/math/lib_atanl.c +++ /dev/null @@ -1,48 +0,0 @@ -/************************************************************************ - * libc/math/lib_atanl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double atanl(long double x) -{ - return asinl(x / sqrtl(x * x + 1)); -} -#endif diff --git a/nuttx/libc/math/lib_ceil.c b/nuttx/libc/math/lib_ceil.c deleted file mode 100644 index 3c6678dc1d..0000000000 --- a/nuttx/libc/math/lib_ceil.c +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************ - * libc/math/lib_ceil.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double ceil(double x) -{ - modf(x, &x); - if (x > 0.0) - { - x += 1.0; - } - - return x; -} -#endif diff --git a/nuttx/libc/math/lib_ceilf.c b/nuttx/libc/math/lib_ceilf.c deleted file mode 100644 index afbe2cf13b..0000000000 --- a/nuttx/libc/math/lib_ceilf.c +++ /dev/null @@ -1,47 +0,0 @@ -/************************************************************************ - * libc/math/lib_ceilf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float ceilf(float x) -{ - modff(x, &x); - if (x > 0.0) - { - x += 1.0; - } - - return x; -} diff --git a/nuttx/libc/math/lib_ceill.c b/nuttx/libc/math/lib_ceill.c deleted file mode 100644 index 757016b530..0000000000 --- a/nuttx/libc/math/lib_ceill.c +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************ - * libc/math/lib_ceil;.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double ceill(long double x) -{ - modfl(x, &x); - if (x > 0.0) - { - x += 1.0; - } - - return x; -} -#endif diff --git a/nuttx/libc/math/lib_cos.c b/nuttx/libc/math/lib_cos.c deleted file mode 100644 index 4b4e1a20b9..0000000000 --- a/nuttx/libc/math/lib_cos.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_cos.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double cos(double x) -{ - return sin(x + M_PI_2); -} -#endif diff --git a/nuttx/libc/math/lib_cosf.c b/nuttx/libc/math/lib_cosf.c deleted file mode 100644 index d9ac951f62..0000000000 --- a/nuttx/libc/math/lib_cosf.c +++ /dev/null @@ -1,41 +0,0 @@ -/************************************************************************ - * libc/math/lib_cosf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float cosf(float x) -{ - return sinf(x + M_PI_2); -} diff --git a/nuttx/libc/math/lib_cosh.c b/nuttx/libc/math/lib_cosh.c deleted file mode 100644 index 3246ea5f96..0000000000 --- a/nuttx/libc/math/lib_cosh.c +++ /dev/null @@ -1,47 +0,0 @@ -/************************************************************************ - * libc/math/lib_cosh.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double cosh(double x) -{ - x = exp(x); - return ((x + (1.0 / x)) / 2.0); -} -#endif diff --git a/nuttx/libc/math/lib_coshf.c b/nuttx/libc/math/lib_coshf.c deleted file mode 100644 index f0c28ab2ea..0000000000 --- a/nuttx/libc/math/lib_coshf.c +++ /dev/null @@ -1,42 +0,0 @@ -/************************************************************************ - * libc/math/lib_coshf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float coshf(float x) -{ - x = expf(x); - return ((x + (1.0 / x)) / 2.0); -} diff --git a/nuttx/libc/math/lib_coshl.c b/nuttx/libc/math/lib_coshl.c deleted file mode 100644 index 957ec61a73..0000000000 --- a/nuttx/libc/math/lib_coshl.c +++ /dev/null @@ -1,47 +0,0 @@ -/************************************************************************ - * libc/math/lib_coshl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double coshl(long double x) -{ - x = expl(x); - return ((x + (1.0 / x)) / 2.0); -} -#endif diff --git a/nuttx/libc/math/lib_cosl.c b/nuttx/libc/math/lib_cosl.c deleted file mode 100644 index 972d4aa9da..0000000000 --- a/nuttx/libc/math/lib_cosl.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_cosl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double cosl(long double x) -{ - return sinl(x + M_PI_2); -} -#endif diff --git a/nuttx/libc/math/lib_exp.c b/nuttx/libc/math/lib_exp.c deleted file mode 100644 index 62494251de..0000000000 --- a/nuttx/libc/math/lib_exp.c +++ /dev/null @@ -1,126 +0,0 @@ -/************************************************************************ - * libc/math/lib_exp.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -#include "lib_internal.h" - -#ifdef CONFIG_HAVE_DOUBLE - -/************************************************************************ - * Private Data - ************************************************************************/ - -static double _dbl_inv_fact[] = -{ - 1.0 / 1.0, // 1 / 0! - 1.0 / 1.0, // 1 / 1! - 1.0 / 2.0, // 1 / 2! - 1.0 / 6.0, // 1 / 3! - 1.0 / 24.0, // 1 / 4! - 1.0 / 120.0, // 1 / 5! - 1.0 / 720.0, // 1 / 6! - 1.0 / 5040.0, // 1 / 7! - 1.0 / 40320.0, // 1 / 8! - 1.0 / 362880.0, // 1 / 9! - 1.0 / 3628800.0, // 1 / 10! - 1.0 / 39916800.0, // 1 / 11! - 1.0 / 479001600.0, // 1 / 12! - 1.0 / 6227020800.0, // 1 / 13! - 1.0 / 87178291200.0, // 1 / 14! - 1.0 / 1307674368000.0, // 1 / 15! - 1.0 / 20922789888000.0, // 1 / 16! - 1.0 / 355687428096000.0, // 1 / 17! - 1.0 / 6402373705728000.0, // 1 / 18! -}; - -/************************************************************************ - * Public Functions - ************************************************************************/ - -double exp(double x) -{ - size_t int_part; - bool invert; - double value; - double x0; - size_t i; - - if (x == 0) - { - return 1; - } - else if (x < 0) - { - invert = true; - x = -x; - } - else - { - invert = false; - } - - /* Extract integer component */ - - int_part = (size_t) x; - - /* Set x to fractional component */ - - x -= (double)int_part; - - /* Perform Taylor series approximation with nineteen terms */ - - value = 0.0; - x0 = 1.0; - for (i = 0; i < 19; i++) - { - value += x0 * _dbl_inv_fact[i]; - x0 *= x; - } - - /* Multiply by exp of the integer component */ - - value *= lib_expi(int_part); - - if (invert) - { - return (1.0 / value); - } - else - { - return value; - } -} -#endif diff --git a/nuttx/libc/math/lib_expf.c b/nuttx/libc/math/lib_expf.c deleted file mode 100644 index 3e43c54a6c..0000000000 --- a/nuttx/libc/math/lib_expf.c +++ /dev/null @@ -1,112 +0,0 @@ -/************************************************************************ - * libc/math/lib_expf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include "lib_internal.h" - -/************************************************************************ - * Private Data - ************************************************************************/ - -static float _flt_inv_fact[] = -{ - 1.0 / 1.0, // 1/0! - 1.0 / 1.0, // 1/1! - 1.0 / 2.0, // 1/2! - 1.0 / 6.0, // 1/3! - 1.0 / 24.0, // 1/4! - 1.0 / 120.0, // 1/5! - 1.0 / 720.0, // 1/6! - 1.0 / 5040.0, // 1/7! - 1.0 / 40320.0, // 1/8! - 1.0 / 362880.0, // 1/9! - 1.0 / 3628800.0, // 1/10! -}; - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float expf(float x) -{ - size_t int_part; - bool invert; - float value; - float x0; - size_t i; - - if (x == 0) - { - return 1; - } - else if (x < 0) - { - invert = true; - x = -x; - } - else - { - invert = false; - } - - /* Extract integer component */ - - int_part = (size_t) x; - - /* set x to fractional component */ - - x -= (float)int_part; - - /* Perform Taylor series approximation with eleven terms */ - - value = 0.0; - x0 = 1.0; - for (i = 0; i < 10; i++) - { - value += x0 * _flt_inv_fact[i]; - x0 *= x; - } - - /* Multiply by exp of the integer component */ - - value *= lib_expi(int_part); - - if (invert) - { - return (1.0 / value); - } - else - { - return value; - } -} diff --git a/nuttx/libc/math/lib_expl.c b/nuttx/libc/math/lib_expl.c deleted file mode 100644 index 231faa35f1..0000000000 --- a/nuttx/libc/math/lib_expl.c +++ /dev/null @@ -1,126 +0,0 @@ -/************************************************************************ - * libc/math/lib_expl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -#include "lib_internal.h" - -#ifdef CONFIG_HAVE_LONG_DOUBLE - -/************************************************************************ - * Private Data - ************************************************************************/ - -static long double _ldbl_inv_fact[] = -{ - 1.0 / 1.0, // 1 / 0! - 1.0 / 1.0, // 1 / 1! - 1.0 / 2.0, // 1 / 2! - 1.0 / 6.0, // 1 / 3! - 1.0 / 24.0, // 1 / 4! - 1.0 / 120.0, // 1 / 5! - 1.0 / 720.0, // 1 / 6! - 1.0 / 5040.0, // 1 / 7! - 1.0 / 40320.0, // 1 / 8! - 1.0 / 362880.0, // 1 / 9! - 1.0 / 3628800.0, // 1 / 10! - 1.0 / 39916800.0, // 1 / 11! - 1.0 / 479001600.0, // 1 / 12! - 1.0 / 6227020800.0, // 1 / 13! - 1.0 / 87178291200.0, // 1 / 14! - 1.0 / 1307674368000.0, // 1 / 15! - 1.0 / 20922789888000.0, // 1 / 16! - 1.0 / 355687428096000.0, // 1 / 17! - 1.0 / 6402373705728000.0, // 1 / 18! -}; - -/************************************************************************ - * Public Functions - ************************************************************************/ - -long double expl(long double x) -{ - size_t int_part; - bool invert; - long double value; - long double x0; - size_t i; - - if (x == 0) - { - return 1; - } - else if (x < 0) - { - invert = true; - x = -x; - } - else - { - invert = false; - } - - /* Extract integer component */ - - int_part = (size_t) x; - - /* Set x to fractional component */ - - x -= (long double)int_part; - - /* Perform Taylor series approximation with nineteen terms */ - - value = 0.0; - x0 = 1.0; - for (i = 0; i < 19; i++) - { - value += x0 * _ldbl_inv_fact[i]; - x0 *= x; - } - - /* Multiply by exp of the integer component */ - - value *= lib_expi(int_part); - - if (invert) - { - return (1.0 / value); - } - else - { - return value; - } -} -#endif diff --git a/nuttx/libc/math/lib_fabs.c b/nuttx/libc/math/lib_fabs.c deleted file mode 100644 index 774755087b..0000000000 --- a/nuttx/libc/math/lib_fabs.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_fabs.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double fabs(double x) -{ - return ((x < 0) ? -x : x); -} -#endif diff --git a/nuttx/libc/math/lib_fabsf.c b/nuttx/libc/math/lib_fabsf.c deleted file mode 100644 index 4c8ebae620..0000000000 --- a/nuttx/libc/math/lib_fabsf.c +++ /dev/null @@ -1,41 +0,0 @@ -/************************************************************************ - * libc/math/lib_fabsf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float fabsf(float x) -{ - return ((x < 0) ? -x : x); -} diff --git a/nuttx/libc/math/lib_fabsl.c b/nuttx/libc/math/lib_fabsl.c deleted file mode 100644 index 96ac7d5db3..0000000000 --- a/nuttx/libc/math/lib_fabsl.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_fabsl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double fabsl(long double x) -{ - return ((x < 0) ? -x : x); -} -#endif diff --git a/nuttx/libc/math/lib_floor.c b/nuttx/libc/math/lib_floor.c deleted file mode 100644 index 3330607ce9..0000000000 --- a/nuttx/libc/math/lib_floor.c +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************ - * libc/math/lib_floor.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double floor(double x) -{ - modf(x, &x); - if (x < 0.0) - { - x -= 1.0; - } - - return x; -} -#endif diff --git a/nuttx/libc/math/lib_floorf.c b/nuttx/libc/math/lib_floorf.c deleted file mode 100644 index 81483d4c9c..0000000000 --- a/nuttx/libc/math/lib_floorf.c +++ /dev/null @@ -1,47 +0,0 @@ -/************************************************************************ - * libc/math/lib_floorf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float floorf(float x) -{ - modff(x, &x); - if (x < 0.0) - { - x -= 1.0; - } - - return x; -} diff --git a/nuttx/libc/math/lib_floorl.c b/nuttx/libc/math/lib_floorl.c deleted file mode 100644 index 0d9ec43b45..0000000000 --- a/nuttx/libc/math/lib_floorl.c +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************ - * libc/math/lib_floorl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double floorl(long double x) -{ - modfl(x, &x); - if (x < 0.0) - { - x -= 1.0; - } - - return x; -} -#endif diff --git a/nuttx/libc/math/lib_fmod.c b/nuttx/libc/math/lib_fmod.c deleted file mode 100644 index c66210cdea..0000000000 --- a/nuttx/libc/math/lib_fmod.c +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************ - * libc/math/lib_fmod.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double fmod(double x, double div) -{ - double n0; - - x /= div; - x = modf(x, &n0); - x *= div; - - return x; -} -#endif diff --git a/nuttx/libc/math/lib_fmodf.c b/nuttx/libc/math/lib_fmodf.c deleted file mode 100644 index d70bb791ca..0000000000 --- a/nuttx/libc/math/lib_fmodf.c +++ /dev/null @@ -1,47 +0,0 @@ -/************************************************************************ - * libc/math/lib_fmodf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float fmodf(float x, float div) -{ - float n0; - - x /= div; - x = modff(x, &n0); - x *= div; - - return x; -} diff --git a/nuttx/libc/math/lib_fmodl.c b/nuttx/libc/math/lib_fmodl.c deleted file mode 100644 index 1299bf6e89..0000000000 --- a/nuttx/libc/math/lib_fmodl.c +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************ - * libc/math/lib_fmodl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double fmodl(long double x, long double div) -{ - long double n0; - - x /= div; - x = modfl(x, &n0); - x *= div; - - return x; -} -#endif diff --git a/nuttx/libc/math/lib_frexp.c b/nuttx/libc/math/lib_frexp.c deleted file mode 100644 index b9576dfd4d..0000000000 --- a/nuttx/libc/math/lib_frexp.c +++ /dev/null @@ -1,47 +0,0 @@ -/************************************************************************ - * libc/math/lib_frexp.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double frexp(double x, int *exponent) -{ - *exponent = (int)ceil(log2(x)); - return x / ldexp(1.0, *exponent); -} -#endif diff --git a/nuttx/libc/math/lib_frexpf.c b/nuttx/libc/math/lib_frexpf.c deleted file mode 100644 index d93ffb1731..0000000000 --- a/nuttx/libc/math/lib_frexpf.c +++ /dev/null @@ -1,42 +0,0 @@ -/************************************************************************ - * libc/math/lib_frexpf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float frexpf(float x, int *exponent) -{ - *exponent = (int)ceilf(log2f(x)); - return x / ldexpf(1.0, *exponent); -} diff --git a/nuttx/libc/math/lib_frexpl.c b/nuttx/libc/math/lib_frexpl.c deleted file mode 100644 index 90993b137b..0000000000 --- a/nuttx/libc/math/lib_frexpl.c +++ /dev/null @@ -1,47 +0,0 @@ -/************************************************************************ - * libc/math/lib_frexpl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double frexpl(long double x, int *exponent) -{ - *exponent = (int)ceill(log2(x)); - return x / ldexpl(1.0, *exponent); -} -#endif diff --git a/nuttx/libc/math/lib_ldexp.c b/nuttx/libc/math/lib_ldexp.c deleted file mode 100644 index 9b74d53d71..0000000000 --- a/nuttx/libc/math/lib_ldexp.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_ldexp.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double ldexp(double x, int n) -{ - return (x * pow(2.0, (double)n)); -} -#endif diff --git a/nuttx/libc/math/lib_ldexpf.c b/nuttx/libc/math/lib_ldexpf.c deleted file mode 100644 index f3aaf555b4..0000000000 --- a/nuttx/libc/math/lib_ldexpf.c +++ /dev/null @@ -1,41 +0,0 @@ -/************************************************************************ - * libc/math/lib_ldexpf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float ldexpf(float x, int n) -{ - return (x * powf(2.0, (float)n)); -} diff --git a/nuttx/libc/math/lib_ldexpl.c b/nuttx/libc/math/lib_ldexpl.c deleted file mode 100644 index 29764aaba3..0000000000 --- a/nuttx/libc/math/lib_ldexpl.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_ldexpl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double ldexpl(long double x, int n) -{ - return (x * powl(2.0, (long double)n)); -} -#endif diff --git a/nuttx/libc/math/lib_libexpi.c b/nuttx/libc/math/lib_libexpi.c deleted file mode 100644 index 33ba537b1e..0000000000 --- a/nuttx/libc/math/lib_libexpi.c +++ /dev/null @@ -1,103 +0,0 @@ -/************************************************************************ - * libc/math/lib_libexpi.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -#define M_E2 (M_E * M_E) -#define M_E4 (M_E2 * M_E2) -#define M_E8 (M_E4 * M_E4) -#define M_E16 (M_E8 * M_E8) -#define M_E32 (M_E16 * M_E16) -#define M_E64 (M_E32 * M_E32) -#define M_E128 (M_E64 * M_E64) -#define M_E256 (M_E128 * M_E128) -#define M_E512 (M_E256 * M_E256) -#define M_E1024 (M_E512 * M_E512) - -/************************************************************************ - * Private Data - ************************************************************************/ - -static double _expi_square_tbl[11] = -{ - M_E, // e^1 - M_E2, // e^2 - M_E4, // e^4 - M_E8, // e^8 - M_E16, // e^16 - M_E32, // e^32 - M_E64, // e^64 - M_E128, // e^128 - M_E256, // e^256 - M_E512, // e^512 - M_E1024, // e^1024 -}; - -/************************************************************************ - * Public Functions - ************************************************************************/ - -double lib_expi(size_t n) -{ - size_t i; - double val; - - if (n > 1024) - { - return INFINITY; - } - - val = 1.0; - - for (i = 0; n; i++) - { - if (n & (1 << i)) - { - n &= ~(1 << i); - val *= _expi_square_tbl[i]; - } - } - - return val; -} - diff --git a/nuttx/libc/math/lib_libsqrtapprox.c b/nuttx/libc/math/lib_libsqrtapprox.c deleted file mode 100644 index b6a9b0d54c..0000000000 --- a/nuttx/libc/math/lib_libsqrtapprox.c +++ /dev/null @@ -1,50 +0,0 @@ -/************************************************************************ - * libc/math/lib_libsqrtapprox.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float lib_sqrtapprox(float x) -{ - int32_t i; - - /* Floats + bit manipulation = +inf fun! */ - - i = *((int32_t *) & x); - i = 0x1fc00000 + (i >> 1); - x = *((float *)&i); - - return x; -} diff --git a/nuttx/libc/math/lib_log.c b/nuttx/libc/math/lib_log.c deleted file mode 100644 index 7156f6b411..0000000000 --- a/nuttx/libc/math/lib_log.c +++ /dev/null @@ -1,82 +0,0 @@ -/************************************************************************ - * libc/math/lib_log.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double log(double x) -{ - double y, y_old, ey, epsilon; - - y = 0.0; - y_old = 1.0; - epsilon = DBL_EPSILON; - - while (y > y_old + epsilon || y < y_old - epsilon) - { - y_old = y; - ey = exp(y); - y -= (ey - x) / ey; - - if (y > 700.0) - { - y = 700.0; - } - - if (y < -700.0) - { - y = -700.0; - } - - epsilon = (fabs(y) > 1.0) ? fabs(y) * DBL_EPSILON : DBL_EPSILON; - } - - if (y == 700.0) - { - return INFINITY; - } - - if (y == -700.0) - { - return INFINITY; - } - - return y; -} -#endif diff --git a/nuttx/libc/math/lib_log10.c b/nuttx/libc/math/lib_log10.c deleted file mode 100644 index 9daa914925..0000000000 --- a/nuttx/libc/math/lib_log10.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_log10.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double log10(double x) -{ - return (log(x) / M_LN10); -} -#endif diff --git a/nuttx/libc/math/lib_log10f.c b/nuttx/libc/math/lib_log10f.c deleted file mode 100644 index 778daedd5b..0000000000 --- a/nuttx/libc/math/lib_log10f.c +++ /dev/null @@ -1,41 +0,0 @@ -/************************************************************************ - * libc/math/lib_log10f.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float log10f(float x) -{ - return (logf(x) / M_LN10); -} diff --git a/nuttx/libc/math/lib_log10l.c b/nuttx/libc/math/lib_log10l.c deleted file mode 100644 index efbeb721b4..0000000000 --- a/nuttx/libc/math/lib_log10l.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_log10l.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double log10l(long double x) -{ - return (logl(x) / M_LN10); -} -#endif diff --git a/nuttx/libc/math/lib_log2.c b/nuttx/libc/math/lib_log2.c deleted file mode 100644 index 4da39acdc3..0000000000 --- a/nuttx/libc/math/lib_log2.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_log2.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double log2(double x) -{ - return (log(x) / M_LN2); -} -#endif diff --git a/nuttx/libc/math/lib_log2f.c b/nuttx/libc/math/lib_log2f.c deleted file mode 100644 index f514e5a9e0..0000000000 --- a/nuttx/libc/math/lib_log2f.c +++ /dev/null @@ -1,41 +0,0 @@ -/************************************************************************ - * libc/math/lib_log2f.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float log2f(float x) -{ - return (logf(x) / M_LN2); -} diff --git a/nuttx/libc/math/lib_log2l.c b/nuttx/libc/math/lib_log2l.c deleted file mode 100644 index 21e80a930f..0000000000 --- a/nuttx/libc/math/lib_log2l.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_log2l.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double log2l(long double x) -{ - return (logl(x) / M_LN2); -} -#endif diff --git a/nuttx/libc/math/lib_logf.c b/nuttx/libc/math/lib_logf.c deleted file mode 100644 index 3815fef84c..0000000000 --- a/nuttx/libc/math/lib_logf.c +++ /dev/null @@ -1,77 +0,0 @@ -/************************************************************************ - * libc/math/lib_logf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float logf(float x) -{ - float y, y_old, ey, epsilon; - - y = 0.0; - y_old = 1.0; - epsilon = FLT_EPSILON; - - while (y > y_old + epsilon || y < y_old - epsilon) - { - y_old = y; - ey = exp(y); - y -= (ey - x) / ey; - - if (y > 700.0) - { - y = 700.0; - } - - if (y < -700.0) - { - y = -700.0; - } - - epsilon = (fabs(y) > 1.0) ? fabs(y) * FLT_EPSILON : FLT_EPSILON; - } - - if (y == 700.0) - { - return INFINITY; - } - - if (y == -700.0) - { - return INFINITY; - } - - return y; -} diff --git a/nuttx/libc/math/lib_logl.c b/nuttx/libc/math/lib_logl.c deleted file mode 100644 index 6128160114..0000000000 --- a/nuttx/libc/math/lib_logl.c +++ /dev/null @@ -1,80 +0,0 @@ -/************************************************************************ - * libc/math/lib_lol.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double logl(long double x) -{ - long double y, y_old, ey, epsilon; - - y = 0.0; - y_old = 1.0; - epsilon = LDBL_EPSILON; - - while (y > y_old + epsilon || y < y_old - epsilon) - { - y_old = y; - ey = expl(y); - y -= (ey - x) / ey; - - if (y > 700.0) - { - y = 700.0; - } - - if (y < -700.0) - { - y = -700.0; - } - } - - if (y == 700.0) - { - return INFINITY; - } - - if (y == -700.0) - { - return INFINITY; - } - - return y; -} -#endif diff --git a/nuttx/libc/math/lib_modf.c b/nuttx/libc/math/lib_modf.c deleted file mode 100644 index f3f25f6fb0..0000000000 --- a/nuttx/libc/math/lib_modf.c +++ /dev/null @@ -1,58 +0,0 @@ -/************************************************************************ - * libc/math/lib_modf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double modf(double x, double *iptr) -{ - if (fabs(x) >= 4503599627370496.0) - { - *iptr = x; - return 0.0; - } - else if (fabs(x) < 1.0) - { - *iptr = 0.0; - return x; - } - else - { - *iptr = (double)(int64_t) x; - return (x - *iptr); - } -} -#endif diff --git a/nuttx/libc/math/lib_modff.c b/nuttx/libc/math/lib_modff.c deleted file mode 100644 index 28d3a3ae0b..0000000000 --- a/nuttx/libc/math/lib_modff.c +++ /dev/null @@ -1,55 +0,0 @@ -/************************************************************************ - * libc/math/lib_modff.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float modff(float x, float *iptr) -{ - if (fabsf(x) >= 8388608.0) - { - *iptr = x; - return 0.0; - } - else if (fabs(x) < 1.0) - { - *iptr = 0.0; - return x; - } - else - { - *iptr = (float)(int)x; - return (x - *iptr); - } -} diff --git a/nuttx/libc/math/lib_modfl.c b/nuttx/libc/math/lib_modfl.c deleted file mode 100644 index 77bba0e0c0..0000000000 --- a/nuttx/libc/math/lib_modfl.c +++ /dev/null @@ -1,61 +0,0 @@ -/************************************************************************ - * libc/math/lib_modfl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double modfl(long double x, long double *iptr) -{ - if (fabs(x) >= 4503599627370496.0) - { - *iptr = x; - return 0.0; - } - else if (fabs(x) < 1.0) - { - *iptr = 0.0; - return x; - } - else - { - *iptr = (long double)(int64_t) x; - return (x - *iptr); - } -} -#endif diff --git a/nuttx/libc/math/lib_pow.c b/nuttx/libc/math/lib_pow.c deleted file mode 100644 index a19d491fad..0000000000 --- a/nuttx/libc/math/lib_pow.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_pow.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double pow(double b, double e) -{ - return exp(e * log(b)); -} -#endif diff --git a/nuttx/libc/math/lib_powf.c b/nuttx/libc/math/lib_powf.c deleted file mode 100644 index 5709048982..0000000000 --- a/nuttx/libc/math/lib_powf.c +++ /dev/null @@ -1,41 +0,0 @@ -/************************************************************************ - * libc/math/lib_powf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float powf(float b, float e) -{ - return expf(e * logf(b)); -} diff --git a/nuttx/libc/math/lib_powl.c b/nuttx/libc/math/lib_powl.c deleted file mode 100644 index 81438217cf..0000000000 --- a/nuttx/libc/math/lib_powl.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_powl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double powl(long double b, long double e) -{ - return expl(e * logl(b)); -} -#endif diff --git a/nuttx/libc/math/lib_sin.c b/nuttx/libc/math/lib_sin.c deleted file mode 100644 index e005d98cb6..0000000000 --- a/nuttx/libc/math/lib_sin.c +++ /dev/null @@ -1,114 +0,0 @@ -/************************************************************************ - * libc/math/lib_sin.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -#ifdef CONFIG_HAVE_DOUBLE - -/************************************************************************ - * Private Data - ************************************************************************/ - -static double _dbl_inv_fact[] = -{ - 1.0 / 1.0, // 1 / 1! - 1.0 / 6.0, // 1 / 3! - 1.0 / 120.0, // 1 / 5! - 1.0 / 5040.0, // 1 / 7! - 1.0 / 362880.0, // 1 / 9! - 1.0 / 39916800.0, // 1 / 11! - 1.0 / 6227020800.0, // 1 / 13! - 1.0 / 1307674368000.0, // 1 / 15! - 1.0 / 355687428096000.0, // 1 / 17! - 1.0 / 121645100408832000.0, // 1 / 19! -}; - -/************************************************************************ - * Public Functions - ************************************************************************/ - -double sin(double x) -{ - double x_squared; - double sin_x; - size_t i; - - /* Move x to [-pi, pi) */ - - x = fmod(x, 2 * M_PI); - if (x >= M_PI) - { - x -= 2 * M_PI; - } - - if (x < -M_PI) - { - x += 2 * M_PI; - } - - /* Move x to [-pi/2, pi/2) */ - - if (x >= M_PI_2) - { - x = M_PI - x; - } - - if (x < -M_PI_2) - { - x = -M_PI - x; - } - - x_squared = x * x; - sin_x = 0.0; - - /* Perform Taylor series approximation for sin(x) with ten terms */ - - for (i = 0; i < 10; i++) - { - if (i % 2 == 0) - { - sin_x += x * _dbl_inv_fact[i]; - } - else - { - sin_x -= x * _dbl_inv_fact[i]; - } - - x *= x_squared; - } - - return sin_x; -} -#endif diff --git a/nuttx/libc/math/lib_sinf.c b/nuttx/libc/math/lib_sinf.c deleted file mode 100644 index 9e493d8efc..0000000000 --- a/nuttx/libc/math/lib_sinf.c +++ /dev/null @@ -1,104 +0,0 @@ -/************************************************************************ - * libc/math/lib_sinf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -/************************************************************************ - * Private Data - ************************************************************************/ - -static float _flt_inv_fact[] = -{ - 1.0 / 1.0, // 1 / 1! - 1.0 / 6.0, // 1 / 3! - 1.0 / 120.0, // 1 / 5! - 1.0 / 5040.0, // 1 / 7! - 1.0 / 362880.0, // 1 / 9! - 1.0 / 39916800.0, // 1 / 11! -}; - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float sinf(float x) -{ - float x_squared; - float sin_x; - size_t i; - - /* Move x to [-pi, pi) */ - - x = fmodf(x, 2 * M_PI); - if (x >= M_PI) - { - x -= 2 * M_PI; - } - - if (x < -M_PI) - { - x += 2 * M_PI; - } - - /* Move x to [-pi/2, pi/2) */ - - if (x >= M_PI_2) - { - x = M_PI - x; - } - - if (x < -M_PI_2) - { - x = -M_PI - x; - } - - x_squared = x * x; - sin_x = 0.0; - - /* Perform Taylor series approximation for sin(x) with six terms */ - - for (i = 0; i < 6; i++) - { - if (i % 2 == 0) - { - sin_x += x * _flt_inv_fact[i]; - } - else - { - sin_x -= x * _flt_inv_fact[i]; - } - - x *= x_squared; - } - - return sin_x; -} diff --git a/nuttx/libc/math/lib_sinh.c b/nuttx/libc/math/lib_sinh.c deleted file mode 100644 index 0c3e2d11d8..0000000000 --- a/nuttx/libc/math/lib_sinh.c +++ /dev/null @@ -1,47 +0,0 @@ -/************************************************************************ - * libc/math/lib_sinh.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double sinh(double x) -{ - x = exp(x); - return ((x - (1.0 / x)) / 2.0); -} -#endif diff --git a/nuttx/libc/math/lib_sinhf.c b/nuttx/libc/math/lib_sinhf.c deleted file mode 100644 index e9d198440f..0000000000 --- a/nuttx/libc/math/lib_sinhf.c +++ /dev/null @@ -1,42 +0,0 @@ -/************************************************************************ - * libc/math/lib_sinhf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float sinhf(float x) -{ - x = expf(x); - return ((x - (1.0 / x)) / 2.0); -} diff --git a/nuttx/libc/math/lib_sinhl.c b/nuttx/libc/math/lib_sinhl.c deleted file mode 100644 index a1bcad81e8..0000000000 --- a/nuttx/libc/math/lib_sinhl.c +++ /dev/null @@ -1,47 +0,0 @@ -/************************************************************************ - * libc/math/lib_sinhl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double sinhl(long double x) -{ - x = expl(x); - return ((x - (1.0 / x)) / 2.0); -} -#endif diff --git a/nuttx/libc/math/lib_sinl.c b/nuttx/libc/math/lib_sinl.c deleted file mode 100644 index 6ed539a39d..0000000000 --- a/nuttx/libc/math/lib_sinl.c +++ /dev/null @@ -1,114 +0,0 @@ -/************************************************************************ - * libc/math/lib_sinl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -#ifdef CONFIG_HAVE_LONG_DOUBLE - -/************************************************************************ - * Private Data - ************************************************************************/ - -static long double _ldbl_inv_fact[] = -{ - 1.0 / 1.0, // 1 / 1! - 1.0 / 6.0, // 1 / 3! - 1.0 / 120.0, // 1 / 5! - 1.0 / 5040.0, // 1 / 7! - 1.0 / 362880.0, // 1 / 9! - 1.0 / 39916800.0, // 1 / 11! - 1.0 / 6227020800.0, // 1 / 13! - 1.0 / 1307674368000.0, // 1 / 15! - 1.0 / 355687428096000.0, // 1 / 17! - 1.0 / 121645100408832000.0, // 1 / 19! -}; - -/************************************************************************ - * Public Functions - ************************************************************************/ - -long double sinl(long double x) -{ - long double x_squared; - long double sin_x; - size_t i; - - /* Move x to [-pi, pi) */ - - x = fmodl(x, 2 * M_PI); - if (x >= M_PI) - { - x -= 2 * M_PI; - } - - if (x < -M_PI) - { - x += 2 * M_PI; - } - - /* Move x to [-pi/2, pi/2) */ - - if (x >= M_PI_2) - { - x = M_PI - x; - } - - if (x < -M_PI_2) - { - x = -M_PI - x; - } - - x_squared = x * x; - sin_x = 0.0; - - /* Perform Taylor series approximation for sin(x) with ten terms */ - - for (i = 0; i < 10; i++) - { - if (i % 2 == 0) - { - sin_x += x * _ldbl_inv_fact[i]; - } - else - { - sin_x -= x * _ldbl_inv_fact[i]; - } - - x *= x_squared; - } - - return sin_x; -} -#endif diff --git a/nuttx/libc/math/lib_sqrt.c b/nuttx/libc/math/lib_sqrt.c deleted file mode 100644 index e8a1c42ea2..0000000000 --- a/nuttx/libc/math/lib_sqrt.c +++ /dev/null @@ -1,99 +0,0 @@ -/************************************************************************ - * libc/math/lib_sqrt.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -#include "lib_internal.h" - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double sqrt(double x) -{ - long double y, y1; - - if (x < 0.0) - { - errno = EDOM; - return NAN; - } - - if (isnan(x)) - { - return NAN; - } - - if (isinf(x)) - { - return INFINITY; - } - - if (x == 0.0) - { - return 0.0; - } - - /* Guess square root (using bit manipulation) */ - - y = lib_sqrtapprox(x); - - /* Perform four iterations of approximation. This number (4) is - * definitely optimal - */ - - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - - /* If guess was terribe (out of range of float). Repeat approximation - * until convergence. - */ - - if (y * y < x - 1.0 || y * y > x + 1.0) - { - y1 = -1.0; - while (y != y1) - { - y1 = y; - y = 0.5 * (y + x / y); - } - } - - return y; -} -#endif diff --git a/nuttx/libc/math/lib_sqrtf.c b/nuttx/libc/math/lib_sqrtf.c deleted file mode 100644 index cf45ccacc3..0000000000 --- a/nuttx/libc/math/lib_sqrtf.c +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************ - * libc/math/lib_sqrtf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -#include "lib_internal.h" - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float sqrtf(float x) -{ - float y; - - /* Filter out invalid/trivial inputs */ - - if (x < 0.0) - { - errno = EDOM; - return NAN; - } - - if (isnan(x)) - { - return NAN; - } - - if (isinf(x)) - { - return INFINITY; - } - - if (x == 0.0) - { - return 0.0; - } - - /* Guess square root (using bit manipulation) */ - - y = lib_sqrtapprox(x); - - /* Perform three iterations of approximation. This number (3) is - * definitely optimal - */ - - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - - return y; -} diff --git a/nuttx/libc/math/lib_sqrtl.c b/nuttx/libc/math/lib_sqrtl.c deleted file mode 100644 index 4035992feb..0000000000 --- a/nuttx/libc/math/lib_sqrtl.c +++ /dev/null @@ -1,101 +0,0 @@ -/************************************************************************ - * libc/math/lib_sqrtl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009-2011 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include -#include - -#include "lib_internal.h" - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double sqrtl(long double x) -{ - long double y, y1; - - /* Filter out invalid/trivial inputs */ - - if (x < 0.0) - { - errno = EDOM; - return NAN; - } - - if (isnan(x)) - { - return NAN; - } - - if (isinf(x)) - { - return INFINITY; - } - - if (x == 0.0) - { - return 0.0; - } - - /* Guess square root (using bit manipulation) */ - - y = lib_sqrtapprox(x); - - /* Perform four iterations of approximation. This number (4) is - * definitely optimal - */ - - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - y = 0.5 * (y + x / y); - - /* If guess was terribe (out of range of float). Repeat approximation - * until convergence - */ - - if (y * y < x - 1.0 || y * y > x + 1.0) - { - y1 = -1.0; - while (y != y1) - { - y1 = y; - y = 0.5 * (y + x / y); - } - } - - return y; -} -#endif diff --git a/nuttx/libc/math/lib_tan.c b/nuttx/libc/math/lib_tan.c deleted file mode 100644 index 4c091c09bc..0000000000 --- a/nuttx/libc/math/lib_tan.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_tan.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double tan(double x) -{ - return (sin(x) / cos(x)); -} -#endif diff --git a/nuttx/libc/math/lib_tanf.c b/nuttx/libc/math/lib_tanf.c deleted file mode 100644 index 0c9110a0b7..0000000000 --- a/nuttx/libc/math/lib_tanf.c +++ /dev/null @@ -1,41 +0,0 @@ -/************************************************************************ - * libc/math/lib_tanf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float tanf(float x) -{ - return (sinf(x) / cosf(x)); -} diff --git a/nuttx/libc/math/lib_tanh.c b/nuttx/libc/math/lib_tanh.c deleted file mode 100644 index 3b9ea0f418..0000000000 --- a/nuttx/libc/math/lib_tanh.c +++ /dev/null @@ -1,49 +0,0 @@ -/************************************************************************ - * libc/math/lib_tanh.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_DOUBLE -double tanh(double x) -{ - double x0 = exp(x); - double x1 = 1.0 / x0; - - return ((x0 + x1) / (x0 - x1)); -} -#endif diff --git a/nuttx/libc/math/lib_tanhf.c b/nuttx/libc/math/lib_tanhf.c deleted file mode 100644 index 43d4182044..0000000000 --- a/nuttx/libc/math/lib_tanhf.c +++ /dev/null @@ -1,44 +0,0 @@ -/************************************************************************ - * libc/math/lib_tanhf.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -float tanhf(float x) -{ - float x0 = expf(x); - float x1 = 1.0 / x0; - - return ((x0 + x1) / (x0 - x1)); -} diff --git a/nuttx/libc/math/lib_tanhl.c b/nuttx/libc/math/lib_tanhl.c deleted file mode 100644 index 5aafd1e7b9..0000000000 --- a/nuttx/libc/math/lib_tanhl.c +++ /dev/null @@ -1,49 +0,0 @@ -/************************************************************************ - * libc/math/lib_tanhl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double tanhl(long double x) -{ - long double x0 = exp(x); - long double x1 = 1.0 / x0; - - return ((x0 + x1) / (x0 - x1)); -} -#endif diff --git a/nuttx/libc/math/lib_tanl.c b/nuttx/libc/math/lib_tanl.c deleted file mode 100644 index e77abe0f1e..0000000000 --- a/nuttx/libc/math/lib_tanl.c +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************ - * libc/math/lib_tanl.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Ported by: Darcy Gong - * - * It derives from the Rhombs OS math library by Nick Johnson which has - * a compatibile, MIT-style license: - * - * Copyright (C) 2009, 2010 Nick Johnson - * - * Permission to use, copy, modify, and distribute this software for any - * purpose with or without fee is hereby granted, provided that the above - * copyright notice and this permission notice appear in all copies. - * - * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES - * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR - * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES - * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN - * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF - * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include - -/************************************************************************ - * Public Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_DOUBLE -long double tanl(long double x) -{ - return (sinl(x) / cosl(x)); -} -#endif diff --git a/nuttx/libc/misc/Make.defs b/nuttx/libc/misc/Make.defs deleted file mode 100644 index f4284ac60c..0000000000 --- a/nuttx/libc/misc/Make.defs +++ /dev/null @@ -1,69 +0,0 @@ -############################################################################ -# libc/misc/Make.defs -# -# 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. -# -############################################################################ - -# Add the internal C files to the build - -CSRCS += lib_init.c lib_filesem.c - -# Add C files that depend on file OR socket descriptors - -ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) - -CSRCS += lib_sendfile.c -ifneq ($(CONFIG_NFILE_STREAMS),0) -CSRCS += lib_streamsem.c -endif - -else -ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0) - -CSRCS += lib_sendfile.c -ifneq ($(CONFIG_NFILE_STREAMS),0) -CSRCS += lib_streamsem.c -endif - -endif -endif - -# Add the miscellaneous C files to the build - -CSRCS += lib_match.c -CSRCS += lib_crc32.c -CSRCS += lib_dbg.c lib_dumpbuffer.c - -# Add the misc directory to the build - -DEPPATH += --dep-path misc -VPATH += :misc diff --git a/nuttx/libc/misc/lib_crc32.c b/nuttx/libc/misc/lib_crc32.c deleted file mode 100644 index ae73ba3d79..0000000000 --- a/nuttx/libc/misc/lib_crc32.c +++ /dev/null @@ -1,123 +0,0 @@ -/************************************************************************************************ - * libc/misc/lib_crc32.c - * - * This file is a part of NuttX: - * - * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. - * - * The logic in this file was developed by Gary S. Brown: - * - * COPYRIGHT (C) 1986 Gary S. Brown. You may use this program, or code or tables - * extracted from it, as desired without restriction. - * - * First, the polynomial itself and its table of feedback terms. The polynomial is: - * - * X^32+X^26+X^23+X^22+X^16+X^12+X^11+X^10+X^8+X^7+X^5+X^4+X^2+X^1+X^0 - * - * Note that we take it "backwards" and put the highest-order term in the lowest-order bit. - * The X^32 term is "implied"; the LSB is the X^31 term, etc. The X^0 term (usually shown - * as "+1") results in the MSB being 1 - * - * Note that the usual hardware shift register implementation, which is what we're using - * (we're merely optimizing it by doing eight-bit chunks at a time) shifts bits into the - * lowest-order term. In our implementation, that means shifting towards the right. Why - * do we do it this way? Because the calculated CRC must be transmitted in order from - * highest-order term to lowest-order term. UARTs transmit characters in order from LSB - * to MSB. By storing the CRC this way we hand it to the UART in the order low-byte to - * high-byte; the UART sends each low-bit to hight-bit; and the result is transmission bit - * by bit from highest- to lowest-order term without requiring any bit shuffling on our - * part. Reception works similarly - * - * The feedback terms table consists of 256, 32-bit entries. Notes - * - * - The table can be generated at runtime if desired; code to do so is shown later. It - * might not be obvious, but the feedback terms simply represent the results of eight - * shift/xor operations for all combinations of data and CRC register values - * - * - The values must be right-shifted by eight bits by the updcrc logic; the shift must - * be u_(bring in zeroes). On some hardware you could probably optimize the shift in - * assembler by using byte-swap instructions polynomial $edb88320 - ************************************************************************************************/ - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include -#include - -/************************************************************************************************ - * Private Data - ************************************************************************************************/ - -static const uint32_t crc32_tab[] = -{ - 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3, - 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91, - 0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7, - 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5, - 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b, - 0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59, - 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f, - 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d, - 0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433, - 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01, - 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457, - 0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65, - 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb, - 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9, - 0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f, - 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad, - 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683, - 0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1, - 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7, - 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5, - 0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b, - 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79, - 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f, - 0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d, - 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713, - 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21, - 0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777, - 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45, - 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db, - 0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9, - 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf, - 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d -}; - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ -/************************************************************************************************ - * Name: crc32part - * - * Description: - * Continue CRC calculation on a part of the buffer. - * - ************************************************************************************************/ - -uint32_t crc32part(FAR const uint8_t *src, size_t len, uint32_t crc32val) -{ - size_t i; - - for (i = 0; i < len; i++) - { - crc32val = crc32_tab[(crc32val ^ src[i]) & 0xff] ^ (crc32val >> 8); - } - return crc32val; -} - -/************************************************************************************************ - * Name: crc32 - * - * Description: - * Return a 32-bit CRC of the contents of the 'src' buffer, length 'len' - * - ************************************************************************************************/ - -uint32_t crc32(FAR const uint8_t *src, size_t len) -{ - return crc32part(src, len, 0); -} diff --git a/nuttx/libc/misc/lib_dbg.c b/nuttx/libc/misc/lib_dbg.c deleted file mode 100644 index 5605ff828f..0000000000 --- a/nuttx/libc/misc/lib_dbg.c +++ /dev/null @@ -1,165 +0,0 @@ -/**************************************************************************** - * libc/misc/lib_dbg.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/* Debug output is initially disabled */ - -#ifdef CONFIG_DEBUG_ENABLE -bool g_dbgenable; -#endif - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: dbg_enable - * - * Description: - * Enable or disable debug output. - * - ****************************************************************************/ - -#ifdef CONFIG_DEBUG_ENABLE -void dbg_enable(bool enable) -{ - g_dbgenable = enable; -} -#endif - -/**************************************************************************** - * Name: dbg, lldbg, vdbg - * - * Description: - * If the cross-compiler's pre-processor does not support variable - * length arguments, then these additional APIs will be built. - * - ****************************************************************************/ - -#ifndef CONFIG_CPP_HAVE_VARARGS -#ifdef CONFIG_DEBUG -int dbg(const char *format, ...) -{ - va_list ap; - int ret; - -#ifdef CONFIG_DEBUG_ENABLE - ret = 0; - if (g_dbgenable) -#endif - { - va_start(ap, format); - ret = lib_rawvprintf(format, ap); - va_end(ap); - } - - return ret; -} - -#ifdef CONFIG_ARCH_LOWPUTC -int lldbg(const char *format, ...) -{ - va_list ap; - int ret; - -#ifdef CONFIG_DEBUG_ENABLE - ret = 0; - if (g_dbgenable) -#endif - { - va_start(ap, format); - ret = lib_lowvprintf(format, ap); - va_end(ap); - } - - return ret; -} -#endif - -#ifdef CONFIG_DEBUG_VERBOSE -int vdbg(const char *format, ...) -{ - va_list ap; - int ret; - -#ifdef CONFIG_DEBUG_ENABLE - ret = 0; - if (g_dbgenable) -#endif - { - va_start(ap, format); - ret = lib_rawvprintf(format, ap); - va_end(ap); - } - - return ret; -} - -#ifdef CONFIG_ARCH_LOWPUTC -int llvdbg(const char *format, ...) -{ - va_list ap; - int ret; - -#ifdef CONFIG_DEBUG_ENABLE - ret = 0; - if (g_dbgenable) -#endif - { - va_start(ap, format); - ret = lib_lowvprintf(format, ap); - va_end(ap); - } - - return ret; -} -#endif /* CONFIG_ARCH_LOWPUTC */ -#endif /* CONFIG_DEBUG_VERBOSE */ -#endif /* CONFIG_DEBUG */ -#endif /* CONFIG_CPP_HAVE_VARARGS */ diff --git a/nuttx/libc/misc/lib_dumpbuffer.c b/nuttx/libc/misc/lib_dumpbuffer.c deleted file mode 100644 index 52158b2204..0000000000 --- a/nuttx/libc/misc/lib_dumpbuffer.c +++ /dev/null @@ -1,129 +0,0 @@ -/**************************************************************************** - * libc/misc/lib_dumpbuffer.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include - -#include -#include - -/**************************************************************************** - * Pre-processor definitions - ****************************************************************************/ - -/* Select the lowest level debug interface available */ - -#ifdef CONFIG_CPP_HAVE_VARARGS -# ifdef CONFIG_ARCH_LOWPUTC -# define message(format, arg...) lib_lowprintf(format, ##arg) -# else -# define message(format, arg...) lib_rawprintf(format, ##arg) -# endif -#else -# ifdef CONFIG_ARCH_LOWPUTC -# define message lib_lowprintf -# else -# define message lib_rawprintf -# endif -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_dumpbuffer - * - * Description: - * Do a pretty buffer dump - * - ****************************************************************************/ - -void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer, unsigned int buflen) -{ - int i, j, k; - - message("%s (%p):\n", msg, buffer); - for (i = 0; i < buflen; i += 32) - { - message("%04x: ", i); - for (j = 0; j < 32; j++) - { - k = i + j; - - if (j == 16) - { - message(" "); - } - - if (k < buflen) - { - message("%02x", buffer[k]); - } - else - { - message(" "); - } - } - - message(" "); - for (j = 0; j < 32; j++) - { - k = i + j; - - if (j == 16) - { - message(" "); - } - - if (k < buflen) - { - if (buffer[k] >= 0x20 && buffer[k] < 0x7f) - { - message("%c", buffer[k]); - } - else - { - message("."); - } - } - } - message("\n"); - } -} diff --git a/nuttx/libc/misc/lib_filesem.c b/nuttx/libc/misc/lib_filesem.c deleted file mode 100644 index 5cc4624ec6..0000000000 --- a/nuttx/libc/misc/lib_filesem.c +++ /dev/null @@ -1,145 +0,0 @@ -/************************************************************************ - * libc/misc/lib_filesem.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -#if CONFIG_STDIO_BUFFER_SIZE > 0 - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -/************************************************************************ - * Private Data - ************************************************************************/ - -/************************************************************************ - * Global Functions - ************************************************************************/ - -/************************************************************************ - * lib_sem_initialize - ************************************************************************/ - -void lib_sem_initialize(FAR struct file_struct *stream) -{ - /* Initialize the LIB semaphore to one (to support one-at- - * a-time access to private data sets. - */ - - (void)sem_init(&stream->fs_sem, 0, 1); - - stream->fs_holder = -1; - stream->fs_counts = 0; -} - -/************************************************************************ - * lib_take_semaphore - ************************************************************************/ - -void lib_take_semaphore(FAR struct file_struct *stream) -{ - pid_t my_pid = getpid(); - - /* Do I already have the semaphore? */ - - if (stream->fs_holder == my_pid) - { - /* Yes, just increment the number of references that I have */ - - stream->fs_counts++; - } - else - { - /* Take the semaphore (perhaps waiting) */ - - while (sem_wait(&stream->fs_sem) != 0) - { - /* The only case that an error should occr here is if - * the wait was awakened by a signal. - */ - - ASSERT(get_errno() == EINTR); - } - - /* We have it. Claim the stak and return */ - - stream->fs_holder = my_pid; - stream->fs_counts = 1; - } -} - -/************************************************************************ - * lib_give_semaphore - ************************************************************************/ - -void lib_give_semaphore(FAR struct file_struct *stream) -{ - pid_t my_pid = getpid(); - - /* I better be holding at least one reference to the semaphore */ - - ASSERT(stream->fs_holder == my_pid); - - /* Do I hold multiple references to the semphore */ - - if (stream->fs_counts > 1) - { - /* Yes, just release one count and return */ - - stream->fs_counts--; - } - else - { - /* Nope, this is the last reference I have */ - - stream->fs_holder = -1; - stream->fs_counts = 0; - ASSERT(sem_post(&stream->fs_sem) == 0); - } -} -#endif /* CONFIG_STDIO_BUFFER_SIZE */ diff --git a/nuttx/libc/misc/lib_init.c b/nuttx/libc/misc/lib_init.c deleted file mode 100644 index 6a120f7b13..0000000000 --- a/nuttx/libc/misc/lib_init.c +++ /dev/null @@ -1,207 +0,0 @@ -/************************************************************ - * libc/misc/lib_init.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -#include -#include -#include - -#include -#include -#include - -#include "lib_internal.h" - -/************************************************************ - * Definitions - ************************************************************/ - -/************************************************************ - * Private Variables - ************************************************************/ - -/************************************************************ - * Private Functions - ************************************************************/ - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * lib_initialize - ************************************************************/ - -/* General library initialization hook */ - -void weak_const_function lib_initialize(void) -{ -} - -#if CONFIG_NFILE_STREAMS > 0 -/* The following function is called when a new TCB is allocated. It - * creates the streamlist instance that is stored in the TCB. - */ - -FAR struct streamlist *lib_alloclist(void) -{ - FAR struct streamlist *list; - list = (FAR struct streamlist*)lib_zalloc(sizeof(struct streamlist)); - if (list) - { - int i; - - /* Start with a reference count of one */ - - list->sl_crefs = 1; - - /* Initialize the list access mutex */ - - (void)sem_init(&list->sl_sem, 0, 1); - - /* Initialize each FILE structure */ - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) - { - /* Clear the IOB */ - - memset(&list->sl_streams[i], 0, sizeof(FILE)); - - /* Indicate not opened */ - - list->sl_streams[i].fs_filedes = -1; - - /* Initialize the stream semaphore to one to support one-at- - * a-time access to private data sets. - */ - - lib_sem_initialize(&list->sl_streams[i]); - } - } - return list; - -} - -/* This function is called when a TCB is closed (such as with - * pthread_create(). It increases the reference count on the stream - * list. - */ - -void lib_addreflist(FAR struct streamlist *list) -{ - if (list) - { - /* Increment the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - list->sl_crefs++; - irqrestore(flags); - } -} - -/* this function is called when a TCB is destroyed. Note that is - * does not close the file by release this inode. This happens - * separately when the file descriptor list is freed. - */ - -void lib_releaselist(FAR struct streamlist *list) -{ - int crefs; - if (list) - { - /* Decrement the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - crefs = --(list->sl_crefs); - irqrestore(flags); - - /* If the count decrements to zero, then there is no reference - * to the structure and it should be deallocated. Since there - * are references, it would be an error if any task still held - * a reference to the list's semaphore. - */ - - if (crefs <= 0) - { -#if CONFIG_STDIO_BUFFER_SIZE > 0 - int i; -#endif - /* Destroy the semaphore and release the filelist */ - - (void)sem_destroy(&list->sl_sem); - - /* Release each stream in the list */ - -#if CONFIG_STDIO_BUFFER_SIZE > 0 - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) - { - /* Destroy the semaphore that protects the IO buffer */ - - (void)sem_destroy(&list->sl_streams[i].fs_sem); - - /* Release the IO buffer */ - if (list->sl_streams[i].fs_bufstart) - { - sched_free(list->sl_streams[i].fs_bufstart); - } - } -#endif - /* Finally, release the list itself */ - - sched_free(list); - } - } -} - -#endif /* CONFIG_NFILE_STREAMS */ - - diff --git a/nuttx/libc/misc/lib_match.c b/nuttx/libc/misc/lib_match.c deleted file mode 100644 index a8cfad3293..0000000000 --- a/nuttx/libc/misc/lib_match.c +++ /dev/null @@ -1,148 +0,0 @@ -/**************************************************************************** - * libc/misc/lib_match.c - simple shell-style filename matcher - * - * Simple shell-style filename pattern matcher written by Jef Poskanzer - * This pattern matcher only handles '?', '*' and '**', and multiple - * patterns separated by '|'. - * - * Copyright © 1995,2000 by Jef Poskanzer . - * All rights reserved. - * - * 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. - * - * THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: match_one - * - * Description: - * Does all of the work for one '|' delimited pattern - * - * Returned Value: - * Returns 1 (match) or 0 (no-match). - * - ****************************************************************************/ - -static int match_one(const char *pattern, int patlen, const char *string) -{ - const char *p; - int pl; - int i; - - for (p = pattern; p - pattern < patlen; p++, string++) - { - if (*p == '?' && *string != '\0') - { - continue; - } - - if (*p == '*') - { - p++; - if (*p == '*') - { - /* Double-wildcard matches anything. */ - - p++; - i = strlen(string); - } - else - { - /* Single-wildcard matches anything but slash. */ - - i = strcspn(string, "/"); - } - - pl = patlen - (p - pattern); - for (; i >= 0; i--) - { - if (match_one(p, pl, &(string[i]))) - { - return 1; - } - } - return 0; - } - - if (*p != *string) - { - return 0; - } - } - - if (*string == '\0') - { - return 1; - } - return 0; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: match - * - * Description: - * Simple shell-style filename pattern matcher written by Jef Poskanzer - * This pattern matcher only handles '?', '*' and '**', and multiple - * patterns separated by '|'. - * - * Returned Value: - * Returns 1 (match) or 0 (no-match). - * - ****************************************************************************/ - -int match(const char *pattern, const char *string) -{ - const char *or; - - for (;;) - { - or = strchr(pattern, '|'); - if (or == (char *)0) - { - return match_one(pattern, strlen(pattern), string); - } - - if (match_one(pattern, or - pattern, string)) - { - return 1; - } - - pattern = or + 1; - } -} - diff --git a/nuttx/libc/misc/lib_sendfile.c b/nuttx/libc/misc/lib_sendfile.c deleted file mode 100644 index 8a38dc317e..0000000000 --- a/nuttx/libc/misc/lib_sendfile.c +++ /dev/null @@ -1,297 +0,0 @@ -/************************************************************************ - * libc/misc/lib_streamsem.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0 - -/************************************************************************ - * Private types - ************************************************************************/ - -/************************************************************************ - * Private Variables - ************************************************************************/ - -/************************************************************************ - * Public Variables - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: sendfile - * - * Description: - * sendfile() copies data between one file descriptor and another. - * sendfile() basically just wraps a sequence of reads() and writes() - * to perform a copy. It serves a purpose in systems where there is - * a penalty for copies to between user and kernal space, but really - * nothing in NuttX but provide some Linux compatible (and adding - * another 'almost standard' interface). - * - * NOTE: This interface is *not* specified in POSIX.1-2001, or other - * standards. The implementation here is very similar to the Linux - * sendfile interface. Other UNIX systems implement sendfile() with - * different semantics and prototypes. sendfile() should not be used - * in portable programs. - * - * Input Parmeters: - * infd - A file (or socket) descriptor opened for reading - * outfd - A descriptor opened for writing. - * offset - If 'offset' is not NULL, then it points to a variable - * holding the file offset from which sendfile() will start - * reading data from 'infd'. When sendfile() returns, this - * variable will be set to the offset of the byte following - * the last byte that was read. If 'offset' is not NULL, - * then sendfile() does not modify the current file offset of - * 'infd'; otherwise the current file offset is adjusted to - * reflect the number of bytes read from 'infd.' - * - * If 'offset' is NULL, then data will be read from 'infd' - * starting at the current file offset, and the file offset - * will be updated by the call. - * count - The number of bytes to copy between the file descriptors. - * - * Returned Value: - * If the transfer was successful, the number of bytes written to outfd is - * returned. On error, -1 is returned, and errno is set appropriately. - * There error values are those returned by read() or write() plus: - * - * EINVAL - Bad input parameters. - * ENOMEM - Could not allocated an I/O buffer - * - ************************************************************************/ - -ssize_t sendfile(int outfd, int infd, off_t *offset, size_t count) -{ - FAR uint8_t *iobuffer; - FAR uint8_t *wrbuffer; - off_t startpos = 0; - ssize_t nbytesread; - ssize_t nbyteswritten; - size_t ntransferred; - bool endxfr; - - /* Get the current file position. */ - - if (offset) - { - /* Use lseek to get the current file position */ - - startpos = lseek(infd, 0, SEEK_CUR); - if (startpos == (off_t)-1) - { - return ERROR; - } - - /* Use lseek again to set the new file position */ - - if (lseek(infd, *offset, SEEK_SET) == (off_t)-1) - { - return ERROR; - } - } - - /* Allocate an I/O buffer */ - - iobuffer = (FAR void *)malloc(CONFIG_LIB_SENDFILE_BUFSIZE); - if (!iobuffer) - { - set_errno(ENOMEM); - return ERROR; - } - - /* Now transfer 'count' bytes from the infd to the outfd */ - - for (ntransferred = 0, endxfr = false; ntransferred < count && !endxfr; ) - { - /* Loop until the read side of the transfer comes to some conclusion */ - - do - { - /* Read a buffer of data from the infd */ - - nbytesread = read(infd, iobuffer, CONFIG_LIB_SENDFILE_BUFSIZE); - - /* Check for end of file */ - - if (nbytesread == 0) - { - /* End of file. Break out and return current number of bytes - * transferred. - */ - - endxfr = true; - break; - } - - /* Check for a read ERROR. EINTR is a special case. This function - * should break out and return an error if EINTR is returned and - * no data has been transferred. But what should it do if some - * data has been transferred? I suppose just continue? - */ - - else if (nbytesread < 0) - { - /* EINTR is not an error (but will still stop the copy) */ - -#ifndef CONFIG_DISABLE_SIGNALS - if (errno != EINTR || ntransferred == 0) -#endif - { - /* Read error. Break out and return the error condition. */ - - ntransferred = ERROR; - endxfr = true; - break; - } - } - } - while (nbytesread < 0); - - /* Was anything read? */ - - if (!endxfr) - { - /* Yes.. Loop until the read side of the transfer comes to some - * conclusion. - */ - - wrbuffer = iobuffer; - do - { - /* Write the buffer of data to the outfd */ - - nbyteswritten = write(outfd, wrbuffer, nbytesread); - - /* Check for a complete (or parial) write. write() should not - * return zero. - */ - - if (nbyteswritten >= 0) - { - /* Advance the buffer pointer and decrement the number of bytes - * remaining in the iobuffer. Typically, nbytesread will now - * be zero. - */ - - wrbuffer += nbyteswritten; - nbytesread -= nbyteswritten; - - /* Increment the total number of bytes successfully transferred. */ - - ntransferred += nbyteswritten; - } - - /* Otherwise an error occurred */ - - else - { - /* Check for a read ERROR. EINTR is a special case. This - * function should break out and return an error if EINTR - * is returned and no data has been transferred. But what - * should it do if some data has been transferred? I - * suppose just continue? - */ - -#ifndef CONFIG_DISABLE_SIGNALS - if (errno != EINTR || ntransferred == 0) -#endif - { - /* Write error. Break out and return the error condition */ - - ntransferred = ERROR; - endxfr = true; - break; - } - } - } - while (nbytesread > 0); - } - } - - /* Release the I/O buffer */ - - free(iobuffer); - - /* Return the current file position */ - - if (offset) - { - /* Use lseek to get the current file position */ - - off_t curpos = lseek(infd, 0, SEEK_CUR); - if (curpos == (off_t)-1) - { - return ERROR; - } - - /* Return the current file position */ - - *offset = curpos; - - /* Use lseek again to restore the original file position */ - - if (lseek(infd, startpos, SEEK_SET) == (off_t)-1) - { - return ERROR; - } - } - - /* Finally return the number of bytes actually transferred (or ERROR - * if any failure occurred). - */ - - return ntransferred; -} - -#endif /* CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0 */ diff --git a/nuttx/libc/misc/lib_streamsem.c b/nuttx/libc/misc/lib_streamsem.c deleted file mode 100644 index e38298bdbb..0000000000 --- a/nuttx/libc/misc/lib_streamsem.c +++ /dev/null @@ -1,90 +0,0 @@ -/************************************************************************ - * libc/misc/lib_streamsem.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -/************************************************************************ - * Private types - ************************************************************************/ - -/************************************************************************ - * Private Variables - ************************************************************************/ - -/************************************************************************ - * Public Variables - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -void stream_semtake(FAR struct streamlist *list) -{ - /* Take the semaphore (perhaps waiting) */ - - while (sem_wait(&list->sl_sem) != 0) - { - /* The only case that an error should occr here is if - * the wait was awakened by a signal. - */ - - ASSERT(get_errno() == EINTR); - } -} - -void stream_semgive(FAR struct streamlist *list) -{ - sem_post(&list->sl_sem); -} - - diff --git a/nuttx/libc/mqueue/Make.defs b/nuttx/libc/mqueue/Make.defs deleted file mode 100644 index 826970fa32..0000000000 --- a/nuttx/libc/mqueue/Make.defs +++ /dev/null @@ -1,48 +0,0 @@ -############################################################################ -# libc/mqueue/Make.defs -# -# 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. -# -############################################################################ - -ifneq ($(CONFIG_DISABLE_MQUEUE),y) - -# Add the mqueue C files to the build - -CSRCS += mq_setattr.c mq_getattr.c - -# Add the mqueue directory to the build - -DEPPATH += --dep-path mqueue -VPATH += :mqueue - -endif - diff --git a/nuttx/libc/mqueue/mq_getattr.c b/nuttx/libc/mqueue/mq_getattr.c deleted file mode 100644 index 2fc0e131be..0000000000 --- a/nuttx/libc/mqueue/mq_getattr.c +++ /dev/null @@ -1,104 +0,0 @@ -/************************************************************************ - * libc/mqueue/mq_getattr.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include -#include - -/************************************************************************ - * Definitions - ************************************************************************/ - -/************************************************************************ - * Private Type Declarations - ************************************************************************/ - -/************************************************************************ - * Global Variables - ************************************************************************/ - -/************************************************************************ - * Private Variables - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Function: mq_getattr - * - * Description: - * This functions gets status information and attributes - * associated with the specified message queue. - * - * Parameters: - * mqdes - Message queue descriptor - * mq_stat - Buffer in which to return attributes - * - * Return Value: - * 0 (OK) if attributes provided, -1 (ERROR) otherwise. - * - * Assumptions: - * - ************************************************************************/ - -int mq_getattr(mqd_t mqdes, struct mq_attr *mq_stat) -{ - int ret = ERROR; - - if (mqdes && mq_stat) - { - /* Return the attributes */ - - mq_stat->mq_maxmsg = mqdes->msgq->maxmsgs; - mq_stat->mq_msgsize = mqdes->msgq->maxmsgsize; - mq_stat->mq_flags = mqdes->oflags; - mq_stat->mq_curmsgs = mqdes->msgq->nmsgs; - - ret = OK; - } - - return ret; -} diff --git a/nuttx/libc/mqueue/mq_setattr.c b/nuttx/libc/mqueue/mq_setattr.c deleted file mode 100644 index 45a848e6d7..0000000000 --- a/nuttx/libc/mqueue/mq_setattr.c +++ /dev/null @@ -1,118 +0,0 @@ -/************************************************************************ - * libc/mqueue/mq_setattr.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include /* O_NONBLOCK */ -#include - -#include - -/************************************************************************ - * Definitions - ************************************************************************/ - -/************************************************************************ - * Private Type Declarations - ************************************************************************/ - -/************************************************************************ - * Global Variables - ************************************************************************/ - -/************************************************************************ - * Private Variables - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Function: mq_setattr - * - * Description: - * This function sets the attributes associated with the - * specified message queue "mqdes." Only the "O_NONBLOCK" - * bit of the "mq_flags" can be changed. - * - * If "oldstat" is non-null, mq_setattr() will store the - * previous message queue attributes at that location (just - * as would have been returned by mq_getattr()). - * - * Parameters: - * mqdes - Message queue descriptor - * mq_stat - New attributes - * oldstate - Old attributes - * - * Return Value: - * 0 (OK) if attributes are set successfully, otherwise - * -1 (ERROR). - * - * Assumptions: - * - ************************************************************************/ - -int mq_setattr(mqd_t mqdes, const struct mq_attr *mq_stat, - struct mq_attr *oldstat) -{ - int ret = ERROR; - - if (mqdes && mq_stat) - { - /* Return the attributes if so requested */ - - if (oldstat) - { - (void)mq_getattr(mqdes, oldstat); - } - - /* Set the new value of the O_NONBLOCK flag. */ - - mqdes->oflags = ((mq_stat->mq_flags & O_NONBLOCK) | - (mqdes->oflags & (~O_NONBLOCK))); - ret = OK; - } - - return ret; -} diff --git a/nuttx/libc/net/Make.defs b/nuttx/libc/net/Make.defs deleted file mode 100644 index 9d4e5c06b3..0000000000 --- a/nuttx/libc/net/Make.defs +++ /dev/null @@ -1,44 +0,0 @@ -############################################################################ -# libc/net/Make.defs -# -# 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. -# -############################################################################ - -# Add the networking C files to the build - -CSRCS += lib_etherntoa.c lib_htons.c lib_htonl.c lib_inetaddr.c -CSRCS += lib_inetntoa.c lib_inetntop.c lib_inetpton.c - -# Add the net directory to the build - -DEPPATH += --dep-path net -VPATH += :net diff --git a/nuttx/libc/net/lib_etherntoa.c b/nuttx/libc/net/lib_etherntoa.c deleted file mode 100644 index 91fb01c570..0000000000 --- a/nuttx/libc/net/lib_etherntoa.c +++ /dev/null @@ -1,69 +0,0 @@ -/**************************************************************************** - * libc/net/lib_etherntoa.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include - -#include -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: ether_ntoa - * - * Description: - * The ether_ntoa() function converts the Ethernet host address addr given - * in network byte order to a string in standard hex-digits-and-colons - * notation. The string is returned in a statically allocated buffer, which - * subsequent calls will overwrite. - * - ****************************************************************************/ - -FAR char *ether_ntoa(FAR const struct ether_addr *addr) -{ - static char buffer[20]; - sprintf(buffer, "%02x:%02x:%02x:%02x:%02x:%02x", - addr->ether_addr_octet[0], addr->ether_addr_octet[1], - addr->ether_addr_octet[2], addr->ether_addr_octet[3], - addr->ether_addr_octet[4], addr->ether_addr_octet[5]); - return buffer; -} diff --git a/nuttx/libc/net/lib_htonl.c b/nuttx/libc/net/lib_htonl.c deleted file mode 100644 index a10f54f379..0000000000 --- a/nuttx/libc/net/lib_htonl.c +++ /dev/null @@ -1,68 +0,0 @@ -/************************************************************ - * libc/net/lib_ntohl.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -#include -#include - -/************************************************************ - * Global Functions - ************************************************************/ - -uint32_t htonl(uint32_t hl) -{ -#ifdef CONFIG_ENDIAN_BIG - return hl; -#else - return (( (hl) >> 24) | - (((hl) >> 8) & 0x0000ff00) | - (((hl) << 8) & 0x00ff0000) | - ( (hl) << 24)); -#endif -} - -uint32_t ntohl(uint32_t nl) -{ -#ifdef CONFIG_ENDIAN_BIG - return nl; -#else - return htonl(nl); -#endif -} diff --git a/nuttx/libc/net/lib_htons.c b/nuttx/libc/net/lib_htons.c deleted file mode 100644 index 13addd9136..0000000000 --- a/nuttx/libc/net/lib_htons.c +++ /dev/null @@ -1,65 +0,0 @@ -/*************************************************************************** - * libc/net/lib_htons.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ***************************************************************************/ - -/*************************************************************************** - * Compilation Switches - ***************************************************************************/ - -/*************************************************************************** - * Included Files - ***************************************************************************/ - -#include - -#include -#include - -/*************************************************************************** - * Global Functions - ***************************************************************************/ - -uint16_t htons(uint16_t hs) -{ - return HTONS(hs); -} - -uint16_t ntohs(uint16_t ns) -{ -#ifdef CONFIG_ENDIAN_BIG - return ns; -#else - return htons(ns); -#endif -} diff --git a/nuttx/libc/net/lib_inetaddr.c b/nuttx/libc/net/lib_inetaddr.c deleted file mode 100644 index 46c6c548dc..0000000000 --- a/nuttx/libc/net/lib_inetaddr.c +++ /dev/null @@ -1,74 +0,0 @@ -/**************************************************************************** - * libc/net/lib_inetaddr.c - * - * Copyright (C) 2011 Yu Qiang. All rights reserved. - * Author: Yu Qiang - * - * This file is a part of NuttX: - * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. - * - * 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 - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * name inet_addr - * - * Description: - * The inet_addr() function converts the string pointed to by cp, in the - * standard IPv4 dotted decimal notation, to an integer value suitable for - * use as an Internet address. - - ****************************************************************************/ - -in_addr_t inet_addr(FAR const char *cp) -{ - unsigned int a, b, c, d; - uint32_t result; - - sscanf(cp, "%u.%u.%u.%u", &a, &b, &c, &d); - result = a << 8; - result |= b; - result <<= 8; - result |= c; - result <<= 8; - result |= d; - return HTONL(result); -} diff --git a/nuttx/libc/net/lib_inetntoa.c b/nuttx/libc/net/lib_inetntoa.c deleted file mode 100644 index e2d92d8648..0000000000 --- a/nuttx/libc/net/lib_inetntoa.c +++ /dev/null @@ -1,79 +0,0 @@ -/**************************************************************************** - * libc/net/lib_inetntoa.c - * - * Copyright (C) 2007-2008, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -#ifndef CONFIG_NET_IPv6 - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: inet_ntoa - * - * Description: - * The inet_ntoa() function converts the Internet host address in given in - * network byte order to a string in standard numbers-and-dots notation. - * The string is returned in a statically allocated buffer, which subsequent - * calls will overwrite. - * - ****************************************************************************/ - -#ifdef CONFIG_CAN_PASS_STRUCTS -FAR char *inet_ntoa(struct in_addr in) -{ - static char buffer[INET_ADDRSTRLEN+2]; - FAR char *ptr = (FAR char*)&in.s_addr; - sprintf(buffer, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]); - return buffer; -} -#else -FAR char *_inet_ntoa(in_addr_t in) -{ - static char buffer[INET_ADDRSTRLEN+2]; - FAR char *ptr = (FAR char*)∈ - sprintf(buffer, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]); - return buffer; -} -#endif -#endif /* !CONFIG_NET_IPv6 */ - diff --git a/nuttx/libc/net/lib_inetntop.c b/nuttx/libc/net/lib_inetntop.c deleted file mode 100644 index 25c32c48cf..0000000000 --- a/nuttx/libc/net/lib_inetntop.c +++ /dev/null @@ -1,202 +0,0 @@ -/**************************************************************************** - * libc/net/lib_inetntop.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Includes some logic extracted from hwport_ftpd, written by Jaehyuk Cho - * which was released under the BSD license. - * - * Copyright (C) HWPORT.COM. All rights reserved. - * Author: JAEHYUK CHO - * - * 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 - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: inet_ntop - * - * Description: - * The inet_ntop() function converts a numeric address into a text string - * suitable for presentation. - * - * Input Parameters: - * af - The af argument specifies the family of the address. This can be - * AF_INET or AF_INET6. - * src - The src argument points to a buffer holding an address of the - * specified type. The address must be in network byte order. - * dst - The dst argument points to a buffer where the function stores - * the resulting text string; it shall not be NULL. - * size - The size argument specifies the size of this buffer, which must - * be large enough to hold the text string (INET_ADDRSTRLEN - * characters for IPv4, INET6_ADDRSTRLEN characters for IPv6). - * - * Returned Value: - * inet_ntop() returns a pointer to the buffer containing the text string - * if the conversion succeeds. Otherwise, NULL is returned and the errno - * is set to indicate the error. There follow errno values may be set: - * - * EAFNOSUPPORT - The af argument is invalid. - * ENOSPC - The size of the inet_ntop() result buffer is inadequate - * - ****************************************************************************/ - -FAR const char *inet_ntop(int af, FAR const void *src, FAR char *dst, socklen_t size) -{ - int errval; -#ifndef CONFIG_NET_IPv6 - FAR char *ptr; - - DEBUGASSERT(src && dst); - - if (af != AF_INET) - { - errval = EAFNOSUPPORT; - goto errout; - } - - if (size < INET_ADDRSTRLEN) - { - errval = ENOSPC; - goto errout; - } - - ptr = (FAR char*)src; - sprintf(dst, "%d.%d.%d.%d", ptr[0], ptr[1], ptr[2], ptr[3]); - return dst; -#else - FAR const struct in6_addr *in6_addr; - uint16_t warray[8]; - int offset; - int entry; - int count; - int maxentry; - int maxcount; - - DEBUGASSERT(src && dst); - - if (af != AF_INET6) - { - errval = EAFNOSUPPORT; - goto errout; - } - - if (size < INET6_ADDRSTRLEN) - { - errval = ENOSPC; - goto errout; - } - - in6_addr = (FAR const struct in6_addr *)src; - entry = -1; - maxentry = -1; - maxcount = 0; - offset = 0; - - while (offset < 8) - { - warray[offset] = ntohs(in6_addr->s6_addr16[offset]); - if (warray[offset] == 0) - { - entry = offset; - count = 1; - offset++; - - while (offset < 8) - { - warray[offset] = ntohs(in6_addr->s6_addr16[offset]); - if (warray[offset] != 0) - { - break; - } - offset++; - count++; - } - - if (count > maxcount) - { - maxentry = entry; - maxcount = count; - } - } - offset++; - } - - offset = 0; - dst[0] = '\0'; - - while (offset < 8) - { - if (offset == maxentry) - { - size -= snprintf(&dst[strlen(dst)], size, ":"); - offset += maxcount; - if (offset >= 8) - { - size -= snprintf(&dst[strlen(dst)], size, ":"); - } - } - else - { - if (offset > 0) - { - size -= snprintf(&dst[strlen(dst)], size, ":"); - } - - size -= snprintf(&dst[strlen(dst)], size, "%x", warray[offset]); - offset++; - } - } - - return dst; -#endif - -errout: - set_errno(errval); - memset(dst, 0, size); - return NULL; -} diff --git a/nuttx/libc/net/lib_inetpton.c b/nuttx/libc/net/lib_inetpton.c deleted file mode 100644 index c5f117535b..0000000000 --- a/nuttx/libc/net/lib_inetpton.c +++ /dev/null @@ -1,338 +0,0 @@ -/**************************************************************************** - * libc/net/lib_inetpton.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Includes some logic extracted from hwport_ftpd, written by Jaehyuk Cho - * which was released under the BSD license. - * - * Copyright (C) HWPORT.COM. All rights reserved. - * Author: JAEHYUK CHO - * - * 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 - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: inet_pton - * - * Description: - * The inet_pton() function converts an address in its standard text - * presentation form into its numeric binary form. - * - * If the af argument of inet_pton() is AF_INET, the src string will be - * in the standard IPv4 dotted-decimal form: - * - * ddd.ddd.ddd.ddd - * - * where "ddd" is a one to three digit decimal number between 0 and 255. - * - * If the af argument of inet_pton() is AF_INET6, the src string will be in - * one of the following standard IPv6 text forms: - * - * 1. The preferred form is "x:x:x:x:x:x:x:x", where the 'x' s are the - * hexadecimal values of the eight 16-bit pieces of the address. Leading - * zeros in individual fields can be omitted, but there must be at least - * one numeral in every field. - * - * 2. A string of contiguous zero fields in the preferred form can be shown - * as "::". The "::" can only appear once in an address. Unspecified - * addresses ( "0:0:0:0:0:0:0:0" ) may be represented simply as "::". - * - * 3. A third form that is sometimes more convenient when dealing with a - * mixed environment of IPv4 and IPv6 nodes is "x:x:x:x:x:x:d.d.d.d", - * where the 'x' s are the hexadecimal values of the six high-order - * 16-bit pieces of the address, and the 'd' s are the decimal values - * of the four low-order 8-bit pieces of the address (standard IPv4 - * representation). - * - * Input Parameters: - * af - The af argument specifies the family of the address. This can be - * AF_INET or AF_INET6. - * src - The src argument points to the string being passed in. - * dst - The dst argument points to a numstr into which the function stores - * the numeric address; this must be large enough to hold the numeric - * address (32 bits for AF_INET, 128 bits for AF_INET6). - * - * Returned Value: - * The inet_pton() function returns 1 if the conversion succeeds, with the - * address pointed to by dst in network byte order. It will return 0 if the - * input is not a valid IPv4 dotted-decimal string or a valid IPv6 address - * string, or -1 with errno set to EAFNOSUPPOR] if the af argument is unknown. - * - ****************************************************************************/ - -int inet_pton(int af, FAR const char *src, FAR void *dst) -{ -#ifndef CONFIG_NET_IPv6 - size_t srcoffset; - size_t numoffset; - int value; - int ndots; - uint8_t ch; - char numstr[4]; - uint8_t *ip; - - DEBUGASSERT(src && dst); - - if (af != AF_INET) - { - set_errno(EAFNOSUPPORT); - return -1; - } - - (void)memset(dst, 0, sizeof(struct in_addr)); - - ip = (uint8_t *)dst; - srcoffset = 0; - numoffset = 0; - ndots = 0; - - for(;;) - { - ch = (uint8_t)src[srcoffset++]; - - if (ch == '.' || ch == '\0') - { - if (ch == '.' && ndots >= 4) - { - /* Too many dots */ - - break; - } - - if (numoffset <= 0) - { - /* Empty numeric string */ - - break; - } - - numstr[numoffset] = '\0'; - numoffset = 0; - - value = atoi(numstr); - if (value < 0 || value > 255) - { - /* Out of range value */ - - break; - } - - ip[ndots] = (uint8_t)value; - - if (ch == '\0') - { - if (ndots != 3) - { - /* Not enough dots */ - - break; - } - - /* Return 1 if the conversion succeeds */ - - return 1; - } - - ndots++; - } - else if (ch >= '0' && ch <= '9') - { - numstr[numoffset++] = ch; - if (numoffset >= 4) - { - /* Number is too long */ - - break; - } - } - else - { - /* Illegal character */ - - break; - } - } - - /* Return zero if there is any problem parsing the input */ - - return 0; -#else - size_t srcoffset; - size_t numoffset; - long value; - int nsep; - int nrsep; - uint8_t ch; - char numstr[5]; - uint8_t ip[sizeof(struct in6_addr)]; - uint8_t rip[sizeof(struct in6_addr)]; - bool rtime; - - DEBUGASSERT(src && dst); - - if (af != AF_INET6) - { - set_errno(EAFNOSUPPORT); - return -1; - } - - (void)memset(dst, 0, sizeof(struct in6_addr)); - - srcoffset = 0; - numoffset = 0; - nsep = 0; - nrsep = 0; - rtime = false; - - for(;;) - { - ch = (uint8_t)src[srcoffset++]; - - if (ch == ':' || ch == '\0') - { - if (ch == ':' && (nsep + nrsep) >= 8) - { - /* Too many separators */ - - break; - } - - if (ch != '\0' && numoffset <= 0) - { - /* Empty numeric string */ - - if (rtime && nrsep > 1) - { - /* dup simple */ - - break; - } - - numoffset = 0; - rtime = true; - continue; - } - - numstr[numoffset] = '\0'; - numoffset = 0; - - value = strtol(numstr, NULL, 16); - if (value < 0 || value > 0xffff) - { - /* Out of range value */ - - break; - } - - if (!rtime) - { - ip[(nsep << 1) + 0] = (uint8_t)((value >> 8) & 0xff); - ip[(nsep << 1) + 1] = (uint8_t)((value >> 0) & 0xff); - nsep++; - } - else - { - rip[(nrsep << 1) + 0] = (uint8_t)((value >> 8) & 0xff); - rip[(nrsep << 1) + 1] = (uint8_t)((value >> 0) & 0xff); - nrsep++; - } - - if (ch == '\0' /* || ch == '/' */) - { - if ((nsep <= 1 && nrsep <= 0) || - (nsep + nrsep) < 1 || - (nsep + nrsep) > 8) - { - /* Separator count problem */ - - break; - } - - if (nsep > 0) - { - memcpy(dst, &ip[0], nsep << 1); - } - - if (nrsep > 0) - { - memcpy(dst + (16 - (nrsep << 1)), &rip[0], nrsep << 1); - } - - /* Return 1 if the conversion succeeds */ - - return 1; - } - } - else if ((ch >= '0' && ch <= '9') || - (ch >= 'a' && ch <= 'f') || - (ch >= 'A' && ch <= 'F')) - { - numstr[numoffset++] = ch; - if (numoffset >= 5) - { - /* Numeric string is too long */ - - break; - } - } - else - { - /* Illegal character */ - - break; - } - } - - - /* Return zero if there is any problem parsing the input */ - - return 0; -#endif -} diff --git a/nuttx/libc/pthread/Make.defs b/nuttx/libc/pthread/Make.defs deleted file mode 100644 index 07e4f05701..0000000000 --- a/nuttx/libc/pthread/Make.defs +++ /dev/null @@ -1,56 +0,0 @@ -############################################################################ -# libc/pthread/Make.defs -# -# 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. -# -############################################################################ - -# Add the pthread C files to the build - -CSRCS += pthread_attrinit.c pthread_attrdestroy.c \ - pthread_attrsetschedpolicy.c pthread_attrgetschedpolicy.c \ - pthread_attrsetinheritsched.c pthread_attrgetinheritsched.c \ - pthread_attrsetstacksize.c pthread_attrgetstacksize.c \ - pthread_attrsetschedparam.c pthread_attrgetschedparam.c \ - pthread_barrierattrinit.c pthread_barrierattrdestroy.c \ - pthread_barrierattrgetpshared.c pthread_barrierattrsetpshared.c \ - pthread_condattrinit.c pthread_condattrdestroy.c \ - pthread_mutexattrinit.c pthread_mutexattrdestroy.c \ - pthread_mutexattrgetpshared.c pthread_mutexattrsetpshared.c - -ifeq ($(CONFIG_MUTEX_TYPES),y) -CSRCS += pthread_mutexattrsettype.c pthread_mutexattrgettype.c -endif - -# Add the pthread directory to the build - -DEPPATH += --dep-path pthread -VPATH += :pthread diff --git a/nuttx/libc/pthread/pthread_attrdestroy.c b/nuttx/libc/pthread/pthread_attrdestroy.c deleted file mode 100644 index 37ad46ebcd..0000000000 --- a/nuttx/libc/pthread/pthread_attrdestroy.c +++ /dev/null @@ -1,108 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_attrdestroy.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_attr_destroy - * - * Description: - * An attributes object can be deleted when it is no longer - * needed. - * - * Parameters: - * attr - * - * Return Value: - * 0 meaning success - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_attr_destroy(FAR pthread_attr_t *attr) -{ - int ret; - - sdbg("attr=0x%p\n", attr); - - if (!attr) - { - ret = EINVAL; - } - else - { - memset(attr, 0, sizeof(pthread_attr_t)); - ret = OK; - } - - sdbg("Returning %d\n", ret); - return ret; -} - - diff --git a/nuttx/libc/pthread/pthread_attrgetinheritsched.c b/nuttx/libc/pthread/pthread_attrgetinheritsched.c deleted file mode 100644 index 6ec8ae71f6..0000000000 --- a/nuttx/libc/pthread/pthread_attrgetinheritsched.c +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_attrgetinheritsched.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_attr_getinheritsched - * - * Description: - * Report whether the scheduling info in the pthread - * attributes will be used or if the thread will - * inherit the properties of the parent. - * - * Parameters: - * attr - * inheritsched - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_attr_getinheritsched(FAR const pthread_attr_t *attr, - FAR int *inheritsched) -{ - int ret; - - sdbg("attr=0x%p inheritsched=0x%p\n", attr, inheritsched); - - if (!attr || !inheritsched) - { - ret = EINVAL; - } - else - { - *inheritsched = (int)attr->inheritsched; - ret = OK; - } - - sdbg("Returning %d\n", ret); - return ret; -} - - diff --git a/nuttx/libc/pthread/pthread_attrgetschedparam.c b/nuttx/libc/pthread/pthread_attrgetschedparam.c deleted file mode 100644 index 6bcc9618e9..0000000000 --- a/nuttx/libc/pthread/pthread_attrgetschedparam.c +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_attrgetschedparam.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_attr_getschedparam - * - * Description: - * - * Parameters: - * attr - * param - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_attr_getschedparam(FAR pthread_attr_t *attr, - FAR struct sched_param *param) -{ - int ret; - - sdbg("attr=0x%p param=0x%p\n", attr, param); - - if (!attr || !param) - { - ret = EINVAL; - } - else - { - param->sched_priority = attr->priority; - ret = OK; - } - - sdbg("Returning %d\n", ret); - return ret; -} - - - diff --git a/nuttx/libc/pthread/pthread_attrgetschedpolicy.c b/nuttx/libc/pthread/pthread_attrgetschedpolicy.c deleted file mode 100644 index 8845e2bd81..0000000000 --- a/nuttx/libc/pthread/pthread_attrgetschedpolicy.c +++ /dev/null @@ -1,105 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_attrgetschedpolicy.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_attr_getschedpolicy - * - * Description: - * Obtain the scheduling algorithm attribute. - * - * Parameters: - * attr - * policy - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_attr_getschedpolicy(FAR pthread_attr_t *attr, int *policy) -{ - int ret; - - sdbg("attr=0x%p policy=0x%p\n", attr, policy); - - if (!attr || !policy) - { - ret = EINVAL; - } - else - { - *policy = attr->policy; - ret = OK; - } - - sdbg("Returning %d\n", ret); - return ret; -} diff --git a/nuttx/libc/pthread/pthread_attrgetstacksize.c b/nuttx/libc/pthread/pthread_attrgetstacksize.c deleted file mode 100644 index 9fde29e810..0000000000 --- a/nuttx/libc/pthread/pthread_attrgetstacksize.c +++ /dev/null @@ -1,106 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_attrgetstacksize.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_attr_getstacksize - * - * Description: - * - * Parameters: - * attr - * stacksize - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_attr_getstacksize(FAR pthread_attr_t *attr, FAR long *stacksize) -{ - int ret; - - sdbg("attr=0x%p stacksize=0x%p\n", attr, stacksize); - - if (!stacksize) - { - ret = EINVAL; - } - else - { - *stacksize = attr->stacksize; - ret = OK; - } - - sdbg("Returning %d\n", ret); - return ret; -} - - diff --git a/nuttx/libc/pthread/pthread_attrinit.c b/nuttx/libc/pthread/pthread_attrinit.c deleted file mode 100644 index 427a582b91..0000000000 --- a/nuttx/libc/pthread/pthread_attrinit.c +++ /dev/null @@ -1,123 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_attrinit.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/* Default pthread attributes (see included/nuttx/pthread.h). When configured - * to build separate kernel- and user-address spaces, this global is - * duplicated in each address spaced. This copy can only be shared within - * the user address space. - */ - -#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__) -pthread_attr_t g_default_pthread_attr = PTHREAD_ATTR_INITIALIZER; -#endif - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_attr_init - * - * Description: - * Initializes a thread attributes object (attr) with - * default values for all of the individual attributes - * used by a given implementation. - * - * Parameters: - * attr - * - * Return Value: - * 0 on success, otherwise an error number - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_attr_init(FAR pthread_attr_t *attr) -{ - int ret = OK; - - sdbg("attr=0x%p\n", attr); - if (!attr) - { - ret = ENOMEM; - } - else - { - /* Set the child thread priority to be the default - * priority. Set the child stack size to some arbitrary - * default value. - */ - - memcpy(attr, &g_default_pthread_attr, sizeof(pthread_attr_t)); - } - - sdbg("Returning %d\n", ret); - return ret; -} - diff --git a/nuttx/libc/pthread/pthread_attrsetinheritsched.c b/nuttx/libc/pthread/pthread_attrsetinheritsched.c deleted file mode 100644 index 1102fe176a..0000000000 --- a/nuttx/libc/pthread/pthread_attrsetinheritsched.c +++ /dev/null @@ -1,113 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_attrsetinheritsched.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_attr_setinheritsched - * - * Description: - * Indicate whether the scheduling info in the pthread - * attributes will be used or if the thread will - * inherit the properties of the parent. - * - * Parameters: - * attr - * policy - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_attr_setinheritsched(FAR pthread_attr_t *attr, - int inheritsched) -{ - int ret; - - sdbg("inheritsched=%d\n", inheritsched); - - if (!attr || - (inheritsched != PTHREAD_INHERIT_SCHED && - inheritsched != PTHREAD_EXPLICIT_SCHED)) - { - ret = EINVAL; - } - else - { - attr->inheritsched = (uint8_t)inheritsched; - ret = OK; - } - - sdbg("Returning %d\n", ret); - return ret; -} - diff --git a/nuttx/libc/pthread/pthread_attrsetschedparam.c b/nuttx/libc/pthread/pthread_attrsetschedparam.c deleted file mode 100644 index 587d62206b..0000000000 --- a/nuttx/libc/pthread/pthread_attrsetschedparam.c +++ /dev/null @@ -1,108 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_attrsetschedparam.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_attr_setschedparam - * - * Description: - * - * Parameters: - * attr - * param - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_attr_setschedparam(FAR pthread_attr_t *attr, - FAR const struct sched_param *param) -{ - int ret; - - sdbg("attr=0x%p param=0x%p\n", attr, param); - - if (!attr || !param) - { - ret = EINVAL; - } - else - { - attr->priority = (short)param->sched_priority; - ret = OK; - } - sdbg("Returning %d\n", ret); - return ret; -} - - diff --git a/nuttx/libc/pthread/pthread_attrsetschedpolicy.c b/nuttx/libc/pthread/pthread_attrsetschedpolicy.c deleted file mode 100644 index e1d1c86195..0000000000 --- a/nuttx/libc/pthread/pthread_attrsetschedpolicy.c +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_attrsetschedpolicy.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_attr_setschedpolicy - * - * Description: - * Set the scheduling algorithm attribute. - * - * Parameters: - * attr - * policy - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_attr_setschedpolicy(FAR pthread_attr_t *attr, int policy) -{ - int ret; - - sdbg("attr=0x%p policy=%d\n", attr, policy); - -#if CONFIG_RR_INTERVAL > 0 - if (!attr || (policy != SCHED_FIFO && policy != SCHED_RR)) -#else - if (!attr || policy != SCHED_FIFO ) -#endif - { - ret = EINVAL; - } - else - { - attr->policy = policy; - ret = OK; - } - - sdbg("Returning %d\n", ret); - return ret; -} diff --git a/nuttx/libc/pthread/pthread_attrsetstacksize.c b/nuttx/libc/pthread/pthread_attrsetstacksize.c deleted file mode 100644 index fca993baf8..0000000000 --- a/nuttx/libc/pthread/pthread_attrsetstacksize.c +++ /dev/null @@ -1,106 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_attrsetstacksize.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_attr_setstacksize - * - * Description: - * - * Parameters: - * attr - * stacksize - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_attr_setstacksize(FAR pthread_attr_t *attr, long stacksize) -{ - int ret; - - sdbg("attr=0x%p stacksize=%ld\n", attr, stacksize); - - if (!attr || stacksize < PTHREAD_STACK_MIN) - { - ret = EINVAL; - } - else - { - attr->stacksize = stacksize; - ret = OK; - } - - sdbg("Returning %d\n", ret); - return ret; -} - diff --git a/nuttx/libc/pthread/pthread_barrierattrdestroy.c b/nuttx/libc/pthread/pthread_barrierattrdestroy.c deleted file mode 100644 index 5519caa61f..0000000000 --- a/nuttx/libc/pthread/pthread_barrierattrdestroy.c +++ /dev/null @@ -1,102 +0,0 @@ -/******************************************************************************** - * libc/pthread/pthread_barrierattrdestroy.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ********************************************************************************/ - -/******************************************************************************** - * Included Files - ********************************************************************************/ - -#include - -#include -#include -#include - -/******************************************************************************** - * Definitions - ********************************************************************************/ - -/******************************************************************************** - * Private Type Declarations - ********************************************************************************/ - -/******************************************************************************** - * Global Variables - ********************************************************************************/ - -/******************************************************************************** - * Private Variables - ********************************************************************************/ - -/******************************************************************************** - * Private Function Prototypes - ********************************************************************************/ - -/******************************************************************************** - * Public Functions - ********************************************************************************/ - -/******************************************************************************** - * Function: pthread_barrierattr_destroy - * - * Description: - * The pthread_barrierattr_destroy() function will destroy a barrier attributes - * object. A destroyed attr attributes object can be reinitialized using - * pthread_barrierattr_init(); the results of otherwise referencing the object - * after it has been destroyed are undefined. - * - * Parameters: - * attr - barrier attributes to be destroyed. - * - * Return Value: - * 0 (OK) on success or EINVAL if attr is invalid. - * - * Assumptions: - * - ********************************************************************************/ - -int pthread_barrierattr_destroy(FAR pthread_barrierattr_t *attr) -{ - int ret = OK; - - if (!attr) - { - ret = EINVAL; - } - else - { - attr->pshared = PTHREAD_PROCESS_PRIVATE; - } - return ret; -} diff --git a/nuttx/libc/pthread/pthread_barrierattrgetpshared.c b/nuttx/libc/pthread/pthread_barrierattrgetpshared.c deleted file mode 100644 index 83faffae08..0000000000 --- a/nuttx/libc/pthread/pthread_barrierattrgetpshared.c +++ /dev/null @@ -1,101 +0,0 @@ -/******************************************************************************** - * libc/pthread/pthread_barrierattrgetpshared.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ********************************************************************************/ - -/******************************************************************************** - * Included Files - ********************************************************************************/ - -#include - -#include -#include -#include - -/******************************************************************************** - * Definitions - ********************************************************************************/ - -/******************************************************************************** - * Private Type Declarations - ********************************************************************************/ - -/******************************************************************************** - * Global Variables - ********************************************************************************/ - -/******************************************************************************** - * Private Variables - ********************************************************************************/ - -/******************************************************************************** - * Private Function Prototypes - ********************************************************************************/ - -/******************************************************************************** - * Public Functions - ********************************************************************************/ - -/******************************************************************************** - * Function: pthread_barrierattr_getpshared - * - * Description: - * The pthread_barrierattr_getpshared() function will obtain the value of the - * process-shared attribute from the attributes object referenced by attr. - * - * Parameters: - * attr - barrier attributes to be queried. - * pshared - the location to stored the current value of the pshared attribute. - * - * Return Value: - * 0 (OK) on success or EINVAL if either attr or pshared is invalid. - * - * Assumptions: - * - ********************************************************************************/ - -int pthread_barrierattr_getpshared(FAR const pthread_barrierattr_t *attr, FAR int *pshared) -{ - int ret = OK; - - if (!attr || !pshared) - { - ret = EINVAL; - } - else - { - *pshared = attr->pshared; - } - return ret; -} diff --git a/nuttx/libc/pthread/pthread_barrierattrinit.c b/nuttx/libc/pthread/pthread_barrierattrinit.c deleted file mode 100644 index 7ab1018835..0000000000 --- a/nuttx/libc/pthread/pthread_barrierattrinit.c +++ /dev/null @@ -1,101 +0,0 @@ -/******************************************************************************** - * libc/pthread/pthread_barrierattrinit.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ********************************************************************************/ - -/******************************************************************************** - * Included Files - ********************************************************************************/ - -#include - -#include -#include -#include - -/******************************************************************************** - * Definitions - ********************************************************************************/ - -/******************************************************************************** - * Private Type Declarations - ********************************************************************************/ - -/******************************************************************************** - * Global Variables - ********************************************************************************/ - -/******************************************************************************** - * Private Variables - ********************************************************************************/ - -/******************************************************************************** - * Private Function Prototypes - ********************************************************************************/ - -/******************************************************************************** - * Public Functions - ********************************************************************************/ - -/******************************************************************************** - * Function: pthread_barrierattr_init - * - * Description: - * The pthread_barrierattr_init() function will initialize a barrier attribute - * object attr with the default value for all of the attributes defined by the - * implementation. - * - * Parameters: - * attr - barrier attributes to be initialized. - * - * Return Value: - * 0 (OK) on success or EINVAL if attr is invalid. - * - * Assumptions: - * - ********************************************************************************/ - -int pthread_barrierattr_init(FAR pthread_barrierattr_t *attr) -{ - int ret = OK; - - if (!attr) - { - ret = EINVAL; - } - else - { - attr->pshared = PTHREAD_PROCESS_PRIVATE; - } - return ret; -} diff --git a/nuttx/libc/pthread/pthread_barrierattrsetpshared.c b/nuttx/libc/pthread/pthread_barrierattrsetpshared.c deleted file mode 100644 index 2585de7a0d..0000000000 --- a/nuttx/libc/pthread/pthread_barrierattrsetpshared.c +++ /dev/null @@ -1,111 +0,0 @@ -/******************************************************************************** - * libc/pthread/pthread_barrierattrsetpshared.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ********************************************************************************/ - -/******************************************************************************** - * Included Files - ********************************************************************************/ - -#include - -#include -#include -#include - -/******************************************************************************** - * Definitions - ********************************************************************************/ - -/******************************************************************************** - * Private Type Declarations - ********************************************************************************/ - -/******************************************************************************** - * Global Variables - ********************************************************************************/ - -/******************************************************************************** - * Private Variables - ********************************************************************************/ - -/******************************************************************************** - * Private Function Prototypes - ********************************************************************************/ - -/******************************************************************************** - * Public Functions - ********************************************************************************/ - -/******************************************************************************** - * Function: pthread_barrierattr_setpshared - * - * Description: - * The process-shared attribute is set to PTHREAD_PROCESS_SHARED to permit a - * barrier to be operated upon by any thread that has access to the memory where - * the barrier is allocated. If the process-shared attribute is - * PTHREAD_PROCESS_PRIVATE, the barrier can only be operated upon by threads - * created within the same process as the thread that initialized the barrier. - * If threads of different processes attempt to operate on such a barrier, the - * behavior is undefined. The default value of the attribute is - * PTHREAD_PROCESS_PRIVATE. - * - * Both constants PTHREAD_PROCESS_SHARED and PTHREAD_PROCESS_PRIVATE are defined - * in pthread.h. - * - * Parameters: - * attr - barrier attributes to be modified. - * pshared - the new value of the pshared attribute. - * - * Return Value: - * 0 (OK) on success or EINVAL if either attr is invalid or pshared is not one - * of PTHREAD_PROCESS_SHARED or PTHREAD_PROCESS_PRIVATE. - * - * Assumptions: - * - ********************************************************************************/ - -int pthread_barrierattr_setpshared(FAR pthread_barrierattr_t *attr, int pshared) -{ - int ret = OK; - - if (!attr || (pshared != PTHREAD_PROCESS_SHARED && pshared != PTHREAD_PROCESS_PRIVATE)) - { - ret = EINVAL; - } - else - { - attr->pshared = pshared; - } - return ret; -} diff --git a/nuttx/libc/pthread/pthread_condattrdestroy.c b/nuttx/libc/pthread/pthread_condattrdestroy.c deleted file mode 100644 index 30a0c4db1b..0000000000 --- a/nuttx/libc/pthread/pthread_condattrdestroy.c +++ /dev/null @@ -1,82 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_condattrdestroy.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_condattr_destroy - * - * Description: - * Operations on condition variable attributes - * - * Parameters: - * None - * - * Return Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_condattr_destroy(FAR pthread_condattr_t *attr) -{ - int ret = OK; - - sdbg("attr=0x%p\n", attr); - - if (!attr) - { - ret = EINVAL; - } - - sdbg("Returning %d\n", ret); - return ret; -} - - - diff --git a/nuttx/libc/pthread/pthread_condattrinit.c b/nuttx/libc/pthread/pthread_condattrinit.c deleted file mode 100644 index 511376f2e6..0000000000 --- a/nuttx/libc/pthread/pthread_condattrinit.c +++ /dev/null @@ -1,85 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_condattrinit.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_condattr_init - * - * Description: - * Operations on condition variable attributes - * - * Parameters: - * None - * - * Return Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_condattr_init(FAR pthread_condattr_t *attr) -{ - int ret = OK; - - sdbg("attr=0x%p\n", attr); - - if (!attr) - { - ret = EINVAL; - } - else - { - *attr = 0; - } - - sdbg("Returning %d\n", ret); - return ret; -} - - diff --git a/nuttx/libc/pthread/pthread_mutexattrdestroy.c b/nuttx/libc/pthread/pthread_mutexattrdestroy.c deleted file mode 100644 index 82a13c300e..0000000000 --- a/nuttx/libc/pthread/pthread_mutexattrdestroy.c +++ /dev/null @@ -1,104 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_mutexattrdestroy.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_mutexattr_destroy - * - * Description: - * Destroy mutex attributes. - * - * Parameters: - * attr - * pshared - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_mutexattr_destroy(FAR pthread_mutexattr_t *attr) -{ - int ret = OK; - - sdbg("attr=0x%p\n", attr); - - if (!attr) - { - ret = EINVAL; - } - else - { - attr->pshared = 0; - } - - sdbg("Returning %d\n", ret); - return ret; -} diff --git a/nuttx/libc/pthread/pthread_mutexattrgetpshared.c b/nuttx/libc/pthread/pthread_mutexattrgetpshared.c deleted file mode 100644 index dc18484ec5..0000000000 --- a/nuttx/libc/pthread/pthread_mutexattrgetpshared.c +++ /dev/null @@ -1,104 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_mutexattrgetpshared.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_mutexattr_getpshared - * - * Description: - * Get pshared mutex attribute. - * - * Parameters: - * attr - * pshared - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_mutexattr_getpshared(FAR pthread_mutexattr_t *attr, FAR int *pshared) -{ - int ret = OK; - - sdbg("attr=0x%p pshared=0x%p\n", attr, pshared); - - if (!attr || !pshared) - { - ret = EINVAL; - } - else - { - *pshared = attr->pshared; - } - - sdbg("Returning %d\n", ret); - return ret; -} diff --git a/nuttx/libc/pthread/pthread_mutexattrgettype.c b/nuttx/libc/pthread/pthread_mutexattrgettype.c deleted file mode 100644 index 3b8b3ec052..0000000000 --- a/nuttx/libc/pthread/pthread_mutexattrgettype.c +++ /dev/null @@ -1,98 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_mutexattrgettype.c - * - * Copyright (C) 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -#ifdef CONFIG_MUTEX_TYPES - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_mutexattr_gettype - * - * Description: - * Return the mutex type from the mutex attributes. - * - * Parameters: - * attr - The mutex attributes to query - * type - Location to return the mutex type - * - * Return Value: - * 0, if the mutex type was successfully return in 'type', or - * EINVAL, if any NULL pointers provided. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_mutexattr_gettype(const pthread_mutexattr_t *attr, int *type) -{ - if (attr && type) - { - *type = attr->type; - return 0; - } - return EINVAL; -} - -#endif /* CONFIG_MUTEX_TYPES */ diff --git a/nuttx/libc/pthread/pthread_mutexattrinit.c b/nuttx/libc/pthread/pthread_mutexattrinit.c deleted file mode 100644 index f8c2721953..0000000000 --- a/nuttx/libc/pthread/pthread_mutexattrinit.c +++ /dev/null @@ -1,106 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_mutexattrinit.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_mutexattr_init - * - * Description: - * Create mutex attributes. - * - * Parameters: - * attr - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_mutexattr_init(FAR pthread_mutexattr_t *attr) -{ - int ret = OK; - - sdbg("attr=0x%p\n", attr); - - if (!attr) - { - ret = EINVAL; - } - else - { - attr->pshared = 0; -#ifdef CONFIG_MUTEX_TYPES - attr->type = PTHREAD_MUTEX_DEFAULT; -#endif - } - - sdbg("Returning %d\n", ret); - return ret; -} diff --git a/nuttx/libc/pthread/pthread_mutexattrsetpshared.c b/nuttx/libc/pthread/pthread_mutexattrsetpshared.c deleted file mode 100644 index 7501fd980b..0000000000 --- a/nuttx/libc/pthread/pthread_mutexattrsetpshared.c +++ /dev/null @@ -1,104 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_mutexattrsetpshared.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_mutexattr_setpshared - * - * Description: - * Set pshared mutex attribute. - * - * Parameters: - * attr - * pshared - * - * Return Value: - * 0 if successful. Otherwise, an error code. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_mutexattr_setpshared(FAR pthread_mutexattr_t *attr, int pshared) -{ - int ret = OK; - - sdbg("attr=0x%p pshared=%d\n", attr, pshared); - - if (!attr || (pshared != 0 && pshared != 1)) - { - ret = EINVAL; - } - else - { - attr->pshared = pshared; - } - - sdbg("Returning %d\n", ret); - return ret; -} diff --git a/nuttx/libc/pthread/pthread_mutexattrsettype.c b/nuttx/libc/pthread/pthread_mutexattrsettype.c deleted file mode 100644 index 068a27dc26..0000000000 --- a/nuttx/libc/pthread/pthread_mutexattrsettype.c +++ /dev/null @@ -1,98 +0,0 @@ -/**************************************************************************** - * libc/pthread/pthread_mutexattrsettype.c - * - * Copyright (C) 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -#ifdef CONFIG_MUTEX_TYPES - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: pthread_mutexattr_settype - * - * Description: - * Set the mutex type in the mutex attributes. - * - * Parameters: - * attr - The mutex attributes in which to set the mutex type. - * type - The mutex type value to set. - * - * Return Value: - * 0, if the mutex type was successfully set in 'attr', or - * EINVAL, if 'attr' is NULL or 'type' unrecognized. - * - * Assumptions: - * - ****************************************************************************/ - -int pthread_mutexattr_settype(pthread_mutexattr_t *attr, int type) -{ - if (attr && type >= PTHREAD_MUTEX_NORMAL && type <= PTHREAD_MUTEX_RECURSIVE) - { - attr->type = type; - return OK; - } - return EINVAL; -} - -#endif /* CONFIG_MUTEX_TYPES */ diff --git a/nuttx/libc/queue/Make.defs b/nuttx/libc/queue/Make.defs deleted file mode 100644 index 9a843dbdc9..0000000000 --- a/nuttx/libc/queue/Make.defs +++ /dev/null @@ -1,47 +0,0 @@ -############################################################################ -# libc/queue/Make.defs -# -# 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. -# -############################################################################ - -# Add the queue C files to the build - -CSRCS += sq_addlast.c sq_addfirst.c sq_addafter.c \ - sq_rem.c sq_remlast.c sq_remfirst.c sq_remafter.c - -CSRCS += dq_addlast.c dq_addfirst.c dq_addafter.c dq_addbefore.c \ - dq_rem.c dq_remlast.c dq_remfirst.c - -# Add the queue directory to the build - -DEPPATH += --dep-path queue -VPATH += :queue diff --git a/nuttx/libc/queue/dq_addafter.c b/nuttx/libc/queue/dq_addafter.c deleted file mode 100644 index e4d1abf63d..0000000000 --- a/nuttx/libc/queue/dq_addafter.c +++ /dev/null @@ -1,74 +0,0 @@ -/************************************************************ - * libc/queue/dq_addafter.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: dq_addafter - * - * Description: - * dq_addafter function adds 'node' after 'qqqq' in the - * 'queue.' - * - ************************************************************/ - -void dq_addafter(FAR dq_entry_t *prev, FAR dq_entry_t *node, - dq_queue_t *queue) -{ - if (!queue->head || prev == queue->tail) - { - dq_addlast(node, queue); - } - else - { - FAR dq_entry_t *next = prev->flink; - node->blink = prev; - node->flink = next; - next->blink = node; - prev->flink = node; - } -} diff --git a/nuttx/libc/queue/dq_addbefore.c b/nuttx/libc/queue/dq_addbefore.c deleted file mode 100644 index 3c403fc944..0000000000 --- a/nuttx/libc/queue/dq_addbefore.c +++ /dev/null @@ -1,69 +0,0 @@ -/**************************************************************************** - * libc/queue/dq_addbefore.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: dq_addbefore - * - * Description: - * dq_addbefore adds 'node' before 'next' in 'queue' - * - ****************************************************************************/ - -void dq_addbefore(FAR dq_entry_t *next, FAR dq_entry_t *node, - dq_queue_t *queue) -{ - if (!queue->head || next == queue->head) - { - dq_addfirst(node, queue); - } - else - { - FAR dq_entry_t *prev = next->blink; - node->flink = next; - node->blink = prev; - prev->flink = node; - next->blink = node; - } -} diff --git a/nuttx/libc/queue/dq_addfirst.c b/nuttx/libc/queue/dq_addfirst.c deleted file mode 100644 index 56767b9289..0000000000 --- a/nuttx/libc/queue/dq_addfirst.c +++ /dev/null @@ -1,74 +0,0 @@ -/************************************************************ - * libc/queue/dq_addfirst.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: dq_addfirst - * - * Description: - * dq_addfirst affs 'node' at the beginning of 'queue' - * - ************************************************************/ - -void dq_addfirst(FAR dq_entry_t *node, dq_queue_t *queue) -{ - node->blink = NULL; - node->flink = queue->head; - - if (!queue->head) - { - queue->head = node; - queue->tail = node; - } - else - { - queue->head->blink = node; - queue->head = node; - } -} - diff --git a/nuttx/libc/queue/dq_addlast.c b/nuttx/libc/queue/dq_addlast.c deleted file mode 100644 index 3ef08abd05..0000000000 --- a/nuttx/libc/queue/dq_addlast.c +++ /dev/null @@ -1,74 +0,0 @@ -/************************************************************ - * libc/queue/dq_addlast.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: dq_addlast - * - * Description - * dq_addlast adds 'node' to the end of 'queue' - * - ************************************************************/ - -void dq_addlast(FAR dq_entry_t *node, dq_queue_t *queue) -{ - node->flink = NULL; - node->blink = queue->tail; - - if (!queue->head) - { - queue->head = node; - queue->tail = node; - } - else - { - queue->tail->flink = node; - queue->tail = node; - } -} - diff --git a/nuttx/libc/queue/dq_rem.c b/nuttx/libc/queue/dq_rem.c deleted file mode 100644 index db20762c75..0000000000 --- a/nuttx/libc/queue/dq_rem.c +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************ - * libc/queue/dq_rem.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: dq_rem - * - * Descripton: - * dq_rem removes 'node' from 'queue' - * - ************************************************************/ - -void dq_rem(FAR dq_entry_t *node, dq_queue_t *queue) -{ - FAR dq_entry_t *prev = node->blink; - FAR dq_entry_t *next = node->flink; - - if (!prev) - { - queue->head = next; - } - else - { - prev->flink = next; - } - - if (!next) - { - queue->tail = prev; - } - else - { - next->blink = prev; - } - - node->flink = NULL; - node->blink = NULL; -} - diff --git a/nuttx/libc/queue/dq_remfirst.c b/nuttx/libc/queue/dq_remfirst.c deleted file mode 100644 index e87acc3382..0000000000 --- a/nuttx/libc/queue/dq_remfirst.c +++ /dev/null @@ -1,82 +0,0 @@ -/************************************************************ - * libc/queue/dq_remfirst.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: dq_remfirst - * - * Description: - * dq_remfirst removes 'node' from the head of 'queue' - * - ************************************************************/ - -FAR dq_entry_t *dq_remfirst(dq_queue_t *queue) -{ - FAR dq_entry_t *ret = queue->head; - - if (ret) - { - FAR dq_entry_t *next = ret->flink; - if (!next) - { - queue->head = NULL; - queue->tail = NULL; - } - else - { - queue->head = next; - next->blink = NULL; - } - - ret->flink = NULL; - ret->blink = NULL; - } - - return ret; -} - diff --git a/nuttx/libc/queue/dq_remlast.c b/nuttx/libc/queue/dq_remlast.c deleted file mode 100644 index 18c1823359..0000000000 --- a/nuttx/libc/queue/dq_remlast.c +++ /dev/null @@ -1,78 +0,0 @@ -/**************************************************************************** - * libc/queue/dq_remlast.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/***************************************************(************************ - * Name: dq_remlast - * - * Description: - * dq_remlast removes the last entry from 'queue' - * - ****************************************************************************/ - -FAR dq_entry_t *dq_remlast(dq_queue_t *queue) -{ - FAR dq_entry_t *ret = queue->tail; - - if (ret) - { - FAR dq_entry_t *prev = ret->blink; - if (!prev) - { - queue->head = NULL; - queue->tail = NULL; - } - else - { - queue->tail = prev; - prev->flink = NULL; - } - - ret->flink = NULL; - ret->blink = NULL; - } - - return ret; -} - diff --git a/nuttx/libc/queue/sq_addafter.c b/nuttx/libc/queue/sq_addafter.c deleted file mode 100644 index 5d47feba0f..0000000000 --- a/nuttx/libc/queue/sq_addafter.c +++ /dev/null @@ -1,71 +0,0 @@ -/************************************************************ - * libc/queue/sq_addafter.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: sq_addafter.c - * - * Description: - * The sq_addafter function adds 'node' after 'prev' in the - * 'queue.' - * - ************************************************************/ - -void sq_addafter(FAR sq_entry_t *prev, FAR sq_entry_t *node, - sq_queue_t *queue) -{ - if (!queue->head || prev == queue->tail) - { - sq_addlast(node, queue); - } - else - { - node->flink = prev->flink; - prev->flink = node; - } -} diff --git a/nuttx/libc/queue/sq_addfirst.c b/nuttx/libc/queue/sq_addfirst.c deleted file mode 100644 index 9624861541..0000000000 --- a/nuttx/libc/queue/sq_addfirst.c +++ /dev/null @@ -1,67 +0,0 @@ -/************************************************************ - * libc/queue/sq_addfirst.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: sq_addfirst - * - * Description: - * The sq_addfirst function places the 'node' at the head - * of the 'queue' - * - ************************************************************/ - -void sq_addfirst(FAR sq_entry_t *node, sq_queue_t *queue) -{ - node->flink = queue->head; - if (!queue->head) - { - queue->tail = node; - } - queue->head = node; -} diff --git a/nuttx/libc/queue/sq_addlast.c b/nuttx/libc/queue/sq_addlast.c deleted file mode 100644 index faa07efb5c..0000000000 --- a/nuttx/libc/queue/sq_addlast.c +++ /dev/null @@ -1,72 +0,0 @@ -/************************************************************ - * libc/queue/sq_addlast.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: sq_addlast - * - * Description: - * The sq_addlast function places the 'node' at the tail of - * the 'queue' - ************************************************************/ - -void sq_addlast(FAR sq_entry_t *node, sq_queue_t *queue) -{ - node->flink = NULL; - if (!queue->head) - { - queue->head = node; - queue->tail = node; - } - else - { - queue->tail->flink = node; - queue->tail = node; - } -} - diff --git a/nuttx/libc/queue/sq_rem.c b/nuttx/libc/queue/sq_rem.c deleted file mode 100644 index 720be182cd..0000000000 --- a/nuttx/libc/queue/sq_rem.c +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************ - * libc/queue/sq_rem.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * public Functions - ************************************************************/ - -/************************************************************ - * Name: sq_rem - * - * Description: - * sq_rem removes a 'node' for 'queue.' - * - ************************************************************/ - -void sq_rem(FAR sq_entry_t *node, sq_queue_t *queue) -{ - if (queue->head && node) - { - if (node == queue->head) - { - queue->head = node->flink; - if (node == queue->tail) - { - queue->tail = NULL; - } - } - else - { - FAR sq_entry_t *prev; - for(prev = (FAR sq_entry_t*)queue->head; - prev && prev->flink != node; - prev = prev->flink); - - if (prev) - { - sq_remafter(prev, queue); - } - } - } -} diff --git a/nuttx/libc/queue/sq_remafter.c b/nuttx/libc/queue/sq_remafter.c deleted file mode 100644 index 0545a00f95..0000000000 --- a/nuttx/libc/queue/sq_remafter.c +++ /dev/null @@ -1,79 +0,0 @@ -/************************************************************ - * libc/queue/sq_remafter.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: - * - * Description: - * sq_remafter removes the entry following 'node; from the - * 'queue' Returns a reference to the removed entry. - * - ************************************************************/ - -FAR sq_entry_t *sq_remafter(FAR sq_entry_t *node, sq_queue_t *queue) -{ - FAR sq_entry_t *ret = node->flink; - if (queue->head && ret) - { - if (queue->tail == ret) - { - queue->tail = node; - node->flink = NULL; - } - else - { - node->flink = ret->flink; - } - - ret->flink = NULL; - } - - return ret; -} - diff --git a/nuttx/libc/queue/sq_remfirst.c b/nuttx/libc/queue/sq_remfirst.c deleted file mode 100644 index f81c18dc2e..0000000000 --- a/nuttx/libc/queue/sq_remfirst.c +++ /dev/null @@ -1,76 +0,0 @@ -/************************************************************ - * libc/queue/sq_remfirst.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: sq_remfirst - * - * Description: - * sq_remfirst function removes the first entry from - * 'queue' - * - ************************************************************/ - -FAR sq_entry_t *sq_remfirst(sq_queue_t *queue) -{ - FAR sq_entry_t *ret = queue->head; - - if (ret) - { - queue->head = ret->flink; - if (!queue->head) - { - queue->tail = NULL; - } - - ret->flink = NULL; - } - - return ret; -} - diff --git a/nuttx/libc/queue/sq_remlast.c b/nuttx/libc/queue/sq_remlast.c deleted file mode 100644 index 8f045e4932..0000000000 --- a/nuttx/libc/queue/sq_remlast.c +++ /dev/null @@ -1,87 +0,0 @@ -/************************************************************ - * libc/queue/sq_remlast.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include - -/************************************************************ - * Public Functions - ************************************************************/ - -/************************************************************ - * Name: sq_remlast - * - * Description: - * Removes the last entry in a singly-linked queue. - * - ************************************************************/ - -FAR sq_entry_t *sq_remlast(sq_queue_t *queue) -{ - FAR sq_entry_t *ret = queue->tail; - - if (ret) - { - if (queue->head == queue->tail) - { - queue->head = NULL; - queue->tail = NULL; - } - else - { - FAR sq_entry_t *prev; - for(prev = queue->head; - prev && prev->flink != ret; - prev = prev->flink); - - if (prev) - { - prev->flink = NULL; - queue->tail = prev; - } - } - - ret->flink = NULL; - } - - return ret; -} diff --git a/nuttx/libc/sched/Make.defs b/nuttx/libc/sched/Make.defs deleted file mode 100644 index d2356db0f1..0000000000 --- a/nuttx/libc/sched/Make.defs +++ /dev/null @@ -1,43 +0,0 @@ -############################################################################ -# libc/sched/Make.defs -# -# 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. -# -############################################################################ - -# Add the sched C files to the build - -CSRCS += sched_getprioritymax.c sched_getprioritymin.c - -# Add the sched directory to the build - -DEPPATH += --dep-path sched -VPATH += :sched diff --git a/nuttx/libc/sched/sched_getprioritymax.c b/nuttx/libc/sched/sched_getprioritymax.c deleted file mode 100644 index 6ea37e76a9..0000000000 --- a/nuttx/libc/sched/sched_getprioritymax.c +++ /dev/null @@ -1,100 +0,0 @@ -/************************************************************************ - * libc/sched/sched_getprioritymax.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include - -/************************************************************************ - * Definitions - ************************************************************************/ - -/************************************************************************ - * Private Type Declarations - ************************************************************************/ - -/************************************************************************ - * Global Variables - ************************************************************************/ - -/************************************************************************ - * Private Variables - ************************************************************************/ - -/************************************************************************ - * Private Function Prototypes - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: ched_get_priority_max - * - * Description: - * This function returns the value of the highest possible - * task priority for a specified scheduling policy. - * - * Inputs: - * policy - Scheduling policy requested. - * - * Return Value: - * The maximum priority value or -1 (ERROR) - * (errno is not set) - * - * Assumptions: - * - ************************************************************************/ - -int sched_get_priority_max(int policy) -{ - if (policy != SCHED_FIFO && policy != SCHED_RR) - { - return ERROR; - } - else - { - return SCHED_PRIORITY_MAX; - } -} diff --git a/nuttx/libc/sched/sched_getprioritymin.c b/nuttx/libc/sched/sched_getprioritymin.c deleted file mode 100644 index dbb46d81eb..0000000000 --- a/nuttx/libc/sched/sched_getprioritymin.c +++ /dev/null @@ -1,100 +0,0 @@ -/************************************************************************ - * libc/sched/sched_getprioritymin.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include - -/************************************************************************ - * Definitions - ************************************************************************/ - -/************************************************************************ - * Private Type Declarations - ************************************************************************/ - -/************************************************************************ - * Global Variables - ************************************************************************/ - -/************************************************************************ - * Private Variables - ************************************************************************/ - -/************************************************************************ - * Private Function Prototypes - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: sched_get_priority_min - * - * Description: - * This function returns the value of the lowest possible - * task priority for a specified scheduling policy. - * - * Inputs: - * policy - Scheduling policy requested. - * - * Return Value: - * The minimum priority value or -1 (ERROR) - * (errno is not set) - * - * Assumptions: - * - ************************************************************************/ - -int sched_get_priority_min(int policy) -{ - if (policy != SCHED_FIFO && policy != SCHED_RR) - { - return ERROR; - } - else - { - return SCHED_PRIORITY_MIN; - } -} diff --git a/nuttx/libc/semaphore/Make.defs b/nuttx/libc/semaphore/Make.defs deleted file mode 100644 index b6551ff96a..0000000000 --- a/nuttx/libc/semaphore/Make.defs +++ /dev/null @@ -1,43 +0,0 @@ -############################################################################ -# libc/semaphore/Make.defs -# -# 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. -# -############################################################################ - -# Add the semaphore C files to the build - -CSRCS += sem_init.c sem_getvalue.c - -# Add the semaphore directory to the build - -DEPPATH += --dep-path semaphore -VPATH += :semaphore diff --git a/nuttx/libc/semaphore/sem_getvalue.c b/nuttx/libc/semaphore/sem_getvalue.c deleted file mode 100644 index ce9d12611a..0000000000 --- a/nuttx/libc/semaphore/sem_getvalue.c +++ /dev/null @@ -1,108 +0,0 @@ -/**************************************************************************** - * libc/semaphore/sem_getvalue.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: sem_getvalue - * - * Description: - * This function updates the location referenced by 'sval' argument to - * have the value of the semaphore referenced by 'sem' without effecting - * the state of the semaphore. The updated value represents the actual - * semaphore value that occurred at some unspecified time during the call, - * but may not reflect the actual value of the semaphore when it is - * returned to the calling task. - * - * If 'sem' is locked, the value return by sem_getvalue() will either be - * zero or a negative number whose absolute value represents the number - * of tasks waiting for the semaphore. - * - * Parameters: - * sem - Semaphore descriptor - * sval - Buffer by which the value is returned - * - * Return Value: - * 0 (OK), or -1 (ERROR) if unsuccessful - * - * Assumptions: - * - ****************************************************************************/ - -int sem_getvalue(FAR sem_t *sem, FAR int *sval) -{ - if (sem && sval) - { - *sval = sem->semcount; - return OK; - } - else - { - set_errno(EINVAL); - return ERROR; - } -} diff --git a/nuttx/libc/semaphore/sem_init.c b/nuttx/libc/semaphore/sem_init.c deleted file mode 100644 index 7732eb57a5..0000000000 --- a/nuttx/libc/semaphore/sem_init.c +++ /dev/null @@ -1,125 +0,0 @@ -/**************************************************************************** - * libc/sem/sem_init.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: sem_init - * - * Description: - * This function initializes the UNAMED semaphore sem. Following a - * successful call to sem_init(), the semaophore may be used in subsequent - * calls to sem_wait(), sem_post(), and sem_trywait(). The semaphore - * remains usable until it is destroyed. - * - * Only sem itself may be used for performing synchronization. The result - * of referring to copies of sem in calls to sem_wait(), sem_trywait(), - * sem_post(), and sem_destroy() is undefined. - * - * Parameters: - * sem - Semaphore to be initialized - * pshared - Process sharing (not used) - * value - Semaphore initialization value - * - * Return Value: - * 0 (OK), or -1 (ERROR) if unsuccessful. - * - * Assumptions: - * - ****************************************************************************/ - -int sem_init(FAR sem_t *sem, int pshared, unsigned int value) -{ - /* Verify that a semaphore was provided and the count is within the valid - * range. - */ - - if (sem && value <= SEM_VALUE_MAX) - { - /* Initialize the seamphore count */ - - sem->semcount = (int16_t)value; - - /* Initialize to support priority inheritance */ - -#ifdef CONFIG_PRIORITY_INHERITANCE -# if CONFIG_SEM_PREALLOCHOLDERS > 0 - sem->hhead = NULL; -# else - sem->holder.htcb = NULL; - sem->holder.counts = 0; -# endif -#endif - return OK; - } - else - { - set_errno(EINVAL); - return ERROR; - } -} diff --git a/nuttx/libc/signal/Make.defs b/nuttx/libc/signal/Make.defs deleted file mode 100644 index fe7eb180e7..0000000000 --- a/nuttx/libc/signal/Make.defs +++ /dev/null @@ -1,47 +0,0 @@ -############################################################################ -# libc/signal/Make.defs -# -# 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. -# -############################################################################ - -ifneq ($(CONFIG_DISABLE_SIGNALS),y) - -# Add the signal C files to the build - -CSRCS += sig_emptyset.c sig_fillset.c sig_addset.c sig_delset.c sig_ismember.c - -# Add the signal directory to the build - -DEPPATH += --dep-path signal -VPATH += :signal - -endif diff --git a/nuttx/libc/signal/sig_addset.c b/nuttx/libc/signal/sig_addset.c deleted file mode 100644 index 06ddabd6b2..0000000000 --- a/nuttx/libc/signal/sig_addset.c +++ /dev/null @@ -1,100 +0,0 @@ -/**************************************************************************** - * libc/signal/sig_addset.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: sigaddset - * - * Description: - * This function adds the signal specified by signo to the signal set - * specified by set. - * - * Parameters: - * set - Signal set to add signal to - * signo - Signal to add - * - * Return Value: - * 0 (OK), or -1 (ERROR) if the signal number is invalid. - * - * Assumptions: - * - ****************************************************************************/ - -int sigaddset(FAR sigset_t *set, int signo) -{ - int ret = ERROR; - - /* Verify the signal */ - - if (GOOD_SIGNO(signo)) - { - /* Add the signal to the set */ - - *set |= SIGNO2SET(signo); - ret = OK; - } - - return ret; -} - diff --git a/nuttx/libc/signal/sig_delset.c b/nuttx/libc/signal/sig_delset.c deleted file mode 100644 index 04112d8729..0000000000 --- a/nuttx/libc/signal/sig_delset.c +++ /dev/null @@ -1,100 +0,0 @@ -/**************************************************************************** - * libc/signal/sig_delset.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: sigdelset - * - * Description: - * This function deletes the signal specified by signo from the signal - * set specified by the 'set' argument. - * - * Parameters: - * set - Signal set to delete the signal from - * signo - Signal to delete - * - * Return Value: - * 0 (OK), or -1 (ERROR) if the signal number is invalid. - * - * Assumptions: - * - ****************************************************************************/ - -int sigdelset(FAR sigset_t *set, int signo) -{ - int ret = ERROR; - - /* Verify the signal */ - - if (GOOD_SIGNO(signo)) - { - /* Delete the signal to the set */ - - *set &= ~SIGNO2SET(signo); - ret = OK; - } - - return ret; -} - diff --git a/nuttx/libc/signal/sig_emptyset.c b/nuttx/libc/signal/sig_emptyset.c deleted file mode 100644 index 16ddd3f68f..0000000000 --- a/nuttx/libc/signal/sig_emptyset.c +++ /dev/null @@ -1,88 +0,0 @@ -/**************************************************************************** - * libc/signal/sig_emptyset.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: sigemptyset - * - * Description: - * This function initializes the signal set specified by set such that all - * signals are excluded. - * - * Parameters: - * set - Signal set to initalize - * - * Return Value: - * 0 (OK), or -1 (ERROR) if the signal set cannot be initialized. - * - * Assumptions: - * - ****************************************************************************/ - -int sigemptyset(FAR sigset_t *set) -{ - *set = NULL_SIGNAL_SET; - return OK; -} - diff --git a/nuttx/libc/signal/sig_fillset.c b/nuttx/libc/signal/sig_fillset.c deleted file mode 100644 index 99ee95c1ff..0000000000 --- a/nuttx/libc/signal/sig_fillset.c +++ /dev/null @@ -1,88 +0,0 @@ -/**************************************************************************** - * libc/signal/sig_fillset.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Publics Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: sigfillset - * - * Description: - * This function initializes the signal set specified by set such that all - * signals are included. - * - * Parameters: - * set - Signal set to initalize - * - * Return Value: - * 0 (OK), or -1 (ERROR) if the signal set cannot be initialized. - * - * Assumptions: - * - ****************************************************************************/ - -int sigfillset(FAR sigset_t *set) -{ - *set = ALL_SIGNAL_SET; - return OK; -} - diff --git a/nuttx/libc/signal/sig_ismember.c b/nuttx/libc/signal/sig_ismember.c deleted file mode 100644 index 1a8590e003..0000000000 --- a/nuttx/libc/signal/sig_ismember.c +++ /dev/null @@ -1,101 +0,0 @@ -/**************************************************************************** - * libc/signal/sig_ismember.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: sigismember - * - * Description: - * This function tests whether the signal specified by signo is a member - * of the set specified by set. - * - * Parameters: - * set - Signal set to test - * signo - Signal to test for - * - * Return Value: - * 1 (true), if the specified signal is a member of the set, - * 0 (OK or FALSE), if it is not, or - * -1 (ERROR) if the signal number is invalid. - * - * Assumptions: - * - ****************************************************************************/ - -int sigismember(FAR const sigset_t *set, int signo) -{ - int ret = ERROR; - - /* Verify the signal */ - - if (GOOD_SIGNO(signo)) - { - /* Check if the signal is in the set */ - - ret = ((*set & SIGNO2SET(signo)) != 0); - } - - return ret; -} - diff --git a/nuttx/libc/stdio/Make.defs b/nuttx/libc/stdio/Make.defs deleted file mode 100644 index e18ab0220f..0000000000 --- a/nuttx/libc/stdio/Make.defs +++ /dev/null @@ -1,85 +0,0 @@ -############################################################################ -# libc/stdio/Make.defs -# -# 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. -# -############################################################################ - -# Add the stdio C files to the build -# This first group of C files do not depend on having file descriptors or -# C streams. - -CSRCS += lib_fileno.c lib_printf.c lib_rawprintf.c lib_lowprintf.c \ - lib_sprintf.c lib_asprintf.c lib_snprintf.c lib_libsprintf.c \ - lib_vsprintf.c lib_avsprintf.c lib_vsnprintf.c lib_libvsprintf.c \ - lib_meminstream.c lib_memoutstream.c lib_lowinstream.c \ - lib_lowoutstream.c lib_zeroinstream.c lib_nullinstream.c \ - lib_nulloutstream.c lib_sscanf.c - -# The remaining sources files depend upon file descriptors - -ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) - -CSRCS += lib_rawinstream.c lib_rawoutstream.c - -# And these depend upon both file descriptors and C streams - -ifneq ($(CONFIG_NFILE_STREAMS),0) - -CSRCS += lib_fopen.c lib_fclose.c lib_fread.c lib_libfread.c lib_fseek.c \ - lib_ftell.c lib_fsetpos.c lib_fgetpos.c lib_fgetc.c lib_fgets.c \ - lib_gets.c lib_fwrite.c lib_libfwrite.c lib_fflush.c \ - lib_libflushall.c lib_libfflush.c lib_rdflush.c lib_wrflush.c \ - lib_fputc.c lib_puts.c lib_fputs.c lib_ungetc.c lib_vprintf.c \ - lib_fprintf.c lib_vfprintf.c lib_stdinstream.c lib_stdoutstream.c \ - lib_perror.c lib_feof.c lib_ferror.c lib_clearerr.c - -endif -endif - -# Other support that depends on specific, configured features. - -ifeq ($(CONFIG_SYSLOG),y) -CSRCS += lib_syslogstream.c -endif - -ifeq ($(CONFIG_LIBC_FLOATINGPOINT),y) -CSRCS += lib_dtoa.c -endif - -ifeq ($(CONFIG_STDIO_LINEBUFFER),y) -CSRCS += lib_libnoflush.c -endif - -# Add the stdio directory to the build - -DEPPATH += --dep-path stdio -VPATH += :stdio diff --git a/nuttx/libc/stdio/lib_asprintf.c b/nuttx/libc/stdio/lib_asprintf.c deleted file mode 100644 index 20ca6de326..0000000000 --- a/nuttx/libc/stdio/lib_asprintf.c +++ /dev/null @@ -1,105 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_asprintf.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: asprintf - * - * Description: - * This function is similar to sprintf, except that it dynamically - * allocates a string (as with malloc) to hold the output, instead of - * putting the output in a buffer you allocate in advance. The ptr - * argument should be the address of a char * object, and a successful - * call to asprintf stores a pointer to the newly allocated string at that - * location. - * - * Returned Value: - * The returned value is the number of characters allocated for the buffer, - * or less than zero if an error occurred. Usually this means that the buffer - * could not be allocated. - * - ****************************************************************************/ - -int asprintf (FAR char **ptr, const char *fmt, ...) -{ - va_list ap; - int ret; - - /* Let avsprintf do all of the work */ - - va_start(ap, fmt); - ret = avsprintf(ptr, fmt, ap); - va_end(ap); - - return ret; -} diff --git a/nuttx/libc/stdio/lib_avsprintf.c b/nuttx/libc/stdio/lib_avsprintf.c deleted file mode 100644 index 15ff8c9fbd..0000000000 --- a/nuttx/libc/stdio/lib_avsprintf.c +++ /dev/null @@ -1,146 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_avsprintf.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: avsprintf - * - * Description: - * This function is similar to vsprintf, except that it dynamically - * allocates a string (as with malloc) to hold the output, instead of - * putting the output in a buffer you allocate in advance. The ptr - * argument should be the address of a char * object, and a successful - * call to avsprintf stores a pointer to the newly allocated string at that - * location. - * - * Returned Value: - * The returned value is the number of characters allocated for the buffer, - * or less than zero if an error occurred. Usually this means that the buffer - * could not be allocated. - * - ****************************************************************************/ - -int avsprintf(FAR char **ptr, const char *fmt, va_list ap) -{ - struct lib_outstream_s nulloutstream; - struct lib_memoutstream_s memoutstream; - FAR char *buf; - int nbytes; - - DEBUGASSERT(ptr && fmt); - - /* First, use a nullstream to get the size of the buffer. The number - * of bytes returned may or may not include the null terminator. - */ - - lib_nulloutstream(&nulloutstream); - nbytes = lib_vsprintf((FAR struct lib_outstream_s *)&nulloutstream, fmt, ap); - - /* Then allocate a buffer to hold that number of characters, adding one - * for the null terminator. - */ - - buf = (FAR char *)malloc(nulloutstream.nput + 1); - if (!buf) - { - return ERROR; - } - - /* Initialize a memory stream to write into the allocated buffer. The - * memory stream will reserve one byte at the end of the buffer for the - * null terminator and will not report this in the number of output bytes. - */ - - lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, - buf, nulloutstream.nput + 1); - - /* Then let lib_vsprintf do it's real thing */ - - nbytes = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, fmt, ap); - - /* Return a pointer to the string to the caller. NOTE: the memstream put() - * method has already added the NUL terminator to the end of the string (not - * included in the nput count). - * - * Hmmm.. looks like the memory would be stranded if lib_vsprintf() returned - * an error. Does that ever happen? - */ - - DEBUGASSERT(nbytes < 0 || nbytes == nulloutstream.nput); - *ptr = buf; - return nbytes; -} diff --git a/nuttx/libc/stdio/lib_clearerr.c b/nuttx/libc/stdio/lib_clearerr.c deleted file mode 100644 index 589b56feb6..0000000000 --- a/nuttx/libc/stdio/lib_clearerr.c +++ /dev/null @@ -1,69 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_clearerr.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include - -#if CONFIG_NFILE_STREAMS > 0 - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: Functions - * - * Description: - * Clear any end-of-file or error conditions. - * - * Returned Value: - * None - * - ****************************************************************************/ - -void clearerr(FILE *stream) -{ - stream->fs_flags = 0; -} -#endif /* CONFIG_NFILE_STREAMS */ - diff --git a/nuttx/libc/stdio/lib_dtoa.c b/nuttx/libc/stdio/lib_dtoa.c deleted file mode 100644 index 44290ae328..0000000000 --- a/nuttx/libc/stdio/lib_dtoa.c +++ /dev/null @@ -1,1641 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_dtoa.c - * - * This file was ported to NuttX by Yolande Cates. - * - * Copyright (c) 1990, 1993 - * The Regents of the University of California. All rights reserved. - * - * This code is derived from software contributed to Berkeley by - * Chris Torek. - * - * 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. All advertising materials mentioning features or use of this software - * must display the following acknowledgement: - * This product includes software developed by the University of - * California, Berkeley and its contributors. - * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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 "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#ifdef Unsigned_Shifts -# define Sign_Extend(a,b) if (b < 0) a |= 0xffff0000; -#else -# define Sign_Extend(a,b) /* no-op */ -#endif - -#ifdef CONFIG_ENDIAN_BIG -# define word0(x) ((uint32_t *)&x)[0] -# define word1(x) ((uint32_t *)&x)[1] -#else -# define word0(x) ((uint32_t *)&x)[1] -# define word1(x) ((uint32_t *)&x)[0] -#endif - -#ifdef CONFIG_ENDIAN_BIG -# define Storeinc(a,b,c) (((unsigned short *)a)[0] = (unsigned short)b, \ - ((unsigned short *)a)[1] = (unsigned short)c, a++) -#else -# define Storeinc(a,b,c) (((unsigned short *)a)[1] = (unsigned short)b, \ - ((unsigned short *)a)[0] = (unsigned short)c, a++) -#endif - -#define Exp_shift 20 -#define Exp_shift1 20 -#define Exp_msk1 0x100000 -#define Exp_msk11 0x100000 -#define Exp_mask 0x7ff00000 -#define P 53 -#define Bias 1023 -#define IEEE_Arith -#define Emin (-1022) -#define Exp_1 0x3ff00000 -#define Exp_11 0x3ff00000 -#define Ebits 11 -#define Frac_mask 0xfffff -#define Frac_mask1 0xfffff -#define Ten_pmax 22 -#define Bletch 0x10 -#define Bndry_mask 0xfffff -#define Bndry_mask1 0xfffff -#define LSB 1 -#define Sign_bit 0x80000000 -#define Log2P 1 -#define Tiny0 0 -#define Tiny1 1 -#define Quick_max 14 -#define Int_max 14 -#define Infinite(x) (word0(x) == 0x7ff00000) /* sufficient test for here */ - -#define Kmax 15 - -#define Bcopy(x,y) memcpy((char *)&x->sign, (char *)&y->sign, \ - y->wds*sizeof(long) + 2*sizeof(int)) - -/**************************************************************************** - * Private Type Definitions - ****************************************************************************/ - -struct Bigint -{ - struct Bigint *next; - int k, maxwds, sign, wds; - unsigned long x[1]; -}; - -typedef struct Bigint Bigint; - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static Bigint *freelist[Kmax + 1]; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -static Bigint *Balloc(int k) -{ - int x; - Bigint *rv; - - if ((rv = freelist[k])) - { - freelist[k] = rv->next; - } - else - { - x = 1 << k; - rv = (Bigint *)lib_malloc(sizeof(Bigint) + (x - 1) * sizeof(long)); - rv->k = k; - rv->maxwds = x; - } - rv->sign = rv->wds = 0; - return rv; -} - -static void Bfree(Bigint * v) -{ - if (v) - { - v->next = freelist[v->k]; - freelist[v->k] = v; - } -} - -/* multiply by m and add a */ - -static Bigint *multadd(Bigint * b, int m, int a) -{ - int i, wds; - unsigned long *x, y; -#ifdef Pack_32 - unsigned long xi, z; -#endif - Bigint *b1; - - wds = b->wds; - x = b->x; - i = 0; - do - { -#ifdef Pack_32 - xi = *x; - y = (xi & 0xffff) * m + a; - z = (xi >> 16) * m + (y >> 16); - a = (int)(z >> 16); - *x++ = (z << 16) + (y & 0xffff); -#else - y = *x * m + a; - a = (int)(y >> 16); - *x++ = y & 0xffff; -#endif - } - while (++i < wds); - if (a) - { - if (wds >= b->maxwds) - { - b1 = Balloc(b->k + 1); - Bcopy(b1, b); - Bfree(b); - b = b1; - } - b->x[wds++] = a; - b->wds = wds; - } - return b; -} - -static int hi0bits(unsigned long x) -{ - int k = 0; - - if (!(x & 0xffff0000)) - { - k = 16; - x <<= 16; - } - - if (!(x & 0xff000000)) - { - k += 8; - x <<= 8; - } - - if (!(x & 0xf0000000)) - { - k += 4; - x <<= 4; - } - - if (!(x & 0xc0000000)) - { - k += 2; - x <<= 2; - } - - if (!(x & 0x80000000)) - { - k++; - if (!(x & 0x40000000)) - { - return 32; - } - } - return k; -} - -static int lo0bits(unsigned long *y) -{ - int k; - unsigned long x = *y; - - if (x & 7) - { - if (x & 1) - { - return 0; - } - if (x & 2) - { - *y = x >> 1; - return 1; - } - *y = x >> 2; - return 2; - } - - k = 0; - if (!(x & 0xffff)) - { - k = 16; - x >>= 16; - } - - if (!(x & 0xff)) - { - k += 8; - x >>= 8; - } - - if (!(x & 0xf)) - { - k += 4; - x >>= 4; - } - - if (!(x & 0x3)) - { - k += 2; - x >>= 2; - } - - if (!(x & 1)) - { - k++; - x >>= 1; - if (!x & 1) - { - return 32; - } - } - *y = x; - return k; -} - -static Bigint *i2b(int i) -{ - Bigint *b; - - b = Balloc(1); - b->x[0] = i; - b->wds = 1; - return b; -} - -static Bigint *mult(Bigint * a, Bigint * b) -{ - Bigint *c; - int k, wa, wb, wc; - unsigned long carry, y, z; - unsigned long *x, *xa, *xae, *xb, *xbe, *xc, *xc0; -#ifdef Pack_32 - uint32_t z2; -#endif - - if (a->wds < b->wds) - { - c = a; - a = b; - b = c; - } - - k = a->k; - wa = a->wds; - wb = b->wds; - wc = wa + wb; - if (wc > a->maxwds) - { - k++; - } - c = Balloc(k); - for (x = c->x, xa = x + wc; x < xa; x++) - { - *x = 0; - } - xa = a->x; - xae = xa + wa; - xb = b->x; - xbe = xb + wb; - xc0 = c->x; -#ifdef Pack_32 - for (; xb < xbe; xb++, xc0++) - { - if ((y = *xb & 0xffff)) - { - x = xa; - xc = xc0; - carry = 0; - do - { - z = (*x & 0xffff) * y + (*xc & 0xffff) + carry; - carry = z >> 16; - z2 = (*x++ >> 16) * y + (*xc >> 16) + carry; - carry = z2 >> 16; - Storeinc(xc, z2, z); - } - while (x < xae); - *xc = carry; - } - if ((y = *xb >> 16)) - { - x = xa; - xc = xc0; - carry = 0; - z2 = *xc; - do - { - z = (*x & 0xffff) * y + (*xc >> 16) + carry; - carry = z >> 16; - Storeinc(xc, z, z2); - z2 = (*x++ >> 16) * y + (*xc & 0xffff) + carry; - carry = z2 >> 16; - } - while (x < xae); - *xc = z2; - } - } -#else - for (; xb < xbe; xc0++) - { - if ((y = *xb++)) - { - x = xa; - xc = xc0; - carry = 0; - do - { - z = *x++ * y + *xc + carry; - carry = z >> 16; - *xc++ = z & 0xffff; - } - while (x < xae); - *xc = carry; - } - } -#endif - for (xc0 = c->x, xc = xc0 + wc; wc > 0 && !*--xc; --wc); - c->wds = wc; - return c; -} - -static Bigint *p5s; - -static Bigint *pow5mult(Bigint * b, int k) -{ - Bigint *b1, *p5, *p51; - int i; - static int p05[3] = { 5, 25, 125 }; - - if ((i = k & 3)) - b = multadd(b, p05[i - 1], 0); - - if (!(k >>= 2)) - { - return b; - } - - if (!(p5 = p5s)) - { - /* first time */ - p5 = p5s = i2b(625); - p5->next = 0; - } - - for (;;) - { - if (k & 1) - { - b1 = mult(b, p5); - Bfree(b); - b = b1; - } - if (!(k >>= 1)) - { - break; - } - - if (!(p51 = p5->next)) - { - p51 = p5->next = mult(p5, p5); - p51->next = 0; - } - p5 = p51; - } - return b; -} - -static Bigint *lshift(Bigint * b, int k) -{ - int i, k1, n, n1; - Bigint *b1; - unsigned long *x, *x1, *xe, z; - -#ifdef Pack_32 - n = k >> 5; -#else - n = k >> 4; -#endif - k1 = b->k; - n1 = n + b->wds + 1; - for (i = b->maxwds; n1 > i; i <<= 1) - { - k1++; - } - b1 = Balloc(k1); - x1 = b1->x; - for (i = 0; i < n; i++) - { - *x1++ = 0; - } - x = b->x; - xe = x + b->wds; -#ifdef Pack_32 - if (k &= 0x1f) - { - k1 = 32 - k; - z = 0; - do - { - *x1++ = *x << k | z; - z = *x++ >> k1; - } - while (x < xe); - if ((*x1 = z)) - { - ++n1; - } - } -#else - if (k &= 0xf) - { - k1 = 16 - k; - z = 0; - do - { - *x1++ = ((*x << k) & 0xffff) | z; - z = *x++ >> k1; - } - while (x < xe); - if ((*x1 = z)) - { - ++n1; - } - } -#endif - else - do - { - *x1++ = *x++; - } - while (x < xe); - b1->wds = n1 - 1; - Bfree(b); - return b1; -} - -static int cmp(Bigint * a, Bigint * b) -{ - unsigned long *xa, *xa0, *xb, *xb0; - int i, j; - - i = a->wds; - j = b->wds; -#ifdef CONFIG_DEBUG_LIB - if (i > 1 && !a->x[i - 1]) - { - ldbg("cmp called with a->x[a->wds-1] == 0\n"); - } - if (j > 1 && !b->x[j - 1]) - { - ldbg("cmp called with b->x[b->wds-1] == 0\n"); - } -#endif - if (i -= j) - return i; - xa0 = a->x; - xa = xa0 + j; - xb0 = b->x; - xb = xb0 + j; - for (;;) - { - if (*--xa != *--xb) - return *xa < *xb ? -1 : 1; - if (xa <= xa0) - break; - } - return 0; -} - -static Bigint *diff(Bigint * a, Bigint * b) -{ - Bigint *c; - int i, wa, wb; - long borrow, y; /* We need signed shifts here. */ - unsigned long *xa, *xae, *xb, *xbe, *xc; -#ifdef Pack_32 - int32_t z; -#endif - - i = cmp(a, b); - if (!i) - { - c = Balloc(0); - c->wds = 1; - c->x[0] = 0; - return c; - } - if (i < 0) - { - c = a; - a = b; - b = c; - i = 1; - } - else - i = 0; - c = Balloc(a->k); - c->sign = i; - wa = a->wds; - xa = a->x; - xae = xa + wa; - wb = b->wds; - xb = b->x; - xbe = xb + wb; - xc = c->x; - borrow = 0; -#ifdef Pack_32 - do - { - y = (*xa & 0xffff) - (*xb & 0xffff) + borrow; - borrow = y >> 16; - Sign_Extend(borrow, y); - z = (*xa++ >> 16) - (*xb++ >> 16) + borrow; - borrow = z >> 16; - Sign_Extend(borrow, z); - Storeinc(xc, z, y); - } - while (xb < xbe); - while (xa < xae) - { - y = (*xa & 0xffff) + borrow; - borrow = y >> 16; - Sign_Extend(borrow, y); - z = (*xa++ >> 16) + borrow; - borrow = z >> 16; - Sign_Extend(borrow, z); - Storeinc(xc, z, y); - } -#else - do - { - y = *xa++ - *xb++ + borrow; - borrow = y >> 16; - Sign_Extend(borrow, y); - *xc++ = y & 0xffff; - } - while (xb < xbe); - while (xa < xae) - { - y = *xa++ + borrow; - borrow = y >> 16; - Sign_Extend(borrow, y); - *xc++ = y & 0xffff; - } -#endif - while (!*--xc) - wa--; - c->wds = wa; - return c; -} - -static Bigint *d2b(double d, int *e, int *bits) -{ - Bigint *b; - int de, i, k; - unsigned long *x, y, z; - -#ifdef Pack_32 - b = Balloc(1); -#else - b = Balloc(2); -#endif - x = b->x; - - z = word0(d) & Frac_mask; - word0(d) &= 0x7fffffff; /* clear sign bit, which we ignore */ - if ((de = (int)(word0(d) >> Exp_shift))) - z |= Exp_msk1; -#ifdef Pack_32 - if ((y = word1(d))) - { - if ((k = lo0bits(&y))) - { - x[0] = y | z << (32 - k); - z >>= k; - } - else - x[0] = y; - i = b->wds = (x[1] = z) ? 2 : 1; - } - else - { -#ifdef CONFIG_DEBUG_LIB - if (!z) - { - ldbg("Zero passed to d2b\n"); - } -#endif - k = lo0bits(&z); - x[0] = z; - i = b->wds = 1; - k += 32; - } -#else - if ((y = word1(d))) - { - if ((k = lo0bits(&y))) - if (k >= 16) - { - x[0] = y | ((z << (32 - k)) & 0xffff); - x[1] = z >> (k - 16) & 0xffff; - x[2] = z >> k; - i = 2; - } - else - { - x[0] = y & 0xffff; - x[1] = (y >> 16) | ((z << (16 - k)) & 0xffff); - x[2] = z >> k & 0xffff; - x[3] = z >> (k + 16); - i = 3; - } - else - { - x[0] = y & 0xffff; - x[1] = y >> 16; - x[2] = z & 0xffff; - x[3] = z >> 16; - i = 3; - } - } - else - { -#ifdef CONFIG_DEBUG_LIB - if (!z) - { - ldbg("Zero passed to d2b\n"); - } -#endif - k = lo0bits(&z); - if (k >= 16) - { - x[0] = z; - i = 0; - } - else - { - x[0] = z & 0xffff; - x[1] = z >> 16; - i = 1; - } - k += 32; - } - while (!x[i]) - --i; - b->wds = i + 1; -#endif - if (de) - { - *e = de - Bias - (P - 1) + k; - *bits = P - k; - } - else - { - *e = de - Bias - (P - 1) + 1 + k; -#ifdef Pack_32 - *bits = 32 * i - hi0bits(x[i - 1]); -#else - *bits = (i + 2) * 16 - hi0bits(x[i]); -#endif - } - return b; -} - -static const double tens[] = { - 1e0, 1e1, 1e2, 1e3, 1e4, 1e5, 1e6, 1e7, 1e8, 1e9, - 1e10, 1e11, 1e12, 1e13, 1e14, 1e15, 1e16, 1e17, 1e18, 1e19, - 1e20, 1e21, 1e22 -}; - -#ifdef IEEE_Arith -static const double bigtens[] = { 1e16, 1e32, 1e64, 1e128, 1e256 }; -static const double tinytens[] = { 1e-16, 1e-32, 1e-64, 1e-128, 1e-256 }; - -# define n_bigtens 5 -#else -static const double bigtens[] = { 1e16, 1e32 }; -static const double tinytens[] = { 1e-16, 1e-32 }; - -# define n_bigtens 2 -#endif - -static int quorem(Bigint * b, Bigint * S) -{ - int n; - long borrow, y; - unsigned long carry, q, ys; - unsigned long *bx, *bxe, *sx, *sxe; -#ifdef Pack_32 - int32_t z; - uint32_t si, zs; -#endif - - n = S->wds; -#ifdef CONFIG_DEBUG_LIB - if (b->wds > n) - { - ldbg("oversize b in quorem\n"); - } -#endif - if (b->wds < n) - { - return 0; - } - sx = S->x; - sxe = sx + --n; - bx = b->x; - bxe = bx + n; - q = *bxe / (*sxe + 1); /* ensure q <= true quotient */ -#ifdef CONFIG_DEBUG_LIB - if (q > 9) - { - ldbg("oversized quotient in quorem\n"); - } -#endif - if (q) - { - borrow = 0; - carry = 0; - do - { -#ifdef Pack_32 - si = *sx++; - ys = (si & 0xffff) * q + carry; - zs = (si >> 16) * q + (ys >> 16); - carry = zs >> 16; - y = (*bx & 0xffff) - (ys & 0xffff) + borrow; - borrow = y >> 16; - Sign_Extend(borrow, y); - z = (*bx >> 16) - (zs & 0xffff) + borrow; - borrow = z >> 16; - Sign_Extend(borrow, z); - Storeinc(bx, z, y); -#else - ys = *sx++ * q + carry; - carry = ys >> 16; - y = *bx - (ys & 0xffff) + borrow; - borrow = y >> 16; - Sign_Extend(borrow, y); - *bx++ = y & 0xffff; -#endif - } - while (sx <= sxe); - if (!*bxe) - { - bx = b->x; - while (--bxe > bx && !*bxe) - --n; - b->wds = n; - } - } - if (cmp(b, S) >= 0) - { - q++; - borrow = 0; - carry = 0; - bx = b->x; - sx = S->x; - do - { -#ifdef Pack_32 - si = *sx++; - ys = (si & 0xffff) + carry; - zs = (si >> 16) + (ys >> 16); - carry = zs >> 16; - y = (*bx & 0xffff) - (ys & 0xffff) + borrow; - borrow = y >> 16; - Sign_Extend(borrow, y); - z = (*bx >> 16) - (zs & 0xffff) + borrow; - borrow = z >> 16; - Sign_Extend(borrow, z); - Storeinc(bx, z, y); -#else - ys = *sx++ + carry; - carry = ys >> 16; - y = *bx - (ys & 0xffff) + borrow; - borrow = y >> 16; - Sign_Extend(borrow, y); - *bx++ = y & 0xffff; -#endif - } - while (sx <= sxe); - bx = b->x; - bxe = bx + n; - if (!*bxe) - { - while (--bxe > bx && !*bxe) - --n; - b->wds = n; - } - } - return q; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/* dtoa for IEEE arithmetic (dmg): convert double to ASCII string. - * - * Inspired by "How to Print Floating-Point Numbers Accurately" by - * Guy L. Steele, Jr. and Jon L. White [Proc. ACM SIGPLAN '90, pp. 92-101]. - * - * Modifications: - * 1. Rather than iterating, we use a simple numeric overestimate - * to determine k = floor(log10(d)). We scale relevant - * quantities using O(log2(k)) rather than O(k) multiplications. - * 2. For some modes > 2 (corresponding to ecvt and fcvt), we don't - * try to generate digits strictly left to right. Instead, we - * compute with fewer bits and propagate the carry if necessary - * when rounding the final digit up. This is often faster. - * 3. Under the assumption that input will be rounded nearest, - * mode 0 renders 1e23 as 1e23 rather than 9.999999999999999e22. - * That is, we allow equality in stopping tests when the - * round-nearest rule will give the same floating-point value - * as would satisfaction of the stopping test with strict - * inequality. - * 4. We remove common factors of powers of 2 from relevant - * quantities. - * 5. When converting floating-point integers less than 1e16, - * we use floating-point arithmetic rather than resorting - * to multiple-precision integers. - * 6. When asked to produce fewer than 15 digits, we first try - * to get by with floating-point arithmetic; we resort to - * multiple-precision integer arithmetic only if we cannot - * guarantee that the floating-point calculation has given - * the correctly rounded result. For k requested digits and - * "uniformly" distributed input, the probability is - * something like 10^(k-15) that we must resort to the int32_t - * calculation. - */ - -char *__dtoa(double d, int mode, int ndigits, int *decpt, int *sign, char **rve) -{ - /* Arguments ndigits, decpt, sign are similar to those of ecvt and fcvt; - * trailing zeros are suppressed from the returned string. If not null, *rve - * is set to point to the end of the return value. If d is +-Infinity or - * NaN, then *decpt is set to 9999. - * - * mode: 0 ==> shortest string that yields d when read in and rounded to - * nearest. 1 ==> like 0, but with Steele & White stopping rule; e.g. with - * IEEE P754 arithmetic , mode 0 gives 1e23 whereas mode 1 gives - * 9.999999999999999e22. 2 ==> max(1,ndigits) significant digits. This gives - * a return value similar to that of ecvt, except that trailing zeros are - * suppressed. 3 ==> through ndigits past the decimal point. This gives a - * return value similar to that from fcvt, except that trailing zeros are - * suppressed, and ndigits can be negative. 4-9 should give the same return - * values as 2-3, i.e., 4 <= mode <= 9 ==> same return as mode 2 + (mode & - * 1). These modes are mainly for debugging; often they run slower but - * sometimes faster than modes 2-3. 4,5,8,9 ==> left-to-right digit - * generation. 6-9 ==> don't try fast floating-point estimate (if - * applicable). - * - * Values of mode other than 0-9 are treated as mode 0. - * - * Sufficient space is allocated to the return value to hold the suppressed - * trailing zeros. */ - - int bbits, b2, b5, be, dig, i, ieps, ilim = 0, ilim0, ilim1 = 0, - j, j_1, k, k0, k_check, leftright, m2, m5, s2, s5, spec_case = 0, try_quick; - long L; - int denorm; - unsigned long x; - Bigint *b, *b1, *delta, *mlo = NULL, *mhi, *S; - double d2, ds, eps; - char *s, *s0; - static Bigint *result; - static int result_k; - - if (result) - { - result->k = result_k; - result->maxwds = 1 << result_k; - Bfree(result); - result = 0; - } - - if (word0(d) & Sign_bit) - { - /* set sign for everything, including 0's and NaNs */ - *sign = 1; - word0(d) &= ~Sign_bit; /* clear sign bit */ - } - else - { - *sign = 0; - } - -#if defined(IEEE_Arith) -# ifdef IEEE_Arith - if ((word0(d) & Exp_mask) == Exp_mask) -#else - if (word0(d) == 0x8000) -#endif - { - /* Infinity or NaN */ - *decpt = 9999; - s = -#ifdef IEEE_Arith - !word1(d) && !(word0(d) & 0xfffff) ? "Infinity" : -#endif - "NaN"; - if (rve) - *rve = -#ifdef IEEE_Arith - s[3] ? s + 8 : -#endif - s + 3; - return s; - } -#endif - if (!d) - { - *decpt = 1; - s = "0"; - if (rve) - *rve = s + 1; - return s; - } - - b = d2b(d, &be, &bbits); - if ((i = (int)(word0(d) >> Exp_shift1 & (Exp_mask >> Exp_shift1)))) - { - d2 = d; - word0(d2) &= Frac_mask1; - word0(d2) |= Exp_11; - - /* log(x) ~=~ log(1.5) + (x-1.5)/1.5 log10(x) = log(x) / log(10) ~=~ - * log(1.5)/log(10) + (x-1.5)/(1.5*log(10)) log10(d) = - * (i-Bias)*log(2)/log(10) + log10(d2) This suggests computing an - * approximation k to log10(d) by k = (i - Bias)*0.301029995663981 + ( - * (d2-1.5)*0.289529654602168 + 0.176091259055681 ); We want k to be too - * large rather than too small. The error in the first-order Taylor - * series approximation is in our favor, so we just round up the constant - * enough to compensate for any error in the multiplication of (i - Bias) - * by 0.301029995663981; since |i - Bias| <= 1077, and 1077 * 0.30103 * - * 2^-52 ~=~ 7.2e-14, adding 1e-13 to the constant term more than - * suffices. Hence we adjust the constant term to 0.1760912590558. (We - * could get a more accurate k by invoking log10, but this is probably - * not worthwhile.) */ - - i -= Bias; - denorm = 0; - } - else - { - /* d is denormalized */ - - i = bbits + be + (Bias + (P - 1) - 1); - x = i > 32 ? word0(d) << (64 - i) | word1(d) >> (i - 32) - : word1(d) << (32 - i); - d2 = x; - word0(d2) -= 31 * Exp_msk1; /* adjust exponent */ - i -= (Bias + (P - 1) - 1) + 1; - denorm = 1; - } - - ds = (d2 - 1.5) * 0.289529654602168 + 0.1760912590558 + i * 0.301029995663981; - k = (int)ds; - if (ds < 0. && ds != k) - { - k--; /* want k = floor(ds) */ - } - k_check = 1; - - if (k >= 0 && k <= Ten_pmax) - { - if (d < tens[k]) - k--; - k_check = 0; - } - - j = bbits - i - 1; - if (j >= 0) - { - b2 = 0; - s2 = j; - } - else - { - b2 = -j; - s2 = 0; - } - - if (k >= 0) - { - b5 = 0; - s5 = k; - s2 += k; - } - else - { - b2 -= k; - b5 = -k; - s5 = 0; - } - - if (mode < 0 || mode > 9) - { - mode = 0; - } - - try_quick = 1; - if (mode > 5) - { - mode -= 4; - try_quick = 0; - } - - leftright = 1; - switch (mode) - { - case 0: - case 1: - ilim = ilim1 = -1; - i = 18; - ndigits = 0; - break; - - case 2: - leftright = 0; - /* no break */ - case 4: - if (ndigits <= 0) - { - ndigits = 1; - } - - ilim = ilim1 = i = ndigits; - break; - - case 3: - leftright = 0; - /* no break */ - case 5: - i = ndigits + k + 1; - ilim = i; - ilim1 = i - 1; - if (i <= 0) - { - i = 1; - } - } - - j = sizeof(unsigned long); - for (result_k = 0; - (signed)(sizeof(Bigint) - sizeof(unsigned long) + j) <= i; - j <<= 1) - { - result_k++; - } - - result = Balloc(result_k); - s = s0 = (char *)result; - - if (ilim >= 0 && ilim <= Quick_max && try_quick) - { - /* Try to get by with floating-point arithmetic. */ - - i = 0; - d2 = d; - k0 = k; - ilim0 = ilim; - ieps = 2; /* conservative */ - - if (k > 0) - { - ds = tens[k & 0xf]; - j = k >> 4; - - if (j & Bletch) - { - /* prevent overflows */ - j &= Bletch - 1; - d /= bigtens[n_bigtens - 1]; - ieps++; - } - - for (; j; j >>= 1, i++) - { - if (j & 1) - { - ieps++; - ds *= bigtens[i]; - } - } - - d /= ds; - } - else if ((j_1 = -k)) - { - d *= tens[j_1 & 0xf]; - for (j = j_1 >> 4; j; j >>= 1, i++) - { - if (j & 1) - { - ieps++; - d *= bigtens[i]; - } - } - } - - if (k_check && d < 1. && ilim > 0) - { - if (ilim1 <= 0) - { - goto fast_failed; - } - - ilim = ilim1; - k--; - d *= 10.; - ieps++; - } - - eps = ieps * d + 7.; - word0(eps) -= (P - 1) * Exp_msk1; - if (ilim == 0) - { - S = mhi = 0; - d -= 5.; - if (d > eps) - goto one_digit; - if (d < -eps) - goto no_digits; - goto fast_failed; - } - -#ifndef No_leftright - if (leftright) - { - /* Use Steele & White method of only generating digits needed. */ - - eps = 0.5 / tens[ilim - 1] - eps; - for (i = 0;;) - { - L = (int)d; - d -= L; - *s++ = '0' + (int)L; - if (d < eps) - goto ret1; - if (1. - d < eps) - goto bump_up; - if (++i >= ilim) - break; - eps *= 10.; - d *= 10.; - } - } - else - { -#endif - /* Generate ilim digits, then fix them up. */ - - eps *= tens[ilim - 1]; - for (i = 1;; i++, d *= 10.) - { - L = (int)d; - d -= L; - *s++ = '0' + (int)L; - if (i == ilim) - { - if (d > 0.5 + eps) - goto bump_up; - else if (d < 0.5 - eps) - { - while (*--s == '0'); - s++; - goto ret1; - } - break; - } - } -#ifndef No_leftright - } -#endif - fast_failed: - s = s0; - d = d2; - k = k0; - ilim = ilim0; - } - - /* Do we have a "small" integer? */ - - if (be >= 0 && k <= Int_max) - { - /* Yes. */ - - ds = tens[k]; - if (ndigits < 0 && ilim <= 0) - { - S = mhi = 0; - if (ilim < 0 || d <= 5 * ds) - goto no_digits; - goto one_digit; - } - - for (i = 1;; i++) - { - L = (int)(d / ds); - d -= L * ds; -#ifdef Check_FLT_ROUNDS - /* If FLT_ROUNDS == 2, L will usually be high by 1 */ - if (d < 0) - { - L--; - d += ds; - } -#endif - *s++ = '0' + (int)L; - if (i == ilim) - { - d += d; - if (d > ds || (d == ds && (L & 1))) - { - bump_up: - while (*--s == '9') - if (s == s0) - { - k++; - *s = '0'; - break; - } - ++*s++; - } - break; - } - if (!(d *= 10.)) - { - break; - } - } - - goto ret1; - } - - m2 = b2; - m5 = b5; - mhi = mlo = 0; - if (leftright) - { - if (mode < 2) - { - i = denorm ? be + (Bias + (P - 1) - 1 + 1) : 1 + P - bbits; - } - else - { - j = ilim - 1; - if (m5 >= j) - m5 -= j; - else - { - s5 += j -= m5; - b5 += j; - m5 = 0; - } - if ((i = ilim) < 0) - { - m2 -= i; - i = 0; - } - } - - b2 += i; - s2 += i; - mhi = i2b(1); - } - - if (m2 > 0 && s2 > 0) - { - i = m2 < s2 ? m2 : s2; - b2 -= i; - m2 -= i; - s2 -= i; - } - - if (b5 > 0) - { - if (leftright) - { - if (m5 > 0) - { - mhi = pow5mult(mhi, m5); - b1 = mult(mhi, b); - Bfree(b); - b = b1; - } - if ((j = b5 - m5)) - b = pow5mult(b, j); - } - else - { - b = pow5mult(b, b5); - } - } - - S = i2b(1); - if (s5 > 0) - { - S = pow5mult(S, s5); - } - - /* Check for special case that d is a normalized power of 2. */ - - if (mode < 2) - { - if (!word1(d) && !(word0(d) & Bndry_mask) && word0(d) & Exp_mask) - { - /* The special case */ - b2 += Log2P; - s2 += Log2P; - spec_case = 1; - } - else - { - spec_case = 0; - } - } - - /* Arrange for convenient computation of quotients: shift left if - * necessary so divisor has 4 leading 0 bits. - * - * Perhaps we should just compute leading 28 bits of S once and for all - * and pass them and a shift to quorem, so it can do shifts and ors - * to compute the numerator for q. - */ - -#ifdef Pack_32 - if ((i = ((s5 ? 32 - hi0bits(S->x[S->wds - 1]) : 1) + s2) & 0x1f)) - { - i = 32 - i; - } -#else - if ((i = ((s5 ? 32 - hi0bits(S->x[S->wds - 1]) : 1) + s2) & 0xf)) - { - i = 16 - i; - } -#endif - - if (i > 4) - { - i -= 4; - b2 += i; - m2 += i; - s2 += i; - } - else if (i < 4) - { - i += 28; - b2 += i; - m2 += i; - s2 += i; - } - - if (b2 > 0) - { - b = lshift(b, b2); - } - - if (s2 > 0) - { - S = lshift(S, s2); - } - - if (k_check) - { - if (cmp(b, S) < 0) - { - k--; - b = multadd(b, 10, 0); /* we botched the k estimate */ - if (leftright) - { - mhi = multadd(mhi, 10, 0); - } - - ilim = ilim1; - } - } - - if (ilim <= 0 && mode > 2) - { - if (ilim < 0 || cmp(b, S = multadd(S, 5, 0)) <= 0) - { - /* no digits, fcvt style */ - no_digits: - k = -1 - ndigits; - goto ret; - } - one_digit: - *s++ = '1'; - k++; - goto ret; - } - - if (leftright) - { - if (m2 > 0) - { - mhi = lshift(mhi, m2); - } - - /* Compute mlo -- check for special case that d is a normalized power of - * 2. */ - - mlo = mhi; - if (spec_case) - { - mhi = Balloc(mhi->k); - Bcopy(mhi, mlo); - mhi = lshift(mhi, Log2P); - } - - for (i = 1;; i++) - { - dig = quorem(b, S) + '0'; - /* Do we yet have the shortest decimal string that will round to d? */ - j = cmp(b, mlo); - delta = diff(S, mhi); - j_1 = delta->sign ? 1 : cmp(b, delta); - Bfree(delta); -#ifndef ROUND_BIASED - if (j_1 == 0 && !mode && !(word1(d) & 1)) - { - if (dig == '9') - { - goto round_9_up; - } - - if (j > 0) - { - dig++; - } - - *s++ = dig; - goto ret; - } -#endif - if (j < 0 || (j == 0 && !mode -#ifndef ROUND_BIASED - && (!(word1(d) & 1)) -#endif - )) - { - if ((j_1 > 0)) - { - b = lshift(b, 1); - j_1 = cmp(b, S); - if ((j_1 > 0 || (j_1 == 0 && (dig & 1))) && dig++ == '9') - { - goto round_9_up; - } - } - - *s++ = dig; - goto ret; - } - - if (j_1 > 0) - { - if (dig == '9') - { /* possible if i == 1 */ - round_9_up: - *s++ = '9'; - goto roundoff; - } - - *s++ = dig + 1; - goto ret; - } - - *s++ = dig; - if (i == ilim) - { - break; - } - - b = multadd(b, 10, 0); - if (mlo == mhi) - { - mlo = mhi = multadd(mhi, 10, 0); - } - else - { - mlo = multadd(mlo, 10, 0); - mhi = multadd(mhi, 10, 0); - } - } - } - else - { - for (i = 1;; i++) - { - *s++ = dig = quorem(b, S) + '0'; - if (i >= ilim) - { - break; - } - - b = multadd(b, 10, 0); - } - } - - /* Round off last digit */ - - b = lshift(b, 1); - j = cmp(b, S); - if (j > 0 || (j == 0 && (dig & 1))) - { - roundoff: - while (*--s == '9') - if (s == s0) - { - k++; - *s++ = '1'; - goto ret; - } - ++*s++; - } - else - { - while (*--s == '0'); - s++; - } - -ret: - Bfree(S); - if (mhi) - { - if (mlo && mlo != mhi) - { - Bfree(mlo); - } - - Bfree(mhi); - } -ret1: - Bfree(b); - if (s == s0) - { /* don't return empty string */ - *s++ = '0'; - k = 0; - } - - *s = 0; - *decpt = k + 1; - if (rve) - { - *rve = s; - } - - return s0; -} diff --git a/nuttx/libc/stdio/lib_fclose.c b/nuttx/libc/stdio/lib_fclose.c deleted file mode 100644 index c04537adf7..0000000000 --- a/nuttx/libc/stdio/lib_fclose.c +++ /dev/null @@ -1,154 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fclose.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fclose - * - * Description - * The fclose() function will flush the stream pointed to by stream - * (writing any buffered output data using lib_fflush()) and close the - * underlying file descriptor. - * - * Returned Value: - * Upon successful completion 0 is returned. Otherwise, EOF is returned - * and the global variable errno is set to indicate the error. In either - * case any further access (including another call to fclose()) to the - * stream results in undefined behaviour. - * - ****************************************************************************/ - -int fclose(FAR FILE *stream) -{ - int err = EINVAL; - int ret = ERROR; - int status; - - /* Verify that a stream was provided. */ - - if (stream) - { - /* Check that the underlying file descriptor corresponds to an an open - * file. - */ - - ret = OK; - if (stream->fs_filedes >= 0) - { - /* If the stream was opened for writing, then flush the stream */ - - if ((stream->fs_oflags & O_WROK) != 0) - { - ret = lib_fflush(stream, true); - err = errno; - } - - /* Close the underlying file descriptor and save the return status */ - - status = close(stream->fs_filedes); - - /* If close() returns an error but flush() did not then make sure - * that we return the close() error condition. - */ - - if (ret == OK) - { - ret = status; - err = errno; - } - } - -#if CONFIG_STDIO_BUFFER_SIZE > 0 - /* Destroy the semaphore */ - - sem_destroy(&stream->fs_sem); - - /* Release the buffer */ - - if (stream->fs_bufstart) - { - lib_free(stream->fs_bufstart); - } - - /* Clear the whole structure */ - - memset(stream, 0, sizeof(FILE)); -#else -#if CONFIG_NUNGET_CHARS > 0 - /* Reset the number of ungetc characters */ - - stream->fs_nungotten = 0; -#endif - /* Reset the flags */ - - stream->fs_oflags = 0; -#endif - /* Setting the fs_filedescriptor to -1 makes the stream available for reuse */ - - stream->fs_filedes = -1; - } - - /* On an error, reset the errno to the first error encountered and return - * EOF. - */ - - if (ret != OK) - { - set_errno(err); - return EOF; - } - - /* Return success */ - - return OK; -} - diff --git a/nuttx/libc/stdio/lib_feof.c b/nuttx/libc/stdio/lib_feof.c deleted file mode 100644 index e036398fda..0000000000 --- a/nuttx/libc/stdio/lib_feof.c +++ /dev/null @@ -1,77 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_feof.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include - -#if CONFIG_NFILE_STREAMS > 0 - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: feof - * - * Description: - * The feof() function shall test if the currently file pointer for the - * stream is at the end of file. - * - * Returned Value: - * This function will return non-zero if the the file pointer is positioned - * at the end of file. - * - ****************************************************************************/ - -int feof(FILE *stream) -{ - /* If the end-of-file condition is encountered by any of the C-buffered - * I/O functions that perform read operations, they should set the - * __FS_FLAG_EOF in the fs_flags field of struct file_struct. - */ - - return (stream->fs_flags & __FS_FLAG_EOF) != 0; -} - -#endif /* CONFIG_NFILE_STREAMS */ - diff --git a/nuttx/libc/stdio/lib_ferror.c b/nuttx/libc/stdio/lib_ferror.c deleted file mode 100644 index a977394cb1..0000000000 --- a/nuttx/libc/stdio/lib_ferror.c +++ /dev/null @@ -1,90 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_ferror.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include - -#if CONFIG_NFILE_STREAMS > 0 - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: ferror - * - * Description: - * This function will test if the last operation resulted in an eror. This - * is used to disambiguate EOF and error conditions. - * - * Return Value: - * A non-zero value is returned to indicate the error condition. - * - ****************************************************************************/ - -int ferror(FILE *stream) -{ -#if 0 - /* If an error is encountered by any of the C-buffered I/O functions, they - * should set the __FS_FLAG_ERROR in the fs_flags field of struct - * file_struct. - */ - - return (stream->fs_flags & __FS_FLAG_ERROR) != 0; -#else - /* However, nothing currenlty sets the __FS_FLAG_ERROR flag (that is a job - * for another day). The __FS_FLAG_EOF is set by operations that perform - * read operations. Since ferror() is probably only called to disambiguate - * the meaning of other functions that return EOF, to indicate either EOF or - * an error, just testing for not EOF is probably sufficient for now. - * - * This approach would not work if ferror() is called in other contexts. In - * those cases, ferror() will always report an error. - */ - - return (stream->fs_flags & __FS_FLAG_EOF) == 0; -#endif -} - -#endif /* CONFIG_NFILE_STREAMS */ - diff --git a/nuttx/libc/stdio/lib_fflush.c b/nuttx/libc/stdio/lib_fflush.c deleted file mode 100644 index a84a14a599..0000000000 --- a/nuttx/libc/stdio/lib_fflush.c +++ /dev/null @@ -1,132 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fflush.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fflush - * - * Description: - * The function fflush() forces a write of all user-space buffered data for - * the given output or update stream via the stream's underlying write - * function. The open status of the stream is unaffected. - * - * If the stream argument is NULL, fflush() flushes all open output streams. - * - * Return: - * OK on success EOF on failure (with errno set appropriately) - * - ****************************************************************************/ - -int fflush(FAR FILE *stream) -{ - int ret; - - /* Is the stream argument NULL? */ - - if (!stream) - { - /* Yes... then this is a request to flush all streams */ - - ret = lib_flushall(sched_getstreams()); - } - else - { - ret = lib_fflush(stream, true); - } - - /* Check the return value */ - - if (ret < 0) - { - /* An error occurred during the flush AND/OR we were unable to flush - * all of the buffered write data. Set the errno value. - */ - - set_errno(-ret); - - /* And return EOF on failure. */ - - return EOF; - } - - return OK; -} - diff --git a/nuttx/libc/stdio/lib_fgetc.c b/nuttx/libc/stdio/lib_fgetc.c deleted file mode 100644 index 81e2e4ba72..0000000000 --- a/nuttx/libc/stdio/lib_fgetc.c +++ /dev/null @@ -1,101 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fgetc.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/************************************************************************** - * Global Constant Data - **************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/************************************************************************** - * Private Constant Data - **************************************************************************/ - -/**************************************************************************** - * Private Variables - **************************************************************************/ - -/**************************************************************************** - * Global Functions - **************************************************************************/ - -/**************************************************************************** - * fgetc - **************************************************************************/ - -int fgetc(FAR FILE *stream) -{ - unsigned char ch; - ssize_t ret; - - ret = lib_fread(&ch, 1, stream); - if (ret > 0) - { - return ch; - } - else - { - return EOF; - } -} diff --git a/nuttx/libc/stdio/lib_fgetpos.c b/nuttx/libc/stdio/lib_fgetpos.c deleted file mode 100644 index 7663ca2dbe..0000000000 --- a/nuttx/libc/stdio/lib_fgetpos.c +++ /dev/null @@ -1,123 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fgetpos.c - * - * Copyright (C) 2008-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fgetpos - * - * Description: - * fgetpos() function is an alternate interfaces equivalent to ftell(). - * It gets the current value of the file offset and store it in the location - * referenced by pos. On some non-UNIX systems an fpos_t object may be a - * complex object and fsetpos may be the only way to portably reposition a - * stream. - * - * Returned Value: - * Zero on succes; -1 on failure with errno set appropriately. - * - ****************************************************************************/ - -int fgetpos(FAR FILE *stream, FAR fpos_t *pos) -{ - long position; - -#if CONFIG_DEBUG - if (!stream || !pos) - { - set_errno(EINVAL); - return ERROR; - } -#endif - - position = ftell(stream); - if (position == -1) - { - return ERROR; - } - - *pos = (fpos_t)position; - return OK; -} diff --git a/nuttx/libc/stdio/lib_fgets.c b/nuttx/libc/stdio/lib_fgets.c deleted file mode 100644 index 35d024ebb0..0000000000 --- a/nuttx/libc/stdio/lib_fgets.c +++ /dev/null @@ -1,207 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fgets.c - * - * Copyright (C) 2007-2008, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ -/* Some environments may return CR as end-of-line, others LF, and others - * both. If not specified, the logic here assumes either (but not both) as - * the default. - */ - -#if defined(CONFIG_EOL_IS_CR) -# undef CONFIG_EOL_IS_LF -# undef CONFIG_EOL_IS_BOTH_CRLF -# undef CONFIG_EOL_IS_EITHER_CRLF -#elif defined(CONFIG_EOL_IS_LF) -# undef CONFIG_EOL_IS_CR -# undef CONFIG_EOL_IS_BOTH_CRLF -# undef CONFIG_EOL_IS_EITHER_CRLF -#elif defined(CONFIG_EOL_IS_BOTH_CRLF) -# undef CONFIG_EOL_IS_CR -# undef CONFIG_EOL_IS_LF -# undef CONFIG_EOL_IS_EITHER_CRLF -#elif defined(CONFIG_EOL_IS_EITHER_CRLF) -# undef CONFIG_EOL_IS_CR -# undef CONFIG_EOL_IS_LF -# undef CONFIG_EOL_IS_BOTH_CRLF -#else -# undef CONFIG_EOL_IS_CR -# undef CONFIG_EOL_IS_LF -# undef CONFIG_EOL_IS_BOTH_CRLF -# define CONFIG_EOL_IS_EITHER_CRLF 1 -#endif - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fgets - * - * Description: - * fgets() reads in at most one less than 'buflen' characters from stream - * and stores them into the buffer pointed to by 'buf'. Reading stops after - * an EOF or a newline. If a newline is read, it is stored into the - * buffer. A null terminator is stored after the last character in the - * buffer. - * - **************************************************************************/ - -char *fgets(FAR char *buf, int buflen, FILE *stream) -{ - int nch = 0; - - /* Sanity checks */ - - if (!stream || !buf || buflen < 1 || stream->fs_filedes < 0) - { - return NULL; - } - - if (buflen < 2) - { - *buf = '\0'; - return buf; - } - - /* Read characters until we have a full line. On each the loop we must - * be assured that there are two free bytes in the line buffer: One for - * the next character and one for the null terminator. - */ - - for(;;) - { - /* Get the next character */ - - int ch = fgetc(stream); - - /* Check for end-of-line. This is tricky only in that some - * environments may return CR as end-of-line, others LF, and - * others both. - */ - -#if defined(CONFIG_EOL_IS_LF) || defined(CONFIG_EOL_IS_BOTH_CRLF) - if (ch == '\n') -#elif defined(CONFIG_EOL_IS_CR) - if (ch == '\r') -#else /* elif CONFIG_EOL_IS_EITHER_CRLF */ - if (ch == '\n' || ch == '\r') -#endif - { - /* The newline is stored in the buffer along with the null - * terminator. - */ - - buf[nch++] = '\n'; - buf[nch] = '\0'; - return buf; - } - - /* Check for end-of-file */ - - else if (ch == EOF) - { - /* End of file with no data? */ - - if (!nch) - { - /* Yes.. return NULL as the end of file mark */ - - return NULL; - } - else - { - /* Terminate the line */ - - buf[nch] = '\0'; - return buf; - } - } - - /* Otherwise, check if the character is printable and, if so, put the - * character in the line buffer - */ - - else if (isprint(ch)) - { - buf[nch++] = ch; - - /* Check if there is room for another character and the line's - * null terminator. If not then we have to end the line now. - */ - - if (nch + 1 >= buflen) - { - buf[nch] = '\0'; - return buf; - } - } - } -} - diff --git a/nuttx/libc/stdio/lib_fileno.c b/nuttx/libc/stdio/lib_fileno.c deleted file mode 100644 index f227aa372b..0000000000 --- a/nuttx/libc/stdio/lib_fileno.c +++ /dev/null @@ -1,70 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fileno.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include - -#if CONFIG_NFILE_STREAMS > 0 - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -int fileno(FAR FILE *stream) -{ - int ret = -1; - if (stream) - { - ret = stream->fs_filedes; - } - - if (ret < 0) - { - set_errno(EBADF); - return ERROR; - } - - return ret; -} -#endif /* CONFIG_NFILE_STREAMS */ - diff --git a/nuttx/libc/stdio/lib_fopen.c b/nuttx/libc/stdio/lib_fopen.c deleted file mode 100644 index cb68b35843..0000000000 --- a/nuttx/libc/stdio/lib_fopen.c +++ /dev/null @@ -1,299 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fopen.c - * - * Copyright (C) 2007-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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -enum open_mode_e -{ - MODE_NONE = 0, /* No access mode determined */ - MODE_R, /* "r" or "rb" open for reading */ - MODE_W, /* "w" or "wb" open for writing, truncating or creating file */ - MODE_A, /* "a" or "ab" open for writing, appending to file */ - MODE_RPLUS, /* "r+", "rb+", or "r+b" open for update (reading and writing) */ - MODE_WPLUS, /* "w+", "wb+", or "w+b" open for update, truncating or creating file */ - MODE_APLUS /* "a+", "ab+", or "a+b" open for update, appending to file */ -}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_mode2oflags - ****************************************************************************/ - -static int lib_mode2oflags(FAR const char *mode) -{ - enum open_mode_e state; - int oflags; - - /* Verify that a mode string was provided. No error is */ - - if (!mode) - { - goto errout; - } - - /* Parse the mode string to determine the corresponding open flags */ - - state = MODE_NONE; - oflags = 0; - - for (; *mode; mode++) - { - switch (*mode) - { - /* Open for read access ("r", "r[+]", "r[b]", "r[b+]", or "r[+b]") */ - - case 'r' : - if (state == MODE_NONE) - { - /* Open for read access */ - - oflags = O_RDOK; - state = MODE_R; - } - else - { - goto errout; - } - break; - - /* Open for write access ("w", "w[+]", "w[b]", "w[b+]", or "w[+b]") */ - - case 'w' : - if (state == MODE_NONE) - { - /* Open for write access, truncating any existing file */ - - oflags = O_WROK|O_CREAT|O_TRUNC; - state = MODE_W; - } - else - { - goto errout; - } - break; - - /* Open for write/append access ("a", "a[+]", "a[b]", "a[b+]", or "a[+b]") */ - - case 'a' : - if (state == MODE_NONE) - { - /* Write to the end of the file */ - - oflags = O_WROK|O_CREAT|O_APPEND; - state = MODE_A; - } - else - { - goto errout; - } - break; - - /* Open for update access ("[r]+", "[rb]+]", "[r]+[b]", "[w]+", - * "[wb]+]", "[w]+[b]", "[a]+", "[ab]+]", "[a]+[b]") - */ - - case '+' : - switch (state) - { - case MODE_R: - { - /* Retain any binary mode selection */ - - oflags &= O_BINARY; - - /* Open for read/write access */ - - oflags |= O_RDWR; - state = MODE_RPLUS; - } - break; - - case MODE_W: - { - /* Retain any binary mode selection */ - - oflags &= O_BINARY; - - /* Open for write read/access, truncating any existing file */ - - oflags |= O_RDWR|O_CREAT|O_TRUNC; - state = MODE_WPLUS; - } - break; - - case MODE_A: - { - /* Retain any binary mode selection */ - - oflags &= O_BINARY; - - /* Read from the beginning of the file; write to the end */ - - oflags |= O_RDWR|O_CREAT|O_APPEND; - state = MODE_APLUS; - } - break; - - default: - goto errout; - break; - } - break; - - /* Open for binary access ("[r]b", "[r]b[+]", "[r+]b", "[w]b", - * "[w]b[+]", "[w+]b", "[a]b", "[a]b[+]", "[a+]b") - */ - - case 'b' : - if (state != MODE_NONE) - { - /* The file is opened in binary mode */ - - oflags |= O_BINARY; - } - else - { - goto errout; - } - break; - - /* Unrecognized or unsupported mode */ - - default: - goto errout; - break; - } - } - - return oflags; - -/* Both fopen and fdopen should fail with errno == EINVAL if the mode - * string is invalid. - */ - -errout: - set_errno(EINVAL); - return ERROR; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fdopen - ****************************************************************************/ - -FAR FILE *fdopen(int fd, FAR const char *mode) -{ - FAR FILE *ret = NULL; - int oflags; - - /* Map the open mode string to open flags */ - - oflags = lib_mode2oflags(mode); - if (oflags >= 0) - { - ret = fs_fdopen(fd, oflags, NULL); - } - - return ret; -} - -/**************************************************************************** - * Name: fopen - ****************************************************************************/ - -FAR FILE *fopen(FAR const char *path, FAR const char *mode) -{ - FAR FILE *ret = NULL; - int oflags; - int fd; - - /* Map the open mode string to open flags */ - - oflags = lib_mode2oflags(mode); - if (oflags < 0) - { - return NULL; - } - - /* Open the file */ - - fd = open(path, oflags, 0666); - - /* If the open was successful, then fdopen() the fil using the file - * desciptor returned by open. If open failed, then just return the - * NULL stream -- open() has already set the errno. - */ - - if (fd >= 0) - { - ret = fs_fdopen(fd, oflags, NULL); - if (!ret) - { - /* Don't forget to close the file descriptor if any other - * failures are reported by fdopen(). - */ - - (void)close(fd); - } - } - return ret; -} diff --git a/nuttx/libc/stdio/lib_fprintf.c b/nuttx/libc/stdio/lib_fprintf.c deleted file mode 100644 index 5b6fe58f42..0000000000 --- a/nuttx/libc/stdio/lib_fprintf.c +++ /dev/null @@ -1,93 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fprintf.c - * - * Copyright (C) 2007, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fprintf - ****************************************************************************/ - -int fprintf(FAR FILE *stream, FAR const char *fmt, ...) -{ - va_list ap; - int n; - - /* vfprintf into the stream */ - - va_start(ap, fmt); - n = vfprintf(stream, fmt, ap); - va_end(ap); - return n; -} diff --git a/nuttx/libc/stdio/lib_fputc.c b/nuttx/libc/stdio/lib_fputc.c deleted file mode 100644 index 5d8065b431..0000000000 --- a/nuttx/libc/stdio/lib_fputc.c +++ /dev/null @@ -1,113 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fputc.c - * - * Copyright (C) 2007, 2008, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fputc - ****************************************************************************/ - -int fputc(int c, FAR FILE *stream) -{ - unsigned char buf = (unsigned char)c; - int ret; - - ret = lib_fwrite(&buf, 1, stream); - if (ret > 0) - { - /* Flush the buffer if a newline is output */ - -#ifdef CONFIG_STDIO_LINEBUFFER - if (c == '\n') - { - ret = lib_fflush(stream, true); - if (ret < 0) - { - return EOF; - } - } -#endif - return c; - } - else - { - return EOF; - } -} diff --git a/nuttx/libc/stdio/lib_fputs.c b/nuttx/libc/stdio/lib_fputs.c deleted file mode 100644 index 7b87a89d00..0000000000 --- a/nuttx/libc/stdio/lib_fputs.c +++ /dev/null @@ -1,220 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fputs.c - * - * Copyright (C) 2007, 2008, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fputs - * - * Description: - * fputs() writes the string s to stream, without its trailing '\0'. - * - ****************************************************************************/ - -#if defined(CONFIG_ARCH_ROMGETC) -int fputs(FAR const char *s, FAR FILE *stream) -{ - int nput; - int ret; - char ch; - - /* Make sure that a string was provided. */ - -#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */ - if (!s) - { - set_errno(EINVAL); - return EOF; - } -#endif - - /* Write the string. Loop until the null terminator is encountered */ - - for (nput = 0, ch = up_romgetc(s); ch; nput++, s++, ch = up_romgetc(s)) - { - /* Write the next character to the stream buffer */ - - ret = lib_fwrite(&ch, 1, stream); - if (ret <= 0) - { - return EOF; - } - - /* Flush the buffer if a newline was written to the buffer */ - -#ifdef CONFIG_STDIO_LINEBUFFER - if (ch == '\n') - { - ret = lib_fflush(stream, true); - if (ret < 0) - { - return EOF; - } - } -#endif - } - - return nput; -} - -#elif defined(CONFIG_STDIO_LINEBUFFER) -int fputs(FAR const char *s, FAR FILE *stream) -{ - int nput; - int ret; - - /* Make sure that a string was provided. */ - -#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */ - if (!s) - { - set_errno(EINVAL); - return EOF; - } -#endif - - /* Write the string. Loop until the null terminator is encountered */ - - for (nput = 0; *s; nput++, s++) - { - /* Write the next character to the stream buffer */ - - ret = lib_fwrite(s, 1, stream); - if (ret <= 0) - { - return EOF; - } - - /* Flush the buffer if a newline was written to the buffer */ - - if (*s == '\n') - { - ret = lib_fflush(stream, true); - if (ret < 0) - { - return EOF; - } - } - } - - return nput; -} - -#else -int fputs(FAR const char *s, FAR FILE *stream) -{ - int ntowrite; - int nput; - - /* Make sure that a string was provided. */ - -#ifdef CONFIG_DEBUG /* Most parameter checking is disabled if DEBUG is off */ - if (!s) - { - set_errno(EINVAL); - return EOF; - } -#endif - - /* Get the length of the string. */ - - ntowrite = strlen(s); - if (ntowrite == 0) - { - return 0; - } - - /* Write the string */ - - nput = lib_fwrite(s, ntowrite, stream); - if (nput < 0) - { - return EOF; - } - return nput; -} -#endif diff --git a/nuttx/libc/stdio/lib_fread.c b/nuttx/libc/stdio/lib_fread.c deleted file mode 100644 index 6717141225..0000000000 --- a/nuttx/libc/stdio/lib_fread.c +++ /dev/null @@ -1,101 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fread.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fread - ****************************************************************************/ - -size_t fread(FAR void *ptr, size_t size, size_t n_items, FAR FILE *stream) -{ - size_t full_size = n_items * (size_t)size; - ssize_t bytes_read; - size_t items_read = 0; - - /* Write the data into the stream buffer */ - - bytes_read = lib_fread(ptr, full_size, stream); - if (bytes_read > 0) - { - /* Return the number of full items read */ - - items_read = bytes_read / size; - } - return items_read; -} - - diff --git a/nuttx/libc/stdio/lib_fseek.c b/nuttx/libc/stdio/lib_fseek.c deleted file mode 100644 index 36216d94a9..0000000000 --- a/nuttx/libc/stdio/lib_fseek.c +++ /dev/null @@ -1,138 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fseek.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fseek - * - * Description: - * The fseek() function sets the file position indicator for the stream - * pointed to by stream. The new position, measured in bytes, is obtained - * by adding offset bytes to the position specified by whence. If whence is - * set to SEEK_SET, SEEK_CUR, or SEEK_END, the offset is relative to the - * start of the file, the current position indicator, or end-of-file, - * respectively. A successful call to the fseek() function clears the - * end-of-file indicator for the stream and undoes any effects of the ungetc(3) - * function on the same stream. - * - * Returned Value: - * Zero on succes; -1 on failure with errno set appropriately. - * - ****************************************************************************/ - -int fseek(FAR FILE *stream, long int offset, int whence) -{ - #if CONFIG_STDIO_BUFFER_SIZE > 0 - /* Flush any valid read/write data in the buffer (also verifies stream) */ - - if (lib_rdflush(stream) < 0 || lib_wrflush(stream) < 0) - { - return ERROR; - } -#else - /* Verify that we were provided with a stream */ - - if (!stream) - { - set_errno(EBADF); - return ERROR; - } -#endif - - /* On success or failure, discard any characters saved by ungetc() */ - -#if CONFIG_NUNGET_CHARS > 0 - stream->fs_nungotten = 0; -#endif - - /* Perform the fseek on the underlying file descriptor */ - - return lseek(stream->fs_filedes, offset, whence) == (off_t)-1 ? ERROR : OK; -} - - diff --git a/nuttx/libc/stdio/lib_fsetpos.c b/nuttx/libc/stdio/lib_fsetpos.c deleted file mode 100644 index 3d79a18775..0000000000 --- a/nuttx/libc/stdio/lib_fsetpos.c +++ /dev/null @@ -1,116 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fsetpos.c - * - * Copyright (C) 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fsetpos - * - * Description: - * fsetpos() function is an alternate interfaces equivalent to fseek() - * (with whence set to SEEK_SET). It sets the current value of the file - * offset to value in the location referenced by pos. On some non-UNIX - * systems an fpos_t object may be a complex object and fsetpos may be the - * only way to portably reposition a stream. - * - * Returned Value: - * Zero on succes; -1 on failure with errno set appropriately. - * - ****************************************************************************/ - -int fsetpos(FAR FILE *stream, FAR fpos_t *pos) -{ -#if CONFIG_DEBUG - if (!stream || !pos) - { - set_errno(EINVAL); - return ERROR; - } -#endif - - return fseek(stream, (FAR off_t)*pos, SEEK_SET); -} diff --git a/nuttx/libc/stdio/lib_ftell.c b/nuttx/libc/stdio/lib_ftell.c deleted file mode 100644 index 99fc20f340..0000000000 --- a/nuttx/libc/stdio/lib_ftell.c +++ /dev/null @@ -1,129 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_ftell.c - * - * Copyright (C) 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: ftell - * - * Description: - * ftell() returns the current value of the file position indicator for the - * stream pointed to by stream. - * - * Returned Value: - * Zero on succes; -1 on failure with errno set appropriately. - * - ****************************************************************************/ - -long ftell(FAR FILE *stream) -{ - off_t position; - - /* Verify that we were provided with a stream */ - - if (!stream) - { - set_errno(EBADF); - return ERROR; - } - - /* Perform the lseek to the current position. This will not move the - * file pointer, but will return its current setting - */ - - position = lseek(stream->fs_filedes, 0, SEEK_CUR); - if (position != (off_t)-1) - { - return (long)position; - } - else - { - return ERROR; - } -} - - diff --git a/nuttx/libc/stdio/lib_fwrite.c b/nuttx/libc/stdio/lib_fwrite.c deleted file mode 100644 index e8de004feb..0000000000 --- a/nuttx/libc/stdio/lib_fwrite.c +++ /dev/null @@ -1,99 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_fwrite.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: fwrite - ****************************************************************************/ - -size_t fwrite(FAR const void *ptr, size_t size, size_t n_items, FAR FILE *stream) -{ - size_t full_size = n_items * (size_t)size; - ssize_t bytes_written; - size_t items_written = 0; - - /* Write the data into the stream buffer */ - - bytes_written = lib_fwrite(ptr, full_size, stream); - if (bytes_written > 0) - { - /* Return the number of full items written */ - - items_written = bytes_written / size; - } - return items_written; -} diff --git a/nuttx/libc/stdio/lib_gets.c b/nuttx/libc/stdio/lib_gets.c deleted file mode 100644 index 39c31d273d..0000000000 --- a/nuttx/libc/stdio/lib_gets.c +++ /dev/null @@ -1,120 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_gets.c - * - * Copyright (C) 2007-2008, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: gets - * - * Description: - * gets() reads a line from stdin into the buffer pointed to by s until - * either a terminating newline or EOF, which it replaces with '\0'. No - * check for buffer overrun is performed - * - * This API should not be used because it is inherently unsafe. Consider - * using fgets which is safer and slightly more efficient. - * - **************************************************************************/ - -FAR char *gets(FAR char *s) -{ - /* gets is ALMOST the same as fgets using stdin and no length limit - * (hence, the unsafeness of gets). So let fgets do most of the work. - */ - - FAR char *ret = fgets(s, INT_MAX, stdin); - if (ret) - { - /* Another subtle difference from fgets is that gets replaces - * end-of-line markers with null terminators. We will do that as - * a second step (with some loss in performance). - */ - - int len = strlen(ret); - if (len > 0 && ret[len-1] == '\n') - { - ret[len-1] = '\0'; - } - } - - return ret; -} - diff --git a/nuttx/libc/stdio/lib_libdtoa.c b/nuttx/libc/stdio/lib_libdtoa.c deleted file mode 100644 index 29f61fd76e..0000000000 --- a/nuttx/libc/stdio/lib_libdtoa.c +++ /dev/null @@ -1,304 +0,0 @@ -/**************************************************************************** - * libc/unistd/lib_libdtoa.c - * - * This file was ported to NuttX by Yolande Cates. - * - * Copyright (c) 1990, 1993 - * The Regents of the University of California. All rights reserved. - * - * This code is derived from software contributed to Berkeley by - * Chris Torek. - * - * 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. All advertising materials mentioning features or use of this software - * must display the following acknowledgement: - * This product includes software developed by the University of - * California, Berkeley and its contributors. - * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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 - ****************************************************************************/ - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define MAX_PREC 16 - -#ifndef MIN -# define MIN(a,b) (a < b ? a : b) -#endif - -#ifndef MAX -# define MAX(a,b) (a > b ? a : b) -#endif - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Name: zeroes - * - * Description: - * Print the specified number of zeres - * - ****************************************************************************/ - -static void zeroes(FAR struct lib_outstream_s *obj, int nzeroes) -{ - int i; - - for (i = nzeroes; i > 0; i--) - { - obj->put(obj, '0'); - } -} - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_dtoa - * - * Description: - * This is part of lib_vsprintf(). It handles the floating point formats. - * This version supports only the %f (with precision). If no precision - * was provided in the format, this will use precision == 0 which is - * probably not what you want. - * - * Input Parameters: - * obj - The output stream object - * fmt - The format character. Not used 'f' is always assumed - * prec - The number of digits to the right of the decimal point. If no - * precision is provided in the format, this will be zero. And, - * unfortunately in this case, it will be treated literally as - * a precision of zero. - * flags - Only ALTFORM and SHOWPLUS flags are supported. ALTFORM only - * applies if prec == 0 which is not supported anyway. - * value - The floating point value to convert. - * - ****************************************************************************/ - -static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec, - uint8_t flags, double value) -{ - FAR char *digits; /* String returned by __dtoa */ - FAR char *digalloc; /* Copy of digits to be freed after usage */ - FAR char *rve; /* Points to the end of the return value */ - int expt; /* Integer value of exponent */ - int numlen; /* Actual number of digits returned by cvt */ - int nchars; /* Number of characters to print */ - int dsgn; /* Unused sign indicator */ - int i; - - /* Non-zero... positive or negative */ - - if (value < 0) - { - value = -value; - SET_NEGATE(flags); - } - - /* Perform the conversion */ - - digits = __dtoa(value, 3, prec, &expt, &dsgn, &rve); - digalloc = digits; - numlen = rve - digits; - - if (IS_NEGATE(flags)) - { - obj->put(obj, '-'); - } - else if (IS_SHOWPLUS(flags)) - { - obj->put(obj, '+'); - } - - /* Special case exact zero or the case where the number is smaller than - * the print precision. - */ - - if (value == 0 || expt < -prec) - { - /* kludge for __dtoa irregularity */ - - obj->put(obj, '0'); - - /* A decimal point is printed only in the alternate form or if a - * particular precision is requested. - */ - - if (prec > 0 || IS_ALTFORM(flags)) - { - obj->put(obj, '.'); - - /* Always print at least one digit to the right of the decimal point. */ - - prec = MAX(1, prec); - } - } - - /* A non-zero value will be printed */ - - else - { - - /* Handle the case where the value is less than 1.0 (in magnitude) and - * will need a leading zero. - */ - - if (expt <= 0) - { - /* Print a single zero to the left of the decimal point */ - - obj->put(obj, '0'); - - /* Print the decimal point */ - - obj->put(obj, '.'); - - /* Print any leading zeros to the right of the decimal point */ - - if (expt < 0) - { - nchars = MIN(-expt, prec); - zeroes(obj, nchars); - prec -= nchars; - } - } - - /* Handle the general case where the value is greater than 1.0 (in - * magnitude). - */ - - else - { - /* Print the integer part to the left of the decimal point */ - - for (i = expt; i > 0; i--) - { - if (*digits != '\0') - { - obj->put(obj, *digits); - digits++; - } - else - { - obj->put(obj, '0'); - } - } - - /* Get the length of the fractional part */ - - numlen -= expt; - - /* If there is no fractional part, then a decimal point is printed - * only in the alternate form or if a particular precision is - * requested. - */ - - if (numlen > 0 || prec > 0 || IS_ALTFORM(flags)) - { - /* Print the decimal point */ - - obj->put(obj, '.'); - - /* Always print at least one digit to the right of the decimal - * point. - */ - - prec = MAX(1, prec); - } - } - - /* If a precision was specified, then limit the number digits to the - * right of the decimal point. - */ - - if (prec > 0) - { - nchars = MIN(numlen, prec); - } - else - { - nchars = numlen; - } - - /* Print the fractional part to the right of the decimal point */ - - for (i = nchars; i > 0; i--) - { - obj->put(obj, *digits); - digits++; - } - - /* Decremnt to get the number of trailing zeroes to print */ - - prec -= nchars; - } - - /* Finally, print any trailing zeroes */ - - zeroes(obj, prec); - - /* Is this memory supposed to be freed or not? */ - -#if 0 - if (digalloc) - { - free(digalloc); - } -#endif -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - diff --git a/nuttx/libc/stdio/lib_libfflush.c b/nuttx/libc/stdio/lib_libfflush.c deleted file mode 100644 index f2f0cfe144..0000000000 --- a/nuttx/libc/stdio/lib_libfflush.c +++ /dev/null @@ -1,202 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_libfflush.c - * - * Copyright (C) 2007-2008, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_fflush - * - * Description: - * The function lib_fflush() forces a write of all user-space buffered data for - * the given output or update stream via the stream's underlying write - * function. The open status of the stream is unaffected. - * - * Parmeters: - * stream - the stream to flush - * bforce - flush must be complete. - * - * Return: - * A negated errno value on failure, otherwise the number of bytes remaining - * in the buffer. - * - ****************************************************************************/ - -ssize_t lib_fflush(FAR FILE *stream, bool bforce) -{ -#if CONFIG_STDIO_BUFFER_SIZE > 0 - FAR const unsigned char *src; - ssize_t bytes_written; - ssize_t nbuffer; - - /* Return EBADF if the file is not opened for writing */ - - if (stream->fs_filedes < 0 || (stream->fs_oflags & O_WROK) == 0) - { - return -EBADF; - } - - /* Make sure that we have exclusive access to the stream */ - - lib_take_semaphore(stream); - - /* Make sure that the buffer holds valid data */ - - if (stream->fs_bufpos != stream->fs_bufstart) - { - /* Make sure that the buffer holds buffered write data. We do not - * support concurrent read/write buffer usage. - */ - - if (stream->fs_bufread != stream->fs_bufstart) - { - /* The buffer holds read data... just return zero meaning "no bytes - * remaining in the buffer." - */ - - lib_give_semaphore(stream); - return 0; - } - - /* How many bytes of write data are used in the buffer now */ - - nbuffer = stream->fs_bufpos - stream->fs_bufstart; - - /* Try to write that amount */ - - src = stream->fs_bufstart; - do - { - /* Perform the write */ - - bytes_written = write(stream->fs_filedes, src, nbuffer); - if (bytes_written < 0) - { - /* Write failed. The cause of the failure is in 'errno'. - * returned the negated errno value. - */ - - lib_give_semaphore(stream); - return -get_errno(); - } - - /* Handle partial writes. fflush() must either return with - * an error condition or with the data successfully flushed - * from the buffer. - */ - - src += bytes_written; - nbuffer -= bytes_written; - } - while (bforce && nbuffer > 0); - - /* Reset the buffer position to the beginning of the buffer */ - - stream->fs_bufpos = stream->fs_bufstart; - - /* For the case of an incomplete write, nbuffer will be non-zero - * It will hold the number of bytes that were not written. - * Move the data down in the buffer to handle this (rare) case - */ - - while (nbuffer) - { - *stream->fs_bufpos++ = *src++; - --nbuffer; - } - } - - /* Restore normal access to the stream and return the number of bytes - * remaining in the buffer. - */ - - lib_give_semaphore(stream); - return stream->fs_bufpos - stream->fs_bufstart; -#else - /* Return no bytes remaining in the buffer */ - - return 0; -#endif -} - diff --git a/nuttx/libc/stdio/lib_libflushall.c b/nuttx/libc/stdio/lib_libflushall.c deleted file mode 100644 index 7ac3da7e0e..0000000000 --- a/nuttx/libc/stdio/lib_libflushall.c +++ /dev/null @@ -1,137 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_libflushall.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_flushall - * - * Description: - * Called either (1) by the OS when a task exits, or (2) from fflush() - * when a NULL stream argument is provided. - * - ****************************************************************************/ - -int lib_flushall(FAR struct streamlist *list) -{ - int lasterrno = OK; - int ret; - - /* Make sure that there are streams associated with this thread */ - - if (list) - { - int i; - - /* Process each stream in the thread's stream list */ - - stream_semtake(list); - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) - { - FILE *stream = &list->sl_streams[i]; - - /* If the stream is open (i.e., assigned a non-negative file - * descriptor) and opened for writing, then flush all of the pending - * write data in the stream. - */ - - if (stream->fs_filedes >= 0 && (stream->fs_oflags & O_WROK) != 0) - { - /* Flush the writable FILE */ - - ret = lib_fflush(stream, true); - if (ret < 0) - { - /* An error occurred during the flush AND/OR we were unable - * to flush all of the buffered write data. Remember the - * last errcode. - */ - - lasterrno = ret; - } - } - } - - stream_semgive(list); - } - - /* If any flush failed, return the errorcode of the last failed flush */ - - return lasterrno; -} diff --git a/nuttx/libc/stdio/lib_libfread.c b/nuttx/libc/stdio/lib_libfread.c deleted file mode 100644 index bc6479037d..0000000000 --- a/nuttx/libc/stdio/lib_libfread.c +++ /dev/null @@ -1,315 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_libfread.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include /* for CONFIG_STDIO_BUFFER_SIZE */ - -#include -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_fread - ****************************************************************************/ - -ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) -{ - unsigned char *dest = (unsigned char*)ptr; - ssize_t bytes_read; - int ret; - - /* Make sure that reading from this stream is allowed */ - - if (!stream || (stream->fs_oflags & O_RDOK) == 0) - { - set_errno(EBADF); - bytes_read = -1; - } - else - { - /* The stream must be stable until we complete the read */ - - lib_take_semaphore(stream); - -#if CONFIG_NUNGET_CHARS > 0 - /* First, re-read any previously ungotten characters */ - - while ((stream->fs_nungotten > 0) && (count > 0)) - { - /* Decrement the count of ungotten bytes to get an index */ - - stream->fs_nungotten--; - - /* Return the last ungotten byte */ - - *dest++ = stream->fs_ungotten[stream->fs_nungotten]; - - /* That's one less byte that we have to read */ - - count--; - } -#endif - -#if CONFIG_STDIO_BUFFER_SIZE > 0 - /* If the buffer is currently being used for write access, then - * flush all of the buffered write data. We do not support concurrent - * buffered read/write access. - */ - - ret = lib_wrflush(stream); - if (ret < 0) - { - lib_give_semaphore(stream); - return ret; - } - - /* Now get any other needed chars from the buffer or the file. */ - - while (count > 0) - { - /* Is there readable data in the buffer? */ - - while ((count > 0) && (stream->fs_bufpos < stream->fs_bufread)) - { - /* Yes, copy a byte into the user buffer */ - - *dest++ = *stream->fs_bufpos++; - count--; - } - - /* The buffer is empty OR we have already supplied the number of - * bytes requested in the read. Check if we need to read - * more from the file. - */ - - if (count > 0) - { - size_t buffer_available; - - /* We need to read more data into the buffer from the file */ - - /* Mark the buffer empty */ - - stream->fs_bufpos = stream->fs_bufread = stream->fs_bufstart; - - /* How much space is available in the buffer? */ - - buffer_available = stream->fs_bufend - stream->fs_bufread; - - /* Will the number of bytes that we need to read fit into - * the buffer space that is available? If the read size is - * larger than the buffer, then read some of the data - * directly into the user's buffer. - */ - - if (count > buffer_available) - { - bytes_read = read(stream->fs_filedes, dest, count); - if (bytes_read < 0) - { - /* An error occurred on the read. The error code is - * in the 'errno' variable. - */ - - goto errout_with_errno; - } - else if (bytes_read == 0) - { - /* We are at the end of the file. But we may already - * have buffered data. In that case, we will report - * the EOF indication later. - */ - - goto shortread; - } - else - { - /* Some bytes were read. Adjust the dest pointer */ - - dest += bytes_read; - - /* Were all of the requested bytes read? */ - - if (bytes_read < count) - { - /* No. We must be at the end of file. */ - - goto shortread; - } - else - { - /* Yes. We are done. */ - - count = 0; - } - } - } - else - { - /* The number of bytes required to satisfy the read - * is less than or equal to the size of the buffer - * space that we have left. Read as much as we can - * into the buffer. - */ - - bytes_read = read(stream->fs_filedes, stream->fs_bufread, buffer_available); - if (bytes_read < 0) - { - /* An error occurred on the read. The error code is - * in the 'errno' variable. - */ - - goto errout_with_errno; - } - else if (bytes_read == 0) - { - /* We are at the end of the file. But we may already - * have buffered data. In that case, we will report - * the EOF indication later. - */ - - goto shortread; - } - else - { - /* Some bytes were read */ - - stream->fs_bufread += bytes_read; - } - } - } - } -#else - /* Now get any other needed chars from the file. */ - - while (count > 0) - { - bytes_read = read(stream->fs_filedes, dest, count); - if (bytes_read < 0) - { - /* An error occurred on the read. The error code is - * in the 'errno' variable. - */ - - goto errout_with_errno; - } - else if (bytes_read == 0) - { - /* We are at the end of the file. But we may already - * have buffered data. In that case, we will report - * the EOF indication later. - */ - - break; - } - else - { - dest += bytes_read; - count -= bytes_read; - } - } -#endif - /* Here after a successful (but perhaps short) read */ - -#if CONFIG_STDIO_BUFFER_SIZE > 0 - shortread: -#endif - bytes_read = dest - (unsigned char*)ptr; - - /* Set or clear the EOF indicator. If we get here because of a - * short read and the total number of* bytes read is zero, then - * we must be at the end-of-file. - */ - - if (bytes_read > 0) - { - stream->fs_flags &= ~__FS_FLAG_EOF; - } - else - { - stream->fs_flags |= __FS_FLAG_EOF; - } - } - - lib_give_semaphore(stream); - return bytes_read; - -/* Error exits */ - -errout_with_errno: - lib_give_semaphore(stream); - return -get_errno(); -} - diff --git a/nuttx/libc/stdio/lib_libfwrite.c b/nuttx/libc/stdio/lib_libfwrite.c deleted file mode 100644 index b917b3b564..0000000000 --- a/nuttx/libc/stdio/lib_libfwrite.c +++ /dev/null @@ -1,179 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_libfwrite.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include /* for CONFIG_STDIO_BUFFER_SIZE */ - -#include -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_fwrite - ****************************************************************************/ - -ssize_t lib_fwrite(FAR const void *ptr, size_t count, FAR FILE *stream) -#if CONFIG_STDIO_BUFFER_SIZE > 0 -{ - FAR const unsigned char *start = ptr; - FAR const unsigned char *src = ptr; - ssize_t ret = ERROR; - unsigned char *dest; - - /* Make sure that writing to this stream is allowed */ - - if (!stream || (stream->fs_oflags & O_WROK) == 0) - { - set_errno(EBADF); - goto errout; - } - - /* Get exclusive access to the stream */ - - lib_take_semaphore(stream); - - /* If the buffer is currently being used for read access, then - * discard all of the read-ahead data. We do not support concurrent - * buffered read/write access. - */ - - if (lib_rdflush(stream) < 0) - { - goto errout_with_semaphore; - } - - /* Loop until all of the bytes have been buffered */ - - while (count > 0) - { - /* Determine the number of bytes left in the buffer */ - - size_t gulp_size = stream->fs_bufend - stream->fs_bufpos; - - /* Will the user data fit into the amount of buffer space - * that we have left? - */ - - if (gulp_size > count) - { - /* Yes, clip the gulp to the size of the user data */ - - gulp_size = count; - } - - /* Adjust the number of bytes remaining to be transferred - * on the next pass through the loop (might be zero). - */ - - count -= gulp_size; - - /* Transfer the data into the buffer */ - - for (dest = stream->fs_bufpos; gulp_size > 0; gulp_size--) - { - *dest++ = *src++; - } - stream->fs_bufpos = dest; - - /* Is the buffer full? */ - - if (dest >= stream->fs_bufend) - { - /* Flush the buffered data to the IO stream */ - - int bytes_buffered = lib_fflush(stream, false); - if (bytes_buffered < 0) - { - goto errout_with_semaphore; - } - } - } - - /* Return the number of bytes written */ - - ret = src - start; - -errout_with_semaphore: - lib_give_semaphore(stream); - -errout: - return ret; -} -#else -{ - return write(stream->fs_filedes, ptr, count); -} -#endif /* CONFIG_STDIO_BUFFER_SIZE */ - diff --git a/nuttx/libc/stdio/lib_libnoflush.c b/nuttx/libc/stdio/lib_libnoflush.c deleted file mode 100644 index 076f8a17e6..0000000000 --- a/nuttx/libc/stdio/lib_libnoflush.c +++ /dev/null @@ -1,103 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_libnoflush.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include - -#include "lib_internal.h" - -#ifdef CONFIG_STDIO_LINEBUFFER - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_noflush - * - * Description: - * lib_noflush() provides a common, dummy flush method for output streams - * that are not flushable. Only used if CONFIG_STDIO_LINEBUFFER is selected. - * - * Return: - * Always returns OK - * - ****************************************************************************/ - -int lib_noflush(FAR struct lib_outstream_s *this) -{ - return OK; -} - -#endif /* CONFIG_STDIO_LINEBUFFER */ - diff --git a/nuttx/libc/stdio/lib_libsprintf.c b/nuttx/libc/stdio/lib_libsprintf.c deleted file mode 100644 index 2d820ab37b..0000000000 --- a/nuttx/libc/stdio/lib_libsprintf.c +++ /dev/null @@ -1,90 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_libsprintf.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_sprintf - ****************************************************************************/ - -int lib_sprintf(FAR struct lib_outstream_s *obj, const char *fmt, ...) -{ - va_list ap; - int n; - - /* Let lib_vsprintf do the real work */ - - va_start(ap, fmt); - n = lib_vsprintf(obj, fmt, ap); - va_end(ap); - return n; -} diff --git a/nuttx/libc/stdio/lib_libvsprintf.c b/nuttx/libc/stdio/lib_libvsprintf.c deleted file mode 100644 index 9a391610dc..0000000000 --- a/nuttx/libc/stdio/lib_libvsprintf.c +++ /dev/null @@ -1,1620 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_libvsprintf.c - * - * Copyright (C) 2007-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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ -/* If you have floating point but no fieldwidth, then use a fixed (but - * configurable) floating point precision. - */ - -#if defined(CONFIG_LIBC_FLOATINGPOINT) && \ - defined(CONFIG_NOPRINTF_FIELDWIDTH) && \ - !defined(CONFIG_LIBC_FIXEDPRECISION) -# define CONFIG_LIBC_FIXEDPRECISION 3 -#endif - -#define FLAG_SHOWPLUS 0x01 -#define FLAG_ALTFORM 0x02 -#define FLAG_HASDOT 0x04 -#define FLAG_HASASTERISKWIDTH 0x08 -#define FLAG_HASASTERISKTRUNC 0x10 -#define FLAG_LONGPRECISION 0x20 -#define FLAG_LONGLONGPRECISION 0x40 -#define FLAG_NEGATE 0x80 - -#define SET_SHOWPLUS(f) do (f) |= FLAG_SHOWPLUS; while (0) -#define SET_ALTFORM(f) do (f) |= FLAG_ALTFORM; while (0) -#define SET_HASDOT(f) do (f) |= FLAG_HASDOT; while (0) -#define SET_HASASTERISKWIDTH(f) do (f) |= FLAG_HASASTERISKWIDTH; while (0) -#define SET_HASASTERISKTRUNC(f) do (f) |= FLAG_HASASTERISKTRUNC; while (0) -#define SET_LONGPRECISION(f) do (f) |= FLAG_LONGPRECISION; while (0) -#define SET_LONGLONGPRECISION(f) do (f) |= FLAG_LONGLONGPRECISION; while (0) -#define SET_NEGATE(f) do (f) |= FLAG_NEGATE; while (0) - -#define CLR_SHOWPLUS(f) do (f) &= ~FLAG_SHOWPLUS; while (0) -#define CLR_ALTFORM(f) do (f) &= ~FLAG_ALTFORM; while (0) -#define CLR_HASDOT(f) do (f) &= ~FLAG_HASDOT; while (0) -#define CLR_HASASTERISKWIDTH(f) do (f) &= ~FLAG_HASASTERISKWIDTH; while (0) -#define CLR_HASASTERISKTRUNC(f) do (f) &= ~FLAG_HASASTERISKTRUNC; while (0) -#define CLR_LONGPRECISION(f) do (f) &= ~FLAG_LONGPRECISION; while (0) -#define CLR_LONGLONGPRECISION(f) do (f) &= ~FLAG_LONGLONGPRECISION; while (0) -#define CLR_NEGATE(f) do (f) &= ~FLAG_NEGATE; while (0) -#define CLR_SIGNED(f) do (f) &= ~(FLAG_SHOWPLUS|FLAG_NEGATE); while (0) - -#define IS_SHOWPLUS(f) (((f) & FLAG_SHOWPLUS) != 0) -#define IS_ALTFORM(f) (((f) & FLAG_ALTFORM) != 0) -#define IS_HASDOT(f) (((f) & FLAG_HASDOT) != 0) -#define IS_HASASTERISKWIDTH(f) (((f) & FLAG_HASASTERISKWIDTH) != 0) -#define IS_HASASTERISKTRUNC(f) (((f) & FLAG_HASASTERISKTRUNC) != 0) -#define IS_LONGPRECISION(f) (((f) & FLAG_LONGPRECISION) != 0) -#define IS_LONGLONGPRECISION(f) (((f) & FLAG_LONGLONGPRECISION) != 0) -#define IS_NEGATE(f) (((f) & FLAG_NEGATE) != 0) -#define IS_SIGNED(f) (((f) & (FLAG_SHOWPLUS|FLAG_NEGATE)) != 0) - -/* If CONFIG_ARCH_ROMGETC is defined, then it is assumed that the format - * string data cannot be accessed by simply de-referencing the format string - * pointer. This might be in the case in Harvard architectures where string - * data might be stored in instruction space or if string data were stored - * on some media like EEPROM or external serial FLASH. In all of these cases, - * string data has to be accessed indirectly using the architecture-supplied - * up_romgetc(). The following mechanisms attempt to make these different - * access methods indistinguishable in the following code. - * - * NOTE: It is assumed that string arguments for %s still reside in memory - * that can be directly accessed by de-referencing the string pointer. - */ - -#ifdef CONFIG_ARCH_ROMGETC -# define FMT_TOP ch = up_romgetc(src) /* Loop initialization */ -# define FMT_BOTTOM src++, ch = up_romgetc(src) /* Bottom of a loop */ -# define FMT_CHAR ch /* Access a character */ -# define FMT_NEXT src++; ch = up_romgetc(src) /* Advance to the next character */ -# define FMT_PREV src--; ch = up_romgetc(src) /* Backup to the previous character */ -#else -# define FMT_TOP /* Loop initialization */ -# define FMT_BOTTOM src++ /* Bottom of a loop */ -# define FMT_CHAR *src /* Access a character */ -# define FMT_NEXT src++ /* Advance to the next character */ -# define FMT_PREV src-- /* Backup to the previous character */ -#endif - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -enum -{ - FMT_RJUST = 0, /* Default */ - FMT_LJUST, - FMT_RJUST0, - FMT_CENTER -}; - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/* Pointer to ASCII conversion */ - -#ifdef CONFIG_PTR_IS_NOT_INT -static void ptohex(FAR struct lib_outstream_s *obj, uint8_t flags, FAR void *p); -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static int getsizesize(uint8_t fmt, uint8_t flags, FAR void *p) -#endif /* CONFIG_NOPRINTF_FIELDWIDTH */ -#endif /* CONFIG_PTR_IS_NOT_INT */ - -/* Unsigned int to ASCII conversion */ - -static void utodec(FAR struct lib_outstream_s *obj, unsigned int n); -static void utohex(FAR struct lib_outstream_s *obj, unsigned int n, uint8_t a); -static void utooct(FAR struct lib_outstream_s *obj, unsigned int n); -static void utobin(FAR struct lib_outstream_s *obj, unsigned int n); -static void utoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, - uint8_t flags, unsigned int lln); - -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static void fixup(uint8_t fmt, FAR uint8_t *flags, int *n); -static int getusize(uint8_t fmt, uint8_t flags, unsigned int lln); -#endif - -/* Unsigned long int to ASCII conversion */ - -#ifdef CONFIG_LONG_IS_NOT_INT -static void lutodec(FAR struct lib_outstream_s *obj, unsigned long ln); -static void lutohex(FAR struct lib_outstream_s *obj, unsigned long ln, uint8_t a); -static void lutooct(FAR struct lib_outstream_s *obj, unsigned long ln); -static void lutobin(FAR struct lib_outstream_s *obj, unsigned long ln); -static void lutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, - uint8_t flags, unsigned long ln); -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static void lfixup(uint8_t fmt, FAR uint8_t *flags, long *ln); -static int getlusize(uint8_t fmt, FAR uint8_t flags, unsigned long ln); -#endif -#endif - -/* Unsigned long long int to ASCII conversions */ - -#ifdef CONFIG_HAVE_LONG_LONG -static void llutodec(FAR struct lib_outstream_s *obj, unsigned long long lln); -static void llutohex(FAR struct lib_outstream_s *obj, unsigned long long lln, uint8_t a); -static void llutooct(FAR struct lib_outstream_s *obj, unsigned long long lln); -static void llutobin(FAR struct lib_outstream_s *obj, unsigned long long lln); -static void llutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, - uint8_t flags, unsigned long long lln); -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static void llfixup(uint8_t fmt, FAR uint8_t *flags, FAR long long *lln); -static int getllusize(uint8_t fmt, FAR uint8_t flags, FAR unsigned long long lln); -#endif -#endif - -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static void prejustify(FAR struct lib_outstream_s *obj, uint8_t fmt, - uint8_t flags, int fieldwidth, int valwidth); -static void postjustify(FAR struct lib_outstream_s *obj, uint8_t fmt, - uint8_t flags, int fieldwidth, int valwidth); -#endif - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -static const char g_nullstring[] = "(null)"; - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/* Include floating point functions */ - -#ifdef CONFIG_LIBC_FLOATINGPOINT -# include "stdio/lib_libdtoa.c" -#endif - -/**************************************************************************** - * Name: ptohex - ****************************************************************************/ - -#ifdef CONFIG_PTR_IS_NOT_INT -static void ptohex(FAR struct lib_outstream_s *obj, uint8_t flags, FAR void *p) -{ - union - { - uint32_t dw; - FAR void *p; - } u; - uint8_t bits; - - /* Check for alternate form */ - - if (IS_ALTFORM(flags)) - { - /* Prefix the number with "0x" */ - - obj->put(obj, '0'); - obj->put(obj, 'x'); - } - - u.dw = 0; - u.p = p; - - for (bits = 8*sizeof(void *); bits > 0; bits -= 4) - { - uint8_t nibble = (uint8_t)((u.dw >> (bits - 4)) & 0xf); - if (nibble < 10) - { - obj->put(obj, nibble + '0'); - } - else - { - obj->put(obj, nibble + 'a' - 10); - } - } -} - -/**************************************************************************** - * Name: getpsize - ****************************************************************************/ - -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static int getpsize(uint8_t flags, FAR void *p) -{ - struct lib_outstream_s nulloutstream; - lib_nulloutstream(&nulloutstream); - - ptohex(&nulloutstream, flags, p); - return nulloutstream.nput; -} - -#endif /* CONFIG_NOPRINTF_FIELDWIDTH */ -#endif /* CONFIG_PTR_IS_NOT_INT */ - -/**************************************************************************** - * Name: utodec - ****************************************************************************/ - -static void utodec(FAR struct lib_outstream_s *obj, unsigned int n) -{ - unsigned int remainder = n % 10; - unsigned int dividend = n / 10; - - if (dividend) - { - utodec(obj, dividend); - } - - obj->put(obj, (remainder + (unsigned int)'0')); -} - -/**************************************************************************** - * Name: utohex - ****************************************************************************/ - -static void utohex(FAR struct lib_outstream_s *obj, unsigned int n, uint8_t a) -{ - bool nonzero = false; - uint8_t bits; - - for (bits = 8*sizeof(unsigned int); bits > 0; bits -= 4) - { - uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf); - if (nibble || nonzero) - { - nonzero = true; - - if (nibble < 10) - { - obj->put(obj, nibble + '0'); - } - else - { - obj->put(obj, nibble + a - 10); - } - } - } - - if (!nonzero) - { - obj->put(obj, '0'); - } -} - -/**************************************************************************** - * Name: utooct - ****************************************************************************/ - -static void utooct(FAR struct lib_outstream_s *obj, unsigned int n) -{ - unsigned int remainder = n & 0x7; - unsigned int dividend = n >> 3; - - if (dividend) - { - utooct(obj, dividend); - } - - obj->put(obj, (remainder + (unsigned int)'0')); -} - -/**************************************************************************** - * Name: utobin - ****************************************************************************/ - -static void utobin(FAR struct lib_outstream_s *obj, unsigned int n) -{ - unsigned int remainder = n & 1; - unsigned int dividend = n >> 1; - - if (dividend) - { - utobin(obj, dividend); - } - - obj->put(obj, (remainder + (unsigned int)'0')); -} - -/**************************************************************************** - * Name: utoascii - ****************************************************************************/ - -static void utoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned int n) -{ - /* Perform the integer conversion according to the format specifier */ - - switch (fmt) - { - case 'd': - case 'i': - /* Signed base 10 */ - { -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - if ((int)n < 0) - { - obj->put(obj, '-'); - n = (unsigned int)(-(int)n); - } - else if (IS_SHOWPLUS(flags)) - { - obj->put(obj, '+'); - } -#endif - /* Convert the unsigned value to a string. */ - - utodec(obj, n); - } - break; - - case 'u': - /* Unigned base 10 */ - { -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - if (IS_SHOWPLUS(flags)) - { - obj->put(obj, '+'); - } -#endif - /* Convert the unsigned value to a string. */ - - utodec(obj, n); - } - break; - -#ifndef CONFIG_PTR_IS_NOT_INT - case 'p': -#endif - case 'x': - case 'X': - /* Hexadecimal */ - { - /* Check for alternate form */ - - if (IS_ALTFORM(flags)) - { - /* Prefix the number with "0x" */ - - obj->put(obj, '0'); - obj->put(obj, 'x'); - } - - /* Convert the unsigned value to a string. */ - - if (fmt == 'X') - { - utohex(obj, n, 'A'); - } - else - { - utohex(obj, n, 'a'); - } - } - break; - - case 'o': - /* Octal */ - { - /* Check for alternate form */ - - if (IS_ALTFORM(flags)) - { - /* Prefix the number with '0' */ - - obj->put(obj, '0'); - } - - /* Convert the unsigned value to a string. */ - - utooct(obj, n); - } - break; - - case 'b': - /* Binary */ - { - /* Convert the unsigned value to a string. */ - - utobin(obj, n); - } - break; - -#ifdef CONFIG_PTR_IS_NOT_INT - case 'p': -#endif - default: - break; - } -} - -/**************************************************************************** - * Name: fixup - ****************************************************************************/ - -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static void fixup(uint8_t fmt, FAR uint8_t *flags, FAR int *n) -{ - /* Perform the integer conversion according to the format specifier */ - - switch (fmt) - { - case 'd': - case 'i': - /* Signed base 10 */ - - if (*n < 0) - { - SET_NEGATE(*flags); - CLR_SHOWPLUS(*flags); - *n = -*n; - } - break; - - case 'u': - /* Unsigned base 10 */ - break; - - case 'p': - case 'x': - case 'X': - /* Hexadecimal */ - case 'o': - /* Octal */ - case 'b': - /* Binary */ - CLR_SIGNED(*flags); - break; - - default: - break; - } -} - -/**************************************************************************** - * Name: getusize - ****************************************************************************/ - -static int getusize(uint8_t fmt, uint8_t flags, unsigned int n) -{ - struct lib_outstream_s nulloutstream; - lib_nulloutstream(&nulloutstream); - - utoascii(&nulloutstream, fmt, flags, n); - return nulloutstream.nput; -} - -/**************************************************************************** - * Name: getdblsize - ****************************************************************************/ - -#ifdef CONFIG_LIBC_FLOATINGPOINT -static int getdblsize(uint8_t fmt, int trunc, uint8_t flags, double n) -{ - struct lib_outstream_s nulloutstream; - lib_nulloutstream(&nulloutstream); - - lib_dtoa(&nulloutstream, fmt, trunc, flags, n); - return nulloutstream.nput; -} -#endif -#endif /* CONFIG_NOPRINTF_FIELDWIDTH */ - -#ifdef CONFIG_LONG_IS_NOT_INT -/**************************************************************************** - * Name: lutodec - ****************************************************************************/ - -static void lutodec(FAR struct lib_outstream_s *obj, unsigned long n) -{ - unsigned int remainder = n % 10; - unsigned long dividend = n / 10; - - if (dividend) - { - lutodec(obj, dividend); - } - - obj->put(obj, (remainder + (unsigned int)'0')); -} - -/**************************************************************************** - * Name: lutohex - ****************************************************************************/ - -static void lutohex(FAR struct lib_outstream_s *obj, unsigned long n, uint8_t a) -{ - bool nonzero = false; - uint8_t bits; - - for (bits = 8*sizeof(unsigned long); bits > 0; bits -= 4) - { - uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf); - if (nibble || nonzero) - { - nonzero = true; - - if (nibble < 10) - { - obj->put(obj, nibble + '0'); - } - else - { - obj->put(obj, nibble + a - 10); - } - } - } - - if (!nonzero) - { - obj->put(obj, '0'); - } -} - -/**************************************************************************** - * Name: lutooct - ****************************************************************************/ - -static void lutooct(FAR struct lib_outstream_s *obj, unsigned long n) -{ - unsigned int remainder = n & 0x7; - unsigned long dividend = n >> 3; - - if (dividend) - { - lutooct(obj, dividend); - } - - obj->put(obj, (remainder + (unsigned int)'0')); -} - -/**************************************************************************** - * Name: lutobin - ****************************************************************************/ - -static void lutobin(FAR struct lib_outstream_s *obj, unsigned long n) -{ - unsigned int remainder = n & 1; - unsigned long dividend = n >> 1; - - if (dividend) - { - lutobin(obj, dividend); - } - - obj->put(obj, (remainder + (unsigned int)'0')); -} - -/**************************************************************************** - * Name: lutoascii - ****************************************************************************/ - -static void lutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned long ln) -{ - /* Perform the integer conversion according to the format specifier */ - - switch (fmt) - { - case 'd': - case 'i': - /* Signed base 10 */ - { -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - if ((long)ln < 0) - { - obj->put(obj, '-'); - ln = (unsigned long)(-(long)ln); - } - else if (IS_SHOWPLUS(flags)) - { - obj->put(obj, '+'); - } -#endif - /* Convert the unsigned value to a string. */ - - lutodec(obj, ln); - } - break; - - case 'u': - /* Unigned base 10 */ - { -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - if (IS_SHOWPLUS(flags)) - { - obj->put(obj, '+'); - } -#endif - /* Convert the unsigned value to a string. */ - - lutodec(obj, ln); - } - break; - - case 'x': - case 'X': - /* Hexadecimal */ - { - /* Check for alternate form */ - - if (IS_ALTFORM(flags)) - { - /* Prefix the number with "0x" */ - - obj->put(obj, '0'); - obj->put(obj, 'x'); - } - - /* Convert the unsigned value to a string. */ - - if (fmt == 'X') - { - lutohex(obj, ln, 'A'); - } - else - { - lutohex(obj, ln, 'a'); - } - } - break; - - case 'o': - /* Octal */ - { - /* Check for alternate form */ - - if (IS_ALTFORM(flags)) - { - /* Prefix the number with '0' */ - - obj->put(obj, '0'); - } - - /* Convert the unsigned value to a string. */ - - lutooct(obj, ln); - } - break; - - case 'b': - /* Binary */ - { - /* Convert the unsigned value to a string. */ - - lutobin(obj, ln); - } - break; - - case 'p': - default: - break; - } -} - -/**************************************************************************** - * Name: lfixup - ****************************************************************************/ - -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static void lfixup(uint8_t fmt, FAR uint8_t *flags, FAR long *ln) -{ - /* Perform the integer conversion according to the format specifier */ - - switch (fmt) - { - case 'd': - case 'i': - /* Signed base 10 */ - - if (*ln < 0) - { - SET_NEGATE(*flags); - CLR_SHOWPLUS(*flags); - *ln = -*ln; - } - break; - - case 'u': - /* Unsigned base 10 */ - break; - - case 'p': - case 'x': - case 'X': - /* Hexadecimal */ - case 'o': - /* Octal */ - case 'b': - /* Binary */ - CLR_SIGNED(*flags); - break; - - default: - break; - } -} - -/**************************************************************************** - * Name: getlusize - ****************************************************************************/ - -static int getlusize(uint8_t fmt, uint8_t flags, unsigned long ln) -{ - struct lib_outstream_s nulloutstream; - lib_nulloutstream(&nulloutstream); - - lutoascii(&nulloutstream, fmt, flags, ln); - return nulloutstream.nput; -} - -#endif /* CONFIG_NOPRINTF_FIELDWIDTH */ -#endif /* CONFIG_LONG_IS_NOT_INT */ - -#ifdef CONFIG_HAVE_LONG_LONG -/**************************************************************************** - * Name: llutodec - ****************************************************************************/ - -static void llutodec(FAR struct lib_outstream_s *obj, unsigned long long n) -{ - unsigned int remainder = n % 10; - unsigned long long dividend = n / 10; - - if (dividend) - { - llutodec(obj, dividend); - } - - obj->put(obj, (remainder + (unsigned int)'0')); -} - -/**************************************************************************** - * Name: llutohex - ****************************************************************************/ - -static void llutohex(FAR struct lib_outstream_s *obj, unsigned long long n, uint8_t a) -{ - bool nonzero = false; - uint8_t bits; - - for (bits = 8*sizeof(unsigned long long); bits > 0; bits -= 4) - { - uint8_t nibble = (uint8_t)((n >> (bits - 4)) & 0xf); - if (nibble || nonzero) - { - nonzero = true; - - if (nibble < 10) - { - obj->put(obj, (nibble + '0')); - } - else - { - obj->put(obj, (nibble + a - 10)); - } - } - } - - if (!nonzero) - { - obj->put(obj, '0'); - } -} - -/**************************************************************************** - * Name: llutooct - ****************************************************************************/ - -static void llutooct(FAR struct lib_outstream_s *obj, unsigned long long n) -{ - unsigned int remainder = n & 0x7; - unsigned long long dividend = n >> 3; - - if (dividend) - { - llutooct(obj, dividend); - } - - obj->put(obj, (remainder + (unsigned int)'0')); -} - -/**************************************************************************** - * Name: llutobin - ****************************************************************************/ - -static void llutobin(FAR struct lib_outstream_s *obj, unsigned long long n) -{ - unsigned int remainder = n & 1; - unsigned long long dividend = n >> 1; - - if (dividend) - { - llutobin(obj, dividend); - } - - obj->put(obj, (remainder + (unsigned int)'0')); -} - -/**************************************************************************** - * Name: llutoascii - ****************************************************************************/ - -static void llutoascii(FAR struct lib_outstream_s *obj, uint8_t fmt, uint8_t flags, unsigned long long lln) -{ - /* Perform the integer conversion according to the format specifier */ - - switch (fmt) - { - case 'd': - case 'i': - /* Signed base 10 */ - { -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - if ((long long)lln < 0) - { - obj->put(obj, '-'); - lln = (unsigned long long)(-(long long)lln); - } - else if (IS_SHOWPLUS(flags)) - { - obj->put(obj, '+'); - } -#endif - /* Convert the unsigned value to a string. */ - - llutodec(obj, (unsigned long long)lln); - } - break; - - case 'u': - /* Unigned base 10 */ - { -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - if (IS_SHOWPLUS(flags)) - { - obj->put(obj, '+'); - } -#endif - /* Convert the unsigned value to a string. */ - - llutodec(obj, (unsigned long long)lln); - } - break; - - case 'x': - case 'X': - /* Hexadecimal */ - { - /* Check for alternate form */ - - if (IS_ALTFORM(flags)) - { - /* Prefix the number with "0x" */ - - obj->put(obj, '0'); - obj->put(obj, 'x'); - } - - /* Convert the unsigned value to a string. */ - - if (fmt == 'X') - { - llutohex(obj, (unsigned long long)lln, 'A'); - } - else - { - llutohex(obj, (unsigned long long)lln, 'a'); - } - } - break; - - case 'o': - /* Octal */ - { - /* Check for alternate form */ - - if (IS_ALTFORM(flags)) - { - /* Prefix the number with '0' */ - - obj->put(obj, '0'); - } - - /* Convert the unsigned value to a string. */ - - llutooct(obj, (unsigned long long)lln); - } - break; - - case 'b': - /* Binary */ - { - /* Convert the unsigned value to a string. */ - - llutobin(obj, (unsigned long long)lln); - } - break; - - case 'p': - default: - break; - } -} - -/**************************************************************************** - * Name: llfixup - ****************************************************************************/ - -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static void llfixup(uint8_t fmt, FAR uint8_t *flags, FAR long long *lln) -{ - /* Perform the integer conversion according to the format specifier */ - - switch (fmt) - { - case 'd': - case 'i': - /* Signed base 10 */ - - if (*lln < 0) - { - SET_NEGATE(*flags); - CLR_SHOWPLUS(*flags); - *lln = -*lln; - } - break; - - case 'u': - /* Unsigned base 10 */ - break; - - case 'p': - case 'x': - case 'X': - /* Hexadecimal */ - case 'o': - /* Octal */ - case 'b': - /* Binary */ - CLR_SIGNED(*flags); - break; - - default: - break; - } -} - -/**************************************************************************** - * Name: getllusize - ****************************************************************************/ - -static int getllusize(uint8_t fmt, uint8_t flags, unsigned long long lln) -{ - struct lib_outstream_s nulloutstream; - lib_nulloutstream(&nulloutstream); - - - llutoascii(&nulloutstream, fmt, flags, lln); - return nulloutstream.nput; -} - -#endif /* CONFIG_NOPRINTF_FIELDWIDTH */ -#endif /* CONFIG_HAVE_LONG_LONG */ - -/**************************************************************************** - * Name: prejustify - ****************************************************************************/ - -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static void prejustify(FAR struct lib_outstream_s *obj, uint8_t fmt, - uint8_t flags, int fieldwidth, int valwidth) -{ - int i; - - switch (fmt) - { - default: - case FMT_RJUST: - if (IS_SIGNED(flags)) - { - valwidth++; - } - - for (i = fieldwidth - valwidth; i > 0; i--) - { - obj->put(obj, ' '); - } - - if (IS_NEGATE(flags)) - { - obj->put(obj, '-'); - } - else if (IS_SHOWPLUS(flags)) - { - obj->put(obj, '+'); - } - break; - - case FMT_RJUST0: - if (IS_NEGATE(flags)) - { - obj->put(obj, '-'); - valwidth++; - } - else if (IS_SHOWPLUS(flags)) - { - obj->put(obj, '+'); - valwidth++; - } - - for (i = fieldwidth - valwidth; i > 0; i--) - { - obj->put(obj, '0'); - } - break; - - case FMT_LJUST: - if (IS_NEGATE(flags)) - { - obj->put(obj, '-'); - } - else if (IS_SHOWPLUS(flags)) - { - obj->put(obj, '+'); - } - break; - } -} -#endif - -/**************************************************************************** - * Name: postjustify - ****************************************************************************/ - -#ifndef CONFIG_NOPRINTF_FIELDWIDTH -static void postjustify(FAR struct lib_outstream_s *obj, uint8_t fmt, - uint8_t flags, int fieldwidth, int valwidth) -{ - int i; - - /* Apply field justification to the integer value. */ - - switch (fmt) - { - default: - case FMT_RJUST: - case FMT_RJUST0: - break; - - case FMT_LJUST: - if (IS_SIGNED(flags)) - { - valwidth++; - } - - for (i = fieldwidth - valwidth; i > 0; i--) - { - obj->put(obj, ' '); - } - break; - } -} -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * libc/stdio/lib_vsprintf - ****************************************************************************/ - -int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list ap) -{ - FAR char *ptmp; -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - int width; -#ifdef CONFIG_LIBC_FLOATINGPOINT - int trunc; -#endif - uint8_t fmt; -#endif - uint8_t flags; -#ifdef CONFIG_ARCH_ROMGETC - char ch; -#endif - - for (FMT_TOP; FMT_CHAR; FMT_BOTTOM) - { - /* Just copy regular characters */ - - if (FMT_CHAR != '%') - { - /* Output the character */ - - obj->put(obj, FMT_CHAR); - - /* Flush the buffer if a newline is encountered */ - -#ifdef CONFIG_STDIO_LINEBUFFER - if (FMT_CHAR == '\n') - { - /* Should return an error on a failure to flush */ - - (void)obj->flush(obj); - } -#endif - /* Process the next character in the format */ - - continue; - } - - /* We have found a format specifier. Move past it. */ - - FMT_NEXT; - - /* Assume defaults */ - - flags = 0; -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - fmt = FMT_RJUST; - width = 0; -#ifdef CONFIG_LIBC_FLOATINGPOINT - trunc = 0; -#endif -#endif - - /* Process each format qualifier. */ - - for (; FMT_CHAR; FMT_BOTTOM) - { - /* Break out of the loop when the format is known. */ - - if (strchr("diuxXpobeEfgGlLsc%", FMT_CHAR)) - { - break; - } - - /* Check for left justification. */ - - else if (FMT_CHAR == '-') - { -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - fmt = FMT_LJUST; -#endif - } - - /* Check for leading zero fill right justification. */ - - else if (FMT_CHAR == '0') - { -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - fmt = FMT_RJUST0; -#endif - } -#if 0 - /* Center justification. */ - - else if (FMT_CHAR == '~') - { -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - fmt = FMT_CENTER; -#endif - } -#endif - - else if (FMT_CHAR == '*') - { -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - int value = va_arg(ap, int); - if (IS_HASDOT(flags)) - { -#ifdef CONFIG_LIBC_FLOATINGPOINT - trunc = value; - SET_HASASTERISKTRUNC(flags); -#endif - } - else - { - width = value; - SET_HASASTERISKWIDTH(flags); - } -#endif - } - - /* Check for field width */ - - else if (FMT_CHAR >= '1' && FMT_CHAR <= '9') - { -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - do - { - FMT_NEXT; - } - while (FMT_CHAR >= '0' && FMT_CHAR <= '9'); -#else - /* Accumulate the field width integer. */ - - int n = ((int)(FMT_CHAR)) - (int)'0'; - for (;;) - { - FMT_NEXT; - if (FMT_CHAR >= '0' && FMT_CHAR <= '9') - { - n = 10*n + (((int)(FMT_CHAR)) - (int)'0'); - } - else - { - break; - } - } - - if (IS_HASDOT(flags)) - { -#ifdef CONFIG_LIBC_FLOATINGPOINT - trunc = n; -#endif - } - else - { - width = n; - } -#endif - /* Back up to the last digit. */ - - FMT_PREV; - } - - /* Check for a decimal point. */ - - else if (FMT_CHAR == '.') - { -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - SET_HASDOT(flags); -#endif - } - - /* Check for leading plus sign. */ - - else if (FMT_CHAR == '+') - { - SET_SHOWPLUS(flags); - } - - /* Check for alternate form. */ - - else if (FMT_CHAR == '#') - { - SET_ALTFORM(flags); - } - } - - /* "%%" means that a literal '%' was intended (instead of a format - * specification). - */ - - if (FMT_CHAR == '%') - { - obj->put(obj, '%'); - continue; - } - - /* Check for the string format. */ - - if (FMT_CHAR == 's') - { -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - int swidth; -#endif - /* Get the string to output */ - - ptmp = va_arg(ap, char *); - if (!ptmp) - { - ptmp = (char*)g_nullstring; - } - - /* Get the widith of the string and perform right-justification - * operations. - */ - -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - swidth = strlen(ptmp); - prejustify(obj, fmt, 0, width, swidth); -#endif - /* Concatenate the string into the output */ - - while (*ptmp) - { - obj->put(obj, *ptmp); - ptmp++; - } - - /* Perform left-justification operations. */ - -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - postjustify(obj, fmt, 0, width, swidth); -#endif - continue; - } - - /* Check for the character output */ - - else if (FMT_CHAR == 'c') - { - /* Just copy the character into the output. */ - - int n = va_arg(ap, int); - obj->put(obj, n); - continue; - } - - /* Check for the long long prefix. */ - - if (FMT_CHAR == 'L') - { - SET_LONGLONGPRECISION(flags); - FMT_NEXT; - } - else if (FMT_CHAR == 'l') - { - SET_LONGPRECISION(flags); - FMT_NEXT; - if (FMT_CHAR == 'l') - { - SET_LONGLONGPRECISION(flags); - FMT_NEXT; - } - } - - /* Handle integer conversions */ - - if (strchr("diuxXpob", FMT_CHAR)) - { -#ifdef CONFIG_HAVE_LONG_LONG - if (IS_LONGLONGPRECISION(flags) && FMT_CHAR != 'p') - { - long long lln; -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - int lluwidth; -#endif - /* Extract the long long value. */ - - lln = va_arg(ap, long long); - -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - /* Output the number */ - - llutoascii(obj, FMT_CHAR, flags, (unsigned long long)lln); -#else - /* Resolve sign-ness and format issues */ - - llfixup(FMT_CHAR, &flags, &lln); - - /* Get the width of the output */ - - lluwidth = getllusize(FMT_CHAR, flags, lln); - - /* Perform left field justification actions */ - - prejustify(obj, fmt, flags, width, lluwidth); - - /* Output the number */ - - llutoascii(obj, FMT_CHAR, flags, (unsigned long long)lln); - - /* Perform right field justification actions */ - - postjustify(obj, fmt, flags, width, lluwidth); -#endif - } - else -#endif /* CONFIG_HAVE_LONG_LONG */ -#ifdef CONFIG_LONG_IS_NOT_INT - if (IS_LONGPRECISION(flags) && FMT_CHAR != 'p') - { - long ln; -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - int luwidth; -#endif - /* Extract the long value. */ - - ln = va_arg(ap, long); - -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - /* Output the number */ - - lutoascii(obj, FMT_CHAR, flags, (unsigned long)ln); -#else - /* Resolve sign-ness and format issues */ - - lfixup(FMT_CHAR, &flags, &ln); - - /* Get the width of the output */ - - luwidth = getlusize(FMT_CHAR, flags, ln); - - /* Perform left field justification actions */ - - prejustify(obj, fmt, flags, width, luwidth); - - /* Output the number */ - - lutoascii(obj, FMT_CHAR, flags, (unsigned long)ln); - - /* Perform right field justification actions */ - - postjustify(obj, fmt, flags, width, luwidth); -#endif - } - else -#endif /* CONFIG_LONG_IS_NOT_INT */ -#ifdef CONFIG_PTR_IS_NOT_INT - if (FMT_CHAR == 'p') - { - void *p; -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - int pwidth; -#endif - /* Extract the integer value. */ - - p = va_arg(ap, void *); - -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - /* Output the pointer value */ - - ptohex(obj, flags, p); -#else - /* Resolve sign-ness and format issues */ - - lfixup(FMT_CHAR, &flags, &ln); - - /* Get the width of the output */ - - luwidth = getpsize(FMT_CHAR, flags, p); - - /* Perform left field justification actions */ - - prejustify(obj, fmt, flags, width, pwidth); - - /* Output the pointer value */ - - ptohex(obj, flags, p); - - /* Perform right field justification actions */ - - postjustify(obj, fmt, flags, width, pwidth); -#endif - } - else -#endif - { - int n; -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - int uwidth; -#endif - /* Extract the long long value. */ - - n = va_arg(ap, int); - -#ifdef CONFIG_NOPRINTF_FIELDWIDTH - /* Output the number */ - - utoascii(obj, FMT_CHAR, flags, (unsigned int)n); -#else - /* Resolve sign-ness and format issues */ - - fixup(FMT_CHAR, &flags, &n); - - /* Get the width of the output */ - - uwidth = getusize(FMT_CHAR, flags, n); - - /* Perform left field justification actions */ - - prejustify(obj, fmt, flags, width, uwidth); - - /* Output the number */ - - utoascii(obj, FMT_CHAR, flags, (unsigned int)n); - - /* Perform right field justification actions */ - - postjustify(obj, fmt, flags, width, uwidth); -#endif - } - } - - /* Handle floating point conversions */ - -#ifdef CONFIG_LIBC_FLOATINGPOINT - else if (strchr("eEfgG", FMT_CHAR)) - { -#ifndef CONFIG_NOPRINTF_FIELDWIDTH - double dblval = va_arg(ap, double); - int dblsize; - - /* Get the width of the output */ - - dblsize = getdblsize(FMT_CHAR, trunc, flags, dblval); - - /* Perform left field justification actions */ - - prejustify(obj, fmt, 0, width, dblsize); - - /* Output the number */ - - lib_dtoa(obj, FMT_CHAR, trunc, flags, dblval); - - /* Perform right field justification actions */ - - postjustify(obj, fmt, 0, width, dblsize); -#else - /* Output the number with a fixed precision */ - - double dblval = va_arg(ap, double); - lib_dtoa(obj, FMT_CHAR, CONFIG_LIBC_FIXEDPRECISION, flags, dblval); -#endif - } -#endif /* CONFIG_LIBC_FLOATINGPOINT */ - } - - return obj->nput; -} - - diff --git a/nuttx/libc/stdio/lib_lowinstream.c b/nuttx/libc/stdio/lib_lowinstream.c deleted file mode 100644 index 7284601e8e..0000000000 --- a/nuttx/libc/stdio/lib_lowinstream.c +++ /dev/null @@ -1,102 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_lowinstream.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include - -#include "lib_internal.h" - -#ifdef CONFIG_ARCH_LOWGETC - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lowinstream_getc - ****************************************************************************/ - -static int lowinstream_getc(FAR struct lib_instream_s *this) -{ - int ret; - - DEBUGASSERT(this); - - /* Get the next character from the incoming stream */ - - ret = up_getc(ch) - if (ret != EOF) - { - this->nget++; - } - - return ret; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_lowinstream - * - * Description: - * Initializes a stream for use with low-level, architecture-specific I/O. - * - * Input parameters: - * lowoutstream - User allocated, uninitialized instance of struct - * lib_lowoutstream_s to be initialized. - * - * Returned Value: - * None (User allocated instance initialized). - * - ****************************************************************************/ - -void lib_lowinstream(FAR struct lib_instream_s *stream) -{ - stream->get = lowinstream_getc; - stream->nget = 0; -} - -#endif /* CONFIG_ARCH_LOWGETC */ diff --git a/nuttx/libc/stdio/lib_lowoutstream.c b/nuttx/libc/stdio/lib_lowoutstream.c deleted file mode 100644 index f600bc614a..0000000000 --- a/nuttx/libc/stdio/lib_lowoutstream.c +++ /dev/null @@ -1,97 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_lowoutstream.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#ifdef CONFIG_ARCH_LOWPUTC - -#include -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lowoutstream_putc - ****************************************************************************/ - -static void lowoutstream_putc(FAR struct lib_outstream_s *this, int ch) -{ - DEBUGASSERT(this); - - if (up_putc(ch) != EOF) - { - this->nput++; - } -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_lowoutstream - * - * Description: - * Initializes a stream for use with low-level, architecture-specific I/O. - * - * Input parameters: - * lowoutstream - User allocated, uninitialized instance of struct - * lib_lowoutstream_s to be initialized. - * - * Returned Value: - * None (User allocated instance initialized). - * - ****************************************************************************/ - -void lib_lowoutstream(FAR struct lib_outstream_s *stream) -{ - stream->put = lowoutstream_putc; -#ifdef CONFIG_STDIO_LINEBUFFER - stream->flush = lib_noflush; -#endif - stream->nput = 0; -} - -#endif /* CONFIG_ARCH_LOWPUTC */ diff --git a/nuttx/libc/stdio/lib_lowprintf.c b/nuttx/libc/stdio/lib_lowprintf.c deleted file mode 100644 index f7d4ffe2fe..0000000000 --- a/nuttx/libc/stdio/lib_lowprintf.c +++ /dev/null @@ -1,128 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_lowprintf.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include -#include "lib_internal.h" - -/* This interface can only be used from within the kernel */ - -#if !defined(CONFIG_NUTTX_KERNEL) || defined(__KERNEL__) - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_lowvprintf - ****************************************************************************/ - -#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_SYSLOG) - -int lib_lowvprintf(const char *fmt, va_list ap) -{ - struct lib_outstream_s stream; - - /* Wrap the stdout in a stream object and let lib_vsprintf do the work. */ - -#ifdef CONFIG_SYSLOG - lib_syslogstream((FAR struct lib_outstream_s *)&stream); -#else - lib_lowoutstream((FAR struct lib_outstream_s *)&stream); -#endif - return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); -} - -/**************************************************************************** - * Name: lib_lowprintf - ****************************************************************************/ - -int lib_lowprintf(const char *fmt, ...) -{ - va_list ap; - int ret; - -#ifdef CONFIG_DEBUG_ENABLE - ret = 0; - if (g_dbgenable) -#endif - { - va_start(ap, fmt); - ret = lib_lowvprintf(fmt, ap); - va_end(ap); - } - - return ret; -} - -#endif /* CONFIG_ARCH_LOWPUTC || CONFIG_SYSLOG */ -#endif /* __KERNEL__ */ diff --git a/nuttx/libc/stdio/lib_meminstream.c b/nuttx/libc/stdio/lib_meminstream.c deleted file mode 100644 index 2a30d956d6..0000000000 --- a/nuttx/libc/stdio/lib_meminstream.c +++ /dev/null @@ -1,104 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_meminstream.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: meminstream_getc - ****************************************************************************/ - -static int meminstream_getc(FAR struct lib_instream_s *this) -{ - FAR struct lib_meminstream_s *mthis = (FAR struct lib_meminstream_s *)this; - int ret; - - DEBUGASSERT(this); - - /* Get the next character (if any) from the buffer */ - - if (this->nget < mthis->buflen) - { - ret = mthis->buffer[this->nget]; - this->nget++; - } - else - { - ret = EOF; - } - - return ret; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_meminstream - * - * Description: - * Initializes a stream for use with a fixed-size memory buffer. - * - * Input parameters: - * meminstream - User allocated, uninitialized instance of struct - * lib_meminstream_s to be initialized. - * bufstart - Address of the beginning of the fixed-size memory buffer - * buflen - Size of the fixed-sized memory buffer in bytes - * - * Returned Value: - * None (meminstream initialized). - * - ****************************************************************************/ - -void lib_meminstream(FAR struct lib_meminstream_s *meminstream, - FAR const char *bufstart, int buflen) -{ - meminstream->public.get = meminstream_getc; - meminstream->public.nget = 0; /* Will be buffer index */ - meminstream->buffer = bufstart; /* Start of buffer */ - meminstream->buflen = buflen; /* Length of the buffer */ -} - - diff --git a/nuttx/libc/stdio/lib_memoutstream.c b/nuttx/libc/stdio/lib_memoutstream.c deleted file mode 100644 index efd527cbc5..0000000000 --- a/nuttx/libc/stdio/lib_memoutstream.c +++ /dev/null @@ -1,105 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_memoutstream.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: memoutstream_putc - ****************************************************************************/ - -static void memoutstream_putc(FAR struct lib_outstream_s *this, int ch) -{ - FAR struct lib_memoutstream_s *mthis = (FAR struct lib_memoutstream_s *)this; - - DEBUGASSERT(this); - - /* If this will not overrun the buffer, then write the character to the - * buffer. Not that buflen was pre-decremented when the stream was - * created so it is okay to write past the end of the buflen by one. - */ - - if (this->nput < mthis->buflen) - { - mthis->buffer[this->nput] = ch; - this->nput++; - mthis->buffer[this->nput] = '\0'; - } -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_memoutstream - * - * Description: - * Initializes a stream for use with a fixed-size memory buffer. - * - * Input parameters: - * memoutstream - User allocated, uninitialized instance of struct - * lib_memoutstream_s to be initialized. - * bufstart - Address of the beginning of the fixed-size memory buffer - * buflen - Size of the fixed-sized memory buffer in bytes - * - * Returned Value: - * None (memoutstream initialized). - * - ****************************************************************************/ - -void lib_memoutstream(FAR struct lib_memoutstream_s *memoutstream, - FAR char *bufstart, int buflen) -{ - memoutstream->public.put = memoutstream_putc; -#ifdef CONFIG_STDIO_LINEBUFFER - memoutstream->public.flush = lib_noflush; -#endif - memoutstream->public.nput = 0; /* Will be buffer index */ - memoutstream->buffer = bufstart; /* Start of buffer */ - memoutstream->buflen = buflen - 1; /* Save space for null terminator */ - memoutstream->buffer[0] = '\0'; /* Start with an empty string */ -} - - diff --git a/nuttx/libc/stdio/lib_nullinstream.c b/nuttx/libc/stdio/lib_nullinstream.c deleted file mode 100644 index aeb0af3790..0000000000 --- a/nuttx/libc/stdio/lib_nullinstream.c +++ /dev/null @@ -1,79 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_nullinstream.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -static int nullinstream_getc(FAR struct lib_instream_s *this) -{ - return EOF; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_nullinstream - * - * Description: - * Initializes a NULL stream. The initialized stream will will return only - * EOF. - * - * Input parameters: - * nullinstream - User allocated, uninitialized instance of struct - * lib_instream_s to be initialized. - * - * Returned Value: - * None (User allocated instance initialized). - * - ****************************************************************************/ - -void lib_nullinstream(FAR struct lib_instream_s *nullinstream) -{ - nullinstream->get = nullinstream_getc; - nullinstream->nget = 0; -} - diff --git a/nuttx/libc/stdio/lib_nulloutstream.c b/nuttx/libc/stdio/lib_nulloutstream.c deleted file mode 100644 index 5742953448..0000000000 --- a/nuttx/libc/stdio/lib_nulloutstream.c +++ /dev/null @@ -1,84 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_nulloutstream.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -static void nulloutstream_putc(FAR struct lib_outstream_s *this, int ch) -{ - DEBUGASSERT(this); - this->nput++; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_nulloutstream - * - * Description: - * Initializes a NULL streams. The initialized stream will write all data - * to the bit-bucket. - * - * Input parameters: - * nulloutstream - User allocated, uninitialized instance of struct - * lib_outstream_s to be initialized. - * - * Returned Value: - * None (User allocated instance initialized). - * - ****************************************************************************/ - -void lib_nulloutstream(FAR struct lib_outstream_s *nulloutstream) -{ - nulloutstream->put = nulloutstream_putc; -#ifdef CONFIG_STDIO_LINEBUFFER - nulloutstream->flush = lib_noflush; -#endif - nulloutstream->nput = 0; -} - diff --git a/nuttx/libc/stdio/lib_perror.c b/nuttx/libc/stdio/lib_perror.c deleted file mode 100644 index 1818983292..0000000000 --- a/nuttx/libc/stdio/lib_perror.c +++ /dev/null @@ -1,99 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_perror.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* POSIX requires that perror provide its output on stderr. This option may - * be defined, however, to provide perror output that is serialized with - * other stdout messages. - */ - -#ifdef CONFIG_LIBC_PERROR_STDOUT -# define PERROR_STREAM stdout -#else -# define PERROR_STREAM stderr -#endif - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: perror - ****************************************************************************/ - -void perror(FAR const char *s) -{ - - /* If strerror() is not enabled, then just print the error number */ - -#ifdef CONFIG_LIBC_STRERROR - (void)fprintf(PERROR_STREAM, "%s: %s\n", s, strerror(errno)); -#else - (void)fprintf(PERROR_STREAM, "%s: Error %d\n", s, errno); -#endif -} - diff --git a/nuttx/libc/stdio/lib_printf.c b/nuttx/libc/stdio/lib_printf.c deleted file mode 100644 index 0e90c7ca5a..0000000000 --- a/nuttx/libc/stdio/lib_printf.c +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_printf.c - * - * Copyright (C) 2007-2008, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/************************************************************************** - * Global Constant Data - **************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/************************************************************************** - * Private Constant Data - **************************************************************************/ - -/**************************************************************************** - * Private Variables - **************************************************************************/ - -/**************************************************************************** - * Global Functions - **************************************************************************/ - -/**************************************************************************** - * Name: printf - **************************************************************************/ - -int printf(const char *fmt, ...) -{ - va_list ap; - int ret; - - va_start(ap, fmt); -#if CONFIG_NFILE_STREAMS > 0 - ret = vfprintf(stdout, fmt, ap); -#elif CONFIG_NFILE_DESCRIPTORS > 0 - ret = lib_rawvprintf(fmt, ap); -#elif defined(CONFIG_ARCH_LOWPUTC) - ret = lib_lowvprintf(fmt, ap); -#else -# ifdef CONFIG_CPP_HAVE_WARNING -# warning "printf has no data sink" -# endif - ret = 0; -#endif - va_end(ap); - - return ret; -} - diff --git a/nuttx/libc/stdio/lib_puts.c b/nuttx/libc/stdio/lib_puts.c deleted file mode 100644 index 53eda7081e..0000000000 --- a/nuttx/libc/stdio/lib_puts.c +++ /dev/null @@ -1,130 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_puts.c - * - * Copyright (C) 2007, 2008, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: puts - * - * Description: - * puts() writes the string s and a trailing newline to stdout. - * - ****************************************************************************/ - -int puts(FAR const char *s) -{ - FILE *stream = stdout; - int nwritten; - int nput = EOF; - int ret; - - /* Write the string (the next two steps must be atomic) */ - - lib_take_semaphore(stream); - - /* Write the string without its trailing '\0' */ - - nwritten = fputs(s, stream); - if (nwritten > 0) - { - /* Followed by a newline */ - - char newline = '\n'; - ret = lib_fwrite(&newline, 1, stream); - if (ret > 0) - { - nput = nwritten + 1; - - /* Flush the buffer after the newline is output. */ - -#ifdef CONFIG_STDIO_LINEBUFFER - ret = lib_fflush(stream, true); - if (ret < 0) - { - nput = EOF; - } -#endif - } - } - - lib_give_semaphore(stdout); - return nput; -} - diff --git a/nuttx/libc/stdio/lib_rawinstream.c b/nuttx/libc/stdio/lib_rawinstream.c deleted file mode 100644 index 55456769eb..0000000000 --- a/nuttx/libc/stdio/lib_rawinstream.c +++ /dev/null @@ -1,107 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_rawinstream.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: rawinstream_getc - ****************************************************************************/ - -static int rawinstream_getc(FAR struct lib_instream_s *this) -{ - FAR struct lib_rawinstream_s *rthis = (FAR struct lib_rawinstream_s *)this; - int nwritten; - char ch; - - DEBUGASSERT(this && rthis->fd >= 0); - - /* Attempt to read one character */ - - nwritten = read(rthis->fd, &ch, 1); - if (nwritten == 1) - { - this->nget++; - return ch; - } - - /* Return EOF on any failure to read from the incoming byte stream. The - * only expected error is EINTR meaning that the read was interrupted - * by a signal. A Zero return value would indicated an end-of-file - * confition. - */ - - return EOF; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_rawinstream - * - * Description: - * Initializes a stream for use with a file descriptor. - * - * Input parameters: - * rawinstream - User allocated, uninitialized instance of struct - * lib_rawinstream_s to be initialized. - * fd - User provided file/socket descriptor (must have been opened - * for the correct access). - * - * Returned Value: - * None (User allocated instance initialized). - * - ****************************************************************************/ - -void lib_rawinstream(FAR struct lib_rawinstream_s *rawinstream, int fd) -{ - rawinstream->public.get = rawinstream_getc; - rawinstream->public.nget = 0; - rawinstream->fd = fd; -} - diff --git a/nuttx/libc/stdio/lib_rawoutstream.c b/nuttx/libc/stdio/lib_rawoutstream.c deleted file mode 100644 index e1fe371346..0000000000 --- a/nuttx/libc/stdio/lib_rawoutstream.c +++ /dev/null @@ -1,115 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_rawoutstream.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: rawoutstream_putc - ****************************************************************************/ - -static void rawoutstream_putc(FAR struct lib_outstream_s *this, int ch) -{ - FAR struct lib_rawoutstream_s *rthis = (FAR struct lib_rawoutstream_s *)this; - int nwritten; - char buffer = ch; - - DEBUGASSERT(this && rthis->fd >= 0); - - /* Loop until the character is successfully transferred or until an - * irrecoverable error occurs. - */ - - do - { - nwritten = write(rthis->fd, &buffer, 1); - if (nwritten == 1) - { - this->nput++; - return; - } - - /* The only expected error is EINTR, meaning that the write operation - * was awakened by a signal. Zero would not be a valid return value - * from write(). - */ - - DEBUGASSERT(nwritten < 0); - } - while (get_errno() == EINTR); -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_rawoutstream - * - * Description: - * Initializes a stream for use with a file descriptor. - * - * Input parameters: - * rawoutstream - User allocated, uninitialized instance of struct - * lib_rawoutstream_s to be initialized. - * fd - User provided file/socket descriptor (must have been opened - * for write access). - * - * Returned Value: - * None (User allocated instance initialized). - * - ****************************************************************************/ - -void lib_rawoutstream(FAR struct lib_rawoutstream_s *rawoutstream, int fd) -{ - rawoutstream->public.put = rawoutstream_putc; -#ifdef CONFIG_STDIO_LINEBUFFER - rawoutstream->public.flush = lib_noflush; -#endif - rawoutstream->public.nput = 0; - rawoutstream->fd = fd; -} - diff --git a/nuttx/libc/stdio/lib_rawprintf.c b/nuttx/libc/stdio/lib_rawprintf.c deleted file mode 100644 index 98bbbea053..0000000000 --- a/nuttx/libc/stdio/lib_rawprintf.c +++ /dev/null @@ -1,151 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_rawprintf.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Some output destinations are only available from within the kernel */ - -#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__) -# undef CONFIG_SYSLOG -# undef CONFIG_ARCH_LOWPUTC -#endif - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_rawvprintf - ****************************************************************************/ - -int lib_rawvprintf(const char *fmt, va_list ap) -{ -#if defined(CONFIG_SYSLOG) - - struct lib_outstream_s stream; - - /* Wrap the low-level output in a stream object and let lib_vsprintf - * do the work. - */ - - lib_syslogstream((FAR struct lib_outstream_s *)&stream); - return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); - -#elif CONFIG_NFILE_DESCRIPTORS > 0 - - struct lib_rawoutstream_s rawoutstream; - - /* Wrap the stdout in a stream object and let lib_vsprintf - * do the work. - */ - - lib_rawoutstream(&rawoutstream, 1); - return lib_vsprintf(&rawoutstream.public, fmt, ap); - -#elif defined(CONFIG_ARCH_LOWPUTC) - - struct lib_outstream_s stream; - - /* Wrap the low-level output in a stream object and let lib_vsprintf - * do the work. - */ - - lib_lowoutstream((FAR struct lib_outstream_s *)&stream); - return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); - -#else - return 0; -#endif -} - -/**************************************************************************** - * Name: lib_rawprintf - ****************************************************************************/ - -int lib_rawprintf(const char *fmt, ...) -{ - va_list ap; - int ret; - -#ifdef CONFIG_DEBUG_ENABLE - ret = 0; - if (g_dbgenable) -#endif - { - va_start(ap, fmt); - ret = lib_rawvprintf(fmt, ap); - va_end(ap); - } - - return ret; -} diff --git a/nuttx/libc/stdio/lib_rdflush.c b/nuttx/libc/stdio/lib_rdflush.c deleted file mode 100644 index c6136792bb..0000000000 --- a/nuttx/libc/stdio/lib_rdflush.c +++ /dev/null @@ -1,144 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_rdflush.c - * - * Copyright (C) 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_rdflush - * - * Description: - * Flush read data from the I/O buffer and adjust the file pointer to - * account for the unread data - * - ****************************************************************************/ - -#if CONFIG_STDIO_BUFFER_SIZE > 0 -int lib_rdflush(FAR FILE *stream) -{ - if (!stream) - { - set_errno(EBADF); - return ERROR; - } - - /* Get exclusive access to the stream */ - - lib_take_semaphore(stream); - - /* If the buffer is currently being used for read access, then discard all - * of the read-ahead data. We do not support concurrent buffered read/write - * access. - */ - - if (stream->fs_bufread != stream->fs_bufstart) - { - /* Now adjust the stream pointer to account for the read-ahead data that - * was not actually read by the user. - */ - -#if CONFIG_NUNGET_CHARS > 0 - off_t rdoffset = stream->fs_bufread - stream->fs_bufpos + stream->fs_nungotten; -#else - off_t rdoffset = stream->fs_bufread - stream->fs_bufpos; -#endif - /* Mark the buffer as empty (do this before calling fseek() because fseek() - * also calls this function). - */ - - stream->fs_bufpos = stream->fs_bufread = stream->fs_bufstart; -#if CONFIG_NUNGET_CHARS > 0 - stream->fs_nungotten = 0; -#endif - /* Then seek to the position corresponding to the last data read by the user */ - - if (fseek(stream, -rdoffset, SEEK_CUR) < 0) - { - lib_give_semaphore(stream); - return ERROR; - } - } - - lib_give_semaphore(stream); - return OK; -} -#endif /* CONFIG_STDIO_BUFFER_SIZE */ - diff --git a/nuttx/libc/stdio/lib_snprintf.c b/nuttx/libc/stdio/lib_snprintf.c deleted file mode 100644 index a4ba0dbb30..0000000000 --- a/nuttx/libc/stdio/lib_snprintf.c +++ /dev/null @@ -1,99 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_snprintf.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * sprintf - ****************************************************************************/ - -int snprintf(FAR char *buf, size_t size, const char *format, ...) -{ - struct lib_memoutstream_s memoutstream; - va_list ap; - int n; - - /* Initialize a memory stream to write to the buffer */ - - lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, size); - - /* Then let lib_vsprintf do the real work */ - - va_start(ap, format); - n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, format, ap); - va_end(ap); - return n; -} diff --git a/nuttx/libc/stdio/lib_sprintf.c b/nuttx/libc/stdio/lib_sprintf.c deleted file mode 100644 index deb0669a3b..0000000000 --- a/nuttx/libc/stdio/lib_sprintf.c +++ /dev/null @@ -1,95 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_sprintf.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * sprintf - ****************************************************************************/ - -int sprintf (FAR char *buf, const char *fmt, ...) -{ - struct lib_memoutstream_s memoutstream; - va_list ap; - int n; - - /* Initialize a memory stream to write to the buffer */ - - lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, LIB_BUFLEN_UNKNOWN); - - /* Then let lib_vsprintf do the real work */ - - va_start(ap, fmt); - n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, fmt, ap); - va_end(ap); - return n; -} diff --git a/nuttx/libc/stdio/lib_sscanf.c b/nuttx/libc/stdio/lib_sscanf.c deleted file mode 100644 index 77a6cf212f..0000000000 --- a/nuttx/libc/stdio/lib_sscanf.c +++ /dev/null @@ -1,507 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_sscanf.c - * - * Copyright (C) 2007, 2008, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -#define MAXLN 128 - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -int vsscanf(char *buf, const char *fmt, va_list ap); - -/************************************************************************** - * Global Constant Data - **************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/************************************************************************** - * Private Constant Data - **************************************************************************/ - -static const char spaces[] = " \t\n\r\f\v"; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: findwidth - * - * Description: - * Try to figure out the width of the input data. - * - ****************************************************************************/ - -static int findwidth(FAR const char *buf, FAR const char *fmt) -{ - FAR const char *next = fmt + 1; - - /* No... is there a space after the format? Or does the format string end - * here? - */ - - if (isspace(*next) || *next == 0) - { - /* Use the input up until the first white space is encountered. */ - - return strcspn(buf, spaces); - } - - /* No.. Another possibility is the the format character is followed by - * some recognizable delimiting value. - */ - - if (*next != '%') - { - /* If so we will say that the string ends there if we can find that - * delimiter in the input string. - */ - - FAR const char *ptr = strchr(buf, *next); - if (ptr) - { - return (int)(ptr - buf); - } - } - - /* No... the format has not delimiter and is back-to-back with the next - * formats (or no is following by a delimiter that does not exist in the - * input string). At this point we just bail and Use the input up until - * the first white space is encountered. - * - * NOTE: This means that values from the following format may be - * concatenated with the first. This is a bug. We have no generic way of - * determining the width of the data if there is no fieldwith, no space - * separating the input, and no usable delimiter character. - */ - - return strcspn(buf, spaces); -} - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Function: sscanf - * - * Description: - * ANSI standard sscanf implementation. - * - ****************************************************************************/ - -int sscanf(FAR const char *buf, FAR const char *fmt, ...) -{ - va_list ap; - int count; - - va_start(ap, fmt); - count = vsscanf((FAR char*)buf, fmt, ap); - va_end(ap); - return count; -} - -/**************************************************************************** - * Function: vsscanf - * - * Description: - * ANSI standard vsscanf implementation. - * - ****************************************************************************/ - -int vsscanf(FAR char *buf, FAR const char *fmt, va_list ap) -{ - FAR char *bufstart; - FAR char *tv; - FAR const char *tc; - bool lflag; - bool noassign; - int count; - int width; - int base = 10; - char tmp[MAXLN]; - - lvdbg("vsscanf: buf=\"%s\" fmt=\"%s\"\n", buf, fmt); - - /* Remember the start of the input buffer. We will need this for %n - * calculations. - */ - - bufstart = buf; - - /* Parse the format, extracting values from the input buffer as needed */ - - count = 0; - width = 0; - noassign = false; - lflag = false; - - while (*fmt && *buf) - { - /* Skip over white space */ - - while (isspace(*fmt)) - { - fmt++; - } - - /* Check for a conversion specifier */ - - if (*fmt == '%') - { - lvdbg("vsscanf: Specifier found\n"); - - /* Check for qualifiers on the conversion specifier */ - fmt++; - for (; *fmt; fmt++) - { - lvdbg("vsscanf: Processing %c\n", *fmt); - - if (strchr("dibouxcsefgn%", *fmt)) - { - break; - } - - if (*fmt == '*') - { - noassign = true; - } - else if (*fmt == 'l' || *fmt == 'L') - { - /* NOTE: Missing check for long long ('ll') */ - - lflag = true; - } - else if (*fmt >= '1' && *fmt <= '9') - { - for (tc = fmt; isdigit(*fmt); fmt++); - strncpy(tmp, tc, fmt - tc); - tmp[fmt - tc] = '\0'; - width = atoi(tmp); - fmt--; - } - } - - /* Process %s: String conversion */ - - if (*fmt == 's') - { - lvdbg("vsscanf: Performing string conversion\n"); - - while (isspace(*buf)) - { - buf++; - } - - /* Was a fieldwidth specified? */ - - if (!width) - { - /* No... Guess a field width using some heuristics */ - - width = findwidth(buf, fmt); - } - - if (!noassign) - { - tv = va_arg(ap, char*); - strncpy(tv, buf, width); - tv[width] = '\0'; - } - - buf += width; - } - - /* Process %c: Character conversion */ - - else if (*fmt == 'c') - { - lvdbg("vsscanf: Performing character conversion\n"); - - /* Was a fieldwidth specified? */ - - if (!width) - { - /* No, then width is this one single character */ - - width = 1; - } - - if (!noassign) - { - tv = va_arg(ap, char*); - strncpy(tv, buf, width); - tv[width] = '\0'; - } - - buf += width; - } - - /* Process %d, %o, %b, %x, %u: Various integer conversions */ - - else if (strchr("dobxu", *fmt)) - { - lvdbg("vsscanf: Performing integer conversion\n"); - - /* Skip over any white space before the integer string */ - - while (isspace(*buf)) - { - buf++; - } - - /* The base of the integer conversion depends on the specific - * conversion specification. - */ - - if (*fmt == 'd' || *fmt == 'u') - { - base = 10; - } - else if (*fmt == 'x') - { - base = 16; - } - else if (*fmt == 'o') - { - base = 8; - } - else if (*fmt == 'b') - { - base = 2; - } - - /* Was a fieldwidth specified? */ - - if (!width) - { - /* No... Guess a field width using some heuristics */ - - width = findwidth(buf, fmt); - } - - /* Copy the numeric string into a temporary working buffer. */ - - strncpy(tmp, buf, width); - tmp[width] = '\0'; - - lvdbg("vsscanf: tmp[]=\"%s\"\n", tmp); - - /* Perform the integer conversion */ - - buf += width; - if (!noassign) - { -#ifdef SDCC - char *endptr; - long tmplong = strtol(tmp, &endptr, base); -#else - long tmplong = strtol(tmp, NULL, base); -#endif - if (lflag) - { - long *plong = va_arg(ap, long*); - lvdbg("vsscanf: Return %ld to 0x%p\n", tmplong, plong); - *plong = tmplong; - } - else - { - int *pint = va_arg(ap, int*); - lvdbg("vsscanf: Return %ld to 0x%p\n", tmplong, pint); - *pint = (int)tmplong; - } - } - } - - /* Process %f: Floating point conversion */ - - else if (*fmt == 'f') - { -#ifndef CONFIG_LIBC_FLOATINGPOINT - /* No floating point conversions */ - - void *pv = va_arg(ap, void*); - - lvdbg("vsscanf: Return 0.0 to %p\n", pv); - *((double_t*)pv) = 0.0; -#else - lvdbg("vsscanf: Performing floating point conversion\n"); - - /* Skip over any white space before the real string */ - - while (isspace(*buf)) - { - buf++; - } - - /* Was a fieldwidth specified? */ - - if (!width) - { - /* No... Guess a field width using some heuristics */ - - width = findwidth(buf, fmt); - } - - /* Copy the real string into a temporary working buffer. */ - - strncpy(tmp, buf, width); - tmp[width] = '\0'; - buf += width; - - lvdbg("vsscanf: tmp[]=\"%s\"\n", tmp); - - /* Perform the floating point conversion */ - - if (!noassign) - { - /* strtod always returns a double */ -#ifdef SDCC - char *endptr; - double_t dvalue = strtod(tmp,&endptr); -#else - double_t dvalue = strtod(tmp, NULL); -#endif - void *pv = va_arg(ap, void*); - - lvdbg("vsscanf: Return %f to %p\n", dvalue, pv); - - /* But we have to check whether we need to return a - * float or a double. - */ - -#ifdef CONFIG_HAVE_DOUBLE - if (lflag) - { - *((double_t*)pv) = dvalue; - } - else -#endif - { - *((float*)pv) = (float)dvalue; - } - } -#endif - } - - /* Process %n: Character count */ - - else if (*fmt == 'n') - { - lvdbg("vsscanf: Performing character count\n"); - - if (!noassign) - { - size_t nchars = (size_t)(buf - bufstart); - - if (lflag) - { - long *plong = va_arg(ap, long*); - *plong = (long)nchars; - } - else - { - int *pint = va_arg(ap, int*); - *pint = (int)nchars; - } - } - } - - /* Note %n does not count as a conversion */ - - if (!noassign && *fmt != 'n') - { - count++; - } - - width = 0; - noassign = false; - lflag = false; - - fmt++; - } - - /* Its is not a conversion specifier */ - - else - { - while (isspace(*buf)) - { - buf++; - } - - if (*fmt != *buf) - { - break; - } - else - { - fmt++; - buf++; - } - } - } - - return count; -} diff --git a/nuttx/libc/stdio/lib_stdinstream.c b/nuttx/libc/stdio/lib_stdinstream.c deleted file mode 100644 index 261b266346..0000000000 --- a/nuttx/libc/stdio/lib_stdinstream.c +++ /dev/null @@ -1,99 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_stdinstream.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: stdinstream_getc - ****************************************************************************/ - -static int stdinstream_getc(FAR struct lib_instream_s *this) -{ - FAR struct lib_stdinstream_s *sthis = (FAR struct lib_stdinstream_s *)this; - int ret; - - DEBUGASSERT(this); - - /* Get the next character from the incoming stream */ - - ret = getc(sthis->stream); - if (ret != EOF) - { - this->nget++; - } - - return ret; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_stdinstream - * - * Description: - * Initializes a stream for use with a FILE instance. - * - * Input parameters: - * stdinstream - User allocated, uninitialized instance of struct - * lib_stdinstream_s to be initialized. - * stream - User provided stream instance (must have been opened for - * read access). - * - * Returned Value: - * None (User allocated instance initialized). - * - ****************************************************************************/ - -void lib_stdinstream(FAR struct lib_stdinstream_s *stdinstream, - FAR FILE *stream) -{ - stdinstream->public.get = stdinstream_getc; - stdinstream->public.nget = 0; - stdinstream->stream = stream; -} - - diff --git a/nuttx/libc/stdio/lib_stdoutstream.c b/nuttx/libc/stdio/lib_stdoutstream.c deleted file mode 100644 index dfe67271f1..0000000000 --- a/nuttx/libc/stdio/lib_stdoutstream.c +++ /dev/null @@ -1,147 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_stdoutstream.c - * - * Copyright (C) 2007-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: stdoutstream_putc - ****************************************************************************/ - -static void stdoutstream_putc(FAR struct lib_outstream_s *this, int ch) -{ - FAR struct lib_stdoutstream_s *sthis = (FAR struct lib_stdoutstream_s *)this; - int result; - - DEBUGASSERT(this && sthis->stream); - - /* Loop until the character is successfully transferred or an irrecoverable - * error occurs. - */ - - do - { - result = fputc(ch, sthis->stream); - if (result != EOF) - { - this->nput++; - return; - } - - /* EINTR (meaning that fputc was interrupted by a signal) is the only - * recoverable error. - */ - } - while (get_errno() == EINTR); -} - -/**************************************************************************** - * Name: stdoutstream_flush - ****************************************************************************/ - -#if defined(CONFIG_STDIO_LINEBUFFER) && CONFIG_STDIO_BUFFER_SIZE > 0 -int stdoutstream_flush(FAR struct lib_outstream_s *this) -{ - FAR struct lib_stdoutstream_s *sthis = (FAR struct lib_stdoutstream_s *)this; - return lib_fflush(sthis->stream, true); -} -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_stdoutstream - * - * Description: - * Initializes a stream for use with a FILE instance. - * - * Input parameters: - * stdoutstream - User allocated, uninitialized instance of struct - * lib_stdoutstream_s to be initialized. - * stream - User provided stream instance (must have been opened for - * write access). - * - * Returned Value: - * None (User allocated instance initialized). - * - ****************************************************************************/ - -void lib_stdoutstream(FAR struct lib_stdoutstream_s *stdoutstream, - FAR FILE *stream) -{ - /* Select the put operation */ - - stdoutstream->public.put = stdoutstream_putc; - - /* Select the correct flush operation. This flush is only called when - * a newline is encountered in the output stream. However, we do not - * want to support this line buffering behavior if the stream was - * opened in binary mode. In binary mode, the newline has no special - * meaning. - */ - -#ifdef CONFIG_STDIO_LINEBUFFER -#if CONFIG_STDIO_BUFFER_SIZE > 0 - if ((stream->fs_oflags & O_BINARY) == 0) - { - stdoutstream->public.flush = stdoutstream_flush; - } - else -#endif - { - stdoutstream->public.flush = lib_noflush; - } -#endif - - /* Set the number of bytes put to zero and remember the stream */ - - stdoutstream->public.nput = 0; - stdoutstream->stream = stream; -} - - diff --git a/nuttx/libc/stdio/lib_syslogstream.c b/nuttx/libc/stdio/lib_syslogstream.c deleted file mode 100644 index 5529c5de8c..0000000000 --- a/nuttx/libc/stdio/lib_syslogstream.c +++ /dev/null @@ -1,122 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_syslogstream.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include - -#include "lib_internal.h" - -#ifdef CONFIG_SYSLOG - -/**************************************************************************** - * Pre-processor definition - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: syslogstream_putc - ****************************************************************************/ - -static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) -{ - int ret; - - /* Try writing until the write was successful or until an irrecoverable - * error occurs. - */ - - do - { - /* Write the character to the supported logging device */ - - ret = syslog_putc(ch); - if (ret == OK) - { - this->nput++; - return; - } - - /* On failure syslog_putc will return a negated errno value. The - * errno variable will not be set. The special value -EINTR means that - * syslog_putc() was awakened by a signal. This is not a real error and - * must be ignored in this context. - */ - } - while (ret == -EINTR); -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_syslogstream - * - * Description: - * Initializes a stream for use with the configured syslog interface. - * - * Input parameters: - * lowoutstream - User allocated, uninitialized instance of struct - * lib_lowoutstream_s to be initialized. - * - * Returned Value: - * None (User allocated instance initialized). - * - ****************************************************************************/ - -void lib_syslogstream(FAR struct lib_outstream_s *stream) -{ - stream->put = syslogstream_putc; -#ifdef CONFIG_STDIO_LINEBUFFER - stream->flush = lib_noflush; -#endif - stream->nput = 0; -} - -#endif /* CONFIG_SYSLOG */ - - diff --git a/nuttx/libc/stdio/lib_ungetc.c b/nuttx/libc/stdio/lib_ungetc.c deleted file mode 100644 index 178aeddd10..0000000000 --- a/nuttx/libc/stdio/lib_ungetc.c +++ /dev/null @@ -1,121 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_ungetc.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include -#include -#include -#include "lib_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/************************************************************************** - * Global Constant Data - **************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/************************************************************************** - * Private Constant Data - **************************************************************************/ - -/**************************************************************************** - * Private Variables - **************************************************************************/ - -/**************************************************************************** - * Public Functions - **************************************************************************/ - -/**************************************************************************** - * Name: ungetc - **************************************************************************/ - -int ungetc(int c, FAR FILE *stream) -{ -#if CONFIG_NUNGET_CHARS > 0 - int nungotten; -#endif - - /* Stream must be open for read access */ - - if ((stream && stream->fs_filedes < 0) || - ((stream->fs_oflags & O_RDOK) == 0)) - { - set_errno(EBADF); - return EOF; - } - -#if CONFIG_NUNGET_CHARS > 0 - nungotten = stream->fs_nungotten; - if (stream->fs_nungotten < CONFIG_NUNGET_CHARS) - { - stream->fs_ungotten[nungotten] = c; - stream->fs_nungotten = nungotten + 1; - return c; - } - else -#endif - { - set_errno(ENOMEM); - return EOF; - } -} - diff --git a/nuttx/libc/stdio/lib_vfprintf.c b/nuttx/libc/stdio/lib_vfprintf.c deleted file mode 100644 index cd117ddc30..0000000000 --- a/nuttx/libc/stdio/lib_vfprintf.c +++ /dev/null @@ -1,102 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_vfprintf.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -int vfprintf(FAR FILE *stream, FAR const char *fmt, va_list ap) -{ - struct lib_stdoutstream_s stdoutstream; - int n = ERROR; - - if (stream) - { - /* Wrap the stream in a stream object and let lib_vsprintf - * do the work. - */ - - lib_stdoutstream(&stdoutstream, stream); - - /* Hold the stream semaphore throughout the lib_vsprintf - * call so that this thread can get its entire message out - * before being pre-empted by the next thread. - */ - - lib_take_semaphore(stream); - n = lib_vsprintf(&stdoutstream.public, fmt, ap); - lib_give_semaphore(stream); - } - return n; -} diff --git a/nuttx/libc/stdio/lib_vprintf.c b/nuttx/libc/stdio/lib_vprintf.c deleted file mode 100644 index 6ddfe2b246..0000000000 --- a/nuttx/libc/stdio/lib_vprintf.c +++ /dev/null @@ -1,92 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_vprintf.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/************************************************************************** - * Global Constant Data - **************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/************************************************************************** - * Private Constant Data - **************************************************************************/ - -/**************************************************************************** - * Private Variables - **************************************************************************/ - -/**************************************************************************** - * Public Functions - **************************************************************************/ - -/**************************************************************************** - * Name: vprintf - **************************************************************************/ - -int vprintf(FAR const char *fmt, va_list ap) -{ - /* vfprintf into stdout */ - - return vfprintf(stdout, fmt, ap); -} - diff --git a/nuttx/libc/stdio/lib_vsnprintf.c b/nuttx/libc/stdio/lib_vsnprintf.c deleted file mode 100644 index f7fd02e427..0000000000 --- a/nuttx/libc/stdio/lib_vsnprintf.c +++ /dev/null @@ -1,96 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_vsnprintf.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: vsnprintf - ****************************************************************************/ - -int vsnprintf(FAR char *buf, size_t size, const char *format, va_list ap) -{ - struct lib_memoutstream_s memoutstream; - int n; - - /* Initialize a memory stream to write to the buffer */ - - lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, buf, size); - - /* Then let lib_vsprintf do the real work */ - - n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, format, ap); - return n; -} diff --git a/nuttx/libc/stdio/lib_vsprintf.c b/nuttx/libc/stdio/lib_vsprintf.c deleted file mode 100644 index b6d80808f9..0000000000 --- a/nuttx/libc/stdio/lib_vsprintf.c +++ /dev/null @@ -1,92 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_vsprintf.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: vsprintf - ****************************************************************************/ - -int vsprintf(FAR char *dest, const char *src, va_list ap) -{ - struct lib_memoutstream_s memoutstream; - - /* Wrap the destination buffer in a stream object and let - * libc/stdio/lib_vsprintf do the work. - */ - - lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, dest, LIB_BUFLEN_UNKNOWN); - return lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, src, ap); -} diff --git a/nuttx/libc/stdio/lib_wrflush.c b/nuttx/libc/stdio/lib_wrflush.c deleted file mode 100644 index 40b8e38c8d..0000000000 --- a/nuttx/libc/stdio/lib_wrflush.c +++ /dev/null @@ -1,134 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_wrflush.c - * - * Copyright (C) 2008-2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_wrflush - * - * Description: - * This is simply a version of fflush that does not report an error if - * the file is not open for writing. - * - ****************************************************************************/ - -int lib_wrflush(FAR FILE *stream) -{ -#if CONFIG_STDIO_BUFFER_SIZE > 0 - /* Verify that we were passed a valid (i.e., non-NULL) stream */ - -#ifdef CONFIG_DEBUG - if (!stream) - { - return -EINVAL; - } -#endif - - /* Verify that the stream is opened for writing... lib_fflush will - * return an error if it is called for a stream that is not opened for - * writing. Check that first so that this function will not fail in - * that case. - */ - - if ((stream->fs_oflags & O_WROK) == 0) - { - /* Report that the success was successful if we attempt to flush a - * read-only stream. - */ - - return OK; - } - - /* Flush the stream. Return success if there is no buffered write data - * -- i.e., that the stream is opened for writing and that all of the - * buffered write data was successfully flushed by lib_fflush(). - */ - - return lib_fflush(stream, true); -#else - /* Verify that we were passed a valid (i.e., non-NULL) stream */ - -#ifdef CONFIG_DEBUG - if (!stream) - { - return -EINVAL; - } -#endif - - return OK; -#endif -} diff --git a/nuttx/libc/stdio/lib_zeroinstream.c b/nuttx/libc/stdio/lib_zeroinstream.c deleted file mode 100644 index a52ecc1d06..0000000000 --- a/nuttx/libc/stdio/lib_zeroinstream.c +++ /dev/null @@ -1,79 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_zeroinstream.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -static int zeroinstream_getc(FAR struct lib_instream_s *this) -{ - this->nget++; - return 0; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_zeroinstream - * - * Description: - * Initializes a NULL stream. The initialized stream will return an - * infinitely long stream of zeroes. - * - * Input parameters: - * zeroinstream - User allocated, uninitialized instance of struct - * lib_instream_s to be initialized. - * - * Returned Value: - * None (User allocated instance initialized). - * - ****************************************************************************/ - -void lib_zeroinstream(FAR struct lib_instream_s *zeroinstream) -{ - zeroinstream->get = zeroinstream_getc; - zeroinstream->nget = 0; -} - diff --git a/nuttx/libc/stdlib/Make.defs b/nuttx/libc/stdlib/Make.defs deleted file mode 100644 index dcc4dab26a..0000000000 --- a/nuttx/libc/stdlib/Make.defs +++ /dev/null @@ -1,44 +0,0 @@ -############################################################################ -# libc/stdlib/Make.defs -# -# 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. -# -############################################################################ - -# Add the stdlib C files to the build - -CSRCS += lib_abs.c lib_abort.c lib_imaxabs.c lib_labs.c lib_llabs.c \ - lib_rand.c lib_qsort.c - -# Add the stdlib directory to the build - -DEPPATH += --dep-path stdlib -VPATH += :stdlib diff --git a/nuttx/libc/stdlib/lib_abort.c b/nuttx/libc/stdlib/lib_abort.c deleted file mode 100644 index 1c7442c7f5..0000000000 --- a/nuttx/libc/stdlib/lib_abort.c +++ /dev/null @@ -1,121 +0,0 @@ -/************************************************************************ - * libc/stdlib/lib_abort.c - * - * Copyright (C) 2007, 2009, 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include -#include - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -/************************************************************************ - * Private Type Declarations - ************************************************************************/ - -/************************************************************************ - * Global Variables - ************************************************************************/ - -/************************************************************************ - * Private Variables - ************************************************************************/ - -/************************************************************************ - * Private Function Prototypes - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: Abort - * - * Description: - * The abort() first unblocks the SIGABRT signal, and then raises that - * signal for the calling process. This results in the abnormal - * termination of the process unless the SIGABRT signal is caught and - * the signal handler does not return. - * - * If the abort() function causes process termination, all open - * streams are closed and flushed. - * - * If the SIGABRT signal is ignored, or caught by a handler that - * returns, the abort() function will still terminate the process. - * It does this by restoring the default disposition for SIGABRT and - * then raising the signal for a second time. - * - * Input parameters: - * None - * - * Returned Value: - * This function does not return, - * - ************************************************************************/ - -void abort(void) -{ - /* NuttX does not support standard signal functionality (like the - * behavior of the SIGABRT signal). So no attempt is made to provide - * a conformant version of abort() at this time. This version does not - * signal the calling thread all. - * - * Note that pthread_exit() is called instead of exit(). That is because - * we do no know if abort was called from a pthread or a normal thread - * (we could find out, of course). If abort() is called from a non-pthread, - * then pthread_exit() should fail and fall back to call exit() anyway. - * - * If exit() is called (either below or via pthread_exit()), then exit() - * will flush and close all open files and terminate the thread. If this - * function was called from a pthread, then pthread_exit() will complete - * any joins, but will not flush or close any streams. - */ - -#ifdef CONFIG_DISABLE_PTHREAD - exit(EXIT_FAILURE); -#else - pthread_exit(NULL); -#endif -} diff --git a/nuttx/libc/stdlib/lib_abs.c b/nuttx/libc/stdlib/lib_abs.c deleted file mode 100644 index a4e4ec6694..0000000000 --- a/nuttx/libc/stdlib/lib_abs.c +++ /dev/null @@ -1,54 +0,0 @@ -/************************************************************************ - * libc/stdlib/lib_abs.c - * - * Copyright (C) 2010-2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -/************************************************************************ - * Global Functions - ************************************************************************/ - -int abs(int j) -{ - if (j < 0) - { - j = -j; - } - return j; -} diff --git a/nuttx/libc/stdlib/lib_imaxabs.c b/nuttx/libc/stdlib/lib_imaxabs.c deleted file mode 100644 index d365043727..0000000000 --- a/nuttx/libc/stdlib/lib_imaxabs.c +++ /dev/null @@ -1,54 +0,0 @@ -/************************************************************************ - * libc/stdlib//lib_abs.c - * - * Copyright (C) 2010-2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -/************************************************************************ - * Global Functions - ************************************************************************/ - -intmax_t imaxabs(intmax_t j) -{ - if (j < 0) - { - j = -j; - } - return j; -} diff --git a/nuttx/libc/stdlib/lib_labs.c b/nuttx/libc/stdlib/lib_labs.c deleted file mode 100644 index 7cf92a0a19..0000000000 --- a/nuttx/libc/stdlib/lib_labs.c +++ /dev/null @@ -1,54 +0,0 @@ -/************************************************************************ - * libc/stdlib/lib_labs.c - * - * Copyright (C) 2010-2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -/************************************************************************ - * Global Functions - ************************************************************************/ - -long int labs(long int j) -{ - if (j < 0) - { - j = -j; - } - return j; -} diff --git a/nuttx/libc/stdlib/lib_llabs.c b/nuttx/libc/stdlib/lib_llabs.c deleted file mode 100644 index 3630d1716f..0000000000 --- a/nuttx/libc/stdlib/lib_llabs.c +++ /dev/null @@ -1,57 +0,0 @@ -/************************************************************************ - * libc/stdlib/lib_llabs.c - * - * Copyright (C) 2010-2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include -#include - -/************************************************************************ - * Global Functions - ************************************************************************/ - -#ifdef CONFIG_HAVE_LONG_LONG -long long int llabs(long long int j) -{ - if (j < 0) - { - j = -j; - } - return j; -} -#endif diff --git a/nuttx/libc/stdlib/lib_qsort.c b/nuttx/libc/stdlib/lib_qsort.c deleted file mode 100644 index 021e782d40..0000000000 --- a/nuttx/libc/stdlib/lib_qsort.c +++ /dev/null @@ -1,238 +0,0 @@ -/**************************************************************************** - * libc/stdlib/lib_qsort.c - * - * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Leveraged from: - * - * Copyright (c) 1992, 1993 - * The Regents of the University of California. All rights reserved. - * - * 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. All advertising materials mentioning features or use of this software - * must display the following acknowledgement: - * This product includes software developed by the University of - * California, Berkeley and its contributors. - * 4. Neither the name of the University 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 REGENTS 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 REGENTS 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 - -/**************************************************************************** - * Preprocessor Definitions - ****************************************************************************/ - -#define min(a, b) (a) < (b) ? a : b - -#define swapcode(TYPE, parmi, parmj, n) \ - { \ - long i = (n) / sizeof (TYPE); \ - register TYPE *pi = (TYPE *) (parmi); \ - register TYPE *pj = (TYPE *) (parmj); \ - do { \ - register TYPE t = *pi; \ - *pi++ = *pj; \ - *pj++ = t; \ - } while (--i > 0); \ - } - -#define SWAPINIT(a, size) \ - swaptype = ((char *)a - (char *)0) % sizeof(long) || \ - size % sizeof(long) ? 2 : size == sizeof(long)? 0 : 1; - -#define swap(a, b) \ - if (swaptype == 0) \ - { \ - long t = *(long *)(a); \ - *(long *)(a) = *(long *)(b); \ - *(long *)(b) = t; \ - } \ - else \ - { \ - swapfunc(a, b, size, swaptype); \ - } - -#define vecswap(a, b, n) if ((n) > 0) swapfunc(a, b, n, swaptype) - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -static inline void swapfunc(char *a, char *b, int n, int swaptype); -static inline char *med3(char *a, char *b, char *c, - int (*compar)(const void *, const void *)); - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -static inline void swapfunc(char *a, char *b, int n, int swaptype) -{ - if(swaptype <= 1) - { - swapcode(long, a, b, n) - } - else - { - swapcode(char, a, b, n) - } -} - -static inline char *med3(char *a, char *b, char *c, - int (*compar)(const void *, const void *)) -{ - return compar(a, b) < 0 ? - (compar(b, c) < 0 ? b : (compar(a, c) < 0 ? c : a )) - :(compar(b, c) > 0 ? b : (compar(a, c) < 0 ? a : c )); -} - -/**************************************************************************** - * Public Function - ****************************************************************************/ - -/**************************************************************************** - * Name: qsort - * - * Description: - * Qsort routine from Bentley & McIlroy's "Engineering a Sort Function". - * - ****************************************************************************/ - -void qsort(void *base, size_t nmemb, size_t size, - int(*compar)(const void *, const void *)) -{ - char *pa, *pb, *pc, *pd, *pl, *pm, *pn; - int d, r, swaptype, swap_cnt; - -loop: - SWAPINIT(base, size); - swap_cnt = 0; - if (nmemb < 7) - { - for (pm = (char *) base + size; pm < (char *) base + nmemb * size; pm += size) - { - for (pl = pm; pl > (char *) base && compar(pl - size, pl) > 0; pl -= size) - { - swap(pl, pl - size); - } - } - return; - } - - pm = (char *) base + (nmemb / 2) * size; - if (nmemb > 7) - { - pl = base; - pn = (char *) base + (nmemb - 1) * size; - if (nmemb > 40) - { - d = (nmemb / 8) * size; - pl = med3(pl, pl + d, pl + 2 * d, compar); - pm = med3(pm - d, pm, pm + d, compar); - pn = med3(pn - 2 * d, pn - d, pn, compar); - } - pm = med3(pl, pm, pn, compar); - } - swap(base, pm); - pa = pb = (char *) base + size; - - pc = pd = (char *) base + (nmemb - 1) * size; - for (;;) - { - while (pb <= pc && (r = compar(pb, base)) <= 0) - { - if (r == 0) - { - swap_cnt = 1; - swap(pa, pb); - pa += size; - } - pb += size; - } - while (pb <= pc && (r = compar(pc, base)) >= 0) - { - if (r == 0) - { - swap_cnt = 1; - swap(pc, pd); - pd -= size; - } - pc -= size; - } - - if (pb > pc) - { - break; - } - - swap(pb, pc); - swap_cnt = 1; - pb += size; - pc -= size; - } - - if (swap_cnt == 0) - { - /* Switch to insertion sort */ - - for (pm = (char *) base + size; pm < (char *) base + nmemb * size; pm += size) - { - for (pl = pm; pl > (char *) base && compar(pl - size, pl) > 0; pl -= size) - { - swap(pl, pl - size); - } - } - return; - } - - pn = (char *) base + nmemb * size; - r = min(pa - (char *)base, pb - pa); - vecswap(base, pb - r, r); - r = min(pd - pc, pn - pd - size); - vecswap(pb, pn - r, r); - - if ((r = pb - pa) > size) - { - qsort(base, r / size, size, compar); - } - - if ((r = pd - pc) > size) - { - /* Iterate rather than recurse to save stack space */ - base = pn - r; - nmemb = r / size; - goto loop; - } -} - diff --git a/nuttx/libc/stdlib/lib_rand.c b/nuttx/libc/stdlib/lib_rand.c deleted file mode 100644 index cb998fb12e..0000000000 --- a/nuttx/libc/stdlib/lib_rand.c +++ /dev/null @@ -1,220 +0,0 @@ -/************************************************************ - * libc/stdlib/lib_rand.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include -#include - -/************************************************************ - * Definitions - ************************************************************/ - -#ifndef CONFIG_LIB_RAND_ORDER -#define CONFIG_LIB_RAND_ORDER 1 -#endif - -/* Values needed by the random number generator */ - -#define RND1_CONSTK 470001 -#define RND1_CONSTP 999563 -#define RND2_CONSTK1 366528 -#define RND2_CONSTK2 508531 -#define RND2_CONSTP 998917 -#define RND3_CONSTK1 360137 -#define RND3_CONSTK2 519815 -#define RND3_CONSTK3 616087 -#define RND3_CONSTP 997783 - -#if CONFIG_LIB_RAND_ORDER == 1 -# define RND_CONSTP RND1_CONSTP -#elif CONFIG_LIB_RAND_ORDER == 2 -# define RND_CONSTP RND2_CONSTP -#else -# define RND_CONSTP RND3_CONSTP -#endif - -/************************************************************ - * Private Type Declarations - ************************************************************/ - -/************************************************************ - * Private Function Prototypes - ************************************************************/ - -static unsigned int nrand(unsigned int nLimit); -static double_t frand1(void); -#if (CONFIG_LIB_RAND_ORDER > 1) -static double_t frand2(void); -#if (CONFIG_LIB_RAND_ORDER > 2) -static double_t frand3(void); -#endif -#endif - -/********************************************************** - * Global Constant Data - **********************************************************/ - -/************************************************************ - * Global Variables - ************************************************************/ - -/********************************************************** - * Private Constant Data - **********************************************************/ - -/************************************************************ - * Private Variables - ************************************************************/ - -static unsigned long g_nRandInt1; -#if (CONFIG_LIB_RAND_ORDER > 1) -static unsigned long g_nRandInt2; -#if (CONFIG_LIB_RAND_ORDER > 2) -static unsigned long g_nRandInt3; -#endif -#endif - -/************************************************************ - * Private Functions - ************************************************************/ - -static unsigned int nrand(unsigned int nLimit) -{ - unsigned long nResult; - double_t fRatio; - - /* Loop to be sure a legal random number is generated */ - do { - - /* Get a random integer in the requested range */ -#if (CONFIG_LIB_RAND_ORDER == 1) - fRatio = frand1(); -#elif (CONFIG_LIB_RAND_ORDER == 2) - fRatio = frand2(); -#else - fRatio = frand3(); -#endif - - /* Then, produce the return-able value */ - nResult = (unsigned long)(((double_t)nLimit) * fRatio); - - } while (nResult >= (unsigned long)nLimit); - - return (unsigned int)nResult; - -} /* end nrand */ - -static double_t frand1(void) -{ - unsigned long nRandInt; - - /* First order congruential generator */ - nRandInt = (RND1_CONSTK * g_nRandInt1) % RND1_CONSTP; - g_nRandInt1 = nRandInt; - - /* Construct an floating point value in the range from 0.0 up to 1.0 */ - return ((double_t)nRandInt) / ((double_t)RND_CONSTP); - -} /* end frand */ - -#if (CONFIG_LIB_RAND_ORDER > 1) -static double_t frand2(void) -{ - unsigned long nRandInt; - - /* Second order congruential generator */ - nRandInt = (RND2_CONSTK1 * g_nRandInt1 + RND2_CONSTK2 * g_nRandInt2) % - RND2_CONSTP; - g_nRandInt2 = g_nRandInt1; - g_nRandInt1 = nRandInt; - - /* Construct an floating point value in the range from 0.0 up to 1.0 */ - return ((double_t)nRandInt) / ((double_t)RND_CONSTP); - -} /* end frand */ - -#if (CONFIG_LIB_RAND_ORDER > 2) -static double_t frand3(void) -{ - unsigned long nRandInt; - - /* Third order congruential generator */ - nRandInt = (RND3_CONSTK1 * g_nRandInt1 + RND3_CONSTK2 * g_nRandInt2 + - RND3_CONSTK2 * g_nRandInt3) % RND3_CONSTP; - g_nRandInt3 = g_nRandInt2; - g_nRandInt2 = g_nRandInt1; - g_nRandInt1 = nRandInt; - - /* Construct an floating point value in the range from 0.0 up to 1.0 */ - return ((double_t)nRandInt) / ((double_t)RND_CONSTP); - -} /* end frand */ -#endif -#endif - -/************************************************************ - * Public Functions - ************************************************************/ -/************************************************************ - * Function: srand, rand - ************************************************************/ - -void srand(unsigned int seed) -{ - g_nRandInt1 = seed; -#if (CONFIG_LIB_RAND_ORDER > 1) - g_nRandInt2 = seed; - (void)frand1(); -#if (CONFIG_LIB_RAND_ORDER > 2) - g_nRandInt3 = seed; - (void)frand2(); -#endif -#endif - -} /* end srand */ - -int rand(void) -{ - return (int)nrand(32768); - -} /* end rand */ - diff --git a/nuttx/libc/string/Make.defs b/nuttx/libc/string/Make.defs deleted file mode 100644 index 311c8afd27..0000000000 --- a/nuttx/libc/string/Make.defs +++ /dev/null @@ -1,58 +0,0 @@ -############################################################################ -# libc/string/Make.defs -# -# 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. -# -############################################################################ - -# Add the string C files to the build - -CSRCS += lib_checkbase.c lib_isbasedigit.c lib_memset.c lib_memchr.c \ - lib_memccpy.c lib_memcmp.c lib_memmove.c lib_skipspace.c \ - lib_strcasecmp.c lib_strcat.c lib_strchr.c lib_strcpy.c lib_strcmp.c \ - lib_strcspn.c lib_strdup.c lib_strerror.c lib_strlen.c lib_strnlen.c \ - lib_strncasecmp.c lib_strncat.c lib_strncmp.c lib_strncpy.c \ - lib_strndup.c lib_strcasestr.c lib_strpbrk.c lib_strrchr.c\ - lib_strspn.c lib_strstr.c lib_strtok.c lib_strtokr.c lib_strtol.c \ - lib_strtoll.c lib_strtoul.c lib_strtoull.c lib_strtod.c - -ifneq ($(CONFIG_ARCH_MEMCPY),y) -ifeq ($(CONFIG_MEMCPY_VIK),y) -CSRCS += lib_vikmemcpy.c -else -CSRCS += lib_memcpy.c -endif -endif - -# Add the string directory to the build - -DEPPATH += --dep-path string -VPATH += :string diff --git a/nuttx/libc/string/lib_checkbase.c b/nuttx/libc/string/lib_checkbase.c deleted file mode 100644 index 32ae58dca3..0000000000 --- a/nuttx/libc/string/lib_checkbase.c +++ /dev/null @@ -1,115 +0,0 @@ -/**************************************************************************** - * libc/string/lib_checkbase.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_checkbase - * - * Description: - * This is part of the strol() family implementation. This function checks - * the initial part of a string to see if it can determine the numeric - * base that is represented. - * - * Assumptions: - * *ptr points to the first, non-whitespace character in the string. - * - ****************************************************************************/ - -int lib_checkbase(int base, const char **pptr) -{ - const char *ptr = *pptr; - - /* Check for unspecified base */ - - if (!base) - { - /* Assume base 10 */ - - base = 10; - - /* Check for leading '0' - that would signify octal or hex (or binary) */ - - if (*ptr == '0') - { - /* Assume octal */ - - base = 8; - ptr++; - - /* Check for hexidecimal */ - - if ((*ptr == 'X' || *ptr == 'x') && - lib_isbasedigit(ptr[1], 16, NULL)) - { - base = 16; - ptr++; - } - } - } - - /* If it a hexidecimal representation, than discard any leading "0X" or "0x" */ - - else if (base == 16) - { - if (ptr[0] == '0' && (ptr[1] == 'X' || ptr[1] == 'x')) - { - ptr += 2; - } - } - - /* Return the updated pointer and base */ - - *pptr = ptr; - return base; -} - diff --git a/nuttx/libc/string/lib_isbasedigit.c b/nuttx/libc/string/lib_isbasedigit.c deleted file mode 100644 index dff8138811..0000000000 --- a/nuttx/libc/string/lib_isbasedigit.c +++ /dev/null @@ -1,105 +0,0 @@ -/**************************************************************************** - * libc/string/lib_isbasedigit.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_isbasedigit - * - * Description: - * Given an ASCII character, ch, and a base (1-36) do two - * things: 1) Determine if ch is a valid charcter, and 2) - * convert ch to its binary value. - * - ****************************************************************************/ - -bool lib_isbasedigit(int ch, int base, int *value) -{ - bool ret = false; - int tmp = 0; - - if (base <= 10) - { - if (ch >= '0' && ch <= base + '0' - 1) - { - tmp = ch - '0'; - ret = true; - } - } - else if (base <= 36) - { - if (ch >= '0' && ch <= '9') - { - tmp = ch - '0'; - ret = true; - } - else if (ch >= 'a' && ch <= 'a' + base - 11) - { - tmp = ch - 'a' + 10; - ret = true; - } - else if (ch >= 'A' && ch <= 'A' + base - 11) - { - tmp = ch - 'A' + 10; - ret = true; - } - } - - if (value) - { - *value = tmp; - } - return ret; -} - - diff --git a/nuttx/libc/string/lib_memccpy.c b/nuttx/libc/string/lib_memccpy.c deleted file mode 100644 index 1d77f58fe9..0000000000 --- a/nuttx/libc/string/lib_memccpy.c +++ /dev/null @@ -1,99 +0,0 @@ -/**************************************************************************** - * libc/string/lib_memccpy.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - - -/**************************************************************************** - * Name: memccpy - * - * Description: - * The memccpy() function copies bytes from memory area s2 into s1, - * stopping after the first occurrence of byte c (converted to an unsigned - * char) is copied, or after n bytes are copied, whichever comes first. If - * copying takes place between objects that overlap, the behavior is - * undefined. - * - * Returned Value: - * The memccpy() function returns a pointer to the byte after the copy of c - * in s1, or a null pointer if c was not found in the first n bytes of s2. - * - ****************************************************************************/ - -FAR void *memccpy(FAR void *s1, FAR const void *s2, int c, size_t n) -{ - FAR unsigned char *pout = (FAR unsigned char*)s1; - FAR unsigned char *pin = (FAR unsigned char*)s2; - - /* Copy at most n bytes */ - - while (n-- > 0) - { - /* Copy one byte */ - - *pout = *pin++; - - /* Did we just copy the terminating byte c? */ - - if (*pout == (unsigned char)c) - { - /* Yes return a pointer to the byte after the copy of c into s1 */ - - return (FAR void *)pout; - } - - /* No increment to the next destination location */ - - pout++; - } - - /* C was not found in the first n bytes of s2 */ - - return NULL; -} diff --git a/nuttx/libc/string/lib_memchr.c b/nuttx/libc/string/lib_memchr.c deleted file mode 100644 index 0ac6091042..0000000000 --- a/nuttx/libc/string/lib_memchr.c +++ /dev/null @@ -1,80 +0,0 @@ -/**************************************************************************** - * libc/string/lib_memchr.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: memchr - * - * Description: - * The memchr() function locates the first occurrence of 'c' (converted to - * an unsigned char) in the initial 'n' bytes (each interpreted as - * unsigned char) of the object pointed to by s. - * - * Returned Value: - * The memchr() function returns a pointer to the located byte, or a null - * pointer if the byte does not occur in the object. - * - ****************************************************************************/ - -FAR void *memchr(FAR const void *s, int c, size_t n) -{ - FAR const unsigned char *p = (FAR const unsigned char *)s; - - if (s) - { - while (n--) - { - if (*p == (unsigned char)c) - { - return (FAR void *)p; - } - - p++; - } - } - - return NULL; -} diff --git a/nuttx/libc/string/lib_memcmp.c b/nuttx/libc/string/lib_memcmp.c deleted file mode 100644 index e1722a4d8d..0000000000 --- a/nuttx/libc/string/lib_memcmp.c +++ /dev/null @@ -1,74 +0,0 @@ -/************************************************************ - * libc/string/lib_memcmp.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include -#include -#include - -/************************************************************ - * Global Functions - ************************************************************/ - -#ifndef CONFIG_ARCH_MEMCMP -int memcmp(const void *s1, const void *s2, size_t n) -{ - unsigned char *p1 = (unsigned char *)s1; - unsigned char *p2 = (unsigned char *)s2; - - while (n-- > 0) - { - if (*p1 < *p2) - { - return -1; - } - else if (*p1 > *p2) - { - return 1; - } - - p1++; - p2++; - } - return 0; -} -#endif diff --git a/nuttx/libc/string/lib_memcpy.c b/nuttx/libc/string/lib_memcpy.c deleted file mode 100644 index 2ebd5beee1..0000000000 --- a/nuttx/libc/string/lib_memcpy.c +++ /dev/null @@ -1,64 +0,0 @@ -/**************************************************************************** - * libc/string/lib_memcpy.c - * - * Copyright (C) 2007, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: memcpy - ****************************************************************************/ - -#ifndef CONFIG_ARCH_MEMCPY -FAR void *memcpy(FAR void *dest, FAR const void *src, size_t n) -{ - FAR unsigned char *pout = (FAR unsigned char*)dest; - FAR unsigned char *pin = (FAR unsigned char*)src; - while (n-- > 0) *pout++ = *pin++; - return dest; -} -#endif diff --git a/nuttx/libc/string/lib_memmove.c b/nuttx/libc/string/lib_memmove.c deleted file mode 100644 index cbc26fb26f..0000000000 --- a/nuttx/libc/string/lib_memmove.c +++ /dev/null @@ -1,77 +0,0 @@ -/************************************************************ - * libc/string/lib_memmove.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Compilation Switches - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include -#include -#include - -/************************************************************ - * Global Functions - ************************************************************/ - -#ifndef CONFIG_ARCH_MEMMOVE -void *memmove(void *dest, const void *src, size_t count) -{ - char *tmp, *s; - if (dest <= src) - { - tmp = (char*) dest; - s = (char*) src; - while (count--) - { - *tmp++ = *s++; - } - } - else - { - tmp = (char*) dest + count; - s = (char*) src + count; - while (count--) - { - *--tmp = *--s; - } - } - - return dest; -} -#endif diff --git a/nuttx/libc/string/lib_memset.c b/nuttx/libc/string/lib_memset.c deleted file mode 100644 index 0b98ebf96f..0000000000 --- a/nuttx/libc/string/lib_memset.c +++ /dev/null @@ -1,188 +0,0 @@ - -/**************************************************************************** - * libc/string/lib_memset.c - * - * Copyright (C) 2007, 2011 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. - * - ****************************************************************************/ - - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Can't support CONFIG_MEMSET_64BIT if the platform does not have 64-bit - * integer types. - */ - -#ifndef CONFIG_HAVE_LONG_LONG -# undef CONFIG_MEMSET_64BIT -#endif - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -#ifndef CONFIG_ARCH_MEMSET -void *memset(void *s, int c, size_t n) -{ -#ifdef CONFIG_MEMSET_OPTSPEED - /* This version is optimized for speed (you could do better - * still by exploiting processor caching or memory burst - * knowledge.) - */ - - uintptr_t addr = (uintptr_t)s; - uint16_t val16 = ((uint16_t)c << 8) | (uint16_t)c; - uint32_t val32 = ((uint32_t)val16 << 16) | (uint32_t)val16; -#ifdef CONFIG_MEMSET_64BIT - uint64_t val64 = ((uint64_t)val32 << 32) | (uint64_t)val32; -#endif - - /* Make sure that there is something to be cleared */ - - if (n > 0) - { - /* Align to a 16-bit boundary */ - - if ((addr & 1) != 0) - { - *(uint8_t*)addr = (uint8_t)c; - addr += 1; - n -= 1; - } - - /* Check if there are at least 16-bits left to be written */ - - if (n >= 2) - { - /* Align to a 32-bit boundary (we know that the destination - * address is already aligned to at least a 16-bit boundary). - */ - - if ((addr & 3) != 0) - { - *(uint16_t*)addr = val16; - addr += 2; - n -= 2; - } - -#ifndef CONFIG_MEMSET_64BIT - /* Loop while there are at least 32-bits left to be written */ - - while (n >= 4) - { - *(uint32_t*)addr = val32; - addr += 4; - n -= 4; - } -#else - /* Check if there are at least 32-bits left to be written */ - - if (n >= 4) - { - /* Align to a 64-bit boundary (we know that the destination - * address is already aligned to at least a 32-bit boundary). - */ - - if ((addr & 7) != 0) - { - *(uint32_t*)addr = val32; - addr += 4; - n -= 4; - } - - /* Loop while there are at least 64-bits left to be written */ - - while (n >= 8) - { - *(uint64_t*)addr = val64; - addr += 8; - n -= 8; - } - } -#endif - } - -#ifdef CONFIG_MEMSET_64BIT - /* We may get here with n in the range 0..7. If n >= 4, then we should - * have 64-bit alignment. - */ - - if (n >= 4) - { - *(uint32_t*)addr = val32; - addr += 4; - n -= 4; - } -#endif - - /* We may get here under the following conditions: - * - * n = 0, addr may or may not be aligned - * n = 1, addr is aligned to at least a 16-bit boundary - * n = 2, addr is aligned to a 32-bit boundary - * n = 3, addr is aligned to a 32-bit boundary - */ - - if (n >= 2) - { - *(uint16_t*)addr = val16; - addr += 2; - n -= 2; - } - - if (n >= 1) - { - *(uint8_t*)addr = (uint8_t)c; - } - } -#else - /* This version is optimized for size */ - - unsigned char *p = (unsigned char*)s; - while (n-- > 0) *p++ = c; -#endif - return s; -} -#endif diff --git a/nuttx/libc/string/lib_skipspace.c b/nuttx/libc/string/lib_skipspace.c deleted file mode 100644 index 4b72b1ec37..0000000000 --- a/nuttx/libc/string/lib_skipspace.c +++ /dev/null @@ -1,69 +0,0 @@ -/**************************************************************************** - * libc/string/lib_skipspace.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_skipspace - * - * Description: - * Skip over leading whitespace - * - ****************************************************************************/ - -void lib_skipspace(const char **pptr) -{ - const char *ptr = *pptr; - while (isspace(*ptr)) ptr++; - *pptr = ptr; -} - - diff --git a/nuttx/libc/string/lib_strcasecmp.c b/nuttx/libc/string/lib_strcasecmp.c deleted file mode 100644 index df6f08118d..0000000000 --- a/nuttx/libc/string/lib_strcasecmp.c +++ /dev/null @@ -1,65 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strcasecmp.c - * - * Copyright (C) 2008-2009, 2011 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. - * - *****************************************************************************/ - -/**************************************************************************** - * Included Files - *****************************************************************************/ - -#include - -#include -#include - -/**************************************************************************** - * Public Functions - *****************************************************************************/ - -#ifndef CONFIG_ARCH_STRCMP -int strcasecmp(const char *cs, const char *ct) -{ - int result; - for (;;) - { - if ((result = (int)toupper(*cs) - (int)toupper(*ct)) != 0 || !*cs) - { - break; - } - - cs++; - ct++; - } - return result; -} -#endif diff --git a/nuttx/libc/string/lib_strcasestr.c b/nuttx/libc/string/lib_strcasestr.c deleted file mode 100644 index 5a8d53beef..0000000000 --- a/nuttx/libc/string/lib_strcasestr.c +++ /dev/null @@ -1,134 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strstr.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use str 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 str binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer str - * 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 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -static FAR char *strcasechr(FAR const char *s, int uc) -{ - register char ch; - - if (s) - { - for (; *s; s++) - { - ch = *s; - if (toupper(ch) == uc) - { - return (FAR char*)s; - } - } - } - - return NULL; -} - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -FAR char *strcasestr(FAR const char *str, FAR const char *substr) -{ - const char *candidate; /* Candidate in str with matching start character */ - char ch; /* First character of the substring */ - int len; /* The length of the substring */ - - /* Special case the empty substring */ - - len = strlen(substr); - ch = *substr; - - if (!ch) - { - /* We'll say that an empty substring matches at the beginning of - * the string - */ - - return (char*)str; - } - - /* Search for the substring */ - - candidate = str; - ch = toupper(ch); - - for (;;) - { - /* strcasechr() will return a pointer to the next occurrence of the - * character ch in the string (ignoring case) - */ - - candidate = strcasechr(candidate, ch); - if (!candidate || strlen(candidate) < len) - { - /* First character of the substring does not appear in the string - * or the remainder of the string is not long enough to contain the - * substring. - */ - - return NULL; - } - - /* Check if this is the beginning of a matching substring (ignoring case) */ - - if (strncasecmp(candidate, substr, len) == 0) - { - /* Yes.. return the pointer to the first occurrence of the matching - * substring. - */ - - return (char*)candidate; - } - - /* No, find the next candidate after this one */ - - candidate++; - } - - /* Won't get here, but some compilers might complain */ - - return NULL; -} - diff --git a/nuttx/libc/string/lib_strcat.c b/nuttx/libc/string/lib_strcat.c deleted file mode 100644 index b331d3f1c1..0000000000 --- a/nuttx/libc/string/lib_strcat.c +++ /dev/null @@ -1,62 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strcat.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -#ifndef CONFIG_ARCH_STRCAT -char *strcat(char *dest, const char *src) -{ - char *ret = dest; - - dest += strlen(dest); - while (*src != '\0') - { - *dest++ = *src++; - } - *dest = '\0'; - - return ret; -} -#endif diff --git a/nuttx/libc/string/lib_strchr.c b/nuttx/libc/string/lib_strchr.c deleted file mode 100644 index e6af56eee5..0000000000 --- a/nuttx/libc/string/lib_strchr.c +++ /dev/null @@ -1,78 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strchr.c - * - * Copyright (C) 2007, 2009, 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: strchr - * - * Description: - * The strchr() function locates the first occurrence of 'c' (converted to - * a char) in the string pointed to by 's'. The terminating null byte is - * considered to be part of the string. - * - * Returned Value: - * Upon completion, strchr() returns a pointer to the byte, or a null - * pointer if the byte was not found. - * - ****************************************************************************/ - -#ifndef CONFIG_ARCH_STRCHR -FAR char *strchr(FAR const char *s, int c) -{ - if (s) - { - for (; *s; s++) - { - if (*s == c) - { - return (FAR char *)s; - } - } - } - - return NULL; -} -#endif diff --git a/nuttx/libc/string/lib_strcmp.c b/nuttx/libc/string/lib_strcmp.c deleted file mode 100644 index d4036cd3ea..0000000000 --- a/nuttx/libc/string/lib_strcmp.c +++ /dev/null @@ -1,59 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strcmp.c - * - * Copyright (C) 2007-2009, 2011 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. - * - *****************************************************************************/ - -/**************************************************************************** - * Included Files - *****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Public Functions - *****************************************************************************/ - -#ifndef CONFIG_ARCH_STRCMP -int strcmp(const char *cs, const char *ct) -{ - register signed char result; - for (;;) - { - if ((result = *cs - *ct++) != 0 || !*cs++) - break; - } - return result; -} -#endif diff --git a/nuttx/libc/string/lib_strcpy.c b/nuttx/libc/string/lib_strcpy.c deleted file mode 100644 index 7a0576f5af..0000000000 --- a/nuttx/libc/string/lib_strcpy.c +++ /dev/null @@ -1,55 +0,0 @@ -/************************************************************************ - * libc/string/lib_strcpy.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include - -/************************************************************************ - * Global Functions - ************************************************************************/ - -#ifndef CONFIG_ARCH_STRCPY -char *strcpy(char *dest, const char *src) -{ - char *tmp = dest; - while ((*dest++ = *src++) != '\0'); - return tmp; -} -#endif diff --git a/nuttx/libc/string/lib_strcspn.c b/nuttx/libc/string/lib_strcspn.c deleted file mode 100644 index 23e913fadf..0000000000 --- a/nuttx/libc/string/lib_strcspn.c +++ /dev/null @@ -1,67 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strcspn.c - * - * Copyright (C) 2007, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: strcspn - * - * Description: - * strspn() calculates the length of the initial segment of s which - * consists entirely of characters not in reject - * - ****************************************************************************/ - -size_t strcspn(const char *s, const char *reject) -{ - size_t i; - for (i = 0; s[i] && strchr(reject, s[i]) == NULL; i++); - return i; -} - diff --git a/nuttx/libc/string/lib_strdup.c b/nuttx/libc/string/lib_strdup.c deleted file mode 100644 index a5b3a1e8c1..0000000000 --- a/nuttx/libc/string/lib_strdup.c +++ /dev/null @@ -1,62 +0,0 @@ -/************************************************************************ - * libc/string//lib_strdup.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include - -#include "lib_internal.h" - -/************************************************************************ - * Global Functions - ************************************************************************/ - -FAR char *strdup(const char *s) -{ - FAR char *news = NULL; - if (s) - { - news = (FAR char*)lib_malloc(strlen(s) + 1); - if (news) - { - strcpy(news, s); - } - } - return news; -} diff --git a/nuttx/libc/string/lib_strerror.c b/nuttx/libc/string/lib_strerror.c deleted file mode 100644 index 0c7ca28fd8..0000000000 --- a/nuttx/libc/string/lib_strerror.c +++ /dev/null @@ -1,375 +0,0 @@ -/************************************************************************ - * libc/string/lib_strerror.c - * - * Copyright (C) 2007, 2009, 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include -#include -#include - -/************************************************************************ - * Definitions - ************************************************************************/ - -/************************************************************************ - * Private Types - ************************************************************************/ - -struct errno_strmap_s -{ - uint8_t errnum; - const char *str; -}; - -/************************************************************************ - * Private Data - ************************************************************************/ - -#ifdef CONFIG_LIBC_STRERROR - -/* This table maps all error numbers to descriptive strings. - * The only assumption that the code makes with regard to this - * this table is that it is ordered by error number. - * - * The size of this table is quite large. Its size can be - * reduced by eliminating some of the more obscure error - * strings. - */ - -#ifndef CONFIG_LIBC_STRERROR_SHORT - -static const struct errno_strmap_s g_errnomap[] = -{ - { EPERM, EPERM_STR }, - { ENOENT, ENOENT_STR }, - { ESRCH, ESRCH_STR }, - { EINTR, EINTR_STR }, - { EIO, EIO_STR }, - { ENXIO, ENXIO_STR }, - { E2BIG, E2BIG_STR }, - { ENOEXEC, ENOEXEC_STR }, - { EBADF, EBADF_STR }, - { ECHILD, ECHILD_STR }, - { EAGAIN, EAGAIN_STR }, - { ENOMEM, ENOMEM_STR }, - { EACCES, EACCES_STR }, - { EFAULT, EFAULT_STR }, - { ENOTBLK, ENOTBLK_STR }, - { EBUSY, EBUSY_STR }, - { EEXIST, EEXIST_STR }, - { EXDEV, EXDEV_STR }, - { ENODEV, ENODEV_STR }, - { ENOTDIR, ENOTDIR_STR }, - { EISDIR, EISDIR_STR }, - { EINVAL, EINVAL_STR }, - { ENFILE, ENFILE_STR }, - { EMFILE, EMFILE_STR }, - { ENOTTY, ENOTTY_STR }, - { ETXTBSY, ETXTBSY_STR }, - { EFBIG, EFBIG_STR }, - { ENOSPC, ENOSPC_STR }, - { ESPIPE, ESPIPE_STR }, - { EROFS, EROFS_STR }, - { EMLINK, EMLINK_STR }, - { EPIPE, EPIPE_STR }, - { EDOM, EDOM_STR }, - { ERANGE, ERANGE_STR }, - { EDEADLK, EDEADLK_STR }, - { ENAMETOOLONG, ENAMETOOLONG_STR }, - { ENOLCK, ENOLCK_STR }, - { ENOSYS, ENOSYS_STR }, - { ENOTEMPTY, ENOTEMPTY_STR }, - { ELOOP, ELOOP_STR }, - { ENOMSG, ENOMSG_STR }, - { EIDRM, EIDRM_STR }, - { ECHRNG, ECHRNG_STR }, - { EL2NSYNC, EL2NSYNC_STR }, - { EL3HLT, EL3HLT_STR }, - { EL3RST, EL3RST_STR }, - { ELNRNG, ELNRNG_STR }, - { EUNATCH, EUNATCH_STR }, - { ENOCSI, ENOCSI_STR }, - { EL2HLT, EL2HLT_STR }, - { EBADE, EBADE_STR }, - { EBADR, EBADR_STR }, - { EXFULL, EXFULL_STR }, - { ENOANO, ENOANO_STR }, - { EBADRQC, EBADRQC_STR }, - { EBADSLT, EBADSLT_STR }, - { EBFONT, EBFONT_STR }, - { ENOSTR, ENOSTR_STR }, - { ENODATA, ENODATA_STR }, - { ETIME, ETIME_STR }, - { ENOSR, ENOSR_STR }, - { ENONET, ENONET_STR }, - { ENOPKG, ENOPKG_STR }, - { EREMOTE, EREMOTE_STR }, - { ENOLINK, ENOLINK_STR }, - { EADV, EADV_STR }, - { ESRMNT, ESRMNT_STR }, - { ECOMM, ECOMM_STR }, - { EPROTO, EPROTO_STR }, - { EMULTIHOP, EMULTIHOP_STR }, - { EDOTDOT, EDOTDOT_STR }, - { EBADMSG, EBADMSG_STR }, - { EOVERFLOW, EOVERFLOW_STR }, - { ENOTUNIQ, ENOTUNIQ_STR }, - { EBADFD, EBADFD_STR }, - { EREMCHG, EREMCHG_STR }, - { ELIBACC, ELIBACC_STR }, - { ELIBBAD, ELIBBAD_STR }, - { ELIBSCN, ELIBSCN_STR }, - { ELIBMAX, ELIBMAX_STR }, - { ELIBEXEC, ELIBEXEC_STR }, - { EILSEQ, EILSEQ_STR }, - { ERESTART, ERESTART_STR }, - { ESTRPIPE, ESTRPIPE_STR }, - { EUSERS, EUSERS_STR }, - { ENOTSOCK, ENOTSOCK_STR }, - { EDESTADDRREQ, EDESTADDRREQ_STR }, - { EMSGSIZE, EMSGSIZE_STR }, - { EPROTOTYPE, EPROTOTYPE_STR }, - { ENOPROTOOPT, ENOPROTOOPT_STR }, - { EPROTONOSUPPORT, EPROTONOSUPPORT_STR }, - { ESOCKTNOSUPPORT, ESOCKTNOSUPPORT_STR }, - { EOPNOTSUPP, EOPNOTSUPP_STR }, - { EPFNOSUPPORT, EPFNOSUPPORT_STR }, - { EAFNOSUPPORT, EAFNOSUPPORT_STR }, - { EADDRINUSE, EADDRINUSE_STR }, - { EADDRNOTAVAIL, EADDRNOTAVAIL_STR }, - { ENETDOWN, ENETDOWN_STR }, - { ENETUNREACH, ENETUNREACH_STR }, - { ENETRESET, ENETRESET_STR }, - { ECONNABORTED, ECONNABORTED_STR }, - { ECONNRESET, ECONNRESET_STR }, - { ENOBUFS, ENOBUFS_STR }, - { EISCONN, EISCONN_STR }, - { ENOTCONN, ENOTCONN_STR }, - { ESHUTDOWN, ESHUTDOWN_STR }, - { ETOOMANYREFS, ETOOMANYREFS_STR }, - { ETIMEDOUT, ETIMEDOUT_STR }, - { ECONNREFUSED, ECONNREFUSED_STR }, - { EHOSTDOWN, EHOSTDOWN_STR }, - { EHOSTUNREACH, EHOSTUNREACH_STR }, - { EALREADY, EALREADY_STR }, - { EINPROGRESS, EINPROGRESS_STR }, - { ESTALE, ESTALE_STR }, - { EUCLEAN, EUCLEAN_STR }, - { ENOTNAM, ENOTNAM_STR }, - { ENAVAIL, ENAVAIL_STR }, - { EISNAM, EISNAM_STR }, - { EREMOTEIO, EREMOTEIO_STR }, - { EDQUOT, EDQUOT_STR }, - { ENOMEDIUM, ENOMEDIUM_STR }, - { EMEDIUMTYPE, EMEDIUMTYPE_STR } -}; - -#else /* CONFIG_LIBC_STRERROR_SHORT */ - -static const struct errno_strmap_s g_errnomap[] = -{ - { EPERM, "EPERM" }, - { ENOENT, "ENOENT" }, - { ESRCH, "ESRCH" }, - { EINTR, "EINTR" }, - { EIO, "EIO" }, - { ENXIO, "ENXIO" }, - { E2BIG, "E2BIG" }, - { ENOEXEC, "ENOEXEC" }, - { EBADF, "EBADF" }, - { ECHILD, "ECHILD" }, - { EAGAIN, "EAGAIN" }, - { ENOMEM, "ENOMEM" }, - { EACCES, "EACCES" }, - { EFAULT, "EFAULT" }, - { ENOTBLK, "ENOTBLK" }, - { EBUSY, "EBUSY" }, - { EEXIST, "EEXIST" }, - { EXDEV, "EXDEV" }, - { ENODEV, "ENODEV" }, - { ENOTDIR, "ENOTDIR" }, - { EISDIR, "EISDIR" }, - { EINVAL, "EINVAL" }, - { ENFILE, "ENFILE" }, - { EMFILE, "EMFILE" }, - { ENOTTY, "ENOTTY" }, - { ETXTBSY, "ETXTBSY" }, - { EFBIG, "EFBIG" }, - { ENOSPC, "ENOSPC" }, - { ESPIPE, "ESPIPE" }, - { EROFS, "EROFS" }, - { EMLINK, "EMLINK" }, - { EPIPE, "EPIPE" }, - { EDOM, "EDOM" }, - { ERANGE, "ERANGE" }, - { EDEADLK, "EDEADLK" }, - { ENAMETOOLONG, "ENAMETOOLONG" }, - { ENOLCK, "ENOLCK" }, - { ENOSYS, "ENOSYS" }, - { ENOTEMPTY, "ENOTEMPTY" }, - { ELOOP, "ELOOP" }, - { ENOMSG, "ENOMSG" }, - { EIDRM, "EIDRM" }, - { ECHRNG, "ECHRNG" }, - { EL2NSYNC, "EL2NSYNC" }, - { EL3HLT, "EL3HLT" }, - { EL3RST, "EL3RST" }, - { EL3RST, "EL3RST" }, - { EUNATCH, "EUNATCH" }, - { ENOCSI, "ENOCSI" }, - { EL2HLT, "EL2HLT" }, - { EBADE, "EBADE" }, - { EBADR, "EBADR" }, - { EXFULL, "EXFULL" }, - { ENOANO, "ENOANO" }, - { EBADRQC, "EBADRQC" }, - { EBADSLT, "EBADSLT" }, - { EBFONT, "EBFONT" }, - { ENOSTR, "ENOSTR" }, - { ENODATA, "ENODATA" }, - { ETIME, "ETIME" }, - { ENOSR, "ENOSR" }, - { ENONET, "ENONET" }, - { ENOPKG, "ENOPKG" }, - { EREMOTE, "EREMOTE" }, - { ENOLINK, "ENOLINK" }, - { EADV, "EADV" }, - { ESRMNT, "ESRMNT" }, - { ECOMM, "ECOMM" }, - { EPROTO, "EPROTO" }, - { EMULTIHOP, "EMULTIHOP" }, - { EDOTDOT, "EDOTDOT" }, - { EBADMSG, "EBADMSG" }, - { EOVERFLOW, "EOVERFLOW" }, - { ENOTUNIQ, "ENOTUNIQ" }, - { EBADFD, "EBADFD" }, - { EREMCHG, "EREMCHG" }, - { ELIBACC, "ELIBACC" }, - { ELIBBAD, "ELIBBAD" }, - { ELIBSCN, "ELIBSCN" }, - { ELIBMAX, "ELIBMAX" }, - { ELIBEXEC, "ELIBEXEC" }, - { EILSEQ, "EILSEQ" }, - { ERESTART, "ERESTART" }, - { ESTRPIPE, "ESTRPIPE" }, - { EUSERS, "EUSERS" }, - { ENOTSOCK, "ENOTSOCK" }, - { EDESTADDRREQ, "EDESTADDRREQ" }, - { EMSGSIZE, "EMSGSIZE" }, - { EPROTOTYPE, "EPROTOTYPE" }, - { ENOPROTOOPT, "ENOPROTOOPT" }, - { EPROTONOSUPPORT, "EPROTONOSUPPORT" }, - { ESOCKTNOSUPPORT, "ESOCKTNOSUPPORT" }, - { EOPNOTSUPP, "EOPNOTSUPP" }, - { EPFNOSUPPORT, "EPFNOSUPPORT" }, - { EAFNOSUPPORT, "EAFNOSUPPORT" }, - { EADDRINUSE, "EADDRINUSE" }, - { EADDRNOTAVAIL, "EADDRNOTAVAIL" }, - { ENETDOWN, "ENETDOWN" }, - { ENETUNREACH, "ENETUNREACH" }, - { ENETRESET, "ENETRESET" }, - { ECONNABORTED, "ECONNABORTED" }, - { ECONNRESET, "ECONNRESET" }, - { ENOBUFS, "ENOBUFS" }, - { EISCONN, "EISCONN" }, - { ENOTCONN, "ENOTCONN" }, - { ESHUTDOWN, "ESHUTDOWN" }, - { ETOOMANYREFS, "ETOOMANYREFS" }, - { ETIMEDOUT, "ETIMEDOUT" }, - { ECONNREFUSED, "ECONNREFUSED" }, - { EHOSTDOWN, "EHOSTDOWN" }, - { EHOSTUNREACH, "EHOSTUNREACH" }, - { EALREADY, "EALREADY" }, - { EINPROGRESS, "EINPROGRESS" }, - { ESTALE, "ESTALE" }, - { EUCLEAN, "EUCLEAN" }, - { ENOTNAM, "ENOTNAM" }, - { ENAVAIL, "ENAVAIL" }, - { EISNAM, "EISNAM" }, - { EREMOTEIO, "EREMOTEIO" }, - { EDQUOT, "EDQUOT" }, - { ENOMEDIUM, "ENOMEDIUM" }, - { EMEDIUMTYPE, "EMEDIUMTYPE" } -}; - -#endif /* CONFIG_LIBC_STRERROR_SHORT */ - -#define NERRNO_STRS (sizeof(g_errnomap) / sizeof(struct errno_strmap_s)) - -#endif /* CONFIG_LIBC_STRERROR */ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: strerror - ************************************************************************/ - -FAR const char *strerror(int errnum) -{ -#ifdef CONFIG_LIBC_STRERROR - int ndxlow = 0; - int ndxhi = NERRNO_STRS - 1; - int ndxmid; - - do - { - ndxmid = (ndxlow + ndxhi) >> 1; - if (errnum > g_errnomap[ndxmid].errnum) - { - ndxlow = ndxmid + 1; - } - else if (errnum < g_errnomap[ndxmid].errnum) - { - ndxhi = ndxmid - 1; - } - else - { - return g_errnomap[ndxmid].str; - } - } - while (ndxlow <= ndxhi); -#endif - return "Unknown error"; -} diff --git a/nuttx/libc/string/lib_strlen.c b/nuttx/libc/string/lib_strlen.c deleted file mode 100644 index 6077858e23..0000000000 --- a/nuttx/libc/string/lib_strlen.c +++ /dev/null @@ -1,55 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strlen.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -#ifndef CONFIG_ARCH_STRLEN -size_t strlen(const char *s) -{ - const char *sc; - for (sc = s; *sc != '\0'; ++sc); - return sc - s; -} -#endif diff --git a/nuttx/libc/string/lib_strncasecmp.c b/nuttx/libc/string/lib_strncasecmp.c deleted file mode 100644 index 35f701c5ef..0000000000 --- a/nuttx/libc/string/lib_strncasecmp.c +++ /dev/null @@ -1,70 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strncasecmp.c - * - * Copyright (C) 2007-2009, 2011 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. - * - *****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - *****************************************************************************/ - -/**************************************************************************** - * Included Files - *****************************************************************************/ - -#include - -#include -#include -#include - -/**************************************************************************** - * Global Functions - *****************************************************************************/ - -#ifndef CONFIG_ARCH_STRNCASECMP -int strncasecmp(const char *cs, const char *ct, size_t nb) -{ - int result = 0; - for (; nb > 0; nb--) - { - if ((result = (int)toupper(*cs) - (int)toupper(*ct)) != 0 || !*cs) - { - break; - } - - cs++; - ct++; - } - return result; -} -#endif diff --git a/nuttx/libc/string/lib_strncat.c b/nuttx/libc/string/lib_strncat.c deleted file mode 100644 index 78c54835e0..0000000000 --- a/nuttx/libc/string/lib_strncat.c +++ /dev/null @@ -1,62 +0,0 @@ -/************************************************************ - * libc/string/lib_strncat.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include -#include -#include - -/************************************************************ - * Global Functions - ************************************************************/ - -#ifndef CONFIG_ARCH_STRNCAT -char *strncat(char *dest, const char *src, size_t n) -{ - char *ret = dest; - - dest += strlen(dest); - for (; n > 0 && *src != '\0' ; n--) - { - *dest++ = *src++; - } - *dest = '\0'; - - return ret; -} -#endif diff --git a/nuttx/libc/string/lib_strncmp.c b/nuttx/libc/string/lib_strncmp.c deleted file mode 100644 index dd8b57fd0b..0000000000 --- a/nuttx/libc/string/lib_strncmp.c +++ /dev/null @@ -1,65 +0,0 @@ -/**************************************************************************** - * libc/lib_strncmp.c - * - * Copyright (C) 2007-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. - * - *****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - *****************************************************************************/ - -/**************************************************************************** - * Included Files - *****************************************************************************/ - -#include -#include -#include - -/**************************************************************************** - * Global Functions - *****************************************************************************/ - -#ifndef CONFIG_ARCH_STRNCMP -int strncmp(const char *cs, const char *ct, size_t nb) -{ - int result = 0; - for (; nb > 0; nb--) - { - if ((result = (int)*cs - (int)*ct++) != 0 || !*cs++) - { - break; - } - } - return result; -} -#endif diff --git a/nuttx/libc/string/lib_strncpy.c b/nuttx/libc/string/lib_strncpy.c deleted file mode 100644 index 8a97aa67b7..0000000000 --- a/nuttx/libc/string/lib_strncpy.c +++ /dev/null @@ -1,57 +0,0 @@ -/************************************************************ - * libc/string/lib_strncpy.c - * - * Copyright (C) 2007, 2011 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. - * - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include -#include -#include - -/************************************************************ - * Global Functions - ************************************************************/ - -#ifndef CONFIG_ARCH_STRNCPY -char *strncpy(char *dest, const char *src, size_t n) -{ - char *ret = dest; /* Value to be returned */ - char *end = dest + n; /* End of dest buffer + 1 byte */ - - while ((*dest++ = *src++) != '\0' && dest != end); - return ret; -} -#endif diff --git a/nuttx/libc/string/lib_strndup.c b/nuttx/libc/string/lib_strndup.c deleted file mode 100644 index 524e09754e..0000000000 --- a/nuttx/libc/string/lib_strndup.c +++ /dev/null @@ -1,93 +0,0 @@ -/************************************************************************ - * libc/string//lib_strndup.c - * - * Copyright (C) 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include - -#include "lib_internal.h" - -/************************************************************************ - * Global Functions - ************************************************************************/ -/************************************************************************ - * Name: strndup - * - * Description: - * The strndup() function is equivalent to the strdup() function, - * duplicating the provided 's' in a new block of memory allocated as - * if by using malloc(), with the exception being that strndup() copies - * at most 'size' plus one bytes into the newly allocated memory, - * terminating the new string with a NUL character. If the length of 's' - * is larger than 'size', only 'size' bytes will be duplicated. If - * 'size' is larger than the length of 's', all bytes in s will be - * copied into the new memory buffer, including the terminating NUL - * character. The newly created string will always be properly - * terminated. - * - ************************************************************************/ - -FAR char *strndup(FAR const char *s, size_t size) -{ - FAR char *news = NULL; - if (s) - { - /* Get the size of the new string = MIN(strlen(s), size) */ - - size_t allocsize = strlen(s); - if (allocsize > size) - { - allocsize = size; - } - - /* Allocate the new string, adding 1 for the NUL terminator */ - - news = (FAR char*)lib_malloc(allocsize + 1); - if (news) - { - /* Copy the string into the allocated memory and add a NUL - * terminator in any case. - */ - - memcpy(news, s, allocsize); - news[allocsize] = '\0'; - } - } - return news; -} diff --git a/nuttx/libc/string/lib_strnlen.c b/nuttx/libc/string/lib_strnlen.c deleted file mode 100644 index 9bc3064cb1..0000000000 --- a/nuttx/libc/string/lib_strnlen.c +++ /dev/null @@ -1,62 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strnlen.c - * - * This file is part of NuttX, contributed by Michael Hrabanek - * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Michael Hrabanek - * - * Derives from the file libc/lib_strlen.c: - * - * Copyright (C) 2007, 2008, 2010 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -#ifndef CONFIG_ARCH_STRNLEN -size_t strnlen(const char *s, size_t maxlen) -{ - const char *sc; - for (sc = s; maxlen != 0 && *sc != '\0'; maxlen--, ++sc); - return sc - s; -} -#endif diff --git a/nuttx/libc/string/lib_strpbrk.c b/nuttx/libc/string/lib_strpbrk.c deleted file mode 100644 index ef9b0f3e97..0000000000 --- a/nuttx/libc/string/lib_strpbrk.c +++ /dev/null @@ -1,85 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strpbrk.c - * - * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use str 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 str binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer str - * 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 - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -char *strpbrk(const char *str, const char *charset) -{ - /* Sanity checking */ - -#ifdef CONFIG_DEBUG - if (!str || !charset) - { - return NULL; - } -#endif - - /* Check each character in the string */ - - while (*str) - { - /* Check if the character from the string matches any character in the charset */ - - if (strchr(charset, *str) != NULL) - { - /* Yes, then this position must be the first occurrence in string */ - - return (char*)str; - } - - /* This character from the strings matches none of those in the charset. - * Try the next character from the string. - */ - - str++; - } - - /* We have looked at every character in the string, and none of them match any of - * the characters in charset. - */ - - return NULL; -} - diff --git a/nuttx/libc/string/lib_strrchr.c b/nuttx/libc/string/lib_strrchr.c deleted file mode 100644 index 08575c82bf..0000000000 --- a/nuttx/libc/string/lib_strrchr.c +++ /dev/null @@ -1,68 +0,0 @@ -/************************************************************************ - * libc/string/lib_strrchr.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include - -/************************************************************************ - * Global Functions - ************************************************************************/ - -/* The strrchr() function returns a pointer to the last - * occurrence of the character c in the string s. - */ - -char *strrchr(const char *s, int c) -{ - if (s) - { - const char *p = &s[strlen(s) - 1]; - for (; p >= s; p--) - { - if (*p == c) - { - return (char*)p; - } - } - } - - return NULL; -} - diff --git a/nuttx/libc/string/lib_strspn.c b/nuttx/libc/string/lib_strspn.c deleted file mode 100644 index 6894b2b9dc..0000000000 --- a/nuttx/libc/string/lib_strspn.c +++ /dev/null @@ -1,66 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strspn.c - * - * Copyright (C) 2007, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: strspn - * - * Description: - * strspn() calculates the length of the initial segment of s which - * consists entirely of characters in accept. - * - ****************************************************************************/ - -size_t strspn(const char *s, const char *accept) -{ - size_t i; - for (i = 0; s[i] && strchr(accept, s[i]) != NULL; i++); - return i; -} diff --git a/nuttx/libc/string/lib_strstr.c b/nuttx/libc/string/lib_strstr.c deleted file mode 100644 index 02f4809d2b..0000000000 --- a/nuttx/libc/string/lib_strstr.c +++ /dev/null @@ -1,104 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strstr.c - * - * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use str 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 str binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer str - * 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 - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -char *strstr(const char *str, const char *substr) -{ - const char *candidate; /* Candidate in str with matching start character */ - char ch; /* First character of the substring */ - int len; /* The length of the substring */ - - /* Special case the empty substring */ - - len = strlen(substr); - ch = *substr; - - if (!ch) - { - /* We'll say that an empty substring matches at the beginning of - * the string - */ - - return (char*)str; - } - - /* Search for the substring */ - - candidate = str; - for (;;) - { - /* strchr() will return a pointer to the next occurrence of the - * character ch in the string - */ - - candidate = strchr(candidate, ch); - if (!candidate || strlen(candidate) < len) - { - /* First character of the substring does not appear in the string - * or the remainder of the string is not long enough to contain the - * substring. - */ - - return NULL; - } - - /* Check if this is the beginning of a matching substring */ - - if (strncmp(candidate, substr, len) == 0) - { - return (char*)candidate; - } - - /* No, find the next candidate after this one */ - - candidate++; - } - - /* Won't get here, but some compilers might complain */ - - return NULL; -} - diff --git a/nuttx/libc/string/lib_strtod.c b/nuttx/libc/string/lib_strtod.c deleted file mode 100644 index 58dfd6a292..0000000000 --- a/nuttx/libc/string/lib_strtod.c +++ /dev/null @@ -1,241 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strtod.c - * Convert string to double - * - * Copyright (C) 2002 Michael Ringgaard. All rights reserved. - * Copyright (C) 2006-2007 H. Peter Anvin. - * - * 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 of the project 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_HAVE_DOUBLE - -/**************************************************************************** - * Pre-processor definitions - ****************************************************************************/ - -/* These are predefined with GCC, but could be issues for other compilers. If - * not defined, an arbitrary big number is put in for now. These should be - * added to nuttx/compiler for your compiler. - */ - -#if !defined(__DBL_MIN_EXP__) || !defined(__DBL_MAX_EXP__) -# ifdef CONFIG_CPP_HAVE_WARNING -# warning "Size of exponent is unknown" -# endif -# undef __DBL_MIN_EXP__ -# define __DBL_MIN_EXP__ (-1021) -# undef __DBL_MAX_EXP__ -# define __DBL_MAX_EXP__ (1024) -#endif - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -static inline int is_real(double x) -{ - const double_t infinite = 1.0/0.0; - return (x < infinite) && (x >= -infinite); -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/***************************************************(************************ - * Name: strtod - * - * Description: - * Convert a string to a double value - * - ****************************************************************************/ - -double_t strtod(const char *str, char **endptr) -{ - double_t number; - int exponent; - int negative; - char *p = (char *) str; - double p10; - int n; - int num_digits; - int num_decimals; - const double_t infinite = 1.0/0.0; - - /* Skip leading whitespace */ - - while (isspace(*p)) - { - p++; - } - - /* Handle optional sign */ - - negative = 0; - switch (*p) - { - case '-': - negative = 1; /* Fall through to increment position */ - case '+': - p++; - } - - number = 0.; - exponent = 0; - num_digits = 0; - num_decimals = 0; - - /* Process string of digits */ - - while (isdigit(*p)) - { - number = number * 10. + (*p - '0'); - p++; - num_digits++; - } - - /* Process decimal part */ - - if (*p == '.') - { - p++; - - while (isdigit(*p)) - { - number = number * 10. + (*p - '0'); - p++; - num_digits++; - num_decimals++; - } - - exponent -= num_decimals; - } - - if (num_digits == 0) - { - set_errno(ERANGE); - return 0.0; - } - - /* Correct for sign */ - - if (negative) - { - number = -number; - } - - /* Process an exponent string */ - - if (*p == 'e' || *p == 'E') - { - /* Handle optional sign */ - - negative = 0; - switch(*++p) - { - case '-': - negative = 1; /* Fall through to increment pos */ - case '+': - p++; - } - - /* Process string of digits */ - - n = 0; - while (isdigit(*p)) - { - n = n * 10 + (*p - '0'); - p++; - } - - if (negative) - { - exponent -= n; - } - else - { - exponent += n; - } - } - - if (exponent < __DBL_MIN_EXP__ || - exponent > __DBL_MAX_EXP__) - { - set_errno(ERANGE); - return infinite; - } - - /* Scale the result */ - - p10 = 10.; - n = exponent; - if (n < 0) n = -n; - while (n) - { - if (n & 1) - { - if (exponent < 0) - { - number /= p10; - } - else - { - number *= p10; - } - } - n >>= 1; - p10 *= p10; - } - - if (!is_real(number)) - { - set_errno(ERANGE); - } - - if (endptr) - { - *endptr = p; - } - - return number; -} - -#endif /* CONFIG_HAVE_DOUBLE */ - diff --git a/nuttx/libc/string/lib_strtok.c b/nuttx/libc/string/lib_strtok.c deleted file mode 100644 index 85d6597d74..0000000000 --- a/nuttx/libc/string/lib_strtok.c +++ /dev/null @@ -1,87 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strtok.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static char *g_saveptr = NULL; - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: strtok - * - * Description: - * The strtok() function parses a string into a - * sequence of tokens. On the first call to strtok() the - * string to be parsed should be specified in 'str'. In - * each subsequent call that should parse the same string, - * 'str' should be NULL. - * - * The 'delim' argument specifies a set of characters that - * delimit the tokens in the parsed string. The caller - * may specify different strings in delim in successive - * calls that parse the same string. - * - * Each call to strtok() returns a pointer to a null- - * terminated string containing the next token. This - * string does not include the delimiting character. If - * no more tokens are found, strtok() returns NULL. - * - * A sequence of two or more contiguous delimiter - * characters in the parsed string is considered to be a - * single delimiter. Delimiter characters at the start or - * end of the string are ignored. The tokens returned by - * strtok() are always non-empty strings. - * - * Return - * strtok() returns a pointer to the next token, or NULL - * if there are no more tokens. - * - ****************************************************************************/ - -char *strtok(char *str, const char *delim) -{ - return strtok_r(str, delim, &g_saveptr); -} diff --git a/nuttx/libc/string/lib_strtokr.c b/nuttx/libc/string/lib_strtokr.c deleted file mode 100644 index c7845be642..0000000000 --- a/nuttx/libc/string/lib_strtokr.c +++ /dev/null @@ -1,157 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strtokr.c - * - * Copyright (C) 2007, 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: strtok_r - * - * Description: - * The strtok_r() function is a reentrant version strtok(). - * Like strtok(), it parses a string into a sequence of - * tokens. On the first call to strtok() the string to be - * parsed should be specified in 'str'. In each subsequent - * call that should parse the same string, 'str' should be - * NULL. - * - * The 'saveptr' argument is a pointer to a char * - * variable that is used internally by strtok_r() in - * order to maintain context between successive calls - * that parse the same string. - * - * On the first call to strtok_r(), 'str' should point to the - * string to be parsed, and the value of 'saveptr' is - * ignored. In subsequent calls, 'str' should be NULL, and - * saveptr should be unchanged since the previous call. - * - * The 'delim' argument specifies a set of characters that - * delimit the tokens in the parsed string. The caller - * may specify different strings in delim in successive - * calls that parse the same string. - * - * Each call to strtok_r() returns a pointer to a null- - * terminated string containing the next token. This - * string does not include the delimiting character. If - * no more tokens are found, strtok_r() returns NULL. - * - * A sequence of two or more contiguous delimiter - * characters in the parsed string is considered to be a - * single delimiter. Delimiter characters at the start or - * end of the string are ignored. The tokens returned by - * strtok() are always non-empty strings. - * - * Return - * strtok_r() returns a pointer to the next token, or NULL - * if there are no more tokens. - * - ****************************************************************************/ - -FAR char *strtok_r(FAR char *str, FAR const char *delim, FAR char **saveptr) -{ - char *pbegin; - char *pend = NULL; - - /* Decide if we are starting a new string or continuing from - * the point we left off. - */ - - if (str) - { - pbegin = str; - } - else if (saveptr && *saveptr) - { - pbegin = *saveptr; - } - else - { - return NULL; - } - - /* Find the beginning of the next token */ - - for (; - *pbegin && strchr(delim, *pbegin) != NULL; - pbegin++); - - /* If we are at the end of the string with nothing - * but delimiters found, then return NULL. - */ - - if (!*pbegin) - { - return NULL; - } - - /* Find the end of the token */ - - for (pend = pbegin + 1; - *pend && strchr(delim, *pend) == NULL; - pend++); - - - /* pend either points to the end of the string or to - * the first delimiter after the string. - */ - - if (*pend) - { - /* Turn the delimiter into a null terminator */ - - *pend++ = '\0'; - } - - /* Save the pointer where we left off and return the - * beginning of the token. - */ - - if (saveptr) - { - *saveptr = pend; - } - return pbegin; -} diff --git a/nuttx/libc/string/lib_strtol.c b/nuttx/libc/string/lib_strtol.c deleted file mode 100644 index 6ac0d6827d..0000000000 --- a/nuttx/libc/string/lib_strtol.c +++ /dev/null @@ -1,103 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strtol.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: strtol - * - * Description: - * The strtol() function converts the initial part of the string in - * nptr to a long integer value according to the given base, which must be - * between 2 and 36 inclusive, or be the special value 0. - * - * Warning: does not check for integer overflow! - * - ****************************************************************************/ - -long strtol(const char *nptr, char **endptr, int base) -{ - unsigned long accum = 0; - bool negate = false; - - if (nptr) - { - /* Skip leading spaces */ - - lib_skipspace(&nptr); - - /* Check for leading + or - */ - - if (*nptr == '-') - { - negate = true; - nptr++; - } - else if (*nptr == '+') - { - nptr++; - } - - /* Get the unsigned value */ - - accum = strtoul(nptr, endptr, base); - - /* Correct the sign of the result */ - - if (negate) - { - return -(long)accum; - } - } - return (long)accum; -} - diff --git a/nuttx/libc/string/lib_strtoll.c b/nuttx/libc/string/lib_strtoll.c deleted file mode 100644 index 99fba08eba..0000000000 --- a/nuttx/libc/string/lib_strtoll.c +++ /dev/null @@ -1,107 +0,0 @@ -/**************************************************************************** - * libc/string/lib_strtoll.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include "lib_internal.h" - -#ifdef CONFIG_HAVE_LONG_LONG - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: strtoll - * - * Description: - * The strtol() function converts the initial part of the string in - * nptr to a long long integer value according to the given base, which - * must be between 2 and 36 inclusive, or be the special value 0. - * - * Warning: does not check for integer overflow! - * - ****************************************************************************/ - -long long strtoll(const char *nptr, char **endptr, int base) -{ - unsigned long long accum = 0; - bool negate = false; - - if (nptr) - { - /* Skip leading spaces */ - - lib_skipspace(&nptr); - - /* Check for leading + or - */ - - if (*nptr == '-') - { - negate = true; - nptr++; - } - else if (*nptr == '+') - { - nptr++; - } - - /* Get the unsigned value */ - - accum = strtoull(nptr, endptr, base); - - /* Correct the sign of the result */ - - if (negate) - { - return -(long long)accum; - } - } - return (long long)accum; -} - -#endif - diff --git a/nuttx/libc/string/lib_strtoul.c b/nuttx/libc/string/lib_strtoul.c deleted file mode 100644 index 8f27ae3f2d..0000000000 --- a/nuttx/libc/string/lib_strtoul.c +++ /dev/null @@ -1,98 +0,0 @@ -/**************************************************************************** - * /libc/string/lib_strtoul.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include "lib_internal.h" - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: strtoul - * - * Description: - * The strtol() function converts the initial part of the string in - * nptr to a long unsigned integer value according to the given base, which - * must be between 2 and 36 inclusive, or be the special value 0. - * - * Warning: does not check for integer overflow! - * - ****************************************************************************/ - -unsigned long strtoul(const char *nptr, char **endptr, int base) -{ - unsigned long accum = 0; - int value; - - if (nptr) - { - /* Skip leading spaces */ - - lib_skipspace(&nptr); - - /* Check for unspecified base */ - - base = lib_checkbase(base, &nptr); - - /* Accumulate each "digit" */ - - while (lib_isbasedigit(*nptr, base, &value)) - { - accum = accum*base + value; - nptr++; - } - - /* Return the final pointer to the unused value */ - - if (endptr) - { - *endptr = (char *)nptr; - } - } - return accum; -} - diff --git a/nuttx/libc/string/lib_strtoull.c b/nuttx/libc/string/lib_strtoull.c deleted file mode 100644 index 4808114afe..0000000000 --- a/nuttx/libc/string/lib_strtoull.c +++ /dev/null @@ -1,100 +0,0 @@ -/**************************************************************************** - * /libc/string/lib_strtoull.c - * - * Copyright (C) 2009, 2010 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include - -#include - -#include "lib_internal.h" - -#ifdef CONFIG_HAVE_LONG_LONG - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: strtoull - * - * Description: - * The strtol() function converts the initial part of the string in - * nptr to a long unsigned integer value according to the given base, which - * must be between 2 and 36 inclusive, or be the special value 0. - * - ****************************************************************************/ - -unsigned long long strtoull(const char *nptr, char **endptr, int base) -{ - unsigned long long accum = 0; - int value; - - if (nptr) - { - /* Skip leading spaces */ - - lib_skipspace(&nptr); - - /* Check for unspecified base */ - - base = lib_checkbase(base, &nptr); - - /* Accumulate each "digit" */ - - while (lib_isbasedigit(*nptr, base, &value)) - { - accum = accum*base + value; - nptr++; - } - - /* Return the final pointer to the unused value */ - - if (endptr) - { - *endptr = (char *)nptr; - } - } - return accum; -} -#endif - diff --git a/nuttx/libc/string/lib_vikmemcpy.c b/nuttx/libc/string/lib_vikmemcpy.c deleted file mode 100644 index 28bf4a4ced..0000000000 --- a/nuttx/libc/string/lib_vikmemcpy.c +++ /dev/null @@ -1,348 +0,0 @@ -/**************************************************************************** - * File: libc/string/lib_vikmemcpy.c - * - * This is version of the optimized memcpy by Daniel Vik, adapted to the - * NuttX environment. - * - * Copyright (C) 1999-2010 Daniel Vik - * - * Adaptations include: - * - File name change - * - Use of types defined in stdint.h - * - Integration with the NuttX configuration system - * - Other cosmetic changes for consistency with NuttX coding standards - * - * This software is provided 'as-is', without any express or implied - * warranty. In no event will the authors be held liable for any - * damages arising from the use of this software. - * Permission is granted to anyone to use this software for any - * purpose, including commercial applications, and to alter it and - * redistribute it freely, subject to the following restrictions: - * - * 1. The origin of this software must not be misrepresented; you - * must not claim that you wrote the original software. If you - * use this software in a product, an acknowledgment in the - * use this software in a product, an acknowledgment in the - * product documentation would be appreciated but is not - * required. - * - * 2. Altered source versions must be plainly marked as such, and - * must not be misrepresented as being the original software. - * - * 3. This notice may not be removed or altered from any source - * distribution. - * - * Description: Implementation of the standard library function memcpy. - * This implementation of memcpy() is ANSI-C89 compatible. - * - * The following configuration options can be set: - * - * CONFIG_ENDIAN_BIG - * Uses processor with big endian addressing. Default is little endian. - * - * CONFIG_MEMCPY_PRE_INC_PTRS - * Use pre increment of pointers. Default is post increment of pointers. - * - * CONFIG_MEMCPY_INDEXED_COPY - * Copying data using array indexing. Using this option, disables the - * CONFIG_MEMCPY_PRE_INC_PTRS option. - * - * CONFIG_MEMCPY_64BIT - Compiles memcpy for 64 bit architectures - * - ****************************************************************************/ - -/**************************************************************************** - * Configuration definitions. - ****************************************************************************/ - -#define CONFIG_MEMCPY_INDEXED_COPY - -/******************************************************************** - * Included Files - *******************************************************************/ - -#include -#include - -#include -#include -#include - -/******************************************************************** - * Pre-processor Definitions - *******************************************************************/ - -/* Can't support CONFIG_MEMCPY_64BIT if the platform does not have 64-bit - * integer types. - */ - -#ifndef CONFIG_HAVE_LONG_LONG -# undef CONFIG_MEMCPY_64BIT -#endif - -/* Remove definitions when CONFIG_MEMCPY_INDEXED_COPY is defined */ - -#if defined (CONFIG_MEMCPY_INDEXED_COPY) -# if defined (CONFIG_MEMCPY_PRE_INC_PTRS) -# undef CONFIG_MEMCPY_PRE_INC_PTRS -# endif /* CONFIG_MEMCPY_PRE_INC_PTRS */ -#endif /* CONFIG_MEMCPY_INDEXED_COPY */ - -/* Definitions for pre and post increment of pointers */ - -#if defined (CONFIG_MEMCPY_PRE_INC_PTRS) - -# define START_VAL(x) (x)-- -# define INC_VAL(x) *++(x) -# define CAST_TO_U8(p, o) ((uint8_t*)p + o + TYPE_WIDTH) -# define WHILE_DEST_BREAK (TYPE_WIDTH - 1) -# define PRE_LOOP_ADJUST - (TYPE_WIDTH - 1) -# define PRE_SWITCH_ADJUST + 1 - -#else /* CONFIG_MEMCPY_PRE_INC_PTRS */ - -# define START_VAL(x) -# define INC_VAL(x) *(x)++ -# define CAST_TO_U8(p, o) ((uint8_t*)p + o) -# define WHILE_DEST_BREAK 0 -# define PRE_LOOP_ADJUST -# define PRE_SWITCH_ADJUST - -#endif /* CONFIG_MEMCPY_PRE_INC_PTRS */ - -/* Definitions for endian-ness */ - -#ifdef CONFIG_ENDIAN_BIG - -# define SHL << -# define SHR >> - -#else /* CONFIG_ENDIAN_BIG */ - -# define SHL >> -# define SHR << - -#endif /* CONFIG_ENDIAN_BIG */ - -/******************************************************************** - * Macros for copying words of different alignment. - * Uses incremening pointers. - *******************************************************************/ - -#define CP_INCR() \ -{ \ - INC_VAL(dstN) = INC_VAL(srcN); \ -} - -#define CP_INCR_SH(shl, shr) \ -{ \ - dstWord = srcWord SHL shl; \ - srcWord = INC_VAL(srcN); \ - dstWord |= srcWord SHR shr; \ - INC_VAL(dstN) = dstWord; \ -} - -/******************************************************************** - * Macros for copying words of different alignment. - * Uses array indexes. - *******************************************************************/ - -#define CP_INDEX(idx) \ -{ \ - dstN[idx] = srcN[idx]; \ -} - -#define CP_INDEX_SH(x, shl, shr) \ -{ \ - dstWord = srcWord SHL shl; \ - srcWord = srcN[x]; \ - dstWord |= srcWord SHR shr; \ - dstN[x] = dstWord; \ -} - -/******************************************************************** - * Macros for copying words of different alignment. - * Uses incremening pointers or array indexes depending on - * configuration. - *******************************************************************/ - -#if defined (CONFIG_MEMCPY_INDEXED_COPY) - -# define CP(idx) CP_INDEX(idx) -# define CP_SH(idx, shl, shr) CP_INDEX_SH(idx, shl, shr) - -# define INC_INDEX(p, o) ((p) += (o)) - -#else /* CONFIG_MEMCPY_INDEXED_COPY */ - -# define CP(idx) CP_INCR() -# define CP_SH(idx, shl, shr) CP_INCR_SH(shl, shr) - -# define INC_INDEX(p, o) - -#endif /* CONFIG_MEMCPY_INDEXED_COPY */ - -#define COPY_REMAINING(count) \ -{ \ - START_VAL(dst8); \ - START_VAL(src8); \ - \ - switch (count) \ - { \ - case 7: INC_VAL(dst8) = INC_VAL(src8); \ - case 6: INC_VAL(dst8) = INC_VAL(src8); \ - case 5: INC_VAL(dst8) = INC_VAL(src8); \ - case 4: INC_VAL(dst8) = INC_VAL(src8); \ - case 3: INC_VAL(dst8) = INC_VAL(src8); \ - case 2: INC_VAL(dst8) = INC_VAL(src8); \ - case 1: INC_VAL(dst8) = INC_VAL(src8); \ - case 0: \ - default: break; \ - } \ -} - -#define COPY_NO_SHIFT() \ -{ \ - UIntN* dstN = (UIntN*)(dst8 PRE_LOOP_ADJUST); \ - UIntN* srcN = (UIntN*)(src8 PRE_LOOP_ADJUST); \ - size_t length = count / TYPE_WIDTH; \ - \ - while (length & 7) \ - { \ - CP_INCR(); \ - length--; \ - } \ - \ - length /= 8; \ - \ - while (length--) \ - { \ - CP(0); \ - CP(1); \ - CP(2); \ - CP(3); \ - CP(4); \ - CP(5); \ - CP(6); \ - CP(7); \ - \ - INC_INDEX(dstN, 8); \ - INC_INDEX(srcN, 8); \ - } \ - \ - src8 = CAST_TO_U8(srcN, 0); \ - dst8 = CAST_TO_U8(dstN, 0); \ - \ - COPY_REMAINING(count & (TYPE_WIDTH - 1)); \ - \ - return dest; \ -} - -#define COPY_SHIFT(shift) \ -{ \ - UIntN* dstN = (UIntN*)((((UIntN)dst8) PRE_LOOP_ADJUST) & \ - ~(TYPE_WIDTH - 1)); \ - UIntN* srcN = (UIntN*)((((UIntN)src8) PRE_LOOP_ADJUST) & \ - ~(TYPE_WIDTH - 1)); \ - size_t length = count / TYPE_WIDTH; \ - UIntN srcWord = INC_VAL(srcN); \ - UIntN dstWord; \ - \ - while (length & 7) \ - { \ - CP_INCR_SH(8 * shift, 8 * (TYPE_WIDTH - shift)); \ - length--; \ - } \ - \ - length /= 8; \ - \ - while (length--) \ - { \ - CP_SH(0, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ - CP_SH(1, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ - CP_SH(2, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ - CP_SH(3, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ - CP_SH(4, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ - CP_SH(5, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ - CP_SH(6, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ - CP_SH(7, 8 * shift, 8 * (TYPE_WIDTH - shift)); \ - \ - INC_INDEX(dstN, 8); \ - INC_INDEX(srcN, 8); \ - } \ - \ - src8 = CAST_TO_U8(srcN, (shift - TYPE_WIDTH)); \ - dst8 = CAST_TO_U8(dstN, 0); \ - \ - COPY_REMAINING(count & (TYPE_WIDTH - 1)); \ - \ - return dest; \ -} - -/******************************************************************** - * Type Definitions - *******************************************************************/ - -#ifdef CONFIG_MEMCPY_64BIT -typedef uint64_t UIntN; -# define TYPE_WIDTH 8L -#else -typedef uint32_t UIntN; -# define TYPE_WIDTH 4L -#endif - -/******************************************************************** - * Public Functions - *******************************************************************/ -/******************************************************************** - * Name: memcpy - * - * Description: - * Copies count bytes from src to dest. No overlap check is performed. - * - * Input Parameters: - * dest - pointer to destination buffer - * src - pointer to source buffer - * count - number of bytes to copy - * - * Returned Value: - * A pointer to destination buffer - * - *******************************************************************/ - -void *memcpy(void *dest, const void *src, size_t count) -{ - uint8_t *dst8 = (uint8_t*)dest; - uint8_t *src8 = (uint8_t*)src; - - if (count < 8) - { - COPY_REMAINING(count); - return dest; - } - - START_VAL(dst8); - START_VAL(src8); - - while (((UIntN)dst8 & (TYPE_WIDTH - 1)) != WHILE_DEST_BREAK) - { - INC_VAL(dst8) = INC_VAL(src8); - count--; - } - - switch ((((UIntN)src8) PRE_SWITCH_ADJUST) & (TYPE_WIDTH - 1)) - { - case 0: COPY_NO_SHIFT(); break; - case 1: COPY_SHIFT(1); break; - case 2: COPY_SHIFT(2); break; - case 3: COPY_SHIFT(3); break; -#if TYPE_WIDTH > 4 - case 4: COPY_SHIFT(4); break; - case 5: COPY_SHIFT(5); break; - case 6: COPY_SHIFT(6); break; - case 7: COPY_SHIFT(7); break; -#endif - } - - return dest; -} diff --git a/nuttx/libc/termios/Make.defs b/nuttx/libc/termios/Make.defs deleted file mode 100644 index d20a5f95c7..0000000000 --- a/nuttx/libc/termios/Make.defs +++ /dev/null @@ -1,54 +0,0 @@ -############################################################################ -# libc/misc/Make.defs -# -# 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. -# -############################################################################ - -# termios.h support requires file descriptors and that CONFIG_SERIAL_TERMIOS -# is defined - -ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) -ifeq ($(CONFIG_SERIAL_TERMIOS),y) - -# Add the termios C files to the build - -CSRCS += lib_cfgetspeed.c lib_cfsetspeed.c lib_tcflush.c -CSRCS += lib_tcgetattr.c lib_tcsetattr.c - -# Add the termios directory to the build - -DEPPATH += --dep-path termios -VPATH += termios - -endif -endif - diff --git a/nuttx/libc/termios/lib_cfgetspeed.c b/nuttx/libc/termios/lib_cfgetspeed.c deleted file mode 100644 index da10daac1e..0000000000 --- a/nuttx/libc/termios/lib_cfgetspeed.c +++ /dev/null @@ -1,93 +0,0 @@ -/**************************************************************************** - * libc/termios/lib_cfgetspeed.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: cfgetspeed - * - * Descripton: - * The cfgetspeed() function is a non-POSIX function will extract the baud - * from the termios structure to which the termiosp argument points. - * - * This function will return exactly the value in the termios data - * structure, without interpretation. - * - * NOTE 1: NuttX does not control input/output baud independently. Both - * must be the same. The POSIX standard interfaces, cfisetispeed() and - * cfisetospeed() are defined to be cfgetspeed() in termios.h. - * NOTE 2. In Nuttx, the speed_t is defined to be uint32_t and the baud - * encodings of termios.h are the actual baud values themselves. Therefore, - * any baud value may be returned here... not just those enumerated in - * termios.h - * - * Input Parameters: - * termiosp - The termiosp argument is a pointer to a termios structure. - * - * Returned Value: - * Encoded baud value from the termios structure. - * - ****************************************************************************/ - -speed_t cfgetspeed(FAR const struct termios *termiosp) -{ - DEBUGASSERT(termiosp); - return termiosp->c_speed; -} diff --git a/nuttx/libc/termios/lib_cfsetspeed.c b/nuttx/libc/termios/lib_cfsetspeed.c deleted file mode 100644 index a2a9475c4b..0000000000 --- a/nuttx/libc/termios/lib_cfsetspeed.c +++ /dev/null @@ -1,116 +0,0 @@ -/**************************************************************************** - * libc/termios/lib_cfsetspeed.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: cfsetspeed - * - * Descripton: - * The cfsetspeed() function is a non-POSIX function that sets the baud - * stored in the structure pointed to by termiosp to speed. - * - * There is no effect on the baud set in the hardware until a subsequent - * successful call to tcsetattr() on the same termios structure. - * - * NOTE 1: NuttX does not control input/output baud independently. Both - * must be the same. The POSIX standard interfaces, cfisetispeed() and - * cfisetospeed() are defined to be cfsetspeed() in termios.h. - * - * NOTE 3: A consequence of NOTE 1 is that you should never attempt to - * set the input and output baud to different values. - * - * Also, the following POSIX requirement cannot be supported: "If the input - * baud rate stored in the termios structure pointed to by termios_p is 0, - * the input baud rate given to the hardware will be the same as the output - * baud rate stored in the termios structure." - * - * NOTE 2. In Nuttx, the speed_t is defined to be uint32_t and the baud - * encodings of termios.h are the actual baud values themselves. Therefore, - * any baud value can be provided as the speed argument here. However, if - * you do so, your code will *NOT* be portable to other environments where - * speed_t is smaller and where the termios.h baud values are encoded! To - * avoid portability issues, use the baud definitions in termios.h! - * - * Linux, for example, would require this (also non-portable) sequence: - * - * cfsetispeed(termiosp, BOTHER); - * termiosp->c_ispeed = baud; - * - * cfsetospeed(termiosp, BOTHER); - * termiosp->c_ospeed = baud; - * - * Input Parameters: - * termiosp - The termiosp argument is a pointer to a termios structure. - * speed - The new input speed - * - * Returned Value: - * Baud is not checked... OK is always returned (this is non-standard - * behavior). - * - ****************************************************************************/ - -int cfsetspeed(FAR struct termios *termiosp, speed_t speed) -{ - DEBUGASSERT(termiosp); - termiosp->c_speed = speed; - return OK; -} diff --git a/nuttx/libc/termios/lib_tcflush.c b/nuttx/libc/termios/lib_tcflush.c deleted file mode 100644 index 1a9710f6a0..0000000000 --- a/nuttx/libc/termios/lib_tcflush.c +++ /dev/null @@ -1,88 +0,0 @@ -/**************************************************************************** - * libc/termios/lib_tcflush.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: tcflush - * - * Descripton: - * Function for flushing a terminal/serial device - * - * Input Parameters: - * fd - The 'fd' argument is an open file descriptor associated with a terminal. - * cmd - The TCFLSH ioctl argument. - * - * Returned Value: - * Upon successful completion, 0 is returned. Otherwise, -1 is returned and - * errno is set to indicate the error. - * - ****************************************************************************/ - -int tcflush(int fd, int cmd) -{ - return ioctl(fd, TCFLSH, (unsigned long)cmd); -} diff --git a/nuttx/libc/termios/lib_tcgetattr.c b/nuttx/libc/termios/lib_tcgetattr.c deleted file mode 100644 index e8d3112603..0000000000 --- a/nuttx/libc/termios/lib_tcgetattr.c +++ /dev/null @@ -1,93 +0,0 @@ -/**************************************************************************** - * libc/termios/lib_tcgetattr.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: tcgetattr - * - * Descripton: - * The tcgetattr() function gets the parameters associated with the - * terminal referred to by 'fd' and stores them in the termios structure - * referenced by 'termiosp'. - * - * Input Parameters: - * fd - The 'fd' argument is an open file descriptor associated with a terminal. - * termiosp - The termiosp argument is a pointer to a termios structure. - * - * Returned Value: - * Upon successful completion, 0 is returned. Otherwise, -1 is returned and - * errno is set to indicate the error. The following errors may be reported: - * - * - EBADF: The 'fd' argument is not a valid file descriptor. - * - ENOTTY: The file associated with 'fd' is not a terminal. - * - ****************************************************************************/ - -int tcgetattr(int fd, FAR struct termios *termiosp) -{ - return ioctl(fd, TCGETS, (unsigned long)termiosp); -} diff --git a/nuttx/libc/termios/lib_tcsetattr.c b/nuttx/libc/termios/lib_tcsetattr.c deleted file mode 100644 index 901f2a1368..0000000000 --- a/nuttx/libc/termios/lib_tcsetattr.c +++ /dev/null @@ -1,122 +0,0 @@ -/**************************************************************************** - * libc/termios/lib_tcsetattr.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: tcsetattr - * - * Descripton: - * The tcsetattr() function sets the parameters associated with the - * terminal referred to by the open file descriptor 'fd' from the termios - * structure referenced by 'termiop' as follows: - * - * If 'options' is TCSANOW, the change will occur immediately. - * - * If 'options' is TCSADRAIN, the change will occur after all output - * written to 'fd' is transmitted. This function should be used when changing - * parameters that affect output. - * - * If 'options' is TCSAFLUSH, the change will occur after all - * output written to 'fd' is transmitted, and all input so far received but - * not read will be discarded before the change is made. - * - * The tcsetattr() function will return successfully if it was able to - * perform any of the requested actions, even if some of the requested - * actions could not be performed. It will set all the attributes that - * implementation supports as requested and leave all the attributes not - * supported by the implementation unchanged. If no part of the request - * can be honoured, it will return -1 and set errno to EINVAL. - * - * The effect of tcsetattr() is undefined if the value of the termios - * structure pointed to by 'termiop' was not derived from the result of - * a call to tcgetattr() on 'fd'; an application should modify only fields - * and flags defined by this specification between the call to tcgetattr() - * and tcsetattr(), leaving all other fields and flags unmodified. - * - * Returned Value: - * - * Upon successful completion, 0 is returned. Otherwise, -1 is returned - * and errno is set to indicate the error. The following errors may be - * reported: - * - * - EBADF: The 'fd' argument is not a valid file descriptor. - * - EINTR: A signal interrupted tcsetattr(). - * - EINVAL: The 'options' argument is not a supported value, or - * an attempt was made to change an attribute represented in the - * termios structure to an unsupported value. - * - ENOTTY: The file associated with 'fd' is not a terminal. - * - ****************************************************************************/ - -int tcsetattr(int fd, int options, FAR const struct termios *termiosp) -{ - if (options == TCSANOW) - { - return ioctl(fd, TCSETS, (unsigned long)termiosp); - } - return -ENOSYS; -} diff --git a/nuttx/libc/time/Make.defs b/nuttx/libc/time/Make.defs deleted file mode 100644 index 4848813d11..0000000000 --- a/nuttx/libc/time/Make.defs +++ /dev/null @@ -1,44 +0,0 @@ -############################################################################ -# libc/time/Make.defs -# -# 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. -# -############################################################################ - -# Add the time C files to the build - -CSRCS += lib_mktime.c lib_gmtime.c lib_gmtimer.c lib_strftime.c \ - lib_calendar2utc.c lib_daysbeforemonth.c lib_isleapyear.c lib_time.c - -# Add the time directory to the build - -DEPPATH += --dep-path time -VPATH += :time diff --git a/nuttx/libc/time/lib_calendar2utc.c b/nuttx/libc/time/lib_calendar2utc.c deleted file mode 100644 index 1b8c40a9ea..0000000000 --- a/nuttx/libc/time/lib_calendar2utc.c +++ /dev/null @@ -1,209 +0,0 @@ -/**************************************************************************** - * libc/time/lib_calendar2utc.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: clock_gregorian2utc, clock_julian2utc - * - * Description: - * UTC conversion routines. These conversions are based - * on algorithms from p. 604 of Seidelman, P. K. 1992. - * Explanatory Supplement to the Astronomical Almanac. - * University Science Books, Mill Valley. - * - ****************************************************************************/ - -#ifdef CONFIG_GREGORIAN_TIME -static time_t clock_gregorian2utc(int year, int month, int day) -{ - int temp; - - /* temp = (month - 14)/12; */ - - temp = (month <= 2 ? -1:0); - - return (1461*(year + 4800 + temp))/4 - + (367*(month - 2 - 12*temp))/12 - - (3*((year + 4900 + temp)/100))/4 + day - 32075; -} - -#ifdef CONFIG_JULIAN_TIME -static time_t clock_julian2utc(int year, int month, int day) -{ - return 367*year - - (7*(year + 5001 + (month-9)/7))/4 - + (275*month)/9 - + day + 1729777; -} -#endif /* CONFIG_JULIAN_TIME */ -#endif /* CONFIG_GREGORIAN_TIME */ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: clock_calendar2utc - * - * Description: - * Calendar/UTC conversion based on algorithms from p. 604 - * of Seidelman, P. K. 1992. Explanatory Supplement to - * the Astronomical Almanac. University Science Books, - * Mill Valley. - * - ****************************************************************************/ - -#ifdef CONFIG_GREGORIAN_TIME -time_t clock_calendar2utc(int year, int month, int day) -{ - int dyear; -#ifdef CONFIG_JULIAN_TIME - bool isgreg; -#endif /* CONFIG_JULIAN_TIME */ - - /* Correct year & month ranges. Shift month into range 1-12 */ - - dyear = (month-1) / 12; - month -= 12 * dyear; - year += dyear; - - if (month < 1) - { - month += 12; - year -= 1; - } - -#ifdef CONFIG_JULIAN_TIME - /* Determine which calendar to use */ - - if (year > GREG_YEAR) - { - isgreg = true; - } - else if (year < GREG_YEAR) - { - isgreg = false; - } - else if (month > GREG_MONTH) - { - isgreg = true; - } - else if (month < GREG_MONTH) - { - isgreg = false; - } - else - { - isgreg = (day >= GREG_DAY); - } - - /* Calculate and return date */ - - if (isgreg) - { - return clock_gregorian2utc(year, month, day) - JD_OF_EPOCH; - } - else - { - return clock_julian2utc (year, month, day) - JD_OF_EPOCH; - } - -#else /* CONFIG_JULIAN_TIME */ - - return clock_gregorian2utc(year, month, day) - JD_OF_EPOCH; - -#endif /* CONFIG_JULIAN_TIME */ -} -#else - -/* A highly simplified version that only handles days in the time - * since Jan 1, 1970. - */ - -time_t clock_calendar2utc(int year, int month, int day) -{ - struct tm t; - - /* mktime can (kind of) do this */ - - t.tm_year = year; - t.tm_mon = month; - t.tm_mday = day; - t.tm_hour = 0; - t.tm_min = 0; - t.tm_sec = 0; - return mktime(&t); -} -#endif /* CONFIG_GREGORIAN_TIME */ - diff --git a/nuttx/libc/time/lib_daysbeforemonth.c b/nuttx/libc/time/lib_daysbeforemonth.c deleted file mode 100644 index 28f4d67a97..0000000000 --- a/nuttx/libc/time/lib_daysbeforemonth.c +++ /dev/null @@ -1,102 +0,0 @@ -/**************************************************************************** - * libc/time/lib_daysbeforemonth.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -uint16_t g_daysbeforemonth[13] = -{ - 0, 31, 59, 90, 120, 151, 181, 212, 243, 273, 304, 334, 365 -}; - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: clock_daysbeforemonth - * - * Description: - * Get the number of days that occurred before the beginning of the month. - * - ****************************************************************************/ - -int clock_daysbeforemonth(int month, bool leapyear) -{ - int retval = g_daysbeforemonth[month]; - if (month >= 2 && leapyear) - { - retval++; - } - return retval; -} - - diff --git a/nuttx/libc/time/lib_gmtime.c b/nuttx/libc/time/lib_gmtime.c deleted file mode 100644 index 7a4d0f5e14..0000000000 --- a/nuttx/libc/time/lib_gmtime.c +++ /dev/null @@ -1,93 +0,0 @@ -/**************************************************************************** - * libc/time/lib_gmtime.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/************************************************************************** - * Public Constant Data - **************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/************************************************************************** - * Private Variables - **************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: gmtime - * - * Description: - * Similar to gmtime_r, but not thread-safe - * - ****************************************************************************/ - -struct tm *gmtime(const time_t *timer) -{ - static struct tm tm; - return gmtime_r(timer, &tm); -} - diff --git a/nuttx/libc/time/lib_gmtimer.c b/nuttx/libc/time/lib_gmtimer.c deleted file mode 100644 index d986205276..0000000000 --- a/nuttx/libc/time/lib_gmtimer.c +++ /dev/null @@ -1,355 +0,0 @@ -/**************************************************************************** - * libc/time/lib_gmtimer.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -#define SEC_PER_MIN ((time_t)60) -#define SEC_PER_HOUR ((time_t)60 * SEC_PER_MIN) -#define SEC_PER_DAY ((time_t)24 * SEC_PER_HOUR) - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/* Calendar/UTC conversion routines */ - -static void clock_utc2calendar(time_t utc, int *year, int *month, int *day); -#ifdef CONFIG_GREGORIAN_TIME -static void clock_utc2gregorian (time_t jdn, int *year, int *month, int *day); - -#ifdef CONFIG_JULIAN_TIME -static void clock_utc2julian(time_t jdn, int *year, int *month, int *day); -#endif /* CONFIG_JULIAN_TIME */ -#endif /* CONFIG_GREGORIAN_TIME */ - -/************************************************************************** - * Public Constant Data - **************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/************************************************************************** - * Private Variables - **************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: clock_calendar2utc, clock_gregorian2utc, - * and clock_julian2utc - * - * Description: - * Calendar to UTC conversion routines. These conversions - * are based on algorithms from p. 604 of Seidelman, P. K. - * 1992. Explanatory Supplement to the Astronomical - * Almanac. University Science Books, Mill Valley. - * - ****************************************************************************/ - -#ifdef CONFIG_GREGORIAN_TIME -static void clock_utc2calendar(time_t utc, int *year, int *month, int *day) -{ -#ifdef CONFIG_JULIAN_TIME - - if (utc >= GREG_DUTC) - { - clock_utc2gregorian(utc + JD_OF_EPOCH, year, month, day); - } - else - { - clock_utc2julian (utc + JD_OF_EPOCH, year, month, day); - } - -#else /* CONFIG_JULIAN_TIME */ - - clock_utc2gregorian(utc + JD_OF_EPOCH, year, month, day); - -#endif /* CONFIG_JULIAN_TIME */ -} - -static void clock_utc2gregorian(time_t jd, int *year, int *month, int *day) -{ - long l, n, i, j, d, m, y; - - l = jd + 68569; - n = (4*l) / 146097; - l = l - (146097*n + 3)/4; - i = (4000*(l+1))/1461001; - l = l - (1461*i)/4 + 31; - j = (80*l)/2447; - d = l - (2447*j)/80; - l = j/11; - m = j + 2 - 12*l; - y = 100*(n-49) + i + l; - - *year = y; - *month = m; - *day = d; -} - -#ifdef CONFIG_JULIAN_TIME - -static void clock_utc2julian(time_t jd, int *year, int *month, int *day) -{ - long j, k, l, n, d, i, m, y; - - j = jd + 1402; - k = (j-1)/1461; - l = j - 1461*k; - n = (l-1)/365 - l/1461; - i = l - 365*n + 30; - j = (80*i)/2447; - d = i - (2447*j)/80; - i = j/11; - m = j + 2 - 12*i; - y = 4*k + n + i - 4716; - - *year = y; - *month = m; - *day = d; -} - -#endif /* CONFIG_JULIAN_TIME */ -#else/* CONFIG_GREGORIAN_TIME */ - -/* Only handles dates since Jan 1, 1970 */ - -static void clock_utc2calendar(time_t days, int *year, int *month, int *day) -{ - int value; - int min; - int max; - int tmp; - bool leapyear; - - /* There is one leap year every four years, so we can get close with the - * following: - */ - - value = days / (4*365 + 1); /* Number of 4-years periods since the epoch*/ - days -= value * (4*365 + 1); /* Remaining days */ - value <<= 2; /* Years since the epoch */ - - /* Then we will brute force the next 0-3 years */ - - for (;;) - { - /* Is this year a leap year (we'll need this later too) */ - - leapyear = clock_isleapyear(value + 1970); - - /* Get the number of days in the year */ - - tmp = (leapyear ? 366 : 365); - - /* Do we have that many days? */ - - if (days >= tmp) - { - /* Yes.. bump up the year */ - - value++; - days -= tmp; - } - else - { - /* Nope... then go handle months */ - - break; - } - } - - /* At this point, value has the year and days has number days into this year */ - - *year = 1970 + value; - - /* Handle the month (zero based) */ - - min = 0; - max = 11; - - do - { - /* Get the midpoint */ - - value = (min + max) >> 1; - - /* Get the number of days that occurred before the beginning of the month - * following the midpoint. - */ - - tmp = clock_daysbeforemonth(value + 1, leapyear); - - /* Does the number of days before this month that equal or exceed the - * number of days we have remaining? - */ - - if (tmp > days) - { - /* Yes.. then the month we want is somewhere from 'min' and to the - * midpoint, 'value'. Could it be the midpoint? - */ - - tmp = clock_daysbeforemonth(value, leapyear); - if (tmp > days) - { - /* No... The one we want is somewhere between min and value-1 */ - - max = value - 1; - } - else - { - /* Yes.. 'value' contains the month that we want */ - - break; - } - } - else - { - /* No... The one we want is somwhere between value+1 and max */ - - min = value + 1; - } - - /* If we break out of the loop because min == max, then we want value - * to be equal to min == max. - */ - - value = min; - } - while (min < max); - - /* The selected month number is in value. Subtract the number of days in the - * selected month - */ - - days -= clock_daysbeforemonth(value, leapyear); - - /* At this point, value has the month into this year (zero based) and days has - * number of days into this month (zero based) - */ - - *month = value + 1; /* 1-based */ - *day = days + 1; /* 1-based */ -} - -#endif /* CONFIG_GREGORIAN_TIME */ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: gmtime_r - * - * Description: - * Time conversion (based on the POSIX API) - * - ****************************************************************************/ - -FAR struct tm *gmtime_r(FAR const time_t *timer, FAR struct tm *result) -{ - time_t epoch; - time_t jdn; - int year; - int month; - int day; - int hour; - int min; - int sec; - - /* Get the seconds since the EPOCH */ - - epoch = *timer; - sdbg("timer=%d\n", (int)epoch); - - /* Convert to days, hours, minutes, and seconds since the EPOCH */ - - jdn = epoch / SEC_PER_DAY; - epoch -= SEC_PER_DAY * jdn; - - hour = epoch / SEC_PER_HOUR; - epoch -= SEC_PER_HOUR * hour; - - min = epoch / SEC_PER_MIN; - epoch -= SEC_PER_MIN * min; - - sec = epoch; - - sdbg("hour=%d min=%d sec=%d\n", - (int)hour, (int)min, (int)sec); - - /* Convert the days since the EPOCH to calendar day */ - - clock_utc2calendar(jdn, &year, &month, &day); - - sdbg("jdn=%d year=%d month=%d day=%d\n", - (int)jdn, (int)year, (int)month, (int)day); - - /* Then return the struct tm contents */ - - result->tm_year = (int)year - 1900; /* Relative to 1900 */ - result->tm_mon = (int)month - 1; /* zero-based */ - result->tm_mday = (int)day; /* one-based */ - result->tm_hour = (int)hour; - result->tm_min = (int)min; - result->tm_sec = (int)sec; - - return result; -} - diff --git a/nuttx/libc/time/lib_isleapyear.c b/nuttx/libc/time/lib_isleapyear.c deleted file mode 100644 index 386e205b2e..0000000000 --- a/nuttx/libc/time/lib_isleapyear.c +++ /dev/null @@ -1,88 +0,0 @@ -/**************************************************************************** - * libc/time/lib_isleapyear.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: clock_isleapyear - * - * Description: - * Return true if the specified year is a leap year - * - ****************************************************************************/ - -int clock_isleapyear(int year) -{ - return year % 400 ? (year % 100 ? (year % 4 ? 0 : 1) : 0) : 1; -} - diff --git a/nuttx/libc/time/lib_mktime.c b/nuttx/libc/time/lib_mktime.c deleted file mode 100644 index 25254d70e5..0000000000 --- a/nuttx/libc/time/lib_mktime.c +++ /dev/null @@ -1,141 +0,0 @@ -/**************************************************************************** - * libc/time/lib_mktime.c - * - * Copyright (C) 2007, 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: mktime - * - * Description: - * Time conversion (based on the POSIX API) - * - ****************************************************************************/ - -#ifdef CONFIG_GREGORIAN_TIME -time_t mktime(const struct tm *tp) -{ - time_t ret; - time_t jdn; - - /* Get the EPOCH-relative julian date from the calendar year, - * month, and date - */ - - jdn = clock_calendar2utc(tp->tm_year+1900, tp->tm_mon+1, tp->tm_mday); - sdbg("jdn=%d tm_year=%d tm_mon=%d tm_mday=%d\n", - (int)jdn, tp->tm_year, tp->tm_mon, tp->tm_mday); - - /* Return the seconds into the julian day. */ - - ret = ((jdn*24 + tp->tm_hour)*60 + tp->tm_min)*60 + tp->tm_sec; - sdbg("ret=%d tm_hour=%d tm_min=%d tm_sec=%d\n", - (int)ret, tp->tm_hour, tp->tm_min, tp->tm_sec); - - return ret; -} -#else - -/* Simple version that only works for dates within a (relatively) small range - * from the epoch. It does not handle earlier days or longer days where leap - * seconds, etc. apply. - */ - -time_t mktime(const struct tm *tp) -{ - unsigned int days; - - /* Years since epoch in units of days (ignoring leap years). */ - - days = (tp->tm_year - 70) * 365; - - /* Add in the extra days for the leap years prior to the current year. */ - - days += (tp->tm_year - 69) >> 2; - - /* Add in the days up to the beginning of this month. */ - - days += (time_t)clock_daysbeforemonth(tp->tm_mon, clock_isleapyear(tp->tm_year + 1900)); - - /* Add in the days since the beginning of this month (days are 1-based). */ - - days += tp->tm_mday - 1; - - /* Then convert the seconds and add in hours, minutes, and seconds */ - - return ((days * 24 + tp->tm_hour) * 60 + tp->tm_min) * 60 + tp->tm_sec; -} -#endif /* CONFIG_GREGORIAN_TIME */ - diff --git a/nuttx/libc/time/lib_strftime.c b/nuttx/libc/time/lib_strftime.c deleted file mode 100644 index 3b0c8dd8f3..0000000000 --- a/nuttx/libc/time/lib_strftime.c +++ /dev/null @@ -1,398 +0,0 @@ -/**************************************************************************** - * libc/time/lib_strftime.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include - -#include -#include -#include - -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static const char * const g_abbrevmonthname[12] = -{ - "Jan", "Feb", "Mar", "Apr", "May", "Jun", - "Jul", "Aug", "Sep", "Oct", "Nov", "Dec" -}; - -static const char * const g_monthname[12] = -{ - "January", "February", "March", "April", "May", "June", - "July", "August", "September", "October", "November", "December" -}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: strftime - * - * Description: - * The strftime() function formats the broken-down time tm according to - * the format specification format and places the result in the character - * array s of size max. - * - * Ordinary characters placed in the format string are copied to s without - * conversion. Conversion specifications are introduced by a '%' charac- - * ter, and terminated by a conversion specifier character, and are - * replaced in s as follows: - * - * %b The abbreviated month name according to the current locale. - * %B The full month name according to the current locale. - * %C The century number (year/100) as a 2-digit integer. (SU) - * %d The day of the month as a decimal number (range 01 to 31). - * %e Like %d, the day of the month as a decimal number, but a leading - * zero is replaced by a space. - * %h Equivalent to %b. (SU) - * %H The hour as a decimal number using a 24-hour clock (range 00 to 23). - * %I The hour as a decimal number using a 12-hour clock (range 01 to 12). - * %j The day of the year as a decimal number (range 001 to 366). - * %k The hour (24-hour clock) as a decimal number (range 0 to 23); - * single digits are preceded by a blank. (See also %H.) (TZ) - * %l The hour (12-hour clock) as a decimal number (range 1 to 12); - * single digits are preceded by a blank. (See also %I.) (TZ) - * %m The month as a decimal number (range 01 to 12). - * %M The minute as a decimal number (range 00 to 59). - * %n A newline character. (SU) - * %p Either "AM" or "PM" according to the given time value, or the - * corresponding strings for the current locale. Noon is treated - * as "PM" and midnight as "AM". - * %P Like %p but in lowercase: "am" or "pm" or a corresponding string - * for the current locale. (GNU) - * %s The number of seconds since the Epoch, that is, since 1970-01-01 - * 00:00:00 UTC. (TZ) - * %S The second as a decimal number (range 00 to 60). (The range is - * up to 60 to allow for occasional leap seconds.) - * %t A tab character. (SU) - * %y The year as a decimal number without a century (range 00 to 99). - * %Y The year as a decimal number including the century. - * %% A literal '%' character. - * - * Returned Value: - * The strftime() function returns the number of characters placed in the - * array s, not including the terminating null byte, provided the string, - * including the terminating null byte, fits. Otherwise, it returns 0, - * and the contents of the array is undefined. - * - ****************************************************************************/ - -size_t strftime(char *s, size_t max, const char *format, const struct tm *tm) -{ - const char *str; - char *dest = s; - int chleft = max; - int value; - int len; - - while (*format && chleft > 0) - { - /* Just copy regular characters */ - - if (*format != '%') - { - *dest++ = *format++; - chleft--; - continue; - } - - /* Handle the format character */ - - format++; - len = 0; - - switch (*format++) - { - /* %a: A three-letter abbreviation for the day of the week. */ - /* %A: The full name for the day of the week. */ - - case 'a': - case 'A': - { - len = snprintf(dest, chleft, "Day"); /* Not supported */ - } - break; - - /* %h: Equivalent to %b */ - - case 'h': - - /* %b: The abbreviated month name according to the current locale. */ - - case 'b': - { - if (tm->tm_mon < 12) - { - str = g_abbrevmonthname[tm->tm_mon]; - len = snprintf(dest, chleft, "%s", str); - } - } - break; - - /* %B: The full month name according to the current locale. */ - - case 'B': - { - if (tm->tm_mon < 12) - { - str = g_monthname[tm->tm_mon]; - len = snprintf(dest, chleft, "%s", str); - } - } - break; - - /* %y: The year as a decimal number without a century (range 00 to 99). */ - - case 'y': - - /* %C: The century number (year/100) as a 2-digit integer. */ - - case 'C': - { - len = snprintf(dest, chleft, "%02d", tm->tm_year % 100); - } - break; - - /* %d: The day of the month as a decimal number (range 01 to 31). */ - - case 'd': - { - len = snprintf(dest, chleft, "%02d", tm->tm_mday); - } - break; - - /* %e: Like %d, the day of the month as a decimal number, but a leading - * zero is replaced by a space. - */ - - case 'e': - { - len = snprintf(dest, chleft, "%2d", tm->tm_mday); - } - break; - - /* %H: The hour as a decimal number using a 24-hour clock (range 00 to 23). */ - - case 'H': - { - len = snprintf(dest, chleft, "%02d", tm->tm_hour); - } - break; - - /* %I: The hour as a decimal number using a 12-hour clock (range 01 to 12). */ - - case 'I': - { - len = snprintf(dest, chleft, "%02d", tm->tm_hour % 12); - } - break; - - /* %j: The day of the year as a decimal number (range 001 to 366). */ - - case 'j': - { - if (tm->tm_mon < 12) - { - value = clock_daysbeforemonth(tm->tm_mon, clock_isleapyear(tm->tm_year)) + tm->tm_mday; - len = snprintf(dest, chleft, "%03d", value); - } - } - break; - - /* %k: The hour (24-hour clock) as a decimal number (range 0 to 23); - * single digits are preceded by a blank. - */ - - case 'k': - { - len = snprintf(dest, chleft, "%2d", tm->tm_hour); - } - break; - - /* %l: The hour (12-hour clock) as a decimal number (range 1 to 12); - * single digits are preceded by a blank. - */ - - case 'l': - { - len = snprintf(dest, chleft, "%2d", tm->tm_hour % 12); - } - break; - - /* %m: The month as a decimal number (range 01 to 12). */ - - case 'm': - { - len = snprintf(dest, chleft, "%02d", tm->tm_mon + 1); - } - break; - - /* %M: The minute as a decimal number (range 00 to 59). */ - - case 'M': - { - len = snprintf(dest, chleft, "%02d", tm->tm_min); - } - break; - - /* %n: A newline character. */ - - case 'n': - { - *dest = '\n'; - len = 1; - } - break; - - /* %p: Either "AM" or "PM" according to the given time value. */ - - case 'p': - { - if (tm->tm_hour >= 12) - { - str = "PM"; - } - else - { - str = "AM"; - } - len = snprintf(dest, chleft, "%s", str); - } - break; - - /* %P: Like %p but in lowercase: "am" or "pm" */ - - case 'P': - { - if (tm->tm_hour >= 12) - { - str = "pm"; - } - else - { - str = "am"; - } - len = snprintf(dest, chleft, "%s", str); - } - break; - - /* %s: The number of seconds since the Epoch, that is, since 1970-01-01 - * 00:00:00 UTC. - */ - - case 's': - { - len = snprintf(dest, chleft, "%d", mktime(tm)); - } - break; - - /* %S: The second as a decimal number (range 00 to 60). (The range is - * up to 60 to allow for occasional leap seconds.) - */ - - case 'S': - { - len = snprintf(dest, chleft, "%02d", tm->tm_sec); - } - break; - - /* %t: A tab character. */ - - case 't': - { - *dest = '\t'; - len = 1; - } - break; - - /* %Y: The year as a decimal number including the century. */ - - case 'Y': - { - len = snprintf(dest, chleft, "%04d", tm->tm_year + 1900); - } - break; - - /* %%: A literal '%' character. */ - - case '%': - { - *dest = '%'; - len = 1; - } - break; - } - - /* Update counts and pointers */ - - dest += len; - chleft -= len; - } - - return max - chleft; -} diff --git a/nuttx/libc/time/lib_time.c b/nuttx/libc/time/lib_time.c deleted file mode 100644 index 673f6fdcdd..0000000000 --- a/nuttx/libc/time/lib_time.c +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * libc/time/lib_time.c - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#ifndef CONFIG_DISABLE_CLOCK - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: time - * - * Description: - * Get the current calendar time as a time_t object. The function returns - * this value, and if the argument is not a null pointer, the value is also - * set to the object pointed by tloc. - * - * Note that this function is just a thin wrapper around gettimeofday() - * and is provided for compatibility. gettimeofday() is the preffered way - * to obtain system time. - * - * Parameters: - * Pointer to an object of type time_t, where the time value is stored. - * Alternativelly, this parameter can be a null pointer, in which case the - * parameter is not used, but a time_t object is still returned by the - * function. - * - * Return Value: - * The current calendar time as a time_t object. If the argument is not - * a null pointer, the return value is the same as the one stored in the - * location pointed by the argument. - * - * If the function could not retrieve the calendar time, it returns a -1 - * value. - * - ****************************************************************************/ - -time_t time(time_t *tloc) -{ - struct timeval tp; - int ret; - - /* Get the current time from the system */ - - ret = gettimeofday(&tp, NULL); - if (ret == OK) - { - /* Return the seconds since the epoch */ - - if (tloc) - { - *tloc = tp.tv_sec; - } - - return tp.tv_sec; - } - - return (time_t)ERROR; -} - -#endif /* !CONFIG_DISABLE_CLOCK */ diff --git a/nuttx/libc/unistd/Make.defs b/nuttx/libc/unistd/Make.defs deleted file mode 100644 index 67fce9b1d7..0000000000 --- a/nuttx/libc/unistd/Make.defs +++ /dev/null @@ -1,49 +0,0 @@ -############################################################################ -# libc/unistd/Make.defs -# -# 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. -# -############################################################################ - -# Add the unistd C files to the build - -CSRCS += lib_getopt.c lib_getoptargp.c lib_getoptindp.c lib_getoptoptp.c - -ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) -ifneq ($(CONFIG_DISABLE_ENVIRON),y) -CSRCS += lib_chdir.c lib_getcwd.c -endif -endif - -# Add the unistd directory to the build - -DEPPATH += --dep-path unistd -VPATH += :unistd diff --git a/nuttx/libc/unistd/lib_chdir.c b/nuttx/libc/unistd/lib_chdir.c deleted file mode 100644 index 8953fb19b6..0000000000 --- a/nuttx/libc/unistd/lib_chdir.c +++ /dev/null @@ -1,179 +0,0 @@ -/**************************************************************************** - * libc/unistd/lib_chdir.c - * - * Copyright (C) 2008-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON) - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: _trimdir - ****************************************************************************/ - -#if 0 -static inline void _trimdir(char *path) -{ - /* Skip any trailing '/' characters (unless it is also the leading '/') */ - - int len = strlen(path) - 1; - while (len > 0 && path[len] == '/') - { - path[len] = '\0'; - len--; - } -} -#else -# define _trimdir(p) -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: chdir - * - * Description: - * The chdir() function causes the directory named by the pathname pointed - * to by the 'path' argument to become the current working directory; that - * is, the starting point for path searches for pathnames not beginning - * with '/'. - * - * Input Parmeters: - * path - A pointer to a directory to use as the new current working - * directory - * - * Returned Value: - * 0(OK) on success; -1(ERROR) on failure with errno set appropriately: - * - * EACCES - * Search permission is denied for any component of the pathname. - * ELOOP - * A loop exists in symbolic links encountered during resolution of the - * 'path' argument OR more that SYMLOOP_MAX symbolic links in the - * resolution of the 'path' argument. - * ENAMETOOLONG - * The length of the path argument exceeds PATH_MAX or a pathname component - * is longer than NAME_MAX. - * ENOENT - * A component of 'path' does not name an existing directory or path is - * an empty string. - * ENOTDIR - * A component of the pathname is not a directory. - * - ****************************************************************************/ - -int chdir(FAR const char *path) -{ - struct stat buf; - char *oldpwd; - char *alloc; - int err; - int ret; - - /* Verify the input parameters */ - - if (!path) - { - err = ENOENT; - goto errout; - } - - /* Verify that 'path' refers to a directory */ - - ret = stat(path, &buf); - if (ret != 0) - { - err = ENOENT; - goto errout; - } - - /* Something exists here... is it a directory? */ - - if (!S_ISDIR(buf.st_mode)) - { - err = ENOTDIR; - goto errout; - } - - /* Yes, it is a directory. Remove any trailing '/' characters from the path */ - - _trimdir(path); - - /* Replace any preceding OLDPWD with the current PWD (this is to - * support 'cd -' in NSH) - */ - - sched_lock(); - oldpwd = getenv("PWD"); - if (!oldpwd) - { - oldpwd = CONFIG_LIB_HOMEDIR; - } - - alloc = strdup(oldpwd); /* kludge needed because environment is realloc'ed */ - setenv("OLDPWD", alloc, TRUE); - lib_free(alloc); - - /* Set the cwd to the input 'path' */ - - setenv("PWD", path, TRUE); - sched_unlock(); - return OK; - -errout: - set_errno(err); - return ERROR; -} -#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/libc/unistd/lib_getcwd.c b/nuttx/libc/unistd/lib_getcwd.c deleted file mode 100644 index 717ef29717..0000000000 --- a/nuttx/libc/unistd/lib_getcwd.c +++ /dev/null @@ -1,132 +0,0 @@ -/**************************************************************************** - * libc/unistd/lib_getcwd.c - * - * Copyright (C) 2008, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include "lib_internal.h" - -#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON) - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: getwcd - * - * Description: - * getcwd() function places the absolute pathname of the current working - * directory in the array pointed to by 'buf', and returns 'buf.' The - * pathname copied to the array shall contain no components that are - * symbolic links. The 'size' argument is the size in bytes of the - * character array pointed to by the 'buf' argument. - * - * Input Parmeters: - * buf - a pointer to the location in which the current working directory - * pathaname is returned. - * size - The size in bytes avaiable at 'buf' - * - * Returned Value: - * Upon successful completion, getcwd() returns the 'buf' argument. - * Otherwise, getcwd() returns a null pointer and sets errno to indicate - * the error: - * - * EINVAL - * The 'size' argument is 0 or the 'buf' argument is NULL. - * ERANGE - * The size argument is greater than 0, but is smaller than the length - * of the currrent working directory pathname +1. - * EACCES - * Read or search permission was denied for a component of the pathname. - * ENOMEM - * Insufficient storage space is available. - * - ****************************************************************************/ - -FAR char *getcwd(FAR char *buf, size_t size) -{ - char *pwd; - - /* Verify input parameters */ - -#ifdef CONFIG_DEBUG - if (!buf || !size) - { - set_errno(EINVAL); - return NULL; - } -#endif - - /* If no working directory is defined, then default to the home directory */ - - pwd = getenv("PWD"); - if (!pwd) - { - pwd = CONFIG_LIB_HOMEDIR; - } - - /* Verify that the cwd will fit into the user-provided buffer */ - - if (strlen(pwd) + 1 > size) - { - set_errno(ERANGE); - return NULL; - } - - /* Copy the cwd to the user buffer */ - - strcpy(buf, pwd); - sched_unlock(); - return buf; -} -#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/libc/unistd/lib_getopt.c b/nuttx/libc/unistd/lib_getopt.c deleted file mode 100644 index 1a91909765..0000000000 --- a/nuttx/libc/unistd/lib_getopt.c +++ /dev/null @@ -1,269 +0,0 @@ -/**************************************************************************** - * libc/unistd/lib_getopt.c - * - * Copyright (C) 2007-2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -FAR char *optarg; /* Optional argument following option */ -int optind = 1; /* Index into argv */ -int optopt = '?'; /* unrecognized option character */ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -static FAR char *g_optptr = NULL; -static bool g_binitialized = false; - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: getopt - * - * Description: getopt() parses command-line arguments. Its arguments argc - * and argv are the argument count and array as passed to the main() - * function on program invocation. An element of argv that starts with - * '-' is an option element. The characters of this element (aside from - * the initial '-') are option characters. If getopt() is called repeatedly, - * it returns successively each of the option characters from each of the - * option elements. - * - * If getopt() finds another option character, it returns that character, - * updating the external variable optind and a static variable nextchar so - * that the next call to getopt() can resume the scan with the following - * option character or argv-element. - * - * If there are no more option characters, getopt() returns -1. Then optind - * is the index in argv of the first argv-element that is not an option. - * - * The 'optstring' argument is a string containing the legitimate option - * characters. If such a character is followed by a colon, this indicates - * that the option requires an argument. If an argument is required for an - * option so getopt() places a pointer to the following text in the same - * argv-element, or the text of the following argv-element, in optarg. - * - * NOTES: - * 1. opterr is not supported and this implementation of getopt() never - * printfs error messages. - * 2. getopt is NOT threadsafe! - * 3. This version of getopt() does not reset global variables until - * -1 is returned. As a result, your command line parsing loops - * must call getopt() repeatedly and continue to parse if other - * errors are returned ('?' or ':') until getopt() finally returns -1. - * (You can also set optind to -1 to force a reset). - * - * Return: If an option was successfully found, then getopt() returns the - * option character. If all command-line options have been parsed, then - * getopt() returns -1. If getopt() encounters an option character that - * was not in optstring, then '?' is returned. If getopt() encounters an - * option with a missing argument, then the return value depends on the - * first character in optstring: if it is ':', then ':' is returned; - * otherwise '?' is returned. - * - ****************************************************************************/ - -int getopt(int argc, FAR char *const argv[], FAR const char *optstring) -{ - if (argv && optstring && argc > 1) - { - int noarg_ret = '?'; - char *optchar; - - /* The inital value of optind is 1. If getopt() is called again in the - * program, optind must be reset to some value <= 1. - */ - - if (optind < 1 || !g_binitialized) - { - optind = 1; /* Skip over the program name */ - g_optptr = NULL; /* Start at the beginning of the first argument */ - g_binitialized = true; /* Now we are initialized */ - } - - /* If the first character of opstring s ':', then ':' is in the event of - * a missing argument. Otherwise '?' is returned. - */ - - if (*optstring == ':') - { - noarg_ret = ':'; - optstring++; - } - - /* Are we resuming in the middle, or at the end of a string of arguments? - * g_optptr == NULL means that we are started at the beginning of argv[optind]; - * *g_optptr == \0 means that we are starting at the beginning of optind+1 - */ - - while (!g_optptr || !*g_optptr) - { - /* We need to start at the beginning of the next argv. Check if we need - * to increment optind - */ - - if (g_optptr) - { - /* Yes.. Increment it and check for the case where where we have - * processed everything in the argv[] array. - */ - - optind++; - } - - /* Check for the end of the argument list */ - - g_optptr = argv[optind]; - if (!g_optptr) - { - /* There are no more arguments, we are finished */ - - g_binitialized = false; - return ERROR; - } - - /* We are starting at the beginning of argv[optind]. In this case, the - * first character must be '-' - */ - - if (*g_optptr != '-') - { - /* The argument does not start with '-', we are finished */ - - g_binitialized = false; - return ERROR; - } - - /* Skip over the '-' */ - - g_optptr++; - } - - /* Special case handling of "-" and "-:" */ - - if (!*g_optptr) - { - optopt = '\0'; /* We'll fix up g_optptr the next time we are called */ - return '?'; - } - - /* Handle the case of "-:" */ - - if (*g_optptr == ':') - { - optopt = ':'; - g_optptr++; - return '?'; - } - - /* g_optptr now points at the next option and it is not something crazy. - * check if the option is in the list of valid options. - */ - - optchar = strchr(optstring, *g_optptr); - if (!optchar) - { - /* No this character is not in the list of valid options */ - - optopt = *g_optptr; - g_optptr++; - return '?'; - } - - /* Yes, the character is in the list of valid options. Does it have an - * required argument? - */ - - if (optchar[1] != ':') - { - /* No, no arguments. Just return the character that we found */ - - g_optptr++; - return *optchar; - } - - /* Yes, it has a required argument. Is the required argument - * immediately after the command in this same argument? - */ - - if (g_optptr[1] != '\0') - { - /* Yes, return a pointer into the current argument */ - - optarg = &g_optptr[1]; - optind++; - g_optptr = NULL; - return *optchar; - } - - /* No.. is the optional argument the next argument in argv[] ? */ - - if (argv[optind+1] && *argv[optind+1] != '-') - { - /* Yes.. return that */ - - optarg = argv[optind+1]; - optind += 2; - g_optptr = NULL; - return *optchar; - } - - /* No argument was supplied */ - - optarg = NULL; - optopt = *optchar; - optind++; - return noarg_ret; - } - - g_binitialized = false; - return ERROR; -} diff --git a/nuttx/libc/unistd/lib_getoptargp.c b/nuttx/libc/unistd/lib_getoptargp.c deleted file mode 100644 index 5610342ca9..0000000000 --- a/nuttx/libc/unistd/lib_getoptargp.c +++ /dev/null @@ -1,73 +0,0 @@ -/**************************************************************************** - * libc/unistd/lib_getoptargp.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: getoptargp - * - * Description: - * Returns a pointer to optarg. This function is only used for external - * modules that need to access the base, global variable, optarg. - * - ****************************************************************************/ - -FAR char **getoptargp(void) -{ - return &optarg; -} - diff --git a/nuttx/libc/unistd/lib_getoptindp.c b/nuttx/libc/unistd/lib_getoptindp.c deleted file mode 100644 index 94ea4d3fcd..0000000000 --- a/nuttx/libc/unistd/lib_getoptindp.c +++ /dev/null @@ -1,73 +0,0 @@ -/**************************************************************************** - * libc/unistd/lib_getoptindp.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: getoptindp - * - * Description: - * Returns a pointer to optind. This function is only used for external - * modules that need to access the base, global variable, optind. - * - ****************************************************************************/ - -int *getoptindp(void) -{ - return &optind; -} - diff --git a/nuttx/libc/unistd/lib_getoptoptp.c b/nuttx/libc/unistd/lib_getoptoptp.c deleted file mode 100644 index cd99b172f0..0000000000 --- a/nuttx/libc/unistd/lib_getoptoptp.c +++ /dev/null @@ -1,73 +0,0 @@ -/**************************************************************************** - * libc/unistd/lib_getoptoptp.c - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: getoptoptp - * - * Description: - * Returns a pointer to optopt. This function is only used for external - * modules that need to access the base, global variable, optopt. - * - ****************************************************************************/ - -int *getoptoptp(void) -{ - return &optopt; -} - diff --git a/nuttx/libxx/libxx_cxa_atexit.cxx b/nuttx/libxx/libxx_cxa_atexit.cxx deleted file mode 100644 index cd31f94f61..0000000000 --- a/nuttx/libxx/libxx_cxa_atexit.cxx +++ /dev/null @@ -1,146 +0,0 @@ -//*************************************************************************** -// libxx/libxx_eabi_atexit.cxx -// -// 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. -// -//*************************************************************************** - -//*************************************************************************** -// Included Files -//*************************************************************************** - -#include - -#include -#include - -#include "libxx_internal.hxx" - -//*************************************************************************** -// Pre-processor Definitions -//*************************************************************************** - -//*************************************************************************** -// Private Types -//*************************************************************************** - -struct __cxa_atexit_s -{ - __cxa_exitfunc_t func; - FAR void *arg; -}; - -//*************************************************************************** -// Private Data -//*************************************************************************** - -extern "C" -{ - //************************************************************************* - // Public Data - //************************************************************************* - - FAR void *__dso_handle = NULL; - - //************************************************************************* - // Private Functions - //************************************************************************* - - //************************************************************************* - // Name: __cxa_callback - // - // Description: - // This is really just an "adaptor" function that matches the form of - // the __cxa_exitfunc_t to an onexitfunc_t using an allocated structure - // to marshall the call parameters. - // - //************************************************************************* - -#if CONFIG_SCHED_ONEXIT - static void __cxa_callback(int exitcode, FAR void *arg) - { - FAR struct __cxa_atexit_s *alloc = (FAR struct __cxa_atexit_s *)arg; - DEBUGASSERT(alloc && alloc->func); - - alloc->func(alloc->arg); - free(alloc); - } -#endif - - //************************************************************************* - // Public Functions - //************************************************************************* - - //************************************************************************* - // Name: __cxa_atexit - // - // Description: - // __cxa_atexit() registers a destructor function to be called by exit(). - // On a call to exit(), the registered functions should be called with - // the single argument 'arg'. Destructor functions shall always be - // called in the reverse order to their registration (i.e. the most - // recently registered function shall be called first), - // - // If shared libraries were supported, the callbacks should be invoked - // when the shared library is unloaded as well. - // - // Reference: - // Linux base - // - //************************************************************************* - - int __cxa_atexit(__cxa_exitfunc_t func, FAR void *arg, FAR void *dso_handle) - { -#if CONFIG_SCHED_ONEXIT - // Allocate memory to hold the marshaled __cxa_exitfunc_t call - // information. - - FAR struct __cxa_atexit_s *alloc = - (FAR struct __cxa_atexit_s *)malloc(sizeof(struct __cxa_atexit_s)); - - if (alloc) - { - // Register the function to be called when the task/thread exists. - - alloc->func = func; - alloc->arg = arg; - - return on_exit(__cxa_callback, alloc); - } - else -#endif - { - // What else can we do? - - return 0; - } - } -} diff --git a/nuttx/libxx/libxx_internal.hxx b/nuttx/libxx/libxx_internal.hxx deleted file mode 100644 index fe84c763ed..0000000000 --- a/nuttx/libxx/libxx_internal.hxx +++ /dev/null @@ -1,67 +0,0 @@ -//*************************************************************************** -// lib/libxx_internal.h -// -// 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. -// -//*************************************************************************** - -#ifndef __LIBXX_LIBXX_INTERNAL_HXX -#define __LIBXX_LIBXX_INTERNAL_HXX - -//*************************************************************************** -// Included Files -//*************************************************************************** - -#include - -//*************************************************************************** -// Definitions -//*************************************************************************** - -//*************************************************************************** -// Public Types -//***************************************************************************/ - -typedef CODE void (*__cxa_exitfunc_t)(void *arg); - -//*************************************************************************** -// Public Variables -//*************************************************************************** - -extern "C" FAR void *__dso_handle; - -//*************************************************************************** -// Public Function Prototypes -//*************************************************************************** - -extern "C" int __cxa_atexit(__cxa_exitfunc_t func, void *arg, void *dso_handle); - -#endif // __LIBXX_LIBXX_INTERNAL_HXX diff --git a/nuttx/libxx/libxx_stdthrow.cxx b/nuttx/libxx/libxx_stdthrow.cxx deleted file mode 100644 index 588fae2642..0000000000 --- a/nuttx/libxx/libxx_stdthrow.cxx +++ /dev/null @@ -1,74 +0,0 @@ -//*************************************************************************** -// libxx/libxx_newa.cxx -// -// Copyright (C) 2012 Gregory Nutt. All rights reserved. -// Author: Petteri Aimonen ; -// -// 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 - -//*************************************************************************** -// Definitions -//*************************************************************************** - -//*************************************************************************** -// Private Data -//*************************************************************************** - -//*************************************************************************** -// Public Functions -//*************************************************************************** - -namespace std -{ - void __throw_out_of_range(const char*) - { - dbg("C++: Vector .at() with argument out of range\n"); - abort(); - } - - void __throw_length_error(const char*) - { - dbg("C++: Vector resize to excessive length\n"); - abort(); - } - - void __throw_bad_alloc() - { - dbg("C++: Bad allocation\n"); - abort(); - } -} diff --git a/nuttx/sched/pause.c b/nuttx/sched/pause.c deleted file mode 100644 index 607c4c7751..0000000000 --- a/nuttx/sched/pause.c +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * sched/pause.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -/**************************************************************************** - * Preprocessor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Definitions - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: pause - * - * Description: - * The pause() function will suspend the calling thread until delivery of a - * non-blocked signal. - * - * Input Parameters: - * None - * - * Returned Value: - * Since pause() suspends thread execution indefinitely unless interrupted - * a signal, there is no successful completion return value. A value of -1 - * will always be returned and errno set to indicate the error (EINTR). - * - * POSIX compatibility: - * In the POSIX description of this function is the pause() function will - * suspend the calling thread until delivery of a signal whose action is - * either to execute a signal-catching function or to terminate the - * process. This implementation only waits for any non-blocked signal - * to be received. - * - ****************************************************************************/ - -int pause(void) -{ - sigset_t set; - struct siginfo value; - - /* Set up for the sleep. Using the empty set means that we are not - * waiting for any particular signal. However, any unmasked signal - * can still awaken sigtimedwait(). - */ - - (void)sigemptyset(&set); - - /* sigtwaitinfo() cannot succeed. It should always return error EINTR - * meaning that some unblocked signal was caught. - */ - - return sigwaitinfo(&set, &value); -} diff --git a/nuttx/tools/define.bat b/nuttx/tools/define.bat deleted file mode 100644 index 13d29ac319..0000000000 --- a/nuttx/tools/define.bat +++ /dev/null @@ -1,178 +0,0 @@ -@echo off - -rem tools/define.bat -rem -rem Copyright (C) 2012 Gregory Nutt. All rights reserved. -rem Author: Gregory Nutt -rem -rem Redistribution and use in source and binary forms, with or without -rem modification, are permitted provided that the following conditions -rem are met: -rem -rem 1. Redistributions of source code must retain the above copyright -rem notice, this list of conditions and the following disclaimer. -rem 2. Redistributions in binary form must reproduce the above copyright -rem notice, this list of conditions and the following disclaimer in -rem the documentation and/or other materials provided with the -rem distribution. -rem 3. Neither the name NuttX nor the names of its contributors may be -rem used to endorse or promote products derived from this software -rem without specific prior written permission. -rem -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -rem POSSIBILITY OF SUCH DAMAGE. - -rem Handle command line options -rem [-h] [-val ] [ [-val ] [ [-val ] ...]] -rem [-w] [-d] ignored for compatibility with define.sh - -set progname=%0 - -:ArgLoop -if "%1"=="-d" goto :NextArg -if "%1"=="-w" goto :NextArg -if "%1"=="-h" goto :ShowUsage - -goto :CheckCompilerPath - -:NextArg -shift -goto :ArgLoop - -:CheckCompilerPath - -if "%1"=="" ( - echo Missing compiler path - goto :ShowUsage -) - -set ccpath=%1 -shift - -set compiler= -for /F %%i in ("%ccpath%") do set compiler=%%~ni - -if "%1"=="" ( - echo Missing definition list - goto :ShowUsage -) - -rem Check for some well known, non-GCC Windows native tools that require -rem a special output format as well as special paths - -:GetFormat -set fmt=std -if "%compiler%"=="ez8cc" goto :SetZdsFormt -if "%compiler%"=="zneocc" goto :SetZdsFormt -if "%compiler%"=="ez80cc" goto :SetZdsFormt -goto :ProcessDefinitions - -:SetZdsFormt -set fmt=zds - -rem Now process each directory in the directory list - -:ProcessDefinitions -set response= - -:DefinitionLoop -if "%1"=="" goto :Done - -set varname=%1 -shift - -rem Handle the output depending on if there is a value for the variable or not - -if "%1"=="-val" goto :GetValue - -rem Handle the output using the selected format - -:NoValue -if "%fmt%"=="zds" goto :NoValueZDS - -:NoValueStandard -rem Treat the first definition differently - -if "%response%"=="" ( - set response=-D%varname% - goto :DefinitionLoop -) - -set response=%response% -D%varname% -goto :DefinitionLoop - -:NoValueZDS -rem Treat the first definition differently - -if "%response%"=="" ( - set response=-define:%varname% - goto :DefinitionLoop -) - -set response=%response% -define:%varname% -goto :DefinitionLoop - -rem Get value following the variable name - -:GetValue -shift -set varvalue=%1 -shift - -rem Handle the output using the selected format - -if "%fmt%"=="zds" goto :ValueZDS - -:ValueStandard -rem Treat the first definition differently - -if "%response%"=="" ( - set response=-D%varname%=%varvalue% - goto :DefinitionLoop -) - -set response=%response% -D%varname%=%varvalue% -goto :DefinitionLoop - -:ValueZds -rem Treat the first definition differently - -if "%response%"=="" ( - set response=-define:%varname%=%varvalue% - goto :DefinitionLoop -) - -set response=%response% -define:%varname%=%varvalue% -goto :DefinitionLoop - -:Done -echo %response% -goto :End - -:ShowUsage -echo %progname% is a tool for flexible generation of command line pre-processor -echo definitions arguments for a variety of diffent ccpaths in a variety of -echo compilation environments" -echo USAGE:%progname% [-h] ^ [-val ^<^val1^>] [^ [-val ^] [^ [-val ^] ...]] -echo Where:" -echo ^ -echo The full path to your ccpath -echo ^ ^ ^ ... -echo A list of pre-preprocesser variable names to be defined. -echo [-val ^] [-val ^] [-val ^] ... -echo optional values to be assigned to each pre-processor variable. -echo If not supplied, the variable will be defined with no explicit value. -echo -h -echo Show this text and exit - -:End diff --git a/nuttx/tools/incdir.bat b/nuttx/tools/incdir.bat deleted file mode 100755 index 093c5bd2e3..0000000000 --- a/nuttx/tools/incdir.bat +++ /dev/null @@ -1,133 +0,0 @@ -@echo off - -rem tools/incdir.sh -rem -rem Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved. -rem Author: Gregory Nutt -rem -rem Redistribution and use in source and binary forms, with or without -rem modification, are permitted provided that the following conditions -rem are met: -rem -rem 1. Redistributions of source code must retain the above copyright -rem notice, this list of conditions and the following disclaimer. -rem 2. Redistributions in binary form must reproduce the above copyright -rem notice, this list of conditions and the following disclaimer in -rem the documentation and/or other materials provided with the -rem distribution. -rem 3. Neither the name NuttX nor the names of its contributors may be -rem used to endorse or promote products derived from this software -rem without specific prior written permission. -rem -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -rem POSSIBILITY OF SUCH DAMAGE. -rem - -rem Handle command line options - -set progname=%0 - -:ArgLoop - -rem [-d] [-w] [-h]. [-w] and [-d] Ignored for compatibility with incdir.sh - -if "%1"=="-d" goto :NextArg -if "%1"=="-w" goto :NextArg -if "%1"=="-h" goto :Usage -goto :CheckCompiler - -:NextArg -shift -goto :ArgLoop - -:CheckCompiler -if "%1"=="" ( - echo ERROR: Missing compiler name - goto :Usage -) - -set ccpath=%1 -shift - -set compiler= -for /F %%i in ("%ccpath%") do set compiler=%%~ni - -if "%1"=="" ( - echo ERROR: Missing directory paths - goto :Usage -) - -rem Check for some well known, non-GCC Windows native tools that require -rem a special output format as well as special paths - -:GetFormat -set fmt=std -if "%compiler%"=="ez8cc" goto :SetZdsFormt -if "%compiler%"=="zneocc" goto :SetZdsFormt -if "%compiler%"=="ez80cc" goto :SetZdsFormt -goto :GeneratePaths - -:SetZdsFormt -set fmt=zds - -rem Generate the compiler include path directives. - -:GeneratePaths -set response= - -:DirLoop -if "%1" == "" ( - echo %response% - goto :End -) - -if not exist %1 ( - echo ERROR: Path %1 does not exist - goto :Usage -) - -if "%fmt%"=="zds" goto :GenerateZdsPath - -if "%response"=="" ( - set response=-I "%1" -) else ( - set response=%response% -I "%1" -) -goto :EndOfDirLoop - -:GenerateZdsPath - -if "%response"=="" ( - set response=-usrinc:%1 -) else ( - set response=%response%;%1 -) - -:EndOfDirLoop -shift -goto :DirLoop - -:Usage -echo %progname% is a tool for flexible generation of include path arguments for a -echo variety of different compilers in a variety of compilation environments -echo USAGE: %progname% [-w] [-d] [-h] ^ ^ [^ [^ ...]] -echo Where: -echo ^ -echo The full path to your compiler -echo ^ [^ [^ ...]] -echo A list of include directories -echo -w, -d -echo For compatibility with incdir.sh (ignored) -echo -h -echo Shows this help text and exits. -:End diff --git a/nuttx/tools/mkdeps.bat b/nuttx/tools/mkdeps.bat deleted file mode 100644 index 23aab0b715..0000000000 --- a/nuttx/tools/mkdeps.bat +++ /dev/null @@ -1,173 +0,0 @@ -@echo off - -rem tools/mkdeps.sh -rem -rem Copyright (C) 2012 Gregory Nutt. All rights reserved. -rem Author: Gregory Nutt -rem -rem Redistribution and use in source and binary forms, with or without -rem modification, are permitted provided that the following conditions -rem are met: -rem -rem 1. Redistributions of source code must retain the above copyright -rem notice, this list of conditions and the following disclaimer. -rem 2. Redistributions in binary form must reproduce the above copyright -rem notice, this list of conditions and the following disclaimer in -rem the documentation and/or other materials provided with the -rem distribution. -rem 3. Neither the name NuttX nor the names of its contributors may be -rem used to endorse or promote products derived from this software -rem without specific prior written permission. -rem -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -rem POSSIBILITY OF SUCH DAMAGE. - -rem Accumulate CFLAGS up to "--" - -set cc= -set cflags= -set altpath= -set files= -set args= -set debug=n - -:Loop -if "%1"=="" goto Continue - -if "%1"=="--" ( - set cc=%cflags% - set cflags=%args% - set args= - goto NextParm -) - -if "%1"=="--dep-path" ( - if "%args%"=="" ( - set altpath=%altpath% %2 - ) else ( - set args=%args% %2 - ) - shift - goto NextParm -) - -if "%1"=="--dep-debug" ( -rem @echo on - set debug=y - goto NextParm -) - -if "%1"=="--help" goto Usage - -if "%args%"=="" ( - set args=%1 -) else ( - set args=%args% %1 -) - -:NextParm -shift -goto Loop -:Continue - -set files=%args% - -if "%debug%"=="y" ( - echo cc=%cc% - echo cflags=%cflags% - echo files=%files% - echo altpath=%altpath% -) - -rem Now check if we have everything - -if "%cc%"=="" ( - echo ERROR: No compiler specified - goto Usage -) - -if "%files%"=="" ( - rem Don't report an error -- this happens normally in some configurations - echo # No files specified for dependency generataion - goto End -) - -rem Then get the dependencies for each file - -if "%altpath%"=="" goto NoPaths -for %%G in (%files%) do ( - set fullpath= - set file=%%G - call :Checkpaths - if "%debug%"=="y" echo %file%: fullpath=%fullpath% - if "%fullpath%"=="" goto :NoFile - if "%debug%"=="y" echo CMD: %cc% -M %cflags% %fullpath% - %cc% -M %cflags% %fullpath% || goto DepFail -) -goto :End - -:NoPaths -for %%G in (%files%) do ( - set fullpath= - set file=%%G - call :CheckFile %%G -) -goto :End - -:CheckFile -if "%debug%"=="y" echo Checkfile: Checking %file% -if not exist %file% goto :NoFile -set fullpath=%file% - if "%debug%"=="y" echo CMD: %cc% -M %cflags% %fullpath% -%cc% -M %cflags% %fullpath% || goto DepFail -goto :EOF - -:CheckPaths -for %%H in (%altpath%) do ( - set tmppath=%%H\%file% - if "%debug%"=="y" echo Checkfile: Checking %tmppath% - if exist %tmppath% ( - set fullpath=%tmppath% - goto :EOF - ) -) -goto :EOF - -:NoFile -echo ERROR: No readable file at %file% -goto Usage - -:DepFail -echo ERROR: Failed to created dependencies for %file% - -:Usage -echo Usage: mkdeps [OPTIONS] CC -- CFLAGS -- file [file [file...]] -echo Where: -echo CC -echo A variable number of arguments that define how to execute the compiler -echo CFLAGS -echo The compiler compilation flags -echo file -echo One or more C files whose dependencies will be checked. Each file is expected -echo to reside in the current directory unless --dep-path is provided on the command line -echo And [OPTIONS] include: -echo --dep-debug -echo Enable script debug -echo --dep-path ^ -echo Do not look in the current directory for the file. Instead, look in to see -echo if the file resides there. --dep-path may be used multiple times to specify -echo multiple alternative location -echo --help -echo Shows this message and exits - -:End diff --git a/nuttx/tools/mkdeps.c b/nuttx/tools/mkdeps.c deleted file mode 100644 index 64d81cbd77..0000000000 --- a/nuttx/tools/mkdeps.c +++ /dev/null @@ -1,721 +0,0 @@ -/**************************************************************************** - * tools/mkdeps.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define MAX_BUFFER (4096) - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -enum slashmode_e -{ - MODE_FSLASH = 0, - MODE_BSLASH = 1, - MODE_DBLBACK = 2 -}; - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static char *g_cc = NULL; -static char *g_cflags = NULL; -static char *g_files = NULL; -static char *g_altpath = NULL; -static int g_debug = 0; -static bool g_winnative = false; -#ifdef HAVE_WINPATH -static bool g_winpath = false; -static char *g_topdir = NULL; -#endif - -static char g_command[MAX_BUFFER]; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - - /* MinGW does not seem to provide strtok_r */ - -#ifndef HAVE_STRTOK_R -static char *MY_strtok_r(char *str, const char *delim, char **saveptr) -{ - char *pbegin; - char *pend = NULL; - - /* Decide if we are starting a new string or continuing from - * the point we left off. - */ - - if (str) - { - pbegin = str; - } - else if (saveptr && *saveptr) - { - pbegin = *saveptr; - } - else - { - return NULL; - } - - /* Find the beginning of the next token */ - - for (; - *pbegin && strchr(delim, *pbegin) != NULL; - pbegin++); - - /* If we are at the end of the string with nothing - * but delimiters found, then return NULL. - */ - - if (!*pbegin) - { - return NULL; - } - - /* Find the end of the token */ - - for (pend = pbegin + 1; - *pend && strchr(delim, *pend) == NULL; - pend++); - - /* pend either points to the end of the string or to - * the first delimiter after the string. - */ - - if (*pend) - { - /* Turn the delimiter into a null terminator */ - - *pend++ = '\0'; - } - - /* Save the pointer where we left off and return the - * beginning of the token. - */ - - if (saveptr) - { - *saveptr = pend; - } - return pbegin; -} - -#define strtok_r MY_strtok_r -#endif - -static void append(char **base, char *str) -{ - char *oldbase; - char *newbase; - int alloclen; - - oldbase = *base; - if (!oldbase) - { - newbase = strdup(str); - if (!newbase) - { - fprintf(stderr, "ERROR: Failed to strdup %s\n", str); - exit(EXIT_FAILURE); - } - } - else - { - alloclen = strlen(oldbase) + strlen(str) + 2; - newbase = (char *)malloc(alloclen); - if (!newbase) - { - fprintf(stderr, "ERROR: Failed to allocate %d bytes\n", alloclen); - exit(EXIT_FAILURE); - } - - snprintf(newbase, alloclen, "%s %s\n", oldbase, str); - free(oldbase); - } - - *base = newbase; -} - -static void show_usage(const char *progname, const char *msg, int exitcode) -{ - if (msg) - { - fprintf(stderr, "\n"); - fprintf(stderr, "%s:\n", msg); - } - - fprintf(stderr, "\n"); - fprintf(stderr, "%s [OPTIONS] CC -- CFLAGS -- file [file [file...]]\n", - progname); - fprintf(stderr, "\n"); - fprintf(stderr, "Where:\n"); - fprintf(stderr, " CC\n"); - fprintf(stderr, " A variable number of arguments that define how to execute the compiler\n"); - fprintf(stderr, " CFLAGS\n"); - fprintf(stderr, " The compiler compilation flags\n"); - fprintf(stderr, " file\n"); - fprintf(stderr, " One or more C files whose dependencies will be checked. Each file is expected\n"); - fprintf(stderr, " to reside in the current directory unless --dep-path is provided on the command line\n"); - fprintf(stderr, "\n"); - fprintf(stderr, "And [OPTIONS] include:\n"); - fprintf(stderr, " --dep-debug\n"); - fprintf(stderr, " Enable script debug\n"); - fprintf(stderr, " --dep-path \n"); - fprintf(stderr, " Do not look in the current directory for the file. Instead, look in to see\n"); - fprintf(stderr, " if the file resides there. --dep-path may be used multiple times to specify\n"); - fprintf(stderr, " multiple alternative location\n"); - fprintf(stderr, " --winnative\n"); - fprintf(stderr, " By default, a POSIX-style environment is assumed (e.g., Linux, Cygwin, etc.) This option is\n"); - fprintf(stderr, " inform the tool that is working in a pure Windows native environment.\n"); -#ifdef HAVE_WINPATH - fprintf(stderr, " --winpaths \n"); - fprintf(stderr, " This option is useful when using a Windows native toolchain in a POSIX environment (such\n"); - fprintf(stderr, " such as Cygwin). In this case, will CC generates dependency lists using Windows paths\n"); - fprintf(stderr, " (e.g., C:\\blablah\\blabla). This switch instructs the script to use 'cygpath' to convert\n"); - fprintf(stderr, " the Windows paths to Cygwin POSIXE paths.\n"); -#endif - fprintf(stderr, " --help\n"); - fprintf(stderr, " Shows this message and exits\n"); - exit(exitcode); -} - -static void parse_args(int argc, char **argv) -{ - char *args = NULL; - int argidx; - - /* Accumulate CFLAGS up to "--" */ - - for (argidx = 1; argidx < argc; argidx++) - { - if (strcmp(argv[argidx], "--") == 0) - { - g_cc = g_cflags; - g_cflags = args; - args = NULL; - } - else if (strcmp(argv[argidx], "--dep-debug") == 0) - { - g_debug++; - } - else if (strcmp(argv[argidx], "--dep-path") == 0) - { - argidx++; - if (argidx >= argc) - { - show_usage(argv[0], "ERROR: Missing argument to --dep-path", EXIT_FAILURE); - } - - if (args) - { - append(&args, argv[argidx]); - } - else - { - append(&g_altpath, argv[argidx]); - } - } - else if (strcmp(argv[argidx], "--winnative") == 0) - { - g_winnative = true; - } -#ifdef HAVE_WINPATH - else if (strcmp(argv[argidx], "--winpath") == 0) - { - g_winpath = true; - if (g_topdir) - { - free(g_topdir); - } - - argidx++; - if (argidx >= argc) - { - show_usage(argv[0], "ERROR: Missing argument to --winpath", EXIT_FAILURE); - } - - g_topdir = strdup(argv[argidx]); - } -#endif - else if (strcmp(argv[argidx], "--help") == 0) - { - show_usage(argv[0], NULL, EXIT_SUCCESS); - } - else - { - append(&args, argv[argidx]); - } - } - - /* The final thing accumulated is the list of files */ - - g_files = args; - - /* If no paths were specified, then look in the current directory only */ - - if (!g_altpath) - { - g_altpath = strdup("."); - } - - if (g_debug) - { - fprintf(stderr, "SELECTIONS\n"); - fprintf(stderr, " CC : [%s]\n", g_cc ? g_cc : "(None)"); - fprintf(stderr, " CFLAGS : [%s]\n", g_cflags ? g_cflags : "(None)"); - fprintf(stderr, " FILES : [%s]\n", g_files ? g_files : "(None)"); - fprintf(stderr, " PATHS : [%s]\n", g_altpath ? g_altpath : "(None)"); -#ifdef HAVE_WINPATH - fprintf(stderr, " Windows Paths : [%s]\n", g_winpath ? "TRUE" : "FALSE"); - if (g_winpath) - { - fprintf(stderr, " TOPDIR : [%s]\n", g_topdir); - } -#endif - fprintf(stderr, " Windows Native : [%s]\n", g_winnative ? "TRUE" : "FALSE"); - } - - /* Check for required paramters */ - - if (!g_cc) - { - show_usage(argv[0], "ERROR: No compiler specified", EXIT_FAILURE); - } - - if (!g_files) - { - /* Don't report an error -- this happens normally in some configurations */ - - printf("# No files specified for dependency generataion\n"); - exit(EXIT_SUCCESS); - } - -#ifdef HAVE_WINPATH - if (g_winnative && g_winpath) - { - show_usage(argv[0], "ERROR: Both --winnative and --winpapth makes no sense", EXIT_FAILURE); - } -#endif -} - -static void do_dependency(const char *file, char separator) -{ - static const char moption[] = " -M "; - struct stat buf; - char *alloc; - char *altpath; - char *path; - char *lasts; - int cmdlen; - int pathlen; - int filelen; - int totallen; - int ret; - - /* Copy the compiler into the command buffer */ - - cmdlen = strlen(g_cc); - if (cmdlen >= MAX_BUFFER) - { - fprintf(stderr, "ERROR: Compiler string is too long [%d/%d]: %s\n", - cmdlen, MAX_BUFFER, g_cc); - exit(EXIT_FAILURE); - } - - strcpy(g_command, g_cc); - - /* Copy " -M " */ - - cmdlen += strlen(moption); - if (cmdlen >= MAX_BUFFER) - { - fprintf(stderr, "ERROR: Option string is too long [%d/%d]: %s\n", - cmdlen, MAX_BUFFER, moption); - exit(EXIT_FAILURE); - } - - strcat(g_command, moption); - - /* Copy the CFLAGS into the command buffer */ - - cmdlen += strlen(g_cflags); - if (cmdlen >= MAX_BUFFER) - { - fprintf(stderr, "ERROR: CFLAG string is too long [%d/%d]: %s\n", - cmdlen, MAX_BUFFER, g_cflags); - exit(EXIT_FAILURE); - } - - strcat(g_command, g_cflags); - - /* Add a space */ - - g_command[cmdlen] = ' '; - cmdlen++; - g_command[cmdlen] = '\0'; - - /* Make a copy of g_altpath. We need to do this because at least the version - * of strtok_r above does modifie it. - */ - - alloc = strdup(g_altpath); - if (!alloc) - { - fprintf(stderr, "ERROR: Failed to strdup paths\n"); - exit(EXIT_FAILURE); - } - - altpath = alloc; - - /* Try each path. This loop will continue until each path has been tried - * (failure) or until stat() finds the file - */ - - while ((path = strtok_r(altpath, " ", &lasts)) != NULL) - { - /* Create a full path to the file */ - - pathlen = strlen(path); - totallen = cmdlen + pathlen; - if (totallen >= MAX_BUFFER) - { - fprintf(stderr, "ERROR: Path is too long [%d/%d]: %s\n", - totallen, MAX_BUFFER, path); - exit(EXIT_FAILURE); - } - - strcpy(&g_command[cmdlen], path); - - if (g_command[totallen] != '\0') - { - fprintf(stderr, "ERROR: Missing NUL terminator\n"); - exit(EXIT_FAILURE); - } - - if (g_command[totallen-1] != separator) - { - g_command[totallen] = separator; - g_command[totallen+1] = '\0'; - pathlen++; - totallen++; - } - - filelen = strlen(file); - totallen += filelen; - if (totallen >= MAX_BUFFER) - { - fprintf(stderr, "ERROR: Path+file is too long [%d/%d]\n", - totallen, MAX_BUFFER); - exit(EXIT_FAILURE); - } - - strcat(g_command, file); - - /* Check that a file actually exists at this path */ - - if (g_debug) - { - fprintf(stderr, "Trying path=%s file=%s fullpath=%s\n", - path, file, &g_command[cmdlen]); - } - - ret = stat(&g_command[cmdlen], &buf); - if (ret < 0) - { - altpath = NULL; - continue; - } - - if (!S_ISREG(buf.st_mode)) - { - fprintf(stderr, "ERROR: File %s exists but is not a regular file\n", - &g_command[cmdlen]); - exit(EXIT_FAILURE); - } - - /* Okay.. we have. Create the dependency. One a failure to start the - * compiler, system() will return -1; Otherwise, the returned value - * from the compiler is in WEXITSTATUS(ret). - */ - - ret = system(g_command); -#ifdef WEXITSTATUS - if (ret < 0 || WEXITSTATUS(ret) != 0) - { - if (ret < 0) - { - fprintf(stderr, "ERROR: system failed: %s\n", strerror(errno)); - } - else - { - fprintf(stderr, "ERROR: %s failed: %d\n", g_cc, WEXITSTATUS(ret)); - } - - fprintf(stderr, " command: %s\n", g_command); - exit(EXIT_FAILURE); - } -#else - if (ret < 0) - { - fprintf(stderr, "ERROR: system failed: %s\n", strerror(errno)); - fprintf(stderr, " command: %s\n", g_command); - exit(EXIT_FAILURE); - } -#endif - - /* We don't really know that the command succeeded... Let's assume that it did */ - - free(alloc); - return; - } - - printf("# ERROR: File \"%s\" not found at any location\n", file); - exit(EXIT_FAILURE); -} - -/* Convert a Cygwin path to a Windows path */ - -#ifdef HAVE_WINPATH -static char *cywin2windows(const char *str, const char *append, enum slashmode_e mode) -{ - static const char cygdrive[] = "/cydrive"; - const char *src = src; - char *dest; - char *newpath; - char *allocpath = NULL; - int srclen = strlen(str); - int alloclen = 0; - int drive = 0; - int lastchar; - - /* Skip any leading whitespace */ - - while (isspace(*str)) str++; - - /* Were we asked to append something? */ - - if (append) - { - char *tmp; - - alloclen = sizeof(str) + sizeof(append) + 1; - allocpath = (char *)malloc(alloclen); - if (!allocpath) - { - fprintf(stderr, "ERROR: Failed to allocate %d bytes\n", alloclen); - exit(EXIT_FAILURE); - } - - snprintf(allocpath, alloclen, "%s/%s", str, append); - } - - /* Looking for path of the form /cygdrive/c/bla/bla/bla */ - - if (strcasecmp(src, cygdrive) == 0) - { - int cygsize = sizeof(cygdrive); - if (src[cygsize] == '/') - { - cygsize++; - srclen -= cygsize; - src += cygsize; - - if (srclen <= 0) - { - fprintf(stderr, "ERROR: Unhandled path: \"%s\"\n", str); - exit(EXIT_FAILURE); - } - - drive = toupper(*src); - if (drive < 'A' || drive > 'Z') - { - fprintf(stderr, "ERROR: Drive charager: \"%s\"\n", str); - exit(EXIT_FAILURE); - } - - srclen--; - src++; - alloclen = 2; - } - } - - /* Determine the size of the new path */ - - alloclen += sizeof(src) + 1; - if (mode == MODE_DBLBACK) - { - const char *tmpptr; - for (tmpptr = src; *tmpptr; tmpptr++) - { - if (*tmpptr == '/') alloclen++; - } - } - - /* Allocate memory for the new path */ - - newpath = (char *)malloc(alloclen); - if (!newpath) - { - fprintf(stderr, "ERROR: Failed to allocate %d bytes\n", alloclen); - exit(EXIT_FAILURE); - } - - dest = newpath; - - /* Copy the drive character */ - - if (drive) - { - *dest++ = drive; - *dest++ = ':'; - } - - /* Copy each character from the source, making modifications for foward - * slashes as required. - */ - - lastchar = '\0'; - for (; *src; src++) - { - if (mode != MODE_FSLASH && *src == '/') - { - if (lastchar != '/') - { - *dest++ = '\\'; - if (mode == MODE_DBLBACK) - { - *dest++ = '\\'; - } - } - } - else - { - *dest++ = *src; - } - - lastchar = *src; - } - - *dest++ = '\0'; - if (allocpath) - { - free(allocpath); - } - return dest; -} -#endif - -#ifdef HAVE_WINPATH -static void do_winpath(char *file) -{ - /* The file is in POSIX format. CC expects Windows format to generate the - * dependencies, but GNU make expect the resulting dependencies to be back - * in POSIX format. What a mess! - */ - - char *path = cywin2windows(g_topdir, file, MODE_FSLASH); - - /* Then get the dependency and perform conversions on it to make it - * palatable to the Cygwin make. - */ -#warning "Missing logic" - - free(path); -} -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -int main(int argc, char **argv, char **envp) -{ - char *lasts; - char *files; - char *file; - - /* Parse command line parameters */ - - parse_args(argc, argv); - - /* Then generate dependencies for each path on the command line. NOTE - * strtok_r will clobber the files list. But that is okay because we are - * only going to traverse it once. - */ - - files = g_files; - while ((file = strtok_r(files, " ", &lasts)) != NULL) - { - /* Check if we need to do path conversions for a Windows-natvie tool - * being using in a POSIX/Cygwin environment. - */ - -#ifdef HAVE_WINPATH - if (g_winpath) - { - do_winpath(file); - } - else -#endif - { - do_dependency(file, g_winnative ? '\\' : '/'); - } - - files = NULL; - } - - return EXIT_SUCCESS; -} From be85589e48cdc1b297bffe8e492cd7d69f949b4b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 28 Dec 2012 20:19:47 +0100 Subject: [PATCH 202/206] Fixed some typos --- apps/px4io/comms.c | 1 - apps/px4io/px4io.h | 4 ++-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/apps/px4io/comms.c b/apps/px4io/comms.c index 2b8f95534b..d41de54a2c 100644 --- a/apps/px4io/comms.c +++ b/apps/px4io/comms.c @@ -228,7 +228,6 @@ comms_handle_command(const void *buffer, size_t length) break; } } - system_state.relays[i] != cmd->relay_state[i] } irqrestore(flags); diff --git a/apps/px4io/px4io.h b/apps/px4io/px4io.h index 9cfd8f716d..e9a2ff053e 100644 --- a/apps/px4io/px4io.h +++ b/apps/px4io/px4io.h @@ -162,8 +162,8 @@ extern volatile int timers[TIMER_NUM_TIMERS]; #define LED_SAFETY(_s) stm32_gpiowrite(GPIO_LED3, !(_s)) #define POWER_SERVO(_s) stm32_gpiowrite(GPIO_SERVO_PWR_EN, (_s)) -#define POWER_ACC1(_s) stm32_gpiowrite(GPIO_SERVO_ACC1_EN, (_s)) -#define POWER_ACC2(_s) stm32_gpiowrite(GPIO_SERVO_ACC2_EN, (_s)) +#define POWER_ACC1(_s) stm32_gpiowrite(GPIO_ACC1_PWR_EN, (_s)) +#define POWER_ACC2(_s) stm32_gpiowrite(GPIO_ACC2_PWR_EN, (_s)) #define POWER_RELAY1(_s) stm32_gpiowrite(GPIO_RELAY1_EN, (_s)) #define POWER_RELAY2(_s) stm32_gpiowrite(GPIO_RELAY2_EN, (_s)) From c652f718c0d2ab78fd80f503d5932ecf526136a9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 29 Dec 2012 11:00:15 +0100 Subject: [PATCH 203/206] Minor fixes, pushing WIP --- apps/commander/commander.c | 35 +++++++++++++++---- apps/commander/commander.h | 3 ++ apps/commander/state_machine_helper.c | 1 + .../fixedwing_att_control_main.c | 4 +-- apps/mavlink/mavlink.c | 30 ++++++++++++---- apps/sensors/sensors.cpp | 18 +--------- 6 files changed, 60 insertions(+), 31 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 50544320bf..be50289c3d 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -147,7 +147,6 @@ int commander_thread_main(int argc, char *argv[]); static int buzzer_init(void); static void buzzer_deinit(void); -static void tune_confirm(void); static int led_init(void); static void led_deinit(void); static int led_toggle(int led); @@ -272,6 +271,10 @@ void tune_confirm(void) { ioctl(buzzer, TONE_SET_ALARM, 3); } +void tune_error(void) { + ioctl(buzzer, TONE_SET_ALARM, 4); +} + void do_rc_calibration(int status_pub, struct vehicle_status_s *status) { int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint)); @@ -980,8 +983,13 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta break; case MAV_CMD_PREFLIGHT_STORAGE: { - if (current_status.flag_system_armed) { - mavlink_log_info(mavlink_fd, "[cmd] REJECTING param command while armed"); + if (current_status.flag_system_armed && + ((current_status.system_type == MAV_TYPE_QUADROTOR) || + (current_status.system_type == MAV_TYPE_HEXAROTOR) || + (current_status.system_type == MAV_TYPE_OCTOROTOR))) { + /* do not perform expensive memory tasks on multirotors in flight */ + // XXX this is over-safe, as soon as cmd is in low prio thread this can be allowed + mavlink_log_info(mavlink_fd, "[cmd] REJECTING save cmd while multicopter armed"); } else { // XXX move this to LOW PRIO THREAD of commander app @@ -1680,6 +1688,7 @@ int commander_thread_main(int argc, char *argv[]) * Check if manual control modes have to be switched */ if (!isfinite(sp_man.manual_mode_switch)) { + printf("man mode sw not finite\n"); /* this switch is not properly mapped, set default */ if ((current_status.system_type == MAV_TYPE_QUADROTOR) || @@ -1688,13 +1697,17 @@ int commander_thread_main(int argc, char *argv[]) /* assuming a rotary wing, fall back to SAS */ current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + current_status.flag_control_attitude_enabled = true; + current_status.flag_control_rates_enabled = true; } else { /* assuming a fixed wing, fall back to direct pass-through */ current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT; + current_status.flag_control_attitude_enabled = false; + current_status.flag_control_rates_enabled = false; } - } else if (sp_man.manual_sas_switch < -STICK_ON_OFF_LIMIT) { + } else if (sp_man.manual_mode_switch < -STICK_ON_OFF_LIMIT) { /* bottom stick position, set direct mode for vehicles supporting it */ if ((current_status.system_type == MAV_TYPE_QUADROTOR) || @@ -1703,22 +1716,32 @@ int commander_thread_main(int argc, char *argv[]) /* assuming a rotary wing, fall back to SAS */ current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + current_status.flag_control_attitude_enabled = true; + current_status.flag_control_rates_enabled = true; } else { - /* assuming a fixed wing, fall back to direct pass-through */ + /* assuming a fixed wing, set to direct pass-through as requested */ current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT; + current_status.flag_control_attitude_enabled = false; + current_status.flag_control_rates_enabled = false; } - } else if (sp_man.manual_sas_switch > STICK_ON_OFF_LIMIT) { + } else if (sp_man.manual_mode_switch > STICK_ON_OFF_LIMIT) { /* top stick position, set SAS for all vehicle types */ current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + current_status.flag_control_attitude_enabled = true; + current_status.flag_control_rates_enabled = true; } else { /* center stick position, set rate control */ current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_RATES; + current_status.flag_control_attitude_enabled = false; + current_status.flag_control_rates_enabled = true; } + printf("man ctrl mode: %d\n", (int)current_status.manual_control_mode); + /* * Check if manual stability control modes have to be switched */ diff --git a/apps/commander/commander.h b/apps/commander/commander.h index bea67beada..04b4e72ab3 100644 --- a/apps/commander/commander.h +++ b/apps/commander/commander.h @@ -52,4 +52,7 @@ #define LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 1000.0f #define CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 100.0f +void tune_confirm(void); +void tune_error(void); + #endif /* COMMANDER_H_ */ diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c index 4152142dfb..a8cef8c014 100644 --- a/apps/commander/state_machine_helper.c +++ b/apps/commander/state_machine_helper.c @@ -535,6 +535,7 @@ void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_ { if (!current_status->flag_vector_flight_mode_ok) { mavlink_log_critical(mavlink_fd, "NO POS LOCK, REJ. STAB MODE"); + tune_error(); return; } if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_AUTO) { diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index 5ededa2e35..c51d06579e 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -201,7 +201,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) } else if (vstatus.state_machine == SYSTEM_STATE_STABILIZED) { /* if the RC signal is lost, try to stay level and go slowly back down to ground */ - if(vstatus.rc_signal_lost) { + if (vstatus.rc_signal_lost) { // XXX define failsafe throttle param //param_get(failsafe_throttle_handle, &failsafe_throttle); @@ -244,7 +244,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { /* if the RC signal is lost, try to stay level and go slowly back down to ground */ - if(vstatus.rc_signal_lost) { + if (vstatus.rc_signal_lost) { // XXX define failsafe throttle param //param_get(failsafe_throttle_handle, &failsafe_throttle); diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index 3351d9cfdd..ccc9d6d7d6 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -189,10 +189,34 @@ get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_mode) *mavlink_mode = 0; /* set mode flags independent of system state */ + + /* HIL */ if (v_status.flag_hil_enabled) { *mavlink_mode |= MAV_MODE_FLAG_HIL_ENABLED; } + /* manual input */ + if (v_status.flag_control_manual_enabled) { + *mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; + } + + /* attitude or rate control */ + if (v_status.flag_control_attitude_enabled || + v_status.flag_control_rates_enabled) { + *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED; + } + + /* vector control */ + if (v_status.flag_control_velocity_enabled || + v_status.flag_control_position_enabled) { + *mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED; + } + + /* autonomous mode */ + if (v_status.state_machine == SYSTEM_STATE_AUTO) { + *mavlink_mode |= MAV_MODE_FLAG_AUTO_ENABLED; + } + /* set arming state */ if (armed.armed) { *mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED; @@ -221,20 +245,14 @@ get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_mode) case SYSTEM_STATE_MANUAL: *mavlink_state = MAV_STATE_ACTIVE; - *mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; break; case SYSTEM_STATE_STABILIZED: *mavlink_state = MAV_STATE_ACTIVE; - *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED; - *mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED; break; case SYSTEM_STATE_AUTO: *mavlink_state = MAV_STATE_ACTIVE; - *mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED; - *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED; - *mavlink_mode |= MAV_MODE_FLAG_AUTO_ENABLED; break; case SYSTEM_STATE_MISSION_ABORT: diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index 10d25d347d..c331ec3e3e 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -1088,24 +1088,8 @@ Sensors::ppm_poll() manual_control.timestamp = rc_input.timestamp; - // /* check if input needs to be de-mixed */ - // if (_parameters.rc_demix == (int)RC_DEMIX_DELTA) { - // // XXX hardcoded for testing purposes, replace with inverted delta mixer from ROMFS - - // /* roll input - mixed roll and pitch channels */ - // manual_control.roll = 0.5f * (_rc.chan[_rc.function[ROLL]].scaled - _rc.chan[_rc.function[PITCH]].scaled); - // pitch input - mixed roll and pitch channels - // manual_control.pitch = 0.5f * (_rc.chan[_rc.function[ROLL]].scaled + _rc.chan[_rc.function[PITCH]].scaled); - // /* yaw input - stick right is positive and positive rotation */ - // manual_control.yaw = _rc.chan[_rc.function[YAW]].scaled; - // /* throttle input */ - // manual_control.throttle = _rc.chan[_rc.function[THROTTLE]].scaled; - - // /* direct pass-through of manual input */ - // } else { - /* roll input - rolling right is stick-wise and rotation-wise positive */ - manual_control.roll = _rc.chan[_rc.function[ROLL]].scaled; + manual_control.roll = limit_minus_one_to_one(_rc.chan[_rc.function[ROLL]].scaled); /* * pitch input - stick down is negative, but stick down is pitching up (pos) in NED, * so reverse sign. From b240e31c1c25c07ffe046a3433d43fa8b862c136 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 29 Dec 2012 11:18:49 +0100 Subject: [PATCH 204/206] Safer fixed wing mode switching --- apps/fixedwing_att_control/fixedwing_att_control_main.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index c51d06579e..cd479d40d8 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -240,7 +240,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) /* set flaps to zero */ actuators.control[4] = 0.0f; - } else { + } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) { if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { /* if the RC signal is lost, try to stay level and go slowly back down to ground */ From 4976a3a47d9ed368734135df04ad67634c39c65d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 29 Dec 2012 16:21:59 +0100 Subject: [PATCH 205/206] Added accel magnitude check, added conversion functions for various standard cases --- .../attitude_estimator_ekf_main.c | 27 +++++- .../attitude_estimator_ekf_params.c | 6 +- apps/systemlib/conversions.c | 89 +++++++++++++++++++ apps/systemlib/conversions.h | 22 +++++ 4 files changed, 139 insertions(+), 5 deletions(-) diff --git a/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c b/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c index 6533390bc0..685ab078b2 100644 --- a/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c +++ b/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c @@ -65,6 +65,7 @@ #include #include #include +#include #include "codegen/attitudeKalmanfilter_initialize.h" #include "codegen/attitudeKalmanfilter.h" @@ -254,6 +255,7 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[]) bool initialized = false; float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f }; + float accel_magnitude = CONSTANTS_ONE_G; unsigned offset_count = 0; /* register the perf counter */ @@ -329,13 +331,34 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[]) z_k[1] = raw.gyro_rad_s[1] - gyro_offsets[1]; z_k[2] = raw.gyro_rad_s[2] - gyro_offsets[2]; - /* update accelerometer measurements */ - if (sensor_last_count[1] != raw.accelerometer_counter) { + /* + * Check if assumption of zero acceleration roughly holds. + * If not, do not update the accelerometer, predict only with gyroscopes. + * The violation of the zero acceleration assumption can only hold shortly, + * and predicting the angle with the gyros is safe for + */ + bool acceleration_stationary = true; + + /* lowpass accel magnitude to prevent threshold aliasing in presence of vibrations */ + accel_magnitude = accel_magnitude * 0.95f + 0.05f * sqrtf(raw.accelerometer_m_s2[0] * raw.accelerometer_m_s2[0] + + raw.accelerometer_m_s2[1] * raw.accelerometer_m_s2[1] + + raw.accelerometer_m_s2[2] * raw.accelerometer_m_s2[2]); + + /* check if length of gravity vector differs in more than 15 % from expected result */ + if (fabsf(accel_magnitude - CONSTANTS_ONE_G) > (CONSTANTS_ONE_G * 0.15f)) { + /* acceleration violates assumptions, disable updates */ + acceleration_stationary = false; + } + + /* update accelerometer measurements, reject if vector norm ends up being weird */ + if (sensor_last_count[1] != raw.accelerometer_counter && + acceleration_stationary) { update_vect[1] = 1; sensor_last_count[1] = raw.accelerometer_counter; sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]); sensor_last_timestamp[1] = raw.timestamp; } + z_k[3] = raw.accelerometer_m_s2[0]; z_k[4] = raw.accelerometer_m_s2[1]; z_k[5] = raw.accelerometer_m_s2[2]; diff --git a/apps/attitude_estimator_ekf/attitude_estimator_ekf_params.c b/apps/attitude_estimator_ekf/attitude_estimator_ekf_params.c index 4fc2e0452a..6879f9dc8e 100644 --- a/apps/attitude_estimator_ekf/attitude_estimator_ekf_params.c +++ b/apps/attitude_estimator_ekf/attitude_estimator_ekf_params.c @@ -65,9 +65,9 @@ PARAM_DEFINE_FLOAT(EKF_ATT_R0, 0.01f); PARAM_DEFINE_FLOAT(EKF_ATT_R1, 0.01f); PARAM_DEFINE_FLOAT(EKF_ATT_R2, 0.01f); /* accelerometer measurement noise */ -PARAM_DEFINE_FLOAT(EKF_ATT_R3, 1e1f); -PARAM_DEFINE_FLOAT(EKF_ATT_R4, 1e1f); -PARAM_DEFINE_FLOAT(EKF_ATT_R5, 1e1f); +PARAM_DEFINE_FLOAT(EKF_ATT_R3, 1e2f); +PARAM_DEFINE_FLOAT(EKF_ATT_R4, 1e2f); +PARAM_DEFINE_FLOAT(EKF_ATT_R5, 1e2f); /* magnetometer measurement noise */ PARAM_DEFINE_FLOAT(EKF_ATT_R6, 1e-1f); PARAM_DEFINE_FLOAT(EKF_ATT_R7, 1e-1f); diff --git a/apps/systemlib/conversions.c b/apps/systemlib/conversions.c index 9105d83cbe..32df446d99 100644 --- a/apps/systemlib/conversions.c +++ b/apps/systemlib/conversions.c @@ -55,3 +55,92 @@ int16_t_from_bytes(uint8_t bytes[]) return u.w; } + +void rot2quat(const float R[9], float Q[4]) +{ + float q0_2; + float q1_2; + float q2_2; + float q3_2; + int32_t idx; + + /* conversion of rotation matrix to quaternion + * choose the largest component to begin with */ + q0_2 = (((1.0F + R[0]) + R[4]) + R[8]) / 4.0F; + q1_2 = (((1.0F + R[0]) - R[4]) - R[8]) / 4.0F; + q2_2 = (((1.0F - R[0]) + R[4]) - R[8]) / 4.0F; + q3_2 = (((1.0F - R[0]) - R[4]) + R[8]) / 4.0F; + + idx = 0; + + if (q0_2 < q1_2) { + q0_2 = q1_2; + + idx = 1; + } + + if (q0_2 < q2_2) { + q0_2 = q2_2; + idx = 2; + } + + if (q0_2 < q3_2) { + q0_2 = q3_2; + idx = 3; + } + + q0_2 = sqrtf(q0_2); + + /* solve for the remaining three components */ + if (idx == 0) { + q1_2 = q0_2; + q2_2 = (R[5] - R[7]) / 4.0F / q0_2; + q3_2 = (R[6] - R[2]) / 4.0F / q0_2; + q0_2 = (R[1] - R[3]) / 4.0F / q0_2; + } else if (idx == 1) { + q2_2 = q0_2; + q1_2 = (R[5] - R[7]) / 4.0F / q0_2; + q3_2 = (R[3] + R[1]) / 4.0F / q0_2; + q0_2 = (R[6] + R[2]) / 4.0F / q0_2; + } else if (idx == 2) { + q3_2 = q0_2; + q1_2 = (R[6] - R[2]) / 4.0F / q0_2; + q2_2 = (R[3] + R[1]) / 4.0F / q0_2; + q0_2 = (R[7] + R[5]) / 4.0F / q0_2; + } else { + q1_2 = (R[1] - R[3]) / 4.0F / q0_2; + q2_2 = (R[6] + R[2]) / 4.0F / q0_2; + q3_2 = (R[7] + R[5]) / 4.0F / q0_2; + } + + /* return values */ + Q[0] = q1_2; + Q[1] = q2_2; + Q[2] = q3_2; + Q[3] = q0_2; +} + +void quat2rot(const float Q[4], float R[9]) +{ + float q0_2; + float q1_2; + float q2_2; + float q3_2; + + memset(&R[0], 0, 9U * sizeof(float)); + + q0_2 = Q[0] * Q[0]; + q1_2 = Q[1] * Q[1]; + q2_2 = Q[2] * Q[2]; + q3_2 = Q[3] * Q[3]; + + R[0] = ((q0_2 + q1_2) - q2_2) - q3_2; + R[3] = 2.0F * (Q[1] * Q[2] - Q[0] * Q[3]); + R[6] = 2.0F * (Q[1] * Q[3] + Q[0] * Q[2]); + R[1] = 2.0F * (Q[1] * Q[2] + Q[0] * Q[3]); + R[4] = ((q0_2 + q2_2) - q1_2) - q3_2; + R[7] = 2.0F * (Q[2] * Q[3] - Q[0] * Q[1]); + R[2] = 2.0F * (Q[1] * Q[3] - Q[0] * Q[2]); + R[5] = 2.0F * (Q[2] * Q[3] + Q[0] * Q[1]); + R[8] = ((q0_2 + q3_2) - q1_2) - q2_2; +} \ No newline at end of file diff --git a/apps/systemlib/conversions.h b/apps/systemlib/conversions.h index dc383e770f..3a24ca9b7c 100644 --- a/apps/systemlib/conversions.h +++ b/apps/systemlib/conversions.h @@ -44,6 +44,8 @@ #include #include +#define CONSTANTS_ONE_G 9.80665f + __BEGIN_DECLS /** @@ -56,6 +58,26 @@ __BEGIN_DECLS */ __EXPORT int16_t int16_t_from_bytes(uint8_t bytes[]); +/** + * Converts a 3 x 3 rotation matrix to an unit quaternion. + * + * All orientations are expressed in NED frame. + * + * @param R rotation matrix to convert + * @param Q quaternion to write back to + */ +__EXPORT void rot2quat(const float R[9], float Q[4]); + +/** + * Converts an unit quaternion to a 3 x 3 rotation matrix. + * + * All orientations are expressed in NED frame. + * + * @param Q quaternion to convert + * @param R rotation matrix to write back to + */ +__EXPORT void quat2rot(const float Q[4], float R[9]); + __END_DECLS #endif /* CONVERSIONS_H_ */ From 62a95bf8e6592b31ae7e84e53b654bc5e6b71cd1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 30 Dec 2012 09:53:45 +0100 Subject: [PATCH 206/206] Stabilization enabling / switching --- apps/commander/commander.c | 99 ++++++++++--------- apps/commander/state_machine_helper.c | 21 +++- .../fixedwing_att_control_main.c | 16 ++- .../multirotor_att_control_main.c | 15 ++- 4 files changed, 98 insertions(+), 53 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index be50289c3d..ab50bab16a 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -1684,63 +1684,63 @@ int commander_thread_main(int argc, char *argv[]) if ((hrt_absolute_time() - sp_man.timestamp) < 100000) { - /* - * Check if manual control modes have to be switched - */ - if (!isfinite(sp_man.manual_mode_switch)) { - printf("man mode sw not finite\n"); + // /* + // * Check if manual control modes have to be switched + // */ + // if (!isfinite(sp_man.manual_mode_switch)) { + // printf("man mode sw not finite\n"); - /* this switch is not properly mapped, set default */ - if ((current_status.system_type == MAV_TYPE_QUADROTOR) || - (current_status.system_type == MAV_TYPE_HEXAROTOR) || - (current_status.system_type == MAV_TYPE_OCTOROTOR)) { + // /* this switch is not properly mapped, set default */ + // if ((current_status.system_type == MAV_TYPE_QUADROTOR) || + // (current_status.system_type == MAV_TYPE_HEXAROTOR) || + // (current_status.system_type == MAV_TYPE_OCTOROTOR)) { - /* assuming a rotary wing, fall back to SAS */ - current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; - current_status.flag_control_attitude_enabled = true; - current_status.flag_control_rates_enabled = true; - } else { + // /* assuming a rotary wing, fall back to SAS */ + // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + // current_status.flag_control_attitude_enabled = true; + // current_status.flag_control_rates_enabled = true; + // } else { - /* assuming a fixed wing, fall back to direct pass-through */ - current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT; - current_status.flag_control_attitude_enabled = false; - current_status.flag_control_rates_enabled = false; - } + // /* assuming a fixed wing, fall back to direct pass-through */ + // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT; + // current_status.flag_control_attitude_enabled = false; + // current_status.flag_control_rates_enabled = false; + // } - } else if (sp_man.manual_mode_switch < -STICK_ON_OFF_LIMIT) { + // } else if (sp_man.manual_mode_switch < -STICK_ON_OFF_LIMIT) { - /* bottom stick position, set direct mode for vehicles supporting it */ - if ((current_status.system_type == MAV_TYPE_QUADROTOR) || - (current_status.system_type == MAV_TYPE_HEXAROTOR) || - (current_status.system_type == MAV_TYPE_OCTOROTOR)) { + // /* bottom stick position, set direct mode for vehicles supporting it */ + // if ((current_status.system_type == MAV_TYPE_QUADROTOR) || + // (current_status.system_type == MAV_TYPE_HEXAROTOR) || + // (current_status.system_type == MAV_TYPE_OCTOROTOR)) { - /* assuming a rotary wing, fall back to SAS */ - current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; - current_status.flag_control_attitude_enabled = true; - current_status.flag_control_rates_enabled = true; - } else { + // /* assuming a rotary wing, fall back to SAS */ + // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + // current_status.flag_control_attitude_enabled = true; + // current_status.flag_control_rates_enabled = true; + // } else { - /* assuming a fixed wing, set to direct pass-through as requested */ - current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT; - current_status.flag_control_attitude_enabled = false; - current_status.flag_control_rates_enabled = false; - } + // /* assuming a fixed wing, set to direct pass-through as requested */ + // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT; + // current_status.flag_control_attitude_enabled = false; + // current_status.flag_control_rates_enabled = false; + // } - } else if (sp_man.manual_mode_switch > STICK_ON_OFF_LIMIT) { + // } else if (sp_man.manual_mode_switch > STICK_ON_OFF_LIMIT) { - /* top stick position, set SAS for all vehicle types */ - current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; - current_status.flag_control_attitude_enabled = true; - current_status.flag_control_rates_enabled = true; + // /* top stick position, set SAS for all vehicle types */ + // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + // current_status.flag_control_attitude_enabled = true; + // current_status.flag_control_rates_enabled = true; - } else { - /* center stick position, set rate control */ - current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_RATES; - current_status.flag_control_attitude_enabled = false; - current_status.flag_control_rates_enabled = true; - } + // } else { + // /* center stick position, set rate control */ + // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_RATES; + // current_status.flag_control_attitude_enabled = false; + // current_status.flag_control_rates_enabled = true; + // } - printf("man ctrl mode: %d\n", (int)current_status.manual_control_mode); + // printf("man ctrl mode: %d\n", (int)current_status.manual_control_mode); /* * Check if manual stability control modes have to be switched @@ -1801,7 +1801,7 @@ int commander_thread_main(int argc, char *argv[]) if (sp_man.manual_override_switch > STICK_ON_OFF_LIMIT) { /* enable manual override */ update_state_machine_mode_manual(stat_pub, ¤t_status, mavlink_fd); - } else { + } else if (sp_man.manual_override_switch < -STICK_ON_OFF_LIMIT) { /* check auto mode switch for correct mode */ if (sp_man.auto_mode_switch > STICK_ON_OFF_LIMIT) { /* enable stabilized mode */ @@ -1813,6 +1813,11 @@ int commander_thread_main(int argc, char *argv[]) } else { update_state_machine_mode_hold(stat_pub, ¤t_status, mavlink_fd); } + } else { + /* center stick position, set SAS for all vehicle types */ + current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + current_status.flag_control_attitude_enabled = true; + current_status.flag_control_rates_enabled = true; } /* handle the case where RC signal was regained */ diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c index a8cef8c014..f30fd975b0 100644 --- a/apps/commander/state_machine_helper.c +++ b/apps/commander/state_machine_helper.c @@ -520,9 +520,24 @@ void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *c current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL; current_status->flag_control_manual_enabled = true; - /* enable attitude control per default */ - current_status->flag_control_attitude_enabled = true; - current_status->flag_control_rates_enabled = true; + + /* set behaviour based on airframe */ + if ((current_status.system_type == MAV_TYPE_QUADROTOR) || + (current_status.system_type == MAV_TYPE_HEXAROTOR) || + (current_status.system_type == MAV_TYPE_OCTOROTOR)) { + + /* assuming a rotary wing, set to SAS */ + current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS; + current_status.flag_control_attitude_enabled = true; + current_status.flag_control_rates_enabled = true; + } else { + + /* assuming a fixed wing, set to direct pass-through */ + current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT; + current_status.flag_control_attitude_enabled = false; + current_status.flag_control_rates_enabled = false; + } + if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd); if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) { diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c index cd479d40d8..646deb62eb 100644 --- a/apps/fixedwing_att_control/fixedwing_att_control_main.c +++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c @@ -208,7 +208,13 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) att_sp.roll_body = 0.3f; att_sp.pitch_body = 0.0f; att_sp.yaw_body = 0; - att_sp.thrust = 0.4f; + + /* limit throttle to 60 % of last value */ + if (isfinite(manual_sp.throttle)) { + att_sp.thrust = 0.6f * manual_sp.throttle; + } else { + att_sp.thrust = 0.0f; + } // XXX disable yaw control, loiter @@ -250,7 +256,13 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) //param_get(failsafe_throttle_handle, &failsafe_throttle); att_sp.roll_body = 0.3f; att_sp.pitch_body = 0.0f; - att_sp.thrust = 0.4f; + + /* limit throttle to 60 % of last value */ + if (isfinite(manual_sp.throttle)) { + att_sp.thrust = 0.6f * manual_sp.throttle; + } else { + att_sp.thrust = 0.0f; + } att_sp.yaw_body = 0; // XXX disable yaw control, loiter diff --git a/apps/multirotor_att_control/multirotor_att_control_main.c b/apps/multirotor_att_control/multirotor_att_control_main.c index f184859a3f..1b03e8c229 100644 --- a/apps/multirotor_att_control/multirotor_att_control_main.c +++ b/apps/multirotor_att_control/multirotor_att_control_main.c @@ -253,7 +253,20 @@ mc_thread_main(int argc, char *argv[]) param_get(failsafe_throttle_handle, &failsafe_throttle); att_sp.roll_body = 0.0f; att_sp.pitch_body = 0.0f; - att_sp.thrust = failsafe_throttle; + + /* + * Only go to failsafe throttle if last known throttle was + * high enough to create some lift to make hovering state likely. + * + * This is to prevent that someone landing, but not disarming his + * multicopter (throttle = 0) does not make it jump up in the air + * if shutting down his remote. + */ + if (isfinite(manual.throttle) && manual.throttle > 0.2f) { + att_sp.thrust = failsafe_throttle; + } else { + att_sp.thrust = 0.0f; + } /* keep current yaw, do not attempt to go to north orientation, * since if the pilot regains RC control, he will be lost regarding